diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index d06df2778da67cf5ca8a920707f89428be014e5a..7e140e4f339172cd7ac5cb36679ddfc4b61217a5 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -43,9 +43,8 @@ DEPENDPATH += . \ INCLUDEPATH += . \ lib/QMapControl \ $$BASEDIR/../mavlink/contrib/slugs/include \ - $$BASEDIR/../mavlink/include \ - /usr/include/freetype2 -LIBS += /usr/lib/libftgl.so /usr/lib/libglut.so + $$BASEDIR/../mavlink/include +LIBS += -lglut # ../mavlink/include \ # MAVLink/include \ @@ -160,7 +159,6 @@ HEADERS += src/MG.h \ src/ui/linechart/IncrementalPlot.h \ src/ui/map/Waypoint2DIcon.h \ src/ui/map/MAV2DIcon.h \ - src/ui/map/QGC2DIcon.h \ src/ui/QGCRemoteControlView.h \ src/WaypointGlobal.h \ src/ui/WaypointGlobalView.h \ @@ -230,7 +228,6 @@ SOURCES += src/main.cc \ src/ui/linechart/IncrementalPlot.cc \ src/ui/map/Waypoint2DIcon.cc \ src/ui/map/MAV2DIcon.cc \ - src/ui/map/QGC2DIcon.cc \ src/ui/QGCRemoteControlView.cc \ src/WaypointGlobal.cpp \ src/ui/WaypointGlobalView.cpp \ diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index 7d5d6e354d8135e999e0da77f8b6cadc6917d13d..43e8dc6f1dbc754d7da6b97b50c13669469648a2 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -405,14 +405,14 @@ void MAVLinkSimulationLink::mainloop() streampointer += bufferlength; // GPS RAW - mavlink_msg_gps_raw_pack(systemId, componentId, &ret, 0, 3, 47.376417+x*0.001f, 8.548103+y*0.001f, z, 0, 0, 2.5f, 0.1f); + mavlink_msg_gps_raw_pack(systemId, componentId, &ret, 0, 3, 47.376417+(x*0.001), 8.548103+(y*0.001), z, 0, 0, 2.5f, 0.1f); bufferlength = mavlink_msg_to_send_buffer(buffer, &ret); //add data into datastream memcpy(stream+streampointer,buffer, bufferlength); streampointer += bufferlength; // GLOBAL POSITION - mavlink_msg_global_position_pack(systemId, componentId, &ret, 0, 3, 47.376417+x*0.001f, 8.548103+y*0.001f, z, 0, 0); + mavlink_msg_global_position_pack(systemId, componentId, &ret, 0, 3, 47.376417+(x*0.001), 8.548103+(y*0.001), z, 0, 0); bufferlength = mavlink_msg_to_send_buffer(buffer, &ret); //add data into datastream memcpy(stream+streampointer,buffer, bufferlength); diff --git a/src/comm/MAVLinkXMLParser.cc b/src/comm/MAVLinkXMLParser.cc index 312737a8da1bca36873eb46a10d1d5e5717d3ab5..d4b7dfef67b85408ba6bf4c9491c130a5918f17e 100644 --- a/src/comm/MAVLinkXMLParser.cc +++ b/src/comm/MAVLinkXMLParser.cc @@ -204,31 +204,33 @@ bool MAVLinkXMLParser::generate() usedMessageNames->insert(messageName, QString::number(e.lineNumber())); } - QString channelType = "mavlink_channel_t"; - QString messageType = "mavlink_message_t"; + QString channelType("mavlink_channel_t"); + QString messageType("mavlink_message_t"); // Build up function call - QString commentContainer = "/**\n * @brief Send a %1 message\n *\n%2 * @return length of the message in bytes (excluding serial stream start sign)\n */\n"; - QString commentEntry = " * @param %1 %2\n"; + QString commentContainer("/**\n * @brief Send a %1 message\n *\n%2 * @return length of the message in bytes (excluding serial stream start sign)\n */\n"); + QString commentEntry(" * @param %1 %2\n"); QString idDefine = QString("#define MAVLINK_MSG_ID_%1 %2").arg(messageName.toUpper(), QString::number(messageId)); - QString arrayDefines = ""; + QString arrayDefines; QString cStructName = QString("mavlink_%1_t").arg(messageName); - QString cStruct = "typedef struct __%1 \n{\n%2\n} %1;"; - QString cStructLines = ""; - QString encode = "static inline uint16_t mavlink_msg_%1_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const %2* %1)\n{\n\treturn mavlink_msg_%1_pack(%3);\n}\n"; + QString cStruct("typedef struct __%1 \n{\n%2\n} %1;"); + QString cStructLines; + QString encode("static inline uint16_t mavlink_msg_%1_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const %2* %1)\n{\n\treturn mavlink_msg_%1_pack(%3);\n}\n"); - QString decode = "static inline void mavlink_msg_%1_decode(const mavlink_message_t* msg, %2* %1)\n{\n%3}\n"; - QString pack = "static inline uint16_t mavlink_msg_%1_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg%2)\n{\n\tuint16_t i = 0;\n\tmsg->msgid = MAVLINK_MSG_ID_%3;\n\n%4\n\treturn mavlink_finalize_message(msg, system_id, component_id, i);\n}\n\n"; - QString compactSend = "#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS\n\nstatic inline void mavlink_msg_%3_send(%1 chan%5)\n{\n\t%2 msg;\n\tmavlink_msg_%3_pack(mavlink_system.sysid, mavlink_system.compid, &msg%4);\n\tmavlink_send_uart(chan, &msg);\n}\n\n#endif"; + QString decode("static inline void mavlink_msg_%1_decode(const mavlink_message_t* msg, %2* %1)\n{\n%3}\n"); + QString pack("static inline uint16_t mavlink_msg_%1_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg%2)\n{\n\tuint16_t i = 0;\n\tmsg->msgid = MAVLINK_MSG_ID_%3;\n\n%4\n\treturn mavlink_finalize_message(msg, system_id, component_id, i);\n}\n\n"); + QString compactSend("#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS\n\nstatic inline void mavlink_msg_%3_send(%1 chan%5)\n{\n\t%2 msg;\n\tmavlink_msg_%3_pack(mavlink_system.sysid, mavlink_system.compid, &msg%4);\n\tmavlink_send_uart(chan, &msg);\n}\n\n#endif"); //QString compactStructSend = "#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS\n\nstatic inline void mavlink_msg_%3_struct_send(%1 chan%5)\n{\n\t%2 msg;\n\tmavlink_msg_%3_encode(mavlink_system.sysid, mavlink_system.compid, &msg%4);\n\tmavlink_send_uart(chan, &msg);\n}\n\n#endif"; - QString unpacking = ""; - QString prepends = ""; - QString packParameters = ""; - QString packArguments = "system_id, component_id, msg"; - QString packLines = ""; - QString decodeLines = ""; - QString sendArguments = ""; - QString commentLines = ""; + QString unpacking; + QString prepends; + QString packParameters; + QString packArguments("system_id, component_id, msg"); + QString packLines; + QString decodeLines; + QString sendArguments; + QString commentLines; + + // Get the message fields QDomNode f = e.firstChild(); @@ -241,6 +243,9 @@ bool MAVLinkXMLParser::generate() QString fieldName = e2.attribute("name", ""); QString fieldText = e2.text(); + QString unpackingCode; + QString unpackingComment = QString("/**\n * @brief Get field %1 from %2 message\n *\n * @return %3\n */\n").arg(fieldName, messageName, fieldText); + // Send arguments are the same for integral types and arrays sendArguments += ", " + fieldName; @@ -255,7 +260,7 @@ bool MAVLinkXMLParser::generate() // Add field to C structure cStructLines += QString("\t%1 %2[%3]; ///< %4\n").arg("int8_t", fieldName, QString::number(arrayLength), fieldText); // Add pack line to message_xx_pack function - packLines += QString("\ti += put_%1_by_index(%2, %3, i, msg->payload); //%4\n").arg(arrayType, fieldName, QString::number(arrayLength), e2.text()); + packLines += QString("\ti += put_%1_by_index(%2, %3, i, msg->payload); //%4\n").arg(arrayType, fieldName, QString::number(arrayLength), fieldText); // Add decode function for this type decodeLines += QString("\tmavlink_msg_%1_get_%2(msg, %1->%2);\n").arg(messageName, fieldName); arrayDefines += QString("#define MAVLINK_MSG_%1_FIELD_%2_LEN %3\n").arg(messageName.toUpper(), fieldName.toUpper(), QString::number(arrayLength)); @@ -275,6 +280,29 @@ bool MAVLinkXMLParser::generate() decodeLines += QString("\tmavlink_msg_%1_get_%2(msg, %1->%2);\n").arg(messageName, fieldName); arrayDefines += QString("#define MAVLINK_MSG_%1_FIELD_%2_LEN %3\n").arg(messageName.toUpper(), fieldName.toUpper(), QString::number(arrayLength)); } + // Expand array handling to all valid mavlink data types + else if(fieldType.contains('[') && fieldType.contains(']')) + { + int arrayLength = QString(fieldType.split("[").at(1).split("]").first()).toInt(); + QString arrayType = fieldType.split("[").first(); + packParameters += QString(", const ") + arrayType + "* " + fieldName; + packArguments += ", " + messageName + "->" + fieldName; + + // Add field to C structure + cStructLines += QString("\t%1 %2[%3]; ///< %4\n").arg(arrayType, fieldName, QString::number(arrayLength), fieldText); + // Add pack line to message_xx_pack function + packLines += QString("\ti += put_array_by_index((int8_t*)%1, sizeof(%2)*%3, i, msg->payload); //%4\n").arg(fieldName, arrayType, QString::number(arrayLength), fieldText); + // Add decode function for this type + decodeLines += QString("\tmavlink_msg_%1_get_%2(msg, %1->%2);\n").arg(messageName, fieldName); + arrayDefines += QString("#define MAVLINK_MSG_%1_FIELD_%2_LEN %3\n").arg(messageName.toUpper(), fieldName.toUpper(), QString::number(arrayLength)); + + unpackingCode = QString("\n\tmemcpy(r_data, msg->payload%1, sizeof(%2)*%3);\n\treturn sizeof(%2)*%3;").arg(prepends, arrayType, QString::number(arrayLength)); + + unpacking += unpackingComment + QString("static inline uint16_t mavlink_msg_%1_get_%2(const mavlink_message_t* msg, %3* r_data)\n{\n%4\n}\n\n").arg(messageName, fieldName, arrayType, unpackingCode); +// decodeLines += ""; + prepends += QString("+sizeof(%1)*%2").arg(arrayType, QString::number(arrayLength)); + + } else // Handle simple types like integers and floats { @@ -289,9 +317,9 @@ bool MAVLinkXMLParser::generate() decodeLines += QString("\t%1->%2 = mavlink_msg_%1_get_%2(msg);\n").arg(messageName, fieldName); } commentLines += commentEntry.arg(fieldName, fieldText); - QString unpackingComment = QString("/**\n * @brief Get field %1 from %2 message\n *\n * @return %3\n */\n").arg(fieldName, messageName, fieldText); + // - QString unpackingCode; +// QString unpackingCode; if (fieldType == "uint8_t" || fieldType == "int8_t") { @@ -322,6 +350,7 @@ bool MAVLinkXMLParser::generate() unpackingCode = QString("\n\tstrcpy(r_data, msg->payload%1, %2);\n\treturn %2;").arg(prepends, fieldType.split("[").at(1).split("]").first()); } + // Generate the message decoding function // Array handling is different from simple types if (fieldType.startsWith("array")) @@ -338,6 +367,10 @@ bool MAVLinkXMLParser::generate() QString arrayLength = QString(fieldType.split("[").at(1).split("]").first()); prepends += "+" + arrayLength; } + else if(fieldType.contains('[') && fieldType.contains(']')) + { + // prevent this case from being caught in the following else + } else { unpacking += unpackingComment + QString("static inline %1 mavlink_msg_%2_get_%3(const mavlink_message_t* msg)\n{\n%4\n}\n\n").arg(fieldType, messageName, fieldName, unpackingCode); diff --git a/src/comm/OpalLink.cc b/src/comm/OpalLink.cc index 9c10d5d8e29e5c96058a1c2f89b3a85319806c62..5551c091c3ea35ab989543b4b61bae462f4fdb10 100644 --- a/src/comm/OpalLink.cc +++ b/src/comm/OpalLink.cc @@ -246,6 +246,29 @@ void OpalLink::getSignals() values[OpalRT::B_W_2] ); receiveMessage(bias); + + /* send radio outputs */ + mavlink_message_t rc; + mavlink_msg_rc_channels_pack(systemID, componentID, &rc, + duty2PulseMicros(values[OpalRT::RAW_CHANNEL_1]), + duty2PulseMicros(values[OpalRT::RAW_CHANNEL_2]), + duty2PulseMicros(values[OpalRT::RAW_CHANNEL_3]), + duty2PulseMicros(values[OpalRT::RAW_CHANNEL_4]), + duty2PulseMicros(values[OpalRT::RAW_CHANNEL_5]), + duty2PulseMicros(values[OpalRT::RAW_CHANNEL_6]), + duty2PulseMicros(values[OpalRT::RAW_CHANNEL_7]), + duty2PulseMicros(values[OpalRT::RAW_CHANNEL_8]), + static_cast(values[OpalRT::NORM_CHANNEL_1]*255), + static_cast(values[OpalRT::NORM_CHANNEL_2]*255), + static_cast(values[OpalRT::NORM_CHANNEL_3]*255), + static_cast(values[OpalRT::NORM_CHANNEL_4]*255), + static_cast(values[OpalRT::NORM_CHANNEL_5]*255), + static_cast(values[OpalRT::NORM_CHANNEL_6]*255), + static_cast(values[OpalRT::NORM_CHANNEL_7]*255), + static_cast(values[OpalRT::NORM_CHANNEL_8]*255), + 0 //rssi unused + ); + receiveMessage(rc); } else if (returnVal != EAGAIN) // if returnVal == EAGAIN => data just wasn't ready { @@ -294,6 +317,12 @@ bool OpalLink::isConnected() { return connectState; } +uint16_t OpalLink::duty2PulseMicros(double duty) +{ + /* duty cycle assumed to be of a signal at 70 Hz */ + return static_cast(duty/70*1000000); +} + diff --git a/src/comm/OpalLink.h b/src/comm/OpalLink.h index 07b685c0b28ac715cf4076cd6ab3a50c00e25045..f72ba9d23b3da4c29d9b36f1e73bcb8d31ff7184 100644 --- a/src/comm/OpalLink.h +++ b/src/comm/OpalLink.h @@ -151,6 +151,8 @@ protected: OpalRT::ParameterList *params; unsigned short opalInstID; + + uint16_t duty2PulseMicros(double duty); }; #endif // OPALLINK_H diff --git a/src/comm/OpalRT.h b/src/comm/OpalRT.h index 678c44f177d2ce36416024070f35578fea2c4312..51a7f2e428928c56d6a082d47c3e8653cca5daf3 100644 --- a/src/comm/OpalRT.h +++ b/src/comm/OpalRT.h @@ -41,7 +41,7 @@ namespace OpalRT Configuration info for the model */ - const unsigned short NUM_OUTPUT_SIGNALS=39; + const unsigned short NUM_OUTPUT_SIGNALS=57; /* ------------------------------ Outputs ------------------------------ * @@ -85,7 +85,25 @@ namespace OpalRT B_F_2, B_W_0, B_W_1, - B_W_2 + B_W_2, + RAW_CHANNEL_1 = 39, + RAW_CHANNEL_2, + RAW_CHANNEL_3, + RAW_CHANNEL_4, + RAW_CHANNEL_5, + RAW_CHANNEL_6, + RAW_CHANNEL_7, + RAW_CHANNEL_8, + NORM_CHANNEL_1, + NORM_CHANNEL_2, + NORM_CHANNEL_3, + NORM_CHANNEL_4, + NORM_CHANNEL_5, + NORM_CHANNEL_6, + NORM_CHANNEL_7, + NORM_CHANNEL_8, + CONTROLLER_AILERON, + CONTROLLER_ELEVATOR }; /** Component IDs of the parameters. Currently they are all 1 becuase there is no advantage diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index bf075116a54750fa0b29d3e6af960290ec390838..0c166373dd42cf98712402bb1cc3fe1bf7ed7ba0 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -365,28 +365,34 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) // only accept values in a realistic range // quint64 time = getUnixTime(pos.usec); quint64 time = MG::TIME::getGroundTimeNow(); + emit valueChanged(uasId, "lat", pos.lat, time); emit valueChanged(uasId, "lon", pos.lon, time); - // Check for NaN - int alt = pos.alt; - if (alt != alt) - { - alt = 0; - emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE"); - } - emit valueChanged(uasId, "alt", pos.alt, time); - // Smaller than threshold and not NaN - if (pos.v < 1000000 && pos.v == pos.v) - { - emit valueChanged(uasId, "speed", pos.v, time); - //qDebug() << "GOT GPS RAW"; - emit speedChanged(this, (double)pos.v, 0.0, 0.0, time); - } - else + + if (pos.fix_type > 0) { - emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v)); + emit globalPositionChanged(this, pos.lon, pos.lat, pos.alt, time); + + // Check for NaN + int alt = pos.alt; + if (alt != alt) + { + alt = 0; + emit textMessageReceived(uasId, message.compid, 255, "GCS ERROR: RECEIVED NaN FOR ALTITUDE"); + } + emit valueChanged(uasId, "alt", pos.alt, time); + // Smaller than threshold and not NaN + if (pos.v < 1000000 && pos.v == pos.v) + { + emit valueChanged(uasId, "speed", pos.v, time); + //qDebug() << "GOT GPS RAW"; + emit speedChanged(this, (double)pos.v, 0.0, 0.0, time); + } + else + { + emit textMessageReceived(uasId, message.compid, 255, QString("GCS ERROR: RECEIVED INVALID SPEED OF %1 m/s").arg(pos.v)); + } } - emit globalPositionChanged(this, pos.lon, pos.lat, alt, time); } break; case MAVLINK_MSG_ID_GPS_STATUS: diff --git a/src/ui/HSIDisplay.cc b/src/ui/HSIDisplay.cc index 69bdf153516797fe12d6211112240a96e8dae16b..e7b0944dfd1277845699e7335a9c85490111b1b6 100644 --- a/src/ui/HSIDisplay.cc +++ b/src/ui/HSIDisplay.cc @@ -100,7 +100,7 @@ HSIDisplay::HSIDisplay(QWidget *parent) : topMargin(3.0f) { connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); - refreshTimer->setInterval(60); + refreshTimer->setInterval(120); // this->setScene(new QGraphicsScene(-metricWidth/2.0f, -metricWidth/2.0f, metricWidth, metricWidth, this)); diff --git a/src/ui/HUD.cc b/src/ui/HUD.cc index 5a198a4a5e89957793418ffa03ee31ae6a596309..88b19dba775b30c65e38c8d80e476c346bd099c8 100644 --- a/src/ui/HUD.cc +++ b/src/ui/HUD.cc @@ -448,7 +448,7 @@ void HUD::paintText(QString text, QColor color, float fontSize, float refX, floa QFont font("Bitstream Vera Sans"); // Enforce minimum font size of 5 pixels - int fSize = qMax(1, (int)(fontSize*scalingFactor*1.26f)); + int fSize = qMax(5, (int)(fontSize*scalingFactor*1.26f)); font.setPixelSize(fSize); QFontMetrics metrics = QFontMetrics(font); diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index acaf358436b5954723ad395fc8955f41b241de11..3a6d7d5dc370b8ae11deb051311db78420cc3d30 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -657,14 +657,14 @@ void MainWindow::loadPixhawkView() clearView(); // Engineer view, used in EMAV2009 - // LINE CHART - if (linechartWidget) + // 3D map + if (map3DWidget) { QStackedWidget *centerStack = dynamic_cast(centralWidget()); if (centerStack) { - linechartWidget->setActive(true); - centerStack->setCurrentWidget(linechartWidget); + //map3DWidget->setActive(true); + centerStack->setCurrentWidget(map3DWidget); } } @@ -675,6 +675,18 @@ void MainWindow::loadPixhawkView() controlDockWidget->show(); } + // HORIZONTAL SITUATION INDICATOR + if (hsiDockWidget) + { + HSIDisplay* hsi = dynamic_cast( hsiDockWidget->widget() ); + if (hsi) + { + hsi->start(); + addDockWidget(Qt::LeftDockWidgetArea, hsiDockWidget); + hsiDockWidget->show(); + } + } + // UAS LIST if (listDockWidget) { @@ -696,18 +708,6 @@ void MainWindow::loadPixhawkView() waypointsDockWidget->show(); } - // HORIZONTAL SITUATION INDICATOR - if (hsiDockWidget) - { - HSIDisplay* hsi = dynamic_cast( hsiDockWidget->widget() ); - if (hsi) - { - hsi->start(); - addDockWidget(Qt::BottomDockWidgetArea, hsiDockWidget); - hsiDockWidget->show(); - } - } - // DEBUG CONSOLE if (debugConsoleDockWidget) { @@ -715,13 +715,6 @@ void MainWindow::loadPixhawkView() debugConsoleDockWidget->show(); } - // RADIO CONTROL VIEW - if (rcViewDockWidget) - { - addDockWidget(Qt::BottomDockWidgetArea, rcViewDockWidget); - rcViewDockWidget->show(); - } - // ONBOARD PARAMETERS if (parametersDockWidget) { @@ -981,6 +974,13 @@ void MainWindow::loadEngineerView() parametersDockWidget->show(); } + // RADIO CONTROL VIEW + if (rcViewDockWidget) + { + addDockWidget(Qt::BottomDockWidgetArea, rcViewDockWidget); + rcViewDockWidget->show(); + } + this->show(); } diff --git a/src/ui/MapWidget.cc b/src/ui/MapWidget.cc index 5673d504387c4a8b8bc50080c71fe8dd54d6b23f..a060baf0b36db2244f43341ffc6406ca0109f3d3 100644 --- a/src/ui/MapWidget.cc +++ b/src/ui/MapWidget.cc @@ -37,6 +37,8 @@ This file is part of the QGROUNDCONTROL project #include "ui_MapWidget.h" #include "UASInterface.h" #include "UASManager.h" +#include "MAV2DIcon.h" +#include "Waypoint2DIcon.h" #include "MG.h" @@ -53,7 +55,7 @@ MapWidget::MapWidget(QWidget *parent) : this->setFocusPolicy(Qt::StrongFocus); // create MapControl - mc = new MapControl(QSize(320, 240)); + mc = new qmapcontrol::MapControl(QSize(320, 240)); mc->showScale(true); mc->showCoord(true); mc->enablePersistentCache(); @@ -62,21 +64,21 @@ MapWidget::MapWidget(QWidget *parent) : // create MapAdapter to get maps from //TileMapAdapter* osmAdapter = new TileMapAdapter("tile.openstreetmap.org", "/%1/%2/%3.png", 256, 0, 17); - MapAdapter* mapadapter_overlay = new YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=2.2&t=h&s=256&x=%2&y=%3&z=%1"); + qmapcontrol::MapAdapter* mapadapter_overlay = new qmapcontrol::YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=2.2&t=h&s=256&x=%2&y=%3&z=%1"); // MAP BACKGROUND - mapadapter = new GoogleSatMapAdapter(); - l = new MapLayer("Google Satellite", mapadapter); + mapadapter = new qmapcontrol::GoogleSatMapAdapter(); + l = new qmapcontrol::MapLayer("Google Satellite", mapadapter); mc->addLayer(l); // STREET OVERLAY - overlay = new MapLayer("Overlay", mapadapter_overlay); + overlay = new qmapcontrol::MapLayer("Overlay", mapadapter_overlay); overlay->setVisible(false); mc->addLayer(overlay); // WAYPOINT LAYER // create a layer with the mapadapter and type GeometryLayer (for waypoints) - geomLayer = new GeometryLayer("Waypoints", mapadapter); + geomLayer = new qmapcontrol::GeometryLayer("Waypoints", mapadapter); mc->addLayer(geomLayer); // @@ -188,6 +190,7 @@ MapWidget::MapWidget(QWidget *parent) : connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*))); + connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(activeUASSet(UASInterface*))); connect(mc, SIGNAL(mouseEventCoordinate(const QMouseEvent*, const QPointF)), this, SLOT(captureMapClick(const QMouseEvent*, const QPointF))); @@ -208,7 +211,7 @@ MapWidget::MapWidget(QWidget *parent) : pointPen = new QPen(QColor(0, 255,0)); pointPen->setWidth(3); - path = new LineString (wps, "UAV Path", pointPen); + path = new qmapcontrol::LineString (wps, "UAV Path", pointPen); mc->layer("Waypoints")->addGeometry(path); this->setVisible(false); @@ -224,7 +227,7 @@ void MapWidget::mapproviderSelected(QAction* action) int zoom = mapadapter->adaptedZoom(); mc->setZoom(0); - mapadapter = new OSMMapAdapter(); + mapadapter = new qmapcontrol::OSMMapAdapter(); l->setMapAdapter(mapadapter); geomLayer->setMapAdapter(mapadapter); @@ -240,7 +243,7 @@ void MapWidget::mapproviderSelected(QAction* action) int zoom = mapadapter->adaptedZoom(); mc->setZoom(0); - mapadapter = new YahooMapAdapter(); + mapadapter = new qmapcontrol::YahooMapAdapter(); l->setMapAdapter(mapadapter); geomLayer->setMapAdapter(mapadapter); @@ -256,7 +259,7 @@ void MapWidget::mapproviderSelected(QAction* action) QPointF a = mc->currentCoordinate(); mc->setZoom(0); - mapadapter = new YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=1.7&t=a&s=256&x=%2&y=%3&z=%1"); + mapadapter = new qmapcontrol::YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=1.7&t=a&s=256&x=%2&y=%3&z=%1"); l->setMapAdapter(mapadapter); mc->updateRequestNew(); @@ -267,7 +270,7 @@ void MapWidget::mapproviderSelected(QAction* action) { int zoom = mapadapter->adaptedZoom(); mc->setZoom(0); - mapadapter = new GoogleMapAdapter(); + mapadapter = new qmapcontrol::GoogleMapAdapter(); l->setMapAdapter(mapadapter); geomLayer->setMapAdapter(mapadapter); @@ -281,7 +284,7 @@ void MapWidget::mapproviderSelected(QAction* action) { int zoom = mapadapter->adaptedZoom(); mc->setZoom(0); - mapadapter = new GoogleSatMapAdapter(); + mapadapter = new qmapcontrol::GoogleSatMapAdapter(); l->setMapAdapter(mapadapter); geomLayer->setMapAdapter(mapadapter); @@ -342,10 +345,19 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina str = QString("%1").arg(path->numberOfPoints()); // create the WP and set everything in the LineString to display the path - CirclePoint* tempCirclePoint = new CirclePoint(coordinate.x(), coordinate.y(), 10, str); + Waypoint2DIcon* tempCirclePoint; + + if (mav) + { + tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle, new QPen(mav->getColor())); + } + else + { + tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle); + } mc->layer("Waypoints")->addGeometry(tempCirclePoint); - Point* tempPoint = new Point(coordinate.x(), coordinate.y(),str); + qmapcontrol::Point* tempPoint = new qmapcontrol::Point(coordinate.x(), coordinate.y(),str); wps.append(tempPoint); path->addPoint(tempPoint); @@ -360,7 +372,7 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina } } -void MapWidget::captureGeometryClick(Geometry* geom, QPoint point){ +void MapWidget::captureGeometryClick(qmapcontrol::Geometry* geom, QPoint point){ Q_UNUSED(geom); Q_UNUSED(point); @@ -369,29 +381,35 @@ void MapWidget::captureGeometryClick(Geometry* geom, QPoint point){ } -void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate){ +void MapWidget::captureGeometryDrag(qmapcontrol::Geometry* geom, QPointF coordinate){ Q_UNUSED(coordinate); // Refresh the screen mc->updateRequestNew(); int temp = 0; - Point* point2Find; + qmapcontrol::Point* point2Find; point2Find = wpIndex[geom->name()]; - point2Find->setCoordinate(coordinate); - point2Find = dynamic_cast (geom); - point2Find->setCoordinate(coordinate); + if (point2Find) + { + point2Find->setCoordinate(coordinate); - // qDebug() << geom->name(); - temp = geom->get_myIndex(); - //qDebug() << temp; - emit sendGeometryEndDrag(coordinate,temp); + point2Find = dynamic_cast (geom); + if (point2Find) + { + point2Find->setCoordinate(coordinate); + // qDebug() << geom->name(); + temp = geom->get_myIndex(); + //qDebug() << temp; + emit sendGeometryEndDrag(coordinate,temp); + } + } } -void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate) +void MapWidget::captureGeometryEndDrag(qmapcontrol::Geometry* geom, QPointF coordinate) { mc->setMouseMode(qmapcontrol::MapControl::Panning); @@ -411,10 +429,18 @@ MapWidget::~MapWidget() */ void MapWidget::addUAS(UASInterface* uas) { - mav = uas; connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64))); } +void MapWidget::activeUASSet(UASInterface* uas) +{ + if (uas) + { + mav = uas; + path->setPen(new QPen(mav->getColor())); + } +} + /** * Updates the global position of one MAV and append the last movement to the trail * @@ -446,19 +472,19 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, // Icon QPen* pointpen = new QPen(uasColor); - CirclePoint* p = new CirclePoint(lat, lon, 10, uas->getUASName(), Point::Middle, pointpen); + MAV2DIcon* p = new MAV2DIcon(lat, lon, 20, uas->getUASName(), qmapcontrol::Point::Middle, pointpen); uasIcons.insert(uas->getUASID(), p); geomLayer->addGeometry(p); // Line // A QPen also can use transparency - QList points; - points.append(new Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon))); + QList points; + points.append(new qmapcontrol::Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon))); QPen* linepen = new QPen(uasColor.darker()); linepen->setWidth(2); // Add the Points and the QPen to a LineString - LineString* ls = new LineString(points, uas->getUASName(), linepen); + qmapcontrol::LineString* ls = new qmapcontrol::LineString(points, uas->getUASName(), linepen); uasTrails.insert(uas->getUASID(), ls); // Add the LineString to the layer @@ -466,10 +492,14 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, } else { - CirclePoint* p = uasIcons.value(uas->getUASID()); - p->setCoordinate(QPointF(lat, lon)); + MAV2DIcon* p = dynamic_cast(uasIcons.value(uas->getUASID())); + if (p) + { + p->setCoordinate(QPointF(lat, lon)); + p->setYaw(uas->getYaw()); + } // Extend trail - uasTrails.value(uas->getUASID())->addPoint(new Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon))); + uasTrails.value(uas->getUASID())->addPoint(new qmapcontrol::Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon))); } // points.append(new CirclePoint(8.275145, 50.016992, 15, "Wiesbaden-Mainz-Kastel, Johannes-Goßner-Straße", Point::Middle, pointpen)); diff --git a/src/ui/MapWidget.h b/src/ui/MapWidget.h index 7d79949d6c2f7412b764d3f2d9f01a8b48c05056..c9748efafbd3c1b64a52f46718efcd78e4691bf8 100644 --- a/src/ui/MapWidget.h +++ b/src/ui/MapWidget.h @@ -44,8 +44,6 @@ namespace Ui { class MapWidget; } -using namespace qmapcontrol; - /** * @brief 2D Moving map * @@ -60,6 +58,7 @@ public: public slots: void addUAS(UASInterface* uas); + void activeUASSet(UASInterface* uas); void updateGlobalPosition(UASInterface* uas, double lat, double lon, double alt, quint64 usec); void updatePosition(float time, double lat, double lon); @@ -86,8 +85,8 @@ protected: QMenu* mapMenu; QPushButton* mapButton; - MapControl* mc; ///< QMapControl widget - MapAdapter* mapadapter; ///< Adapter to load the map data + qmapcontrol::MapControl* mc; ///< QMapControl widget + qmapcontrol::MapAdapter* mapadapter; ///< Adapter to load the map data qmapcontrol::Layer* l; ///< Current map layer (background) qmapcontrol::Layer* overlay; ///< Street overlay (foreground) qmapcontrol::GeometryLayer* geomLayer; ///< Layer for waypoints @@ -98,18 +97,18 @@ protected: //Layer* gSatLayer; - QMap uasIcons; - QMap uasTrails; + QMap uasIcons; + QMap uasTrails; UASInterface* mav; quint64 lastUpdate; protected slots: void captureMapClick (const QMouseEvent* event, const QPointF coordinate); void createPathButtonClicked(bool checked); - void captureGeometryClick(Geometry*, QPoint); + void captureGeometryClick(qmapcontrol::Geometry*, QPoint); void mapproviderSelected(QAction* action); - void captureGeometryDrag(Geometry* geom, QPointF coordinate); - void captureGeometryEndDrag(Geometry* geom, QPointF coordinate); + void captureGeometryDrag(qmapcontrol::Geometry* geom, QPointF coordinate); + void captureGeometryEndDrag(qmapcontrol::Geometry* geom, QPointF coordinate); @@ -122,9 +121,9 @@ protected: private: Ui::MapWidget *m_ui; - QList wps; - QHash wpIndex; - LineString* path; + QList wps; + QHash wpIndex; + qmapcontrol::LineString* path; QPen* pointPen; }; diff --git a/src/ui/ParameterInterface.ui b/src/ui/ParameterInterface.ui index df9a778ba64e44edd42f69ddbc81910b4ed1823a..daaa2e6bc84ce879756c1fe64b89ca2e1d1ca818 100644 --- a/src/ui/ParameterInterface.ui +++ b/src/ui/ParameterInterface.ui @@ -13,7 +13,16 @@ Form - + + + 5 + + + 2 + + + 6 + @@ -30,6 +39,9 @@ Onboard Parameters + + 3 + diff --git a/src/ui/QGCRemoteControlView.cc b/src/ui/QGCRemoteControlView.cc index 1968570750abfd7d71ddcd11e57175d7f3c9cab6..26d8efd7ee4630e487c796d7bdbbf7039f79ca7e 100644 --- a/src/ui/QGCRemoteControlView.cc +++ b/src/ui/QGCRemoteControlView.cc @@ -45,6 +45,7 @@ QGCRemoteControlView::QGCRemoteControlView(QWidget *parent) : channelLayout(new QVBoxLayout()), ui(new Ui::QGCRemoteControlView) { + //ui->setupUi(this); QGridLayout* layout = new QGridLayout(this); layout->addLayout(channelLayout, 1, 0, 1, 2); diff --git a/src/ui/QGCSensorSettingsWidget.ui b/src/ui/QGCSensorSettingsWidget.ui index ab8c2583f67048dac3c0d22ca98c3e716d493104..40be710d9afa9c9472a8f347ce6507a3e4c87f8f 100644 --- a/src/ui/QGCSensorSettingsWidget.ui +++ b/src/ui/QGCSensorSettingsWidget.ui @@ -6,135 +6,152 @@ 0 0 - 350 - 545 + 319 + 221 Form - + 0 - - + + - Activate Extended Output + Calibration Wizards - - + + + 6 + + + 2 + + + 6 + + + 2 + + + 12 + + 6 - + - Send RAW Sensor data + RC Calibration - - + + - Send extended status + Mag. Calibration - - + + - Send RC-values + Gyro Calibration - - + + - Send raw controller outputs + Pressure Calibration - - + + + + + + + Activate Extended Output + + + + 6 + + + 2 + + + 6 + + + 2 + + + 5 + + + 2 + + + - Send position setpoint and estimate + RAW Sensor Data - - + + - Send Extra1 + RC Values - - + + - Send Extra2 + Position setpoint - - + + - Send Extra3 + Raw Controller - - - - - - - Calibration Wizards - - - - 6 - - - + + - Start Mag. Calibration + Send Extra1 - - + + - Start Gyro Calibration + Attitude - - + + - Start RC Calibration + Send Extra2 - - + + - Start Pressure Calibration + Send Extra3 - - - - Qt::Horizontal - - - - 0 - 0 - - - - diff --git a/src/ui/WaypointGlobalView.ui b/src/ui/WaypointGlobalView.ui index 7ad20e38549153917c15e4201ab4feb2cb6faf6d..8a04282396e0e1cfe4f8d7d6ec7d0d8bbfc8819f 100644 --- a/src/ui/WaypointGlobalView.ui +++ b/src/ui/WaypointGlobalView.ui @@ -6,12 +6,12 @@ 0 0 - 869 - 60 + 774 + 184 - + 0 0 @@ -144,6 +144,15 @@ QProgressBar::chunk#thrustBar { } + + QLayout::SetDefaultConstraint + + + 0 + + + 0 + @@ -155,7 +164,13 @@ QProgressBar::chunk#thrustBar { - + + + 2 + + + 2 + @@ -168,10 +183,13 @@ QProgressBar::chunk#thrustBar { Qt::Horizontal + + QSizePolicy::MinimumExpanding + - 135 - 13 + 2 + 0 @@ -184,26 +202,7 @@ QProgressBar::chunk#thrustBar { - - - - 0 - 0 - - - - - 120 - 25 - - - - Qt::ScrollBarAlwaysOff - - - true - - + @@ -212,8 +211,8 @@ QProgressBar::chunk#thrustBar { - 50 - 30 + 2 + 0 @@ -226,30 +225,20 @@ QProgressBar::chunk#thrustBar { - - - - 120 - 25 - - - - Qt::ScrollBarAlwaysOff - - - true - - + Qt::Horizontal + + QSizePolicy::MinimumExpanding + - 50 - 30 + 2 + 0 diff --git a/src/ui/WaypointView.ui b/src/ui/WaypointView.ui index 5c8f32af7721b6f5ed1093a812acf4c8f48ec843..2e71ed016e11e3b98f8f237427e400cacbeae851 100644 --- a/src/ui/WaypointView.ui +++ b/src/ui/WaypointView.ui @@ -160,7 +160,7 @@ QProgressBar::chunk#thrustBar { 2 - 5 + 2 @@ -205,7 +205,7 @@ QProgressBar::chunk#thrustBar { 25 - 12 + 0 @@ -355,7 +355,7 @@ QProgressBar::chunk#thrustBar { - + :/images/actions/go-up.svg:/images/actions/go-up.svg @@ -375,7 +375,7 @@ QProgressBar::chunk#thrustBar { - + :/images/actions/go-down.svg:/images/actions/go-down.svg @@ -395,7 +395,7 @@ QProgressBar::chunk#thrustBar { - + :/images/actions/list-remove.svg:/images/actions/list-remove.svg @@ -405,6 +405,8 @@ QProgressBar::chunk#thrustBar { - + + + diff --git a/src/ui/linechart/LinechartPlot.h b/src/ui/linechart/LinechartPlot.h index dfa2b9c5af63fc2f5e3c75b2b2210652ea1ccd23..138df19195ddcf693e6cf351b4a10a8a45f59264 100644 --- a/src/ui/linechart/LinechartPlot.h +++ b/src/ui/linechart/LinechartPlot.h @@ -213,8 +213,8 @@ public: static const int SCALE_BEST_FIT = 1; static const int SCALE_LOGARITHMIC = 2; - static const int DEFAULT_REFRESH_RATE = 40; ///< The default refresh rate is 25 Hz / every 100 ms - static const int DEFAULT_PLOT_INTERVAL = 1000 * 15; ///< The default plot interval is 15 seconds + static const int DEFAULT_REFRESH_RATE = 50; ///< The default refresh rate is 25 Hz / every 100 ms + static const int DEFAULT_PLOT_INTERVAL = 1000 * 12; ///< The default plot interval is 15 seconds static const int DEFAULT_SCALE_INTERVAL = 1000 * 5; public slots: diff --git a/src/ui/linechart/LinechartWidget.cc b/src/ui/linechart/LinechartWidget.cc index f4649daa4c4a3197c25e66a8b8ac57b8e2e78494..b7615b78f4c9f06662dd7cb6fd4a149dc2c0432a 100644 --- a/src/ui/linechart/LinechartWidget.cc +++ b/src/ui/linechart/LinechartWidget.cc @@ -90,7 +90,7 @@ updateTimer(new QTimer()) connect(this, SIGNAL(plotWindowPositionUpdated(int)), scrollbar, SLOT(setValue(int))); connect(scrollbar, SIGNAL(sliderMoved(int)), this, SLOT(setPlotWindowPosition(int))); - updateTimer->setInterval(100); + updateTimer->setInterval(300); connect(updateTimer, SIGNAL(timeout()), this, SLOT(refresh())); updateTimer->start(); } @@ -247,13 +247,13 @@ void LinechartWidget::refresh() str.sprintf("%+.2f", activePlot->getMean(j.key())); j.value()->setText(str); } - QMap::iterator k; - for (k = curveMedians->begin(); k != curveMedians->end(); ++k) - { - // Median - str.sprintf("%+.2f", activePlot->getMedian(k.key())); - k.value()->setText(str); - } +// QMap::iterator k; +// for (k = curveMedians->begin(); k != curveMedians->end(); ++k) +// { +// // Median +// str.sprintf("%+.2f", activePlot->getMedian(k.key())); +// k.value()->setText(str); +// } } @@ -397,11 +397,11 @@ QWidget* LinechartWidget::createCurveItem(QString curve) curveMeans->insert(curve, mean); horizontalLayout->addWidget(mean); - // Median - median = new QLabel(form); - value->setNum(0.00); - curveMedians->insert(curve, median); - horizontalLayout->addWidget(median); +// // Median +// median = new QLabel(form); +// value->setNum(0.00); +// curveMedians->insert(curve, median); +// horizontalLayout->addWidget(median); /* Color picker QColor color = QColorDialog::getColor(Qt::green, this); @@ -418,7 +418,7 @@ QWidget* LinechartWidget::createCurveItem(QString curve) horizontalLayout->setStretchFactor(label, 80); horizontalLayout->setStretchFactor(value, 50); horizontalLayout->setStretchFactor(mean, 50); - horizontalLayout->setStretchFactor(median, 50); +// horizontalLayout->setStretchFactor(median, 50); // Connect actions QObject::connect(checkBox, SIGNAL(clicked(bool)), this, SLOT(takeButtonClick(bool))); diff --git a/src/ui/map/MAV2DIcon.cc b/src/ui/map/MAV2DIcon.cc index 4b4cd92cbf235f9a8e4a1b2f8f2432749947b549..573149a853e851695af11d316bc059bd36f49ab8 100644 --- a/src/ui/map/MAV2DIcon.cc +++ b/src/ui/map/MAV2DIcon.cc @@ -1,27 +1,83 @@ #include "MAV2DIcon.h" #include -MAV2DIcon::MAV2DIcon(QGraphicsItem* parent) : - QGC2DIcon(parent) +MAV2DIcon::MAV2DIcon(qreal x, qreal y, int radius, QString name, Alignment alignment, QPen* pen) + : Point(x, y, name, alignment), + yaw(0.0f) { + size = QSize(radius, radius); + drawIcon(pen); } -/** - * @return the bounding rectangle of the icon - */ -QRectF MAV2DIcon::boundingRect() const +MAV2DIcon::MAV2DIcon(qreal x, qreal y, QString name, Alignment alignment, QPen* pen) + : Point(x, y, name, alignment) +{ + int radius = 10; + size = QSize(radius, radius); + drawIcon(pen); +} + +MAV2DIcon::~MAV2DIcon() +{ + delete mypixmap; +} + +void MAV2DIcon::setPen(QPen* pen) { - qreal penWidth = 1; - return QRectF(-10 - penWidth / 2, -10 - penWidth / 2, - 20 + penWidth, 20 + penWidth); + mypen = pen; + drawIcon(pen); } /** - * @param painter QPainter to draw with - * @param option Visual style - * @param widget Parent widget + * @param yaw in radians, 0 = north, positive = clockwise */ -void MAV2DIcon::paint(QPainter* painter, const QStyleOptionGraphicsItem* option, QWidget* widget) +void MAV2DIcon::setYaw(float yaw) { - painter->drawRoundedRect(-10, -10, 20, 20, 5, 5); + this->yaw = yaw; +} + +void MAV2DIcon::drawIcon(QPen* pen) +{ + mypixmap = new QPixmap(radius+1, radius+1); + mypixmap->fill(Qt::transparent); + QPainter painter(mypixmap); + + // DRAW MICRO AIR VEHICLE + QPointF p(radius/2, radius/2); + + float waypointSize = radius; + QPolygonF poly(3); + // Top point + poly.replace(0, QPointF(p.x(), p.y()+waypointSize/2.0f)); + // Right point + poly.replace(1, QPointF(p.x()-waypointSize/2.0f, p.y()-waypointSize/2.0f)); + // Left point + poly.replace(2, QPointF(p.x()+waypointSize/2.0f, p.y() + waypointSize/2.0f)); + +// // Select color based on if this is the current waypoint +// if (list.at(i)->getCurrent()) +// { +// color = QGC::colorCyan;//uas->getColor(); +// pen.setWidthF(refLineWidthToPen(0.8f)); +// } +// else +// { +// color = uas->getColor(); +// pen.setWidthF(refLineWidthToPen(0.4f)); +// } + + //pen.setColor(color); + if (pen) + { + pen->setWidthF(2); + painter.setPen(*pen); + } + else + { + QPen pen2(Qt::yellow); + pen2.setWidth(2); + painter.setPen(pen2); + } + painter.setBrush(Qt::NoBrush); + painter.drawPolygon(poly); } diff --git a/src/ui/map/MAV2DIcon.h b/src/ui/map/MAV2DIcon.h index 3a82a8eaff5b1276fb9ed554ed5ad3fbb71de228..e59d196e5f1441e588ea9fc72664ea695ca25769 100644 --- a/src/ui/map/MAV2DIcon.h +++ b/src/ui/map/MAV2DIcon.h @@ -1,15 +1,49 @@ #ifndef MAV2DICON_H #define MAV2DICON_H -#include "QGC2DIcon.h" +#include "qmapcontrol.h" -class MAV2DIcon : public QGC2DIcon +class MAV2DIcon : public qmapcontrol::Point { public: - explicit MAV2DIcon(QGraphicsItem* parent = 0); + /*! + * + * @param x longitude + * @param y latitude + * @param name name of the circle point + * @param alignment alignment (Middle or TopLeft) + * @param pen QPen for drawing + */ + MAV2DIcon(qreal x, qreal y, QString name = QString(), Alignment alignment = Middle, QPen* pen=0); + + //! + /*! + * + * @param x longitude + * @param y latitude + * @param radius the radius of the circle + * @param name name of the circle point + * @param alignment alignment (Middle or TopLeft) + * @param pen QPen for drawing + */ + MAV2DIcon(qreal x, qreal y, int radius = 10, QString name = QString(), Alignment alignment = Middle, QPen* pen=0); + virtual ~MAV2DIcon(); + + //! sets the QPen which is used for drawing the circle + /*! + * A QPen can be used to modify the look of the drawn circle + * @param pen the QPen which should be used for drawing + * @see http://doc.trolltech.com/4.3/qpen.html + */ + virtual void setPen(QPen* pen); + + void setYaw(float yaw); + void drawIcon(QPen* pen); + +protected: + float yaw; ///< Yaw angle of the MAV + int radius; ///< Maximum dimension of the MAV icon - QRectF boundingRect() const; - void paint(QPainter*, const QStyleOptionGraphicsItem*, QWidget*); }; diff --git a/src/ui/map/QGC2DIcon.cc b/src/ui/map/QGC2DIcon.cc deleted file mode 100644 index 24a780f104e0854e08c5b9b5014f34358707f58b..0000000000000000000000000000000000000000 --- a/src/ui/map/QGC2DIcon.cc +++ /dev/null @@ -1,58 +0,0 @@ -#include "QGC2DIcon.h" - -QGC2DIcon::QGC2DIcon(QPointF localOriginInGlobalCoords, bool onlyLocal, QGraphicsItem* parent) : - QGraphicsItem(parent), - localOriginInGlobalCoords(localOriginInGlobalCoords), - local(onlyLocal) -{ -} - -QGC2DIcon::QGC2DIcon(bool onlyLocal, QGraphicsItem* parent) : - QGraphicsItem(parent), - localOriginInGlobalCoords(QPointF(0, 0)), - local(onlyLocal) -{ -} - -QGC2DIcon::QGC2DIcon(QGraphicsItem* parent) : - QGraphicsItem(parent), - localOriginInGlobalCoords(QPointF(0, 0)), - local(false) -{ - -} - -QGC2DIcon::~QGC2DIcon() -{ - -} - -QPointF QGC2DIcon::getGlobalPosition() -{ - -} - -QPointF QGC2DIcon::getLocalPosition() -{ - -} - -void QGC2DIcon::setGlobalPosition(QPointF pos) -{ - -} - -void QGC2DIcon::setLocalPosition(QPointF pos) -{ - -} - -void QGC2DIcon::setLocalPosition(float x, float y) -{ - -} - -bool QGC2DIcon::isLocal() -{ - return local; -} diff --git a/src/ui/map/QGC2DIcon.h b/src/ui/map/QGC2DIcon.h deleted file mode 100644 index ddca2787fb97afec6274213b9153f07dccd693ab..0000000000000000000000000000000000000000 --- a/src/ui/map/QGC2DIcon.h +++ /dev/null @@ -1,38 +0,0 @@ -#ifndef QGC2DICON_H -#define QGC2DICON_H - -#include -#include - -class QGC2DIcon : public QGraphicsItem -{ -public: - QGC2DIcon(QPointF localOriginInGlobalCoords, bool onlyLocal=false, QGraphicsItem* parent = 0); - QGC2DIcon(bool onlyLocal=false, QGraphicsItem* parent = 0); - explicit QGC2DIcon(QGraphicsItem* parent = 0); - ~QGC2DIcon(); - - QPointF getGlobalPosition(); - QPointF getLocalPosition(); - - void setGlobalPosition(QPointF pos); - void setLocalPosition(QPointF pos); - void setLocalPosition(float x, float y); - - bool isLocal(); - virtual QRectF boundingRect() const = 0; - virtual void paint(QPainter*, const QStyleOptionGraphicsItem*, QWidget*) = 0; - -signals: - -public slots: - -protected: - QPointF localOriginInGlobalCoords; - QPointF globalPosition; - QPointF localPosition; - bool local; - -}; - -#endif // QGC2DICON_H diff --git a/src/ui/map/Waypoint2DIcon.cc b/src/ui/map/Waypoint2DIcon.cc index a260194ce4b02361cbc3ace32e76de1c4f678ad1..3ccf52a31f4735f227eea1ede1aeb9835de2003e 100644 --- a/src/ui/map/Waypoint2DIcon.cc +++ b/src/ui/map/Waypoint2DIcon.cc @@ -1,31 +1,88 @@ #include "Waypoint2DIcon.h" #include -#include +Waypoint2DIcon::Waypoint2DIcon(qreal x, qreal y, int radius, QString name, Alignment alignment, QPen* pen) + : Point(x, y, name, alignment), + yaw(0.0f), + radius(radius) +{ + size = QSize(radius, radius); + drawIcon(pen); +} -Waypoint2DIcon::Waypoint2DIcon(QGraphicsItem* parent) : - QGC2DIcon(parent) +Waypoint2DIcon::Waypoint2DIcon(qreal x, qreal y, QString name, Alignment alignment, QPen* pen) + : Point(x, y, name, alignment) { + int radius = 10; + size = QSize(radius, radius); + drawIcon(pen); } -/** - * @return the bounding rectangle of the icon - */ -QRectF Waypoint2DIcon::boundingRect() const +Waypoint2DIcon::~Waypoint2DIcon() { - qreal penWidth = 1; - return QRectF(-10 - penWidth / 2, -10 - penWidth / 2, - 20 + penWidth, 20 + penWidth); + delete mypixmap; +} + +void Waypoint2DIcon::setPen(QPen* pen) +{ + mypen = pen; + drawIcon(pen); } /** - * @param painter QPainter to draw with - * @param option Visual style - * @param widget Parent widget + * @param yaw in radians, 0 = north, positive = clockwise */ -void Waypoint2DIcon::paint(QPainter* painter, const QStyleOptionGraphicsItem* option, QWidget* widget) +void Waypoint2DIcon::setYaw(float yaw) { - qDebug() << __FILE__ << __LINE__ << "DRAWING"; - painter->setPen(QPen(Qt::red)); - painter->drawRoundedRect(-10, -10, 20, 20, 5, 5); + this->yaw = yaw; +} + +void Waypoint2DIcon::drawIcon(QPen* pen) +{ + mypixmap = new QPixmap(radius+1, radius+1); + mypixmap->fill(Qt::transparent); + QPainter painter(mypixmap); + + // DRAW WAYPOINT + QPointF p(radius/2, radius/2); + + float waypointSize = radius; + QPolygonF poly(4); + // Top point + poly.replace(0, QPointF(p.x(), p.y()-waypointSize/2.0f)); + // Right point + poly.replace(1, QPointF(p.x()+waypointSize/2.0f, p.y())); + // Bottom point + poly.replace(2, QPointF(p.x(), p.y() + waypointSize/2.0f)); + poly.replace(3, QPointF(p.x() - waypointSize/2.0f, p.y())); + +// // Select color based on if this is the current waypoint +// if (list.at(i)->getCurrent()) +// { +// color = QGC::colorCyan;//uas->getColor(); +// pen.setWidthF(refLineWidthToPen(0.8f)); +// } +// else +// { +// color = uas->getColor(); +// pen.setWidthF(refLineWidthToPen(0.4f)); +// } + + //pen.setColor(color); + if (pen) + { + pen->setWidthF(2); + painter.setPen(*pen); + } + else + { + QPen pen2(Qt::red); + pen2.setWidth(2); + painter.setPen(pen2); + } + painter.setBrush(Qt::NoBrush); + + float rad = (waypointSize/2.0f) * 0.8 * (1/sqrt(2.0f)); + painter.drawLine(p.x(), p.y(), p.x()+sin(yaw) * radius, p.y()-cos(yaw) * rad); + painter.drawPolygon(poly); } diff --git a/src/ui/map/Waypoint2DIcon.h b/src/ui/map/Waypoint2DIcon.h index 56b9a151bf6cd4b2a12dc17bd4c718ada29b8285..18c60973229ff1b1849bf4c2bf2ead57316f7ae1 100644 --- a/src/ui/map/Waypoint2DIcon.h +++ b/src/ui/map/Waypoint2DIcon.h @@ -2,16 +2,49 @@ #define WAYPOINT2DICON_H #include -#include "QGC2DIcon.h" +#include "qmapcontrol.h" -class Waypoint2DIcon : public QGC2DIcon +class Waypoint2DIcon : public qmapcontrol::Point { public: - explicit Waypoint2DIcon(QGraphicsItem* parent = 0); + /*! + * + * @param x longitude + * @param y latitude + * @param name name of the circle point + * @param alignment alignment (Middle or TopLeft) + * @param pen QPen for drawing + */ + Waypoint2DIcon(qreal x, qreal y, QString name = QString(), Alignment alignment = Middle, QPen* pen=0); - QRectF boundingRect() const; - void paint(QPainter*, const QStyleOptionGraphicsItem*, QWidget*); + //! + /*! + * + * @param x longitude + * @param y latitude + * @param radius the radius of the circle + * @param name name of the circle point + * @param alignment alignment (Middle or TopLeft) + * @param pen QPen for drawing + */ + Waypoint2DIcon(qreal x, qreal y, int radius = 10, QString name = QString(), Alignment alignment = Middle, QPen* pen=0); + virtual ~Waypoint2DIcon(); + //! sets the QPen which is used for drawing the circle + /*! + * A QPen can be used to modify the look of the drawn circle + * @param pen the QPen which should be used for drawing + * @see http://doc.trolltech.com/4.3/qpen.html + */ + virtual void setPen(QPen* pen); + + void setYaw(float yaw); + + void drawIcon(QPen* pen); + +protected: + float yaw; ///< Yaw angle of the MAV + int radius; ///< }; diff --git a/src/ui/map3D/CheetahGL.cc b/src/ui/map3D/CheetahGL.cc index 83b50f68b70007c9a935713561a8695b1ef16b7f..01d6ff1ae54bc969f64b3d3968a4019ef3f1bd61 100755 --- a/src/ui/map3D/CheetahGL.cc +++ b/src/ui/map3D/CheetahGL.cc @@ -1,59383 +1,59381 @@ -/*===================================================================== - -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - -======================================================================*/ - -/** - * @file - * @brief Generates a display list which renders a Pixhawk Cheetah MAV. - * - * @author Lionel Heng - * - */ - -/* -This file was produced by Deep Exploration Plugin: CPP Export filter. - -Copyright (C) 1999-2008 Right Hemisphere -Mail support@righthemisphere.com for support. -Visit http://www.righthemisphere.com/dexp.htm for updates. -*/ -#include "CheetahGL.h" - -#include -#include - - -struct sample_MATERIAL -{ - GLfloat ambient[3]; - GLfloat diffuse[3]; - GLfloat specular[3]; - GLfloat emission[3]; - GLfloat alpha; - GLfloat phExp; - int texture; -}; - -static sample_MATERIAL materials [1] = { - {{0.117647f,0.117647f,0.117647f}, {0.596078f,0.666667f,0.686275f}, {0.301176f,0.301176f,0.301176f}, {0.0f,0.0f,0.0f}, 1.0f,8.0f,-1} //Material #1 -}; - -// 38747 Verticies -// 0 Texture Coordinates -// 22155 Normals -// 77848 Triangles - -static unsigned short face_indicies[77848][9] = { -// Battery3.prt - {0,1,2 ,0,1,0 ,0,0,0}, {3,4,5 ,2,2,3 ,0,0,0}, {3,2,4 ,2,0,2 ,0,0,0}, - {5,4,6 ,3,2,3 ,0,0,0}, {2,3,0 ,0,2,0 ,0,0,0}, {7,1,0 ,1,1,0 ,0,0,0}, - {8,7,9 ,4,1,4 ,0,0,0}, {7,8,1 ,1,4,1 ,0,0,0}, {10,11,12 ,5,6,5 ,0,0,0}, - {13,14,15 ,7,7,8 ,0,0,0}, {13,12,14 ,7,5,7 ,0,0,0}, {15,14,16 ,8,7,8 ,0,0,0}, - {12,13,10 ,5,7,5 ,0,0,0}, {17,11,10 ,9,6,5 ,0,0,0}, {18,17,19 ,10,9,11 ,0,0,0}, - {17,18,11 ,9,10,6 ,0,0,0}, {20,21,22 ,12,13,12 ,0,0,0}, {23,24,25 ,14,14,15 ,0,0,0}, - {23,22,24 ,14,12,14 ,0,0,0}, {25,24,26 ,15,14,15 ,0,0,0}, {22,23,20 ,12,14,12 ,0,0,0}, - {27,21,20 ,13,13,12 ,0,0,0}, {28,27,29 ,16,13,16 ,0,0,0}, {27,28,21 ,13,16,13 ,0,0,0}, - {30,31,32 ,17,18,17 ,0,0,0}, {33,34,35 ,19,19,20 ,0,0,0}, {33,32,34 ,19,17,19 ,0,0,0}, - {35,34,36 ,20,19,20 ,0,0,0}, {32,33,30 ,17,19,17 ,0,0,0}, {37,31,30 ,18,18,17 ,0,0,0}, - {38,37,39 ,21,18,21 ,0,0,0}, {37,38,31 ,18,21,18 ,0,0,0}, {40,41,42 ,22,23,24 ,0,0,0}, - {43,44,45 ,25,26,27 ,0,0,0}, {46,40,42 ,28,22,24 ,0,0,0}, {45,44,46 ,27,26,28 ,0,0,0}, - {44,43,47 ,26,25,29 ,0,0,0}, {42,45,46 ,24,27,28 ,0,0,0}, {48,49,50 ,30,31,32 ,0,0,0}, - {49,51,50 ,31,33,32 ,0,0,0}, {47,52,48 ,29,34,30 ,0,0,0}, {49,48,52 ,31,30,34 ,0,0,0}, - {53,54,55 ,35,36,37 ,0,0,0}, {56,57,51 ,38,39,33 ,0,0,0}, {54,57,56 ,36,39,38 ,0,0,0}, - {54,56,55 ,36,38,37 ,0,0,0}, {55,58,53 ,37,40,35 ,0,0,0}, {50,51,57 ,32,33,39 ,0,0,0}, - {47,43,52 ,29,25,34 ,0,0,0}, {40,59,41 ,22,41,23 ,0,0,0}, {60,59,61 ,42,41,43 ,0,0,0}, - {59,60,41 ,41,42,23 ,0,0,0}, {62,63,61 ,44,45,43 ,0,0,0}, {60,61,63 ,42,43,45 ,0,0,0}, - {62,64,65 ,44,46,47 ,0,0,0}, {65,63,62 ,47,45,44 ,0,0,0}, {66,64,67 ,48,46,49 ,0,0,0}, - {64,66,65 ,46,48,47 ,0,0,0}, {68,69,67 ,50,51,49 ,0,0,0}, {66,67,69 ,48,49,51 ,0,0,0}, - {68,70,71 ,50,52,53 ,0,0,0}, {71,69,68 ,53,51,50 ,0,0,0}, {72,70,73 ,54,52,54 ,0,0,0}, - {70,72,71 ,52,54,53 ,0,0,0}, {74,75,76 ,22,55,24 ,0,0,0}, {77,78,79 ,56,57,58 ,0,0,0}, - {80,74,76 ,59,22,24 ,0,0,0}, {79,78,80 ,58,57,59 ,0,0,0}, {78,77,81 ,57,56,60 ,0,0,0}, - {76,79,80 ,24,58,59 ,0,0,0}, {82,83,84 ,61,62,63 ,0,0,0}, {83,85,84 ,62,64,63 ,0,0,0}, - {81,86,82 ,60,65,61 ,0,0,0}, {83,82,86 ,62,61,65 ,0,0,0}, {87,88,89 ,66,67,68 ,0,0,0}, - {90,91,85 ,69,70,64 ,0,0,0}, {88,91,90 ,67,70,69 ,0,0,0}, {88,90,89 ,67,69,68 ,0,0,0}, - {89,92,87 ,68,66,66 ,0,0,0}, {84,85,91 ,63,64,70 ,0,0,0}, {81,77,86 ,60,56,65 ,0,0,0}, - {74,93,75 ,22,71,55 ,0,0,0}, {94,93,95 ,72,71,43 ,0,0,0}, {93,94,75 ,71,72,55 ,0,0,0}, - {96,97,95 ,73,74,43 ,0,0,0}, {94,95,97 ,72,43,74 ,0,0,0}, {96,98,99 ,73,46,75 ,0,0,0}, - {99,97,96 ,75,74,73 ,0,0,0}, {100,98,101 ,76,46,77 ,0,0,0}, {98,100,99 ,46,76,75 ,0,0,0}, - {102,103,101 ,50,78,77 ,0,0,0}, {100,101,103 ,76,77,78 ,0,0,0}, - {102,104,105 ,50,79,80 ,0,0,0}, {105,103,102 ,80,78,50 ,0,0,0}, - {106,104,107 ,81,79,82 ,0,0,0}, {104,106,105 ,79,81,80 ,0,0,0}, - {108,109,110 ,83,84,85 ,0,0,0}, {111,112,113 ,86,87,88 ,0,0,0}, - {114,108,110 ,89,83,85 ,0,0,0}, {113,112,114 ,88,87,89 ,0,0,0}, - {112,111,115 ,87,86,90 ,0,0,0}, {110,113,114 ,85,88,89 ,0,0,0}, - {116,117,118 ,91,92,93 ,0,0,0}, {117,119,118 ,92,94,93 ,0,0,0}, - {115,120,116 ,90,95,91 ,0,0,0}, {117,116,120 ,92,91,95 ,0,0,0}, - {121,122,123 ,96,97,98 ,0,0,0}, {124,125,119 ,99,100,94 ,0,0,0}, - {122,125,124 ,97,100,99 ,0,0,0}, {122,124,123 ,97,99,98 ,0,0,0}, - {123,126,121 ,98,101,96 ,0,0,0}, {118,119,125 ,93,94,100 ,0,0,0}, - {115,111,120 ,90,86,95 ,0,0,0}, {108,127,109 ,83,102,84 ,0,0,0}, - {128,127,129 ,103,102,104 ,0,0,0}, {127,128,109 ,102,103,84 ,0,0,0}, - {130,131,129 ,105,106,104 ,0,0,0}, {128,129,131 ,103,104,106 ,0,0,0}, - {130,132,133 ,105,107,108 ,0,0,0}, {133,131,130 ,108,106,105 ,0,0,0}, - {134,132,135 ,109,107,110 ,0,0,0}, {132,134,133 ,107,109,108 ,0,0,0}, - {136,137,135 ,111,112,110 ,0,0,0}, {134,135,137 ,109,110,112 ,0,0,0}, - {136,138,139 ,111,113,114 ,0,0,0}, {139,137,136 ,114,112,111 ,0,0,0}, - {140,138,141 ,54,113,54 ,0,0,0}, {138,140,139 ,113,54,114 ,0,0,0}, - {142,143,144 ,83,115,85 ,0,0,0}, {145,146,147 ,116,117,118 ,0,0,0}, - {148,142,144 ,119,83,85 ,0,0,0}, {147,146,148 ,118,117,119 ,0,0,0}, - {146,145,149 ,117,116,120 ,0,0,0}, {144,147,148 ,85,118,119 ,0,0,0}, - {150,151,152 ,121,122,123 ,0,0,0}, {151,153,152 ,122,124,123 ,0,0,0}, - {149,154,150 ,120,125,121 ,0,0,0}, {151,150,154 ,122,121,125 ,0,0,0}, - {155,156,157 ,126,127,128 ,0,0,0}, {158,159,153 ,129,130,124 ,0,0,0}, - {156,159,158 ,127,130,129 ,0,0,0}, {156,158,157 ,127,129,128 ,0,0,0}, - {157,160,155 ,128,35,126 ,0,0,0}, {152,153,159 ,123,124,130 ,0,0,0}, - {149,145,154 ,120,116,125 ,0,0,0}, {142,161,143 ,83,131,115 ,0,0,0}, - {162,161,163 ,132,131,133 ,0,0,0}, {161,162,143 ,131,132,115 ,0,0,0}, - {164,165,163 ,134,74,133 ,0,0,0}, {162,163,165 ,132,133,74 ,0,0,0}, - {164,166,167 ,134,135,108 ,0,0,0}, {167,165,164 ,108,74,134 ,0,0,0}, - {168,166,169 ,136,135,137 ,0,0,0}, {166,168,167 ,135,136,108 ,0,0,0}, - {170,171,169 ,138,139,137 ,0,0,0}, {168,169,171 ,136,137,139 ,0,0,0}, - {170,172,173 ,138,79,80 ,0,0,0}, {173,171,170 ,80,139,138 ,0,0,0}, - {174,172,175 ,140,79,140 ,0,0,0}, {172,174,173 ,79,140,80 ,0,0,0}, - {176,177,178 ,141,142,143 ,0,0,0}, {179,180,181 ,144,145,146 ,0,0,0}, - {182,176,178 ,147,141,143 ,0,0,0}, {181,180,182 ,146,145,147 ,0,0,0}, - {180,179,183 ,145,144,148 ,0,0,0}, {178,181,182 ,143,146,147 ,0,0,0}, - {184,185,186 ,149,150,151 ,0,0,0}, {185,187,186 ,150,152,151 ,0,0,0}, - {183,188,184 ,148,153,149 ,0,0,0}, {185,184,188 ,150,149,153 ,0,0,0}, - {189,190,191 ,126,154,155 ,0,0,0}, {192,193,187 ,156,157,152 ,0,0,0}, - {190,193,192 ,154,157,156 ,0,0,0}, {190,192,191 ,154,156,155 ,0,0,0}, - {191,194,189 ,155,35,126 ,0,0,0}, {186,187,193 ,151,152,157 ,0,0,0}, - {183,179,188 ,148,144,153 ,0,0,0}, {176,195,177 ,141,158,142 ,0,0,0}, - {196,195,197 ,159,158,160 ,0,0,0}, {195,196,177 ,158,159,142 ,0,0,0}, - {198,199,197 ,161,162,160 ,0,0,0}, {196,197,199 ,159,160,162 ,0,0,0}, - {198,200,201 ,161,163,164 ,0,0,0}, {201,199,198 ,164,162,161 ,0,0,0}, - {202,200,203 ,165,163,166 ,0,0,0}, {200,202,201 ,163,165,164 ,0,0,0}, - {204,205,203 ,167,168,166 ,0,0,0}, {202,203,205 ,165,166,168 ,0,0,0}, - {204,206,207 ,167,169,170 ,0,0,0}, {207,205,204 ,170,168,167 ,0,0,0}, - {208,206,209 ,140,169,140 ,0,0,0}, {206,208,207 ,169,140,170 ,0,0,0}, - {210,211,212 ,171,172,173 ,0,0,0}, {213,214,215 ,174,175,176 ,0,0,0}, - {216,210,212 ,177,171,173 ,0,0,0}, {215,214,216 ,176,175,177 ,0,0,0}, - {214,213,217 ,175,174,178 ,0,0,0}, {212,215,216 ,173,176,177 ,0,0,0}, - {218,219,220 ,179,180,181 ,0,0,0}, {219,221,220 ,180,182,181 ,0,0,0}, - {217,222,218 ,178,183,179 ,0,0,0}, {219,218,222 ,180,179,183 ,0,0,0}, - {223,224,225 ,35,184,185 ,0,0,0}, {226,227,221 ,186,187,182 ,0,0,0}, - {224,227,226 ,184,187,186 ,0,0,0}, {224,226,225 ,184,186,185 ,0,0,0}, - {225,228,223 ,185,40,35 ,0,0,0}, {220,221,227 ,181,182,187 ,0,0,0}, - {217,213,222 ,178,174,183 ,0,0,0}, {210,229,211 ,171,188,172 ,0,0,0}, - {230,229,231 ,189,188,104 ,0,0,0}, {229,230,211 ,188,189,172 ,0,0,0}, - {232,233,231 ,190,45,104 ,0,0,0}, {230,231,233 ,189,104,45 ,0,0,0}, - {232,234,235 ,190,191,192 ,0,0,0}, {235,233,232 ,192,45,190 ,0,0,0}, - {236,234,237 ,193,191,194 ,0,0,0}, {234,236,235 ,191,193,192 ,0,0,0}, - {238,239,237 ,111,195,194 ,0,0,0}, {236,237,239 ,193,194,195 ,0,0,0}, - {238,240,241 ,111,52,53 ,0,0,0}, {241,239,238 ,53,195,111 ,0,0,0}, - {242,240,243 ,54,52,54 ,0,0,0}, {240,242,241 ,52,54,53 ,0,0,0}, - {244,245,246 ,196,197,197 ,0,0,0}, {247,248,249 ,198,196,198 ,0,0,0}, - {248,244,246 ,196,196,197 ,0,0,0}, {247,249,250 ,198,198,199 ,0,0,0}, - {251,252,253 ,200,82,200 ,0,0,0}, {250,249,254 ,199,198,199 ,0,0,0}, - {254,253,250 ,199,200,199 ,0,0,0}, {253,254,251 ,200,199,200 ,0,0,0}, - {252,251,255 ,82,200,201 ,0,0,0}, {248,247,244 ,196,198,196 ,0,0,0}, - {256,246,245 ,202,197,197 ,0,0,0}, {257,256,258 ,203,202,202 ,0,0,0}, - {245,258,256 ,197,202,202 ,0,0,0}, {259,260,257 ,203,204,203 ,0,0,0}, - {257,258,259 ,203,202,203 ,0,0,0}, {260,261,262 ,204,204,205 ,0,0,0}, - {261,260,259 ,204,204,203 ,0,0,0}, {261,263,262 ,204,205,205 ,0,0,0}, - {264,265,266 ,206,207,208 ,0,0,0}, {267,264,268 ,209,206,210 ,0,0,0}, - {264,267,265 ,206,209,207 ,0,0,0}, {269,270,268 ,211,212,210 ,0,0,0}, - {267,268,270 ,209,210,212 ,0,0,0}, {269,271,272 ,211,213,214 ,0,0,0}, - {272,270,269 ,214,212,211 ,0,0,0}, {273,271,274 ,215,213,216 ,0,0,0}, - {271,273,272 ,213,215,214 ,0,0,0}, {275,276,274 ,217,218,216 ,0,0,0}, - {273,274,276 ,215,216,218 ,0,0,0}, {275,277,278 ,217,219,220 ,0,0,0}, - {278,276,275 ,220,218,217 ,0,0,0}, {279,278,277 ,221,220,219 ,0,0,0}, - {279,280,278 ,221,221,220 ,0,0,0}, {264,266,281 ,206,208,222 ,0,0,0}, - {282,283,266 ,223,224,208 ,0,0,0}, {281,266,283 ,222,208,224 ,0,0,0}, - {282,284,285 ,223,225,226 ,0,0,0}, {285,283,282 ,226,224,223 ,0,0,0}, - {286,284,287 ,227,225,228 ,0,0,0}, {284,286,285 ,225,227,226 ,0,0,0}, - {288,289,287 ,229,230,228 ,0,0,0}, {286,287,289 ,227,228,230 ,0,0,0}, - {288,290,291 ,229,231,232 ,0,0,0}, {291,289,288 ,232,230,229 ,0,0,0}, - {292,290,293 ,233,231,234 ,0,0,0}, {290,292,291 ,231,233,232 ,0,0,0}, - {293,294,292 ,234,235,233 ,0,0,0}, {292,294,295 ,233,235,235 ,0,0,0}, - {296,297,298 ,236,237,238 ,0,0,0}, {299,300,296 ,239,240,236 ,0,0,0}, - {296,298,299 ,236,238,239 ,0,0,0}, {300,301,302 ,240,241,242 ,0,0,0}, - {301,300,299 ,241,240,239 ,0,0,0}, {303,302,304 ,243,242,244 ,0,0,0}, - {301,304,302 ,241,244,242 ,0,0,0}, {305,306,303 ,245,246,243 ,0,0,0}, - {303,304,305 ,243,244,245 ,0,0,0}, {307,306,305 ,247,246,245 ,0,0,0}, - {307,308,306 ,247,126,246 ,0,0,0}, {298,297,309 ,238,237,248 ,0,0,0}, - {309,310,311 ,248,249,250 ,0,0,0}, {310,309,297 ,249,248,237 ,0,0,0}, - {312,311,313 ,251,250,252 ,0,0,0}, {310,313,311 ,249,252,250 ,0,0,0}, - {314,315,312 ,253,254,251 ,0,0,0}, {312,313,314 ,251,252,253 ,0,0,0}, - {315,316,317 ,254,255,256 ,0,0,0}, {316,315,314 ,255,254,253 ,0,0,0}, - {316,318,317 ,255,257,256 ,0,0,0}, {317,318,319 ,256,257,257 ,0,0,0}, - {320,321,322 ,258,259,260 ,0,0,0}, {323,320,324 ,261,258,262 ,0,0,0}, - {320,323,321 ,258,261,259 ,0,0,0}, {325,326,324 ,263,264,262 ,0,0,0}, - {323,324,326 ,261,262,264 ,0,0,0}, {325,327,328 ,263,265,266 ,0,0,0}, - {328,326,325 ,266,264,263 ,0,0,0}, {329,327,330 ,267,265,268 ,0,0,0}, - {327,329,328 ,265,267,266 ,0,0,0}, {331,332,330 ,269,270,268 ,0,0,0}, - {329,330,332 ,267,268,270 ,0,0,0}, {331,333,334 ,269,271,272 ,0,0,0}, - {334,332,331 ,272,270,269 ,0,0,0}, {335,334,333 ,273,272,271 ,0,0,0}, - {335,336,334 ,273,273,272 ,0,0,0}, {320,322,337 ,258,260,274 ,0,0,0}, - {338,339,322 ,275,276,260 ,0,0,0}, {337,322,339 ,274,260,276 ,0,0,0}, - {338,340,341 ,275,277,278 ,0,0,0}, {341,339,338 ,278,276,275 ,0,0,0}, - {342,340,343 ,279,277,280 ,0,0,0}, {340,342,341 ,277,279,278 ,0,0,0}, - {344,345,343 ,281,282,280 ,0,0,0}, {342,343,345 ,279,280,282 ,0,0,0}, - {344,346,347 ,281,283,284 ,0,0,0}, {347,345,344 ,284,282,281 ,0,0,0}, - {348,346,349 ,285,283,286 ,0,0,0}, {346,348,347 ,283,285,284 ,0,0,0}, - {349,350,348 ,286,257,285 ,0,0,0}, {348,350,351 ,285,257,257 ,0,0,0}, - {352,353,354 ,287,288,288 ,0,0,0}, {355,356,357 ,289,287,289 ,0,0,0}, - {356,352,354 ,287,287,288 ,0,0,0}, {355,357,358 ,289,289,290 ,0,0,0}, - {359,360,361 ,291,82,291 ,0,0,0}, {358,357,362 ,290,289,290 ,0,0,0}, - {362,361,358 ,290,291,290 ,0,0,0}, {361,362,359 ,291,290,291 ,0,0,0}, - {360,359,363 ,82,291,292 ,0,0,0}, {356,355,352 ,287,289,287 ,0,0,0}, - {364,354,353 ,293,288,288 ,0,0,0}, {365,364,366 ,203,293,293 ,0,0,0}, - {353,366,364 ,288,293,293 ,0,0,0}, {367,368,365 ,203,294,203 ,0,0,0}, - {365,366,367 ,203,293,203 ,0,0,0}, {368,369,370 ,294,294,205 ,0,0,0}, - {369,368,367 ,294,294,203 ,0,0,0}, {369,371,370 ,294,205,205 ,0,0,0}, - {372,373,374 ,295,296,295 ,0,0,0}, {375,373,376 ,296,296,297 ,0,0,0}, - {373,375,374 ,296,296,295 ,0,0,0}, {377,378,376 ,298,297,297 ,0,0,0}, - {375,376,378 ,296,297,297 ,0,0,0}, {377,379,380 ,298,299,298 ,0,0,0}, - {380,378,377 ,298,297,298 ,0,0,0}, {379,381,380 ,299,300,298 ,0,0,0}, - {382,372,374 ,301,295,295 ,0,0,0}, {383,384,382 ,302,301,301 ,0,0,0}, - {372,382,384 ,295,301,301 ,0,0,0}, {383,385,386 ,302,303,302 ,0,0,0}, - {386,384,383 ,302,301,302 ,0,0,0}, {387,385,388 ,303,303,304 ,0,0,0}, - {385,387,386 ,303,303,302 ,0,0,0}, {387,388,389 ,303,304,304 ,0,0,0}, - {390,391,392 ,305,306,305 ,0,0,0}, {393,391,394 ,306,306,307 ,0,0,0}, - {391,393,392 ,306,306,305 ,0,0,0}, {395,396,394 ,308,307,307 ,0,0,0}, - {393,394,396 ,306,307,307 ,0,0,0}, {395,397,398 ,308,309,308 ,0,0,0}, - {398,396,395 ,308,307,308 ,0,0,0}, {397,399,398 ,309,310,308 ,0,0,0}, - {400,390,392 ,311,305,305 ,0,0,0}, {401,402,400 ,312,311,311 ,0,0,0}, - {390,400,402 ,305,311,311 ,0,0,0}, {401,403,404 ,312,313,312 ,0,0,0}, - {404,402,401 ,312,311,312 ,0,0,0}, {405,403,406 ,313,313,314 ,0,0,0}, - {403,405,404 ,313,313,312 ,0,0,0}, {405,406,407 ,313,314,314 ,0,0,0}, - {408,399,397 ,315,309,309 ,0,0,0}, {409,410,411 ,316,317,317 ,0,0,0}, - {412,413,414 ,318,318,315 ,0,0,0}, {415,416,417 ,319,319,320 ,0,0,0}, - {418,419,420 ,316,321,321 ,0,0,0}, {421,422,417 ,322,320,320 ,0,0,0}, - {415,417,422 ,319,320,320 ,0,0,0}, {423,422,421 ,323,320,322 ,0,0,0}, - {419,416,420 ,321,319,321 ,0,0,0}, {420,416,415 ,321,319,319 ,0,0,0}, - {418,410,409 ,316,317,316 ,0,0,0}, {418,409,419 ,316,316,321 ,0,0,0}, - {411,413,412 ,317,318,318 ,0,0,0}, {410,413,411 ,317,318,317 ,0,0,0}, - {408,414,399 ,315,315,309 ,0,0,0}, {412,414,408 ,318,315,315 ,0,0,0}, - {424,425,426 ,324,324,324 ,0,0,0}, {424,426,427 ,324,324,324 ,0,0,0}, - {428,429,430 ,325,326,325 ,0,0,0}, {431,432,428 ,327,327,325 ,0,0,0}, - {428,430,431 ,325,325,327 ,0,0,0}, {432,433,434 ,327,328,329 ,0,0,0}, - {433,432,431 ,328,327,327 ,0,0,0}, {435,434,436 ,330,329,331 ,0,0,0}, - {433,436,434 ,328,331,329 ,0,0,0}, {437,438,435 ,332,332,330 ,0,0,0}, - {435,436,437 ,330,331,332 ,0,0,0}, {438,439,440 ,332,333,334 ,0,0,0}, - {439,438,437 ,333,332,332 ,0,0,0}, {441,440,442 ,335,334,335 ,0,0,0}, - {439,442,440 ,333,335,334 ,0,0,0}, {443,444,441 ,336,336,335 ,0,0,0}, - {441,442,443 ,335,335,336 ,0,0,0}, {430,429,445 ,325,326,337 ,0,0,0}, - {446,445,447 ,338,337,339 ,0,0,0}, {429,447,445 ,326,339,337 ,0,0,0}, - {448,449,446 ,340,341,338 ,0,0,0}, {446,447,448 ,338,339,340 ,0,0,0}, - {449,450,451 ,341,342,343 ,0,0,0}, {450,449,448 ,342,341,340 ,0,0,0}, - {452,451,453 ,344,343,345 ,0,0,0}, {450,453,451 ,342,345,343 ,0,0,0}, - {454,455,452 ,346,347,344 ,0,0,0}, {452,453,454 ,344,345,346 ,0,0,0}, - {455,456,457 ,347,348,349 ,0,0,0}, {456,455,454 ,348,347,346 ,0,0,0}, - {456,28,457 ,348,16,349 ,0,0,0}, {457,28,29 ,349,16,350 ,0,0,0}, - {458,381,379 ,351,299,299 ,0,0,0}, {459,460,461 ,352,353,353 ,0,0,0}, - {462,463,464 ,354,354,351 ,0,0,0}, {465,466,467 ,355,355,356 ,0,0,0}, - {468,469,470 ,352,357,357 ,0,0,0}, {471,472,467 ,358,356,356 ,0,0,0}, - {465,467,472 ,355,356,356 ,0,0,0}, {473,472,471 ,359,356,358 ,0,0,0}, - {469,466,470 ,357,355,357 ,0,0,0}, {470,466,465 ,357,355,355 ,0,0,0}, - {468,460,459 ,352,353,352 ,0,0,0}, {468,459,469 ,352,352,357 ,0,0,0}, - {461,463,462 ,353,354,354 ,0,0,0}, {460,463,461 ,353,354,353 ,0,0,0}, - {458,464,381 ,351,351,299 ,0,0,0}, {462,464,458 ,354,351,351 ,0,0,0}, - {474,475,476 ,360,324,360 ,0,0,0}, {475,474,477 ,324,360,324 ,0,0,0}, - {478,479,480 ,361,362,361 ,0,0,0}, {481,482,478 ,363,363,361 ,0,0,0}, - {478,480,481 ,361,361,363 ,0,0,0}, {482,483,484 ,363,364,365 ,0,0,0}, - {483,482,481 ,364,363,363 ,0,0,0}, {485,484,486 ,366,365,367 ,0,0,0}, - {483,486,484 ,364,367,365 ,0,0,0}, {487,488,485 ,368,369,366 ,0,0,0}, - {485,486,487 ,366,367,368 ,0,0,0}, {488,489,490 ,369,370,370 ,0,0,0}, - {489,488,487 ,370,369,368 ,0,0,0}, {491,490,492 ,371,370,371 ,0,0,0}, - {489,492,490 ,370,371,370 ,0,0,0}, {493,494,491 ,372,372,371 ,0,0,0}, - {491,492,493 ,371,371,372 ,0,0,0}, {480,479,495 ,361,362,373 ,0,0,0}, - {496,495,497 ,374,373,375 ,0,0,0}, {479,497,495 ,362,375,373 ,0,0,0}, - {498,499,496 ,376,377,374 ,0,0,0}, {496,497,498 ,374,375,376 ,0,0,0}, - {499,500,501 ,377,378,379 ,0,0,0}, {500,499,498 ,378,377,376 ,0,0,0}, - {502,501,503 ,380,379,381 ,0,0,0}, {500,503,501 ,378,381,379 ,0,0,0}, - {504,505,502 ,382,383,380 ,0,0,0}, {502,503,504 ,380,381,382 ,0,0,0}, - {505,506,507 ,383,384,385 ,0,0,0}, {506,505,504 ,384,383,382 ,0,0,0}, - {506,8,507 ,384,4,385 ,0,0,0}, {507,8,9 ,385,4,386 ,0,0,0}, {363,508,509 ,387,388,388 ,0,0,0}, - {510,511,512 ,389,389,390 ,0,0,0}, {513,514,515 ,390,391,391 ,0,0,0}, - {516,517,518 ,392,393,392 ,0,0,0}, {519,520,521 ,394,394,393 ,0,0,0}, - {522,523,518 ,395,395,392 ,0,0,0}, {516,518,523 ,392,392,395 ,0,0,0}, - {522,524,525 ,395,396,396 ,0,0,0}, {525,523,522 ,396,395,395 ,0,0,0}, - {516,521,517 ,392,393,393 ,0,0,0}, {515,514,508 ,391,391,388 ,0,0,0}, - {521,520,517 ,393,394,393 ,0,0,0}, {519,510,520 ,394,389,394 ,0,0,0}, - {511,513,512 ,389,390,390 ,0,0,0}, {519,511,510 ,394,389,389 ,0,0,0}, - {512,513,515 ,390,390,391 ,0,0,0}, {363,509,360 ,387,388,397 ,0,0,0}, - {508,514,509 ,388,391,388 ,0,0,0}, {526,527,528 ,398,399,400 ,0,0,0}, - {529,528,530 ,401,400,402 ,0,0,0}, {527,530,528 ,399,402,400 ,0,0,0}, - {530,531,532 ,402,403,404 ,0,0,0}, {532,529,530 ,404,401,402 ,0,0,0}, - {533,531,534 ,405,403,406 ,0,0,0}, {531,533,532 ,403,405,404 ,0,0,0}, - {535,536,534 ,407,408,406 ,0,0,0}, {533,534,536 ,405,406,408 ,0,0,0}, - {535,537,538 ,407,409,410 ,0,0,0}, {538,536,535 ,410,408,407 ,0,0,0}, - {539,537,540 ,411,409,412 ,0,0,0}, {537,539,538 ,409,411,410 ,0,0,0}, - {541,539,542 ,413,411,414 ,0,0,0}, {540,542,539 ,412,414,411 ,0,0,0}, - {543,544,541 ,415,416,413 ,0,0,0}, {541,542,543 ,413,414,415 ,0,0,0}, - {545,543,546 ,417,415,418 ,0,0,0}, {543,545,544 ,415,417,416 ,0,0,0}, - {547,548,546 ,419,420,418 ,0,0,0}, {545,546,548 ,417,418,420 ,0,0,0}, - {547,549,550 ,419,421,422 ,0,0,0}, {550,548,547 ,422,420,419 ,0,0,0}, - {551,549,552 ,423,421,424 ,0,0,0}, {549,551,550 ,421,423,422 ,0,0,0}, - {553,554,552 ,425,426,424 ,0,0,0}, {551,552,554 ,423,424,426 ,0,0,0}, - {555,556,554 ,427,427,426 ,0,0,0}, {554,553,555 ,426,425,427 ,0,0,0}, - {527,526,557 ,399,398,428 ,0,0,0}, {557,558,559 ,428,429,430 ,0,0,0}, - {558,557,526 ,429,428,398 ,0,0,0}, {560,561,558 ,431,432,429 ,0,0,0}, - {559,558,561 ,430,429,432 ,0,0,0}, {560,562,563 ,431,433,434 ,0,0,0}, - {563,561,560 ,434,432,431 ,0,0,0}, {564,562,565 ,435,433,436 ,0,0,0}, - {562,564,563 ,433,435,434 ,0,0,0}, {566,567,565 ,437,438,436 ,0,0,0}, - {564,565,567 ,435,436,438 ,0,0,0}, {566,568,569 ,437,439,440 ,0,0,0}, - {569,567,566 ,440,438,437 ,0,0,0}, {569,570,571 ,440,441,442 ,0,0,0}, - {570,569,568 ,441,440,439 ,0,0,0}, {572,571,573 ,443,442,444 ,0,0,0}, - {570,573,571 ,441,444,442 ,0,0,0}, {573,574,575 ,444,445,446 ,0,0,0}, - {575,572,573 ,446,443,444 ,0,0,0}, {576,574,577 ,447,445,448 ,0,0,0}, - {574,576,575 ,445,447,446 ,0,0,0}, {578,579,577 ,449,450,448 ,0,0,0}, - {576,577,579 ,447,448,450 ,0,0,0}, {578,580,581 ,449,451,452 ,0,0,0}, - {581,579,578 ,452,450,449 ,0,0,0}, {582,580,583 ,453,451,454 ,0,0,0}, - {580,582,581 ,451,453,452 ,0,0,0}, {583,584,582 ,454,455,453 ,0,0,0}, - {582,584,585 ,453,455,456 ,0,0,0}, {586,587,588 ,457,458,459 ,0,0,0}, - {586,588,589 ,457,459,460 ,0,0,0}, {590,336,335 ,461,273,273 ,0,0,0}, - {591,592,593 ,462,463,464 ,0,0,0}, {594,595,596 ,465,466,467 ,0,0,0}, - {597,598,599 ,468,469,470 ,0,0,0}, {600,601,602 ,471,472,473 ,0,0,0}, - {603,604,605 ,474,475,476 ,0,0,0}, {606,607,608 ,477,478,479 ,0,0,0}, - {609,610,611 ,480,481,482 ,0,0,0}, {609,612,604 ,480,483,475 ,0,0,0}, - {613,610,614 ,484,481,485 ,0,0,0}, {610,613,611 ,481,484,482 ,0,0,0}, - {615,616,614 ,486,487,485 ,0,0,0}, {613,614,616 ,484,485,487 ,0,0,0}, - {617,618,616 ,488,488,487 ,0,0,0}, {616,615,617 ,487,486,488 ,0,0,0}, - {605,604,612 ,476,475,483 ,0,0,0}, {609,611,612 ,480,482,483 ,0,0,0}, - {606,603,607 ,477,474,478 ,0,0,0}, {603,605,607 ,474,476,478 ,0,0,0}, - {599,606,597 ,470,477,468 ,0,0,0}, {606,608,597 ,477,479,468 ,0,0,0}, - {602,601,598 ,473,472,469 ,0,0,0}, {602,598,597 ,473,469,468 ,0,0,0}, - {600,592,591 ,471,463,462 ,0,0,0}, {600,591,601 ,471,462,472 ,0,0,0}, - {593,595,594 ,464,466,465 ,0,0,0}, {592,595,593 ,463,466,464 ,0,0,0}, - {590,596,619 ,461,467,489 ,0,0,0}, {594,596,590 ,465,467,461 ,0,0,0}, - {336,590,619 ,273,461,489 ,0,0,0}, {620,621,622 ,490,491,492 ,0,0,0}, - {623,624,621 ,493,494,491 ,0,0,0}, {625,626,627 ,495,496,497 ,0,0,0}, - {625,620,622 ,495,490,492 ,0,0,0}, {628,629,630 ,498,499,500 ,0,0,0}, - {627,620,625 ,497,490,495 ,0,0,0}, {626,630,629 ,496,500,499 ,0,0,0}, - {631,628,630 ,501,498,500 ,0,0,0}, {627,626,629 ,497,496,499 ,0,0,0}, - {632,633,634 ,502,503,504 ,0,0,0}, {635,632,634 ,505,502,504 ,0,0,0}, - {636,631,633 ,506,501,503 ,0,0,0}, {633,632,636 ,503,502,506 ,0,0,0}, - {634,637,635 ,504,507,505 ,0,0,0}, {631,636,628 ,501,506,498 ,0,0,0}, - {635,637,638 ,505,507,508 ,0,0,0}, {622,621,624 ,492,491,494 ,0,0,0}, - {639,638,637 ,508,508,507 ,0,0,0}, {623,640,641 ,493,509,510 ,0,0,0}, - {641,624,623 ,510,494,493 ,0,0,0}, {642,640,643 ,511,509,512 ,0,0,0}, - {640,642,641 ,509,511,510 ,0,0,0}, {644,645,643 ,513,514,512 ,0,0,0}, - {642,643,645 ,511,512,514 ,0,0,0}, {644,646,647 ,513,515,516 ,0,0,0}, - {647,645,644 ,516,514,513 ,0,0,0}, {648,646,649 ,517,515,518 ,0,0,0}, - {646,648,647 ,515,517,516 ,0,0,0}, {650,651,649 ,519,520,518 ,0,0,0}, - {648,649,651 ,517,518,520 ,0,0,0}, {650,652,653 ,519,521,522 ,0,0,0}, - {653,651,650 ,522,520,519 ,0,0,0}, {654,652,655 ,523,521,524 ,0,0,0}, - {652,654,653 ,521,523,522 ,0,0,0}, {654,655,656 ,523,524,525 ,0,0,0}, - {656,655,657 ,525,524,525 ,0,0,0}, {658,308,307 ,526,527,247 ,0,0,0}, - {659,660,661 ,528,529,530 ,0,0,0}, {662,663,664 ,531,532,533 ,0,0,0}, - {665,666,667 ,534,535,536 ,0,0,0}, {668,669,670 ,537,538,539 ,0,0,0}, - {671,672,673 ,540,541,542 ,0,0,0}, {674,671,667 ,543,540,536 ,0,0,0}, - {675,673,676 ,544,542,545 ,0,0,0}, {672,676,673 ,541,545,542 ,0,0,0}, - {677,678,675 ,546,546,544 ,0,0,0}, {675,676,677 ,544,545,546 ,0,0,0}, - {666,674,667 ,535,543,536 ,0,0,0}, {674,672,671 ,543,541,540 ,0,0,0}, - {670,669,665 ,539,538,534 ,0,0,0}, {669,666,665 ,538,535,534 ,0,0,0}, - {659,661,668 ,528,530,537 ,0,0,0}, {659,668,670 ,528,537,539 ,0,0,0}, - {660,663,662 ,529,532,531 ,0,0,0}, {660,662,661 ,529,531,530 ,0,0,0}, - {664,679,658 ,533,547,526 ,0,0,0}, {663,679,664 ,532,547,533 ,0,0,0}, - {308,658,679 ,527,526,547 ,0,0,0}, {680,681,682 ,548,549,550 ,0,0,0}, - {683,684,681 ,551,552,549 ,0,0,0}, {685,686,687 ,553,554,555 ,0,0,0}, - {685,680,682 ,553,548,550 ,0,0,0}, {688,689,690 ,556,557,558 ,0,0,0}, - {687,680,685 ,555,548,553 ,0,0,0}, {686,690,689 ,554,558,557 ,0,0,0}, - {691,688,690 ,559,556,558 ,0,0,0}, {687,686,689 ,555,554,557 ,0,0,0}, - {692,693,694 ,560,561,562 ,0,0,0}, {695,692,694 ,563,560,562 ,0,0,0}, - {696,691,693 ,564,559,561 ,0,0,0}, {693,692,696 ,561,560,564 ,0,0,0}, - {694,697,695 ,562,565,563 ,0,0,0}, {691,696,688 ,559,564,556 ,0,0,0}, - {695,697,698 ,563,565,508 ,0,0,0}, {682,681,684 ,550,549,552 ,0,0,0}, - {699,698,697 ,508,508,565 ,0,0,0}, {683,700,701 ,551,566,567 ,0,0,0}, - {701,684,683 ,567,552,551 ,0,0,0}, {702,700,703 ,568,566,569 ,0,0,0}, - {700,702,701 ,566,568,567 ,0,0,0}, {704,705,703 ,570,571,569 ,0,0,0}, - {702,703,705 ,568,569,571 ,0,0,0}, {704,706,707 ,570,572,573 ,0,0,0}, - {707,705,704 ,573,571,570 ,0,0,0}, {708,706,709 ,574,572,575 ,0,0,0}, - {706,708,707 ,572,574,573 ,0,0,0}, {710,711,709 ,576,577,575 ,0,0,0}, - {708,709,711 ,574,575,577 ,0,0,0}, {710,712,713 ,576,578,579 ,0,0,0}, - {713,711,710 ,579,577,576 ,0,0,0}, {714,712,715 ,580,578,581 ,0,0,0}, - {712,714,713 ,578,580,579 ,0,0,0}, {714,715,716 ,580,581,525 ,0,0,0}, - {716,715,717 ,525,581,525 ,0,0,0}, {718,280,279 ,582,221,221 ,0,0,0}, - {719,720,721 ,583,584,585 ,0,0,0}, {722,723,724 ,586,587,588 ,0,0,0}, - {725,726,727 ,589,590,591 ,0,0,0}, {728,729,730 ,592,593,594 ,0,0,0}, - {731,732,733 ,595,596,597 ,0,0,0}, {734,735,736 ,598,599,600 ,0,0,0}, - {737,738,739 ,601,602,603 ,0,0,0}, {737,740,732 ,601,604,596 ,0,0,0}, - {741,738,742 ,605,602,606 ,0,0,0}, {738,741,739 ,602,605,603 ,0,0,0}, - {743,744,742 ,607,608,606 ,0,0,0}, {741,742,744 ,605,606,608 ,0,0,0}, - {745,746,744 ,546,546,608 ,0,0,0}, {744,743,745 ,608,607,546 ,0,0,0}, - {733,732,740 ,597,596,604 ,0,0,0}, {737,739,740 ,601,603,604 ,0,0,0}, - {734,731,735 ,598,595,599 ,0,0,0}, {731,733,735 ,595,597,599 ,0,0,0}, - {727,734,725 ,591,598,589 ,0,0,0}, {734,736,725 ,598,600,589 ,0,0,0}, - {730,729,726 ,594,593,590 ,0,0,0}, {730,726,725 ,594,590,589 ,0,0,0}, - {728,720,719 ,592,584,583 ,0,0,0}, {728,719,729 ,592,583,593 ,0,0,0}, - {721,723,722 ,585,587,586 ,0,0,0}, {720,723,721 ,584,587,585 ,0,0,0}, - {718,724,747 ,582,588,609 ,0,0,0}, {722,724,718 ,586,588,582 ,0,0,0}, - {280,718,747 ,221,582,609 ,0,0,0}, {748,749,750 ,610,611,610 ,0,0,0}, - {749,748,751 ,611,610,611 ,0,0,0}, {752,753,754 ,612,613,614 ,0,0,0}, - {755,754,756 ,615,614,616 ,0,0,0}, {753,756,754 ,613,616,614 ,0,0,0}, - {756,757,758 ,616,617,618 ,0,0,0}, {758,755,756 ,618,615,616 ,0,0,0}, - {759,757,760 ,619,617,620 ,0,0,0}, {757,759,758 ,617,619,618 ,0,0,0}, - {761,762,760 ,621,622,620 ,0,0,0}, {759,760,762 ,619,620,622 ,0,0,0}, - {761,763,764 ,621,623,624 ,0,0,0}, {764,762,761 ,624,622,621 ,0,0,0}, - {765,763,766 ,625,623,626 ,0,0,0}, {763,765,764 ,623,625,624 ,0,0,0}, - {767,765,768 ,627,625,628 ,0,0,0}, {766,768,765 ,626,628,625 ,0,0,0}, - {769,770,767 ,629,630,627 ,0,0,0}, {767,768,769 ,627,628,629 ,0,0,0}, - {771,769,772 ,631,629,632 ,0,0,0}, {769,771,770 ,629,631,630 ,0,0,0}, - {773,774,772 ,633,634,632 ,0,0,0}, {771,772,774 ,631,632,634 ,0,0,0}, - {773,775,776 ,633,635,636 ,0,0,0}, {776,774,773 ,636,634,633 ,0,0,0}, - {777,775,778 ,637,635,638 ,0,0,0}, {775,777,776 ,635,637,636 ,0,0,0}, - {779,780,778 ,639,640,638 ,0,0,0}, {777,778,780 ,637,638,640 ,0,0,0}, - {781,782,780 ,641,641,640 ,0,0,0}, {780,779,781 ,640,639,641 ,0,0,0}, - {753,752,783 ,613,612,642 ,0,0,0}, {783,784,785 ,642,643,644 ,0,0,0}, - {784,783,752 ,643,642,612 ,0,0,0}, {786,787,784 ,645,646,643 ,0,0,0}, - {785,784,787 ,644,643,646 ,0,0,0}, {786,788,789 ,645,647,648 ,0,0,0}, - {789,787,786 ,648,646,645 ,0,0,0}, {790,788,791 ,649,647,650 ,0,0,0}, - {788,790,789 ,647,649,648 ,0,0,0}, {792,793,791 ,651,652,650 ,0,0,0}, - {790,791,793 ,649,650,652 ,0,0,0}, {792,794,795 ,651,653,654 ,0,0,0}, - {795,793,792 ,654,652,651 ,0,0,0}, {795,796,797 ,654,655,656 ,0,0,0}, - {796,795,794 ,655,654,653 ,0,0,0}, {798,797,799 ,657,656,658 ,0,0,0}, - {796,799,797 ,655,658,656 ,0,0,0}, {799,800,801 ,658,659,660 ,0,0,0}, - {801,798,799 ,660,657,658 ,0,0,0}, {802,800,803 ,661,659,662 ,0,0,0}, - {800,802,801 ,659,661,660 ,0,0,0}, {804,805,803 ,663,664,662 ,0,0,0}, - {802,803,805 ,661,662,664 ,0,0,0}, {804,806,807 ,663,665,666 ,0,0,0}, - {807,805,804 ,666,664,663 ,0,0,0}, {808,806,809 ,667,665,668 ,0,0,0}, - {806,808,807 ,665,667,666 ,0,0,0}, {809,810,808 ,668,669,667 ,0,0,0}, - {808,810,811 ,667,669,670 ,0,0,0}, {255,812,813 ,671,672,672 ,0,0,0}, - {814,815,816 ,673,674,675 ,0,0,0}, {817,818,819 ,675,676,676 ,0,0,0}, - {820,821,822 ,677,678,677 ,0,0,0}, {823,824,825 ,679,679,678 ,0,0,0}, - {826,827,822 ,680,680,677 ,0,0,0}, {820,822,827 ,677,677,680 ,0,0,0}, - {826,828,829 ,680,396,396 ,0,0,0}, {829,827,826 ,396,680,680 ,0,0,0}, - {820,825,821 ,677,678,678 ,0,0,0}, {819,818,812 ,676,676,672 ,0,0,0}, - {825,824,821 ,678,679,678 ,0,0,0}, {823,814,824 ,679,673,679 ,0,0,0}, - {815,817,816 ,674,675,675 ,0,0,0}, {823,815,814 ,679,674,673 ,0,0,0}, - {816,817,819 ,675,675,676 ,0,0,0}, {255,813,252 ,671,672,681 ,0,0,0}, - {812,818,813 ,672,676,672 ,0,0,0}, {18,19,830 ,21,21,21 ,0,0,0}, - {18,830,831 ,21,21,21 ,0,0,0}, {832,833,834 ,682,683,684 ,0,0,0}, - {835,836,834 ,685,686,684 ,0,0,0}, {832,834,836 ,682,684,686 ,0,0,0}, - {835,837,838 ,685,687,688 ,0,0,0}, {838,836,835 ,688,686,685 ,0,0,0}, - {839,837,840 ,689,687,690 ,0,0,0}, {837,839,838 ,687,689,688 ,0,0,0}, - {841,842,840 ,691,692,690 ,0,0,0}, {839,840,842 ,689,690,692 ,0,0,0}, - {841,843,844 ,691,693,694 ,0,0,0}, {844,842,841 ,694,692,691 ,0,0,0}, - {845,843,846 ,695,693,696 ,0,0,0}, {843,845,844 ,693,695,694 ,0,0,0}, - {847,848,846 ,697,698,696 ,0,0,0}, {845,846,848 ,695,696,698 ,0,0,0}, - {847,849,850 ,697,699,700 ,0,0,0}, {850,848,847 ,700,698,697 ,0,0,0}, - {851,849,852 ,701,699,702 ,0,0,0}, {849,851,850 ,699,701,700 ,0,0,0}, - {853,854,852 ,641,703,702 ,0,0,0}, {851,852,854 ,701,702,703 ,0,0,0}, - {855,854,853 ,641,703,641 ,0,0,0}, {856,833,832 ,704,683,682 ,0,0,0}, - {857,856,858 ,705,704,706 ,0,0,0}, {856,857,833 ,704,705,683 ,0,0,0}, - {859,860,858 ,707,708,706 ,0,0,0}, {857,858,860 ,705,706,708 ,0,0,0}, - {859,861,862 ,707,709,710 ,0,0,0}, {862,860,859 ,710,708,707 ,0,0,0}, - {863,861,864 ,711,709,712 ,0,0,0}, {861,863,862 ,709,711,710 ,0,0,0}, - {865,866,864 ,713,714,712 ,0,0,0}, {863,864,866 ,711,712,714 ,0,0,0}, - {865,867,868 ,713,715,716 ,0,0,0}, {868,866,865 ,716,714,713 ,0,0,0}, - {869,867,870 ,717,715,718 ,0,0,0}, {867,869,868 ,715,717,716 ,0,0,0}, - {871,872,870 ,719,720,718 ,0,0,0}, {869,870,872 ,717,718,720 ,0,0,0}, - {871,873,874 ,719,721,722 ,0,0,0}, {874,872,871 ,722,720,719 ,0,0,0}, - {875,873,876 ,723,721,456 ,0,0,0}, {873,875,874 ,721,723,722 ,0,0,0}, - {875,876,877 ,723,456,724 ,0,0,0}, {38,39,878 ,21,725,725 ,0,0,0}, - {38,878,879 ,21,725,21 ,0,0,0}, {312,41,311 ,726,726,726 ,0,0,0}, - {92,836,880 ,727,727,726 ,0,0,0}, {672,674,881 ,726,726,726 ,0,0,0}, - {856,832,92 ,727,727,727 ,0,0,0}, {89,856,92 ,726,727,727 ,0,0,0}, - {56,882,883 ,726,726,726 ,0,0,0}, {254,458,251 ,726,726,726 ,0,0,0}, - {858,89,90 ,726,726,726 ,0,0,0}, {861,85,83 ,727,726,726 ,0,0,0}, - {884,880,838 ,726,726,726 ,0,0,0}, {885,886,887 ,726,726,726 ,0,0,0}, - {774,888,889 ,727,727,727 ,0,0,0}, {545,890,891 ,726,726,727 ,0,0,0}, - {884,839,892 ,726,726,726 ,0,0,0}, {893,765,894 ,726,726,726 ,0,0,0}, - {764,893,895 ,727,726,726 ,0,0,0}, {842,896,892 ,727,726,726 ,0,0,0}, - {83,86,864 ,726,727,726 ,0,0,0}, {897,194,759 ,726,727,726 ,0,0,0}, - {803,800,196 ,726,726,726 ,0,0,0}, {898,896,844 ,727,726,726 ,0,0,0}, - {77,865,86 ,727,726,727 ,0,0,0}, {899,848,900 ,727,727,727 ,0,0,0}, - {899,898,845 ,727,727,727 ,0,0,0}, {901,900,851 ,726,727,726 ,0,0,0}, - {850,900,848 ,726,727,727 ,0,0,0}, {902,855,903 ,727,726,726 ,0,0,0}, - {902,901,854 ,727,726,726 ,0,0,0}, {903,904,905 ,726,726,726 ,0,0,0}, - {906,907,106 ,726,726,727 ,0,0,0}, {870,79,871 ,726,727,726 ,0,0,0}, - {908,909,906 ,727,727,726 ,0,0,0}, {910,904,911 ,727,726,726 ,0,0,0}, - {99,100,912 ,727,726,726 ,0,0,0}, {518,407,522 ,726,726,726 ,0,0,0}, - {913,914,524 ,727,726,726 ,0,0,0}, {907,915,916 ,726,726,727 ,0,0,0}, - {510,391,390 ,726,726,727 ,0,0,0}, {917,598,918 ,726,726,728 ,0,0,0}, - {508,363,397 ,727,726,727 ,0,0,0}, {918,601,591 ,728,726,726 ,0,0,0}, - {128,342,109 ,728,726,726 ,0,0,0}, {131,339,341 ,726,728,726 ,0,0,0}, - {348,113,110 ,726,726,726 ,0,0,0}, {919,920,604 ,726,726,726 ,0,0,0}, - {113,351,111 ,726,726,726 ,0,0,0}, {359,362,412 ,726,726,727 ,0,0,0}, - {921,124,119 ,726,726,726 ,0,0,0}, {126,123,922 ,726,726,726 ,0,0,0}, - {923,924,589 ,727,726,726 ,0,0,0}, {652,441,444 ,726,726,726 ,0,0,0}, - {925,584,162 ,726,726,726 ,0,0,0}, {926,927,928 ,727,727,726 ,0,0,0}, - {144,583,580 ,726,727,726 ,0,0,0}, {929,930,556 ,727,726,727 ,0,0,0}, - {931,550,932 ,726,726,727 ,0,0,0}, {154,573,151 ,727,726,726 ,0,0,0}, - {933,533,536 ,727,726,726 ,0,0,0}, {526,934,935 ,727,726,726 ,0,0,0}, - {160,157,562 ,727,726,726 ,0,0,0}, {160,560,558 ,727,726,727 ,0,0,0}, - {158,565,157 ,726,727,726 ,0,0,0}, {566,158,153 ,727,726,726 ,0,0,0}, - {935,558,526 ,726,727,727 ,0,0,0}, {936,934,528 ,726,726,726 ,0,0,0}, - {151,570,568 ,726,727,726 ,0,0,0}, {529,937,936 ,727,726,726 ,0,0,0}, - {933,937,532 ,727,726,727 ,0,0,0}, {145,574,154 ,727,726,727 ,0,0,0}, - {538,938,939 ,726,727,727 ,0,0,0}, {939,933,536 ,727,727,726 ,0,0,0}, - {891,940,541 ,727,726,727 ,0,0,0}, {539,940,938 ,726,726,727 ,0,0,0}, - {941,556,930 ,727,727,726 ,0,0,0}, {551,942,932 ,726,726,727 ,0,0,0}, - {554,556,942 ,726,727,726 ,0,0,0}, {942,556,941 ,726,727,727 ,0,0,0}, - {548,931,890 ,726,726,726 ,0,0,0}, {551,554,942 ,726,726,726 ,0,0,0}, - {174,930,929 ,727,726,727 ,0,0,0}, {927,943,168 ,727,726,726 ,0,0,0}, - {174,929,944 ,727,727,726 ,0,0,0}, {168,171,927 ,726,727,727 ,0,0,0}, - {943,167,168 ,726,727,726 ,0,0,0}, {926,928,945 ,727,726,726 ,0,0,0}, - {946,926,945 ,726,727,726 ,0,0,0}, {947,948,589 ,726,726,726 ,0,0,0}, - {589,946,945 ,726,726,726 ,0,0,0}, {948,370,946 ,726,726,726 ,0,0,0}, - {589,879,949 ,726,727,726 ,0,0,0}, {650,440,441 ,726,726,726 ,0,0,0}, - {950,588,951 ,726,726,726 ,0,0,0}, {655,444,952 ,726,726,726 ,0,0,0}, - {593,953,591 ,726,726,726 ,0,0,0}, {953,593,954 ,726,726,726 ,0,0,0}, - {327,139,330 ,726,726,726 ,0,0,0}, {955,333,956 ,726,726,726 ,0,0,0}, - {956,331,140 ,726,726,726 ,0,0,0}, {957,335,955 ,726,726,726 ,0,0,0}, - {335,957,590 ,726,726,726 ,0,0,0}, {333,331,956 ,726,726,726 ,0,0,0}, - {594,590,957 ,726,726,726 ,0,0,0}, {333,955,335 ,726,726,726 ,0,0,0}, - {140,331,330 ,726,726,726 ,0,0,0}, {594,957,954 ,726,726,726 ,0,0,0}, - {137,139,325 ,726,726,726 ,0,0,0}, {919,606,958 ,726,729,726 ,0,0,0}, - {324,320,134 ,726,726,726 ,0,0,0}, {345,110,109 ,726,726,726 ,0,0,0}, - {919,603,606 ,726,726,729 ,0,0,0}, {111,959,120 ,726,728,726 ,0,0,0}, - {920,960,609 ,726,726,726 ,0,0,0}, {921,961,124 ,726,726,726 ,0,0,0}, - {959,921,117 ,728,726,726 ,0,0,0}, {354,364,416 ,727,727,727 ,0,0,0}, - {416,419,354 ,727,727,727 ,0,0,0}, {356,354,419 ,726,727,727 ,0,0,0}, - {962,664,658 ,726,726,726 ,0,0,0}, {419,409,356 ,727,726,726 ,0,0,0}, - {515,508,395 ,726,727,726 ,0,0,0}, {408,359,412 ,727,726,727 ,0,0,0}, - {409,411,357 ,726,726,727 ,0,0,0}, {421,365,368 ,726,726,726 ,0,0,0}, - {614,610,963 ,726,726,726 ,0,0,0}, {363,359,408 ,726,726,727 ,0,0,0}, - {435,646,644 ,726,726,726 ,0,0,0}, {964,965,617 ,726,726,726 ,0,0,0}, - {963,610,960 ,726,726,726 ,0,0,0}, {411,362,357 ,726,726,727 ,0,0,0}, - {357,356,409 ,727,726,726 ,0,0,0}, {434,435,644 ,726,726,726 ,0,0,0}, - {615,964,617 ,726,726,726 ,0,0,0}, {961,966,967 ,726,726,726 ,0,0,0}, - {123,124,922 ,726,726,726 ,0,0,0}, {968,36,657 ,726,726,726 ,0,0,0}, - {966,950,951 ,726,726,726 ,0,0,0}, {966,951,967 ,726,726,726 ,0,0,0}, - {646,438,649 ,726,726,726 ,0,0,0}, {417,416,364 ,726,727,727 ,0,0,0}, - {628,453,629 ,726,728,728 ,0,0,0}, {629,450,627 ,728,728,726 ,0,0,0}, - {515,394,512 ,726,726,726 ,0,0,0}, {429,621,447 ,726,726,728 ,0,0,0}, - {512,394,391 ,726,726,726 ,0,0,0}, {510,512,391 ,726,726,726 ,0,0,0}, - {402,517,520 ,727,726,726 ,0,0,0}, {390,520,510 ,727,726,726 ,0,0,0}, - {494,969,715 ,726,726,726 ,0,0,0}, {520,390,402 ,726,727,727 ,0,0,0}, - {970,971,16 ,726,726,726 ,0,0,0}, {972,973,974 ,726,726,726 ,0,0,0}, - {975,974,26 ,726,726,726 ,0,0,0}, {976,676,977 ,726,726,726 ,0,0,0}, - {973,972,978 ,726,726,726 ,0,0,0}, {305,72,307 ,726,726,726 ,0,0,0}, - {51,882,56 ,726,726,726 ,0,0,0}, {979,980,662 ,726,726,726 ,0,0,0}, - {962,658,72 ,726,726,726 ,0,0,0}, {662,664,979 ,726,726,726 ,0,0,0}, - {962,979,664 ,726,726,726 ,0,0,0}, {981,661,980 ,726,726,726 ,0,0,0}, - {661,662,980 ,726,726,726 ,0,0,0}, {981,982,668 ,726,726,726 ,0,0,0}, - {658,307,72 ,726,726,726 ,0,0,0}, {71,304,69 ,726,726,726 ,0,0,0}, - {982,983,669 ,726,728,726 ,0,0,0}, {63,309,60 ,726,726,728 ,0,0,0}, - {299,66,301 ,726,726,726 ,0,0,0}, {45,319,43 ,726,726,726 ,0,0,0}, - {42,315,317 ,726,726,726 ,0,0,0}, {729,984,985 ,726,726,726 ,0,0,0}, - {882,49,986 ,726,726,728 ,0,0,0}, {986,52,43 ,728,726,726 ,0,0,0}, - {881,977,672 ,726,726,726 ,0,0,0}, {12,987,14 ,726,726,726 ,0,0,0}, - {677,988,989 ,726,726,726 ,0,0,0}, {990,991,992 ,727,727,726 ,0,0,0}, - {485,706,704 ,726,726,726 ,0,0,0}, {425,993,11 ,726,726,726 ,0,0,0}, - {715,969,717 ,726,726,726 ,0,0,0}, {16,971,994 ,726,726,726 ,0,0,0}, - {709,490,710 ,726,726,726 ,0,0,0}, {262,995,996 ,726,726,727 ,0,0,0}, - {246,459,248 ,727,727,726 ,0,0,0}, {256,469,246 ,727,727,727 ,0,0,0}, - {255,251,379 ,726,726,727 ,0,0,0}, {248,459,461 ,726,727,726 ,0,0,0}, - {373,819,376 ,726,726,727 ,0,0,0}, {681,479,683 ,726,726,726 ,0,0,0}, - {814,372,384 ,726,726,727 ,0,0,0}, {208,997,998 ,727,726,726 ,0,0,0}, - {999,748,1000 ,726,726,726 ,0,0,0}, {387,822,821 ,726,726,726 ,0,0,0}, - {389,1001,826 ,726,726,726 ,0,0,0}, {885,887,1002 ,726,726,728 ,0,0,0}, - {1003,1004,751 ,726,726,726 ,0,0,0}, {886,1005,887 ,726,726,726 ,0,0,0}, - {742,738,1006 ,726,728,726 ,0,0,0}, {228,1007,1008 ,726,726,726 ,0,0,0}, - {286,213,285 ,726,726,726 ,0,0,0}, {295,1007,225 ,726,726,726 ,0,0,0}, - {1009,1008,1005 ,726,726,726 ,0,0,0}, {275,236,277 ,726,726,726 ,0,0,0}, - {281,283,215 ,726,726,726 ,0,0,0}, {719,721,984 ,726,726,726 ,0,0,0}, - {722,242,721 ,726,726,726 ,0,0,0}, {1010,726,985 ,726,728,726 ,0,0,0}, - {729,985,726 ,726,726,728 ,0,0,0}, {727,726,1010 ,726,728,726 ,0,0,0}, - {984,729,719 ,726,726,726 ,0,0,0}, {984,721,242 ,726,726,726 ,0,0,0}, - {1010,1011,727 ,726,726,726 ,0,0,0}, {1012,731,1011 ,726,726,726 ,0,0,0}, - {1011,734,727 ,726,726,726 ,0,0,0}, {1012,1013,732 ,726,728,726 ,0,0,0}, - {722,718,241 ,726,726,726 ,0,0,0}, {269,230,271 ,726,728,726 ,0,0,0}, - {279,277,239 ,726,726,726 ,0,0,0}, {212,264,281 ,726,726,726 ,0,0,0}, - {230,268,211 ,728,726,726 ,0,0,0}, {286,222,213 ,726,726,726 ,0,0,0}, - {291,221,219 ,726,726,726 ,0,0,0}, {221,295,226 ,726,726,726 ,0,0,0}, - {1014,1006,738 ,726,726,728 ,0,0,0}, {289,219,222 ,726,726,726 ,0,0,0}, - {1015,743,1006 ,726,726,726 ,0,0,0}, {886,1016,1005 ,726,726,726 ,0,0,0}, - {1017,1018,1019 ,726,726,726 ,0,0,0}, {6,4,698 ,726,726,726 ,0,0,0}, - {8,695,1 ,726,726,726 ,0,0,0}, {799,178,177 ,726,726,727 ,0,0,0}, - {1020,782,1021 ,727,726,726 ,0,0,0}, {386,824,384 ,727,726,727 ,0,0,0}, - {1022,1002,751 ,726,728,726 ,0,0,0}, {1002,1022,885 ,728,726,726 ,0,0,0}, - {751,6,1022 ,726,726,726 ,0,0,0}, {780,1023,777 ,726,726,726 ,0,0,0}, - {791,188,179 ,726,727,727 ,0,0,0}, {759,194,758 ,726,727,726 ,0,0,0}, - {770,1024,894 ,726,727,726 ,0,0,0}, {755,758,191 ,726,726,726 ,0,0,0}, - {897,762,895 ,726,726,726 ,0,0,0}, {191,192,754 ,726,726,726 ,0,0,0}, - {784,187,185 ,726,726,726 ,0,0,0}, {185,786,784 ,726,726,726 ,0,0,0}, - {770,894,767 ,726,726,726 ,0,0,0}, {188,788,185 ,727,727,726 ,0,0,0}, - {1024,771,889 ,727,726,727 ,0,0,0}, {179,181,792 ,727,727,726 ,0,0,0}, - {888,776,1023 ,727,726,726 ,0,0,0}, {796,794,178 ,726,726,726 ,0,0,0}, - {1025,1026,1021 ,726,726,726 ,0,0,0}, {201,804,199 ,727,727,726 ,0,0,0}, - {1027,1028,1029 ,726,726,727 ,0,0,0}, {1030,1025,1028 ,727,726,726 ,0,0,0}, - {1031,1029,1032 ,726,727,727 ,0,0,0}, {1032,1029,1028 ,727,727,726 ,0,0,0}, - {814,384,824 ,726,727,726 ,0,0,0}, {998,1029,1031 ,726,727,726 ,0,0,0}, - {205,207,810 ,727,726,727 ,0,0,0}, {386,387,821 ,727,726,726 ,0,0,0}, - {208,998,1033 ,727,726,726 ,0,0,0}, {1032,1034,1031 ,727,727,726 ,0,0,0}, - {997,1029,998 ,726,727,726 ,0,0,0}, {828,1035,999 ,726,726,726 ,0,0,0}, - {1034,999,1000 ,727,726,726 ,0,0,0}, {1034,1000,1031 ,727,726,726 ,0,0,0}, - {386,821,824 ,727,726,726 ,0,0,0}, {372,816,373 ,726,726,726 ,0,0,0}, - {819,373,816 ,726,726,726 ,0,0,0}, {816,372,814 ,726,726,726 ,0,0,0}, - {377,255,379 ,727,726,727 ,0,0,0}, {376,812,377 ,727,727,727 ,0,0,0}, - {251,458,379 ,726,726,727 ,0,0,0}, {500,689,503 ,726,728,726 ,0,0,0}, - {462,458,254 ,726,726,726 ,0,0,0}, {461,462,249 ,726,726,727 ,0,0,0}, - {249,462,254 ,727,726,726 ,0,0,0}, {461,249,248 ,726,727,726 ,0,0,0}, - {991,990,1036 ,727,727,727 ,0,0,0}, {257,466,256 ,726,726,727 ,0,0,0}, - {246,469,459 ,727,727,727 ,0,0,0}, {1037,1038,916 ,727,727,727 ,0,0,0}, - {404,517,402 ,726,726,727 ,0,0,0}, {518,405,407 ,726,726,726 ,0,0,0}, - {404,518,517 ,726,726,726 ,0,0,0}, {407,913,522 ,726,727,726 ,0,0,0}, - {1039,1040,524 ,726,726,726 ,0,0,0}, {916,106,907 ,727,727,726 ,0,0,0}, - {1041,906,909 ,727,726,727 ,0,0,0}, {906,1041,907 ,726,727,726 ,0,0,0}, - {911,909,908 ,726,727,727 ,0,0,0}, {94,1042,876 ,726,726,726 ,0,0,0}, - {589,588,38 ,726,726,726 ,0,0,0}, {1043,657,655 ,726,726,726 ,0,0,0}, - {368,370,1044 ,726,726,726 ,0,0,0}, {589,38,879 ,726,726,727 ,0,0,0}, - {368,1045,421 ,726,726,726 ,0,0,0}, {589,949,923 ,726,726,727 ,0,0,0}, - {946,589,948 ,726,726,726 ,0,0,0}, {924,947,589 ,726,726,726 ,0,0,0}, - {1046,1044,370 ,726,726,726 ,0,0,0}, {948,1046,370 ,726,726,726 ,0,0,0}, - {1044,1045,368 ,726,726,726 ,0,0,0}, {417,365,421 ,726,726,726 ,0,0,0}, - {417,364,365 ,726,727,726 ,0,0,0}, {644,643,434 ,726,726,726 ,0,0,0}, - {643,640,432 ,726,726,726 ,0,0,0}, {640,623,428 ,726,726,726 ,0,0,0}, - {623,621,429 ,726,726,726 ,0,0,0}, {620,447,621 ,726,728,726 ,0,0,0}, - {411,412,362 ,726,727,726 ,0,0,0}, {434,643,432 ,726,726,726 ,0,0,0}, - {408,397,363 ,727,727,726 ,0,0,0}, {428,432,640 ,726,726,726 ,0,0,0}, - {448,620,627 ,726,726,726 ,0,0,0}, {397,395,508 ,727,726,727 ,0,0,0}, - {428,623,429 ,726,726,726 ,0,0,0}, {636,454,628 ,726,726,726 ,0,0,0}, - {395,394,515 ,726,726,726 ,0,0,0}, {447,620,448 ,728,726,726 ,0,0,0}, - {28,456,632 ,726,726,726 ,0,0,0}, {453,450,629 ,728,728,728 ,0,0,0}, - {635,638,21 ,726,726,726 ,0,0,0}, {454,453,628 ,726,728,726 ,0,0,0}, - {22,638,24 ,726,726,726 ,0,0,0}, {456,454,636 ,726,726,726 ,0,0,0}, - {907,1041,1047 ,726,727,726 ,0,0,0}, {404,405,518 ,726,726,726 ,0,0,0}, - {1040,1047,1041 ,726,726,727 ,0,0,0}, {1039,524,914 ,726,726,726 ,0,0,0}, - {913,524,522 ,727,726,726 ,0,0,0}, {1040,1039,1047 ,726,726,726 ,0,0,0}, - {1048,1036,915 ,726,727,726 ,0,0,0}, {990,992,831 ,727,726,727 ,0,0,0}, - {907,1048,915 ,726,726,726 ,0,0,0}, {105,1049,103 ,726,727,727 ,0,0,0}, - {992,426,831 ,726,727,727 ,0,0,0}, {1050,1051,262 ,726,726,726 ,0,0,0}, - {488,709,706 ,726,726,726 ,0,0,0}, {712,710,491 ,726,726,728 ,0,0,0}, - {26,1052,975 ,726,726,726 ,0,0,0}, {28,632,635 ,726,726,726 ,0,0,0}, - {717,994,971 ,726,726,726 ,0,0,0}, {978,972,1053 ,726,726,726 ,0,0,0}, - {1052,26,24 ,726,726,726 ,0,0,0}, {1052,24,638 ,726,726,726 ,0,0,0}, - {22,21,638 ,726,726,726 ,0,0,0}, {21,28,635 ,726,726,726 ,0,0,0}, - {456,636,632 ,726,726,726 ,0,0,0}, {450,448,627 ,728,726,726 ,0,0,0}, - {438,440,649 ,726,726,726 ,0,0,0}, {435,438,646 ,726,726,726 ,0,0,0}, - {650,441,652 ,726,726,726 ,0,0,0}, {649,440,650 ,726,726,726 ,0,0,0}, - {652,444,655 ,726,726,726 ,0,0,0}, {952,1043,655 ,726,726,726 ,0,0,0}, - {1043,968,657 ,726,726,726 ,0,0,0}, {950,657,36 ,726,726,726 ,0,0,0}, - {34,588,36 ,726,726,726 ,0,0,0}, {950,36,588 ,726,726,726 ,0,0,0}, - {31,588,32 ,726,726,726 ,0,0,0}, {588,34,32 ,726,726,726 ,0,0,0}, - {38,588,31 ,726,726,726 ,0,0,0}, {485,704,484 ,726,726,726 ,0,0,0}, - {426,425,18 ,727,726,726 ,0,0,0}, {257,471,467 ,726,726,726 ,0,0,0}, - {426,18,831 ,727,726,727 ,0,0,0}, {471,260,1051 ,726,726,726 ,0,0,0}, - {991,1036,1048 ,727,727,726 ,0,0,0}, {105,916,1038 ,726,727,727 ,0,0,0}, - {1037,996,995 ,727,727,726 ,0,0,0}, {1037,995,1038 ,727,726,727 ,0,0,0}, - {996,1050,262 ,727,726,726 ,0,0,0}, {1051,260,262 ,726,726,726 ,0,0,0}, - {471,257,260 ,726,726,726 ,0,0,0}, {466,257,467 ,726,726,726 ,0,0,0}, - {466,469,256 ,726,727,727 ,0,0,0}, {703,482,484 ,726,726,726 ,0,0,0}, - {700,478,482 ,726,726,726 ,0,0,0}, {683,479,478 ,726,726,726 ,0,0,0}, - {681,497,479 ,726,729,726 ,0,0,0}, {704,703,484 ,726,726,726 ,0,0,0}, - {680,498,497 ,726,726,729 ,0,0,0}, {703,700,482 ,726,726,726 ,0,0,0}, - {687,500,498 ,726,726,726 ,0,0,0}, {377,812,255 ,727,727,726 ,0,0,0}, - {700,683,478 ,726,726,726 ,0,0,0}, {688,504,503 ,726,726,726 ,0,0,0}, - {376,819,812 ,727,726,727 ,0,0,0}, {681,680,497 ,726,726,729 ,0,0,0}, - {506,504,696 ,726,726,726 ,0,0,0}, {680,687,498 ,726,726,726 ,0,0,0}, - {695,8,692 ,726,726,726 ,0,0,0}, {503,689,688 ,726,728,726 ,0,0,0}, - {475,751,748 ,727,726,726 ,0,0,0}, {688,696,504 ,726,726,726 ,0,0,0}, - {826,1054,828 ,726,726,726 ,0,0,0}, {389,822,387 ,726,726,726 ,0,0,0}, - {1001,1055,826 ,726,727,726 ,0,0,0}, {822,389,826 ,726,726,726 ,0,0,0}, - {1055,1054,826 ,727,726,726 ,0,0,0}, {999,1035,748 ,726,726,726 ,0,0,0}, - {1054,1035,828 ,726,726,726 ,0,0,0}, {1056,748,1057 ,726,726,727 ,0,0,0}, - {748,1035,1057 ,726,726,727 ,0,0,0}, {1058,748,1059 ,726,726,726 ,0,0,0}, - {748,1056,1059 ,726,726,726 ,0,0,0}, {748,1058,475 ,726,726,727 ,0,0,0}, - {477,751,475 ,726,726,727 ,0,0,0}, {2,695,698 ,726,726,726 ,0,0,0}, - {751,1060,1003 ,726,726,726 ,0,0,0}, {751,477,1060 ,726,726,726 ,0,0,0}, - {6,698,1022 ,726,726,726 ,0,0,0}, {1004,6,751 ,726,726,726 ,0,0,0}, - {4,2,698 ,726,726,726 ,0,0,0}, {2,1,695 ,726,726,726 ,0,0,0}, - {506,692,8 ,726,726,726 ,0,0,0}, {506,696,692 ,726,726,726 ,0,0,0}, - {500,687,689 ,726,726,728 ,0,0,0}, {488,490,709 ,726,726,726 ,0,0,0}, - {485,488,706 ,726,726,726 ,0,0,0}, {490,491,710 ,726,728,726 ,0,0,0}, - {491,494,712 ,728,726,726 ,0,0,0}, {715,712,494 ,726,726,726 ,0,0,0}, - {1061,717,969 ,726,726,726 ,0,0,0}, {975,972,974 ,726,726,726 ,0,0,0}, - {1061,994,717 ,726,726,726 ,0,0,0}, {58,14,1062 ,726,726,726 ,0,0,0}, - {987,12,993 ,726,726,726 ,0,0,0}, {1062,14,987 ,726,726,726 ,0,0,0}, - {425,11,18 ,726,726,726 ,0,0,0}, {993,12,11 ,726,726,726 ,0,0,0}, - {1014,737,1013 ,726,726,728 ,0,0,0}, {235,274,233 ,726,726,726 ,0,0,0}, - {215,283,213 ,726,726,726 ,0,0,0}, {731,734,1011 ,726,726,726 ,0,0,0}, - {732,731,1012 ,726,726,726 ,0,0,0}, {737,732,1013 ,726,726,728 ,0,0,0}, - {738,737,1014 ,728,726,726 ,0,0,0}, {745,743,1015 ,726,726,726 ,0,0,0}, - {743,742,1006 ,726,726,726 ,0,0,0}, {1018,1017,1016 ,726,726,726 ,0,0,0}, - {745,1063,1019 ,726,726,726 ,0,0,0}, {1063,745,1015 ,726,726,726 ,0,0,0}, - {1064,1017,1019 ,726,726,726 ,0,0,0}, {1063,1064,1019 ,726,726,726 ,0,0,0}, - {1016,886,1018 ,726,726,726 ,0,0,0}, {1005,1008,887 ,726,726,726 ,0,0,0}, - {228,1008,1009 ,726,726,726 ,0,0,0}, {225,1007,228 ,726,726,726 ,0,0,0}, - {226,295,225 ,726,726,726 ,0,0,0}, {291,292,221 ,726,726,726 ,0,0,0}, - {295,221,292 ,726,726,726 ,0,0,0}, {289,291,219 ,726,726,726 ,0,0,0}, - {286,289,222 ,726,726,726 ,0,0,0}, {283,285,213 ,726,726,726 ,0,0,0}, - {281,215,212 ,726,726,726 ,0,0,0}, {264,212,211 ,726,726,726 ,0,0,0}, - {269,268,230 ,726,726,728 ,0,0,0}, {268,264,211 ,726,726,726 ,0,0,0}, - {233,271,230 ,726,726,728 ,0,0,0}, {235,275,274 ,726,726,726 ,0,0,0}, - {233,274,271 ,726,726,726 ,0,0,0}, {236,239,277 ,726,726,726 ,0,0,0}, - {235,236,275 ,726,726,726 ,0,0,0}, {279,239,718 ,726,726,726 ,0,0,0}, - {722,241,242 ,726,726,726 ,0,0,0}, {718,239,241 ,726,726,726 ,0,0,0}, - {1023,780,1020 ,726,726,727 ,0,0,0}, {202,806,201 ,726,727,727 ,0,0,0}, - {178,794,181 ,726,726,727 ,0,0,0}, {1030,1028,1027 ,727,726,726 ,0,0,0}, - {1026,1025,1030 ,726,726,727 ,0,0,0}, {782,1025,1021 ,726,726,726 ,0,0,0}, - {780,782,1020 ,726,726,727 ,0,0,0}, {776,777,1023 ,726,726,726 ,0,0,0}, - {774,776,888 ,727,726,727 ,0,0,0}, {771,774,889 ,726,727,727 ,0,0,0}, - {770,771,1024 ,726,726,727 ,0,0,0}, {765,767,894 ,726,726,726 ,0,0,0}, - {764,765,893 ,727,726,726 ,0,0,0}, {762,764,895 ,726,727,726 ,0,0,0}, - {759,762,897 ,726,726,726 ,0,0,0}, {758,194,191 ,726,727,726 ,0,0,0}, - {754,755,191 ,726,726,726 ,0,0,0}, {752,754,192 ,727,726,726 ,0,0,0}, - {784,752,187 ,726,727,726 ,0,0,0}, {752,192,187 ,727,726,726 ,0,0,0}, - {788,786,185 ,727,726,726 ,0,0,0}, {791,788,188 ,726,727,727 ,0,0,0}, - {792,791,179 ,726,726,727 ,0,0,0}, {794,792,181 ,726,726,727 ,0,0,0}, - {799,796,178 ,726,726,726 ,0,0,0}, {800,799,177 ,726,726,727 ,0,0,0}, - {199,803,196 ,726,726,726 ,0,0,0}, {196,800,177 ,726,726,727 ,0,0,0}, - {201,806,804 ,727,727,727 ,0,0,0}, {199,804,803 ,726,727,726 ,0,0,0}, - {202,809,806 ,726,726,727 ,0,0,0}, {205,810,202 ,727,727,726 ,0,0,0}, - {809,202,810 ,726,726,727 ,0,0,0}, {810,207,1033 ,727,726,726 ,0,0,0}, - {208,1033,207 ,727,726,726 ,0,0,0}, {145,147,577 ,727,727,726 ,0,0,0}, - {545,891,544 ,726,727,727 ,0,0,0}, {144,578,147 ,726,727,727 ,0,0,0}, - {550,551,932 ,726,726,727 ,0,0,0}, {548,550,931 ,726,726,726 ,0,0,0}, - {545,548,890 ,726,726,726 ,0,0,0}, {541,544,891 ,727,727,727 ,0,0,0}, - {539,541,940 ,726,727,726 ,0,0,0}, {538,539,938 ,726,726,727 ,0,0,0}, - {536,538,939 ,726,726,727 ,0,0,0}, {532,533,933 ,727,726,727 ,0,0,0}, - {529,532,937 ,727,727,726 ,0,0,0}, {528,529,936 ,726,727,726 ,0,0,0}, - {526,528,934 ,727,726,726 ,0,0,0}, {558,935,160 ,727,726,727 ,0,0,0}, - {562,560,160 ,726,726,727 ,0,0,0}, {565,562,157 ,727,726,726 ,0,0,0}, - {566,565,158 ,727,727,726 ,0,0,0}, {568,153,151 ,726,726,726 ,0,0,0}, - {566,153,568 ,727,726,726 ,0,0,0}, {573,570,151 ,726,727,726 ,0,0,0}, - {574,573,154 ,726,726,727 ,0,0,0}, {577,574,145 ,726,726,727 ,0,0,0}, - {578,577,147 ,727,726,727 ,0,0,0}, {143,583,144 ,727,727,726 ,0,0,0}, - {580,578,144 ,726,727,726 ,0,0,0}, {584,143,162 ,726,727,726 ,0,0,0}, - {143,584,583 ,727,726,727 ,0,0,0}, {162,165,925 ,726,726,726 ,0,0,0}, - {943,925,167 ,726,726,727 ,0,0,0}, {165,167,925 ,726,727,726 ,0,0,0}, - {927,171,928 ,727,727,726 ,0,0,0}, {173,944,171 ,726,726,727 ,0,0,0}, - {928,171,944 ,726,727,726 ,0,0,0}, {174,944,173 ,727,726,726 ,0,0,0}, - {917,958,599 ,726,726,726 ,0,0,0}, {133,320,337 ,726,726,728 ,0,0,0}, - {347,348,110 ,728,726,726 ,0,0,0}, {593,594,954 ,726,726,726 ,0,0,0}, - {591,953,918 ,726,726,728 ,0,0,0}, {598,601,918 ,726,726,728 ,0,0,0}, - {599,598,917 ,726,726,726 ,0,0,0}, {606,599,958 ,729,726,726 ,0,0,0}, - {604,603,919 ,726,726,726 ,0,0,0}, {609,604,920 ,726,726,726 ,0,0,0}, - {610,609,960 ,726,726,726 ,0,0,0}, {964,615,614 ,726,726,726 ,0,0,0}, - {614,963,964 ,726,726,726 ,0,0,0}, {617,1065,1066 ,726,726,726 ,0,0,0}, - {1065,617,965 ,726,726,726 ,0,0,0}, {1066,126,922 ,726,726,726 ,0,0,0}, - {1065,126,1066 ,726,726,726 ,0,0,0}, {124,961,967 ,726,726,726 ,0,0,0}, - {124,967,922 ,726,726,726 ,0,0,0}, {117,921,119 ,726,726,726 ,0,0,0}, - {120,959,117 ,726,728,726 ,0,0,0}, {351,959,111 ,726,728,726 ,0,0,0}, - {348,351,113 ,726,726,726 ,0,0,0}, {342,345,109 ,726,726,726 ,0,0,0}, - {345,347,110 ,726,728,726 ,0,0,0}, {341,342,128 ,726,726,728 ,0,0,0}, - {131,337,339 ,726,728,728 ,0,0,0}, {131,341,128 ,726,726,728 ,0,0,0}, - {133,134,320 ,726,726,726 ,0,0,0}, {131,133,337 ,726,726,728 ,0,0,0}, - {134,137,324 ,726,726,726 ,0,0,0}, {325,139,327 ,726,726,726 ,0,0,0}, - {324,137,325 ,726,726,726 ,0,0,0}, {330,139,140 ,726,726,726 ,0,0,0}, - {873,871,76 ,726,726,726 ,0,0,0}, {867,77,870 ,727,727,726 ,0,0,0}, - {910,911,1067 ,727,726,726 ,0,0,0}, {1067,911,908 ,726,726,727 ,0,0,0}, - {905,904,910 ,726,726,727 ,0,0,0}, {855,904,903 ,726,726,726 ,0,0,0}, - {854,855,902 ,726,726,727 ,0,0,0}, {851,854,901 ,726,726,726 ,0,0,0}, - {850,851,900 ,726,726,727 ,0,0,0}, {845,848,899 ,727,727,727 ,0,0,0}, - {844,845,898 ,726,727,727 ,0,0,0}, {842,844,896 ,727,726,726 ,0,0,0}, - {839,842,892 ,726,727,726 ,0,0,0}, {838,839,884 ,726,726,726 ,0,0,0}, - {836,838,880 ,727,726,726 ,0,0,0}, {832,836,92 ,727,727,727 ,0,0,0}, - {858,856,89 ,726,727,726 ,0,0,0}, {859,858,90 ,726,726,726 ,0,0,0}, - {861,859,85 ,727,726,726 ,0,0,0}, {859,90,85 ,726,726,726 ,0,0,0}, - {864,861,83 ,726,727,726 ,0,0,0}, {865,864,86 ,726,726,727 ,0,0,0}, - {867,865,77 ,727,726,727 ,0,0,0}, {79,870,77 ,727,726,727 ,0,0,0}, - {75,873,76 ,727,726,726 ,0,0,0}, {76,871,79 ,726,726,727 ,0,0,0}, - {876,75,94 ,726,727,726 ,0,0,0}, {75,876,873 ,727,726,726 ,0,0,0}, - {94,97,1042 ,726,726,726 ,0,0,0}, {912,1042,99 ,726,726,727 ,0,0,0}, - {97,99,1042 ,726,727,726 ,0,0,0}, {912,100,1049 ,726,726,727 ,0,0,0}, - {1049,105,1038 ,727,726,727 ,0,0,0}, {1049,100,103 ,727,726,727 ,0,0,0}, - {916,105,106 ,727,726,727 ,0,0,0}, {983,674,666 ,728,726,726 ,0,0,0}, - {65,298,63 ,726,726,726 ,0,0,0}, {317,45,42 ,726,726,726 ,0,0,0}, - {668,661,981 ,726,726,726 ,0,0,0}, {669,668,982 ,726,726,726 ,0,0,0}, - {666,669,983 ,726,726,728 ,0,0,0}, {881,674,983 ,726,726,728 ,0,0,0}, - {676,672,977 ,726,726,726 ,0,0,0}, {976,988,677 ,726,726,726 ,0,0,0}, - {677,676,976 ,726,726,726 ,0,0,0}, {1068,989,988 ,726,726,726 ,0,0,0}, - {55,16,14 ,726,726,726 ,0,0,0}, {989,1069,1053 ,726,726,726 ,0,0,0}, - {1069,989,1068 ,726,726,726 ,0,0,0}, {55,14,58 ,726,726,726 ,0,0,0}, - {1069,978,1053 ,726,726,726 ,0,0,0}, {58,1062,26 ,726,726,726 ,0,0,0}, - {58,26,974 ,726,726,726 ,0,0,0}, {55,970,16 ,726,726,726 ,0,0,0}, - {55,56,883 ,726,726,726 ,0,0,0}, {55,883,970 ,726,726,726 ,0,0,0}, - {49,882,51 ,726,726,726 ,0,0,0}, {52,986,49 ,726,728,726 ,0,0,0}, - {319,986,43 ,726,728,726 ,0,0,0}, {317,319,45 ,726,726,726 ,0,0,0}, - {315,42,41 ,726,726,726 ,0,0,0}, {60,311,41 ,728,726,726 ,0,0,0}, - {312,315,41 ,726,726,726 ,0,0,0}, {63,298,309 ,726,726,726 ,0,0,0}, - {60,309,311 ,728,726,726 ,0,0,0}, {65,299,298 ,726,726,726 ,0,0,0}, - {66,69,301 ,726,726,726 ,0,0,0}, {65,66,299 ,726,726,726 ,0,0,0}, - {304,71,305 ,726,726,726 ,0,0,0}, {301,69,304 ,726,726,726 ,0,0,0}, - {72,305,71 ,726,726,726 ,0,0,0}, {1070,371,1071 ,730,730,730 ,0,0,0}, - {267,231,229 ,730,730,730 ,0,0,0}, {88,860,91 ,730,730,730 ,0,0,0}, - {1072,1073,1074 ,730,730,730 ,0,0,0}, {1075,741,744 ,730,730,730 ,0,0,0}, - {460,247,463 ,730,730,730 ,0,0,0}, {483,702,705 ,730,730,730 ,0,0,0}, - {263,1076,1077 ,730,730,730 ,0,0,0}, {1078,1079,1080 ,730,730,730 ,0,0,0}, - {1076,263,1081 ,730,730,730 ,0,0,0}, {1082,1083,104 ,730,730,730 ,0,0,0}, - {849,1084,1085 ,730,730,730 ,0,0,0}, {1082,102,101 ,730,730,730 ,0,0,0}, - {84,862,863 ,730,730,730 ,0,0,0}, {81,82,866 ,730,730,730 ,0,0,0}, - {1086,1087,843 ,730,730,730 ,0,0,0}, {93,877,95 ,730,730,730 ,0,0,0}, - {834,833,87 ,730,730,730 ,0,0,0}, {835,1088,837 ,730,730,730 ,0,0,0}, - {74,874,875 ,730,730,730 ,0,0,0}, {1089,1090,98 ,730,730,730 ,0,0,0}, - {159,156,564 ,730,730,730 ,0,0,0}, {80,78,872 ,730,730,730 ,0,0,0}, - {527,557,1091 ,730,730,730 ,0,0,0}, {875,877,93 ,730,730,730 ,0,0,0}, - {81,868,78 ,730,730,730 ,0,0,0}, {142,582,161 ,730,730,730 ,0,0,0}, - {1092,1093,535 ,730,730,730 ,0,0,0}, {833,857,87 ,730,730,730 ,0,0,0}, - {1089,96,95 ,730,730,730 ,0,0,0}, {1093,1094,537 ,730,730,730 ,0,0,0}, - {150,569,571 ,730,730,730 ,0,0,0}, {834,87,1095 ,730,730,730 ,0,0,0}, - {1090,1082,101 ,730,730,730 ,0,0,0}, {798,195,176 ,730,730,730 ,0,0,0}, - {802,198,197 ,730,730,730 ,0,0,0}, {840,837,1096 ,730,730,730 ,0,0,0}, - {837,1088,1096 ,730,730,730 ,0,0,0}, {1097,1086,841 ,730,730,730 ,0,0,0}, - {1084,849,847 ,730,730,730 ,0,0,0}, {1087,1084,846 ,730,730,730 ,0,0,0}, - {852,1085,1098 ,730,730,730 ,0,0,0}, {1099,1100,1101 ,730,730,730 ,0,0,0}, - {263,261,1081 ,730,730,730 ,0,0,0}, {1102,1103,1083 ,730,730,730 ,0,0,0}, - {261,259,473 ,730,730,730 ,0,0,0}, {1104,1105,1106 ,730,730,730 ,0,0,0}, - {1107,1108,1109 ,730,730,730 ,0,0,0}, {244,247,460 ,730,730,730 ,0,0,0}, - {381,464,253 ,730,730,730 ,0,0,0}, {711,713,492 ,730,730,730 ,0,0,0}, - {690,686,501 ,730,730,730 ,0,0,0}, {1072,1110,1111 ,730,730,730 ,0,0,0}, - {1112,1075,744 ,730,730,730 ,0,0,0}, {1113,1114,740 ,730,730,730 ,0,0,0}, - {1115,728,730 ,730,730,730 ,0,0,0}, {733,1114,1116 ,730,730,730 ,0,0,0}, - {240,238,747 ,730,730,730 ,0,0,0}, {725,1117,1118 ,730,730,730 ,0,0,0}, - {1119,1120,1121 ,730,730,730 ,0,0,0}, {1122,1123,1124 ,730,730,730 ,0,0,0}, - {507,694,693 ,730,730,730 ,0,0,0}, {1121,749,1119 ,730,730,730 ,0,0,0}, - {1125,1126,1127 ,730,730,730 ,0,0,0}, {1128,750,1129 ,730,730,730 ,0,0,0}, - {1130,775,1131 ,730,730,730 ,0,0,0}, {779,1132,781 ,730,730,730 ,0,0,0}, - {1133,1134,769 ,730,730,730 ,0,0,0}, {203,811,204 ,730,730,730 ,0,0,0}, - {1135,766,763 ,730,730,730 ,0,0,0}, {193,190,753 ,730,730,730 ,0,0,0}, - {180,790,793 ,730,730,730 ,0,0,0}, {1136,1125,1127 ,730,730,730 ,0,0,0}, - {1135,763,1137 ,730,730,730 ,0,0,0}, {760,189,1138 ,730,730,730 ,0,0,0}, - {206,811,1139 ,730,730,730 ,0,0,0}, {805,200,198 ,730,730,730 ,0,0,0}, - {176,182,795 ,730,730,730 ,0,0,0}, {787,184,785 ,730,730,730 ,0,0,0}, - {789,790,183 ,730,730,730 ,0,0,0}, {195,801,197 ,730,730,730 ,0,0,0}, - {186,783,785 ,730,730,730 ,0,0,0}, {189,760,757 ,730,730,730 ,0,0,0}, - {756,190,757 ,730,730,730 ,0,0,0}, {808,811,203 ,730,730,730 ,0,0,0}, - {203,200,807 ,730,730,730 ,0,0,0}, {209,1139,1140 ,730,730,730 ,0,0,0}, - {1137,763,761 ,730,730,730 ,0,0,0}, {1140,1136,1141 ,730,730,730 ,0,0,0}, - {216,214,282 ,730,730,730 ,0,0,0}, {195,798,801 ,730,730,730 ,0,0,0}, - {1135,1133,766 ,730,730,730 ,0,0,0}, {1142,772,1134 ,730,730,730 ,0,0,0}, - {775,1130,778 ,730,730,730 ,0,0,0}, {1131,773,1142 ,730,730,730 ,0,0,0}, - {1132,1143,781 ,730,730,730 ,0,0,0}, {1136,1127,1144 ,730,730,730 ,0,0,0}, - {1145,1144,1146 ,730,730,730 ,0,0,0}, {1126,1125,1147 ,730,730,730 ,0,0,0}, - {1148,1126,1147 ,730,730,730 ,0,0,0}, {1149,1150,750 ,730,730,730 ,0,0,0}, - {750,1148,1147 ,730,730,730 ,0,0,0}, {1150,829,1148 ,730,730,730 ,0,0,0}, - {388,827,1151 ,730,730,730 ,0,0,0}, {693,505,507 ,730,730,730 ,0,0,0}, - {7,697,9 ,730,730,730 ,0,0,0}, {1152,243,723 ,730,730,730 ,0,0,0}, - {294,227,224 ,730,730,730 ,0,0,0}, {232,272,273 ,730,730,730 ,0,0,0}, - {237,234,276 ,730,730,730 ,0,0,0}, {284,214,287 ,730,730,730 ,0,0,0}, - {218,288,217 ,730,730,730 ,0,0,0}, {267,229,265 ,730,730,730 ,0,0,0}, - {210,266,265 ,730,730,730 ,0,0,0}, {272,231,270 ,730,730,730 ,0,0,0}, - {238,280,747 ,730,730,730 ,0,0,0}, {232,273,234 ,730,730,730 ,0,0,0}, - {739,1075,1113 ,730,730,730 ,0,0,0}, {1112,746,1074 ,730,730,730 ,0,0,0}, - {735,1117,736 ,730,730,730 ,0,0,0}, {1116,735,733 ,730,730,730 ,0,0,0}, - {728,1152,720 ,730,730,730 ,0,0,0}, {730,1118,1115 ,730,730,730 ,0,0,0}, - {278,238,237 ,730,730,730 ,0,0,0}, {240,724,243 ,730,730,730 ,0,0,0}, - {385,383,825 ,730,730,730 ,0,0,0}, {685,496,499 ,730,730,730 ,0,0,0}, - {486,705,707 ,730,730,730 ,0,0,0}, {250,463,247 ,730,730,730 ,0,0,0}, - {480,701,481 ,730,730,730 ,0,0,0}, {637,29,27 ,730,730,730 ,0,0,0}, - {701,702,481 ,730,730,730 ,0,0,0}, {480,684,701 ,730,730,730 ,0,0,0}, - {682,496,685 ,730,730,730 ,0,0,0}, {690,501,502 ,730,730,730 ,0,0,0}, - {691,690,502 ,730,730,730 ,0,0,0}, {1122,1153,1154 ,730,730,730 ,0,0,0}, - {1155,223,1123 ,730,730,730 ,0,0,0}, {1122,1154,1123 ,730,730,730 ,0,0,0}, - {691,505,693 ,730,730,730 ,0,0,0}, {1124,1123,223 ,730,730,730 ,0,0,0}, - {1154,1120,1119 ,730,730,730 ,0,0,0}, {1120,1154,1153 ,730,730,730 ,0,0,0}, - {699,3,5 ,730,730,730 ,0,0,0}, {502,505,691 ,730,730,730 ,0,0,0}, - {686,499,501 ,730,730,730 ,0,0,0}, {685,499,686 ,730,730,730 ,0,0,0}, - {684,495,682 ,730,730,730 ,0,0,0}, {374,817,815 ,730,730,730 ,0,0,0}, - {818,375,378 ,730,730,730 ,0,0,0}, {253,464,250 ,730,730,730 ,0,0,0}, - {1156,716,1157 ,730,730,730 ,0,0,0}, {713,714,493 ,730,730,730 ,0,0,0}, - {424,17,1158 ,730,730,730 ,0,0,0}, {637,634,29 ,730,730,730 ,0,0,0}, - {1159,714,716 ,730,730,730 ,0,0,0}, {639,27,20 ,730,730,730 ,0,0,0}, - {1160,25,1161 ,730,730,730 ,0,0,0}, {64,62,296 ,730,730,730 ,0,0,0}, - {40,316,314 ,730,730,730 ,0,0,0}, {70,68,303 ,730,730,730 ,0,0,0}, - {1162,73,679 ,730,730,730 ,0,0,0}, {1163,670,1164 ,730,730,730 ,0,0,0}, - {313,59,314 ,730,730,730 ,0,0,0}, {1165,1166,675 ,730,730,730 ,0,0,0}, - {1167,1168,1169 ,730,730,730 ,0,0,0}, {302,68,67 ,730,730,730 ,0,0,0}, - {61,297,62 ,730,730,730 ,0,0,0}, {660,1170,1171 ,730,730,730 ,0,0,0}, - {308,73,306 ,730,730,730 ,0,0,0}, {1172,1164,665 ,730,730,730 ,0,0,0}, - {1173,1167,1174 ,730,730,730 ,0,0,0}, {1175,673,1166 ,730,730,730 ,0,0,0}, - {1172,671,1175 ,730,730,730 ,0,0,0}, {678,1169,1165 ,730,730,730 ,0,0,0}, - {671,1172,667 ,730,730,730 ,0,0,0}, {1162,663,1171 ,730,730,730 ,0,0,0}, - {1170,659,1163 ,730,730,730 ,0,0,0}, {361,414,413 ,730,730,730 ,0,0,0}, - {64,300,67 ,730,730,730 ,0,0,0}, {73,70,306 ,730,730,730 ,0,0,0}, - {310,61,59 ,730,730,730 ,0,0,0}, {633,631,455 ,730,730,730 ,0,0,0}, - {626,625,449 ,730,730,730 ,0,0,0}, {452,631,630 ,730,730,730 ,0,0,0}, - {455,631,452 ,730,730,730 ,0,0,0}, {633,457,634 ,730,730,730 ,0,0,0}, - {1176,318,44 ,730,730,730 ,0,0,0}, {1177,1160,1161 ,730,730,730 ,0,0,0}, - {451,452,630 ,730,730,730 ,0,0,0}, {457,633,455 ,730,730,730 ,0,0,0}, - {53,25,1178 ,730,730,730 ,0,0,0}, {1179,48,50 ,730,730,730 ,0,0,0}, - {27,639,637 ,730,730,730 ,0,0,0}, {20,23,639 ,730,730,730 ,0,0,0}, - {25,53,1161 ,730,730,730 ,0,0,0}, {29,634,457 ,730,730,730 ,0,0,0}, - {1180,1181,525 ,730,730,730 ,0,0,0}, {630,626,451 ,730,730,730 ,0,0,0}, - {451,626,449 ,730,730,730 ,0,0,0}, {519,400,392 ,730,730,730 ,0,0,0}, - {449,625,446 ,730,730,730 ,0,0,0}, {393,513,511 ,730,730,730 ,0,0,0}, - {445,446,622 ,730,730,730 ,0,0,0}, {431,430,641 ,730,730,730 ,0,0,0}, - {624,430,445 ,730,730,730 ,0,0,0}, {645,436,433 ,730,730,730 ,0,0,0}, - {433,431,642 ,730,730,730 ,0,0,0}, {420,352,418 ,730,730,730 ,0,0,0}, - {355,358,410 ,730,730,730 ,0,0,0}, {366,422,367 ,730,730,730 ,0,0,0}, - {423,1182,369 ,730,730,730 ,0,0,0}, {1183,125,1184 ,730,730,730 ,0,0,0}, - {654,1185,443 ,730,730,730 ,0,0,0}, {108,349,346 ,730,730,730 ,0,0,0}, - {132,321,135 ,730,730,730 ,0,0,0}, {108,344,127 ,730,730,730 ,0,0,0}, - {613,616,1186 ,730,730,730 ,0,0,0}, {1187,597,1188 ,730,730,730 ,0,0,0}, - {1189,1190,612 ,730,730,730 ,0,0,0}, {596,1191,1192 ,730,730,730 ,0,0,0}, - {328,329,138 ,730,730,730 ,0,0,0}, {616,618,1186 ,730,730,730 ,0,0,0}, - {135,323,136 ,730,730,730 ,0,0,0}, {611,1193,1189 ,730,730,730 ,0,0,0}, - {1194,334,1195 ,730,730,730 ,0,0,0}, {602,1196,600 ,730,730,730 ,0,0,0}, - {605,1197,607 ,730,730,730 ,0,0,0}, {1188,608,1197 ,730,730,730 ,0,0,0}, - {1196,602,1187 ,730,730,730 ,0,0,0}, {595,1198,1191 ,730,730,730 ,0,0,0}, - {1198,592,1196 ,730,730,730 ,0,0,0}, {612,1190,605 ,730,730,730 ,0,0,0}, - {1192,1195,336 ,730,730,730 ,0,0,0}, {596,1192,619 ,730,730,730 ,0,0,0}, - {141,138,329 ,730,730,730 ,0,0,0}, {1194,141,332 ,730,730,730 ,0,0,0}, - {618,1199,1200 ,730,730,730 ,0,0,0}, {1200,1186,618 ,730,730,730 ,0,0,0}, - {322,321,132 ,730,730,730 ,0,0,0}, {136,326,138 ,730,730,730 ,0,0,0}, - {130,129,340 ,730,730,730 ,0,0,0}, {322,130,338 ,730,730,730 ,0,0,0}, - {121,1201,1202 ,730,730,730 ,0,0,0}, {343,129,127 ,730,730,730 ,0,0,0}, - {118,125,1183 ,730,730,730 ,0,0,0}, {350,112,1203 ,730,730,730 ,0,0,0}, - {366,415,422 ,730,730,730 ,0,0,0}, {116,118,1183 ,730,730,730 ,0,0,0}, - {1204,1205,1184 ,730,730,730 ,0,0,0}, {1205,1204,1206 ,730,730,730 ,0,0,0}, - {30,33,587 ,730,730,730 ,0,0,0}, {587,1207,1206 ,730,730,730 ,0,0,0}, - {1205,1206,1207 ,730,730,730 ,0,0,0}, {1207,587,35 ,730,730,730 ,0,0,0}, - {656,35,1208 ,730,730,730 ,0,0,0}, {540,1209,542 ,730,730,730 ,0,0,0}, - {582,142,581 ,730,730,730 ,0,0,0}, {1210,546,1211 ,730,730,730 ,0,0,0}, - {542,1211,543 ,730,730,730 ,0,0,0}, {1094,1209,540 ,730,730,730 ,0,0,0}, - {530,1212,1213 ,730,730,730 ,0,0,0}, {1092,534,531 ,730,730,730 ,0,0,0}, - {559,155,1214 ,730,730,730 ,0,0,0}, {1091,1212,527 ,730,730,730 ,0,0,0}, - {1215,164,163 ,730,730,730 ,0,0,0}, {561,563,155 ,730,730,730 ,0,0,0}, - {579,142,148 ,730,730,730 ,0,0,0}, {575,576,146 ,730,730,730 ,0,0,0}, - {585,163,161 ,730,730,730 ,0,0,0}, {575,149,572 ,730,730,730 ,0,0,0}, - {166,1215,1216 ,730,730,730 ,0,0,0}, {567,152,159 ,730,730,730 ,0,0,0}, - {155,559,561 ,730,730,730 ,0,0,0}, {1217,169,1216 ,730,730,730 ,0,0,0}, - {170,169,1217 ,730,730,730 ,0,0,0}, {530,527,1212 ,730,730,730 ,0,0,0}, - {552,549,1218 ,730,730,730 ,0,0,0}, {1219,547,1210 ,730,730,730 ,0,0,0}, - {552,1220,553 ,730,730,730 ,0,0,0}, {1218,549,1219 ,730,730,730 ,0,0,0}, - {553,1220,555 ,730,730,730 ,0,0,0}, {172,1221,175 ,730,730,730 ,0,0,0}, - {1217,1222,1223 ,730,730,730 ,0,0,0}, {172,170,1221 ,730,730,730 ,0,0,0}, - {1224,1222,1070 ,730,730,730 ,0,0,0}, {1222,1224,1223 ,730,730,730 ,0,0,0}, - {353,420,415 ,730,730,730 ,0,0,0}, {1224,1070,586 ,730,730,730 ,0,0,0}, - {420,353,352 ,730,730,730 ,0,0,0}, {366,353,415 ,730,730,730 ,0,0,0}, - {352,355,418 ,730,730,730 ,0,0,0}, {410,358,413 ,730,730,730 ,0,0,0}, - {418,355,410 ,730,730,730 ,0,0,0}, {436,647,437 ,730,730,730 ,0,0,0}, - {430,624,641 ,730,730,730 ,0,0,0}, {399,414,1225 ,730,730,730 ,0,0,0}, - {399,1225,360 ,730,730,730 ,0,0,0}, {360,509,399 ,730,730,730 ,0,0,0}, - {514,396,398 ,730,730,730 ,0,0,0}, {439,437,648 ,730,730,730 ,0,0,0}, - {413,358,361 ,730,730,730 ,0,0,0}, {641,642,431 ,730,730,730 ,0,0,0}, - {439,651,442 ,730,730,730 ,0,0,0}, {642,645,433 ,730,730,730 ,0,0,0}, - {654,443,653 ,730,730,730 ,0,0,0}, {645,647,436 ,730,730,730 ,0,0,0}, - {39,586,878 ,730,730,730 ,0,0,0}, {648,651,439 ,730,730,730 ,0,0,0}, - {371,1226,1227 ,730,730,730 ,0,0,0}, {423,367,422 ,730,730,730 ,0,0,0}, - {1182,1226,369 ,730,730,730 ,0,0,0}, {367,423,369 ,730,730,730 ,0,0,0}, - {369,1226,371 ,730,730,730 ,0,0,0}, {1070,1071,586 ,730,730,730 ,0,0,0}, - {1227,1071,371 ,730,730,730 ,0,0,0}, {1228,586,1229 ,730,730,730 ,0,0,0}, - {586,1071,1229 ,730,730,730 ,0,0,0}, {1230,586,1231 ,730,730,730 ,0,0,0}, - {586,1228,1231 ,730,730,730 ,0,0,0}, {586,1230,878 ,730,730,730 ,0,0,0}, - {1232,654,656 ,730,730,730 ,0,0,0}, {586,39,587 ,730,730,730 ,0,0,0}, - {587,37,30 ,730,730,730 ,0,0,0}, {587,39,37 ,730,730,730 ,0,0,0}, - {35,656,1207 ,730,730,730 ,0,0,0}, {33,35,587 ,730,730,730 ,0,0,0}, - {1208,1232,656 ,730,730,730 ,0,0,0}, {1232,1185,654 ,730,730,730 ,0,0,0}, - {442,653,443 ,730,730,730 ,0,0,0}, {653,442,651 ,730,730,730 ,0,0,0}, - {437,647,648 ,730,730,730 ,0,0,0}, {445,622,624 ,730,730,730 ,0,0,0}, - {446,625,622 ,730,730,730 ,0,0,0}, {519,392,511 ,730,730,730 ,0,0,0}, - {399,509,398 ,730,730,730 ,0,0,0}, {521,401,400 ,730,730,730 ,0,0,0}, - {396,514,513 ,730,730,730 ,0,0,0}, {406,403,516 ,730,730,730 ,0,0,0}, - {511,392,393 ,730,730,730 ,0,0,0}, {525,1233,1234 ,730,730,730 ,0,0,0}, - {521,400,519 ,730,730,730 ,0,0,0}, {15,54,13 ,730,730,730 ,0,0,0}, - {401,521,516 ,730,730,730 ,0,0,0}, {1178,13,53 ,730,730,730 ,0,0,0}, - {1160,1235,25 ,730,730,730 ,0,0,0}, {639,23,1235 ,730,730,730 ,0,0,0}, - {25,1235,23 ,730,730,730 ,0,0,0}, {17,10,1158 ,730,730,730 ,0,0,0}, - {1236,13,1178 ,730,730,730 ,0,0,0}, {1237,54,15 ,730,730,730 ,0,0,0}, - {424,19,17 ,730,730,730 ,0,0,0}, {1238,1237,15 ,730,730,730 ,0,0,0}, - {705,486,483 ,730,730,730 ,0,0,0}, {245,470,258 ,730,730,730 ,0,0,0}, - {1239,1240,1101 ,730,730,730 ,0,0,0}, {472,259,465 ,730,730,730 ,0,0,0}, - {406,523,1234 ,730,730,730 ,0,0,0}, {1077,1241,263 ,730,730,730 ,0,0,0}, - {1109,1100,1099 ,730,730,730 ,0,0,0}, {1240,1181,1180 ,730,730,730 ,0,0,0}, - {1240,1180,1101 ,730,730,730 ,0,0,0}, {1181,1233,525 ,730,730,730 ,0,0,0}, - {1234,523,525 ,730,730,730 ,0,0,0}, {406,516,523 ,730,730,730 ,0,0,0}, - {401,516,403 ,730,730,730 ,0,0,0}, {513,393,396 ,730,730,730 ,0,0,0}, - {509,514,398 ,730,730,730 ,0,0,0}, {253,252,381 ,730,730,730 ,0,0,0}, - {252,813,380 ,730,730,730 ,0,0,0}, {707,708,487 ,730,730,730 ,0,0,0}, - {464,463,250 ,730,730,730 ,0,0,0}, {483,481,702 ,730,730,730 ,0,0,0}, - {489,708,711 ,730,730,730 ,0,0,0}, {245,244,468 ,730,730,730 ,0,0,0}, - {460,468,244 ,730,730,730 ,0,0,0}, {486,707,487 ,730,730,730 ,0,0,0}, - {470,465,258 ,730,730,730 ,0,0,0}, {489,711,492 ,730,730,730 ,0,0,0}, - {472,473,259 ,730,730,730 ,0,0,0}, {258,465,259 ,730,730,730 ,0,0,0}, - {427,830,19 ,730,730,730 ,0,0,0}, {1242,1105,1239 ,730,730,730 ,0,0,0}, - {1239,1103,1242 ,730,730,730 ,0,0,0}, {473,1081,261 ,730,730,730 ,0,0,0}, - {1109,1099,1107 ,730,730,730 ,0,0,0}, {1241,1102,1083 ,730,730,730 ,0,0,0}, - {1077,1102,1241 ,730,730,730 ,0,0,0}, {1106,1105,1242 ,730,730,730 ,0,0,0}, - {1104,1243,1244 ,730,730,730 ,0,0,0}, {1243,1104,1106 ,730,730,730 ,0,0,0}, - {1244,830,427 ,730,730,730 ,0,0,0}, {1243,830,1244 ,730,730,730 ,0,0,0}, - {424,427,19 ,730,730,730 ,0,0,0}, {10,13,1236 ,730,730,730 ,0,0,0}, - {10,1236,1158 ,730,730,730 ,0,0,0}, {1245,54,1237 ,730,730,730 ,0,0,0}, - {1238,15,1157 ,730,730,730 ,0,0,0}, {1238,1157,716 ,730,730,730 ,0,0,0}, - {1156,1159,716 ,730,730,730 ,0,0,0}, {1159,493,714 ,730,730,730 ,0,0,0}, - {713,493,492 ,730,730,730 ,0,0,0}, {489,487,708 ,730,730,730 ,0,0,0}, - {480,495,684 ,730,730,730 ,0,0,0}, {495,496,682 ,730,730,730 ,0,0,0}, - {815,382,374 ,730,730,730 ,0,0,0}, {381,252,380 ,730,730,730 ,0,0,0}, - {382,823,383 ,730,730,730 ,0,0,0}, {813,818,378 ,730,730,730 ,0,0,0}, - {820,827,388 ,730,730,730 ,0,0,0}, {374,375,817 ,730,730,730 ,0,0,0}, - {815,823,382 ,730,730,730 ,0,0,0}, {825,383,823 ,730,730,730 ,0,0,0}, - {697,694,9 ,730,730,730 ,0,0,0}, {694,507,9 ,730,730,730 ,0,0,0}, - {0,699,697 ,730,730,730 ,0,0,0}, {0,697,7 ,730,730,730 ,0,0,0}, - {5,1121,699 ,730,730,730 ,0,0,0}, {0,3,699 ,730,730,730 ,0,0,0}, - {749,1121,5 ,730,730,730 ,0,0,0}, {1246,749,1247 ,730,730,730 ,0,0,0}, - {749,5,1247 ,730,730,730 ,0,0,0}, {749,1246,1248 ,730,730,730 ,0,0,0}, - {749,474,476 ,730,730,730 ,0,0,0}, {749,1248,474 ,730,730,730 ,0,0,0}, - {1249,827,1250 ,730,730,730 ,0,0,0}, {749,476,750 ,730,730,730 ,0,0,0}, - {750,1251,1129 ,730,730,730 ,0,0,0}, {750,476,1251 ,730,730,730 ,0,0,0}, - {1148,750,1150 ,730,730,730 ,0,0,0}, {1128,1149,750 ,730,730,730 ,0,0,0}, - {829,1250,827 ,730,730,730 ,0,0,0}, {1150,1250,829 ,730,730,730 ,0,0,0}, - {1249,1151,827 ,730,730,730 ,0,0,0}, {385,820,388 ,730,730,730 ,0,0,0}, - {385,825,820 ,730,730,730 ,0,0,0}, {375,818,817 ,730,730,730 ,0,0,0}, - {378,380,813 ,730,730,730 ,0,0,0}, {1153,1122,1252 ,730,730,730 ,0,0,0}, - {290,218,220 ,730,730,730 ,0,0,0}, {1111,1110,1252 ,730,730,730 ,0,0,0}, - {1110,1153,1252 ,730,730,730 ,0,0,0}, {1073,1072,1111 ,730,730,730 ,0,0,0}, - {746,1072,1074 ,730,730,730 ,0,0,0}, {744,746,1112 ,730,730,730 ,0,0,0}, - {739,741,1075 ,730,730,730 ,0,0,0}, {740,739,1113 ,730,730,730 ,0,0,0}, - {733,740,1114 ,730,730,730 ,0,0,0}, {735,1116,1117 ,730,730,730 ,0,0,0}, - {725,736,1117 ,730,730,730 ,0,0,0}, {730,725,1118 ,730,730,730 ,0,0,0}, - {728,1115,1152 ,730,730,730 ,0,0,0}, {723,720,1152 ,730,730,730 ,0,0,0}, - {724,723,243 ,730,730,730 ,0,0,0}, {747,724,240 ,730,730,730 ,0,0,0}, - {278,280,238 ,730,730,730 ,0,0,0}, {276,278,237 ,730,730,730 ,0,0,0}, - {273,276,234 ,730,730,730 ,0,0,0}, {272,232,231 ,730,730,730 ,0,0,0}, - {267,270,231 ,730,730,730 ,0,0,0}, {265,229,210 ,730,730,730 ,0,0,0}, - {266,210,216 ,730,730,730 ,0,0,0}, {284,282,214 ,730,730,730 ,0,0,0}, - {282,266,216 ,730,730,730 ,0,0,0}, {217,287,214 ,730,730,730 ,0,0,0}, - {218,290,288 ,730,730,730 ,0,0,0}, {217,288,287 ,730,730,730 ,0,0,0}, - {220,293,290 ,730,730,730 ,0,0,0}, {227,294,220 ,730,730,730 ,0,0,0}, - {293,220,294 ,730,730,730 ,0,0,0}, {294,224,1155 ,730,730,730 ,0,0,0}, - {223,1155,224 ,730,730,730 ,0,0,0}, {1138,1137,761 ,730,730,730 ,0,0,0}, - {761,760,1138 ,730,730,730 ,0,0,0}, {769,768,1133 ,730,730,730 ,0,0,0}, - {766,1133,768 ,730,730,730 ,0,0,0}, {772,769,1134 ,730,730,730 ,0,0,0}, - {773,772,1142 ,730,730,730 ,0,0,0}, {775,773,1131 ,730,730,730 ,0,0,0}, - {1130,1132,779 ,730,730,730 ,0,0,0}, {779,778,1130 ,730,730,730 ,0,0,0}, - {1144,1253,1146 ,730,730,730 ,0,0,0}, {1253,1143,1254 ,730,730,730 ,0,0,0}, - {1143,1253,781 ,730,730,730 ,0,0,0}, {1254,1146,1253 ,730,730,730 ,0,0,0}, - {1144,1145,1136 ,730,730,730 ,0,0,0}, {1136,1140,1125 ,730,730,730 ,0,0,0}, - {209,1140,1141 ,730,730,730 ,0,0,0}, {206,1139,209 ,730,730,730 ,0,0,0}, - {204,811,206 ,730,730,730 ,0,0,0}, {807,808,203 ,730,730,730 ,0,0,0}, - {805,807,200 ,730,730,730 ,0,0,0}, {802,805,198 ,730,730,730 ,0,0,0}, - {801,802,197 ,730,730,730 ,0,0,0}, {798,176,797 ,730,730,730 ,0,0,0}, - {793,795,182 ,730,730,730 ,0,0,0}, {795,797,176 ,730,730,730 ,0,0,0}, - {183,790,180 ,730,730,730 ,0,0,0}, {180,793,182 ,730,730,730 ,0,0,0}, - {184,789,183 ,730,730,730 ,0,0,0}, {184,186,785 ,730,730,730 ,0,0,0}, - {184,787,789 ,730,730,730 ,0,0,0}, {186,193,783 ,730,730,730 ,0,0,0}, - {753,190,756 ,730,730,730 ,0,0,0}, {783,193,753 ,730,730,730 ,0,0,0}, - {757,190,189 ,730,730,730 ,0,0,0}, {1214,1091,557 ,730,730,730 ,0,0,0}, - {1214,557,559 ,730,730,730 ,0,0,0}, {531,1213,1092 ,730,730,730 ,0,0,0}, - {530,1213,531 ,730,730,730 ,0,0,0}, {535,534,1092 ,730,730,730 ,0,0,0}, - {537,535,1093 ,730,730,730 ,0,0,0}, {540,537,1094 ,730,730,730 ,0,0,0}, - {542,1209,1211 ,730,730,730 ,0,0,0}, {546,543,1211 ,730,730,730 ,0,0,0}, - {547,546,1210 ,730,730,730 ,0,0,0}, {549,547,1219 ,730,730,730 ,0,0,0}, - {1221,170,1223 ,730,730,730 ,0,0,0}, {552,1218,1220 ,730,730,730 ,0,0,0}, - {1255,555,1220 ,730,730,730 ,0,0,0}, {555,1256,1257 ,730,730,730 ,0,0,0}, - {1256,555,1255 ,730,730,730 ,0,0,0}, {1257,175,1221 ,730,730,730 ,0,0,0}, - {1256,175,1257 ,730,730,730 ,0,0,0}, {170,1217,1223 ,730,730,730 ,0,0,0}, - {166,1216,169 ,730,730,730 ,0,0,0}, {164,1215,166 ,730,730,730 ,0,0,0}, - {585,1215,163 ,730,730,730 ,0,0,0}, {582,585,161 ,730,730,730 ,0,0,0}, - {579,581,142 ,730,730,730 ,0,0,0}, {576,579,148 ,730,730,730 ,0,0,0}, - {149,575,146 ,730,730,730 ,0,0,0}, {146,576,148 ,730,730,730 ,0,0,0}, - {150,572,149 ,730,730,730 ,0,0,0}, {150,152,569 ,730,730,730 ,0,0,0}, - {150,571,572 ,730,730,730 ,0,0,0}, {567,159,564 ,730,730,730 ,0,0,0}, - {569,152,567 ,730,730,730 ,0,0,0}, {564,156,563 ,730,730,730 ,0,0,0}, - {155,563,156 ,730,730,730 ,0,0,0}, {1201,1199,618 ,730,730,730 ,0,0,0}, - {121,1199,1201 ,730,730,730 ,0,0,0}, {611,613,1193 ,730,730,730 ,0,0,0}, - {613,1186,1193 ,730,730,730 ,0,0,0}, {612,611,1189 ,730,730,730 ,0,0,0}, - {605,1190,1197 ,730,730,730 ,0,0,0}, {608,607,1197 ,730,730,730 ,0,0,0}, - {597,608,1188 ,730,730,730 ,0,0,0}, {602,597,1187 ,730,730,730 ,0,0,0}, - {592,600,1196 ,730,730,730 ,0,0,0}, {595,592,1198 ,730,730,730 ,0,0,0}, - {596,595,1191 ,730,730,730 ,0,0,0}, {336,619,1192 ,730,730,730 ,0,0,0}, - {334,336,1195 ,730,730,730 ,0,0,0}, {332,334,1194 ,730,730,730 ,0,0,0}, - {329,332,141 ,730,730,730 ,0,0,0}, {326,328,138 ,730,730,730 ,0,0,0}, - {323,326,136 ,730,730,730 ,0,0,0}, {321,323,135 ,730,730,730 ,0,0,0}, - {322,132,130 ,730,730,730 ,0,0,0}, {340,338,130 ,730,730,730 ,0,0,0}, - {343,340,129 ,730,730,730 ,0,0,0}, {344,343,127 ,730,730,730 ,0,0,0}, - {114,349,108 ,730,730,730 ,0,0,0}, {346,344,108 ,730,730,730 ,0,0,0}, - {350,114,112 ,730,730,730 ,0,0,0}, {114,350,349 ,730,730,730 ,0,0,0}, - {112,115,1203 ,730,730,730 ,0,0,0}, {1183,1203,116 ,730,730,730 ,0,0,0}, - {115,116,1203 ,730,730,730 ,0,0,0}, {1184,125,1204 ,730,730,730 ,0,0,0}, - {122,1202,125 ,730,730,730 ,0,0,0}, {1204,125,1202 ,730,730,730 ,0,0,0}, - {121,1202,122 ,730,730,730 ,0,0,0}, {1095,1088,835 ,730,730,730 ,0,0,0}, - {1095,835,834 ,730,730,730 ,0,0,0}, {841,840,1097 ,730,730,730 ,0,0,0}, - {840,1096,1097 ,730,730,730 ,0,0,0}, {843,841,1086 ,730,730,730 ,0,0,0}, - {846,843,1087 ,730,730,730 ,0,0,0}, {847,846,1084 ,730,730,730 ,0,0,0}, - {852,849,1085 ,730,730,730 ,0,0,0}, {1098,1079,853 ,730,730,730 ,0,0,0}, - {853,852,1098 ,730,730,730 ,0,0,0}, {104,1103,107 ,730,730,730 ,0,0,0}, - {1258,1078,1080 ,730,730,730 ,0,0,0}, {1079,1078,853 ,730,730,730 ,0,0,0}, - {1107,1258,1108 ,730,730,730 ,0,0,0}, {1258,1107,1078 ,730,730,730 ,0,0,0}, - {1103,1239,107 ,730,730,730 ,0,0,0}, {1100,107,1239 ,730,730,730 ,0,0,0}, - {1100,1239,1101 ,730,730,730 ,0,0,0}, {104,1083,1103 ,730,730,730 ,0,0,0}, - {104,102,1082 ,730,730,730 ,0,0,0}, {98,1090,101 ,730,730,730 ,0,0,0}, - {96,1089,98 ,730,730,730 ,0,0,0}, {877,1089,95 ,730,730,730 ,0,0,0}, - {875,93,74 ,730,730,730 ,0,0,0}, {874,74,80 ,730,730,730 ,0,0,0}, - {869,872,78 ,730,730,730 ,0,0,0}, {872,874,80 ,730,730,730 ,0,0,0}, - {81,866,868 ,730,730,730 ,0,0,0}, {78,868,869 ,730,730,730 ,0,0,0}, - {82,863,866 ,730,730,730 ,0,0,0}, {84,91,862 ,730,730,730 ,0,0,0}, - {82,84,863 ,730,730,730 ,0,0,0}, {860,88,857 ,730,730,730 ,0,0,0}, - {862,91,860 ,730,730,730 ,0,0,0}, {87,857,88 ,730,730,730 ,0,0,0}, - {1259,1177,1260 ,730,730,730 ,0,0,0}, {1177,1161,1260 ,730,730,730 ,0,0,0}, - {1173,1174,1259 ,730,730,730 ,0,0,0}, {1174,1177,1259 ,730,730,730 ,0,0,0}, - {1168,1167,1173 ,730,730,730 ,0,0,0}, {678,1167,1169 ,730,730,730 ,0,0,0}, - {675,678,1165 ,730,730,730 ,0,0,0}, {673,675,1166 ,730,730,730 ,0,0,0}, - {671,673,1175 ,730,730,730 ,0,0,0}, {665,667,1172 ,730,730,730 ,0,0,0}, - {670,665,1164 ,730,730,730 ,0,0,0}, {659,670,1163 ,730,730,730 ,0,0,0}, - {660,659,1170 ,730,730,730 ,0,0,0}, {663,660,1171 ,730,730,730 ,0,0,0}, - {679,663,1162 ,730,730,730 ,0,0,0}, {308,679,73 ,730,730,730 ,0,0,0}, - {303,306,70 ,730,730,730 ,0,0,0}, {302,303,68 ,730,730,730 ,0,0,0}, - {300,302,67 ,730,730,730 ,0,0,0}, {296,300,64 ,730,730,730 ,0,0,0}, - {297,296,62 ,730,730,730 ,0,0,0}, {310,297,61 ,730,730,730 ,0,0,0}, - {313,310,59 ,730,730,730 ,0,0,0}, {46,316,40 ,730,730,730 ,0,0,0}, - {40,314,59 ,730,730,730 ,0,0,0}, {318,46,44 ,730,730,730 ,0,0,0}, - {46,318,316 ,730,730,730 ,0,0,0}, {44,47,1176 ,730,730,730 ,0,0,0}, - {1179,1176,48 ,730,730,730 ,0,0,0}, {47,48,1176 ,730,730,730 ,0,0,0}, - {50,57,1179 ,730,730,730 ,0,0,0}, {54,1245,57 ,730,730,730 ,0,0,0}, - {1179,57,1245 ,730,730,730 ,0,0,0}, {53,13,54 ,730,730,730 ,0,0,0}, - {468,470,245 ,730,730,730 ,0,0,0}, {414,361,1225 ,730,730,730 ,0,0,0}, - {361,360,1225 ,730,730,730 ,0,0,0}, {228,1009,1124 ,731,732,733 ,0,0,0}, - {1017,1111,1016 ,734,735,736 ,0,0,0}, {1252,1122,1005 ,737,738,739 ,0,0,0}, - {1112,1015,1075 ,740,741,742 ,0,0,0}, {1064,1063,1074 ,743,744,745 ,0,0,0}, - {1013,1116,1114 ,746,747,748 ,0,0,0}, {1014,1113,1006 ,749,750,751 ,0,0,0}, - {1011,1118,1117 ,752,753,754 ,0,0,0}, {1117,1116,1012 ,754,747,755 ,0,0,0}, - {1118,1010,1115 ,753,756,757 ,0,0,0}, {1010,1118,1011 ,756,753,752 ,0,0,0}, - {1152,1115,985 ,758,757,759 ,0,0,0}, {1010,985,1115 ,756,759,757 ,0,0,0}, - {984,243,1152 ,760,761,758 ,0,0,0}, {1152,985,984 ,758,759,760 ,0,0,0}, - {242,243,984 ,761,761,760 ,0,0,0}, {1014,1013,1114 ,749,746,748 ,0,0,0}, - {1116,1013,1012 ,747,746,755 ,0,0,0}, {1011,1117,1012 ,752,754,755 ,0,0,0}, - {1014,1114,1113 ,749,748,750 ,0,0,0}, {1006,1113,1075 ,751,750,742 ,0,0,0}, - {1015,1112,1063 ,741,740,744 ,0,0,0}, {1015,1006,1075 ,741,751,742 ,0,0,0}, - {1064,1074,1073 ,743,745,762 ,0,0,0}, {1074,1063,1112 ,745,744,740 ,0,0,0}, - {1073,1111,1017 ,762,735,734 ,0,0,0}, {1073,1017,1064 ,762,734,743 ,0,0,0}, - {1005,1016,1252 ,739,736,737 ,0,0,0}, {1111,1252,1016 ,735,737,736 ,0,0,0}, - {1122,1009,1005 ,738,732,739 ,0,0,0}, {228,1124,223 ,731,733,35 ,0,0,0}, - {1009,1122,1124 ,732,738,733 ,0,0,0}, {194,897,1138 ,763,764,765 ,0,0,0}, - {894,1133,893 ,766,767,768 ,0,0,0}, {1135,1137,895 ,769,770,771 ,0,0,0}, - {1131,888,1130 ,772,773,774 ,0,0,0}, {1024,889,1142 ,775,776,777 ,0,0,0}, - {1021,1254,1143 ,778,779,780 ,0,0,0}, {1020,1132,1023 ,781,782,783 ,0,0,0}, - {1030,1145,1146 ,784,785,786 ,0,0,0}, {1146,1254,1026 ,786,779,787 ,0,0,0}, - {1145,1027,1136 ,785,788,789 ,0,0,0}, {1027,1145,1030 ,788,785,784 ,0,0,0}, - {1141,1136,1029 ,790,789,791 ,0,0,0}, {1027,1029,1136 ,788,791,789 ,0,0,0}, - {997,209,1141 ,792,793,790 ,0,0,0}, {1141,1029,997 ,790,791,792 ,0,0,0}, - {208,209,997 ,793,793,792 ,0,0,0}, {1020,1021,1143 ,781,778,780 ,0,0,0}, - {1254,1021,1026 ,779,778,787 ,0,0,0}, {1030,1146,1026 ,784,786,787 ,0,0,0}, - {1020,1143,1132 ,781,780,782 ,0,0,0}, {1023,1132,1130 ,783,782,774 ,0,0,0}, - {888,1131,889 ,773,772,776 ,0,0,0}, {888,1023,1130 ,773,783,774 ,0,0,0}, - {1024,1142,1134 ,775,777,794 ,0,0,0}, {1142,889,1131 ,777,776,772 ,0,0,0}, - {1134,1133,894 ,794,767,766 ,0,0,0}, {1134,894,1024 ,794,766,775 ,0,0,0}, - {895,893,1135 ,771,768,769 ,0,0,0}, {1133,1135,893 ,767,769,768 ,0,0,0}, - {1137,897,895 ,770,764,771 ,0,0,0}, {194,1138,189 ,763,765,126 ,0,0,0}, - {897,1137,1138 ,764,770,765 ,0,0,0}, {160,935,1214 ,763,795,796 ,0,0,0}, - {937,1213,936 ,797,798,799 ,0,0,0}, {1212,1091,934 ,800,801,802 ,0,0,0}, - {1094,938,1209 ,803,804,805 ,0,0,0}, {933,939,1093 ,806,807,808 ,0,0,0}, - {890,1219,1210 ,809,810,811 ,0,0,0}, {891,1211,940 ,812,813,814 ,0,0,0}, - {932,1220,1218 ,815,816,817 ,0,0,0}, {1218,1219,931 ,817,810,818 ,0,0,0}, - {1220,942,1255 ,816,819,820 ,0,0,0}, {942,1220,932 ,819,816,815 ,0,0,0}, - {1256,1255,941 ,821,820,822 ,0,0,0}, {942,941,1255 ,819,822,820 ,0,0,0}, - {930,175,1256 ,823,793,821 ,0,0,0}, {1256,941,930 ,821,822,823 ,0,0,0}, - {174,175,930 ,793,793,823 ,0,0,0}, {891,890,1210 ,812,809,811 ,0,0,0}, - {1219,890,931 ,810,809,818 ,0,0,0}, {932,1218,931 ,815,817,818 ,0,0,0}, - {891,1210,1211 ,812,811,813 ,0,0,0}, {940,1211,1209 ,814,813,805 ,0,0,0}, - {938,1094,939 ,804,803,807 ,0,0,0}, {938,940,1209 ,804,814,805 ,0,0,0}, - {933,1093,1092 ,806,808,824 ,0,0,0}, {1093,939,1094 ,808,807,803 ,0,0,0}, - {1092,1213,937 ,824,798,797 ,0,0,0}, {1092,937,933 ,824,797,806 ,0,0,0}, - {934,936,1212 ,802,799,800 ,0,0,0}, {1213,1212,936 ,798,800,799 ,0,0,0}, - {1091,935,934 ,801,795,802 ,0,0,0}, {160,1214,155 ,763,796,126 ,0,0,0}, - {935,1091,1214 ,795,801,796 ,0,0,0}, {126,1065,1199 ,731,795,796 ,0,0,0}, - {963,1193,964 ,825,826,799 ,0,0,0}, {1186,1200,965 ,827,828,829 ,0,0,0}, - {1197,919,1188 ,830,831,805 ,0,0,0}, {960,920,1190 ,832,833,834 ,0,0,0}, - {918,1198,1196 ,835,836,837 ,0,0,0}, {917,1187,958 ,838,839,814 ,0,0,0}, - {954,1192,1191 ,840,841,842 ,0,0,0}, {1191,1198,953 ,842,836,843 ,0,0,0}, - {1192,957,1195 ,841,844,845 ,0,0,0}, {957,1192,954 ,844,841,840 ,0,0,0}, - {1194,1195,955 ,846,845,847 ,0,0,0}, {957,955,1195 ,844,847,845 ,0,0,0}, - {956,141,1194 ,848,761,846 ,0,0,0}, {1194,955,956 ,846,847,848 ,0,0,0}, - {140,141,956 ,761,761,848 ,0,0,0}, {917,918,1196 ,838,835,837 ,0,0,0}, - {1198,918,953 ,836,835,843 ,0,0,0}, {954,1191,953 ,840,842,843 ,0,0,0}, - {917,1196,1187 ,838,837,839 ,0,0,0}, {958,1187,1188 ,814,839,805 ,0,0,0}, - {919,1197,920 ,831,830,833 ,0,0,0}, {919,958,1188 ,831,814,805 ,0,0,0}, - {960,1190,1189 ,832,834,849 ,0,0,0}, {1190,920,1197 ,834,833,830 ,0,0,0}, - {1189,1193,963 ,849,826,825 ,0,0,0}, {1189,963,960 ,849,825,832 ,0,0,0}, - {965,964,1186 ,829,799,827 ,0,0,0}, {1193,1186,964 ,826,827,799 ,0,0,0}, - {1200,1065,965 ,828,795,829 ,0,0,0}, {126,1199,121 ,731,796,35 ,0,0,0}, - {1065,1200,1199 ,795,828,796 ,0,0,0}, {92,880,1095 ,850,851,852 ,0,0,0}, - {896,1097,892 ,853,854,855 ,0,0,0}, {1096,1088,884 ,856,801,857 ,0,0,0}, - {1084,900,1085 ,830,858,859 ,0,0,0}, {898,899,1087 ,860,861,862 ,0,0,0}, - {903,1080,1079 ,863,864,865 ,0,0,0}, {902,1098,901 ,866,867,868 ,0,0,0}, - {910,1108,1258 ,869,870,871 ,0,0,0}, {1258,1080,905 ,871,864,872 ,0,0,0}, - {1108,1067,1109 ,870,873,874 ,0,0,0}, {1067,1108,910 ,873,870,869 ,0,0,0}, - {1100,1109,908 ,875,874,876 ,0,0,0}, {1067,908,1109 ,873,876,874 ,0,0,0}, - {906,107,1100 ,877,82,875 ,0,0,0}, {1100,908,906 ,875,876,877 ,0,0,0}, - {106,107,906 ,878,82,877 ,0,0,0}, {902,903,1079 ,866,863,865 ,0,0,0}, - {1080,903,905 ,864,863,872 ,0,0,0}, {910,1258,905 ,869,871,872 ,0,0,0}, - {902,1079,1098 ,866,865,867 ,0,0,0}, {901,1098,1085 ,868,867,859 ,0,0,0}, - {900,1084,899 ,858,830,861 ,0,0,0}, {900,901,1085 ,858,868,859 ,0,0,0}, - {898,1087,1086 ,860,862,879 ,0,0,0}, {1087,899,1084 ,862,861,830 ,0,0,0}, - {1086,1097,896 ,879,854,853 ,0,0,0}, {1086,896,898 ,879,853,860 ,0,0,0}, - {884,892,1096 ,857,855,856 ,0,0,0}, {1097,1096,892 ,854,856,855 ,0,0,0}, - {1088,880,884 ,801,851,857 ,0,0,0}, {92,1095,87 ,850,852,850 ,0,0,0}, - {880,1088,1095 ,851,801,852 ,0,0,0}, {58,974,1161 ,731,851,880 ,0,0,0}, - {1069,1173,978 ,881,882,855 ,0,0,0}, {1259,1260,973 ,856,801,857 ,0,0,0}, - {1165,976,1166 ,883,884,859 ,0,0,0}, {1068,988,1169 ,860,885,834 ,0,0,0}, - {983,1164,1172 ,886,887,888 ,0,0,0}, {881,1175,977 ,889,890,868 ,0,0,0}, - {981,1170,1163 ,891,892,893 ,0,0,0}, {1163,1164,982 ,893,887,894 ,0,0,0}, - {1170,980,1171 ,892,895,896 ,0,0,0}, {980,1170,981 ,895,892,891 ,0,0,0}, - {1162,1171,979 ,897,896,898 ,0,0,0}, {980,979,1171 ,895,898,896 ,0,0,0}, - {962,73,1162 ,899,761,897 ,0,0,0}, {1162,979,962 ,897,898,899 ,0,0,0}, - {72,73,962 ,761,761,899 ,0,0,0}, {881,983,1172 ,889,886,888 ,0,0,0}, - {1164,983,982 ,887,886,894 ,0,0,0}, {981,1163,982 ,891,893,894 ,0,0,0}, - {881,1172,1175 ,889,888,890 ,0,0,0}, {977,1175,1166 ,868,890,859 ,0,0,0}, - {976,1165,988 ,884,883,885 ,0,0,0}, {976,977,1166 ,884,868,859 ,0,0,0}, - {1068,1169,1168 ,860,834,849 ,0,0,0}, {1169,988,1165 ,834,885,883 ,0,0,0}, - {1168,1173,1069 ,849,882,881 ,0,0,0}, {1168,1069,1068 ,849,881,860 ,0,0,0}, - {973,978,1259 ,857,855,856 ,0,0,0}, {1173,1259,978 ,882,856,855 ,0,0,0}, - {1260,974,973 ,801,851,857 ,0,0,0}, {58,1161,53 ,731,880,35 ,0,0,0}, - {974,1260,1161 ,851,801,880 ,0,0,0}, {36,968,1208 ,20,900,900 ,0,0,0}, - {952,443,1185 ,901,336,901 ,0,0,0}, {1185,1232,1043 ,901,902,902 ,0,0,0}, - {444,443,952 ,336,336,901 ,0,0,0}, {968,1232,1208 ,900,902,900 ,0,0,0}, - {1232,968,1043 ,902,900,902 ,0,0,0}, {952,1185,1043 ,901,901,902 ,0,0,0}, - {1208,35,36 ,900,20,20 ,0,0,0}, {1229,1071,948 ,903,904,905 ,0,0,0}, - {947,924,1228 ,906,907,908 ,0,0,0}, {947,1228,1229 ,906,908,903 ,0,0,0}, - {947,1229,948 ,906,903,905 ,0,0,0}, {1230,1231,923 ,909,910,911 ,0,0,0}, - {1231,924,923 ,910,907,911 ,0,0,0}, {1228,924,1231 ,908,907,910 ,0,0,0}, - {949,879,878 ,912,21,21 ,0,0,0}, {949,878,1230 ,912,21,909 ,0,0,0}, - {923,949,1230 ,911,912,909 ,0,0,0}, {948,1071,1046 ,905,904,913 ,0,0,0}, - {1044,1046,1227 ,914,913,915 ,0,0,0}, {1071,1227,1046 ,904,915,913 ,0,0,0}, - {1226,1045,1044 ,916,917,914 ,0,0,0}, {1044,1227,1226 ,914,915,916 ,0,0,0}, - {1045,1182,421 ,917,918,322 ,0,0,0}, {1182,1045,1226 ,918,917,916 ,0,0,0}, - {1182,423,421 ,918,322,322 ,0,0,0}, {26,1062,1178 ,15,919,920 ,0,0,0}, - {993,424,1158 ,921,922,921 ,0,0,0}, {1158,1236,987 ,921,923,923 ,0,0,0}, - {425,424,993 ,924,922,921 ,0,0,0}, {1062,1236,1178 ,919,923,920 ,0,0,0}, - {1236,1062,987 ,923,919,923 ,0,0,0}, {993,1158,987 ,921,921,923 ,0,0,0}, - {1178,25,26 ,920,15,15 ,0,0,0}, {16,994,1157 ,8,925,925 ,0,0,0}, - {969,493,1159 ,926,372,926 ,0,0,0}, {1159,1156,1061 ,926,927,927 ,0,0,0}, - {494,493,969 ,372,372,926 ,0,0,0}, {994,1156,1157 ,925,927,925 ,0,0,0}, - {1156,994,1061 ,927,925,927 ,0,0,0}, {969,1159,1061 ,926,926,927 ,0,0,0}, - {1157,15,16 ,925,8,8 ,0,0,0}, {1240,1239,907 ,928,929,930 ,0,0,0}, - {1240,1047,1181 ,928,931,932 ,0,0,0}, {1047,1240,907 ,931,928,930 ,0,0,0}, - {914,1233,1039 ,933,934,935 ,0,0,0}, {1039,1233,1181 ,935,934,932 ,0,0,0}, - {406,1234,913 ,314,936,937 ,0,0,0}, {913,407,406 ,937,314,314 ,0,0,0}, - {913,1234,914 ,937,936,933 ,0,0,0}, {914,1234,1233 ,933,936,934 ,0,0,0}, - {1181,1047,1039 ,932,931,935 ,0,0,0}, {907,1239,1048 ,930,929,938 ,0,0,0}, - {991,1048,1105 ,939,938,940 ,0,0,0}, {1239,1105,1048 ,929,940,938 ,0,0,0}, - {1104,992,991 ,941,942,939 ,0,0,0}, {991,1105,1104 ,939,940,941 ,0,0,0}, - {992,1244,426 ,942,943,944 ,0,0,0}, {1244,992,1104 ,943,942,941 ,0,0,0}, - {1244,427,426 ,943,324,944 ,0,0,0}, {1103,1102,1037 ,945,946,947 ,0,0,0}, - {1103,916,1242 ,945,948,949 ,0,0,0}, {916,1103,1037 ,948,945,947 ,0,0,0}, - {1036,1106,915 ,950,951,952 ,0,0,0}, {915,1106,1242 ,952,951,949 ,0,0,0}, - {830,1243,990 ,953,954,955 ,0,0,0}, {990,831,830 ,955,21,953 ,0,0,0}, - {990,1243,1036 ,955,954,950 ,0,0,0}, {1036,1243,1106 ,950,954,951 ,0,0,0}, - {1242,916,915 ,949,948,952 ,0,0,0}, {1037,1102,996 ,947,946,956 ,0,0,0}, - {1050,996,1077 ,957,956,958 ,0,0,0}, {1102,1077,996 ,946,958,956 ,0,0,0}, - {1076,1051,1050 ,959,960,957 ,0,0,0}, {1050,1077,1076 ,957,958,959 ,0,0,0}, - {1051,1081,471 ,960,961,358 ,0,0,0}, {1081,1051,1076 ,961,960,959 ,0,0,0}, - {1081,473,471 ,961,358,358 ,0,0,0}, {1150,1149,1057 ,962,963,964 ,0,0,0}, - {1035,1054,1250 ,965,966,967 ,0,0,0}, {1035,1250,1150 ,965,967,962 ,0,0,0}, - {1035,1150,1057 ,965,962,964 ,0,0,0}, {1151,1249,1055 ,968,969,970 ,0,0,0}, - {1249,1054,1055 ,969,966,970 ,0,0,0}, {1250,1054,1249 ,967,966,969 ,0,0,0}, - {1001,389,388 ,971,304,304 ,0,0,0}, {1001,388,1151 ,971,304,968 ,0,0,0}, - {1055,1001,1151 ,970,971,968 ,0,0,0}, {1057,1149,1056 ,964,963,972 ,0,0,0}, - {1059,1056,1128 ,973,972,974 ,0,0,0}, {1149,1128,1056 ,963,974,972 ,0,0,0}, - {1129,1058,1059 ,975,976,973 ,0,0,0}, {1059,1128,1129 ,973,974,975 ,0,0,0}, - {1058,1251,475 ,976,977,324 ,0,0,0}, {1251,1058,1129 ,977,976,975 ,0,0,0}, - {1251,476,475 ,977,978,324 ,0,0,0}, {6,1004,1247 ,3,979,979 ,0,0,0}, - {1060,474,1248 ,980,324,980 ,0,0,0}, {1248,1246,1003 ,980,981,981 ,0,0,0}, - {477,474,1060 ,982,324,980 ,0,0,0}, {1004,1246,1247 ,979,981,979 ,0,0,0}, - {1246,1004,1003 ,981,979,981 ,0,0,0}, {1060,1248,1003 ,980,980,981 ,0,0,0}, - {1247,5,6 ,979,3,3 ,0,0,0}, {1154,887,1123 ,983,983,984 ,0,0,0}, - {1008,1007,1155 ,984,985,986 ,0,0,0}, {1123,1008,1155 ,984,984,986 ,0,0,0}, - {1007,295,294 ,985,235,235 ,0,0,0}, {1155,1007,294 ,986,985,235 ,0,0,0}, - {1123,887,1008 ,984,983,984 ,0,0,0}, {1002,887,1154 ,987,983,983 ,0,0,0}, - {1002,1119,751 ,987,987,988 ,0,0,0}, {1119,1002,1154 ,987,987,983 ,0,0,0}, - {1119,749,751 ,987,988,988 ,0,0,0}, {1018,886,1153 ,989,990,990 ,0,0,0}, - {885,1121,1120 ,991,992,991 ,0,0,0}, {1153,886,1120 ,990,990,991 ,0,0,0}, - {698,699,1022 ,508,508,992 ,0,0,0}, {1121,885,1022 ,992,991,992 ,0,0,0}, - {1022,699,1121 ,992,508,992 ,0,0,0}, {885,1120,886 ,991,991,990 ,0,0,0}, - {1153,1110,1018 ,990,989,989 ,0,0,0}, {1110,1072,1019 ,989,993,994 ,0,0,0}, - {1019,1018,1110 ,994,989,989 ,0,0,0}, {745,1072,746 ,546,993,546 ,0,0,0}, - {1072,745,1019 ,993,546,994 ,0,0,0}, {970,883,1245 ,995,996,996 ,0,0,0}, - {882,1176,1179 ,997,998,997 ,0,0,0}, {1245,883,1179 ,996,996,997 ,0,0,0}, - {319,318,986 ,257,257,998 ,0,0,0}, {1176,882,986 ,998,997,998 ,0,0,0}, - {986,318,1176 ,998,257,998 ,0,0,0}, {882,1179,883 ,997,997,996 ,0,0,0}, - {1245,1237,970 ,996,995,995 ,0,0,0}, {1237,1238,971 ,995,999,999 ,0,0,0}, - {971,970,1237 ,999,995,995 ,0,0,0}, {717,1238,716 ,525,999,525 ,0,0,0}, - {1238,717,971 ,999,525,999 ,0,0,0}, {1053,972,1177 ,1000,1001,1001 ,0,0,0}, - {975,1235,1160 ,1002,1003,1004 ,0,0,0}, {1177,972,1160 ,1001,1001,1004 ,0,0,0}, - {638,639,1052 ,508,508,1003 ,0,0,0}, {1235,975,1052 ,1003,1002,1003 ,0,0,0}, - {1052,639,1235 ,1003,508,1003 ,0,0,0}, {975,1160,972 ,1002,1004,1001 ,0,0,0}, - {1177,1174,1053 ,1001,1000,1000 ,0,0,0}, {1174,1167,989 ,1000,1005,1005 ,0,0,0}, - {989,1053,1174 ,1005,1000,1000 ,0,0,0}, {677,1167,678 ,546,1005,546 ,0,0,0}, - {1167,677,989 ,1005,546,1005 ,0,0,0}, {966,961,1184 ,1006,1007,1007 ,0,0,0}, - {921,1203,1183 ,1008,1009,1008 ,0,0,0}, {1184,961,1183 ,1007,1007,1008 ,0,0,0}, - {351,350,959 ,257,257,1009 ,0,0,0}, {1203,921,959 ,1009,1008,1009 ,0,0,0}, - {959,350,1203 ,1009,257,1009 ,0,0,0}, {921,1183,961 ,1008,1008,1007 ,0,0,0}, - {1184,1205,966 ,1007,1006,1006 ,0,0,0}, {1205,1207,950 ,1006,1010,1010 ,0,0,0}, - {950,966,1205 ,1010,1006,1006 ,0,0,0}, {657,1207,656 ,525,1010,525 ,0,0,0}, - {1207,657,950 ,1010,525,1010 ,0,0,0}, {1202,922,1204 ,1011,1011,1012 ,0,0,0}, - {967,951,1206 ,1012,1013,1013 ,0,0,0}, {1204,967,1206 ,1012,1012,1013 ,0,0,0}, - {951,588,587 ,1013,324,324 ,0,0,0}, {1206,951,587 ,1013,1013,324 ,0,0,0}, - {1204,922,967 ,1012,1011,1012 ,0,0,0}, {1066,922,1202 ,1014,1011,1011 ,0,0,0}, - {1066,1201,617 ,1014,1014,488 ,0,0,0}, {1201,1066,1202 ,1014,1014,1011 ,0,0,0}, - {1201,618,617 ,1014,488,488 ,0,0,0}, {1223,928,1221 ,1015,1015,1016 ,0,0,0}, - {944,929,1257 ,1016,1017,1017 ,0,0,0}, {1221,944,1257 ,1016,1016,1017 ,0,0,0}, - {929,556,555 ,1017,427,427 ,0,0,0}, {1257,929,555 ,1017,1017,427 ,0,0,0}, - {1221,928,944 ,1016,1015,1016 ,0,0,0}, {945,928,1223 ,1018,1015,1015 ,0,0,0}, - {945,1224,589 ,1018,1018,1019 ,0,0,0}, {1224,945,1223 ,1018,1018,1015 ,0,0,0}, - {1224,586,589 ,1018,324,1019 ,0,0,0}, {943,927,1217 ,1020,1021,1021 ,0,0,0}, - {926,1070,1222 ,1022,1023,1022 ,0,0,0}, {1217,927,1222 ,1021,1021,1022 ,0,0,0}, - {370,371,946 ,205,205,1023 ,0,0,0}, {1070,926,946 ,1023,1022,1023 ,0,0,0}, - {946,371,1070 ,1023,205,1023 ,0,0,0}, {926,1222,927 ,1022,1022,1021 ,0,0,0}, - {1217,1216,943 ,1021,1020,1020 ,0,0,0}, {1216,1215,925 ,1020,1024,1024 ,0,0,0}, - {925,943,1216 ,1024,1020,1020 ,0,0,0}, {584,1215,585 ,456,1024,456 ,0,0,0}, - {1215,584,925 ,1024,456,1024 ,0,0,0}, {1041,909,1099 ,1025,1026,1026 ,0,0,0}, - {911,1078,1107 ,1027,1028,1027 ,0,0,0}, {1099,909,1107 ,1026,1026,1027 ,0,0,0}, - {855,853,904 ,641,641,1028 ,0,0,0}, {1078,911,904 ,1028,1027,1028 ,0,0,0}, - {904,853,1078 ,1028,641,1028 ,0,0,0}, {911,1107,909 ,1027,1027,1026 ,0,0,0}, - {1099,1101,1041 ,1026,1025,1025 ,0,0,0}, {1101,1180,1040 ,1025,1029,1029 ,0,0,0}, - {1040,1041,1101 ,1029,1025,1025 ,0,0,0}, {524,1180,525 ,396,1029,396 ,0,0,0}, - {1180,524,1040 ,1029,396,1029 ,0,0,0}, {912,1049,1082 ,1030,1031,1031 ,0,0,0}, - {1038,1241,1083 ,1032,1033,1032 ,0,0,0}, {1082,1049,1083 ,1031,1031,1032 ,0,0,0}, - {262,263,995 ,205,205,1033 ,0,0,0}, {1241,1038,995 ,1033,1032,1033 ,0,0,0}, - {995,263,1241 ,1033,205,1033 ,0,0,0}, {1038,1083,1049 ,1032,1032,1031 ,0,0,0}, - {1082,1090,912 ,1031,1030,1030 ,0,0,0}, {1090,1089,1042 ,1030,1034,1034 ,0,0,0}, - {1042,912,1090 ,1034,1030,1030 ,0,0,0}, {876,1089,877 ,456,1034,456 ,0,0,0}, - {1089,876,1042 ,1034,456,1034 ,0,0,0}, {1034,1032,1127 ,1035,1036,1036 ,0,0,0}, - {1028,1253,1144 ,1037,1038,1037 ,0,0,0}, {1127,1032,1144 ,1036,1036,1037 ,0,0,0}, - {782,781,1025 ,641,641,1038 ,0,0,0}, {1253,1028,1025 ,1038,1037,1038 ,0,0,0}, - {1025,781,1253 ,1038,641,1038 ,0,0,0}, {1028,1144,1032 ,1037,1037,1036 ,0,0,0}, - {1127,1126,1034 ,1036,1035,1035 ,0,0,0}, {1126,1148,999 ,1035,1039,1040 ,0,0,0}, - {999,1034,1126 ,1040,1035,1035 ,0,0,0}, {828,1148,829 ,396,1039,396 ,0,0,0}, - {1148,828,999 ,1039,396,1040 ,0,0,0}, {1140,998,1125 ,1041,1041,1042 ,0,0,0}, - {1031,1000,1147 ,1042,1043,1044 ,0,0,0}, {1125,1031,1147 ,1042,1042,1044 ,0,0,0}, - {1000,748,750 ,1043,1045,1045 ,0,0,0}, {1147,1000,750 ,1044,1043,1045 ,0,0,0}, - {1125,998,1031 ,1042,1041,1042 ,0,0,0}, {1033,998,1140 ,1046,1041,1041 ,0,0,0}, - {1033,1139,810 ,1046,1046,670 ,0,0,0}, {1139,1033,1140 ,1046,1046,1041 ,0,0,0}, - {1139,811,810 ,1046,670,670 ,0,0,0} -// BladeProtector2.prt - , {1261,1262,1263 ,126,1047,1048 ,0,0,0}, {1264,1265,1266 ,1049,1050,1051 ,0,0,0}, - {1267,1261,1263 ,1052,126,1048 ,0,0,0}, {1266,1265,1267 ,1051,1050,1052 ,0,0,0}, - {1265,1264,1268 ,1050,1049,1053 ,0,0,0}, {1263,1266,1267 ,1048,1051,1052 ,0,0,0}, - {1269,1270,1271 ,1054,1055,1056 ,0,0,0}, {1270,1272,1271 ,1055,1057,1056 ,0,0,0}, - {1268,1273,1269 ,1053,1058,1054 ,0,0,0}, {1270,1269,1273 ,1055,1054,1058 ,0,0,0}, - {1274,1275,1276 ,21,1059,1060 ,0,0,0}, {1277,1278,1272 ,1061,1062,1057 ,0,0,0}, - {1275,1278,1277 ,1059,1062,1061 ,0,0,0}, {1275,1277,1276 ,1059,1061,1060 ,0,0,0}, - {1276,1279,1274 ,1060,1063,21 ,0,0,0}, {1271,1272,1278 ,1056,1057,1062 ,0,0,0}, - {1268,1264,1273 ,1053,1049,1058 ,0,0,0}, {1261,1280,1262 ,126,1064,1047 ,0,0,0}, - {1281,1280,1282 ,1065,1064,1066 ,0,0,0}, {1280,1281,1262 ,1064,1065,1047 ,0,0,0}, - {1283,1284,1282 ,1067,1068,1066 ,0,0,0}, {1281,1282,1284 ,1065,1066,1068 ,0,0,0}, - {1283,1285,1286 ,1067,1069,1070 ,0,0,0}, {1286,1284,1283 ,1070,1068,1067 ,0,0,0}, - {1287,1285,1288 ,1071,1069,1072 ,0,0,0}, {1285,1287,1286 ,1069,1071,1070 ,0,0,0}, - {1289,1290,1288 ,1073,1074,1072 ,0,0,0}, {1287,1288,1290 ,1071,1072,1074 ,0,0,0}, - {1289,1291,1292 ,1073,1075,1076 ,0,0,0}, {1292,1290,1289 ,1076,1074,1073 ,0,0,0}, - {1293,1291,1294 ,1077,1075,1078 ,0,0,0}, {1291,1293,1292 ,1075,1077,1076 ,0,0,0}, - {1295,1296,1297 ,126,1079,126 ,0,0,0}, {1298,1299,1300 ,1080,1081,1082 ,0,0,0}, - {1301,1295,1297 ,1083,126,126 ,0,0,0}, {1300,1299,1301 ,1082,1081,1083 ,0,0,0}, - {1299,1298,1302 ,1081,1080,1084 ,0,0,0}, {1297,1300,1301 ,126,1082,1083 ,0,0,0}, - {1303,1304,1305 ,1085,1086,1087 ,0,0,0}, {1304,1306,1305 ,1086,1088,1087 ,0,0,0}, - {1302,1307,1303 ,1084,1089,1085 ,0,0,0}, {1304,1303,1307 ,1086,1085,1089 ,0,0,0}, - {1308,1309,1310 ,1090,1091,1092 ,0,0,0}, {1311,1312,1306 ,1093,1094,1088 ,0,0,0}, - {1309,1312,1311 ,1091,1094,1093 ,0,0,0}, {1309,1311,1310 ,1091,1093,1092 ,0,0,0}, - {1310,1313,1308 ,1092,1095,1090 ,0,0,0}, {1305,1306,1312 ,1087,1088,1094 ,0,0,0}, - {1302,1298,1307 ,1084,1080,1089 ,0,0,0}, {1295,1314,1296 ,126,1096,1079 ,0,0,0}, - {1315,1314,1316 ,1097,1096,1098 ,0,0,0}, {1314,1315,1296 ,1096,1097,1079 ,0,0,0}, - {1317,1318,1316 ,1099,1100,1098 ,0,0,0}, {1315,1316,1318 ,1097,1098,1100 ,0,0,0}, - {1317,1319,1320 ,1099,1101,1102 ,0,0,0}, {1320,1318,1317 ,1102,1100,1099 ,0,0,0}, - {1321,1319,1322 ,1103,1101,1072 ,0,0,0}, {1319,1321,1320 ,1101,1103,1102 ,0,0,0}, - {1323,1324,1322 ,1104,1074,1072 ,0,0,0}, {1321,1322,1324 ,1103,1072,1074 ,0,0,0}, - {1323,1325,1326 ,1104,1105,1106 ,0,0,0}, {1326,1324,1323 ,1106,1074,1104 ,0,0,0}, - {1327,1325,1328 ,1107,1105,324 ,0,0,0}, {1325,1327,1326 ,1105,1107,1106 ,0,0,0}, - {1329,1330,1331 ,1108,1109,1108 ,0,0,0}, {1332,1333,1334 ,1110,1111,1112 ,0,0,0}, - {1332,1331,1333 ,1110,1108,1111 ,0,0,0}, {1334,1333,1335 ,1112,1111,1112 ,0,0,0}, - {1331,1332,1329 ,1108,1110,1108 ,0,0,0}, {1336,1330,1329 ,1109,1109,1108 ,0,0,0}, - {1337,1336,1338 ,1113,1109,1113 ,0,0,0}, {1336,1337,1330 ,1109,1113,1109 ,0,0,0}, - {1339,1340,1341 ,1114,1115,1114 ,0,0,0}, {1342,1340,1343 ,1115,1115,1116 ,0,0,0}, - {1340,1342,1341 ,1115,1115,1114 ,0,0,0}, {1344,1345,1343 ,1117,1116,1116 ,0,0,0}, - {1342,1343,1345 ,1115,1116,1116 ,0,0,0}, {1344,1346,1347 ,1117,1118,1117 ,0,0,0}, - {1347,1345,1344 ,1117,1116,1117 ,0,0,0}, {1346,1348,1347 ,1118,1119,1117 ,0,0,0}, - {1349,1339,1341 ,1120,1114,1114 ,0,0,0}, {1350,1351,1349 ,1121,1120,1120 ,0,0,0}, - {1339,1349,1351 ,1114,1120,1120 ,0,0,0}, {1350,1352,1353 ,1121,1122,1121 ,0,0,0}, - {1353,1351,1350 ,1121,1120,1121 ,0,0,0}, {1354,1352,1355 ,1122,1122,1123 ,0,0,0}, - {1352,1354,1353 ,1122,1122,1121 ,0,0,0}, {1354,1355,1356 ,1122,1123,1124 ,0,0,0}, - {1357,1358,1359 ,1125,1126,1127 ,0,0,0}, {1360,1361,1357 ,1128,1129,1125 ,0,0,0}, - {1357,1359,1360 ,1125,1127,1128 ,0,0,0}, {1361,1362,1363 ,1129,1130,1131 ,0,0,0}, - {1362,1361,1360 ,1130,1129,1128 ,0,0,0}, {1364,1363,1365 ,1132,1131,1133 ,0,0,0}, - {1362,1365,1363 ,1130,1133,1131 ,0,0,0}, {1366,1367,1364 ,1134,1135,1132 ,0,0,0}, - {1364,1365,1366 ,1132,1133,1134 ,0,0,0}, {1367,1368,1369 ,1135,1136,1137 ,0,0,0}, - {1368,1367,1366 ,1136,1135,1134 ,0,0,0}, {1370,1369,1371 ,1138,1137,1139 ,0,0,0}, - {1368,1371,1369 ,1136,1139,1137 ,0,0,0}, {1372,1373,1370 ,1140,1141,1138 ,0,0,0}, - {1370,1371,1372 ,1138,1139,1140 ,0,0,0}, {1373,1374,1375 ,1141,1142,1143 ,0,0,0}, - {1374,1373,1372 ,1142,1141,1140 ,0,0,0}, {1376,1375,1377 ,1144,1143,1145 ,0,0,0}, - {1374,1377,1375 ,1142,1145,1143 ,0,0,0}, {1378,1379,1376 ,1146,1147,1144 ,0,0,0}, - {1376,1377,1378 ,1144,1145,1146 ,0,0,0}, {1379,1380,1381 ,1147,1148,1149 ,0,0,0}, - {1380,1379,1378 ,1148,1147,1146 ,0,0,0}, {1382,1381,1383 ,1150,1149,1151 ,0,0,0}, - {1380,1383,1381 ,1148,1151,1149 ,0,0,0}, {1384,1385,1382 ,1152,1153,1150 ,0,0,0}, - {1382,1383,1384 ,1150,1151,1152 ,0,0,0}, {1385,1386,1387 ,1153,1154,1155 ,0,0,0}, - {1386,1385,1384 ,1154,1153,1152 ,0,0,0}, {1388,1387,1389 ,1156,1155,1157 ,0,0,0}, - {1386,1389,1387 ,1154,1157,1155 ,0,0,0}, {1390,1391,1388 ,1158,1159,1156 ,0,0,0}, - {1388,1389,1390 ,1156,1157,1158 ,0,0,0}, {1391,1392,1393 ,1159,1160,1161 ,0,0,0}, - {1392,1391,1390 ,1160,1159,1158 ,0,0,0}, {1394,1393,1395 ,1162,1161,1163 ,0,0,0}, - {1392,1395,1393 ,1160,1163,1161 ,0,0,0}, {1396,1397,1394 ,1164,1164,1162 ,0,0,0}, - {1394,1395,1396 ,1162,1163,1164 ,0,0,0}, {1359,1358,1398 ,1127,1126,1165 ,0,0,0}, - {1399,1398,1400 ,1166,1165,1167 ,0,0,0}, {1358,1400,1398 ,1126,1167,1165 ,0,0,0}, - {1401,1402,1399 ,1168,1169,1166 ,0,0,0}, {1399,1400,1401 ,1166,1167,1168 ,0,0,0}, - {1402,1403,1404 ,1169,1170,1171 ,0,0,0}, {1403,1402,1401 ,1170,1169,1168 ,0,0,0}, - {1405,1404,1406 ,1172,1171,1173 ,0,0,0}, {1403,1406,1404 ,1170,1173,1171 ,0,0,0}, - {1407,1408,1405 ,1174,1175,1172 ,0,0,0}, {1405,1406,1407 ,1172,1173,1174 ,0,0,0}, - {1408,1409,1410 ,1175,1176,1177 ,0,0,0}, {1409,1408,1407 ,1176,1175,1174 ,0,0,0}, - {1411,1410,1412 ,1178,1177,1179 ,0,0,0}, {1409,1412,1410 ,1176,1179,1177 ,0,0,0}, - {1413,1414,1411 ,1180,1181,1178 ,0,0,0}, {1411,1412,1413 ,1178,1179,1180 ,0,0,0}, - {1414,1415,1416 ,1181,1182,1183 ,0,0,0}, {1415,1414,1413 ,1182,1181,1180 ,0,0,0}, - {1417,1416,1418 ,1184,1183,1185 ,0,0,0}, {1415,1418,1416 ,1182,1185,1183 ,0,0,0}, - {1419,1420,1417 ,1186,1187,1184 ,0,0,0}, {1417,1418,1419 ,1184,1185,1186 ,0,0,0}, - {1420,1421,1422 ,1187,1188,1189 ,0,0,0}, {1421,1420,1419 ,1188,1187,1186 ,0,0,0}, - {1423,1422,1424 ,1190,1189,1191 ,0,0,0}, {1421,1424,1422 ,1188,1191,1189 ,0,0,0}, - {1425,1426,1423 ,1192,1193,1190 ,0,0,0}, {1423,1424,1425 ,1190,1191,1192 ,0,0,0}, - {1426,1427,1428 ,1193,1194,1195 ,0,0,0}, {1427,1426,1425 ,1194,1193,1192 ,0,0,0}, - {1429,1428,1430 ,1196,1195,1197 ,0,0,0}, {1427,1430,1428 ,1194,1197,1195 ,0,0,0}, - {1431,1432,1429 ,1198,1199,1196 ,0,0,0}, {1429,1430,1431 ,1196,1197,1198 ,0,0,0}, - {1432,1433,1434 ,1199,1200,1201 ,0,0,0}, {1433,1432,1431 ,1200,1199,1198 ,0,0,0}, - {1433,1435,1434 ,1200,1202,1201 ,0,0,0}, {1434,1435,1436 ,1201,1202,1203 ,0,0,0}, - {1437,1438,1435 ,1204,1204,1205 ,0,0,0}, {1437,1439,1438 ,1204,1206,1204 ,0,0,0}, - {1439,1437,1440 ,1206,1204,1206 ,0,0,0}, {1436,1435,1438 ,324,1205,1204 ,0,0,0}, - {1441,1442,1443 ,1207,1208,1207 ,0,0,0}, {1444,1445,1442 ,1209,1210,1208 ,0,0,0}, - {1442,1445,1443 ,1208,1210,1207 ,0,0,0}, {1446,1447,1444 ,1211,1212,1209 ,0,0,0}, - {1444,1442,1446 ,1209,1208,1211 ,0,0,0}, {1447,1448,1449 ,1212,1213,1214 ,0,0,0}, - {1448,1447,1446 ,1213,1212,1211 ,0,0,0}, {1450,1449,1451 ,1215,1214,1216 ,0,0,0}, - {1448,1451,1449 ,1213,1216,1214 ,0,0,0}, {1452,1450,1453 ,1217,1215,1218 ,0,0,0}, - {1450,1451,1453 ,1215,1216,1218 ,0,0,0}, {1454,1450,1452 ,1217,1215,1217 ,0,0,0}, - {1455,1441,1443 ,1219,1207,1207 ,0,0,0}, {1456,1455,1457 ,1220,1219,1221 ,0,0,0}, - {1456,1441,1455 ,1220,1207,1219 ,0,0,0}, {1458,1457,1459 ,1222,1221,1223 ,0,0,0}, - {1455,1459,1457 ,1219,1223,1221 ,0,0,0}, {1460,1461,1458 ,1224,1225,1222 ,0,0,0}, - {1458,1459,1460 ,1222,1223,1224 ,0,0,0}, {1461,1462,1463 ,1225,1226,1227 ,0,0,0}, - {1462,1461,1460 ,1226,1225,1224 ,0,0,0}, {1463,1464,1337 ,1227,1228,1113 ,0,0,0}, - {1462,1464,1463 ,1226,1228,1227 ,0,0,0}, {1463,1337,1338 ,1227,1113,1113 ,0,0,0}, - {1465,1466,1467 ,1229,1230,1231 ,0,0,0}, {1465,1468,1469 ,1229,1232,1233 ,0,0,0}, - {1467,1466,1470 ,1231,1230,1234 ,0,0,0}, {1470,1466,1471 ,1234,1230,1235 ,0,0,0}, - {1470,1471,1472 ,1234,1235,1236 ,0,0,0}, {1473,1472,1471 ,1237,1236,1235 ,0,0,0}, - {1472,1473,1474 ,1236,1237,1238 ,0,0,0}, {1475,1474,1473 ,1239,1238,1237 ,0,0,0}, - {1475,1476,1477 ,1239,1240,1241 ,0,0,0}, {1474,1475,1477 ,1238,1239,1241 ,0,0,0}, - {1467,1468,1465 ,1231,1232,1229 ,0,0,0}, {1477,1476,1478 ,1241,1240,1242 ,0,0,0}, - {1479,1478,1480 ,1243,1242,1244 ,0,0,0}, {1480,1478,1476 ,1244,1242,1240 ,0,0,0}, - {1479,1480,1481 ,1243,1244,1243 ,0,0,0}, {1482,1469,1483 ,1245,1233,1246 ,0,0,0}, - {1468,1483,1469 ,1232,1246,1233 ,0,0,0}, {1484,1485,1482 ,1247,1248,1245 ,0,0,0}, - {1482,1483,1484 ,1245,1246,1247 ,0,0,0}, {1485,1486,1487 ,1248,1249,1250 ,0,0,0}, - {1486,1485,1484 ,1249,1248,1247 ,0,0,0}, {1488,1487,1489 ,1251,1250,1252 ,0,0,0}, - {1486,1489,1487 ,1249,1252,1250 ,0,0,0}, {1490,1491,1488 ,1253,1254,1251 ,0,0,0}, - {1488,1489,1490 ,1251,1252,1253 ,0,0,0}, {1491,1492,1493 ,1254,1255,1256 ,0,0,0}, - {1492,1491,1490 ,1255,1254,1253 ,0,0,0}, {1494,1493,1495 ,1257,1256,1258 ,0,0,0}, - {1492,1495,1493 ,1255,1258,1256 ,0,0,0}, {1494,1495,1496 ,1257,1258,1257 ,0,0,0}, - {1497,1498,1499 ,1259,1260,1259 ,0,0,0}, {1499,1500,1497 ,1259,1261,1259 ,0,0,0}, - {1501,1502,1498 ,1260,1262,1260 ,0,0,0}, {1503,1500,1499 ,1261,1261,1259 ,0,0,0}, - {1497,1501,1498 ,1259,1260,1260 ,0,0,0}, {1501,1504,1502 ,1260,1262,1262 ,0,0,0}, - {1505,1504,1506 ,1263,1262,1263 ,0,0,0}, {1506,1494,1496 ,1263,1257,1257 ,0,0,0}, - {1505,1502,1504 ,1263,1262,1262 ,0,0,0}, {1506,1496,1505 ,1263,1257,1263 ,0,0,0}, - {1507,1503,1508 ,1264,1261,1264 ,0,0,0}, {1503,1507,1500 ,1261,1264,1261 ,0,0,0}, - {1509,1510,1508 ,1265,1265,1264 ,0,0,0}, {1507,1508,1510 ,1264,1264,1265 ,0,0,0}, - {1509,1511,1512 ,1265,1266,1266 ,0,0,0}, {1512,1510,1509 ,1266,1265,1265 ,0,0,0}, - {1513,1511,1514 ,1267,1266,1267 ,0,0,0}, {1511,1513,1512 ,1266,1267,1266 ,0,0,0}, - {1513,1514,1355 ,1267,1267,1268 ,0,0,0}, {1355,1514,1356 ,1268,1267,1269 ,0,0,0}, - {1515,1348,1346 ,1270,1271,1272 ,0,0,0}, {1516,1517,1518 ,1273,1274,1274 ,0,0,0}, - {1519,1520,1521 ,1275,1275,1270 ,0,0,0}, {1522,1523,1524 ,1276,1276,1277 ,0,0,0}, - {1525,1526,1527 ,1273,1278,1278 ,0,0,0}, {1528,1529,1524 ,1279,1277,1277 ,0,0,0}, - {1522,1524,1529 ,1276,1277,1277 ,0,0,0}, {1530,1529,1528 ,1280,1277,1279 ,0,0,0}, - {1526,1523,1527 ,1278,1276,1278 ,0,0,0}, {1527,1523,1522 ,1278,1276,1276 ,0,0,0}, - {1525,1517,1516 ,1273,1274,1273 ,0,0,0}, {1525,1516,1526 ,1273,1273,1278 ,0,0,0}, - {1518,1520,1519 ,1274,1275,1275 ,0,0,0}, {1517,1520,1518 ,1274,1275,1274 ,0,0,0}, - {1515,1521,1348 ,1270,1270,1271 ,0,0,0}, {1519,1521,1515 ,1275,1270,1270 ,0,0,0}, - {1531,1532,1533 ,1281,1281,1282 ,0,0,0}, {1533,1532,1534 ,1282,1281,1282 ,0,0,0}, - {1532,1531,1535 ,1281,1281,1283 ,0,0,0}, {1536,1535,1531 ,1284,1283,1281 ,0,0,0}, - {1537,1538,1536 ,1285,1285,1284 ,0,0,0}, {1539,1533,1534 ,1286,1282,1282 ,0,0,0}, - {1530,1528,1537 ,1287,1288,1285 ,0,0,0}, {1538,1537,1528 ,1285,1285,1288 ,0,0,0}, - {1536,1538,1535 ,1284,1285,1283 ,0,0,0}, {1540,1539,1541 ,1289,1286,1286 ,0,0,0}, - {1534,1541,1539 ,1282,1286,1286 ,0,0,0}, {1542,1543,1540 ,1289,1290,1289 ,0,0,0}, - {1540,1541,1542 ,1289,1286,1289 ,0,0,0}, {1543,1544,1545 ,1290,1290,1291 ,0,0,0}, - {1544,1543,1542 ,1290,1290,1289 ,0,0,0}, {1546,1545,1547 ,1292,1291,1291 ,0,0,0}, - {1544,1547,1545 ,1290,1291,1291 ,0,0,0}, {1546,1547,1548 ,1292,1291,1292 ,0,0,0}, - {1549,1550,1551 ,1293,1293,1294 ,0,0,0}, {1552,1553,1551 ,1295,1296,1294 ,0,0,0}, - {1549,1551,1553 ,1293,1294,1296 ,0,0,0}, {1552,1554,1555 ,1295,1297,1298 ,0,0,0}, - {1555,1553,1552 ,1298,1296,1295 ,0,0,0}, {1556,1554,1557 ,1299,1297,1300 ,0,0,0}, - {1554,1556,1555 ,1297,1299,1298 ,0,0,0}, {1558,1559,1557 ,1301,1302,1300 ,0,0,0}, - {1556,1557,1559 ,1299,1300,1302 ,0,0,0}, {1558,1560,1561 ,1301,1303,1304 ,0,0,0}, - {1561,1559,1558 ,1304,1302,1301 ,0,0,0}, {1562,1560,1563 ,1305,1303,1306 ,0,0,0}, - {1560,1562,1561 ,1303,1305,1304 ,0,0,0}, {1564,1565,1563 ,1307,1308,1306 ,0,0,0}, - {1562,1563,1565 ,1305,1306,1308 ,0,0,0}, {1564,1566,1567 ,1307,1309,1310 ,0,0,0}, - {1567,1565,1564 ,1310,1308,1307 ,0,0,0}, {1568,1566,1569 ,1311,1309,1312 ,0,0,0}, - {1566,1568,1567 ,1309,1311,1310 ,0,0,0}, {1570,1571,1569 ,1313,1314,1312 ,0,0,0}, - {1568,1569,1571 ,1311,1312,1314 ,0,0,0}, {1570,1572,1573 ,1313,1315,1316 ,0,0,0}, - {1573,1571,1570 ,1316,1314,1313 ,0,0,0}, {1574,1572,1575 ,1317,1315,1318 ,0,0,0}, - {1572,1574,1573 ,1315,1317,1316 ,0,0,0}, {1576,1577,1575 ,1319,1320,1318 ,0,0,0}, - {1574,1575,1577 ,1317,1318,1320 ,0,0,0}, {1576,1578,1579 ,1319,1321,1322 ,0,0,0}, - {1579,1577,1576 ,1322,1320,1319 ,0,0,0}, {1580,1578,1581 ,1323,1321,1324 ,0,0,0}, - {1578,1580,1579 ,1321,1323,1322 ,0,0,0}, {1546,1582,1581 ,1292,1325,1324 ,0,0,0}, - {1580,1581,1582 ,1323,1324,1325 ,0,0,0}, {1548,1582,1546 ,1292,1325,1292 ,0,0,0}, - {1583,1550,1549 ,1326,1293,1293 ,0,0,0}, {1584,1583,1585 ,1327,1326,1328 ,0,0,0}, - {1583,1584,1550 ,1326,1327,1293 ,0,0,0}, {1586,1587,1585 ,1329,1330,1328 ,0,0,0}, - {1584,1585,1587 ,1327,1328,1330 ,0,0,0}, {1586,1588,1589 ,1329,1331,1332 ,0,0,0}, - {1589,1587,1586 ,1332,1330,1329 ,0,0,0}, {1590,1588,1591 ,1333,1331,1334 ,0,0,0}, - {1588,1590,1589 ,1331,1333,1332 ,0,0,0}, {1592,1593,1591 ,1335,1336,1334 ,0,0,0}, - {1590,1591,1593 ,1333,1334,1336 ,0,0,0}, {1592,1594,1595 ,1335,1337,1338 ,0,0,0}, - {1595,1593,1592 ,1338,1336,1335 ,0,0,0}, {1596,1594,1597 ,1339,1337,1340 ,0,0,0}, - {1594,1596,1595 ,1337,1339,1338 ,0,0,0}, {1598,1599,1597 ,1341,1342,1340 ,0,0,0}, - {1596,1597,1599 ,1339,1340,1342 ,0,0,0}, {1598,1600,1601 ,1341,1343,1344 ,0,0,0}, - {1601,1599,1598 ,1344,1342,1341 ,0,0,0}, {1602,1600,1603 ,1345,1343,1346 ,0,0,0}, - {1600,1602,1601 ,1343,1345,1344 ,0,0,0}, {1604,1605,1603 ,1347,1348,1346 ,0,0,0}, - {1602,1603,1605 ,1345,1346,1348 ,0,0,0}, {1604,1606,1607 ,1347,1349,1350 ,0,0,0}, - {1607,1605,1604 ,1350,1348,1347 ,0,0,0}, {1608,1606,1609 ,1351,1349,1352 ,0,0,0}, - {1606,1608,1607 ,1349,1351,1350 ,0,0,0}, {1610,1611,1609 ,1353,1354,1352 ,0,0,0}, - {1608,1609,1611 ,1351,1352,1354 ,0,0,0}, {1610,1612,1613 ,1353,1355,1356 ,0,0,0}, - {1613,1611,1610 ,1356,1354,1353 ,0,0,0}, {1614,1612,1615 ,1357,1355,1358 ,0,0,0}, - {1612,1614,1613 ,1355,1357,1356 ,0,0,0}, {1614,1615,1616 ,1357,1358,1358 ,0,0,0}, - {1617,1615,1618 ,1359,1360,1359 ,0,0,0}, {1615,1617,1616 ,1360,1359,1360 ,0,0,0}, - {1619,1620,1621 ,1361,1362,1363 ,0,0,0}, {1622,1623,1624 ,1364,1365,1366 ,0,0,0}, - {1625,1619,1621 ,1367,1361,1363 ,0,0,0}, {1623,1621,1620 ,1365,1363,1362 ,0,0,0}, - {1626,1619,1625 ,1368,1361,1367 ,0,0,0}, {1627,1628,1629 ,1369,1370,1371 ,0,0,0}, - {1626,1625,1627 ,1368,1367,1369 ,0,0,0}, {1630,1628,1631 ,1372,1370,1373 ,0,0,0}, - {1627,1629,1626 ,1369,1371,1368 ,0,0,0}, {1628,1630,1629 ,1370,1372,1371 ,0,0,0}, - {1631,1632,1633 ,1373,1374,1375 ,0,0,0}, {1620,1624,1623 ,1362,1366,1365 ,0,0,0}, - {1634,1635,1636 ,1376,1377,1378 ,0,0,0}, {1637,1633,1632 ,1379,1375,1374 ,0,0,0}, - {1637,1638,1639 ,1379,1380,1381 ,0,0,0}, {1634,1636,1639 ,1376,1378,1381 ,0,0,0}, - {1634,1639,1638 ,1376,1381,1380 ,0,0,0}, {1636,1635,1640 ,1378,1377,1382 ,0,0,0}, - {1641,1642,1643 ,1383,1384,1385 ,0,0,0}, {1640,1641,1643 ,1382,1383,1385 ,0,0,0}, - {1641,1640,1635 ,1383,1382,1377 ,0,0,0}, {1642,1644,1643 ,1384,1386,1385 ,0,0,0}, - {1638,1637,1632 ,1380,1379,1374 ,0,0,0}, {1644,1645,1646 ,1386,1387,1388 ,0,0,0}, - {1644,1642,1645 ,1386,1384,1387 ,0,0,0}, {1647,1648,1649 ,1389,1390,1391 ,0,0,0}, - {1650,1649,1648 ,1392,1391,1390 ,0,0,0}, {1650,1651,1649 ,1392,1393,1391 ,0,0,0}, - {1651,1646,1645 ,1393,1388,1387 ,0,0,0}, {1651,1650,1646 ,1393,1392,1388 ,0,0,0}, - {1633,1630,1631 ,1375,1372,1373 ,0,0,0}, {1652,1653,1647 ,1394,1395,1389 ,0,0,0}, - {1654,1655,1652 ,1396,1397,1394 ,0,0,0}, {1618,1655,1654 ,1398,1397,1396 ,0,0,0}, - {1648,1647,1653 ,1390,1389,1395 ,0,0,0}, {1655,1653,1652 ,1397,1395,1394 ,0,0,0}, - {1617,1618,1654 ,1398,1398,1396 ,0,0,0}, {1656,1657,1622 ,1399,1400,1364 ,0,0,0}, - {1622,1624,1656 ,1364,1366,1399 ,0,0,0}, {1657,1658,1659 ,1400,1401,1402 ,0,0,0}, - {1658,1657,1656 ,1401,1400,1399 ,0,0,0}, {1660,1659,1661 ,1403,1402,1404 ,0,0,0}, - {1658,1661,1659 ,1401,1404,1402 ,0,0,0}, {1662,1663,1660 ,1405,1406,1403 ,0,0,0}, - {1660,1661,1662 ,1403,1404,1405 ,0,0,0}, {1663,1664,1665 ,1406,1407,1408 ,0,0,0}, - {1664,1663,1662 ,1407,1406,1405 ,0,0,0}, {1666,1665,1667 ,1409,1408,1410 ,0,0,0}, - {1664,1667,1665 ,1407,1410,1408 ,0,0,0}, {1668,1669,1666 ,1411,1412,1409 ,0,0,0}, - {1666,1667,1668 ,1409,1410,1411 ,0,0,0}, {1669,1670,1671 ,1412,1413,1414 ,0,0,0}, - {1670,1669,1668 ,1413,1412,1411 ,0,0,0}, {1672,1671,1673 ,1415,1414,1416 ,0,0,0}, - {1670,1673,1671 ,1413,1416,1414 ,0,0,0}, {1674,1675,1672 ,1417,1418,1415 ,0,0,0}, - {1672,1673,1674 ,1415,1416,1417 ,0,0,0}, {1675,1676,1677 ,1418,1419,1420 ,0,0,0}, - {1676,1675,1674 ,1419,1418,1417 ,0,0,0}, {1678,1677,1679 ,1421,1420,1422 ,0,0,0}, - {1676,1679,1677 ,1419,1422,1420 ,0,0,0}, {1680,1681,1678 ,1423,1424,1421 ,0,0,0}, - {1678,1679,1680 ,1421,1422,1423 ,0,0,0}, {1681,1682,1683 ,1424,1425,1426 ,0,0,0}, - {1682,1681,1680 ,1425,1424,1423 ,0,0,0}, {1684,1683,1685 ,1427,1426,1428 ,0,0,0}, - {1682,1685,1683 ,1425,1428,1426 ,0,0,0}, {1686,1687,1684 ,1429,1430,1427 ,0,0,0}, - {1684,1685,1686 ,1427,1428,1429 ,0,0,0}, {1687,1688,1689 ,1430,1431,1432 ,0,0,0}, - {1688,1687,1686 ,1431,1430,1429 ,0,0,0}, {1690,1689,1691 ,1433,1432,1434 ,0,0,0}, - {1688,1691,1689 ,1431,1434,1432 ,0,0,0}, {1690,1691,1692 ,1433,1434,1433 ,0,0,0}, - {1693,1694,1695 ,1435,1435,1435 ,0,0,0}, {1694,1693,1696 ,1435,1435,1435 ,0,0,0}, - {1697,1698,1699 ,1436,1437,1438 ,0,0,0}, {1700,1701,1702 ,1439,1440,1441 ,0,0,0}, - {1698,1703,1699 ,1437,1442,1438 ,0,0,0}, {1697,1699,1704 ,1436,1438,1443 ,0,0,0}, - {1700,1697,1704 ,1439,1436,1443 ,0,0,0}, {1705,1706,1703 ,1444,1445,1442 ,0,0,0}, - {1705,1703,1698 ,1444,1442,1437 ,0,0,0}, {1707,1708,1709 ,1446,1447,1448 ,0,0,0}, - {1706,1705,1707 ,1445,1444,1446 ,0,0,0}, {1707,1709,1706 ,1446,1448,1445 ,0,0,0}, - {1708,1710,1709 ,1447,1449,1448 ,0,0,0}, {1701,1700,1704 ,1440,1439,1443 ,0,0,0}, - {1708,1711,1710 ,1447,1450,1449 ,0,0,0}, {1712,1713,1714 ,1451,1452,1453 ,0,0,0}, - {1712,1714,1711 ,1451,1453,1450 ,0,0,0}, {1713,1712,1715 ,1452,1451,1454 ,0,0,0}, - {1716,1717,1715 ,1455,1456,1454 ,0,0,0}, {1717,1713,1715 ,1456,1452,1454 ,0,0,0}, - {1718,1719,1720 ,1457,1458,1459 ,0,0,0}, {1717,1716,1721 ,1456,1455,1460 ,0,0,0}, - {1722,1723,1721 ,1461,1462,1460 ,0,0,0}, {1719,1718,1723 ,1458,1457,1462 ,0,0,0}, - {1719,1723,1722 ,1458,1462,1461 ,0,0,0}, {1718,1720,1724 ,1457,1459,1463 ,0,0,0}, - {1716,1722,1721 ,1455,1461,1460 ,0,0,0}, {1725,1724,1726 ,1464,1463,1465 ,0,0,0}, - {1725,1726,1727 ,1464,1465,1466 ,0,0,0}, {1726,1724,1720 ,1465,1463,1459 ,0,0,0}, - {1728,1729,1730 ,1467,1468,1469 ,0,0,0}, {1714,1710,1711 ,1453,1449,1450 ,0,0,0}, - {1728,1731,1727 ,1467,1470,1466 ,0,0,0}, {1731,1728,1730 ,1470,1467,1469 ,0,0,0}, - {1729,1732,1733 ,1468,1471,1472 ,0,0,0}, {1733,1730,1729 ,1472,1469,1468 ,0,0,0}, - {1734,1735,1732 ,1473,1474,1471 ,0,0,0}, {1733,1732,1735 ,1472,1471,1474 ,0,0,0}, - {1734,1696,1693 ,1473,1475,1475 ,0,0,0}, {1734,1693,1735 ,1473,1475,1474 ,0,0,0}, - {1727,1731,1725 ,1466,1470,1464 ,0,0,0}, {1736,1702,1737 ,1476,1441,1477 ,0,0,0}, - {1701,1737,1702 ,1440,1477,1441 ,0,0,0}, {1738,1739,1736 ,1478,1479,1476 ,0,0,0}, - {1736,1737,1738 ,1476,1477,1478 ,0,0,0}, {1739,1740,1741 ,1479,1480,1481 ,0,0,0}, - {1740,1739,1738 ,1480,1479,1478 ,0,0,0}, {1742,1741,1743 ,1482,1481,1483 ,0,0,0}, - {1740,1743,1741 ,1480,1483,1481 ,0,0,0}, {1744,1745,1742 ,1484,1485,1482 ,0,0,0}, - {1742,1743,1744 ,1482,1483,1484 ,0,0,0}, {1745,1746,1747 ,1485,1486,1487 ,0,0,0}, - {1746,1745,1744 ,1486,1485,1484 ,0,0,0}, {1748,1747,1749 ,1488,1487,1489 ,0,0,0}, - {1746,1749,1747 ,1486,1489,1487 ,0,0,0}, {1750,1751,1748 ,1490,1491,1488 ,0,0,0}, - {1748,1749,1750 ,1488,1489,1490 ,0,0,0}, {1751,1752,1753 ,1491,1492,1493 ,0,0,0}, - {1752,1751,1750 ,1492,1491,1490 ,0,0,0}, {1754,1753,1755 ,1494,1493,1495 ,0,0,0}, - {1752,1755,1753 ,1492,1495,1493 ,0,0,0}, {1756,1757,1754 ,1496,1497,1494 ,0,0,0}, - {1754,1755,1756 ,1494,1495,1496 ,0,0,0}, {1757,1758,1759 ,1497,1498,1499 ,0,0,0}, - {1758,1757,1756 ,1498,1497,1496 ,0,0,0}, {1760,1759,1761 ,1500,1499,1501 ,0,0,0}, - {1758,1761,1759 ,1498,1501,1499 ,0,0,0}, {1762,1763,1760 ,1502,1503,1500 ,0,0,0}, - {1760,1761,1762 ,1500,1501,1502 ,0,0,0}, {1763,1764,1765 ,1503,1504,1505 ,0,0,0}, - {1764,1763,1762 ,1504,1503,1502 ,0,0,0}, {1766,1765,1767 ,1506,1505,1507 ,0,0,0}, - {1764,1767,1765 ,1504,1507,1505 ,0,0,0}, {1768,1769,1766 ,1508,1509,1506 ,0,0,0}, - {1766,1767,1768 ,1506,1507,1508 ,0,0,0}, {1769,1770,1771 ,1509,1510,1511 ,0,0,0}, - {1770,1769,1768 ,1510,1509,1508 ,0,0,0}, {1772,1771,1773 ,1512,1511,1513 ,0,0,0}, - {1770,1773,1771 ,1510,1513,1511 ,0,0,0}, {1772,1773,1774 ,1512,1513,1514 ,0,0,0}, - {1775,1776,1777 ,1515,1516,1517 ,0,0,0}, {1778,1779,1777 ,1518,1519,1517 ,0,0,0}, - {1775,1777,1779 ,1515,1517,1519 ,0,0,0}, {1778,1780,1781 ,1518,1520,1521 ,0,0,0}, - {1781,1779,1778 ,1521,1519,1518 ,0,0,0}, {1782,1780,1783 ,1522,1520,1523 ,0,0,0}, - {1780,1782,1781 ,1520,1522,1521 ,0,0,0}, {1784,1785,1783 ,1524,1525,1523 ,0,0,0}, - {1782,1783,1785 ,1522,1523,1525 ,0,0,0}, {1784,1786,1787 ,1524,1526,1527 ,0,0,0}, - {1787,1785,1784 ,1527,1525,1524 ,0,0,0}, {1788,1786,1789 ,1528,1526,1529 ,0,0,0}, - {1786,1788,1787 ,1526,1528,1527 ,0,0,0}, {1790,1791,1789 ,1530,1531,1529 ,0,0,0}, - {1788,1789,1791 ,1528,1529,1531 ,0,0,0}, {1790,1792,1793 ,1530,1532,1533 ,0,0,0}, - {1793,1791,1790 ,1533,1531,1530 ,0,0,0}, {1794,1792,1795 ,1534,1532,1535 ,0,0,0}, - {1792,1794,1793 ,1532,1534,1533 ,0,0,0}, {1796,1797,1795 ,1536,1537,1535 ,0,0,0}, - {1794,1795,1797 ,1534,1535,1537 ,0,0,0}, {1796,1798,1799 ,1536,1538,1539 ,0,0,0}, - {1799,1797,1796 ,1539,1537,1536 ,0,0,0}, {1800,1798,1801 ,1540,1538,1541 ,0,0,0}, - {1798,1800,1799 ,1538,1540,1539 ,0,0,0}, {1802,1803,1801 ,1542,1543,1541 ,0,0,0}, - {1800,1801,1803 ,1540,1541,1543 ,0,0,0}, {1802,1804,1805 ,1542,1544,1545 ,0,0,0}, - {1805,1803,1802 ,1545,1543,1542 ,0,0,0}, {1806,1804,1807 ,1546,1544,1547 ,0,0,0}, - {1804,1806,1805 ,1544,1546,1545 ,0,0,0}, {1808,1809,1807 ,1548,1549,1547 ,0,0,0}, - {1806,1807,1809 ,1546,1547,1549 ,0,0,0}, {1808,1810,1811 ,1548,1550,1551 ,0,0,0}, - {1811,1809,1808 ,1551,1549,1548 ,0,0,0}, {1812,1810,1813 ,1552,1550,1553 ,0,0,0}, - {1810,1812,1811 ,1550,1552,1551 ,0,0,0}, {1814,1815,1813 ,1554,1555,1553 ,0,0,0}, - {1812,1813,1815 ,1552,1553,1555 ,0,0,0}, {1814,1816,1817 ,1554,1556,1557 ,0,0,0}, - {1817,1815,1814 ,1557,1555,1554 ,0,0,0}, {1818,1816,1819 ,1558,1556,1559 ,0,0,0}, - {1816,1818,1817 ,1556,1558,1557 ,0,0,0}, {1820,1821,1819 ,1560,1561,1559 ,0,0,0}, - {1818,1819,1821 ,1558,1559,1561 ,0,0,0}, {1820,1822,1823 ,1560,1562,1563 ,0,0,0}, - {1823,1821,1820 ,1563,1561,1560 ,0,0,0}, {1824,1822,1825 ,1564,1562,1565 ,0,0,0}, - {1822,1824,1823 ,1562,1564,1563 ,0,0,0}, {1826,1827,1825 ,1566,1567,1565 ,0,0,0}, - {1824,1825,1827 ,1564,1565,1567 ,0,0,0}, {1826,1828,1829 ,1566,1568,1569 ,0,0,0}, - {1829,1827,1826 ,1569,1567,1566 ,0,0,0}, {1830,1828,1831 ,1570,1568,1571 ,0,0,0}, - {1828,1830,1829 ,1568,1570,1569 ,0,0,0}, {1772,1832,1831 ,1572,1573,1571 ,0,0,0}, - {1830,1831,1832 ,1570,1571,1573 ,0,0,0}, {1774,1832,1772 ,1574,1573,1572 ,0,0,0}, - {1833,1776,1775 ,1575,1516,1515 ,0,0,0}, {1834,1833,1835 ,1576,1575,1577 ,0,0,0}, - {1833,1834,1776 ,1575,1576,1516 ,0,0,0}, {1836,1837,1835 ,1578,1579,1577 ,0,0,0}, - {1834,1835,1837 ,1576,1577,1579 ,0,0,0}, {1836,1838,1839 ,1578,1580,1581 ,0,0,0}, - {1839,1837,1836 ,1581,1579,1578 ,0,0,0}, {1840,1838,1841 ,1582,1580,1583 ,0,0,0}, - {1838,1840,1839 ,1580,1582,1581 ,0,0,0}, {1842,1843,1841 ,1584,1585,1583 ,0,0,0}, - {1840,1841,1843 ,1582,1583,1585 ,0,0,0}, {1842,1844,1845 ,1584,1586,1587 ,0,0,0}, - {1845,1843,1842 ,1587,1585,1584 ,0,0,0}, {1846,1844,1847 ,1588,1586,1589 ,0,0,0}, - {1844,1846,1845 ,1586,1588,1587 ,0,0,0}, {1848,1849,1847 ,1590,1591,1589 ,0,0,0}, - {1846,1847,1849 ,1588,1589,1591 ,0,0,0}, {1848,1850,1851 ,1590,1592,1593 ,0,0,0}, - {1851,1849,1848 ,1593,1591,1590 ,0,0,0}, {1852,1850,1853 ,1594,1592,1595 ,0,0,0}, - {1850,1852,1851 ,1592,1594,1593 ,0,0,0}, {1854,1855,1853 ,1596,1597,1595 ,0,0,0}, - {1852,1853,1855 ,1594,1595,1597 ,0,0,0}, {1854,1856,1857 ,1596,1598,1599 ,0,0,0}, - {1857,1855,1854 ,1599,1597,1596 ,0,0,0}, {1858,1856,1859 ,1600,1598,1601 ,0,0,0}, - {1856,1858,1857 ,1598,1600,1599 ,0,0,0}, {1860,1861,1859 ,1602,1603,1601 ,0,0,0}, - {1858,1859,1861 ,1600,1601,1603 ,0,0,0}, {1860,1862,1863 ,1602,1604,1605 ,0,0,0}, - {1863,1861,1860 ,1605,1603,1602 ,0,0,0}, {1864,1862,1865 ,1606,1604,1607 ,0,0,0}, - {1862,1864,1863 ,1604,1606,1605 ,0,0,0}, {1866,1867,1865 ,1608,1609,1607 ,0,0,0}, - {1864,1865,1867 ,1606,1607,1609 ,0,0,0}, {1866,1868,1869 ,1608,1610,1611 ,0,0,0}, - {1869,1867,1866 ,1611,1609,1608 ,0,0,0}, {1870,1868,1871 ,1612,1610,1613 ,0,0,0}, - {1868,1870,1869 ,1610,1612,1611 ,0,0,0}, {1872,1873,1871 ,1614,1615,1613 ,0,0,0}, - {1870,1871,1873 ,1612,1613,1615 ,0,0,0}, {1872,1874,1875 ,1614,1616,1617 ,0,0,0}, - {1875,1873,1872 ,1617,1615,1614 ,0,0,0}, {1876,1874,1877 ,1618,1616,1619 ,0,0,0}, - {1874,1876,1875 ,1616,1618,1617 ,0,0,0}, {1878,1879,1877 ,1620,1621,1619 ,0,0,0}, - {1876,1877,1879 ,1618,1619,1621 ,0,0,0}, {1878,1880,1881 ,1620,1622,1623 ,0,0,0}, - {1881,1879,1878 ,1623,1621,1620 ,0,0,0}, {1882,1880,1883 ,1624,1622,1625 ,0,0,0}, - {1880,1882,1881 ,1622,1624,1623 ,0,0,0}, {1884,1885,1883 ,1626,1627,1625 ,0,0,0}, - {1882,1883,1885 ,1624,1625,1627 ,0,0,0}, {1884,1886,1887 ,1626,1628,1629 ,0,0,0}, - {1887,1885,1884 ,1629,1627,1626 ,0,0,0}, {1888,1886,1889 ,1630,1628,21 ,0,0,0}, - {1886,1888,1887 ,1628,1630,1629 ,0,0,0}, {1888,1889,1890 ,1630,21,1631 ,0,0,0}, - {1891,1892,1893 ,1632,1633,1634 ,0,0,0}, {1894,1895,1896 ,1635,1636,1637 ,0,0,0}, - {1892,1897,1893 ,1633,1638,1634 ,0,0,0}, {1891,1893,1898 ,1632,1634,1639 ,0,0,0}, - {1894,1891,1898 ,1635,1632,1639 ,0,0,0}, {1899,1900,1897 ,1640,1641,1638 ,0,0,0}, - {1899,1897,1892 ,1640,1638,1633 ,0,0,0}, {1901,1902,1903 ,1642,1643,1644 ,0,0,0}, - {1900,1899,1901 ,1641,1640,1642 ,0,0,0}, {1901,1903,1900 ,1642,1644,1641 ,0,0,0}, - {1902,1904,1903 ,1643,1645,1644 ,0,0,0}, {1895,1894,1898 ,1636,1635,1639 ,0,0,0}, - {1902,1905,1904 ,1643,1646,1645 ,0,0,0}, {1906,1907,1908 ,1647,1648,1649 ,0,0,0}, - {1906,1908,1905 ,1647,1649,1646 ,0,0,0}, {1907,1906,1909 ,1648,1647,1650 ,0,0,0}, - {1910,1911,1909 ,1651,1652,1650 ,0,0,0}, {1911,1907,1909 ,1652,1648,1650 ,0,0,0}, - {1912,1913,1914 ,1653,1654,1655 ,0,0,0}, {1911,1910,1915 ,1652,1651,1656 ,0,0,0}, - {1916,1917,1915 ,1657,1658,1656 ,0,0,0}, {1913,1912,1917 ,1654,1653,1658 ,0,0,0}, - {1913,1917,1916 ,1654,1658,1657 ,0,0,0}, {1912,1914,1918 ,1653,1655,1659 ,0,0,0}, - {1910,1916,1915 ,1651,1657,1656 ,0,0,0}, {1919,1918,1920 ,1660,1659,1661 ,0,0,0}, - {1919,1920,1921 ,1660,1661,1662 ,0,0,0}, {1920,1918,1914 ,1661,1659,1655 ,0,0,0}, - {1922,1923,1924 ,1663,1664,1665 ,0,0,0}, {1908,1904,1905 ,1649,1645,1646 ,0,0,0}, - {1922,1925,1921 ,1663,1666,1662 ,0,0,0}, {1925,1922,1924 ,1666,1663,1665 ,0,0,0}, - {1923,1926,1927 ,1664,1667,1668 ,0,0,0}, {1927,1924,1923 ,1668,1665,1664 ,0,0,0}, - {1928,1929,1926 ,1669,1670,1667 ,0,0,0}, {1927,1926,1929 ,1668,1667,1670 ,0,0,0}, - {1928,1890,1889 ,1669,1671,1672 ,0,0,0}, {1928,1889,1929 ,1669,1672,1670 ,0,0,0}, - {1921,1925,1919 ,1662,1666,1660 ,0,0,0}, {1930,1896,1931 ,1673,1637,1674 ,0,0,0}, - {1895,1931,1896 ,1636,1674,1637 ,0,0,0}, {1932,1933,1930 ,1675,1676,1673 ,0,0,0}, - {1930,1931,1932 ,1673,1674,1675 ,0,0,0}, {1933,1934,1935 ,1676,1677,1678 ,0,0,0}, - {1934,1933,1932 ,1677,1676,1675 ,0,0,0}, {1936,1935,1937 ,1679,1678,1680 ,0,0,0}, - {1934,1937,1935 ,1677,1680,1678 ,0,0,0}, {1938,1939,1936 ,1681,1682,1679 ,0,0,0}, - {1936,1937,1938 ,1679,1680,1681 ,0,0,0}, {1939,1940,1941 ,1682,1683,1684 ,0,0,0}, - {1940,1939,1938 ,1683,1682,1681 ,0,0,0}, {1942,1941,1943 ,1685,1684,1686 ,0,0,0}, - {1940,1943,1941 ,1683,1686,1684 ,0,0,0}, {1944,1945,1942 ,1687,1688,1685 ,0,0,0}, - {1942,1943,1944 ,1685,1686,1687 ,0,0,0}, {1945,1946,1947 ,1688,1689,1690 ,0,0,0}, - {1946,1945,1944 ,1689,1688,1687 ,0,0,0}, {1948,1947,1949 ,1691,1690,1692 ,0,0,0}, - {1946,1949,1947 ,1689,1692,1690 ,0,0,0}, {1950,1951,1948 ,1693,1694,1691 ,0,0,0}, - {1948,1949,1950 ,1691,1692,1693 ,0,0,0}, {1951,1952,1953 ,1694,1695,1696 ,0,0,0}, - {1952,1951,1950 ,1695,1694,1693 ,0,0,0}, {1954,1953,1955 ,1697,1696,1698 ,0,0,0}, - {1952,1955,1953 ,1695,1698,1696 ,0,0,0}, {1956,1957,1954 ,1699,1700,1697 ,0,0,0}, - {1954,1955,1956 ,1697,1698,1699 ,0,0,0}, {1957,1958,1959 ,1700,1701,1702 ,0,0,0}, - {1958,1957,1956 ,1701,1700,1699 ,0,0,0}, {1960,1959,1961 ,1703,1702,1704 ,0,0,0}, - {1958,1961,1959 ,1701,1704,1702 ,0,0,0}, {1962,1963,1960 ,1705,1706,1703 ,0,0,0}, - {1960,1961,1962 ,1703,1704,1705 ,0,0,0}, {1963,1964,1965 ,1706,1707,1708 ,0,0,0}, - {1964,1963,1962 ,1707,1706,1705 ,0,0,0}, {1966,1965,1967 ,1709,1708,1710 ,0,0,0}, - {1964,1967,1965 ,1707,1710,1708 ,0,0,0}, {1966,1967,1968 ,1709,1710,1709 ,0,0,0}, - {1969,1966,1968 ,1711,1711,1711 ,0,0,0}, {1966,1969,1970 ,1711,1711,1711 ,0,0,0}, - {1971,1972,1973 ,1712,1713,1714 ,0,0,0}, {1974,1975,1971 ,1715,1716,1712 ,0,0,0}, - {1971,1973,1974 ,1712,1714,1715 ,0,0,0}, {1975,1976,1977 ,1716,1717,1718 ,0,0,0}, - {1976,1975,1974 ,1717,1716,1715 ,0,0,0}, {1978,1977,1979 ,1719,1718,1720 ,0,0,0}, - {1976,1979,1977 ,1717,1720,1718 ,0,0,0}, {1980,1981,1978 ,1721,1722,1719 ,0,0,0}, - {1978,1979,1980 ,1719,1720,1721 ,0,0,0}, {1981,1982,1983 ,1722,1723,1724 ,0,0,0}, - {1982,1981,1980 ,1723,1722,1721 ,0,0,0}, {1984,1983,1985 ,1725,1724,1726 ,0,0,0}, - {1982,1985,1983 ,1723,1726,1724 ,0,0,0}, {1986,1987,1984 ,1727,1728,1725 ,0,0,0}, - {1984,1985,1986 ,1725,1726,1727 ,0,0,0}, {1987,1988,1989 ,1728,1729,1730 ,0,0,0}, - {1988,1987,1986 ,1729,1728,1727 ,0,0,0}, {1990,1989,1991 ,1731,1730,1732 ,0,0,0}, - {1988,1991,1989 ,1729,1732,1730 ,0,0,0}, {1992,1993,1990 ,1733,1734,1731 ,0,0,0}, - {1990,1991,1992 ,1731,1732,1733 ,0,0,0}, {1993,1994,1995 ,1734,1735,1736 ,0,0,0}, - {1994,1993,1992 ,1735,1734,1733 ,0,0,0}, {1996,1995,1997 ,1737,1736,1738 ,0,0,0}, - {1994,1997,1995 ,1735,1738,1736 ,0,0,0}, {1998,1999,1996 ,1739,1740,1737 ,0,0,0}, - {1996,1997,1998 ,1737,1738,1739 ,0,0,0}, {1999,2000,2001 ,1740,1741,1742 ,0,0,0}, - {2000,1999,1998 ,1741,1740,1739 ,0,0,0}, {2002,2001,2003 ,1743,1742,1744 ,0,0,0}, - {2000,2003,2001 ,1741,1744,1742 ,0,0,0}, {2004,2005,2002 ,1745,1746,1743 ,0,0,0}, - {2002,2003,2004 ,1743,1744,1745 ,0,0,0}, {2005,2006,2007 ,1746,1747,1748 ,0,0,0}, - {2006,2005,2004 ,1747,1746,1745 ,0,0,0}, {2008,2007,2009 ,1749,1748,1750 ,0,0,0}, - {2006,2009,2007 ,1747,1750,1748 ,0,0,0}, {1970,1969,2008 ,1751,1751,1749 ,0,0,0}, - {2008,2009,1970 ,1749,1750,1751 ,0,0,0}, {1973,1972,2010 ,1714,1713,1752 ,0,0,0}, - {2011,2010,2012 ,1753,1752,1754 ,0,0,0}, {1972,2012,2010 ,1713,1754,1752 ,0,0,0}, - {2013,2014,2011 ,1755,1756,1753 ,0,0,0}, {2011,2012,2013 ,1753,1754,1755 ,0,0,0}, - {2014,2015,2016 ,1756,1757,1758 ,0,0,0}, {2015,2014,2013 ,1757,1756,1755 ,0,0,0}, - {2017,2016,2018 ,1759,1758,1760 ,0,0,0}, {2015,2018,2016 ,1757,1760,1758 ,0,0,0}, - {2019,2020,2017 ,1761,1762,1759 ,0,0,0}, {2017,2018,2019 ,1759,1760,1761 ,0,0,0}, - {2020,2021,2022 ,1762,1763,1764 ,0,0,0}, {2021,2020,2019 ,1763,1762,1761 ,0,0,0}, - {2023,2022,2024 ,1765,1764,1766 ,0,0,0}, {2021,2024,2022 ,1763,1766,1764 ,0,0,0}, - {2025,2026,2023 ,1767,1768,1765 ,0,0,0}, {2023,2024,2025 ,1765,1766,1767 ,0,0,0}, - {2026,2027,2028 ,1768,1769,1770 ,0,0,0}, {2027,2026,2025 ,1769,1768,1767 ,0,0,0}, - {2029,2028,2030 ,1771,1770,1772 ,0,0,0}, {2027,2030,2028 ,1769,1772,1770 ,0,0,0}, - {2031,2032,2029 ,1773,1774,1771 ,0,0,0}, {2029,2030,2031 ,1771,1772,1773 ,0,0,0}, - {2032,2033,2034 ,1774,1775,1776 ,0,0,0}, {2033,2032,2031 ,1775,1774,1773 ,0,0,0}, - {2035,2034,2036 ,1777,1776,1778 ,0,0,0}, {2033,2036,2034 ,1775,1778,1776 ,0,0,0}, - {2037,2038,2035 ,1779,1780,1777 ,0,0,0}, {2035,2036,2037 ,1777,1778,1779 ,0,0,0}, - {2038,2039,2040 ,1780,1781,1782 ,0,0,0}, {2039,2038,2037 ,1781,1780,1779 ,0,0,0}, - {2041,2040,2042 ,1783,1782,1784 ,0,0,0}, {2039,2042,2040 ,1781,1784,1782 ,0,0,0}, - {2043,2044,2041 ,1785,1786,1783 ,0,0,0}, {2041,2042,2043 ,1783,1784,1785 ,0,0,0}, - {2044,2045,2046 ,1786,1787,1788 ,0,0,0}, {2045,2044,2043 ,1787,1786,1785 ,0,0,0}, - {2045,1695,2046 ,1787,1789,1788 ,0,0,0}, {2046,1695,1694 ,1788,1789,1789 ,0,0,0}, - {1396,1692,1397 ,1790,1791,1790 ,0,0,0}, {1692,1396,1690 ,1791,1790,1791 ,0,0,0}, - {1917,1419,1418 ,1792,1792,1792 ,0,0,0}, {1695,2045,1618 ,1792,726,726 ,0,0,0}, - {2039,1648,2042 ,726,726,726 ,0,0,0}, {1735,1693,1615 ,726,726,726 ,0,0,0}, - {1636,1640,2030 ,726,726,726 ,0,0,0}, {1644,2036,2033 ,726,726,726 ,0,0,0}, - {2015,1626,2018 ,726,726,726 ,0,0,0}, {2024,2021,1633 ,726,726,726 ,0,0,0}, - {2012,1620,1619 ,726,726,726 ,0,0,0}, {2013,2012,1619 ,726,726,726 ,0,0,0}, - {1412,1409,1908 ,1792,726,1792 ,0,0,0}, {1925,1924,1427 ,1792,726,1792 ,0,0,0}, - {1893,1897,1401 ,1792,1792,726 ,0,0,0}, {1403,1897,1900 ,726,1792,726 ,0,0,0}, - {1931,1357,1361 ,726,726,726 ,0,0,0}, {1357,1895,1358 ,726,1792,1792 ,0,0,0}, - {1934,1364,1937 ,1792,726,726 ,0,0,0}, {1363,1934,1932 ,1792,1792,1792 ,0,0,0}, - {1373,1944,1943 ,1793,1792,1792 ,0,0,0}, {1369,1940,1938 ,726,1792,1792 ,0,0,0}, - {1946,1944,1375 ,1792,1792,1792 ,0,0,0}, {1373,1375,1944 ,1793,1792,1792 ,0,0,0}, - {1950,1949,1379 ,1792,1793,726 ,0,0,0}, {1946,1375,1376 ,1792,1792,1792 ,0,0,0}, - {1952,1950,1381 ,1792,1792,1792 ,0,0,0}, {1379,1949,1376 ,726,1793,1792 ,0,0,0}, - {1382,1955,1952 ,1792,726,1792 ,0,0,0}, {1952,1381,1382 ,1792,1792,1792 ,0,0,0}, - {1955,1385,1956 ,726,726,726 ,0,0,0}, {1385,1955,1382 ,726,726,1792 ,0,0,0}, - {1958,1956,1387 ,726,726,726 ,0,0,0}, {1388,1958,1387 ,726,726,726 ,0,0,0}, - {1393,1962,1391 ,726,1792,1792 ,0,0,0}, {1961,1958,1388 ,726,726,726 ,0,0,0}, - {1394,1397,1964 ,726,726,726 ,0,0,0}, {1391,1962,1961 ,1792,1792,726 ,0,0,0}, - {1397,1967,1964 ,726,1792,726 ,0,0,0}, {1962,1394,1964 ,1792,726,726 ,0,0,0}, - {1987,1668,1984 ,726,726,726 ,0,0,0}, {1397,1968,1967 ,726,726,1792 ,0,0,0}, - {1918,1421,1912 ,1792,726,726 ,0,0,0}, {1932,1361,1363 ,1792,726,1792 ,0,0,0}, - {1940,1369,1370 ,1792,726,1792 ,0,0,0}, {1943,1370,1373 ,1792,1792,1793 ,0,0,0}, - {1367,1369,1938 ,1792,726,1792 ,0,0,0}, {1937,1364,1367 ,726,726,1792 ,0,0,0}, - {1895,1357,1931 ,1792,726,726 ,0,0,0}, {1931,1361,1932 ,726,726,1792 ,0,0,0}, - {1893,1400,1898 ,1792,1792,1792 ,0,0,0}, {1898,1358,1895 ,1792,1792,1792 ,0,0,0}, - {1561,1740,1559 ,726,726,1792 ,0,0,0}, {1400,1358,1898 ,1792,1792,1792 ,0,0,0}, - {1903,1407,1406 ,1792,1792,726 ,0,0,0}, {1900,1406,1403 ,726,726,726 ,0,0,0}, - {1904,1409,1407 ,726,726,1792 ,0,0,0}, {1903,1406,1900 ,1792,726,726 ,0,0,0}, - {1911,1415,1413 ,1792,1792,1792 ,0,0,0}, {1412,1908,1907 ,1792,1792,726 ,0,0,0}, - {1912,1419,1917 ,726,1792,1792 ,0,0,0}, {1415,1915,1418 ,1792,1792,1792 ,0,0,0}, - {1425,1424,1919 ,726,726,726 ,0,0,0}, {1421,1419,1912 ,726,1792,726 ,0,0,0}, - {1919,1424,1918 ,726,726,1792 ,0,0,0}, {1767,1764,1547 ,1792,726,726 ,0,0,0}, - {1927,1431,1430 ,1793,726,726 ,0,0,0}, {1344,1326,1346 ,1792,1793,726 ,0,0,0}, - {1433,1929,1435 ,1792,726,1792 ,0,0,0}, {1351,1353,1318 ,726,1792,726 ,0,0,0}, - {1315,1353,1354 ,726,1792,1792 ,0,0,0}, {1514,1511,1307 ,726,726,726 ,0,0,0}, - {1514,1298,1300 ,726,726,1792 ,0,0,0}, {1817,1489,1815 ,726,1792,1792 ,0,0,0}, - {1508,1503,1770 ,1792,726,726 ,0,0,0}, {1877,1874,2047 ,726,726,726 ,0,0,0}, - {1788,1472,1787 ,726,1792,1792 ,0,0,0}, {2048,2049,1838 ,1792,1792,726 ,0,0,0}, - {1293,2050,2051 ,1792,726,726 ,0,0,0}, {1844,1842,2052 ,726,1792,726 ,0,0,0}, - {2052,1842,2049 ,726,1792,1792 ,0,0,0}, {1266,1263,1335 ,726,726,1792 ,0,0,0}, - {2052,1335,1847 ,726,1792,1792 ,0,0,0}, {1333,1331,1264 ,1792,1792,1792 ,0,0,0}, - {1264,1331,1273 ,1792,1792,1792 ,0,0,0}, {1854,1853,1262 ,1792,726,726 ,0,0,0}, - {1841,1838,2049 ,1792,726,1792 ,0,0,0}, {1479,2048,1836 ,726,1792,726 ,0,0,0}, - {1454,2053,1450 ,726,1792,1792 ,0,0,0}, {2054,2055,2050 ,1792,1792,726 ,0,0,0}, - {1445,2056,2057 ,726,1792,1792 ,0,0,0}, {1833,1478,1479 ,1792,726,726 ,0,0,0}, - {1479,1836,1835 ,726,726,1792 ,0,0,0}, {1775,1478,1833 ,1792,726,1792 ,0,0,0}, - {1872,1871,2058 ,726,1792,1792 ,0,0,0}, {1477,1478,1779 ,1792,726,726 ,0,0,0}, - {1779,1781,1477 ,726,726,1792 ,0,0,0}, {1878,1877,2059 ,1792,726,1792 ,0,0,0}, - {1474,1477,1782 ,726,1792,726 ,0,0,0}, {1880,2060,1883 ,726,1792,1792 ,0,0,0}, - {1785,1474,1782 ,1792,726,726 ,0,0,0}, {1437,1884,1440 ,1792,726,1792 ,0,0,0}, - {1474,1787,1472 ,726,1792,1792 ,0,0,0}, {1797,1468,1467 ,1792,726,726 ,0,0,0}, - {1793,1467,1470 ,1792,726,1792 ,0,0,0}, {1484,1483,1805 ,1793,726,1792 ,0,0,0}, - {1468,1797,1799 ,726,1792,1792 ,0,0,0}, {1812,1486,1811 ,1792,1792,1792 ,0,0,0}, - {1486,1484,1809 ,1792,1793,1792 ,0,0,0}, {1495,1492,1823 ,1792,726,726 ,0,0,0}, - {1455,2061,1459 ,1792,726,1792 ,0,0,0}, {2062,2063,2064 ,1792,1792,1792 ,0,0,0}, - {1496,1827,1829 ,726,726,726 ,0,0,0}, {1498,1502,1774 ,1792,1792,1792 ,0,0,0}, - {2065,1516,2066 ,726,726,726 ,0,0,0}, {2067,1526,1516 ,1792,1792,726 ,0,0,0}, - {1519,1515,2068 ,726,726,726 ,0,0,0}, {1518,2069,2066 ,726,1792,726 ,0,0,0}, - {1356,1297,1296 ,726,726,1792 ,0,0,0}, {1340,1339,1320 ,1792,726,726 ,0,0,0}, - {2069,1518,1519 ,1792,726,726 ,0,0,0}, {1886,1437,1889 ,1792,1792,1792 ,0,0,0}, - {1343,1321,1324 ,726,1792,726 ,0,0,0}, {1544,1542,1767 ,1792,1792,1792 ,0,0,0}, - {1929,1889,1435 ,726,1792,1792 ,0,0,0}, {1582,1548,1764 ,1793,726,726 ,0,0,0}, - {1433,1431,1929 ,1792,726,726 ,0,0,0}, {2019,1629,1630 ,726,726,726 ,0,0,0}, - {1975,1656,1971 ,726,726,726 ,0,0,0}, {1658,1975,1977 ,726,726,726 ,0,0,0}, - {1737,1556,1738 ,1792,726,726 ,0,0,0}, {1412,1907,1413 ,1792,726,1792 ,0,0,0}, - {1929,1431,1927 ,726,726,1793 ,0,0,0}, {1924,1927,1430 ,726,1793,726 ,0,0,0}, - {1425,1925,1427 ,726,1792,1792 ,0,0,0}, {1427,1924,1430 ,1792,726,726 ,0,0,0}, - {1415,1911,1915 ,1792,1792,1792 ,0,0,0}, {1421,1918,1424 ,726,1792,726 ,0,0,0}, - {1425,1919,1925 ,726,726,1792 ,0,0,0}, {1917,1418,1915 ,1792,1792,1792 ,0,0,0}, - {1907,1911,1413 ,726,1792,1792 ,0,0,0}, {1908,1409,1904 ,1792,726,726 ,0,0,0}, - {1740,1561,1743 ,726,726,726 ,0,0,0}, {1903,1904,1407 ,1792,726,1792 ,0,0,0}, - {1971,1656,1624 ,726,726,726 ,0,0,0}, {1624,1972,1971 ,726,726,726 ,0,0,0}, - {1972,1624,1620 ,726,726,726 ,0,0,0}, {1626,2013,1619 ,726,726,726 ,0,0,0}, - {1620,2012,1972 ,726,726,726 ,0,0,0}, {1555,1556,1737 ,1792,726,1792 ,0,0,0}, - {2019,2018,1629 ,726,726,726 ,0,0,0}, {2018,1626,1629 ,726,726,726 ,0,0,0}, - {1710,1714,1591 ,726,1792,1792 ,0,0,0}, {2021,2019,1630 ,726,726,726 ,0,0,0}, - {1637,2024,1633 ,726,726,726 ,0,0,0}, {2025,1637,1639 ,726,726,726 ,0,0,0}, - {1637,2025,2024 ,726,726,726 ,0,0,0}, {1636,2027,1639 ,726,726,726 ,0,0,0}, - {2025,1639,2027 ,726,726,726 ,0,0,0}, {2027,1636,2030 ,726,726,726 ,0,0,0}, - {1640,1643,2031 ,726,726,726 ,0,0,0}, {1592,1591,1714 ,726,1792,1792 ,0,0,0}, - {2033,1643,1644 ,726,726,726 ,0,0,0}, {1643,2033,2031 ,726,726,726 ,0,0,0}, - {2037,2036,1646 ,726,726,726 ,0,0,0}, {1731,1609,1606 ,726,1792,1792 ,0,0,0}, - {1644,1646,2036 ,726,726,726 ,0,0,0}, {1650,2039,2037 ,726,726,726 ,0,0,0}, - {2037,1646,1650 ,726,726,726 ,0,0,0}, {2039,1650,1648 ,726,726,726 ,0,0,0}, - {1648,1653,2042 ,726,726,726 ,0,0,0}, {2042,1653,2043 ,726,726,726 ,0,0,0}, - {2043,1655,2045 ,726,726,726 ,0,0,0}, {1733,1612,1610 ,1792,726,1793 ,0,0,0}, - {1655,2043,1653 ,726,726,726 ,0,0,0}, {1534,1770,1768 ,726,726,1793 ,0,0,0}, - {1310,1311,1509 ,1793,726,726 ,0,0,0}, {1580,1582,1762 ,726,1793,726 ,0,0,0}, - {1768,1542,1541 ,1793,1792,1792 ,0,0,0}, {1579,1580,1761 ,1792,726,726 ,0,0,0}, - {1577,1579,1758 ,726,1792,726 ,0,0,0}, {1764,1548,1547 ,726,726,726 ,0,0,0}, - {1574,1577,1756 ,1792,726,1792 ,0,0,0}, {1764,1762,1582 ,726,726,1793 ,0,0,0}, - {1573,1574,1755 ,726,1792,1792 ,0,0,0}, {1762,1761,1580 ,726,726,726 ,0,0,0}, - {1571,1573,1752 ,1792,726,1792 ,0,0,0}, {1761,1758,1579 ,726,726,1792 ,0,0,0}, - {1568,1750,1749 ,1792,726,726 ,0,0,0}, {1758,1756,1577 ,726,1792,726 ,0,0,0}, - {1567,1749,1746 ,726,726,1792 ,0,0,0}, {1756,1755,1574 ,1792,1792,1792 ,0,0,0}, - {1565,1746,1744 ,1792,1792,726 ,0,0,0}, {1743,1562,1744 ,726,1792,726 ,0,0,0}, - {1568,1571,1750 ,1792,1792,726 ,0,0,0}, {1740,1738,1559 ,726,726,1792 ,0,0,0}, - {1568,1749,1567 ,1792,726,726 ,0,0,0}, {1977,1978,1661 ,726,726,726 ,0,0,0}, - {1746,1565,1567 ,1792,1792,726 ,0,0,0}, {1978,1981,1662 ,726,726,726 ,0,0,0}, - {1744,1562,1565 ,726,1792,1792 ,0,0,0}, {1981,1983,1664 ,726,726,726 ,0,0,0}, - {1400,1893,1401 ,1792,1792,726 ,0,0,0}, {1401,1897,1403 ,726,1792,726 ,0,0,0}, - {1738,1556,1559 ,726,726,1792 ,0,0,0}, {1667,1664,1983 ,726,726,726 ,0,0,0}, - {1658,1656,1975 ,726,726,726 ,0,0,0}, {1667,1984,1668 ,726,726,726 ,0,0,0}, - {1661,1658,1977 ,726,726,726 ,0,0,0}, {1987,1670,1668 ,726,726,726 ,0,0,0}, - {1662,1661,1978 ,726,726,726 ,0,0,0}, {1989,1673,1670 ,726,726,726 ,0,0,0}, - {1664,1662,1981 ,726,726,726 ,0,0,0}, {1364,1934,1363 ,726,1792,1792 ,0,0,0}, - {1674,1673,1990 ,726,726,726 ,0,0,0}, {1983,1984,1667 ,726,726,726 ,0,0,0}, - {1676,1674,1993 ,726,726,726 ,0,0,0}, {1676,1993,1995 ,726,726,726 ,0,0,0}, - {1367,1938,1937 ,1792,1792,726 ,0,0,0}, {1987,1989,1670 ,726,726,726 ,0,0,0}, - {1370,1943,1940 ,1792,1792,1792 ,0,0,0}, {1996,1679,1995 ,726,726,726 ,0,0,0}, - {1989,1990,1673 ,726,726,726 ,0,0,0}, {1680,1996,1999 ,726,726,726 ,0,0,0}, - {1990,1993,1674 ,726,726,726 ,0,0,0}, {1376,1949,1946 ,1792,1793,1792 ,0,0,0}, - {1995,1679,1676 ,726,726,726 ,0,0,0}, {1999,2001,1682 ,726,726,726 ,0,0,0}, - {1680,1679,1996 ,726,726,726 ,0,0,0}, {2002,1685,2001 ,726,726,726 ,0,0,0}, - {1379,1381,1950 ,726,1792,1792 ,0,0,0}, {2005,1686,2002 ,726,726,726 ,0,0,0}, - {1682,1680,1999 ,726,726,726 ,0,0,0}, {1385,1387,1956 ,726,726,726 ,0,0,0}, - {2001,1685,1682 ,726,726,726 ,0,0,0}, {1688,2005,2007 ,726,726,726 ,0,0,0}, - {1388,1391,1961 ,726,1792,726 ,0,0,0}, {2002,1686,1685 ,726,726,726 ,0,0,0}, - {1691,1688,2007 ,1792,726,726 ,0,0,0}, {1692,1691,2008 ,726,1792,726 ,0,0,0}, - {1393,1394,1962 ,726,726,1792 ,0,0,0}, {1691,2007,2008 ,1792,726,726 ,0,0,0}, - {1969,1968,1692 ,1792,726,726 ,0,0,0}, {1968,1397,1692 ,726,726,726 ,0,0,0}, - {2008,1969,1692 ,726,1792,726 ,0,0,0}, {2005,1688,1686 ,726,726,726 ,0,0,0}, - {1555,1737,1701 ,1792,1792,1792 ,0,0,0}, {1553,1701,1704 ,1792,1792,1792 ,0,0,0}, - {1549,1704,1699 ,1792,1792,1792 ,0,0,0}, {1583,1699,1703 ,726,1792,726 ,0,0,0}, - {1703,1706,1585 ,726,1792,1792 ,0,0,0}, {1626,2015,2013 ,726,726,726 ,0,0,0}, - {1701,1553,1555 ,1792,1792,1792 ,0,0,0}, {1706,1709,1586 ,1792,1792,726 ,0,0,0}, - {1704,1549,1553 ,1792,1792,1792 ,0,0,0}, {1630,1633,2021 ,726,726,726 ,0,0,0}, - {1549,1699,1583 ,1792,1792,726 ,0,0,0}, {1710,1588,1709 ,726,726,1792 ,0,0,0}, - {1703,1585,1583 ,726,1792,726 ,0,0,0}, {1592,1714,1713 ,726,1792,1792 ,0,0,0}, - {1706,1586,1585 ,1792,726,1792 ,0,0,0}, {1594,1592,1713 ,1792,726,1792 ,0,0,0}, - {1709,1588,1586 ,1792,726,726 ,0,0,0}, {1717,1597,1594 ,726,1792,1792 ,0,0,0}, - {1710,1591,1588 ,726,1792,726 ,0,0,0}, {1721,1598,1597 ,726,726,1792 ,0,0,0}, - {1723,1600,1598 ,1792,726,726 ,0,0,0}, {2030,1640,2031 ,726,726,726 ,0,0,0}, - {1594,1713,1717 ,1792,1792,726 ,0,0,0}, {1718,1603,1600 ,726,1792,726 ,0,0,0}, - {1597,1717,1721 ,1792,726,726 ,0,0,0}, {1603,1724,1604 ,1792,726,1792 ,0,0,0}, - {1598,1721,1723 ,726,726,1792 ,0,0,0}, {1606,1604,1725 ,1792,1792,726 ,0,0,0}, - {1603,1718,1724 ,1792,726,726 ,0,0,0}, {1609,1731,1730 ,1792,726,1792 ,0,0,0}, - {1604,1724,1725 ,1792,726,726 ,0,0,0}, {1733,1610,1730 ,1792,1793,1792 ,0,0,0}, - {1606,1725,1731 ,1792,726,726 ,0,0,0}, {1733,1615,1612 ,1792,726,726 ,0,0,0}, - {1610,1609,1730 ,1793,1792,1792 ,0,0,0}, {1615,1693,1618 ,726,726,726 ,0,0,0}, - {1695,1618,1693 ,1792,726,726 ,0,0,0}, {2045,1655,1618 ,726,726,726 ,0,0,0}, - {1733,1735,1615 ,1792,726,726 ,0,0,0}, {1600,1723,1718 ,726,1792,726 ,0,0,0}, - {1562,1743,1561 ,1792,726,726 ,0,0,0}, {1573,1755,1752 ,726,1792,1792 ,0,0,0}, - {1571,1752,1750 ,1792,1792,726 ,0,0,0}, {1490,1817,1818 ,1792,726,1792 ,0,0,0}, - {1544,1767,1547 ,1792,1792,726 ,0,0,0}, {1505,1496,1830 ,1792,726,726 ,0,0,0}, - {1768,1767,1542 ,1793,1792,1792 ,0,0,0}, {1532,1535,2070 ,726,1792,1792 ,0,0,0}, - {1534,1768,1541 ,726,1793,1792 ,0,0,0}, {2071,1524,1523 ,1792,1792,726 ,0,0,0}, - {1515,1346,1327 ,726,726,726 ,0,0,0}, {1526,2072,1523 ,1792,726,726 ,0,0,0}, - {1515,1327,2068 ,726,726,726 ,0,0,0}, {1773,1503,1499 ,726,726,1792 ,0,0,0}, - {1495,1823,1824 ,1792,726,726 ,0,0,0}, {2057,1455,1443 ,1792,1792,1792 ,0,0,0}, - {1812,1815,1489 ,1792,1792,1792 ,0,0,0}, {1484,1805,1806 ,1793,1792,1793 ,0,0,0}, - {1793,1794,1467 ,1792,1792,726 ,0,0,0}, {1847,1335,1848 ,1792,1792,1792 ,0,0,0}, - {1470,1788,1791 ,1792,726,1792 ,0,0,0}, {1800,1483,1468 ,726,726,726 ,0,0,0}, - {1483,1800,1803 ,726,726,1792 ,0,0,0}, {1486,1809,1811 ,1792,1792,1792 ,0,0,0}, - {1821,1490,1818 ,726,1792,1792 ,0,0,0}, {1821,1492,1490 ,726,726,1792 ,0,0,0}, - {1496,1495,1827 ,726,1792,726 ,0,0,0}, {1830,1832,1505 ,726,726,1792 ,0,0,0}, - {1505,1774,1502 ,1792,1792,1792 ,0,0,0}, {1499,1498,1773 ,1792,1792,726 ,0,0,0}, - {2071,2073,1524 ,1792,726,1792 ,0,0,0}, {2074,2075,1538 ,726,1792,726 ,0,0,0}, - {2075,2076,1538 ,1792,726,726 ,0,0,0}, {2077,2070,1535 ,726,1792,1792 ,0,0,0}, - {2070,2078,1532 ,1792,726,726 ,0,0,0}, {1503,1773,1770 ,726,726,726 ,0,0,0}, - {1774,1773,1498 ,1792,726,1792 ,0,0,0}, {1774,1505,1832 ,1792,1792,726 ,0,0,0}, - {1830,1496,1829 ,726,726,726 ,0,0,0}, {1827,1495,1824 ,726,1792,726 ,0,0,0}, - {1823,1492,1821 ,726,726,726 ,0,0,0}, {1490,1489,1817 ,1792,1792,726 ,0,0,0}, - {1489,1486,1812 ,1792,1792,1792 ,0,0,0}, {1484,1806,1809 ,1793,1793,1792 ,0,0,0}, - {1483,1803,1805 ,726,1792,1792 ,0,0,0}, {1468,1799,1800 ,726,1792,726 ,0,0,0}, - {1467,1794,1797 ,726,1792,1792 ,0,0,0}, {1470,1791,1793 ,1792,1792,1792 ,0,0,0}, - {1470,1472,1788 ,1792,1792,726 ,0,0,0}, {1474,1785,1787 ,726,1792,1792 ,0,0,0}, - {1477,1781,1782 ,1792,726,726 ,0,0,0}, {1478,1775,1779 ,726,1792,726 ,0,0,0}, - {1479,1835,1833 ,726,1792,1792 ,0,0,0}, {2048,1838,1836 ,1792,726,726 ,0,0,0}, - {2049,1842,1841 ,1792,1792,1792 ,0,0,0}, {2052,1847,1844 ,726,1792,726 ,0,0,0}, - {1266,1333,1264 ,726,1792,1792 ,0,0,0}, {1270,1273,1331 ,1792,1792,1792 ,0,0,0}, - {1850,1848,1263 ,1792,1792,726 ,0,0,0}, {1330,1272,1270 ,1792,726,1792 ,0,0,0}, - {1276,1337,1464 ,1792,726,1792 ,0,0,0}, {2079,2064,2080 ,726,1792,1792 ,0,0,0}, - {1449,2081,1447 ,726,1792,1792 ,0,0,0}, {2082,1449,1450 ,726,726,1792 ,0,0,0}, - {1444,2056,1445 ,1792,1792,726 ,0,0,0}, {1444,1447,2083 ,1792,1792,726 ,0,0,0}, - {2084,1454,2063 ,726,726,1792 ,0,0,0}, {2085,1460,1459 ,1792,1792,1792 ,0,0,0}, - {2079,2055,2054 ,726,1792,1792 ,0,0,0}, {1286,1859,1284 ,1792,1792,1792 ,0,0,0}, - {1281,1856,1854 ,1792,1792,1792 ,0,0,0}, {1290,1292,1865 ,1792,1792,726 ,0,0,0}, - {1287,1862,1860 ,726,726,726 ,0,0,0}, {1871,1293,2051 ,1792,1792,726 ,0,0,0}, - {2051,2058,1871 ,726,1792,1792 ,0,0,0}, {1868,1293,1871 ,726,1792,1792 ,0,0,0}, - {1868,1866,1292 ,726,726,1792 ,0,0,0}, {1874,1872,2058 ,726,726,1792 ,0,0,0}, - {2059,1877,2047 ,1792,726,726 ,0,0,0}, {2047,1874,2058 ,726,726,1792 ,0,0,0}, - {2059,1880,1878 ,1792,726,1792 ,0,0,0}, {2060,1440,1883 ,1792,1792,1792 ,0,0,0}, - {2059,2060,1880 ,1792,1792,726 ,0,0,0}, {1884,1883,1440 ,726,1792,1792 ,0,0,0}, - {1884,1437,1886 ,726,1792,1792 ,0,0,0}, {1889,1437,1435 ,1792,1792,1792 ,0,0,0}, - {1509,1306,1511 ,726,1792,726 ,0,0,0}, {2068,2069,1519 ,726,1792,726 ,0,0,0}, - {1300,1297,1356 ,1792,726,726 ,0,0,0}, {2066,1516,1518 ,726,726,726 ,0,0,0}, - {2067,1516,2065 ,1792,726,726 ,0,0,0}, {2072,1526,2067 ,726,1792,1792 ,0,0,0}, - {2071,1523,2072 ,1792,726,726 ,0,0,0}, {1528,1524,2073 ,1792,1792,726 ,0,0,0}, - {1528,2086,1538 ,1792,1792,726 ,0,0,0}, {2086,1528,2073 ,1792,1792,726 ,0,0,0}, - {2086,2074,1538 ,1792,726,726 ,0,0,0}, {1535,2076,2077 ,1792,726,726 ,0,0,0}, - {2076,1535,1538 ,726,1792,726 ,0,0,0}, {1534,1313,1770 ,726,726,726 ,0,0,0}, - {2078,1313,1534 ,726,726,726 ,0,0,0}, {2078,1534,1532 ,726,726,726 ,0,0,0}, - {1313,1310,1770 ,726,1793,726 ,0,0,0}, {1508,1310,1509 ,1792,1793,726 ,0,0,0}, - {1310,1508,1770 ,1793,1792,726 ,0,0,0}, {1311,1306,1509 ,726,1792,726 ,0,0,0}, - {1304,1307,1511 ,726,726,726 ,0,0,0}, {1306,1304,1511 ,1792,726,726 ,0,0,0}, - {1307,1298,1514 ,726,726,726 ,0,0,0}, {1300,1356,1514 ,1792,726,726 ,0,0,0}, - {1354,1356,1296 ,1792,726,1792 ,0,0,0}, {1318,1353,1315 ,726,1792,726 ,0,0,0}, - {1315,1354,1296 ,726,1792,1792 ,0,0,0}, {1320,1351,1318 ,726,726,726 ,0,0,0}, - {1320,1321,1340 ,726,1792,1792 ,0,0,0}, {1320,1339,1351 ,726,726,726 ,0,0,0}, - {1343,1324,1344 ,726,726,1792 ,0,0,0}, {1340,1321,1343 ,1792,1792,726 ,0,0,0}, - {1346,1326,1327 ,726,1793,726 ,0,0,0}, {1344,1324,1326 ,1792,726,1793 ,0,0,0}, - {1460,2087,1462 ,1792,726,1792 ,0,0,0}, {2051,2050,2055 ,726,726,1792 ,0,0,0}, - {1464,1462,1279 ,1792,1792,1792 ,0,0,0}, {2079,2080,2055 ,726,1792,1792 ,0,0,0}, - {2064,2063,2080 ,1792,1792,1792 ,0,0,0}, {2084,2063,2062 ,726,1792,1792 ,0,0,0}, - {2053,1454,2084 ,1792,726,726 ,0,0,0}, {2082,1450,2053 ,726,1792,1792 ,0,0,0}, - {2081,1449,2082 ,1792,726,726 ,0,0,0}, {2083,1447,2081 ,726,1792,1792 ,0,0,0}, - {2056,1444,2083 ,1792,1792,726 ,0,0,0}, {1443,1445,2057 ,1792,726,1792 ,0,0,0}, - {2061,1455,2057 ,726,1792,1792 ,0,0,0}, {2085,1459,2061 ,1792,1792,726 ,0,0,0}, - {2087,1460,2085 ,726,1792,1792 ,0,0,0}, {1279,1462,2087 ,1792,1792,726 ,0,0,0}, - {1276,1464,1279 ,1792,1792,1792 ,0,0,0}, {1277,1337,1276 ,1792,726,1792 ,0,0,0}, - {1330,1277,1272 ,1792,1792,726 ,0,0,0}, {1277,1330,1337 ,1792,1792,726 ,0,0,0}, - {1270,1331,1330 ,1792,1792,1792 ,0,0,0}, {1335,1333,1266 ,1792,1792,726 ,0,0,0}, - {1850,1263,1262 ,1792,726,726 ,0,0,0}, {1263,1848,1335 ,726,1792,1792 ,0,0,0}, - {1281,1854,1262 ,1792,1792,726 ,0,0,0}, {1853,1850,1262 ,726,1792,726 ,0,0,0}, - {1284,1856,1281 ,1792,1792,1792 ,0,0,0}, {1286,1860,1859 ,1792,726,1792 ,0,0,0}, - {1284,1859,1856 ,1792,1792,1792 ,0,0,0}, {1287,1290,1862 ,726,1792,726 ,0,0,0}, - {1286,1287,1860 ,1792,726,726 ,0,0,0}, {1865,1292,1866 ,726,1792,726 ,0,0,0}, - {1862,1290,1865 ,726,1792,726 ,0,0,0}, {1868,1292,1293 ,726,1792,1792 ,0,0,0}, - {1616,1734,1732 ,730,730,730 ,0,0,0}, {1398,1894,1359 ,730,730,730 ,0,0,0}, - {1469,1802,1801 ,730,730,730 ,0,0,0}, {1728,1611,1729 ,730,730,730 ,0,0,0}, - {1602,1605,1720 ,730,730,730 ,0,0,0}, {1607,1608,1727 ,730,730,730 ,0,0,0}, - {1593,1595,1712 ,730,730,730 ,0,0,0}, {1596,1599,1716 ,730,730,730 ,0,0,0}, - {1697,1700,1551 ,730,730,730 ,0,0,0}, {1587,1589,1707 ,730,730,730 ,0,0,0}, - {1896,1360,1359 ,730,730,730 ,0,0,0}, {1741,1558,1739 ,730,730,730 ,0,0,0}, - {1368,1936,1939 ,730,730,730 ,0,0,0}, {1942,1945,1374 ,730,730,730 ,0,0,0}, - {1930,1933,1362 ,730,730,730 ,0,0,0}, {1936,1368,1366 ,730,730,730 ,0,0,0}, - {1399,1892,1891 ,730,730,730 ,0,0,0}, {1360,1896,1930 ,730,730,730 ,0,0,0}, - {1404,1405,1901 ,730,730,730 ,0,0,0}, {1974,1657,1976 ,730,730,730 ,0,0,0}, - {1902,1408,1905 ,730,730,730 ,0,0,0}, {1405,1902,1901 ,730,730,730 ,0,0,0}, - {1417,1916,1416 ,730,730,730 ,0,0,0}, {1410,1906,1905 ,730,730,730 ,0,0,0}, - {1923,1922,1428 ,730,730,730 ,0,0,0}, {1921,1920,1423 ,730,730,730 ,0,0,0}, - {1429,1432,1926 ,730,730,730 ,0,0,0}, {2088,1840,1843 ,730,730,730 ,0,0,0}, - {1475,1473,1784 ,730,730,730 ,0,0,0}, {1278,1338,1336 ,730,730,730 ,0,0,0}, - {1288,1863,1864 ,730,730,730 ,0,0,0}, {1438,1888,1890 ,730,730,730 ,0,0,0}, - {1928,1436,1890 ,730,730,730 ,0,0,0}, {2089,2090,1882 ,730,730,730 ,0,0,0}, - {1291,1289,1867 ,730,730,730 ,0,0,0}, {2089,1882,1885 ,730,730,730 ,0,0,0}, - {1879,1881,2090 ,730,730,730 ,0,0,0}, {1441,2091,1442 ,730,730,730 ,0,0,0}, - {1890,1436,1438 ,730,730,730 ,0,0,0}, {1802,1469,1482 ,730,730,730 ,0,0,0}, - {2092,1481,1839 ,730,730,730 ,0,0,0}, {1780,1778,1476 ,730,730,730 ,0,0,0}, - {1288,1864,1289 ,730,730,730 ,0,0,0}, {1334,1849,1851 ,730,730,730 ,0,0,0}, - {1432,1434,1928 ,730,730,730 ,0,0,0}, {1332,1265,1329 ,730,730,730 ,0,0,0}, - {1268,1269,1329 ,730,730,730 ,0,0,0}, {2093,1457,1458 ,730,730,730 ,0,0,0}, - {2089,1885,1439 ,730,730,730 ,0,0,0}, {1438,1439,1887 ,730,730,730 ,0,0,0}, - {2094,1879,2090 ,730,730,730 ,0,0,0}, {1875,1876,2095 ,730,730,730 ,0,0,0}, - {2095,1876,2094 ,730,730,730 ,0,0,0}, {2094,1876,1879 ,730,730,730 ,0,0,0}, - {2090,1881,1882 ,730,730,730 ,0,0,0}, {2096,2097,2098 ,730,730,730 ,0,0,0}, - {1347,1348,1325 ,730,730,730 ,0,0,0}, {1885,1887,1439 ,730,730,730 ,0,0,0}, - {1869,1291,1867 ,730,730,730 ,0,0,0}, {1888,1438,1887 ,730,730,730 ,0,0,0}, - {2099,1453,1451 ,730,730,730 ,0,0,0}, {1458,1461,2100 ,730,730,730 ,0,0,0}, - {1463,1338,1275 ,730,730,730 ,0,0,0}, {1461,1463,1274 ,730,730,730 ,0,0,0}, - {1928,1434,1436 ,730,730,730 ,0,0,0}, {1442,2101,1446 ,730,730,730 ,0,0,0}, - {2102,1456,1457 ,730,730,730 ,0,0,0}, {1334,1851,1261 ,730,730,730 ,0,0,0}, - {1446,2103,1448 ,730,730,730 ,0,0,0}, {1285,1863,1288 ,730,730,730 ,0,0,0}, - {1863,1285,1861 ,730,730,730 ,0,0,0}, {1776,1480,1777 ,730,730,730 ,0,0,0}, - {1792,1466,1795 ,730,730,730 ,0,0,0}, {1789,1786,1471 ,730,730,730 ,0,0,0}, - {1810,1808,1485 ,730,730,730 ,0,0,0}, {1798,1465,1469 ,730,730,730 ,0,0,0}, - {1810,1485,1487 ,730,730,730 ,0,0,0}, {1428,1429,1923 ,730,730,730 ,0,0,0}, - {1432,1928,1926 ,730,730,730 ,0,0,0}, {1926,1923,1429 ,730,730,730 ,0,0,0}, - {1942,1372,1941 ,730,730,730 ,0,0,0}, {1921,1423,1426 ,730,730,730 ,0,0,0}, - {1922,1426,1428 ,730,730,730 ,0,0,0}, {1422,1423,1920 ,730,730,730 ,0,0,0}, - {1921,1426,1922 ,730,730,730 ,0,0,0}, {1422,1914,1420 ,730,730,730 ,0,0,0}, - {1913,1417,1420 ,730,730,730 ,0,0,0}, {1920,1914,1422 ,730,730,730 ,0,0,0}, - {1417,1913,1916 ,730,730,730 ,0,0,0}, {1420,1914,1913 ,730,730,730 ,0,0,0}, - {1751,1570,1569 ,730,730,730 ,0,0,0}, {1910,1414,1416 ,730,730,730 ,0,0,0}, - {1414,1909,1411 ,730,730,730 ,0,0,0}, {1909,1906,1411 ,730,730,730 ,0,0,0}, - {1906,1410,1411 ,730,730,730 ,0,0,0}, {1905,1408,1410 ,730,730,730 ,0,0,0}, - {1902,1405,1408 ,730,730,730 ,0,0,0}, {1402,1899,1892 ,730,730,730 ,0,0,0}, - {1404,1901,1899 ,730,730,730 ,0,0,0}, {1399,1891,1398 ,730,730,730 ,0,0,0}, - {1894,1896,1359 ,730,730,730 ,0,0,0}, {1362,1933,1365 ,730,730,730 ,0,0,0}, - {1366,1365,1935 ,730,730,730 ,0,0,0}, {1368,1939,1371 ,730,730,730 ,0,0,0}, - {1366,1935,1936 ,730,730,730 ,0,0,0}, {1371,1941,1372 ,730,730,730 ,0,0,0}, - {1371,1939,1941 ,730,730,730 ,0,0,0}, {1377,1945,1947 ,730,730,730 ,0,0,0}, - {1374,1372,1942 ,730,730,730 ,0,0,0}, {1378,1377,1947 ,730,730,730 ,0,0,0}, - {1378,1947,1948 ,730,730,730 ,0,0,0}, {1380,1948,1951 ,730,730,730 ,0,0,0}, - {1378,1948,1380 ,730,730,730 ,0,0,0}, {1951,1383,1380 ,730,730,730 ,0,0,0}, - {1951,1953,1383 ,730,730,730 ,0,0,0}, {1383,1953,1384 ,730,730,730 ,0,0,0}, - {1365,1933,1935 ,730,730,730 ,0,0,0}, {1386,1384,1954 ,730,730,730 ,0,0,0}, - {1384,1953,1954 ,730,730,730 ,0,0,0}, {1957,1389,1386 ,730,730,730 ,0,0,0}, - {1957,1386,1954 ,730,730,730 ,0,0,0}, {1389,1959,1390 ,730,730,730 ,0,0,0}, - {1390,1960,1392 ,730,730,730 ,0,0,0}, {1960,1390,1959 ,730,730,730 ,0,0,0}, - {1960,1963,1395 ,730,730,730 ,0,0,0}, {1687,2006,2004 ,730,730,730 ,0,0,0}, - {1396,1395,1963 ,730,730,730 ,0,0,0}, {1966,1970,1690 ,730,730,730 ,0,0,0}, - {1689,2009,2006 ,730,730,730 ,0,0,0}, {1362,1360,1930 ,730,730,730 ,0,0,0}, - {1623,2010,1621 ,730,730,730 ,0,0,0}, {2009,1689,1690 ,730,730,730 ,0,0,0}, - {1891,1894,1398 ,730,730,730 ,0,0,0}, {1745,1563,1742 ,730,730,730 ,0,0,0}, - {1566,1564,1747 ,730,730,730 ,0,0,0}, {1564,1563,1745 ,730,730,730 ,0,0,0}, - {1560,1558,1741 ,730,730,730 ,0,0,0}, {1741,1742,1560 ,730,730,730 ,0,0,0}, - {1739,1557,1736 ,730,730,730 ,0,0,0}, {1739,1558,1557 ,730,730,730 ,0,0,0}, - {1702,1736,1554 ,730,730,730 ,0,0,0}, {1557,1554,1736 ,730,730,730 ,0,0,0}, - {1552,1700,1702 ,730,730,730 ,0,0,0}, {1702,1554,1552 ,730,730,730 ,0,0,0}, - {1698,1550,1584 ,730,730,730 ,0,0,0}, {1551,1700,1552 ,730,730,730 ,0,0,0}, - {1584,1587,1705 ,730,730,730 ,0,0,0}, {1550,1698,1697 ,730,730,730 ,0,0,0}, - {1698,1584,1705 ,730,730,730 ,0,0,0}, {1711,1708,1590 ,730,730,730 ,0,0,0}, - {1632,2022,2023 ,730,730,730 ,0,0,0}, {1593,1711,1590 ,730,730,730 ,0,0,0}, - {1589,1590,1708 ,730,730,730 ,0,0,0}, {1715,1596,1716 ,730,730,730 ,0,0,0}, - {1712,1711,1593 ,730,730,730 ,0,0,0}, {1599,1722,1716 ,730,730,730 ,0,0,0}, - {1596,1715,1595 ,730,730,730 ,0,0,0}, {1602,1719,1601 ,730,730,730 ,0,0,0}, - {1601,1719,1722 ,730,730,730 ,0,0,0}, {1726,1720,1605 ,730,730,730 ,0,0,0}, - {1720,1719,1602 ,730,730,730 ,0,0,0}, {1608,1728,1727 ,730,730,730 ,0,0,0}, - {1607,1727,1726 ,730,730,730 ,0,0,0}, {1732,1613,1614 ,730,730,730 ,0,0,0}, - {1613,1729,1611 ,730,730,730 ,0,0,0}, {1732,1614,1616 ,730,730,730 ,0,0,0}, - {1963,1965,1396 ,730,730,730 ,0,0,0}, {1966,1396,1965 ,730,730,730 ,0,0,0}, - {1684,2003,1683 ,730,730,730 ,0,0,0}, {1395,1392,1960 ,730,730,730 ,0,0,0}, - {1689,2006,1687 ,730,730,730 ,0,0,0}, {1389,1957,1959 ,730,730,730 ,0,0,0}, - {1681,1683,2000 ,730,730,730 ,0,0,0}, {2004,2003,1684 ,730,730,730 ,0,0,0}, - {1678,1681,1998 ,730,730,730 ,0,0,0}, {2003,2000,1683 ,730,730,730 ,0,0,0}, - {1997,1677,1678 ,730,730,730 ,0,0,0}, {1994,1675,1677 ,730,730,730 ,0,0,0}, - {1998,1681,2000 ,730,730,730 ,0,0,0}, {1992,1672,1675 ,730,730,730 ,0,0,0}, - {1997,1678,1998 ,730,730,730 ,0,0,0}, {1374,1945,1377 ,730,730,730 ,0,0,0}, - {1997,1994,1677 ,730,730,730 ,0,0,0}, {1991,1988,1671 ,730,730,730 ,0,0,0}, - {1994,1992,1675 ,730,730,730 ,0,0,0}, {1988,1986,1669 ,730,730,730 ,0,0,0}, - {1986,1985,1666 ,730,730,730 ,0,0,0}, {1985,1982,1665 ,730,730,730 ,0,0,0}, - {1672,1991,1671 ,730,730,730 ,0,0,0}, {1982,1980,1663 ,730,730,730 ,0,0,0}, - {1671,1988,1669 ,730,730,730 ,0,0,0}, {1979,1660,1980 ,730,730,730 ,0,0,0}, - {1669,1986,1666 ,730,730,730 ,0,0,0}, {1659,1979,1976 ,730,730,730 ,0,0,0}, - {1666,1985,1665 ,730,730,730 ,0,0,0}, {1657,1974,1622 ,730,730,730 ,0,0,0}, - {1665,1982,1663 ,730,730,730 ,0,0,0}, {1623,1622,1973 ,730,730,730 ,0,0,0}, - {1980,1660,1663 ,730,730,730 ,0,0,0}, {1621,2011,1625 ,730,730,730 ,0,0,0}, - {1659,1660,1979 ,730,730,730 ,0,0,0}, {1748,1566,1747 ,730,730,730 ,0,0,0}, - {1404,1899,1402 ,730,730,730 ,0,0,0}, {1402,1892,1399 ,730,730,730 ,0,0,0}, - {1622,1974,1973 ,730,730,730 ,0,0,0}, {1748,1751,1569 ,730,730,730 ,0,0,0}, - {1623,1973,2010 ,730,730,730 ,0,0,0}, {1751,1753,1570 ,730,730,730 ,0,0,0}, - {1621,2010,2011 ,730,730,730 ,0,0,0}, {1753,1754,1572 ,730,730,730 ,0,0,0}, - {1754,1757,1575 ,730,730,730 ,0,0,0}, {1745,1747,1564 ,730,730,730 ,0,0,0}, - {1757,1759,1576 ,730,730,730 ,0,0,0}, {1569,1566,1748 ,730,730,730 ,0,0,0}, - {1759,1760,1578 ,730,730,730 ,0,0,0}, {1416,1916,1910 ,730,730,730 ,0,0,0}, - {1414,1910,1909 ,730,730,730 ,0,0,0}, {1753,1572,1570 ,730,730,730 ,0,0,0}, - {1545,1763,1765 ,730,730,730 ,0,0,0}, {1754,1575,1572 ,730,730,730 ,0,0,0}, - {1537,2104,2105 ,730,730,730 ,0,0,0}, {1757,1576,1575 ,730,730,730 ,0,0,0}, - {1342,1345,1322 ,730,730,730 ,0,0,0}, {1316,1350,1317 ,730,730,730 ,0,0,0}, - {1581,1763,1546 ,730,730,730 ,0,0,0}, {1500,1769,1771 ,730,730,730 ,0,0,0}, - {1506,1504,1772 ,730,730,730 ,0,0,0}, {1319,1341,1342 ,730,730,730 ,0,0,0}, - {1494,1828,1826 ,730,730,730 ,0,0,0}, {2106,1520,2107 ,730,730,730 ,0,0,0}, - {1769,1500,1507 ,730,730,730 ,0,0,0}, {1488,1819,1816 ,730,730,730 ,0,0,0}, - {1870,1294,1291 ,730,730,730 ,0,0,0}, {2108,1873,2095 ,730,730,730 ,0,0,0}, - {1875,2095,1873 ,730,730,730 ,0,0,0}, {1873,2108,1294 ,730,730,730 ,0,0,0}, - {2109,2110,2111 ,730,730,730 ,0,0,0}, {1873,1294,1870 ,730,730,730 ,0,0,0}, - {1869,1870,1291 ,730,730,730 ,0,0,0}, {1271,1336,1269 ,730,730,730 ,0,0,0}, - {2102,2091,1456 ,730,730,730 ,0,0,0}, {2112,2113,2114 ,730,730,730 ,0,0,0}, - {1776,1834,1480 ,730,730,730 ,0,0,0}, {1466,1790,1471 ,730,730,730 ,0,0,0}, - {1807,1482,1485 ,730,730,730 ,0,0,0}, {1820,1491,1493 ,730,730,730 ,0,0,0}, - {1820,1819,1491 ,730,730,730 ,0,0,0}, {1822,1493,1825 ,730,730,730 ,0,0,0}, - {1816,1814,1488 ,730,730,730 ,0,0,0}, {1814,1813,1487 ,730,730,730 ,0,0,0}, - {1482,1807,1804 ,730,730,730 ,0,0,0}, {1798,1796,1465 ,730,730,730 ,0,0,0}, - {1465,1795,1466 ,730,730,730 ,0,0,0}, {1790,1789,1471 ,730,730,730 ,0,0,0}, - {1784,1783,1475 ,730,730,730 ,0,0,0}, {1780,1476,1475 ,730,730,730 ,0,0,0}, - {1825,1494,1826 ,730,730,730 ,0,0,0}, {1778,1777,1476 ,730,730,730 ,0,0,0}, - {1834,1481,1480 ,730,730,730 ,0,0,0}, {1837,1839,1481 ,730,730,730 ,0,0,0}, - {1845,2115,2088 ,730,730,730 ,0,0,0}, {2115,1845,1846 ,730,730,730 ,0,0,0}, - {1334,2115,1849 ,730,730,730 ,0,0,0}, {1280,1852,1855 ,730,730,730 ,0,0,0}, - {1283,1282,1858 ,730,730,730 ,0,0,0}, {1280,1261,1852 ,730,730,730 ,0,0,0}, - {1846,1849,2115 ,730,730,730 ,0,0,0}, {1843,1845,2088 ,730,730,730 ,0,0,0}, - {1839,1840,2092 ,730,730,730 ,0,0,0}, {1840,2088,2092 ,730,730,730 ,0,0,0}, - {1834,1837,1481 ,730,730,730 ,0,0,0}, {1777,1480,1476 ,730,730,730 ,0,0,0}, - {1780,1475,1783 ,730,730,730 ,0,0,0}, {1473,1471,1786 ,730,730,730 ,0,0,0}, - {1473,1786,1784 ,730,730,730 ,0,0,0}, {1466,1792,1790 ,730,730,730 ,0,0,0}, - {1465,1796,1795 ,730,730,730 ,0,0,0}, {1469,1801,1798 ,730,730,730 ,0,0,0}, - {1482,1804,1802 ,730,730,730 ,0,0,0}, {1485,1808,1807 ,730,730,730 ,0,0,0}, - {1487,1813,1810 ,730,730,730 ,0,0,0}, {1487,1488,1814 ,730,730,730 ,0,0,0}, - {1488,1491,1819 ,730,730,730 ,0,0,0}, {1493,1822,1820 ,730,730,730 ,0,0,0}, - {1493,1494,1825 ,730,730,730 ,0,0,0}, {1494,1506,1828 ,730,730,730 ,0,0,0}, - {1506,1772,1831 ,730,730,730 ,0,0,0}, {1828,1506,1831 ,730,730,730 ,0,0,0}, - {1772,1504,1501 ,730,730,730 ,0,0,0}, {1501,1497,1771 ,730,730,730 ,0,0,0}, - {1771,1772,1501 ,730,730,730 ,0,0,0}, {1323,1322,1345 ,730,730,730 ,0,0,0}, - {1500,1771,1497 ,730,730,730 ,0,0,0}, {1302,1512,1513 ,730,730,730 ,0,0,0}, - {1323,1345,1347 ,730,730,730 ,0,0,0}, {1348,1521,1328 ,730,730,730 ,0,0,0}, - {1347,1325,1323 ,730,730,730 ,0,0,0}, {1348,1328,1325 ,730,730,730 ,0,0,0}, - {1529,2116,1522 ,730,730,730 ,0,0,0}, {1525,2117,1517 ,730,730,730 ,0,0,0}, - {2118,1530,2119 ,730,730,730 ,0,0,0}, {1537,2120,2119 ,730,730,730 ,0,0,0}, - {1352,1314,1355 ,730,730,730 ,0,0,0}, {2121,1536,2122 ,730,730,730 ,0,0,0}, - {1316,1314,1352 ,730,730,730 ,0,0,0}, {1765,1540,1543 ,730,730,730 ,0,0,0}, - {1766,1539,1540 ,730,730,730 ,0,0,0}, {1305,1512,1303 ,730,730,730 ,0,0,0}, - {1513,1299,1302 ,730,730,730 ,0,0,0}, {1305,1312,1510 ,730,730,730 ,0,0,0}, - {1533,1539,1766 ,730,730,730 ,0,0,0}, {1533,1766,1769 ,730,730,730 ,0,0,0}, - {1540,1765,1766 ,730,730,730 ,0,0,0}, {1545,1765,1543 ,730,730,730 ,0,0,0}, - {1546,1763,1545 ,730,730,730 ,0,0,0}, {1760,1763,1581 ,730,730,730 ,0,0,0}, - {1578,1760,1581 ,730,730,730 ,0,0,0}, {1576,1759,1578 ,730,730,730 ,0,0,0}, - {1625,2014,1627 ,730,730,730 ,0,0,0}, {2017,1627,2016 ,730,730,730 ,0,0,0}, - {1560,1742,1563 ,730,730,730 ,0,0,0}, {2020,1628,2017 ,730,730,730 ,0,0,0}, - {2020,1631,1628 ,730,730,730 ,0,0,0}, {2022,1632,1631 ,730,730,730 ,0,0,0}, - {2014,1625,2011 ,730,730,730 ,0,0,0}, {2023,1638,1632 ,730,730,730 ,0,0,0}, - {2016,1627,2014 ,730,730,730 ,0,0,0}, {1550,1697,1551 ,730,730,730 ,0,0,0}, - {1634,1638,2026 ,730,730,730 ,0,0,0}, {1628,1627,2017 ,730,730,730 ,0,0,0}, - {1635,1634,2028 ,730,730,730 ,0,0,0}, {2020,2022,1631 ,730,730,730 ,0,0,0}, - {1641,1635,2029 ,730,730,730 ,0,0,0}, {1589,1708,1707 ,730,730,730 ,0,0,0}, - {1587,1707,1705 ,730,730,730 ,0,0,0}, {1638,2023,2026 ,730,730,730 ,0,0,0}, - {1642,1641,2032 ,730,730,730 ,0,0,0}, {1642,2032,2034 ,730,730,730 ,0,0,0}, - {2026,2028,1634 ,730,730,730 ,0,0,0}, {1595,1715,1712 ,730,730,730 ,0,0,0}, - {1635,2028,2029 ,730,730,730 ,0,0,0}, {2034,2035,1645 ,730,730,730 ,0,0,0}, - {2038,1651,2035 ,730,730,730 ,0,0,0}, {2029,2032,1641 ,730,730,730 ,0,0,0}, - {1645,1642,2034 ,730,730,730 ,0,0,0}, {2040,1649,2038 ,730,730,730 ,0,0,0}, - {1599,1601,1722 ,730,730,730 ,0,0,0}, {2041,1647,2040 ,730,730,730 ,0,0,0}, - {1651,1645,2035 ,730,730,730 ,0,0,0}, {1605,1607,1726 ,730,730,730 ,0,0,0}, - {2038,1649,1651 ,730,730,730 ,0,0,0}, {2041,2044,1652 ,730,730,730 ,0,0,0}, - {1608,1611,1728 ,730,730,730 ,0,0,0}, {2040,1647,1649 ,730,730,730 ,0,0,0}, - {1654,1652,2044 ,730,730,730 ,0,0,0}, {1654,2046,1617 ,730,730,730 ,0,0,0}, - {1729,1613,1732 ,730,730,730 ,0,0,0}, {1654,2044,2046 ,730,730,730 ,0,0,0}, - {1696,1616,1617 ,730,730,730 ,0,0,0}, {1734,1616,1696 ,730,730,730 ,0,0,0}, - {2046,1694,1617 ,730,730,730 ,0,0,0}, {1696,1617,1694 ,730,730,730 ,0,0,0}, - {2041,1652,1647 ,730,730,730 ,0,0,0}, {1657,1659,1976 ,730,730,730 ,0,0,0}, - {1991,1672,1992 ,730,730,730 ,0,0,0}, {2004,1684,1687 ,730,730,730 ,0,0,0}, - {1966,1690,1396 ,730,730,730 ,0,0,0}, {1970,2009,1690 ,730,730,730 ,0,0,0}, - {1317,1349,1319 ,730,730,730 ,0,0,0}, {2123,1525,1527 ,730,730,730 ,0,0,0}, - {1529,2118,2116 ,730,730,730 ,0,0,0}, {1319,1342,1322 ,730,730,730 ,0,0,0}, - {1319,1349,1341 ,730,730,730 ,0,0,0}, {1317,1350,1349 ,730,730,730 ,0,0,0}, - {1316,1352,1350 ,730,730,730 ,0,0,0}, {1531,1533,2124 ,730,730,730 ,0,0,0}, - {1295,1301,1355 ,730,730,730 ,0,0,0}, {1295,1355,1314 ,730,730,730 ,0,0,0}, - {1513,1301,1299 ,730,730,730 ,0,0,0}, {1301,1513,1355 ,730,730,730 ,0,0,0}, - {1308,1533,1769 ,730,730,730 ,0,0,0}, {1305,1510,1512 ,730,730,730 ,0,0,0}, - {1302,1303,1512 ,730,730,730 ,0,0,0}, {1309,1510,1312 ,730,730,730 ,0,0,0}, - {1769,1309,1308 ,730,730,730 ,0,0,0}, {1507,1309,1769 ,730,730,730 ,0,0,0}, - {1309,1507,1510 ,730,730,730 ,0,0,0}, {1308,2124,1533 ,730,730,730 ,0,0,0}, - {1531,2122,1536 ,730,730,730 ,0,0,0}, {2124,2122,1531 ,730,730,730 ,0,0,0}, - {1536,2104,1537 ,730,730,730 ,0,0,0}, {2121,2104,1536 ,730,730,730 ,0,0,0}, - {2105,2120,1537 ,730,730,730 ,0,0,0}, {2119,1530,1537 ,730,730,730 ,0,0,0}, - {2118,1529,1530 ,730,730,730 ,0,0,0}, {2125,1522,2116 ,730,730,730 ,0,0,0}, - {1527,2125,2123 ,730,730,730 ,0,0,0}, {2125,1527,1522 ,730,730,730 ,0,0,0}, - {2123,2126,1525 ,730,730,730 ,0,0,0}, {2117,2107,1517 ,730,730,730 ,0,0,0}, - {2126,2117,1525 ,730,730,730 ,0,0,0}, {1520,2106,1521 ,730,730,730 ,0,0,0}, - {1517,2107,1520 ,730,730,730 ,0,0,0}, {1328,1521,2106 ,730,730,730 ,0,0,0}, - {1332,1334,1267 ,730,730,730 ,0,0,0}, {1864,1867,1289 ,730,730,730 ,0,0,0}, - {1451,1448,2127 ,730,730,730 ,0,0,0}, {1283,1858,1861 ,730,730,730 ,0,0,0}, - {1861,1285,1283 ,730,730,730 ,0,0,0}, {1857,1858,1282 ,730,730,730 ,0,0,0}, - {1857,1280,1855 ,730,730,730 ,0,0,0}, {1280,1857,1282 ,730,730,730 ,0,0,0}, - {1852,1261,1851 ,730,730,730 ,0,0,0}, {1261,1267,1334 ,730,730,730 ,0,0,0}, - {1267,1265,1332 ,730,730,730 ,0,0,0}, {1265,1268,1329 ,730,730,730 ,0,0,0}, - {1269,1336,1329 ,730,730,730 ,0,0,0}, {1278,1336,1271 ,730,730,730 ,0,0,0}, - {1275,1338,1278 ,730,730,730 ,0,0,0}, {1274,1463,1275 ,730,730,730 ,0,0,0}, - {2100,1461,1274 ,730,730,730 ,0,0,0}, {2093,1458,2100 ,730,730,730 ,0,0,0}, - {2102,1457,2093 ,730,730,730 ,0,0,0}, {1441,1456,2091 ,730,730,730 ,0,0,0}, - {2101,1442,2091 ,730,730,730 ,0,0,0}, {2103,1446,2101 ,730,730,730 ,0,0,0}, - {2127,1448,2103 ,730,730,730 ,0,0,0}, {2128,1453,2099 ,730,730,730 ,0,0,0}, - {2099,1451,2127 ,730,730,730 ,0,0,0}, {1452,2128,2114 ,730,730,730 ,0,0,0}, - {2128,1452,1453 ,730,730,730 ,0,0,0}, {2112,2097,2113 ,730,730,730 ,0,0,0}, - {1452,2114,2113 ,730,730,730 ,0,0,0}, {2096,2098,2109 ,730,730,730 ,0,0,0}, - {2113,2097,2096 ,730,730,730 ,0,0,0}, {2109,2111,2108 ,730,730,730 ,0,0,0}, - {2109,2098,2110 ,730,730,730 ,0,0,0}, {1294,2108,2111 ,730,730,730 ,0,0,0}, - {2108,2095,2058 ,1794,1795,1796 ,0,0,0}, {2109,2051,2055 ,1797,1798,1799 ,0,0,0}, - {2051,2108,2058 ,1798,1794,1796 ,0,0,0}, {2108,2051,2109 ,1794,1798,1797 ,0,0,0}, - {2113,2080,2063 ,1800,1801,1802 ,0,0,0}, {2109,2055,2096 ,1797,1799,1803 ,0,0,0}, - {2113,2096,2080 ,1800,1803,1801 ,0,0,0}, {2063,1454,1452 ,1802,1217,1217 ,0,0,0}, - {2063,1452,2113 ,1802,1217,1800 ,0,0,0}, {2080,2096,2055 ,1801,1803,1799 ,0,0,0}, - {2095,2047,2058 ,1795,1804,1796 ,0,0,0}, {2059,2047,2094 ,1805,1804,1806 ,0,0,0}, - {2095,2094,2047 ,1795,1806,1804 ,0,0,0}, {2090,2060,2059 ,1807,1808,1805 ,0,0,0}, - {2059,2094,2090 ,1805,1806,1807 ,0,0,0}, {2060,2089,1440 ,1808,1809,1206 ,0,0,0}, - {2089,2060,2090 ,1809,1808,1807 ,0,0,0}, {2089,1439,1440 ,1809,1206,1206 ,0,0,0}, - {1335,2052,2115 ,1112,1810,1810 ,0,0,0}, {2048,1481,2092 ,1811,1243,1812 ,0,0,0}, - {2092,2088,2049 ,1812,1813,1813 ,0,0,0}, {1479,1481,2048 ,1243,1243,1811 ,0,0,0}, - {2052,2088,2115 ,1810,1813,1810 ,0,0,0}, {2088,2052,2049 ,1813,1810,1813 ,0,0,0}, - {2048,2092,2049 ,1811,1812,1813 ,0,0,0}, {2115,1334,1335 ,1810,1112,1112 ,0,0,0}, - {1313,2078,2124 ,1814,1815,1816 ,0,0,0}, {2076,2104,2077 ,1817,1818,1819 ,0,0,0}, - {2121,2122,2070 ,1820,1821,1822 ,0,0,0}, {2119,2086,2118 ,1823,1824,82 ,0,0,0}, - {2075,2074,2120 ,1825,1826,1827 ,0,0,0}, {2072,2123,2125 ,1828,1829,1830 ,0,0,0}, - {2071,2116,2073 ,1831,1832,1833 ,0,0,0}, {2065,2117,2126 ,1834,1835,1836 ,0,0,0}, - {2126,2123,2067 ,1836,1829,1837 ,0,0,0}, {2117,2066,2107 ,1835,1838,1839 ,0,0,0}, - {2066,2117,2065 ,1838,1835,1834 ,0,0,0}, {2106,2107,2069 ,1840,1839,1841 ,0,0,0}, - {2066,2069,2107 ,1838,1841,1839 ,0,0,0}, {2068,1328,2106 ,1842,324,1840 ,0,0,0}, - {2106,2069,2068 ,1840,1841,1842 ,0,0,0}, {1327,1328,2068 ,1843,324,1842 ,0,0,0}, - {2071,2072,2125 ,1831,1828,1830 ,0,0,0}, {2123,2072,2067 ,1829,1828,1837 ,0,0,0}, - {2065,2126,2067 ,1834,1836,1837 ,0,0,0}, {2071,2125,2116 ,1831,1830,1832 ,0,0,0}, - {2073,2116,2118 ,1833,1832,82 ,0,0,0}, {2086,2119,2074 ,1824,1823,1826 ,0,0,0}, - {2086,2073,2118 ,1824,1833,82 ,0,0,0}, {2075,2120,2105 ,1825,1827,1844 ,0,0,0}, - {2120,2074,2119 ,1827,1826,1823 ,0,0,0}, {2105,2104,2076 ,1844,1818,1817 ,0,0,0}, - {2105,2076,2075 ,1844,1817,1825 ,0,0,0}, {2070,2077,2121 ,1822,1819,1820 ,0,0,0}, - {2104,2121,2077 ,1818,1820,1819 ,0,0,0}, {2122,2078,2070 ,1821,1815,1822 ,0,0,0}, - {1313,2124,1308 ,1814,1816,1845 ,0,0,0}, {2078,2122,2124 ,1815,1821,1816 ,0,0,0}, - {1279,2087,2100 ,1846,1847,1848 ,0,0,0}, {2057,2091,2061 ,1849,1850,1851 ,0,0,0}, - {2102,2093,2085 ,1820,1852,1822 ,0,0,0}, {2127,2081,2099 ,1853,1854,82 ,0,0,0}, - {2056,2083,2103 ,1855,1856,1857 ,0,0,0}, {2084,2112,2114 ,1858,1859,1860 ,0,0,0}, - {2053,2128,2082 ,1861,1862,82 ,0,0,0}, {2064,2098,2097 ,1863,1864,1865 ,0,0,0}, - {2097,2112,2062 ,1865,1859,1866 ,0,0,0}, {2098,2079,2110 ,1864,1867,1868 ,0,0,0}, - {2079,2098,2064 ,1867,1864,1863 ,0,0,0}, {2111,2110,2054 ,1869,1868,1870 ,0,0,0}, - {2079,2054,2110 ,1867,1870,1868 ,0,0,0}, {2050,1294,2111 ,1871,1872,1869 ,0,0,0}, - {2111,2054,2050 ,1869,1870,1871 ,0,0,0}, {1293,1294,2050 ,1873,1872,1871 ,0,0,0}, - {2053,2084,2114 ,1861,1858,1860 ,0,0,0}, {2112,2084,2062 ,1859,1858,1866 ,0,0,0}, - {2064,2097,2062 ,1863,1865,1866 ,0,0,0}, {2053,2114,2128 ,1861,1860,1862 ,0,0,0}, - {2082,2128,2099 ,82,1862,82 ,0,0,0}, {2081,2127,2083 ,1854,1853,1856 ,0,0,0}, - {2081,2082,2099 ,1854,82,82 ,0,0,0}, {2056,2103,2101 ,1855,1857,1874 ,0,0,0}, - {2103,2083,2127 ,1857,1856,1853 ,0,0,0}, {2101,2091,2057 ,1874,1850,1849 ,0,0,0}, - {2101,2057,2056 ,1874,1849,1855 ,0,0,0}, {2085,2061,2102 ,1822,1851,1820 ,0,0,0}, - {2091,2102,2061 ,1850,1820,1851 ,0,0,0}, {2093,2087,2085 ,1852,1847,1822 ,0,0,0}, - {1279,2100,1274 ,1846,1848,21 ,0,0,0}, {2087,2093,2100 ,1847,1852,1848 ,0,0,0} -// BladeProtector2.prt - , {2129,2130,2131 ,82,1824,1833 ,0,0,0}, {2132,2133,2134 ,1828,1830,1831 ,0,0,0}, - {2135,2129,2131 ,1832,82,1833 ,0,0,0}, {2134,2133,2135 ,1831,1830,1832 ,0,0,0}, - {2133,2132,2136 ,1830,1828,1829 ,0,0,0}, {2131,2134,2135 ,1833,1831,1832 ,0,0,0}, - {2137,2138,2139 ,1836,1834,1835 ,0,0,0}, {2138,2140,2139 ,1834,1838,1835 ,0,0,0}, - {2136,2141,2137 ,1829,1837,1836 ,0,0,0}, {2138,2137,2141 ,1834,1836,1837 ,0,0,0}, - {2142,2143,2144 ,324,1840,1842 ,0,0,0}, {2145,2146,2140 ,1841,1839,1838 ,0,0,0}, - {2143,2146,2145 ,1840,1839,1841 ,0,0,0}, {2143,2145,2144 ,1840,1841,1842 ,0,0,0}, - {2144,2147,2142 ,1842,1843,324 ,0,0,0}, {2139,2140,2146 ,1835,1838,1839 ,0,0,0}, - {2136,2132,2141 ,1829,1828,1837 ,0,0,0}, {2129,2148,2130 ,82,1823,1824 ,0,0,0}, - {2149,2148,2150 ,1826,1823,1827 ,0,0,0}, {2148,2149,2130 ,1823,1826,1824 ,0,0,0}, - {2151,2152,2150 ,1844,1825,1827 ,0,0,0}, {2149,2150,2152 ,1826,1827,1825 ,0,0,0}, - {2151,2153,2154 ,1844,1818,1817 ,0,0,0}, {2154,2152,2151 ,1817,1825,1844 ,0,0,0}, - {2155,2153,2156 ,1819,1818,1820 ,0,0,0}, {2153,2155,2154 ,1818,1819,1817 ,0,0,0}, - {2157,2158,2156 ,1821,1822,1820 ,0,0,0}, {2155,2156,2158 ,1819,1820,1822 ,0,0,0}, - {2157,2159,2160 ,1821,1816,1815 ,0,0,0}, {2160,2158,2157 ,1815,1822,1821 ,0,0,0}, - {2161,2159,2162 ,1814,1816,1845 ,0,0,0}, {2159,2161,2160 ,1816,1814,1815 ,0,0,0}, - {2163,2164,2165 ,82,1854,82 ,0,0,0}, {2166,2167,2168 ,1858,1860,1861 ,0,0,0}, - {2169,2163,2165 ,1862,82,82 ,0,0,0}, {2168,2167,2169 ,1861,1860,1862 ,0,0,0}, - {2167,2166,2170 ,1860,1858,1859 ,0,0,0}, {2165,2168,2169 ,82,1861,1862 ,0,0,0}, - {2171,2172,2173 ,1865,1863,1864 ,0,0,0}, {2172,2174,2173 ,1863,1867,1864 ,0,0,0}, - {2170,2175,2171 ,1859,1866,1865 ,0,0,0}, {2172,2171,2175 ,1863,1865,1866 ,0,0,0}, - {2176,2177,2178 ,1872,1869,1871 ,0,0,0}, {2179,2180,2174 ,1870,1868,1867 ,0,0,0}, - {2177,2180,2179 ,1869,1868,1870 ,0,0,0}, {2177,2179,2178 ,1869,1870,1871 ,0,0,0}, - {2178,2181,2176 ,1871,1873,1872 ,0,0,0}, {2173,2174,2180 ,1864,1867,1868 ,0,0,0}, - {2170,2166,2175 ,1859,1858,1866 ,0,0,0}, {2163,2182,2164 ,82,1853,1854 ,0,0,0}, - {2183,2182,2184 ,1856,1853,1857 ,0,0,0}, {2182,2183,2164 ,1853,1856,1854 ,0,0,0}, - {2185,2186,2184 ,1874,1855,1857 ,0,0,0}, {2183,2184,2186 ,1856,1857,1855 ,0,0,0}, - {2185,2187,2188 ,1874,1850,1849 ,0,0,0}, {2188,2186,2185 ,1849,1855,1874 ,0,0,0}, - {2189,2187,2190 ,1851,1850,1820 ,0,0,0}, {2187,2189,2188 ,1850,1851,1849 ,0,0,0}, - {2191,2192,2190 ,1852,1822,1820 ,0,0,0}, {2189,2190,2192 ,1851,1820,1822 ,0,0,0}, - {2191,2193,2194 ,1852,1848,1847 ,0,0,0}, {2194,2192,2191 ,1847,1822,1852 ,0,0,0}, - {2195,2193,2196 ,1846,1848,21 ,0,0,0}, {2193,2195,2194 ,1848,1846,1847 ,0,0,0}, - {2197,2198,2199 ,1875,1876,1875 ,0,0,0}, {2200,2201,2202 ,1877,1878,1879 ,0,0,0}, - {2200,2199,2201 ,1877,1875,1878 ,0,0,0}, {2202,2201,2203 ,1879,1878,1879 ,0,0,0}, - {2199,2200,2197 ,1875,1877,1875 ,0,0,0}, {2204,2198,2197 ,1876,1876,1875 ,0,0,0}, - {2205,2204,2206 ,1880,1876,1880 ,0,0,0}, {2204,2205,2198 ,1876,1880,1876 ,0,0,0}, - {2207,2208,2209 ,1207,1881,1207 ,0,0,0}, {2210,2208,2211 ,1881,1881,1882 ,0,0,0}, - {2208,2210,2209 ,1881,1881,1207 ,0,0,0}, {2212,2213,2211 ,1883,1882,1882 ,0,0,0}, - {2210,2211,2213 ,1881,1882,1882 ,0,0,0}, {2212,2214,2215 ,1883,1884,1883 ,0,0,0}, - {2215,2213,2212 ,1883,1882,1883 ,0,0,0}, {2214,2216,2215 ,1884,1885,1883 ,0,0,0}, - {2217,2207,2209 ,1886,1207,1207 ,0,0,0}, {2218,2219,2217 ,1887,1886,1886 ,0,0,0}, - {2207,2217,2219 ,1207,1886,1886 ,0,0,0}, {2218,2220,2221 ,1887,1888,1887 ,0,0,0}, - {2221,2219,2218 ,1887,1886,1887 ,0,0,0}, {2222,2220,2223 ,1888,1888,1889 ,0,0,0}, - {2220,2222,2221 ,1888,1888,1887 ,0,0,0}, {2222,2223,2224 ,1888,1889,1890 ,0,0,0}, - {2225,2226,2227 ,1891,1892,1893 ,0,0,0}, {2228,2229,2225 ,1894,1895,1891 ,0,0,0}, - {2225,2227,2228 ,1891,1893,1894 ,0,0,0}, {2229,2230,2231 ,1895,1896,1897 ,0,0,0}, - {2230,2229,2228 ,1896,1895,1894 ,0,0,0}, {2232,2231,2233 ,1898,1897,1899 ,0,0,0}, - {2230,2233,2231 ,1896,1899,1897 ,0,0,0}, {2234,2235,2232 ,1900,1901,1898 ,0,0,0}, - {2232,2233,2234 ,1898,1899,1900 ,0,0,0}, {2235,2236,2237 ,1901,1902,1903 ,0,0,0}, - {2236,2235,2234 ,1902,1901,1900 ,0,0,0}, {2238,2237,2239 ,1904,1903,1905 ,0,0,0}, - {2236,2239,2237 ,1902,1905,1903 ,0,0,0}, {2240,2241,2238 ,1906,1907,1904 ,0,0,0}, - {2238,2239,2240 ,1904,1905,1906 ,0,0,0}, {2241,2242,2243 ,1907,1908,1909 ,0,0,0}, - {2242,2241,2240 ,1908,1907,1906 ,0,0,0}, {2244,2243,2245 ,1910,1909,1911 ,0,0,0}, - {2242,2245,2243 ,1908,1911,1909 ,0,0,0}, {2246,2247,2244 ,1912,1913,1910 ,0,0,0}, - {2244,2245,2246 ,1910,1911,1912 ,0,0,0}, {2247,2248,2249 ,1913,1914,1915 ,0,0,0}, - {2248,2247,2246 ,1914,1913,1912 ,0,0,0}, {2250,2249,2251 ,1916,1915,1917 ,0,0,0}, - {2248,2251,2249 ,1914,1917,1915 ,0,0,0}, {2252,2253,2250 ,1918,1919,1916 ,0,0,0}, - {2250,2251,2252 ,1916,1917,1918 ,0,0,0}, {2253,2254,2255 ,1919,1920,1921 ,0,0,0}, - {2254,2253,2252 ,1920,1919,1918 ,0,0,0}, {2256,2255,2257 ,1922,1921,1923 ,0,0,0}, - {2254,2257,2255 ,1920,1923,1921 ,0,0,0}, {2258,2259,2256 ,1924,1925,1922 ,0,0,0}, - {2256,2257,2258 ,1922,1923,1924 ,0,0,0}, {2259,2260,2261 ,1925,1926,1927 ,0,0,0}, - {2260,2259,2258 ,1926,1925,1924 ,0,0,0}, {2262,2261,2263 ,1928,1927,1929 ,0,0,0}, - {2260,2263,2261 ,1926,1929,1927 ,0,0,0}, {2264,2265,2262 ,1930,1930,1928 ,0,0,0}, - {2262,2263,2264 ,1928,1929,1930 ,0,0,0}, {2227,2226,2266 ,1893,1892,1931 ,0,0,0}, - {2267,2266,2268 ,1932,1931,1933 ,0,0,0}, {2226,2268,2266 ,1892,1933,1931 ,0,0,0}, - {2269,2270,2267 ,1934,1935,1932 ,0,0,0}, {2267,2268,2269 ,1932,1933,1934 ,0,0,0}, - {2270,2271,2272 ,1935,1936,1937 ,0,0,0}, {2271,2270,2269 ,1936,1935,1934 ,0,0,0}, - {2273,2272,2274 ,1938,1937,1939 ,0,0,0}, {2271,2274,2272 ,1936,1939,1937 ,0,0,0}, - {2275,2276,2273 ,1940,1941,1938 ,0,0,0}, {2273,2274,2275 ,1938,1939,1940 ,0,0,0}, - {2276,2277,2278 ,1941,1942,1943 ,0,0,0}, {2277,2276,2275 ,1942,1941,1940 ,0,0,0}, - {2279,2278,2280 ,1944,1943,1945 ,0,0,0}, {2277,2280,2278 ,1942,1945,1943 ,0,0,0}, - {2281,2282,2279 ,1946,1947,1944 ,0,0,0}, {2279,2280,2281 ,1944,1945,1946 ,0,0,0}, - {2282,2283,2284 ,1947,1948,1949 ,0,0,0}, {2283,2282,2281 ,1948,1947,1946 ,0,0,0}, - {2285,2284,2286 ,1950,1949,1951 ,0,0,0}, {2283,2286,2284 ,1948,1951,1949 ,0,0,0}, - {2287,2288,2285 ,1952,1953,1950 ,0,0,0}, {2285,2286,2287 ,1950,1951,1952 ,0,0,0}, - {2288,2289,2290 ,1953,1954,1955 ,0,0,0}, {2289,2288,2287 ,1954,1953,1952 ,0,0,0}, - {2291,2290,2292 ,1956,1955,1957 ,0,0,0}, {2289,2292,2290 ,1954,1957,1955 ,0,0,0}, - {2293,2294,2291 ,1958,1959,1956 ,0,0,0}, {2291,2292,2293 ,1956,1957,1958 ,0,0,0}, - {2294,2295,2296 ,1959,1960,1961 ,0,0,0}, {2295,2294,2293 ,1960,1959,1958 ,0,0,0}, - {2297,2296,2298 ,1962,1961,1963 ,0,0,0}, {2295,2298,2296 ,1960,1963,1961 ,0,0,0}, - {2299,2300,2297 ,1964,1965,1962 ,0,0,0}, {2297,2298,2299 ,1962,1963,1964 ,0,0,0}, - {2300,2301,2302 ,1965,1966,1967 ,0,0,0}, {2301,2300,2299 ,1966,1965,1964 ,0,0,0}, - {2301,2303,2302 ,1966,1968,1967 ,0,0,0}, {2302,2303,2304 ,1967,1968,1969 ,0,0,0}, - {2305,2306,2303 ,1970,1970,1971 ,0,0,0}, {2305,2307,2306 ,1970,1972,1970 ,0,0,0}, - {2307,2305,2308 ,1972,1970,1972 ,0,0,0}, {2304,2303,2306 ,21,1971,1970 ,0,0,0}, - {2309,2310,2311 ,1114,1973,1114 ,0,0,0}, {2312,2313,2310 ,1974,1975,1973 ,0,0,0}, - {2310,2313,2311 ,1973,1975,1114 ,0,0,0}, {2314,2315,2312 ,1976,1977,1974 ,0,0,0}, - {2312,2310,2314 ,1974,1973,1976 ,0,0,0}, {2315,2316,2317 ,1977,1978,1979 ,0,0,0}, - {2316,2315,2314 ,1978,1977,1976 ,0,0,0}, {2318,2317,2319 ,1980,1979,1981 ,0,0,0}, - {2316,2319,2317 ,1978,1981,1979 ,0,0,0}, {2320,2318,2321 ,1982,1980,1983 ,0,0,0}, - {2318,2319,2321 ,1980,1981,1983 ,0,0,0}, {2322,2318,2320 ,1982,1980,1982 ,0,0,0}, - {2323,2309,2311 ,1984,1114,1114 ,0,0,0}, {2324,2323,2325 ,1985,1984,1986 ,0,0,0}, - {2324,2309,2323 ,1985,1114,1984 ,0,0,0}, {2326,2325,2327 ,1987,1986,1988 ,0,0,0}, - {2323,2327,2325 ,1984,1988,1986 ,0,0,0}, {2328,2329,2326 ,1989,1990,1987 ,0,0,0}, - {2326,2327,2328 ,1987,1988,1989 ,0,0,0}, {2329,2330,2331 ,1990,1991,1992 ,0,0,0}, - {2330,2329,2328 ,1991,1990,1989 ,0,0,0}, {2331,2332,2205 ,1992,1993,1880 ,0,0,0}, - {2330,2332,2331 ,1991,1993,1992 ,0,0,0}, {2331,2205,2206 ,1992,1880,1880 ,0,0,0}, - {2333,2334,2335 ,1994,1995,1996 ,0,0,0}, {2333,2336,2337 ,1994,1997,1998 ,0,0,0}, - {2335,2334,2338 ,1996,1995,1999 ,0,0,0}, {2338,2334,2339 ,1999,1995,2000 ,0,0,0}, - {2338,2339,2340 ,1999,2000,2001 ,0,0,0}, {2341,2340,2339 ,2002,2001,2000 ,0,0,0}, - {2340,2341,2342 ,2001,2002,2003 ,0,0,0}, {2343,2342,2341 ,2004,2003,2002 ,0,0,0}, - {2343,2344,2345 ,2004,2005,2006 ,0,0,0}, {2342,2343,2345 ,2003,2004,2006 ,0,0,0}, - {2335,2336,2333 ,1996,1997,1994 ,0,0,0}, {2345,2344,2346 ,2006,2005,2007 ,0,0,0}, - {2347,2346,2348 ,2008,2007,2009 ,0,0,0}, {2348,2346,2344 ,2009,2007,2005 ,0,0,0}, - {2347,2348,2349 ,2008,2009,2008 ,0,0,0}, {2350,2337,2351 ,2010,1998,2011 ,0,0,0}, - {2336,2351,2337 ,1997,2011,1998 ,0,0,0}, {2352,2353,2350 ,2012,2013,2010 ,0,0,0}, - {2350,2351,2352 ,2010,2011,2012 ,0,0,0}, {2353,2354,2355 ,2013,2014,2015 ,0,0,0}, - {2354,2353,2352 ,2014,2013,2012 ,0,0,0}, {2356,2355,2357 ,2016,2015,2017 ,0,0,0}, - {2354,2357,2355 ,2014,2017,2015 ,0,0,0}, {2358,2359,2356 ,2018,2019,2016 ,0,0,0}, - {2356,2357,2358 ,2016,2017,2018 ,0,0,0}, {2359,2360,2361 ,2019,2020,2021 ,0,0,0}, - {2360,2359,2358 ,2020,2019,2018 ,0,0,0}, {2362,2361,2363 ,2022,2021,2023 ,0,0,0}, - {2360,2363,2361 ,2020,2023,2021 ,0,0,0}, {2362,2363,2364 ,2022,2023,2022 ,0,0,0}, - {2365,2366,2367 ,2024,2025,2024 ,0,0,0}, {2367,2368,2365 ,2024,2026,2024 ,0,0,0}, - {2369,2370,2366 ,2025,2027,2025 ,0,0,0}, {2371,2368,2367 ,2026,2026,2024 ,0,0,0}, - {2365,2369,2366 ,2024,2025,2025 ,0,0,0}, {2369,2372,2370 ,2025,2027,2027 ,0,0,0}, - {2373,2372,2374 ,2028,2027,2028 ,0,0,0}, {2374,2362,2364 ,2028,2022,2022 ,0,0,0}, - {2373,2370,2372 ,2028,2027,2027 ,0,0,0}, {2374,2364,2373 ,2028,2022,2028 ,0,0,0}, - {2375,2371,2376 ,2029,2026,2029 ,0,0,0}, {2371,2375,2368 ,2026,2029,2026 ,0,0,0}, - {2377,2378,2376 ,2030,2030,2029 ,0,0,0}, {2375,2376,2378 ,2029,2029,2030 ,0,0,0}, - {2377,2379,2380 ,2030,2031,2031 ,0,0,0}, {2380,2378,2377 ,2031,2030,2030 ,0,0,0}, - {2381,2379,2382 ,2032,2031,2032 ,0,0,0}, {2379,2381,2380 ,2031,2032,2031 ,0,0,0}, - {2381,2382,2223 ,2032,2032,2033 ,0,0,0}, {2223,2382,2224 ,2033,2032,2034 ,0,0,0}, - {2383,2216,2214 ,2035,2036,2037 ,0,0,0}, {2384,2385,2386 ,2038,2039,2039 ,0,0,0}, - {2387,2388,2389 ,2040,2040,2035 ,0,0,0}, {2390,2391,2392 ,2041,2041,2042 ,0,0,0}, - {2393,2394,2395 ,2038,2043,2043 ,0,0,0}, {2396,2397,2392 ,2044,2042,2042 ,0,0,0}, - {2390,2392,2397 ,2041,2042,2042 ,0,0,0}, {2398,2397,2396 ,2045,2042,2044 ,0,0,0}, - {2394,2391,2395 ,2043,2041,2043 ,0,0,0}, {2395,2391,2390 ,2043,2041,2041 ,0,0,0}, - {2393,2385,2384 ,2038,2039,2038 ,0,0,0}, {2393,2384,2394 ,2038,2038,2043 ,0,0,0}, - {2386,2388,2387 ,2039,2040,2040 ,0,0,0}, {2385,2388,2386 ,2039,2040,2039 ,0,0,0}, - {2383,2389,2216 ,2035,2035,2036 ,0,0,0}, {2387,2389,2383 ,2040,2035,2035 ,0,0,0}, - {2399,2400,2401 ,2046,2046,2047 ,0,0,0}, {2401,2400,2402 ,2047,2046,2047 ,0,0,0}, - {2400,2399,2403 ,2046,2046,2048 ,0,0,0}, {2404,2403,2399 ,2049,2048,2046 ,0,0,0}, - {2405,2406,2404 ,2050,2050,2049 ,0,0,0}, {2407,2401,2402 ,2051,2047,2047 ,0,0,0}, - {2398,2396,2405 ,2052,2053,2050 ,0,0,0}, {2406,2405,2396 ,2050,2050,2053 ,0,0,0}, - {2404,2406,2403 ,2049,2050,2048 ,0,0,0}, {2408,2407,2409 ,2054,2051,2051 ,0,0,0}, - {2402,2409,2407 ,2047,2051,2051 ,0,0,0}, {2410,2411,2408 ,2054,2055,2054 ,0,0,0}, - {2408,2409,2410 ,2054,2051,2054 ,0,0,0}, {2411,2412,2413 ,2055,2055,2056 ,0,0,0}, - {2412,2411,2410 ,2055,2055,2054 ,0,0,0}, {2414,2413,2415 ,2057,2056,2056 ,0,0,0}, - {2412,2415,2413 ,2055,2056,2056 ,0,0,0}, {2414,2415,2416 ,2057,2056,2057 ,0,0,0}, - {2417,2418,2419 ,2058,2058,2059 ,0,0,0}, {2420,2421,2419 ,2060,2061,2059 ,0,0,0}, - {2417,2419,2421 ,2058,2059,2061 ,0,0,0}, {2420,2422,2423 ,2060,2062,2063 ,0,0,0}, - {2423,2421,2420 ,2063,2061,2060 ,0,0,0}, {2424,2422,2425 ,2064,2062,2065 ,0,0,0}, - {2422,2424,2423 ,2062,2064,2063 ,0,0,0}, {2426,2427,2425 ,2066,2067,2065 ,0,0,0}, - {2424,2425,2427 ,2064,2065,2067 ,0,0,0}, {2426,2428,2429 ,2066,2068,2069 ,0,0,0}, - {2429,2427,2426 ,2069,2067,2066 ,0,0,0}, {2430,2428,2431 ,2070,2068,2071 ,0,0,0}, - {2428,2430,2429 ,2068,2070,2069 ,0,0,0}, {2432,2433,2431 ,2072,2073,2071 ,0,0,0}, - {2430,2431,2433 ,2070,2071,2073 ,0,0,0}, {2432,2434,2435 ,2072,2074,2075 ,0,0,0}, - {2435,2433,2432 ,2075,2073,2072 ,0,0,0}, {2436,2434,2437 ,2076,2074,2077 ,0,0,0}, - {2434,2436,2435 ,2074,2076,2075 ,0,0,0}, {2438,2439,2437 ,2078,2079,2077 ,0,0,0}, - {2436,2437,2439 ,2076,2077,2079 ,0,0,0}, {2438,2440,2441 ,2078,2080,2081 ,0,0,0}, - {2441,2439,2438 ,2081,2079,2078 ,0,0,0}, {2442,2440,2443 ,2082,2080,2083 ,0,0,0}, - {2440,2442,2441 ,2080,2082,2081 ,0,0,0}, {2444,2445,2443 ,2084,2085,2083 ,0,0,0}, - {2442,2443,2445 ,2082,2083,2085 ,0,0,0}, {2444,2446,2447 ,2084,2086,2087 ,0,0,0}, - {2447,2445,2444 ,2087,2085,2084 ,0,0,0}, {2448,2446,2449 ,2088,2086,2089 ,0,0,0}, - {2446,2448,2447 ,2086,2088,2087 ,0,0,0}, {2414,2450,2449 ,2057,2090,2089 ,0,0,0}, - {2448,2449,2450 ,2088,2089,2090 ,0,0,0}, {2416,2450,2414 ,2057,2090,2057 ,0,0,0}, - {2451,2418,2417 ,2091,2058,2058 ,0,0,0}, {2452,2451,2453 ,2092,2091,2093 ,0,0,0}, - {2451,2452,2418 ,2091,2092,2058 ,0,0,0}, {2454,2455,2453 ,2094,2095,2093 ,0,0,0}, - {2452,2453,2455 ,2092,2093,2095 ,0,0,0}, {2454,2456,2457 ,2094,2096,2097 ,0,0,0}, - {2457,2455,2454 ,2097,2095,2094 ,0,0,0}, {2458,2456,2459 ,2098,2096,2099 ,0,0,0}, - {2456,2458,2457 ,2096,2098,2097 ,0,0,0}, {2460,2461,2459 ,2100,2101,2099 ,0,0,0}, - {2458,2459,2461 ,2098,2099,2101 ,0,0,0}, {2460,2462,2463 ,2100,2102,2103 ,0,0,0}, - {2463,2461,2460 ,2103,2101,2100 ,0,0,0}, {2464,2462,2465 ,2104,2102,2105 ,0,0,0}, - {2462,2464,2463 ,2102,2104,2103 ,0,0,0}, {2466,2467,2465 ,2106,2107,2105 ,0,0,0}, - {2464,2465,2467 ,2104,2105,2107 ,0,0,0}, {2466,2468,2469 ,2106,2108,2109 ,0,0,0}, - {2469,2467,2466 ,2109,2107,2106 ,0,0,0}, {2470,2468,2471 ,2110,2108,2111 ,0,0,0}, - {2468,2470,2469 ,2108,2110,2109 ,0,0,0}, {2472,2473,2471 ,2112,2113,2111 ,0,0,0}, - {2470,2471,2473 ,2110,2111,2113 ,0,0,0}, {2472,2474,2475 ,2112,2114,2115 ,0,0,0}, - {2475,2473,2472 ,2115,2113,2112 ,0,0,0}, {2476,2474,2477 ,2116,2114,2117 ,0,0,0}, - {2474,2476,2475 ,2114,2116,2115 ,0,0,0}, {2478,2479,2477 ,2118,2119,2117 ,0,0,0}, - {2476,2477,2479 ,2116,2117,2119 ,0,0,0}, {2478,2480,2481 ,2118,2120,2121 ,0,0,0}, - {2481,2479,2478 ,2121,2119,2118 ,0,0,0}, {2482,2480,2483 ,2122,2120,2123 ,0,0,0}, - {2480,2482,2481 ,2120,2122,2121 ,0,0,0}, {2482,2483,2484 ,2122,2123,2123 ,0,0,0}, - {2485,2483,2486 ,1435,2124,1435 ,0,0,0}, {2483,2485,2484 ,2124,1435,2124 ,0,0,0}, - {2487,2488,2489 ,2125,2126,2127 ,0,0,0}, {2490,2491,2492 ,2128,2129,2130 ,0,0,0}, - {2493,2487,2489 ,2131,2125,2127 ,0,0,0}, {2491,2489,2488 ,2129,2127,2126 ,0,0,0}, - {2494,2487,2493 ,2132,2125,2131 ,0,0,0}, {2495,2496,2497 ,2133,2134,2135 ,0,0,0}, - {2494,2493,2495 ,2132,2131,2133 ,0,0,0}, {2498,2496,2499 ,2136,2134,2137 ,0,0,0}, - {2495,2497,2494 ,2133,2135,2132 ,0,0,0}, {2496,2498,2497 ,2134,2136,2135 ,0,0,0}, - {2499,2500,2501 ,2137,2138,2139 ,0,0,0}, {2488,2492,2491 ,2126,2130,2129 ,0,0,0}, - {2502,2503,2504 ,2140,2141,2142 ,0,0,0}, {2505,2501,2500 ,2143,2139,2138 ,0,0,0}, - {2505,2506,2507 ,2143,2144,2145 ,0,0,0}, {2502,2504,2507 ,2140,2142,2145 ,0,0,0}, - {2502,2507,2506 ,2140,2145,2144 ,0,0,0}, {2504,2503,2508 ,2142,2141,2146 ,0,0,0}, - {2509,2510,2511 ,2147,2148,2149 ,0,0,0}, {2508,2509,2511 ,2146,2147,2149 ,0,0,0}, - {2509,2508,2503 ,2147,2146,2141 ,0,0,0}, {2510,2512,2511 ,2148,2150,2149 ,0,0,0}, - {2506,2505,2500 ,2144,2143,2138 ,0,0,0}, {2512,2513,2514 ,2150,2151,2152 ,0,0,0}, - {2512,2510,2513 ,2150,2148,2151 ,0,0,0}, {2515,2516,2517 ,2153,2154,2155 ,0,0,0}, - {2518,2517,2516 ,2156,2155,2154 ,0,0,0}, {2518,2519,2517 ,2156,2157,2155 ,0,0,0}, - {2519,2514,2513 ,2157,2152,2151 ,0,0,0}, {2519,2518,2514 ,2157,2156,2152 ,0,0,0}, - {2501,2498,2499 ,2139,2136,2137 ,0,0,0}, {2520,2521,2515 ,2158,2159,2153 ,0,0,0}, - {2522,2523,2520 ,2160,2161,2158 ,0,0,0}, {2486,2523,2522 ,2162,2161,2160 ,0,0,0}, - {2516,2515,2521 ,2154,2153,2159 ,0,0,0}, {2523,2521,2520 ,2161,2159,2158 ,0,0,0}, - {2485,2486,2522 ,2162,2162,2160 ,0,0,0}, {2524,2525,2490 ,2163,2164,2128 ,0,0,0}, - {2490,2492,2524 ,2128,2130,2163 ,0,0,0}, {2525,2526,2527 ,2164,2165,2166 ,0,0,0}, - {2526,2525,2524 ,2165,2164,2163 ,0,0,0}, {2528,2527,2529 ,2167,2166,2168 ,0,0,0}, - {2526,2529,2527 ,2165,2168,2166 ,0,0,0}, {2530,2531,2528 ,2169,2170,2167 ,0,0,0}, - {2528,2529,2530 ,2167,2168,2169 ,0,0,0}, {2531,2532,2533 ,2170,2171,2172 ,0,0,0}, - {2532,2531,2530 ,2171,2170,2169 ,0,0,0}, {2534,2533,2535 ,2173,2172,2174 ,0,0,0}, - {2532,2535,2533 ,2171,2174,2172 ,0,0,0}, {2536,2537,2534 ,2175,2176,2173 ,0,0,0}, - {2534,2535,2536 ,2173,2174,2175 ,0,0,0}, {2537,2538,2539 ,2176,2177,2178 ,0,0,0}, - {2538,2537,2536 ,2177,2176,2175 ,0,0,0}, {2540,2539,2541 ,2179,2178,2180 ,0,0,0}, - {2538,2541,2539 ,2177,2180,2178 ,0,0,0}, {2542,2543,2540 ,2181,2182,2179 ,0,0,0}, - {2540,2541,2542 ,2179,2180,2181 ,0,0,0}, {2543,2544,2545 ,2182,2183,2184 ,0,0,0}, - {2544,2543,2542 ,2183,2182,2181 ,0,0,0}, {2546,2545,2547 ,2185,2184,2186 ,0,0,0}, - {2544,2547,2545 ,2183,2186,2184 ,0,0,0}, {2548,2549,2546 ,2187,2188,2185 ,0,0,0}, - {2546,2547,2548 ,2185,2186,2187 ,0,0,0}, {2549,2550,2551 ,2188,2189,2190 ,0,0,0}, - {2550,2549,2548 ,2189,2188,2187 ,0,0,0}, {2552,2551,2553 ,2191,2190,2192 ,0,0,0}, - {2550,2553,2551 ,2189,2192,2190 ,0,0,0}, {2554,2555,2552 ,2193,2194,2191 ,0,0,0}, - {2552,2553,2554 ,2191,2192,2193 ,0,0,0}, {2555,2556,2557 ,2194,2195,2196 ,0,0,0}, - {2556,2555,2554 ,2195,2194,2193 ,0,0,0}, {2558,2557,2559 ,2197,2196,2198 ,0,0,0}, - {2556,2559,2557 ,2195,2198,2196 ,0,0,0}, {2558,2559,2560 ,2197,2198,2197 ,0,0,0}, - {2561,2562,2563 ,1359,1359,1359 ,0,0,0}, {2562,2561,2564 ,1359,1359,1359 ,0,0,0}, - {2565,2566,2567 ,2199,2200,2201 ,0,0,0}, {2568,2569,2570 ,2202,2203,2204 ,0,0,0}, - {2566,2571,2567 ,2200,2205,2201 ,0,0,0}, {2565,2567,2572 ,2199,2201,2206 ,0,0,0}, - {2568,2565,2572 ,2202,2199,2206 ,0,0,0}, {2573,2574,2571 ,2207,2208,2205 ,0,0,0}, - {2573,2571,2566 ,2207,2205,2200 ,0,0,0}, {2575,2576,2577 ,2209,2210,2211 ,0,0,0}, - {2574,2573,2575 ,2208,2207,2209 ,0,0,0}, {2575,2577,2574 ,2209,2211,2208 ,0,0,0}, - {2576,2578,2577 ,2210,2212,2211 ,0,0,0}, {2569,2568,2572 ,2203,2202,2206 ,0,0,0}, - {2576,2579,2578 ,2210,2213,2212 ,0,0,0}, {2580,2581,2582 ,2214,2215,2216 ,0,0,0}, - {2580,2582,2579 ,2214,2216,2213 ,0,0,0}, {2581,2580,2583 ,2215,2214,2217 ,0,0,0}, - {2584,2585,2583 ,2218,2219,2217 ,0,0,0}, {2585,2581,2583 ,2219,2215,2217 ,0,0,0}, - {2586,2587,2588 ,2220,2221,2222 ,0,0,0}, {2585,2584,2589 ,2219,2218,2223 ,0,0,0}, - {2590,2591,2589 ,2224,2225,2223 ,0,0,0}, {2587,2586,2591 ,2221,2220,2225 ,0,0,0}, - {2587,2591,2590 ,2221,2225,2224 ,0,0,0}, {2586,2588,2592 ,2220,2222,2226 ,0,0,0}, - {2584,2590,2589 ,2218,2224,2223 ,0,0,0}, {2593,2592,2594 ,2227,2226,2228 ,0,0,0}, - {2593,2594,2595 ,2227,2228,2229 ,0,0,0}, {2594,2592,2588 ,2228,2226,2222 ,0,0,0}, - {2596,2597,2598 ,2230,2231,2232 ,0,0,0}, {2582,2578,2579 ,2216,2212,2213 ,0,0,0}, - {2596,2599,2595 ,2230,2233,2229 ,0,0,0}, {2599,2596,2598 ,2233,2230,2232 ,0,0,0}, - {2597,2600,2601 ,2231,2234,2235 ,0,0,0}, {2601,2598,2597 ,2235,2232,2231 ,0,0,0}, - {2602,2603,2600 ,2236,2237,2234 ,0,0,0}, {2601,2600,2603 ,2235,2234,2237 ,0,0,0}, - {2602,2564,2561 ,2236,2238,2238 ,0,0,0}, {2602,2561,2603 ,2236,2238,2237 ,0,0,0}, - {2595,2599,2593 ,2229,2233,2227 ,0,0,0}, {2604,2570,2605 ,2239,2204,2240 ,0,0,0}, - {2569,2605,2570 ,2203,2240,2204 ,0,0,0}, {2606,2607,2604 ,2241,2242,2239 ,0,0,0}, - {2604,2605,2606 ,2239,2240,2241 ,0,0,0}, {2607,2608,2609 ,2242,2243,2244 ,0,0,0}, - {2608,2607,2606 ,2243,2242,2241 ,0,0,0}, {2610,2609,2611 ,2245,2244,2246 ,0,0,0}, - {2608,2611,2609 ,2243,2246,2244 ,0,0,0}, {2612,2613,2610 ,2247,2248,2245 ,0,0,0}, - {2610,2611,2612 ,2245,2246,2247 ,0,0,0}, {2613,2614,2615 ,2248,2249,2250 ,0,0,0}, - {2614,2613,2612 ,2249,2248,2247 ,0,0,0}, {2616,2615,2617 ,2251,2250,2252 ,0,0,0}, - {2614,2617,2615 ,2249,2252,2250 ,0,0,0}, {2618,2619,2616 ,2253,2254,2251 ,0,0,0}, - {2616,2617,2618 ,2251,2252,2253 ,0,0,0}, {2619,2620,2621 ,2254,2255,2256 ,0,0,0}, - {2620,2619,2618 ,2255,2254,2253 ,0,0,0}, {2622,2621,2623 ,2257,2256,2258 ,0,0,0}, - {2620,2623,2621 ,2255,2258,2256 ,0,0,0}, {2624,2625,2622 ,2259,2260,2257 ,0,0,0}, - {2622,2623,2624 ,2257,2258,2259 ,0,0,0}, {2625,2626,2627 ,2260,2261,2262 ,0,0,0}, - {2626,2625,2624 ,2261,2260,2259 ,0,0,0}, {2628,2627,2629 ,2263,2262,2264 ,0,0,0}, - {2626,2629,2627 ,2261,2264,2262 ,0,0,0}, {2630,2631,2628 ,2265,2266,2263 ,0,0,0}, - {2628,2629,2630 ,2263,2264,2265 ,0,0,0}, {2631,2632,2633 ,2266,2267,2268 ,0,0,0}, - {2632,2631,2630 ,2267,2266,2265 ,0,0,0}, {2634,2633,2635 ,2269,2268,2270 ,0,0,0}, - {2632,2635,2633 ,2267,2270,2268 ,0,0,0}, {2636,2637,2634 ,2271,2272,2269 ,0,0,0}, - {2634,2635,2636 ,2269,2270,2271 ,0,0,0}, {2637,2638,2639 ,2272,2273,2274 ,0,0,0}, - {2638,2637,2636 ,2273,2272,2271 ,0,0,0}, {2640,2639,2641 ,2275,2274,2276 ,0,0,0}, - {2638,2641,2639 ,2273,2276,2274 ,0,0,0}, {2640,2641,2642 ,2275,2276,2277 ,0,0,0}, - {2643,2644,2645 ,2278,2279,2280 ,0,0,0}, {2646,2647,2645 ,2281,2282,2280 ,0,0,0}, - {2643,2645,2647 ,2278,2280,2282 ,0,0,0}, {2646,2648,2649 ,2281,2283,2284 ,0,0,0}, - {2649,2647,2646 ,2284,2282,2281 ,0,0,0}, {2650,2648,2651 ,2285,2283,2286 ,0,0,0}, - {2648,2650,2649 ,2283,2285,2284 ,0,0,0}, {2652,2653,2651 ,2287,2288,2286 ,0,0,0}, - {2650,2651,2653 ,2285,2286,2288 ,0,0,0}, {2652,2654,2655 ,2287,2289,2290 ,0,0,0}, - {2655,2653,2652 ,2290,2288,2287 ,0,0,0}, {2656,2654,2657 ,2291,2289,2292 ,0,0,0}, - {2654,2656,2655 ,2289,2291,2290 ,0,0,0}, {2658,2659,2657 ,2293,2294,2292 ,0,0,0}, - {2656,2657,2659 ,2291,2292,2294 ,0,0,0}, {2658,2660,2661 ,2293,2295,2296 ,0,0,0}, - {2661,2659,2658 ,2296,2294,2293 ,0,0,0}, {2662,2660,2663 ,2297,2295,2298 ,0,0,0}, - {2660,2662,2661 ,2295,2297,2296 ,0,0,0}, {2664,2665,2663 ,2299,2300,2298 ,0,0,0}, - {2662,2663,2665 ,2297,2298,2300 ,0,0,0}, {2664,2666,2667 ,2299,2301,2302 ,0,0,0}, - {2667,2665,2664 ,2302,2300,2299 ,0,0,0}, {2668,2666,2669 ,2303,2301,2304 ,0,0,0}, - {2666,2668,2667 ,2301,2303,2302 ,0,0,0}, {2670,2671,2669 ,2305,2306,2304 ,0,0,0}, - {2668,2669,2671 ,2303,2304,2306 ,0,0,0}, {2670,2672,2673 ,2305,2307,2308 ,0,0,0}, - {2673,2671,2670 ,2308,2306,2305 ,0,0,0}, {2674,2672,2675 ,2309,2307,2310 ,0,0,0}, - {2672,2674,2673 ,2307,2309,2308 ,0,0,0}, {2676,2677,2675 ,2311,2312,2310 ,0,0,0}, - {2674,2675,2677 ,2309,2310,2312 ,0,0,0}, {2676,2678,2679 ,2311,2313,2314 ,0,0,0}, - {2679,2677,2676 ,2314,2312,2311 ,0,0,0}, {2680,2678,2681 ,2315,2313,2316 ,0,0,0}, - {2678,2680,2679 ,2313,2315,2314 ,0,0,0}, {2682,2683,2681 ,2317,2318,2316 ,0,0,0}, - {2680,2681,2683 ,2315,2316,2318 ,0,0,0}, {2682,2684,2685 ,2317,2319,2320 ,0,0,0}, - {2685,2683,2682 ,2320,2318,2317 ,0,0,0}, {2686,2684,2687 ,2321,2319,2322 ,0,0,0}, - {2684,2686,2685 ,2319,2321,2320 ,0,0,0}, {2688,2689,2687 ,2323,2324,2322 ,0,0,0}, - {2686,2687,2689 ,2321,2322,2324 ,0,0,0}, {2688,2690,2691 ,2323,2325,2326 ,0,0,0}, - {2691,2689,2688 ,2326,2324,2323 ,0,0,0}, {2692,2690,2693 ,2327,2325,2328 ,0,0,0}, - {2690,2692,2691 ,2325,2327,2326 ,0,0,0}, {2694,2695,2693 ,2329,2330,2328 ,0,0,0}, - {2692,2693,2695 ,2327,2328,2330 ,0,0,0}, {2694,2696,2697 ,2329,2331,2332 ,0,0,0}, - {2697,2695,2694 ,2332,2330,2329 ,0,0,0}, {2698,2696,2699 ,2333,2331,2334 ,0,0,0}, - {2696,2698,2697 ,2331,2333,2332 ,0,0,0}, {2640,2700,2699 ,2335,2336,2334 ,0,0,0}, - {2698,2699,2700 ,2333,2334,2336 ,0,0,0}, {2642,2700,2640 ,2337,2336,2335 ,0,0,0}, - {2701,2644,2643 ,2338,2279,2278 ,0,0,0}, {2702,2701,2703 ,2339,2338,2340 ,0,0,0}, - {2701,2702,2644 ,2338,2339,2279 ,0,0,0}, {2704,2705,2703 ,2341,2342,2340 ,0,0,0}, - {2702,2703,2705 ,2339,2340,2342 ,0,0,0}, {2704,2706,2707 ,2341,2343,2344 ,0,0,0}, - {2707,2705,2704 ,2344,2342,2341 ,0,0,0}, {2708,2706,2709 ,2345,2343,2346 ,0,0,0}, - {2706,2708,2707 ,2343,2345,2344 ,0,0,0}, {2710,2711,2709 ,2347,2348,2346 ,0,0,0}, - {2708,2709,2711 ,2345,2346,2348 ,0,0,0}, {2710,2712,2713 ,2347,2349,2350 ,0,0,0}, - {2713,2711,2710 ,2350,2348,2347 ,0,0,0}, {2714,2712,2715 ,2351,2349,2352 ,0,0,0}, - {2712,2714,2713 ,2349,2351,2350 ,0,0,0}, {2716,2717,2715 ,2353,2354,2352 ,0,0,0}, - {2714,2715,2717 ,2351,2352,2354 ,0,0,0}, {2716,2718,2719 ,2353,2355,2356 ,0,0,0}, - {2719,2717,2716 ,2356,2354,2353 ,0,0,0}, {2720,2718,2721 ,2357,2355,2358 ,0,0,0}, - {2718,2720,2719 ,2355,2357,2356 ,0,0,0}, {2722,2723,2721 ,2359,2360,2358 ,0,0,0}, - {2720,2721,2723 ,2357,2358,2360 ,0,0,0}, {2722,2724,2725 ,2359,2361,2362 ,0,0,0}, - {2725,2723,2722 ,2362,2360,2359 ,0,0,0}, {2726,2724,2727 ,2363,2361,2364 ,0,0,0}, - {2724,2726,2725 ,2361,2363,2362 ,0,0,0}, {2728,2729,2727 ,2365,2366,2364 ,0,0,0}, - {2726,2727,2729 ,2363,2364,2366 ,0,0,0}, {2728,2730,2731 ,2365,2367,2368 ,0,0,0}, - {2731,2729,2728 ,2368,2366,2365 ,0,0,0}, {2732,2730,2733 ,2369,2367,2370 ,0,0,0}, - {2730,2732,2731 ,2367,2369,2368 ,0,0,0}, {2734,2735,2733 ,2371,2372,2370 ,0,0,0}, - {2732,2733,2735 ,2369,2370,2372 ,0,0,0}, {2734,2736,2737 ,2371,2373,2374 ,0,0,0}, - {2737,2735,2734 ,2374,2372,2371 ,0,0,0}, {2738,2736,2739 ,2375,2373,2376 ,0,0,0}, - {2736,2738,2737 ,2373,2375,2374 ,0,0,0}, {2740,2741,2739 ,2377,2378,2376 ,0,0,0}, - {2738,2739,2741 ,2375,2376,2378 ,0,0,0}, {2740,2742,2743 ,2377,2379,2380 ,0,0,0}, - {2743,2741,2740 ,2380,2378,2377 ,0,0,0}, {2744,2742,2745 ,2381,2379,2382 ,0,0,0}, - {2742,2744,2743 ,2379,2381,2380 ,0,0,0}, {2746,2747,2745 ,2383,2384,2382 ,0,0,0}, - {2744,2745,2747 ,2381,2382,2384 ,0,0,0}, {2746,2748,2749 ,2383,2385,2386 ,0,0,0}, - {2749,2747,2746 ,2386,2384,2383 ,0,0,0}, {2750,2748,2751 ,2387,2385,2388 ,0,0,0}, - {2748,2750,2749 ,2385,2387,2386 ,0,0,0}, {2752,2753,2751 ,2389,2390,2388 ,0,0,0}, - {2750,2751,2753 ,2387,2388,2390 ,0,0,0}, {2752,2754,2755 ,2389,2391,2392 ,0,0,0}, - {2755,2753,2752 ,2392,2390,2389 ,0,0,0}, {2756,2754,2757 ,2393,2391,324 ,0,0,0}, - {2754,2756,2755 ,2391,2393,2392 ,0,0,0}, {2756,2757,2758 ,2393,324,2394 ,0,0,0}, - {2759,2760,2761 ,2395,2396,2397 ,0,0,0}, {2762,2763,2764 ,2398,2399,2400 ,0,0,0}, - {2760,2765,2761 ,2396,2401,2397 ,0,0,0}, {2759,2761,2766 ,2395,2397,2402 ,0,0,0}, - {2762,2759,2766 ,2398,2395,2402 ,0,0,0}, {2767,2768,2765 ,2403,2404,2401 ,0,0,0}, - {2767,2765,2760 ,2403,2401,2396 ,0,0,0}, {2769,2770,2771 ,2405,2406,2407 ,0,0,0}, - {2768,2767,2769 ,2404,2403,2405 ,0,0,0}, {2769,2771,2768 ,2405,2407,2404 ,0,0,0}, - {2770,2772,2771 ,2406,2408,2407 ,0,0,0}, {2763,2762,2766 ,2399,2398,2402 ,0,0,0}, - {2770,2773,2772 ,2406,2409,2408 ,0,0,0}, {2774,2775,2776 ,2410,2411,2412 ,0,0,0}, - {2774,2776,2773 ,2410,2412,2409 ,0,0,0}, {2775,2774,2777 ,2411,2410,2413 ,0,0,0}, - {2778,2779,2777 ,2414,2415,2413 ,0,0,0}, {2779,2775,2777 ,2415,2411,2413 ,0,0,0}, - {2780,2781,2782 ,2416,2417,2418 ,0,0,0}, {2779,2778,2783 ,2415,2414,2419 ,0,0,0}, - {2784,2785,2783 ,2420,2421,2419 ,0,0,0}, {2781,2780,2785 ,2417,2416,2421 ,0,0,0}, - {2781,2785,2784 ,2417,2421,2420 ,0,0,0}, {2780,2782,2786 ,2416,2418,2422 ,0,0,0}, - {2778,2784,2783 ,2414,2420,2419 ,0,0,0}, {2787,2786,2788 ,2423,2422,2424 ,0,0,0}, - {2787,2788,2789 ,2423,2424,2425 ,0,0,0}, {2788,2786,2782 ,2424,2422,2418 ,0,0,0}, - {2790,2791,2792 ,2426,2427,2428 ,0,0,0}, {2776,2772,2773 ,2412,2408,2409 ,0,0,0}, - {2790,2793,2789 ,2426,2429,2425 ,0,0,0}, {2793,2790,2792 ,2429,2426,2428 ,0,0,0}, - {2791,2794,2795 ,2427,2430,2431 ,0,0,0}, {2795,2792,2791 ,2431,2428,2427 ,0,0,0}, - {2796,2797,2794 ,2432,2433,2430 ,0,0,0}, {2795,2794,2797 ,2431,2430,2433 ,0,0,0}, - {2796,2758,2757 ,2432,2434,2435 ,0,0,0}, {2796,2757,2797 ,2432,2435,2433 ,0,0,0}, - {2789,2793,2787 ,2425,2429,2423 ,0,0,0}, {2798,2764,2799 ,2436,2400,2437 ,0,0,0}, - {2763,2799,2764 ,2399,2437,2400 ,0,0,0}, {2800,2801,2798 ,2438,2439,2436 ,0,0,0}, - {2798,2799,2800 ,2436,2437,2438 ,0,0,0}, {2801,2802,2803 ,2439,2440,2441 ,0,0,0}, - {2802,2801,2800 ,2440,2439,2438 ,0,0,0}, {2804,2803,2805 ,2442,2441,2443 ,0,0,0}, - {2802,2805,2803 ,2440,2443,2441 ,0,0,0}, {2806,2807,2804 ,2444,2445,2442 ,0,0,0}, - {2804,2805,2806 ,2442,2443,2444 ,0,0,0}, {2807,2808,2809 ,2445,2446,2447 ,0,0,0}, - {2808,2807,2806 ,2446,2445,2444 ,0,0,0}, {2810,2809,2811 ,2448,2447,2449 ,0,0,0}, - {2808,2811,2809 ,2446,2449,2447 ,0,0,0}, {2812,2813,2810 ,2450,2451,2448 ,0,0,0}, - {2810,2811,2812 ,2448,2449,2450 ,0,0,0}, {2813,2814,2815 ,2451,2452,2453 ,0,0,0}, - {2814,2813,2812 ,2452,2451,2450 ,0,0,0}, {2816,2815,2817 ,2454,2453,2455 ,0,0,0}, - {2814,2817,2815 ,2452,2455,2453 ,0,0,0}, {2818,2819,2816 ,2456,2457,2454 ,0,0,0}, - {2816,2817,2818 ,2454,2455,2456 ,0,0,0}, {2819,2820,2821 ,2457,2458,2459 ,0,0,0}, - {2820,2819,2818 ,2458,2457,2456 ,0,0,0}, {2822,2821,2823 ,2460,2459,2461 ,0,0,0}, - {2820,2823,2821 ,2458,2461,2459 ,0,0,0}, {2824,2825,2822 ,2462,2463,2460 ,0,0,0}, - {2822,2823,2824 ,2460,2461,2462 ,0,0,0}, {2825,2826,2827 ,2463,2464,2465 ,0,0,0}, - {2826,2825,2824 ,2464,2463,2462 ,0,0,0}, {2828,2827,2829 ,2466,2465,2467 ,0,0,0}, - {2826,2829,2827 ,2464,2467,2465 ,0,0,0}, {2830,2831,2828 ,2468,2469,2466 ,0,0,0}, - {2828,2829,2830 ,2466,2467,2468 ,0,0,0}, {2831,2832,2833 ,2469,2470,2471 ,0,0,0}, - {2832,2831,2830 ,2470,2469,2468 ,0,0,0}, {2834,2833,2835 ,2472,2471,2473 ,0,0,0}, - {2832,2835,2833 ,2470,2473,2471 ,0,0,0}, {2834,2835,2836 ,2472,2473,2472 ,0,0,0}, - {2837,2834,2836 ,1790,1790,1790 ,0,0,0}, {2834,2837,2838 ,1790,1790,1790 ,0,0,0}, - {2839,2840,2841 ,2474,2475,2476 ,0,0,0}, {2842,2843,2839 ,2477,2478,2474 ,0,0,0}, - {2839,2841,2842 ,2474,2476,2477 ,0,0,0}, {2843,2844,2845 ,2478,2479,2480 ,0,0,0}, - {2844,2843,2842 ,2479,2478,2477 ,0,0,0}, {2846,2845,2847 ,2481,2480,2482 ,0,0,0}, - {2844,2847,2845 ,2479,2482,2480 ,0,0,0}, {2848,2849,2846 ,2483,2484,2481 ,0,0,0}, - {2846,2847,2848 ,2481,2482,2483 ,0,0,0}, {2849,2850,2851 ,2484,2485,2486 ,0,0,0}, - {2850,2849,2848 ,2485,2484,2483 ,0,0,0}, {2852,2851,2853 ,2487,2486,2488 ,0,0,0}, - {2850,2853,2851 ,2485,2488,2486 ,0,0,0}, {2854,2855,2852 ,2489,2490,2487 ,0,0,0}, - {2852,2853,2854 ,2487,2488,2489 ,0,0,0}, {2855,2856,2857 ,2490,2491,2492 ,0,0,0}, - {2856,2855,2854 ,2491,2490,2489 ,0,0,0}, {2858,2857,2859 ,2493,2492,2494 ,0,0,0}, - {2856,2859,2857 ,2491,2494,2492 ,0,0,0}, {2860,2861,2858 ,2495,2496,2493 ,0,0,0}, - {2858,2859,2860 ,2493,2494,2495 ,0,0,0}, {2861,2862,2863 ,2496,2497,2498 ,0,0,0}, - {2862,2861,2860 ,2497,2496,2495 ,0,0,0}, {2864,2863,2865 ,2499,2498,2500 ,0,0,0}, - {2862,2865,2863 ,2497,2500,2498 ,0,0,0}, {2866,2867,2864 ,2501,2502,2499 ,0,0,0}, - {2864,2865,2866 ,2499,2500,2501 ,0,0,0}, {2867,2868,2869 ,2502,2503,2504 ,0,0,0}, - {2868,2867,2866 ,2503,2502,2501 ,0,0,0}, {2870,2869,2871 ,2505,2504,2506 ,0,0,0}, - {2868,2871,2869 ,2503,2506,2504 ,0,0,0}, {2872,2873,2870 ,2507,2508,2505 ,0,0,0}, - {2870,2871,2872 ,2505,2506,2507 ,0,0,0}, {2873,2874,2875 ,2508,2509,2510 ,0,0,0}, - {2874,2873,2872 ,2509,2508,2507 ,0,0,0}, {2876,2875,2877 ,2511,2510,2512 ,0,0,0}, - {2874,2877,2875 ,2509,2512,2510 ,0,0,0}, {2838,2837,2876 ,2513,2513,2511 ,0,0,0}, - {2876,2877,2838 ,2511,2512,2513 ,0,0,0}, {2841,2840,2878 ,2476,2475,2514 ,0,0,0}, - {2879,2878,2880 ,2515,2514,2516 ,0,0,0}, {2840,2880,2878 ,2475,2516,2514 ,0,0,0}, - {2881,2882,2879 ,2517,2518,2515 ,0,0,0}, {2879,2880,2881 ,2515,2516,2517 ,0,0,0}, - {2882,2883,2884 ,2518,2519,2520 ,0,0,0}, {2883,2882,2881 ,2519,2518,2517 ,0,0,0}, - {2885,2884,2886 ,2521,2520,2522 ,0,0,0}, {2883,2886,2884 ,2519,2522,2520 ,0,0,0}, - {2887,2888,2885 ,2523,2524,2521 ,0,0,0}, {2885,2886,2887 ,2521,2522,2523 ,0,0,0}, - {2888,2889,2890 ,2524,2525,2526 ,0,0,0}, {2889,2888,2887 ,2525,2524,2523 ,0,0,0}, - {2891,2890,2892 ,2527,2526,2528 ,0,0,0}, {2889,2892,2890 ,2525,2528,2526 ,0,0,0}, - {2893,2894,2891 ,2529,2530,2527 ,0,0,0}, {2891,2892,2893 ,2527,2528,2529 ,0,0,0}, - {2894,2895,2896 ,2530,2531,2532 ,0,0,0}, {2895,2894,2893 ,2531,2530,2529 ,0,0,0}, - {2897,2896,2898 ,2533,2532,2534 ,0,0,0}, {2895,2898,2896 ,2531,2534,2532 ,0,0,0}, - {2899,2900,2897 ,2535,2536,2533 ,0,0,0}, {2897,2898,2899 ,2533,2534,2535 ,0,0,0}, - {2900,2901,2902 ,2536,2537,2538 ,0,0,0}, {2901,2900,2899 ,2537,2536,2535 ,0,0,0}, - {2903,2902,2904 ,2539,2538,2540 ,0,0,0}, {2901,2904,2902 ,2537,2540,2538 ,0,0,0}, - {2905,2906,2903 ,2541,2542,2539 ,0,0,0}, {2903,2904,2905 ,2539,2540,2541 ,0,0,0}, - {2906,2907,2908 ,2542,2543,2544 ,0,0,0}, {2907,2906,2905 ,2543,2542,2541 ,0,0,0}, - {2909,2908,2910 ,2545,2544,2546 ,0,0,0}, {2907,2910,2908 ,2543,2546,2544 ,0,0,0}, - {2911,2912,2909 ,2547,2548,2545 ,0,0,0}, {2909,2910,2911 ,2545,2546,2547 ,0,0,0}, - {2912,2913,2914 ,2548,2549,2550 ,0,0,0}, {2913,2912,2911 ,2549,2548,2547 ,0,0,0}, - {2913,2563,2914 ,2549,2551,2550 ,0,0,0}, {2914,2563,2562 ,2550,2551,2551 ,0,0,0}, - {2264,2560,2265 ,1711,2552,1711 ,0,0,0}, {2560,2264,2558 ,2552,1711,2552 ,0,0,0}, - {2785,2287,2286 ,1793,1793,1793 ,0,0,0}, {2563,2913,2486 ,1793,726,726 ,0,0,0}, - {2907,2516,2910 ,726,726,726 ,0,0,0}, {2603,2561,2483 ,726,726,726 ,0,0,0}, - {2504,2508,2898 ,726,726,726 ,0,0,0}, {2512,2904,2901 ,726,726,726 ,0,0,0}, - {2883,2494,2886 ,726,726,726 ,0,0,0}, {2892,2889,2501 ,726,726,726 ,0,0,0}, - {2880,2488,2487 ,726,726,726 ,0,0,0}, {2881,2880,2487 ,726,726,726 ,0,0,0}, - {2280,2277,2776 ,1793,726,1793 ,0,0,0}, {2793,2792,2295 ,1793,726,1793 ,0,0,0}, - {2761,2765,2269 ,1793,1793,726 ,0,0,0}, {2271,2765,2768 ,726,1793,726 ,0,0,0}, - {2799,2225,2229 ,726,726,726 ,0,0,0}, {2225,2763,2226 ,726,1793,1793 ,0,0,0}, - {2802,2232,2805 ,1793,726,726 ,0,0,0}, {2231,2802,2800 ,1793,1793,1793 ,0,0,0}, - {2241,2812,2811 ,1792,1793,1793 ,0,0,0}, {2237,2808,2806 ,726,1793,1793 ,0,0,0}, - {2814,2812,2243 ,1793,1793,1793 ,0,0,0}, {2241,2243,2812 ,1792,1793,1793 ,0,0,0}, - {2818,2817,2247 ,1793,1792,726 ,0,0,0}, {2814,2243,2244 ,1793,1793,1793 ,0,0,0}, - {2820,2818,2249 ,1793,1793,1793 ,0,0,0}, {2247,2817,2244 ,726,1792,1793 ,0,0,0}, - {2250,2823,2820 ,1793,726,1793 ,0,0,0}, {2820,2249,2250 ,1793,1793,1793 ,0,0,0}, - {2823,2253,2824 ,726,726,726 ,0,0,0}, {2253,2823,2250 ,726,726,1793 ,0,0,0}, - {2826,2824,2255 ,726,726,726 ,0,0,0}, {2256,2826,2255 ,726,726,726 ,0,0,0}, - {2261,2830,2259 ,726,1793,1793 ,0,0,0}, {2829,2826,2256 ,726,726,726 ,0,0,0}, - {2262,2265,2832 ,726,726,726 ,0,0,0}, {2259,2830,2829 ,1793,1793,726 ,0,0,0}, - {2265,2835,2832 ,726,1793,726 ,0,0,0}, {2830,2262,2832 ,1793,726,726 ,0,0,0}, - {2855,2536,2852 ,726,726,726 ,0,0,0}, {2265,2836,2835 ,726,726,1793 ,0,0,0}, - {2786,2289,2780 ,1793,726,726 ,0,0,0}, {2800,2229,2231 ,1793,726,1793 ,0,0,0}, - {2808,2237,2238 ,1793,726,1793 ,0,0,0}, {2811,2238,2241 ,1793,1793,1792 ,0,0,0}, - {2235,2237,2806 ,1793,726,1793 ,0,0,0}, {2805,2232,2235 ,726,726,1793 ,0,0,0}, - {2763,2225,2799 ,1793,726,726 ,0,0,0}, {2799,2229,2800 ,726,726,1793 ,0,0,0}, - {2761,2268,2766 ,1793,1793,1793 ,0,0,0}, {2766,2226,2763 ,1793,1793,1793 ,0,0,0}, - {2429,2608,2427 ,726,726,1793 ,0,0,0}, {2268,2226,2766 ,1793,1793,1793 ,0,0,0}, - {2771,2275,2274 ,1793,1793,726 ,0,0,0}, {2768,2274,2271 ,726,726,726 ,0,0,0}, - {2772,2277,2275 ,726,726,1793 ,0,0,0}, {2771,2274,2768 ,1793,726,726 ,0,0,0}, - {2779,2283,2281 ,1793,1793,1793 ,0,0,0}, {2280,2776,2775 ,1793,1793,726 ,0,0,0}, - {2780,2287,2785 ,726,1793,1793 ,0,0,0}, {2283,2783,2286 ,1793,1793,1793 ,0,0,0}, - {2293,2292,2787 ,726,726,726 ,0,0,0}, {2289,2287,2780 ,726,1793,726 ,0,0,0}, - {2787,2292,2786 ,726,726,1793 ,0,0,0}, {2635,2632,2415 ,1793,726,726 ,0,0,0}, - {2795,2299,2298 ,1792,726,726 ,0,0,0}, {2212,2194,2214 ,1793,1792,726 ,0,0,0}, - {2301,2797,2303 ,1793,726,1793 ,0,0,0}, {2219,2221,2186 ,726,1793,726 ,0,0,0}, - {2183,2221,2222 ,726,1793,1793 ,0,0,0}, {2382,2379,2175 ,726,726,726 ,0,0,0}, - {2382,2166,2168 ,726,726,1793 ,0,0,0}, {2685,2357,2683 ,726,1793,1793 ,0,0,0}, - {2376,2371,2638 ,1793,726,726 ,0,0,0}, {2745,2742,2915 ,726,726,726 ,0,0,0}, - {2656,2340,2655 ,726,1793,1793 ,0,0,0}, {2916,2917,2706 ,1793,1793,726 ,0,0,0}, - {2161,2918,2919 ,1793,726,726 ,0,0,0}, {2712,2710,2920 ,726,1793,726 ,0,0,0}, - {2920,2710,2917 ,726,1793,1793 ,0,0,0}, {2134,2131,2203 ,726,726,1793 ,0,0,0}, - {2920,2203,2715 ,726,1793,1793 ,0,0,0}, {2201,2199,2132 ,1793,1793,1793 ,0,0,0}, - {2132,2199,2141 ,1793,1793,1793 ,0,0,0}, {2722,2721,2130 ,1793,726,726 ,0,0,0}, - {2709,2706,2917 ,1793,726,1793 ,0,0,0}, {2347,2916,2704 ,726,1793,726 ,0,0,0}, - {2322,2921,2318 ,726,1793,1793 ,0,0,0}, {2922,2923,2918 ,1793,1793,726 ,0,0,0}, - {2313,2924,2925 ,726,1793,1793 ,0,0,0}, {2701,2346,2347 ,1793,726,726 ,0,0,0}, - {2347,2704,2703 ,726,726,1793 ,0,0,0}, {2643,2346,2701 ,1793,726,1793 ,0,0,0}, - {2740,2739,2926 ,726,1793,1793 ,0,0,0}, {2345,2346,2647 ,1793,726,726 ,0,0,0}, - {2647,2649,2345 ,726,726,1793 ,0,0,0}, {2746,2745,2927 ,1793,726,1793 ,0,0,0}, - {2342,2345,2650 ,726,1793,726 ,0,0,0}, {2748,2928,2751 ,726,1793,1793 ,0,0,0}, - {2653,2342,2650 ,1793,726,726 ,0,0,0}, {2305,2752,2308 ,1793,726,1793 ,0,0,0}, - {2342,2655,2340 ,726,1793,1793 ,0,0,0}, {2665,2336,2335 ,1793,726,726 ,0,0,0}, - {2661,2335,2338 ,1793,726,1793 ,0,0,0}, {2352,2351,2673 ,1792,726,1793 ,0,0,0}, - {2336,2665,2667 ,726,1793,1793 ,0,0,0}, {2680,2354,2679 ,1793,1793,1793 ,0,0,0}, - {2354,2352,2677 ,1793,1792,1793 ,0,0,0}, {2363,2360,2691 ,1793,726,726 ,0,0,0}, - {2323,2929,2327 ,1793,726,1793 ,0,0,0}, {2930,2931,2932 ,1793,1793,1793 ,0,0,0}, - {2364,2695,2697 ,726,726,726 ,0,0,0}, {2366,2370,2642 ,1793,1793,1793 ,0,0,0}, - {2933,2384,2934 ,726,726,726 ,0,0,0}, {2935,2394,2384 ,1793,1793,726 ,0,0,0}, - {2387,2383,2936 ,726,726,726 ,0,0,0}, {2386,2937,2934 ,726,1793,726 ,0,0,0}, - {2224,2165,2164 ,726,726,1793 ,0,0,0}, {2208,2207,2188 ,1793,726,726 ,0,0,0}, - {2937,2386,2387 ,1793,726,726 ,0,0,0}, {2754,2305,2757 ,1793,1793,1793 ,0,0,0}, - {2211,2189,2192 ,726,1793,726 ,0,0,0}, {2412,2410,2635 ,1793,1793,1793 ,0,0,0}, - {2797,2757,2303 ,726,1793,1793 ,0,0,0}, {2450,2416,2632 ,1792,726,726 ,0,0,0}, - {2301,2299,2797 ,1793,726,726 ,0,0,0}, {2887,2497,2498 ,726,726,726 ,0,0,0}, - {2843,2524,2839 ,726,726,726 ,0,0,0}, {2526,2843,2845 ,726,726,726 ,0,0,0}, - {2605,2424,2606 ,1793,726,726 ,0,0,0}, {2280,2775,2281 ,1793,726,1793 ,0,0,0}, - {2797,2299,2795 ,726,726,1792 ,0,0,0}, {2792,2795,2298 ,726,1792,726 ,0,0,0}, - {2293,2793,2295 ,726,1793,1793 ,0,0,0}, {2295,2792,2298 ,1793,726,726 ,0,0,0}, - {2283,2779,2783 ,1793,1793,1793 ,0,0,0}, {2289,2786,2292 ,726,1793,726 ,0,0,0}, - {2293,2787,2793 ,726,726,1793 ,0,0,0}, {2785,2286,2783 ,1793,1793,1793 ,0,0,0}, - {2775,2779,2281 ,726,1793,1793 ,0,0,0}, {2776,2277,2772 ,1793,726,726 ,0,0,0}, - {2608,2429,2611 ,726,726,726 ,0,0,0}, {2771,2772,2275 ,1793,726,1793 ,0,0,0}, - {2839,2524,2492 ,726,726,726 ,0,0,0}, {2492,2840,2839 ,726,726,726 ,0,0,0}, - {2840,2492,2488 ,726,726,726 ,0,0,0}, {2494,2881,2487 ,726,726,726 ,0,0,0}, - {2488,2880,2840 ,726,726,726 ,0,0,0}, {2423,2424,2605 ,1793,726,1793 ,0,0,0}, - {2887,2886,2497 ,726,726,726 ,0,0,0}, {2886,2494,2497 ,726,726,726 ,0,0,0}, - {2578,2582,2459 ,726,1793,1793 ,0,0,0}, {2889,2887,2498 ,726,726,726 ,0,0,0}, - {2505,2892,2501 ,726,726,726 ,0,0,0}, {2893,2505,2507 ,726,726,726 ,0,0,0}, - {2505,2893,2892 ,726,726,726 ,0,0,0}, {2504,2895,2507 ,726,726,726 ,0,0,0}, - {2893,2507,2895 ,726,726,726 ,0,0,0}, {2895,2504,2898 ,726,726,726 ,0,0,0}, - {2508,2511,2899 ,726,726,726 ,0,0,0}, {2460,2459,2582 ,726,1793,1793 ,0,0,0}, - {2901,2511,2512 ,726,726,726 ,0,0,0}, {2511,2901,2899 ,726,726,726 ,0,0,0}, - {2905,2904,2514 ,726,726,726 ,0,0,0}, {2599,2477,2474 ,726,1793,1793 ,0,0,0}, - {2512,2514,2904 ,726,726,726 ,0,0,0}, {2518,2907,2905 ,726,726,726 ,0,0,0}, - {2905,2514,2518 ,726,726,726 ,0,0,0}, {2907,2518,2516 ,726,726,726 ,0,0,0}, - {2516,2521,2910 ,726,726,726 ,0,0,0}, {2910,2521,2911 ,726,726,726 ,0,0,0}, - {2911,2523,2913 ,726,726,726 ,0,0,0}, {2601,2480,2478 ,1793,726,1792 ,0,0,0}, - {2523,2911,2521 ,726,726,726 ,0,0,0}, {2402,2638,2636 ,726,726,1792 ,0,0,0}, - {2178,2179,2377 ,1792,726,726 ,0,0,0}, {2448,2450,2630 ,726,1792,726 ,0,0,0}, - {2636,2410,2409 ,1792,1793,1793 ,0,0,0}, {2447,2448,2629 ,1793,726,726 ,0,0,0}, - {2445,2447,2626 ,726,1793,726 ,0,0,0}, {2632,2416,2415 ,726,726,726 ,0,0,0}, - {2442,2445,2624 ,1793,726,1793 ,0,0,0}, {2632,2630,2450 ,726,726,1792 ,0,0,0}, - {2441,2442,2623 ,726,1793,1793 ,0,0,0}, {2630,2629,2448 ,726,726,726 ,0,0,0}, - {2439,2441,2620 ,1793,726,1793 ,0,0,0}, {2629,2626,2447 ,726,726,1793 ,0,0,0}, - {2436,2618,2617 ,1793,726,726 ,0,0,0}, {2626,2624,2445 ,726,1793,726 ,0,0,0}, - {2435,2617,2614 ,726,726,1793 ,0,0,0}, {2624,2623,2442 ,1793,1793,1793 ,0,0,0}, - {2433,2614,2612 ,1793,1793,726 ,0,0,0}, {2611,2430,2612 ,726,1793,726 ,0,0,0}, - {2436,2439,2618 ,1793,1793,726 ,0,0,0}, {2608,2606,2427 ,726,726,1793 ,0,0,0}, - {2436,2617,2435 ,1793,726,726 ,0,0,0}, {2845,2846,2529 ,726,726,726 ,0,0,0}, - {2614,2433,2435 ,1793,1793,726 ,0,0,0}, {2846,2849,2530 ,726,726,726 ,0,0,0}, - {2612,2430,2433 ,726,1793,1793 ,0,0,0}, {2849,2851,2532 ,726,726,726 ,0,0,0}, - {2268,2761,2269 ,1793,1793,726 ,0,0,0}, {2269,2765,2271 ,726,1793,726 ,0,0,0}, - {2606,2424,2427 ,726,726,1793 ,0,0,0}, {2535,2532,2851 ,726,726,726 ,0,0,0}, - {2526,2524,2843 ,726,726,726 ,0,0,0}, {2535,2852,2536 ,726,726,726 ,0,0,0}, - {2529,2526,2845 ,726,726,726 ,0,0,0}, {2855,2538,2536 ,726,726,726 ,0,0,0}, - {2530,2529,2846 ,726,726,726 ,0,0,0}, {2857,2541,2538 ,726,726,726 ,0,0,0}, - {2532,2530,2849 ,726,726,726 ,0,0,0}, {2232,2802,2231 ,726,1793,1793 ,0,0,0}, - {2542,2541,2858 ,726,726,726 ,0,0,0}, {2851,2852,2535 ,726,726,726 ,0,0,0}, - {2544,2542,2861 ,726,726,726 ,0,0,0}, {2544,2861,2863 ,726,726,726 ,0,0,0}, - {2235,2806,2805 ,1793,1793,726 ,0,0,0}, {2855,2857,2538 ,726,726,726 ,0,0,0}, - {2238,2811,2808 ,1793,1793,1793 ,0,0,0}, {2864,2547,2863 ,726,726,726 ,0,0,0}, - {2857,2858,2541 ,726,726,726 ,0,0,0}, {2548,2864,2867 ,726,726,726 ,0,0,0}, - {2858,2861,2542 ,726,726,726 ,0,0,0}, {2244,2817,2814 ,1793,1792,1793 ,0,0,0}, - {2863,2547,2544 ,726,726,726 ,0,0,0}, {2867,2869,2550 ,726,726,726 ,0,0,0}, - {2548,2547,2864 ,726,726,726 ,0,0,0}, {2870,2553,2869 ,726,726,726 ,0,0,0}, - {2247,2249,2818 ,726,1793,1793 ,0,0,0}, {2873,2554,2870 ,726,726,726 ,0,0,0}, - {2550,2548,2867 ,726,726,726 ,0,0,0}, {2253,2255,2824 ,726,726,726 ,0,0,0}, - {2869,2553,2550 ,726,726,726 ,0,0,0}, {2556,2873,2875 ,726,726,726 ,0,0,0}, - {2256,2259,2829 ,726,1793,726 ,0,0,0}, {2870,2554,2553 ,726,726,726 ,0,0,0}, - {2559,2556,2875 ,1793,726,726 ,0,0,0}, {2560,2559,2876 ,726,1793,726 ,0,0,0}, - {2261,2262,2830 ,726,726,1793 ,0,0,0}, {2559,2875,2876 ,1793,726,726 ,0,0,0}, - {2837,2836,2560 ,1793,726,726 ,0,0,0}, {2836,2265,2560 ,726,726,726 ,0,0,0}, - {2876,2837,2560 ,726,1793,726 ,0,0,0}, {2873,2556,2554 ,726,726,726 ,0,0,0}, - {2423,2605,2569 ,1793,1793,1793 ,0,0,0}, {2421,2569,2572 ,1793,1793,1793 ,0,0,0}, - {2417,2572,2567 ,1793,1793,1793 ,0,0,0}, {2451,2567,2571 ,726,1793,726 ,0,0,0}, - {2571,2574,2453 ,726,1793,1793 ,0,0,0}, {2494,2883,2881 ,726,726,726 ,0,0,0}, - {2569,2421,2423 ,1793,1793,1793 ,0,0,0}, {2574,2577,2454 ,1793,1793,726 ,0,0,0}, - {2572,2417,2421 ,1793,1793,1793 ,0,0,0}, {2498,2501,2889 ,726,726,726 ,0,0,0}, - {2417,2567,2451 ,1793,1793,726 ,0,0,0}, {2578,2456,2577 ,726,726,1793 ,0,0,0}, - {2571,2453,2451 ,726,1793,726 ,0,0,0}, {2460,2582,2581 ,726,1793,1793 ,0,0,0}, - {2574,2454,2453 ,1793,726,1793 ,0,0,0}, {2462,2460,2581 ,1793,726,1793 ,0,0,0}, - {2577,2456,2454 ,1793,726,726 ,0,0,0}, {2585,2465,2462 ,726,1793,1793 ,0,0,0}, - {2578,2459,2456 ,726,1793,726 ,0,0,0}, {2589,2466,2465 ,726,726,1793 ,0,0,0}, - {2591,2468,2466 ,1793,726,726 ,0,0,0}, {2898,2508,2899 ,726,726,726 ,0,0,0}, - {2462,2581,2585 ,1793,1793,726 ,0,0,0}, {2586,2471,2468 ,726,1793,726 ,0,0,0}, - {2465,2585,2589 ,1793,726,726 ,0,0,0}, {2471,2592,2472 ,1793,726,1793 ,0,0,0}, - {2466,2589,2591 ,726,726,1793 ,0,0,0}, {2474,2472,2593 ,1793,1793,726 ,0,0,0}, - {2471,2586,2592 ,1793,726,726 ,0,0,0}, {2477,2599,2598 ,1793,726,1793 ,0,0,0}, - {2472,2592,2593 ,1793,726,726 ,0,0,0}, {2601,2478,2598 ,1793,1792,1793 ,0,0,0}, - {2474,2593,2599 ,1793,726,726 ,0,0,0}, {2601,2483,2480 ,1793,726,726 ,0,0,0}, - {2478,2477,2598 ,1792,1793,1793 ,0,0,0}, {2483,2561,2486 ,726,726,726 ,0,0,0}, - {2563,2486,2561 ,1793,726,726 ,0,0,0}, {2913,2523,2486 ,726,726,726 ,0,0,0}, - {2601,2603,2483 ,1793,726,726 ,0,0,0}, {2468,2591,2586 ,726,1793,726 ,0,0,0}, - {2430,2611,2429 ,1793,726,726 ,0,0,0}, {2441,2623,2620 ,726,1793,1793 ,0,0,0}, - {2439,2620,2618 ,1793,1793,726 ,0,0,0}, {2358,2685,2686 ,1793,726,1793 ,0,0,0}, - {2412,2635,2415 ,1793,1793,726 ,0,0,0}, {2373,2364,2698 ,1793,726,726 ,0,0,0}, - {2636,2635,2410 ,1792,1793,1793 ,0,0,0}, {2400,2403,2938 ,726,1793,1793 ,0,0,0}, - {2402,2636,2409 ,726,1792,1793 ,0,0,0}, {2939,2392,2391 ,1793,1793,726 ,0,0,0}, - {2383,2214,2195 ,726,726,726 ,0,0,0}, {2394,2940,2391 ,1793,726,726 ,0,0,0}, - {2383,2195,2936 ,726,726,726 ,0,0,0}, {2641,2371,2367 ,726,726,1793 ,0,0,0}, - {2363,2691,2692 ,1793,726,726 ,0,0,0}, {2925,2323,2311 ,1793,1793,1793 ,0,0,0}, - {2680,2683,2357 ,1793,1793,1793 ,0,0,0}, {2352,2673,2674 ,1792,1793,1792 ,0,0,0}, - {2661,2662,2335 ,1793,1793,726 ,0,0,0}, {2715,2203,2716 ,1793,1793,1793 ,0,0,0}, - {2338,2656,2659 ,1793,726,1793 ,0,0,0}, {2668,2351,2336 ,726,726,726 ,0,0,0}, - {2351,2668,2671 ,726,726,1793 ,0,0,0}, {2354,2677,2679 ,1793,1793,1793 ,0,0,0}, - {2689,2358,2686 ,726,1793,1793 ,0,0,0}, {2689,2360,2358 ,726,726,1793 ,0,0,0}, - {2364,2363,2695 ,726,1793,726 ,0,0,0}, {2698,2700,2373 ,726,726,1793 ,0,0,0}, - {2373,2642,2370 ,1793,1793,1793 ,0,0,0}, {2367,2366,2641 ,1793,1793,726 ,0,0,0}, - {2939,2941,2392 ,1793,726,1793 ,0,0,0}, {2942,2943,2406 ,726,1793,726 ,0,0,0}, - {2943,2944,2406 ,1793,726,726 ,0,0,0}, {2945,2938,2403 ,726,1793,1793 ,0,0,0}, - {2938,2946,2400 ,1793,726,726 ,0,0,0}, {2371,2641,2638 ,726,726,726 ,0,0,0}, - {2642,2641,2366 ,1793,726,1793 ,0,0,0}, {2642,2373,2700 ,1793,1793,726 ,0,0,0}, - {2698,2364,2697 ,726,726,726 ,0,0,0}, {2695,2363,2692 ,726,1793,726 ,0,0,0}, - {2691,2360,2689 ,726,726,726 ,0,0,0}, {2358,2357,2685 ,1793,1793,726 ,0,0,0}, - {2357,2354,2680 ,1793,1793,1793 ,0,0,0}, {2352,2674,2677 ,1792,1792,1793 ,0,0,0}, - {2351,2671,2673 ,726,1793,1793 ,0,0,0}, {2336,2667,2668 ,726,1793,726 ,0,0,0}, - {2335,2662,2665 ,726,1793,1793 ,0,0,0}, {2338,2659,2661 ,1793,1793,1793 ,0,0,0}, - {2338,2340,2656 ,1793,1793,726 ,0,0,0}, {2342,2653,2655 ,726,1793,1793 ,0,0,0}, - {2345,2649,2650 ,1793,726,726 ,0,0,0}, {2346,2643,2647 ,726,1793,726 ,0,0,0}, - {2347,2703,2701 ,726,1793,1793 ,0,0,0}, {2916,2706,2704 ,1793,726,726 ,0,0,0}, - {2917,2710,2709 ,1793,1793,1793 ,0,0,0}, {2920,2715,2712 ,726,1793,726 ,0,0,0}, - {2134,2201,2132 ,726,1793,1793 ,0,0,0}, {2138,2141,2199 ,1793,1793,1793 ,0,0,0}, - {2718,2716,2131 ,1793,1793,726 ,0,0,0}, {2198,2140,2138 ,1793,726,1793 ,0,0,0}, - {2144,2205,2332 ,1793,726,1793 ,0,0,0}, {2947,2932,2948 ,726,1793,1793 ,0,0,0}, - {2317,2949,2315 ,726,1793,1793 ,0,0,0}, {2950,2317,2318 ,726,726,1793 ,0,0,0}, - {2312,2924,2313 ,1793,1793,726 ,0,0,0}, {2312,2315,2951 ,1793,1793,726 ,0,0,0}, - {2952,2322,2931 ,726,726,1793 ,0,0,0}, {2953,2328,2327 ,1793,1793,1793 ,0,0,0}, - {2947,2923,2922 ,726,1793,1793 ,0,0,0}, {2154,2727,2152 ,1793,1793,1793 ,0,0,0}, - {2149,2724,2722 ,1793,1793,1793 ,0,0,0}, {2158,2160,2733 ,1793,1793,726 ,0,0,0}, - {2155,2730,2728 ,726,726,726 ,0,0,0}, {2739,2161,2919 ,1793,1793,726 ,0,0,0}, - {2919,2926,2739 ,726,1793,1793 ,0,0,0}, {2736,2161,2739 ,726,1793,1793 ,0,0,0}, - {2736,2734,2160 ,726,726,1793 ,0,0,0}, {2742,2740,2926 ,726,726,1793 ,0,0,0}, - {2927,2745,2915 ,1793,726,726 ,0,0,0}, {2915,2742,2926 ,726,726,1793 ,0,0,0}, - {2927,2748,2746 ,1793,726,1793 ,0,0,0}, {2928,2308,2751 ,1793,1793,1793 ,0,0,0}, - {2927,2928,2748 ,1793,1793,726 ,0,0,0}, {2752,2751,2308 ,726,1793,1793 ,0,0,0}, - {2752,2305,2754 ,726,1793,1793 ,0,0,0}, {2757,2305,2303 ,1793,1793,1793 ,0,0,0}, - {2377,2174,2379 ,726,1793,726 ,0,0,0}, {2936,2937,2387 ,726,1793,726 ,0,0,0}, - {2168,2165,2224 ,1793,726,726 ,0,0,0}, {2934,2384,2386 ,726,726,726 ,0,0,0}, - {2935,2384,2933 ,1793,726,726 ,0,0,0}, {2940,2394,2935 ,726,1793,1793 ,0,0,0}, - {2939,2391,2940 ,1793,726,726 ,0,0,0}, {2396,2392,2941 ,1793,1793,726 ,0,0,0}, - {2396,2954,2406 ,1793,1793,726 ,0,0,0}, {2954,2396,2941 ,1793,1793,726 ,0,0,0}, - {2954,2942,2406 ,1793,726,726 ,0,0,0}, {2403,2944,2945 ,1793,726,726 ,0,0,0}, - {2944,2403,2406 ,726,1793,726 ,0,0,0}, {2402,2181,2638 ,726,726,726 ,0,0,0}, - {2946,2181,2402 ,726,726,726 ,0,0,0}, {2946,2402,2400 ,726,726,726 ,0,0,0}, - {2181,2178,2638 ,726,1792,726 ,0,0,0}, {2376,2178,2377 ,1793,1792,726 ,0,0,0}, - {2178,2376,2638 ,1792,1793,726 ,0,0,0}, {2179,2174,2377 ,726,1793,726 ,0,0,0}, - {2172,2175,2379 ,726,726,726 ,0,0,0}, {2174,2172,2379 ,1793,726,726 ,0,0,0}, - {2175,2166,2382 ,726,726,726 ,0,0,0}, {2168,2224,2382 ,1793,726,726 ,0,0,0}, - {2222,2224,2164 ,1793,726,1793 ,0,0,0}, {2186,2221,2183 ,726,1793,726 ,0,0,0}, - {2183,2222,2164 ,726,1793,1793 ,0,0,0}, {2188,2219,2186 ,726,726,726 ,0,0,0}, - {2188,2189,2208 ,726,1793,1793 ,0,0,0}, {2188,2207,2219 ,726,726,726 ,0,0,0}, - {2211,2192,2212 ,726,726,1793 ,0,0,0}, {2208,2189,2211 ,1793,1793,726 ,0,0,0}, - {2214,2194,2195 ,726,1792,726 ,0,0,0}, {2212,2192,2194 ,1793,726,1792 ,0,0,0}, - {2328,2955,2330 ,1793,726,1793 ,0,0,0}, {2919,2918,2923 ,726,726,1793 ,0,0,0}, - {2332,2330,2147 ,1793,1793,1793 ,0,0,0}, {2947,2948,2923 ,726,1793,1793 ,0,0,0}, - {2932,2931,2948 ,1793,1793,1793 ,0,0,0}, {2952,2931,2930 ,726,1793,1793 ,0,0,0}, - {2921,2322,2952 ,1793,726,726 ,0,0,0}, {2950,2318,2921 ,726,1793,1793 ,0,0,0}, - {2949,2317,2950 ,1793,726,726 ,0,0,0}, {2951,2315,2949 ,726,1793,1793 ,0,0,0}, - {2924,2312,2951 ,1793,1793,726 ,0,0,0}, {2311,2313,2925 ,1793,726,1793 ,0,0,0}, - {2929,2323,2925 ,726,1793,1793 ,0,0,0}, {2953,2327,2929 ,1793,1793,726 ,0,0,0}, - {2955,2328,2953 ,726,1793,1793 ,0,0,0}, {2147,2330,2955 ,1793,1793,726 ,0,0,0}, - {2144,2332,2147 ,1793,1793,1793 ,0,0,0}, {2145,2205,2144 ,1793,726,1793 ,0,0,0}, - {2198,2145,2140 ,1793,1793,726 ,0,0,0}, {2145,2198,2205 ,1793,1793,726 ,0,0,0}, - {2138,2199,2198 ,1793,1793,1793 ,0,0,0}, {2203,2201,2134 ,1793,1793,726 ,0,0,0}, - {2718,2131,2130 ,1793,726,726 ,0,0,0}, {2131,2716,2203 ,726,1793,1793 ,0,0,0}, - {2149,2722,2130 ,1793,1793,726 ,0,0,0}, {2721,2718,2130 ,726,1793,726 ,0,0,0}, - {2152,2724,2149 ,1793,1793,1793 ,0,0,0}, {2154,2728,2727 ,1793,726,1793 ,0,0,0}, - {2152,2727,2724 ,1793,1793,1793 ,0,0,0}, {2155,2158,2730 ,726,1793,726 ,0,0,0}, - {2154,2155,2728 ,1793,726,726 ,0,0,0}, {2733,2160,2734 ,726,1793,726 ,0,0,0}, - {2730,2158,2733 ,726,1793,726 ,0,0,0}, {2736,2160,2161 ,726,1793,1793 ,0,0,0}, - {2484,2602,2600 ,730,730,730 ,0,0,0}, {2266,2762,2227 ,730,730,730 ,0,0,0}, - {2337,2670,2669 ,730,730,730 ,0,0,0}, {2596,2479,2597 ,730,730,730 ,0,0,0}, - {2470,2473,2588 ,730,730,730 ,0,0,0}, {2475,2476,2595 ,730,730,730 ,0,0,0}, - {2461,2463,2580 ,730,730,730 ,0,0,0}, {2464,2467,2584 ,730,730,730 ,0,0,0}, - {2565,2568,2419 ,730,730,730 ,0,0,0}, {2455,2457,2575 ,730,730,730 ,0,0,0}, - {2764,2228,2227 ,730,730,730 ,0,0,0}, {2609,2426,2607 ,730,730,730 ,0,0,0}, - {2236,2804,2807 ,730,730,730 ,0,0,0}, {2810,2813,2242 ,730,730,730 ,0,0,0}, - {2798,2801,2230 ,730,730,730 ,0,0,0}, {2804,2236,2234 ,730,730,730 ,0,0,0}, - {2267,2760,2759 ,730,730,730 ,0,0,0}, {2228,2764,2798 ,730,730,730 ,0,0,0}, - {2272,2273,2769 ,730,730,730 ,0,0,0}, {2842,2525,2844 ,730,730,730 ,0,0,0}, - {2770,2276,2773 ,730,730,730 ,0,0,0}, {2273,2770,2769 ,730,730,730 ,0,0,0}, - {2285,2784,2284 ,730,730,730 ,0,0,0}, {2278,2774,2773 ,730,730,730 ,0,0,0}, - {2791,2790,2296 ,730,730,730 ,0,0,0}, {2789,2788,2291 ,730,730,730 ,0,0,0}, - {2297,2300,2794 ,730,730,730 ,0,0,0}, {2956,2708,2711 ,730,730,730 ,0,0,0}, - {2343,2341,2652 ,730,730,730 ,0,0,0}, {2146,2206,2204 ,730,730,730 ,0,0,0}, - {2156,2731,2732 ,730,730,730 ,0,0,0}, {2306,2756,2758 ,730,730,730 ,0,0,0}, - {2796,2304,2758 ,730,730,730 ,0,0,0}, {2957,2958,2750 ,730,730,730 ,0,0,0}, - {2159,2157,2735 ,730,730,730 ,0,0,0}, {2957,2750,2753 ,730,730,730 ,0,0,0}, - {2747,2749,2958 ,730,730,730 ,0,0,0}, {2309,2959,2310 ,730,730,730 ,0,0,0}, - {2758,2304,2306 ,730,730,730 ,0,0,0}, {2670,2337,2350 ,730,730,730 ,0,0,0}, - {2960,2349,2707 ,730,730,730 ,0,0,0}, {2648,2646,2344 ,730,730,730 ,0,0,0}, - {2156,2732,2157 ,730,730,730 ,0,0,0}, {2202,2717,2719 ,730,730,730 ,0,0,0}, - {2300,2302,2796 ,730,730,730 ,0,0,0}, {2200,2133,2197 ,730,730,730 ,0,0,0}, - {2136,2137,2197 ,730,730,730 ,0,0,0}, {2961,2325,2326 ,730,730,730 ,0,0,0}, - {2957,2753,2307 ,730,730,730 ,0,0,0}, {2306,2307,2755 ,730,730,730 ,0,0,0}, - {2962,2747,2958 ,730,730,730 ,0,0,0}, {2743,2744,2963 ,730,730,730 ,0,0,0}, - {2963,2744,2962 ,730,730,730 ,0,0,0}, {2962,2744,2747 ,730,730,730 ,0,0,0}, - {2958,2749,2750 ,730,730,730 ,0,0,0}, {2964,2965,2966 ,730,730,730 ,0,0,0}, - {2215,2216,2193 ,730,730,730 ,0,0,0}, {2753,2755,2307 ,730,730,730 ,0,0,0}, - {2737,2159,2735 ,730,730,730 ,0,0,0}, {2756,2306,2755 ,730,730,730 ,0,0,0}, - {2967,2321,2319 ,730,730,730 ,0,0,0}, {2326,2329,2968 ,730,730,730 ,0,0,0}, - {2331,2206,2143 ,730,730,730 ,0,0,0}, {2329,2331,2142 ,730,730,730 ,0,0,0}, - {2796,2302,2304 ,730,730,730 ,0,0,0}, {2310,2969,2314 ,730,730,730 ,0,0,0}, - {2970,2324,2325 ,730,730,730 ,0,0,0}, {2202,2719,2129 ,730,730,730 ,0,0,0}, - {2314,2971,2316 ,730,730,730 ,0,0,0}, {2153,2731,2156 ,730,730,730 ,0,0,0}, - {2731,2153,2729 ,730,730,730 ,0,0,0}, {2644,2348,2645 ,730,730,730 ,0,0,0}, - {2660,2334,2663 ,730,730,730 ,0,0,0}, {2657,2654,2339 ,730,730,730 ,0,0,0}, - {2678,2676,2353 ,730,730,730 ,0,0,0}, {2666,2333,2337 ,730,730,730 ,0,0,0}, - {2678,2353,2355 ,730,730,730 ,0,0,0}, {2296,2297,2791 ,730,730,730 ,0,0,0}, - {2300,2796,2794 ,730,730,730 ,0,0,0}, {2794,2791,2297 ,730,730,730 ,0,0,0}, - {2810,2240,2809 ,730,730,730 ,0,0,0}, {2789,2291,2294 ,730,730,730 ,0,0,0}, - {2790,2294,2296 ,730,730,730 ,0,0,0}, {2290,2291,2788 ,730,730,730 ,0,0,0}, - {2789,2294,2790 ,730,730,730 ,0,0,0}, {2290,2782,2288 ,730,730,730 ,0,0,0}, - {2781,2285,2288 ,730,730,730 ,0,0,0}, {2788,2782,2290 ,730,730,730 ,0,0,0}, - {2285,2781,2784 ,730,730,730 ,0,0,0}, {2288,2782,2781 ,730,730,730 ,0,0,0}, - {2619,2438,2437 ,730,730,730 ,0,0,0}, {2778,2282,2284 ,730,730,730 ,0,0,0}, - {2282,2777,2279 ,730,730,730 ,0,0,0}, {2777,2774,2279 ,730,730,730 ,0,0,0}, - {2774,2278,2279 ,730,730,730 ,0,0,0}, {2773,2276,2278 ,730,730,730 ,0,0,0}, - {2770,2273,2276 ,730,730,730 ,0,0,0}, {2270,2767,2760 ,730,730,730 ,0,0,0}, - {2272,2769,2767 ,730,730,730 ,0,0,0}, {2267,2759,2266 ,730,730,730 ,0,0,0}, - {2762,2764,2227 ,730,730,730 ,0,0,0}, {2230,2801,2233 ,730,730,730 ,0,0,0}, - {2234,2233,2803 ,730,730,730 ,0,0,0}, {2236,2807,2239 ,730,730,730 ,0,0,0}, - {2234,2803,2804 ,730,730,730 ,0,0,0}, {2239,2809,2240 ,730,730,730 ,0,0,0}, - {2239,2807,2809 ,730,730,730 ,0,0,0}, {2245,2813,2815 ,730,730,730 ,0,0,0}, - {2242,2240,2810 ,730,730,730 ,0,0,0}, {2246,2245,2815 ,730,730,730 ,0,0,0}, - {2246,2815,2816 ,730,730,730 ,0,0,0}, {2248,2816,2819 ,730,730,730 ,0,0,0}, - {2246,2816,2248 ,730,730,730 ,0,0,0}, {2819,2251,2248 ,730,730,730 ,0,0,0}, - {2819,2821,2251 ,730,730,730 ,0,0,0}, {2251,2821,2252 ,730,730,730 ,0,0,0}, - {2233,2801,2803 ,730,730,730 ,0,0,0}, {2254,2252,2822 ,730,730,730 ,0,0,0}, - {2252,2821,2822 ,730,730,730 ,0,0,0}, {2825,2257,2254 ,730,730,730 ,0,0,0}, - {2825,2254,2822 ,730,730,730 ,0,0,0}, {2257,2827,2258 ,730,730,730 ,0,0,0}, - {2258,2828,2260 ,730,730,730 ,0,0,0}, {2828,2258,2827 ,730,730,730 ,0,0,0}, - {2828,2831,2263 ,730,730,730 ,0,0,0}, {2555,2874,2872 ,730,730,730 ,0,0,0}, - {2264,2263,2831 ,730,730,730 ,0,0,0}, {2834,2838,2558 ,730,730,730 ,0,0,0}, - {2557,2877,2874 ,730,730,730 ,0,0,0}, {2230,2228,2798 ,730,730,730 ,0,0,0}, - {2491,2878,2489 ,730,730,730 ,0,0,0}, {2877,2557,2558 ,730,730,730 ,0,0,0}, - {2759,2762,2266 ,730,730,730 ,0,0,0}, {2613,2431,2610 ,730,730,730 ,0,0,0}, - {2434,2432,2615 ,730,730,730 ,0,0,0}, {2432,2431,2613 ,730,730,730 ,0,0,0}, - {2428,2426,2609 ,730,730,730 ,0,0,0}, {2609,2610,2428 ,730,730,730 ,0,0,0}, - {2607,2425,2604 ,730,730,730 ,0,0,0}, {2607,2426,2425 ,730,730,730 ,0,0,0}, - {2570,2604,2422 ,730,730,730 ,0,0,0}, {2425,2422,2604 ,730,730,730 ,0,0,0}, - {2420,2568,2570 ,730,730,730 ,0,0,0}, {2570,2422,2420 ,730,730,730 ,0,0,0}, - {2566,2418,2452 ,730,730,730 ,0,0,0}, {2419,2568,2420 ,730,730,730 ,0,0,0}, - {2452,2455,2573 ,730,730,730 ,0,0,0}, {2418,2566,2565 ,730,730,730 ,0,0,0}, - {2566,2452,2573 ,730,730,730 ,0,0,0}, {2579,2576,2458 ,730,730,730 ,0,0,0}, - {2500,2890,2891 ,730,730,730 ,0,0,0}, {2461,2579,2458 ,730,730,730 ,0,0,0}, - {2457,2458,2576 ,730,730,730 ,0,0,0}, {2583,2464,2584 ,730,730,730 ,0,0,0}, - {2580,2579,2461 ,730,730,730 ,0,0,0}, {2467,2590,2584 ,730,730,730 ,0,0,0}, - {2464,2583,2463 ,730,730,730 ,0,0,0}, {2470,2587,2469 ,730,730,730 ,0,0,0}, - {2469,2587,2590 ,730,730,730 ,0,0,0}, {2594,2588,2473 ,730,730,730 ,0,0,0}, - {2588,2587,2470 ,730,730,730 ,0,0,0}, {2476,2596,2595 ,730,730,730 ,0,0,0}, - {2475,2595,2594 ,730,730,730 ,0,0,0}, {2600,2481,2482 ,730,730,730 ,0,0,0}, - {2481,2597,2479 ,730,730,730 ,0,0,0}, {2600,2482,2484 ,730,730,730 ,0,0,0}, - {2831,2833,2264 ,730,730,730 ,0,0,0}, {2834,2264,2833 ,730,730,730 ,0,0,0}, - {2552,2871,2551 ,730,730,730 ,0,0,0}, {2263,2260,2828 ,730,730,730 ,0,0,0}, - {2557,2874,2555 ,730,730,730 ,0,0,0}, {2257,2825,2827 ,730,730,730 ,0,0,0}, - {2549,2551,2868 ,730,730,730 ,0,0,0}, {2872,2871,2552 ,730,730,730 ,0,0,0}, - {2546,2549,2866 ,730,730,730 ,0,0,0}, {2871,2868,2551 ,730,730,730 ,0,0,0}, - {2865,2545,2546 ,730,730,730 ,0,0,0}, {2862,2543,2545 ,730,730,730 ,0,0,0}, - {2866,2549,2868 ,730,730,730 ,0,0,0}, {2860,2540,2543 ,730,730,730 ,0,0,0}, - {2865,2546,2866 ,730,730,730 ,0,0,0}, {2242,2813,2245 ,730,730,730 ,0,0,0}, - {2865,2862,2545 ,730,730,730 ,0,0,0}, {2859,2856,2539 ,730,730,730 ,0,0,0}, - {2862,2860,2543 ,730,730,730 ,0,0,0}, {2856,2854,2537 ,730,730,730 ,0,0,0}, - {2854,2853,2534 ,730,730,730 ,0,0,0}, {2853,2850,2533 ,730,730,730 ,0,0,0}, - {2540,2859,2539 ,730,730,730 ,0,0,0}, {2850,2848,2531 ,730,730,730 ,0,0,0}, - {2539,2856,2537 ,730,730,730 ,0,0,0}, {2847,2528,2848 ,730,730,730 ,0,0,0}, - {2537,2854,2534 ,730,730,730 ,0,0,0}, {2527,2847,2844 ,730,730,730 ,0,0,0}, - {2534,2853,2533 ,730,730,730 ,0,0,0}, {2525,2842,2490 ,730,730,730 ,0,0,0}, - {2533,2850,2531 ,730,730,730 ,0,0,0}, {2491,2490,2841 ,730,730,730 ,0,0,0}, - {2848,2528,2531 ,730,730,730 ,0,0,0}, {2489,2879,2493 ,730,730,730 ,0,0,0}, - {2527,2528,2847 ,730,730,730 ,0,0,0}, {2616,2434,2615 ,730,730,730 ,0,0,0}, - {2272,2767,2270 ,730,730,730 ,0,0,0}, {2270,2760,2267 ,730,730,730 ,0,0,0}, - {2490,2842,2841 ,730,730,730 ,0,0,0}, {2616,2619,2437 ,730,730,730 ,0,0,0}, - {2491,2841,2878 ,730,730,730 ,0,0,0}, {2619,2621,2438 ,730,730,730 ,0,0,0}, - {2489,2878,2879 ,730,730,730 ,0,0,0}, {2621,2622,2440 ,730,730,730 ,0,0,0}, - {2622,2625,2443 ,730,730,730 ,0,0,0}, {2613,2615,2432 ,730,730,730 ,0,0,0}, - {2625,2627,2444 ,730,730,730 ,0,0,0}, {2437,2434,2616 ,730,730,730 ,0,0,0}, - {2627,2628,2446 ,730,730,730 ,0,0,0}, {2284,2784,2778 ,730,730,730 ,0,0,0}, - {2282,2778,2777 ,730,730,730 ,0,0,0}, {2621,2440,2438 ,730,730,730 ,0,0,0}, - {2413,2631,2633 ,730,730,730 ,0,0,0}, {2622,2443,2440 ,730,730,730 ,0,0,0}, - {2405,2972,2973 ,730,730,730 ,0,0,0}, {2625,2444,2443 ,730,730,730 ,0,0,0}, - {2210,2213,2190 ,730,730,730 ,0,0,0}, {2184,2218,2185 ,730,730,730 ,0,0,0}, - {2449,2631,2414 ,730,730,730 ,0,0,0}, {2368,2637,2639 ,730,730,730 ,0,0,0}, - {2374,2372,2640 ,730,730,730 ,0,0,0}, {2187,2209,2210 ,730,730,730 ,0,0,0}, - {2362,2696,2694 ,730,730,730 ,0,0,0}, {2974,2388,2975 ,730,730,730 ,0,0,0}, - {2637,2368,2375 ,730,730,730 ,0,0,0}, {2356,2687,2684 ,730,730,730 ,0,0,0}, - {2738,2162,2159 ,730,730,730 ,0,0,0}, {2976,2741,2963 ,730,730,730 ,0,0,0}, - {2743,2963,2741 ,730,730,730 ,0,0,0}, {2741,2976,2162 ,730,730,730 ,0,0,0}, - {2977,2978,2979 ,730,730,730 ,0,0,0}, {2741,2162,2738 ,730,730,730 ,0,0,0}, - {2737,2738,2159 ,730,730,730 ,0,0,0}, {2139,2204,2137 ,730,730,730 ,0,0,0}, - {2970,2959,2324 ,730,730,730 ,0,0,0}, {2980,2981,2982 ,730,730,730 ,0,0,0}, - {2644,2702,2348 ,730,730,730 ,0,0,0}, {2334,2658,2339 ,730,730,730 ,0,0,0}, - {2675,2350,2353 ,730,730,730 ,0,0,0}, {2688,2359,2361 ,730,730,730 ,0,0,0}, - {2688,2687,2359 ,730,730,730 ,0,0,0}, {2690,2361,2693 ,730,730,730 ,0,0,0}, - {2684,2682,2356 ,730,730,730 ,0,0,0}, {2682,2681,2355 ,730,730,730 ,0,0,0}, - {2350,2675,2672 ,730,730,730 ,0,0,0}, {2666,2664,2333 ,730,730,730 ,0,0,0}, - {2333,2663,2334 ,730,730,730 ,0,0,0}, {2658,2657,2339 ,730,730,730 ,0,0,0}, - {2652,2651,2343 ,730,730,730 ,0,0,0}, {2648,2344,2343 ,730,730,730 ,0,0,0}, - {2693,2362,2694 ,730,730,730 ,0,0,0}, {2646,2645,2344 ,730,730,730 ,0,0,0}, - {2702,2349,2348 ,730,730,730 ,0,0,0}, {2705,2707,2349 ,730,730,730 ,0,0,0}, - {2713,2983,2956 ,730,730,730 ,0,0,0}, {2983,2713,2714 ,730,730,730 ,0,0,0}, - {2202,2983,2717 ,730,730,730 ,0,0,0}, {2148,2720,2723 ,730,730,730 ,0,0,0}, - {2151,2150,2726 ,730,730,730 ,0,0,0}, {2148,2129,2720 ,730,730,730 ,0,0,0}, - {2714,2717,2983 ,730,730,730 ,0,0,0}, {2711,2713,2956 ,730,730,730 ,0,0,0}, - {2707,2708,2960 ,730,730,730 ,0,0,0}, {2708,2956,2960 ,730,730,730 ,0,0,0}, - {2702,2705,2349 ,730,730,730 ,0,0,0}, {2645,2348,2344 ,730,730,730 ,0,0,0}, - {2648,2343,2651 ,730,730,730 ,0,0,0}, {2341,2339,2654 ,730,730,730 ,0,0,0}, - {2341,2654,2652 ,730,730,730 ,0,0,0}, {2334,2660,2658 ,730,730,730 ,0,0,0}, - {2333,2664,2663 ,730,730,730 ,0,0,0}, {2337,2669,2666 ,730,730,730 ,0,0,0}, - {2350,2672,2670 ,730,730,730 ,0,0,0}, {2353,2676,2675 ,730,730,730 ,0,0,0}, - {2355,2681,2678 ,730,730,730 ,0,0,0}, {2355,2356,2682 ,730,730,730 ,0,0,0}, - {2356,2359,2687 ,730,730,730 ,0,0,0}, {2361,2690,2688 ,730,730,730 ,0,0,0}, - {2361,2362,2693 ,730,730,730 ,0,0,0}, {2362,2374,2696 ,730,730,730 ,0,0,0}, - {2374,2640,2699 ,730,730,730 ,0,0,0}, {2696,2374,2699 ,730,730,730 ,0,0,0}, - {2640,2372,2369 ,730,730,730 ,0,0,0}, {2369,2365,2639 ,730,730,730 ,0,0,0}, - {2639,2640,2369 ,730,730,730 ,0,0,0}, {2191,2190,2213 ,730,730,730 ,0,0,0}, - {2368,2639,2365 ,730,730,730 ,0,0,0}, {2170,2380,2381 ,730,730,730 ,0,0,0}, - {2191,2213,2215 ,730,730,730 ,0,0,0}, {2216,2389,2196 ,730,730,730 ,0,0,0}, - {2215,2193,2191 ,730,730,730 ,0,0,0}, {2216,2196,2193 ,730,730,730 ,0,0,0}, - {2397,2984,2390 ,730,730,730 ,0,0,0}, {2393,2985,2385 ,730,730,730 ,0,0,0}, - {2986,2398,2987 ,730,730,730 ,0,0,0}, {2405,2988,2987 ,730,730,730 ,0,0,0}, - {2220,2182,2223 ,730,730,730 ,0,0,0}, {2989,2404,2990 ,730,730,730 ,0,0,0}, - {2184,2182,2220 ,730,730,730 ,0,0,0}, {2633,2408,2411 ,730,730,730 ,0,0,0}, - {2634,2407,2408 ,730,730,730 ,0,0,0}, {2173,2380,2171 ,730,730,730 ,0,0,0}, - {2381,2167,2170 ,730,730,730 ,0,0,0}, {2173,2180,2378 ,730,730,730 ,0,0,0}, - {2401,2407,2634 ,730,730,730 ,0,0,0}, {2401,2634,2637 ,730,730,730 ,0,0,0}, - {2408,2633,2634 ,730,730,730 ,0,0,0}, {2413,2633,2411 ,730,730,730 ,0,0,0}, - {2414,2631,2413 ,730,730,730 ,0,0,0}, {2628,2631,2449 ,730,730,730 ,0,0,0}, - {2446,2628,2449 ,730,730,730 ,0,0,0}, {2444,2627,2446 ,730,730,730 ,0,0,0}, - {2493,2882,2495 ,730,730,730 ,0,0,0}, {2885,2495,2884 ,730,730,730 ,0,0,0}, - {2428,2610,2431 ,730,730,730 ,0,0,0}, {2888,2496,2885 ,730,730,730 ,0,0,0}, - {2888,2499,2496 ,730,730,730 ,0,0,0}, {2890,2500,2499 ,730,730,730 ,0,0,0}, - {2882,2493,2879 ,730,730,730 ,0,0,0}, {2891,2506,2500 ,730,730,730 ,0,0,0}, - {2884,2495,2882 ,730,730,730 ,0,0,0}, {2418,2565,2419 ,730,730,730 ,0,0,0}, - {2502,2506,2894 ,730,730,730 ,0,0,0}, {2496,2495,2885 ,730,730,730 ,0,0,0}, - {2503,2502,2896 ,730,730,730 ,0,0,0}, {2888,2890,2499 ,730,730,730 ,0,0,0}, - {2509,2503,2897 ,730,730,730 ,0,0,0}, {2457,2576,2575 ,730,730,730 ,0,0,0}, - {2455,2575,2573 ,730,730,730 ,0,0,0}, {2506,2891,2894 ,730,730,730 ,0,0,0}, - {2510,2509,2900 ,730,730,730 ,0,0,0}, {2510,2900,2902 ,730,730,730 ,0,0,0}, - {2894,2896,2502 ,730,730,730 ,0,0,0}, {2463,2583,2580 ,730,730,730 ,0,0,0}, - {2503,2896,2897 ,730,730,730 ,0,0,0}, {2902,2903,2513 ,730,730,730 ,0,0,0}, - {2906,2519,2903 ,730,730,730 ,0,0,0}, {2897,2900,2509 ,730,730,730 ,0,0,0}, - {2513,2510,2902 ,730,730,730 ,0,0,0}, {2908,2517,2906 ,730,730,730 ,0,0,0}, - {2467,2469,2590 ,730,730,730 ,0,0,0}, {2909,2515,2908 ,730,730,730 ,0,0,0}, - {2519,2513,2903 ,730,730,730 ,0,0,0}, {2473,2475,2594 ,730,730,730 ,0,0,0}, - {2906,2517,2519 ,730,730,730 ,0,0,0}, {2909,2912,2520 ,730,730,730 ,0,0,0}, - {2476,2479,2596 ,730,730,730 ,0,0,0}, {2908,2515,2517 ,730,730,730 ,0,0,0}, - {2522,2520,2912 ,730,730,730 ,0,0,0}, {2522,2914,2485 ,730,730,730 ,0,0,0}, - {2597,2481,2600 ,730,730,730 ,0,0,0}, {2522,2912,2914 ,730,730,730 ,0,0,0}, - {2564,2484,2485 ,730,730,730 ,0,0,0}, {2602,2484,2564 ,730,730,730 ,0,0,0}, - {2914,2562,2485 ,730,730,730 ,0,0,0}, {2564,2485,2562 ,730,730,730 ,0,0,0}, - {2909,2520,2515 ,730,730,730 ,0,0,0}, {2525,2527,2844 ,730,730,730 ,0,0,0}, - {2859,2540,2860 ,730,730,730 ,0,0,0}, {2872,2552,2555 ,730,730,730 ,0,0,0}, - {2834,2558,2264 ,730,730,730 ,0,0,0}, {2838,2877,2558 ,730,730,730 ,0,0,0}, - {2185,2217,2187 ,730,730,730 ,0,0,0}, {2991,2393,2395 ,730,730,730 ,0,0,0}, - {2397,2986,2984 ,730,730,730 ,0,0,0}, {2187,2210,2190 ,730,730,730 ,0,0,0}, - {2187,2217,2209 ,730,730,730 ,0,0,0}, {2185,2218,2217 ,730,730,730 ,0,0,0}, - {2184,2220,2218 ,730,730,730 ,0,0,0}, {2399,2401,2992 ,730,730,730 ,0,0,0}, - {2163,2169,2223 ,730,730,730 ,0,0,0}, {2163,2223,2182 ,730,730,730 ,0,0,0}, - {2381,2169,2167 ,730,730,730 ,0,0,0}, {2169,2381,2223 ,730,730,730 ,0,0,0}, - {2176,2401,2637 ,730,730,730 ,0,0,0}, {2173,2378,2380 ,730,730,730 ,0,0,0}, - {2170,2171,2380 ,730,730,730 ,0,0,0}, {2177,2378,2180 ,730,730,730 ,0,0,0}, - {2637,2177,2176 ,730,730,730 ,0,0,0}, {2375,2177,2637 ,730,730,730 ,0,0,0}, - {2177,2375,2378 ,730,730,730 ,0,0,0}, {2176,2992,2401 ,730,730,730 ,0,0,0}, - {2399,2990,2404 ,730,730,730 ,0,0,0}, {2992,2990,2399 ,730,730,730 ,0,0,0}, - {2404,2972,2405 ,730,730,730 ,0,0,0}, {2989,2972,2404 ,730,730,730 ,0,0,0}, - {2973,2988,2405 ,730,730,730 ,0,0,0}, {2987,2398,2405 ,730,730,730 ,0,0,0}, - {2986,2397,2398 ,730,730,730 ,0,0,0}, {2993,2390,2984 ,730,730,730 ,0,0,0}, - {2395,2993,2991 ,730,730,730 ,0,0,0}, {2993,2395,2390 ,730,730,730 ,0,0,0}, - {2991,2994,2393 ,730,730,730 ,0,0,0}, {2985,2975,2385 ,730,730,730 ,0,0,0}, - {2994,2985,2393 ,730,730,730 ,0,0,0}, {2388,2974,2389 ,730,730,730 ,0,0,0}, - {2385,2975,2388 ,730,730,730 ,0,0,0}, {2196,2389,2974 ,730,730,730 ,0,0,0}, - {2200,2202,2135 ,730,730,730 ,0,0,0}, {2732,2735,2157 ,730,730,730 ,0,0,0}, - {2319,2316,2995 ,730,730,730 ,0,0,0}, {2151,2726,2729 ,730,730,730 ,0,0,0}, - {2729,2153,2151 ,730,730,730 ,0,0,0}, {2725,2726,2150 ,730,730,730 ,0,0,0}, - {2725,2148,2723 ,730,730,730 ,0,0,0}, {2148,2725,2150 ,730,730,730 ,0,0,0}, - {2720,2129,2719 ,730,730,730 ,0,0,0}, {2129,2135,2202 ,730,730,730 ,0,0,0}, - {2135,2133,2200 ,730,730,730 ,0,0,0}, {2133,2136,2197 ,730,730,730 ,0,0,0}, - {2137,2204,2197 ,730,730,730 ,0,0,0}, {2146,2204,2139 ,730,730,730 ,0,0,0}, - {2143,2206,2146 ,730,730,730 ,0,0,0}, {2142,2331,2143 ,730,730,730 ,0,0,0}, - {2968,2329,2142 ,730,730,730 ,0,0,0}, {2961,2326,2968 ,730,730,730 ,0,0,0}, - {2970,2325,2961 ,730,730,730 ,0,0,0}, {2309,2324,2959 ,730,730,730 ,0,0,0}, - {2969,2310,2959 ,730,730,730 ,0,0,0}, {2971,2314,2969 ,730,730,730 ,0,0,0}, - {2995,2316,2971 ,730,730,730 ,0,0,0}, {2996,2321,2967 ,730,730,730 ,0,0,0}, - {2967,2319,2995 ,730,730,730 ,0,0,0}, {2320,2996,2982 ,730,730,730 ,0,0,0}, - {2996,2320,2321 ,730,730,730 ,0,0,0}, {2980,2965,2981 ,730,730,730 ,0,0,0}, - {2320,2982,2981 ,730,730,730 ,0,0,0}, {2964,2966,2977 ,730,730,730 ,0,0,0}, - {2981,2965,2964 ,730,730,730 ,0,0,0}, {2977,2979,2976 ,730,730,730 ,0,0,0}, - {2977,2966,2978 ,730,730,730 ,0,0,0}, {2162,2976,2979 ,730,730,730 ,0,0,0}, - {2976,2963,2926 ,2553,2554,2555 ,0,0,0}, {2977,2919,2923 ,2556,2557,2558 ,0,0,0}, - {2919,2976,2926 ,2557,2553,2555 ,0,0,0}, {2976,2919,2977 ,2553,2557,2556 ,0,0,0}, - {2981,2948,2931 ,2559,2560,2561 ,0,0,0}, {2977,2923,2964 ,2556,2558,2562 ,0,0,0}, - {2981,2964,2948 ,2559,2562,2560 ,0,0,0}, {2931,2322,2320 ,2561,1982,1982 ,0,0,0}, - {2931,2320,2981 ,2561,1982,2559 ,0,0,0}, {2948,2964,2923 ,2560,2562,2558 ,0,0,0}, - {2963,2915,2926 ,2554,2563,2555 ,0,0,0}, {2927,2915,2962 ,2564,2563,2565 ,0,0,0}, - {2963,2962,2915 ,2554,2565,2563 ,0,0,0}, {2958,2928,2927 ,2566,2567,2564 ,0,0,0}, - {2927,2962,2958 ,2564,2565,2566 ,0,0,0}, {2928,2957,2308 ,2567,2568,1972 ,0,0,0}, - {2957,2928,2958 ,2568,2567,2566 ,0,0,0}, {2957,2307,2308 ,2568,1972,1972 ,0,0,0}, - {2203,2920,2983 ,1879,2569,2569 ,0,0,0}, {2916,2349,2960 ,2570,2008,2571 ,0,0,0}, - {2960,2956,2917 ,2571,2572,2572 ,0,0,0}, {2347,2349,2916 ,2008,2008,2570 ,0,0,0}, - {2920,2956,2983 ,2569,2572,2569 ,0,0,0}, {2956,2920,2917 ,2572,2569,2572 ,0,0,0}, - {2916,2960,2917 ,2570,2571,2572 ,0,0,0}, {2983,2202,2203 ,2569,1879,1879 ,0,0,0}, - {2181,2946,2992 ,1077,1076,1075 ,0,0,0}, {2944,2972,2945 ,1070,1069,1071 ,0,0,0}, - {2989,2990,2938 ,1072,1073,1074 ,0,0,0}, {2987,2954,2986 ,1064,1047,126 ,0,0,0}, - {2943,2942,2988 ,1068,1065,1066 ,0,0,0}, {2940,2991,2993 ,1049,1053,1050 ,0,0,0}, - {2939,2984,2941 ,1051,1052,1048 ,0,0,0}, {2933,2985,2994 ,1055,1056,1054 ,0,0,0}, - {2994,2991,2935 ,1054,1053,1058 ,0,0,0}, {2985,2934,2975 ,1056,1057,1062 ,0,0,0}, - {2934,2985,2933 ,1057,1056,1055 ,0,0,0}, {2974,2975,2937 ,1059,1062,1061 ,0,0,0}, - {2934,2937,2975 ,1057,1061,1062 ,0,0,0}, {2936,2196,2974 ,1060,21,1059 ,0,0,0}, - {2974,2937,2936 ,1059,1061,1060 ,0,0,0}, {2195,2196,2936 ,1063,21,1060 ,0,0,0}, - {2939,2940,2993 ,1051,1049,1050 ,0,0,0}, {2991,2940,2935 ,1053,1049,1058 ,0,0,0}, - {2933,2994,2935 ,1055,1054,1058 ,0,0,0}, {2939,2993,2984 ,1051,1050,1052 ,0,0,0}, - {2941,2984,2986 ,1048,1052,126 ,0,0,0}, {2954,2987,2942 ,1047,1064,1065 ,0,0,0}, - {2954,2941,2986 ,1047,1048,126 ,0,0,0}, {2943,2988,2973 ,1068,1066,1067 ,0,0,0}, - {2988,2942,2987 ,1066,1065,1064 ,0,0,0}, {2973,2972,2944 ,1067,1069,1070 ,0,0,0}, - {2973,2944,2943 ,1067,1070,1068 ,0,0,0}, {2938,2945,2989 ,1074,1071,1072 ,0,0,0}, - {2972,2989,2945 ,1069,1072,1071 ,0,0,0}, {2990,2946,2938 ,1073,1076,1074 ,0,0,0}, - {2181,2992,2176 ,1077,1075,1078 ,0,0,0}, {2946,2990,2992 ,1076,1073,1075 ,0,0,0}, - {2147,2955,2968 ,1107,1106,1105 ,0,0,0}, {2925,2959,2929 ,1102,1101,1103 ,0,0,0}, - {2970,2961,2953 ,1072,1104,1074 ,0,0,0}, {2995,2949,2967 ,1096,1079,126 ,0,0,0}, - {2924,2951,2971 ,1100,1097,1098 ,0,0,0}, {2952,2980,2982 ,1080,1084,1081 ,0,0,0}, - {2921,2996,2950 ,1082,1083,126 ,0,0,0}, {2932,2966,2965 ,1086,1087,1085 ,0,0,0}, - {2965,2980,2930 ,1085,1084,1089 ,0,0,0}, {2966,2947,2978 ,1087,1088,1094 ,0,0,0}, - {2947,2966,2932 ,1088,1087,1086 ,0,0,0}, {2979,2978,2922 ,1091,1094,1093 ,0,0,0}, - {2947,2922,2978 ,1088,1093,1094 ,0,0,0}, {2918,2162,2979 ,1092,1090,1091 ,0,0,0}, - {2979,2922,2918 ,1091,1093,1092 ,0,0,0}, {2161,2162,2918 ,1095,1090,1092 ,0,0,0}, - {2921,2952,2982 ,1082,1080,1081 ,0,0,0}, {2980,2952,2930 ,1084,1080,1089 ,0,0,0}, - {2932,2965,2930 ,1086,1085,1089 ,0,0,0}, {2921,2982,2996 ,1082,1081,1083 ,0,0,0}, - {2950,2996,2967 ,126,1083,126 ,0,0,0}, {2949,2995,2951 ,1079,1096,1097 ,0,0,0}, - {2949,2950,2967 ,1079,126,126 ,0,0,0}, {2924,2971,2969 ,1100,1098,1099 ,0,0,0}, - {2971,2951,2995 ,1098,1097,1096 ,0,0,0}, {2969,2959,2925 ,1099,1101,1102 ,0,0,0}, - {2969,2925,2924 ,1099,1102,1100 ,0,0,0}, {2953,2929,2970 ,1074,1103,1072 ,0,0,0}, - {2959,2970,2929 ,1101,1072,1103 ,0,0,0}, {2961,2955,2953 ,1104,1106,1074 ,0,0,0}, - {2147,2968,2142 ,1107,1105,324 ,0,0,0}, {2955,2961,2968 ,1106,1104,1105 ,0,0,0} -// BladeProtector2.prt - , {2997,2998,2999 ,324,2573,2574 ,0,0,0}, {3000,3001,3002 ,2575,2576,2577 ,0,0,0}, - {3003,2997,2999 ,2578,324,2574 ,0,0,0}, {3002,3001,3003 ,2577,2576,2578 ,0,0,0}, - {3001,3000,3004 ,2576,2575,2579 ,0,0,0}, {2999,3002,3003 ,2574,2577,2578 ,0,0,0}, - {3005,3006,3007 ,2580,2581,2582 ,0,0,0}, {3006,3008,3007 ,2581,2583,2582 ,0,0,0}, - {3004,3009,3005 ,2579,2584,2580 ,0,0,0}, {3006,3005,3009 ,2581,2580,2584 ,0,0,0}, - {3010,3011,3012 ,126,2585,2586 ,0,0,0}, {3013,3014,3008 ,2587,2588,2583 ,0,0,0}, - {3011,3014,3013 ,2585,2588,2587 ,0,0,0}, {3011,3013,3012 ,2585,2587,2586 ,0,0,0}, - {3012,3015,3010 ,2586,2589,126 ,0,0,0}, {3007,3008,3014 ,2582,2583,2588 ,0,0,0}, - {3004,3000,3009 ,2579,2575,2584 ,0,0,0}, {2997,3016,2998 ,324,2590,2573 ,0,0,0}, - {3017,3016,3018 ,2591,2590,2592 ,0,0,0}, {3016,3017,2998 ,2590,2591,2573 ,0,0,0}, - {3019,3020,3018 ,2593,2594,2592 ,0,0,0}, {3017,3018,3020 ,2591,2592,2594 ,0,0,0}, - {3019,3021,3022 ,2593,2595,2596 ,0,0,0}, {3022,3020,3019 ,2596,2594,2593 ,0,0,0}, - {3023,3021,3024 ,2597,2595,2598 ,0,0,0}, {3021,3023,3022 ,2595,2597,2596 ,0,0,0}, - {3025,3026,3024 ,2599,139,2598 ,0,0,0}, {3023,3024,3026 ,2597,2598,139 ,0,0,0}, - {3025,3027,3028 ,2599,2600,53 ,0,0,0}, {3028,3026,3025 ,53,139,2599 ,0,0,0}, - {3029,3027,3030 ,2601,2600,2602 ,0,0,0}, {3027,3029,3028 ,2600,2601,53 ,0,0,0}, - {3031,3032,3033 ,324,2603,324 ,0,0,0}, {3034,3035,3036 ,2604,2605,2606 ,0,0,0}, - {3037,3031,3033 ,2607,324,324 ,0,0,0}, {3036,3035,3037 ,2606,2605,2607 ,0,0,0}, - {3035,3034,3038 ,2605,2604,2608 ,0,0,0}, {3033,3036,3037 ,324,2606,2607 ,0,0,0}, - {3039,3040,3041 ,2609,2610,2611 ,0,0,0}, {3040,3042,3041 ,2610,2612,2611 ,0,0,0}, - {3038,3043,3039 ,2608,2613,2609 ,0,0,0}, {3040,3039,3043 ,2610,2609,2613 ,0,0,0}, - {3044,3045,3046 ,2614,2615,2616 ,0,0,0}, {3047,3048,3042 ,2617,2618,2612 ,0,0,0}, - {3045,3048,3047 ,2615,2618,2617 ,0,0,0}, {3045,3047,3046 ,2615,2617,2616 ,0,0,0}, - {3046,3049,3044 ,2616,2619,2614 ,0,0,0}, {3041,3042,3048 ,2611,2612,2618 ,0,0,0}, - {3038,3034,3043 ,2608,2604,2613 ,0,0,0}, {3031,3050,3032 ,324,2620,2603 ,0,0,0}, - {3051,3050,3052 ,2621,2620,2622 ,0,0,0}, {3050,3051,3032 ,2620,2621,2603 ,0,0,0}, - {3053,3054,3052 ,2623,2624,2622 ,0,0,0}, {3051,3052,3054 ,2621,2622,2624 ,0,0,0}, - {3053,3055,3056 ,2623,2625,2626 ,0,0,0}, {3056,3054,3053 ,2626,2624,2623 ,0,0,0}, - {3057,3055,3058 ,2627,2625,2598 ,0,0,0}, {3055,3057,3056 ,2625,2627,2626 ,0,0,0}, - {3059,3060,3058 ,111,139,2598 ,0,0,0}, {3057,3058,3060 ,2627,2598,139 ,0,0,0}, - {3059,3061,3062 ,111,2628,2629 ,0,0,0}, {3062,3060,3059 ,2629,139,111 ,0,0,0}, - {3063,3061,3064 ,2630,2628,82 ,0,0,0}, {3061,3063,3062 ,2628,2630,2629 ,0,0,0}, - {3065,3066,3067 ,2631,2632,2631 ,0,0,0}, {3068,3069,3070 ,2633,2634,2635 ,0,0,0}, - {3068,3067,3069 ,2633,2631,2634 ,0,0,0}, {3070,3069,3071 ,2635,2634,2635 ,0,0,0}, - {3067,3068,3065 ,2631,2633,2631 ,0,0,0}, {3072,3066,3065 ,2632,2632,2631 ,0,0,0}, - {3073,3072,3074 ,2636,2632,2636 ,0,0,0}, {3072,3073,3066 ,2632,2636,2632 ,0,0,0}, - {3075,3076,3077 ,1273,1278,1273 ,0,0,0}, {3078,3076,3079 ,1278,1278,1276 ,0,0,0}, - {3076,3078,3077 ,1278,1278,1273 ,0,0,0}, {3080,3081,3079 ,1277,1276,1276 ,0,0,0}, - {3078,3079,3081 ,1278,1276,1276 ,0,0,0}, {3080,3082,3083 ,1277,2637,1277 ,0,0,0}, - {3083,3081,3080 ,1277,1276,1277 ,0,0,0}, {3082,3084,3083 ,2637,2638,1277 ,0,0,0}, - {3085,3075,3077 ,1274,1273,1273 ,0,0,0}, {3086,3087,3085 ,1275,1274,1274 ,0,0,0}, - {3075,3085,3087 ,1273,1274,1274 ,0,0,0}, {3086,3088,3089 ,1275,1270,1275 ,0,0,0}, - {3089,3087,3086 ,1275,1274,1275 ,0,0,0}, {3090,3088,3091 ,1270,1270,2639 ,0,0,0}, - {3088,3090,3089 ,1270,1270,1275 ,0,0,0}, {3090,3091,3092 ,1270,2639,2640 ,0,0,0}, - {3093,3094,3095 ,2641,2642,2643 ,0,0,0}, {3096,3097,3093 ,2644,2645,2641 ,0,0,0}, - {3093,3095,3096 ,2641,2643,2644 ,0,0,0}, {3097,3098,3099 ,2645,2646,2647 ,0,0,0}, - {3098,3097,3096 ,2646,2645,2644 ,0,0,0}, {3100,3099,3101 ,2648,2647,2649 ,0,0,0}, - {3098,3101,3099 ,2646,2649,2647 ,0,0,0}, {3102,3103,3100 ,2650,2651,2648 ,0,0,0}, - {3100,3101,3102 ,2648,2649,2650 ,0,0,0}, {3103,3104,3105 ,2651,2652,2653 ,0,0,0}, - {3104,3103,3102 ,2652,2651,2650 ,0,0,0}, {3106,3105,3107 ,2654,2653,2655 ,0,0,0}, - {3104,3107,3105 ,2652,2655,2653 ,0,0,0}, {3108,3109,3106 ,2656,2657,2654 ,0,0,0}, - {3106,3107,3108 ,2654,2655,2656 ,0,0,0}, {3109,3110,3111 ,2657,2658,2659 ,0,0,0}, - {3110,3109,3108 ,2658,2657,2656 ,0,0,0}, {3112,3111,3113 ,2660,2659,2661 ,0,0,0}, - {3110,3113,3111 ,2658,2661,2659 ,0,0,0}, {3114,3115,3112 ,2662,2663,2660 ,0,0,0}, - {3112,3113,3114 ,2660,2661,2662 ,0,0,0}, {3115,3116,3117 ,2663,2664,2665 ,0,0,0}, - {3116,3115,3114 ,2664,2663,2662 ,0,0,0}, {3118,3117,3119 ,2666,2665,2667 ,0,0,0}, - {3116,3119,3117 ,2664,2667,2665 ,0,0,0}, {3120,3121,3118 ,2668,2669,2666 ,0,0,0}, - {3118,3119,3120 ,2666,2667,2668 ,0,0,0}, {3121,3122,3123 ,2669,2670,2671 ,0,0,0}, - {3122,3121,3120 ,2670,2669,2668 ,0,0,0}, {3124,3123,3125 ,2672,2671,2673 ,0,0,0}, - {3122,3125,3123 ,2670,2673,2671 ,0,0,0}, {3126,3127,3124 ,2674,2675,2672 ,0,0,0}, - {3124,3125,3126 ,2672,2673,2674 ,0,0,0}, {3127,3128,3129 ,2675,2676,2677 ,0,0,0}, - {3128,3127,3126 ,2676,2675,2674 ,0,0,0}, {3130,3129,3131 ,2678,2677,2679 ,0,0,0}, - {3128,3131,3129 ,2676,2679,2677 ,0,0,0}, {3132,3133,3130 ,2680,2680,2678 ,0,0,0}, - {3130,3131,3132 ,2678,2679,2680 ,0,0,0}, {3095,3094,3134 ,2643,2642,2681 ,0,0,0}, - {3135,3134,3136 ,2682,2681,2683 ,0,0,0}, {3094,3136,3134 ,2642,2683,2681 ,0,0,0}, - {3137,3138,3135 ,2684,2685,2682 ,0,0,0}, {3135,3136,3137 ,2682,2683,2684 ,0,0,0}, - {3138,3139,3140 ,2685,2686,2687 ,0,0,0}, {3139,3138,3137 ,2686,2685,2684 ,0,0,0}, - {3141,3140,3142 ,2688,2687,2689 ,0,0,0}, {3139,3142,3140 ,2686,2689,2687 ,0,0,0}, - {3143,3144,3141 ,2690,2691,2688 ,0,0,0}, {3141,3142,3143 ,2688,2689,2690 ,0,0,0}, - {3144,3145,3146 ,2691,2692,2693 ,0,0,0}, {3145,3144,3143 ,2692,2691,2690 ,0,0,0}, - {3147,3146,3148 ,2694,2693,2695 ,0,0,0}, {3145,3148,3146 ,2692,2695,2693 ,0,0,0}, - {3149,3150,3147 ,2696,2697,2694 ,0,0,0}, {3147,3148,3149 ,2694,2695,2696 ,0,0,0}, - {3150,3151,3152 ,2697,2698,2699 ,0,0,0}, {3151,3150,3149 ,2698,2697,2696 ,0,0,0}, - {3153,3152,3154 ,2700,2699,2701 ,0,0,0}, {3151,3154,3152 ,2698,2701,2699 ,0,0,0}, - {3155,3156,3153 ,2702,2703,2700 ,0,0,0}, {3153,3154,3155 ,2700,2701,2702 ,0,0,0}, - {3156,3157,3158 ,2703,2704,2705 ,0,0,0}, {3157,3156,3155 ,2704,2703,2702 ,0,0,0}, - {3159,3158,3160 ,2706,2705,2707 ,0,0,0}, {3157,3160,3158 ,2704,2707,2705 ,0,0,0}, - {3161,3162,3159 ,2708,2709,2706 ,0,0,0}, {3159,3160,3161 ,2706,2707,2708 ,0,0,0}, - {3162,3163,3164 ,2709,2710,2711 ,0,0,0}, {3163,3162,3161 ,2710,2709,2708 ,0,0,0}, - {3165,3164,3166 ,2712,2711,2713 ,0,0,0}, {3163,3166,3164 ,2710,2713,2711 ,0,0,0}, - {3167,3168,3165 ,2714,2715,2712 ,0,0,0}, {3165,3166,3167 ,2712,2713,2714 ,0,0,0}, - {3168,3169,3170 ,2715,2716,2717 ,0,0,0}, {3169,3168,3167 ,2716,2715,2714 ,0,0,0}, - {3169,3171,3170 ,2716,2718,2717 ,0,0,0}, {3170,3171,3172 ,2717,2718,2719 ,0,0,0}, - {3173,3174,3171 ,2720,2720,2721 ,0,0,0}, {3173,3175,3174 ,2720,2722,2720 ,0,0,0}, - {3175,3173,3176 ,2722,2720,2722 ,0,0,0}, {3172,3171,3174 ,82,2721,2720 ,0,0,0}, - {3177,3178,3179 ,2038,2723,2038 ,0,0,0}, {3180,3181,3178 ,2724,2725,2723 ,0,0,0}, - {3178,3181,3179 ,2723,2725,2038 ,0,0,0}, {3182,3183,3180 ,2726,2727,2724 ,0,0,0}, - {3180,3178,3182 ,2724,2723,2726 ,0,0,0}, {3183,3184,3185 ,2727,2728,2729 ,0,0,0}, - {3184,3183,3182 ,2728,2727,2726 ,0,0,0}, {3186,3185,3187 ,2730,2729,2731 ,0,0,0}, - {3184,3187,3185 ,2728,2731,2729 ,0,0,0}, {3188,3186,3189 ,2732,2730,2733 ,0,0,0}, - {3186,3187,3189 ,2730,2731,2733 ,0,0,0}, {3190,3186,3188 ,2732,2730,2732 ,0,0,0}, - {3191,3177,3179 ,2734,2038,2038 ,0,0,0}, {3192,3191,3193 ,2735,2734,2736 ,0,0,0}, - {3192,3177,3191 ,2735,2038,2734 ,0,0,0}, {3194,3193,3195 ,2737,2736,2738 ,0,0,0}, - {3191,3195,3193 ,2734,2738,2736 ,0,0,0}, {3196,3197,3194 ,2739,2740,2737 ,0,0,0}, - {3194,3195,3196 ,2737,2738,2739 ,0,0,0}, {3197,3198,3199 ,2740,2741,2742 ,0,0,0}, - {3198,3197,3196 ,2741,2740,2739 ,0,0,0}, {3199,3200,3073 ,2742,2743,2636 ,0,0,0}, - {3198,3200,3199 ,2741,2743,2742 ,0,0,0}, {3199,3073,3074 ,2742,2636,2636 ,0,0,0}, - {3201,3202,3203 ,2744,2745,2746 ,0,0,0}, {3201,3204,3205 ,2744,2747,2748 ,0,0,0}, - {3203,3202,3206 ,2746,2745,2749 ,0,0,0}, {3206,3202,3207 ,2749,2745,2750 ,0,0,0}, - {3206,3207,3208 ,2749,2750,2751 ,0,0,0}, {3209,3208,3207 ,2752,2751,2750 ,0,0,0}, - {3208,3209,3210 ,2751,2752,2753 ,0,0,0}, {3211,3210,3209 ,2754,2753,2752 ,0,0,0}, - {3211,3212,3213 ,2754,2755,2756 ,0,0,0}, {3210,3211,3213 ,2753,2754,2756 ,0,0,0}, - {3203,3204,3201 ,2746,2747,2744 ,0,0,0}, {3213,3212,3214 ,2756,2755,2757 ,0,0,0}, - {3215,3214,3216 ,2758,2757,2759 ,0,0,0}, {3216,3214,3212 ,2759,2757,2755 ,0,0,0}, - {3215,3216,3217 ,2758,2759,2758 ,0,0,0}, {3218,3205,3219 ,2760,2748,2761 ,0,0,0}, - {3204,3219,3205 ,2747,2761,2748 ,0,0,0}, {3220,3221,3218 ,2762,2763,2760 ,0,0,0}, - {3218,3219,3220 ,2760,2761,2762 ,0,0,0}, {3221,3222,3223 ,2763,2764,2765 ,0,0,0}, - {3222,3221,3220 ,2764,2763,2762 ,0,0,0}, {3224,3223,3225 ,2766,2765,2767 ,0,0,0}, - {3222,3225,3223 ,2764,2767,2765 ,0,0,0}, {3226,3227,3224 ,2768,2769,2766 ,0,0,0}, - {3224,3225,3226 ,2766,2767,2768 ,0,0,0}, {3227,3228,3229 ,2769,2770,2771 ,0,0,0}, - {3228,3227,3226 ,2770,2769,2768 ,0,0,0}, {3230,3229,3231 ,2772,2771,2773 ,0,0,0}, - {3228,3231,3229 ,2770,2773,2771 ,0,0,0}, {3230,3231,3232 ,2772,2773,2772 ,0,0,0}, - {3233,3234,3235 ,2774,2775,2774 ,0,0,0}, {3235,3236,3233 ,2774,2776,2774 ,0,0,0}, - {3237,3238,3234 ,2775,2777,2775 ,0,0,0}, {3239,3236,3235 ,2776,2776,2774 ,0,0,0}, - {3233,3237,3234 ,2774,2775,2775 ,0,0,0}, {3237,3240,3238 ,2775,2777,2777 ,0,0,0}, - {3241,3240,3242 ,2778,2777,2778 ,0,0,0}, {3242,3230,3232 ,2778,2772,2772 ,0,0,0}, - {3241,3238,3240 ,2778,2777,2777 ,0,0,0}, {3242,3232,3241 ,2778,2772,2778 ,0,0,0}, - {3243,3239,3244 ,2779,2776,2779 ,0,0,0}, {3239,3243,3236 ,2776,2779,2776 ,0,0,0}, - {3245,3246,3244 ,2780,2780,2779 ,0,0,0}, {3243,3244,3246 ,2779,2779,2780 ,0,0,0}, - {3245,3247,3248 ,2780,2781,2781 ,0,0,0}, {3248,3246,3245 ,2781,2780,2780 ,0,0,0}, - {3249,3247,3250 ,2782,2781,2782 ,0,0,0}, {3247,3249,3248 ,2781,2782,2781 ,0,0,0}, - {3249,3250,3091 ,2782,2782,2783 ,0,0,0}, {3091,3250,3092 ,2783,2782,2784 ,0,0,0}, - {3251,3084,3082 ,1888,2785,2786 ,0,0,0}, {3252,3253,3254 ,1207,1886,1886 ,0,0,0}, - {3255,3256,3257 ,1887,1887,1888 ,0,0,0}, {3258,3259,3260 ,1882,1882,1883 ,0,0,0}, - {3261,3262,3263 ,1207,1881,1881 ,0,0,0}, {3264,3265,3260 ,2787,1883,1883 ,0,0,0}, - {3258,3260,3265 ,1882,1883,1883 ,0,0,0}, {3266,3265,3264 ,2788,1883,2787 ,0,0,0}, - {3262,3259,3263 ,1881,1882,1881 ,0,0,0}, {3263,3259,3258 ,1881,1882,1882 ,0,0,0}, - {3261,3253,3252 ,1207,1886,1207 ,0,0,0}, {3261,3252,3262 ,1207,1207,1881 ,0,0,0}, - {3254,3256,3255 ,1886,1887,1887 ,0,0,0}, {3253,3256,3254 ,1886,1887,1886 ,0,0,0}, - {3251,3257,3084 ,1888,1888,2785 ,0,0,0}, {3255,3257,3251 ,1887,1888,1888 ,0,0,0}, - {3267,3268,3269 ,2789,2789,2790 ,0,0,0}, {3269,3268,3270 ,2790,2789,2790 ,0,0,0}, - {3268,3267,3271 ,2789,2789,2791 ,0,0,0}, {3272,3271,3267 ,2792,2791,2789 ,0,0,0}, - {3273,3274,3272 ,2793,2793,2792 ,0,0,0}, {3275,3269,3270 ,2794,2790,2790 ,0,0,0}, - {3266,3264,3273 ,2795,2796,2793 ,0,0,0}, {3274,3273,3264 ,2793,2793,2796 ,0,0,0}, - {3272,3274,3271 ,2792,2793,2791 ,0,0,0}, {3276,3275,3277 ,2797,2794,2794 ,0,0,0}, - {3270,3277,3275 ,2790,2794,2794 ,0,0,0}, {3278,3279,3276 ,2797,2798,2797 ,0,0,0}, - {3276,3277,3278 ,2797,2794,2797 ,0,0,0}, {3279,3280,3281 ,2798,2798,2799 ,0,0,0}, - {3280,3279,3278 ,2798,2798,2797 ,0,0,0}, {3282,3281,3283 ,2800,2799,2799 ,0,0,0}, - {3280,3283,3281 ,2798,2799,2799 ,0,0,0}, {3282,3283,3284 ,2800,2799,2800 ,0,0,0}, - {3285,3286,3287 ,2801,2801,2802 ,0,0,0}, {3288,3289,3287 ,2803,2804,2802 ,0,0,0}, - {3285,3287,3289 ,2801,2802,2804 ,0,0,0}, {3288,3290,3291 ,2803,2805,2806 ,0,0,0}, - {3291,3289,3288 ,2806,2804,2803 ,0,0,0}, {3292,3290,3293 ,2807,2805,2808 ,0,0,0}, - {3290,3292,3291 ,2805,2807,2806 ,0,0,0}, {3294,3295,3293 ,2809,2810,2808 ,0,0,0}, - {3292,3293,3295 ,2807,2808,2810 ,0,0,0}, {3294,3296,3297 ,2809,2811,2812 ,0,0,0}, - {3297,3295,3294 ,2812,2810,2809 ,0,0,0}, {3298,3296,3299 ,2813,2811,2814 ,0,0,0}, - {3296,3298,3297 ,2811,2813,2812 ,0,0,0}, {3300,3301,3299 ,2815,2816,2814 ,0,0,0}, - {3298,3299,3301 ,2813,2814,2816 ,0,0,0}, {3300,3302,3303 ,2815,2817,2818 ,0,0,0}, - {3303,3301,3300 ,2818,2816,2815 ,0,0,0}, {3304,3302,3305 ,2819,2817,2820 ,0,0,0}, - {3302,3304,3303 ,2817,2819,2818 ,0,0,0}, {3306,3307,3305 ,2821,2822,2820 ,0,0,0}, - {3304,3305,3307 ,2819,2820,2822 ,0,0,0}, {3306,3308,3309 ,2821,2823,2824 ,0,0,0}, - {3309,3307,3306 ,2824,2822,2821 ,0,0,0}, {3310,3308,3311 ,2825,2823,2826 ,0,0,0}, - {3308,3310,3309 ,2823,2825,2824 ,0,0,0}, {3312,3313,3311 ,2827,2828,2826 ,0,0,0}, - {3310,3311,3313 ,2825,2826,2828 ,0,0,0}, {3312,3314,3315 ,2827,2829,2830 ,0,0,0}, - {3315,3313,3312 ,2830,2828,2827 ,0,0,0}, {3316,3314,3317 ,2831,2829,2832 ,0,0,0}, - {3314,3316,3315 ,2829,2831,2830 ,0,0,0}, {3282,3318,3317 ,2800,2833,2832 ,0,0,0}, - {3316,3317,3318 ,2831,2832,2833 ,0,0,0}, {3284,3318,3282 ,2800,2833,2800 ,0,0,0}, - {3319,3286,3285 ,2834,2801,2801 ,0,0,0}, {3320,3319,3321 ,2835,2834,2836 ,0,0,0}, - {3319,3320,3286 ,2834,2835,2801 ,0,0,0}, {3322,3323,3321 ,2837,2838,2836 ,0,0,0}, - {3320,3321,3323 ,2835,2836,2838 ,0,0,0}, {3322,3324,3325 ,2837,2839,2840 ,0,0,0}, - {3325,3323,3322 ,2840,2838,2837 ,0,0,0}, {3326,3324,3327 ,2841,2839,2842 ,0,0,0}, - {3324,3326,3325 ,2839,2841,2840 ,0,0,0}, {3328,3329,3327 ,2843,2844,2842 ,0,0,0}, - {3326,3327,3329 ,2841,2842,2844 ,0,0,0}, {3328,3330,3331 ,2843,2845,2846 ,0,0,0}, - {3331,3329,3328 ,2846,2844,2843 ,0,0,0}, {3332,3330,3333 ,2847,2845,2848 ,0,0,0}, - {3330,3332,3331 ,2845,2847,2846 ,0,0,0}, {3334,3335,3333 ,2849,2850,2848 ,0,0,0}, - {3332,3333,3335 ,2847,2848,2850 ,0,0,0}, {3334,3336,3337 ,2849,2851,2852 ,0,0,0}, - {3337,3335,3334 ,2852,2850,2849 ,0,0,0}, {3338,3336,3339 ,2853,2851,2854 ,0,0,0}, - {3336,3338,3337 ,2851,2853,2852 ,0,0,0}, {3340,3341,3339 ,2855,2856,2854 ,0,0,0}, - {3338,3339,3341 ,2853,2854,2856 ,0,0,0}, {3340,3342,3343 ,2855,2857,2858 ,0,0,0}, - {3343,3341,3340 ,2858,2856,2855 ,0,0,0}, {3344,3342,3345 ,2859,2857,2860 ,0,0,0}, - {3342,3344,3343 ,2857,2859,2858 ,0,0,0}, {3346,3347,3345 ,2861,2862,2860 ,0,0,0}, - {3344,3345,3347 ,2859,2860,2862 ,0,0,0}, {3346,3348,3349 ,2861,2863,2864 ,0,0,0}, - {3349,3347,3346 ,2864,2862,2861 ,0,0,0}, {3350,3348,3351 ,2865,2863,2866 ,0,0,0}, - {3348,3350,3349 ,2863,2865,2864 ,0,0,0}, {3350,3351,3352 ,2865,2866,2866 ,0,0,0}, - {3353,3351,3354 ,2162,2867,2162 ,0,0,0}, {3351,3353,3352 ,2867,2162,2867 ,0,0,0}, - {3355,3356,3357 ,2868,2869,2870 ,0,0,0}, {3358,3359,3360 ,2871,2872,2873 ,0,0,0}, - {3361,3355,3357 ,2874,2868,2870 ,0,0,0}, {3359,3357,3356 ,2872,2870,2869 ,0,0,0}, - {3362,3355,3361 ,2875,2868,2874 ,0,0,0}, {3363,3364,3365 ,2876,2877,2878 ,0,0,0}, - {3362,3361,3363 ,2875,2874,2876 ,0,0,0}, {3366,3364,3367 ,2879,2877,2880 ,0,0,0}, - {3363,3365,3362 ,2876,2878,2875 ,0,0,0}, {3364,3366,3365 ,2877,2879,2878 ,0,0,0}, - {3367,3368,3369 ,2880,2881,2882 ,0,0,0}, {3356,3360,3359 ,2869,2873,2872 ,0,0,0}, - {3370,3371,3372 ,2883,2884,2885 ,0,0,0}, {3373,3369,3368 ,2886,2882,2881 ,0,0,0}, - {3373,3374,3375 ,2886,2887,2888 ,0,0,0}, {3370,3372,3375 ,2883,2885,2888 ,0,0,0}, - {3370,3375,3374 ,2883,2888,2887 ,0,0,0}, {3372,3371,3376 ,2885,2884,2889 ,0,0,0}, - {3377,3378,3379 ,2890,2891,2892 ,0,0,0}, {3376,3377,3379 ,2889,2890,2892 ,0,0,0}, - {3377,3376,3371 ,2890,2889,2884 ,0,0,0}, {3378,3380,3379 ,2891,2893,2892 ,0,0,0}, - {3374,3373,3368 ,2887,2886,2881 ,0,0,0}, {3380,3381,3382 ,2893,2894,2895 ,0,0,0}, - {3380,3378,3381 ,2893,2891,2894 ,0,0,0}, {3383,3384,3385 ,2896,2897,2898 ,0,0,0}, - {3386,3385,3384 ,2899,2898,2897 ,0,0,0}, {3386,3387,3385 ,2899,2900,2898 ,0,0,0}, - {3387,3382,3381 ,2900,2895,2894 ,0,0,0}, {3387,3386,3382 ,2900,2899,2895 ,0,0,0}, - {3369,3366,3367 ,2882,2879,2880 ,0,0,0}, {3388,3389,3383 ,2901,2902,2896 ,0,0,0}, - {3390,3391,3388 ,2903,2904,2901 ,0,0,0}, {3354,3391,3390 ,1359,2904,2903 ,0,0,0}, - {3384,3383,3389 ,2897,2896,2902 ,0,0,0}, {3391,3389,3388 ,2904,2902,2901 ,0,0,0}, - {3353,3354,3390 ,1359,1359,2903 ,0,0,0}, {3392,3393,3358 ,2905,2906,2871 ,0,0,0}, - {3358,3360,3392 ,2871,2873,2905 ,0,0,0}, {3393,3394,3395 ,2906,2907,2908 ,0,0,0}, - {3394,3393,3392 ,2907,2906,2905 ,0,0,0}, {3396,3395,3397 ,2909,2908,2910 ,0,0,0}, - {3394,3397,3395 ,2907,2910,2908 ,0,0,0}, {3398,3399,3396 ,2911,2912,2909 ,0,0,0}, - {3396,3397,3398 ,2909,2910,2911 ,0,0,0}, {3399,3400,3401 ,2912,2913,2914 ,0,0,0}, - {3400,3399,3398 ,2913,2912,2911 ,0,0,0}, {3402,3401,3403 ,2915,2914,2916 ,0,0,0}, - {3400,3403,3401 ,2913,2916,2914 ,0,0,0}, {3404,3405,3402 ,2917,2918,2915 ,0,0,0}, - {3402,3403,3404 ,2915,2916,2917 ,0,0,0}, {3405,3406,3407 ,2918,2919,2920 ,0,0,0}, - {3406,3405,3404 ,2919,2918,2917 ,0,0,0}, {3408,3407,3409 ,2921,2920,2922 ,0,0,0}, - {3406,3409,3407 ,2919,2922,2920 ,0,0,0}, {3410,3411,3408 ,2923,2924,2921 ,0,0,0}, - {3408,3409,3410 ,2921,2922,2923 ,0,0,0}, {3411,3412,3413 ,2924,2925,2926 ,0,0,0}, - {3412,3411,3410 ,2925,2924,2923 ,0,0,0}, {3414,3413,3415 ,2927,2926,2928 ,0,0,0}, - {3412,3415,3413 ,2925,2928,2926 ,0,0,0}, {3416,3417,3414 ,2929,2930,2927 ,0,0,0}, - {3414,3415,3416 ,2927,2928,2929 ,0,0,0}, {3417,3418,3419 ,2930,2931,2932 ,0,0,0}, - {3418,3417,3416 ,2931,2930,2929 ,0,0,0}, {3420,3419,3421 ,2933,2932,2934 ,0,0,0}, - {3418,3421,3419 ,2931,2934,2932 ,0,0,0}, {3422,3423,3420 ,2935,2936,2933 ,0,0,0}, - {3420,3421,3422 ,2933,2934,2935 ,0,0,0}, {3423,3424,3425 ,2936,2937,2938 ,0,0,0}, - {3424,3423,3422 ,2937,2936,2935 ,0,0,0}, {3426,3425,3427 ,1711,2938,2939 ,0,0,0}, - {3424,3427,3425 ,2937,2939,2938 ,0,0,0}, {3426,3427,3428 ,1711,2939,1711 ,0,0,0}, - {3429,3430,3431 ,1398,1398,1398 ,0,0,0}, {3430,3429,3432 ,1398,1398,1398 ,0,0,0}, - {3433,3434,3435 ,2940,2941,2942 ,0,0,0}, {3436,3437,3438 ,2943,2944,2945 ,0,0,0}, - {3434,3439,3435 ,2941,2946,2942 ,0,0,0}, {3433,3435,3440 ,2940,2942,2947 ,0,0,0}, - {3436,3433,3440 ,2943,2940,2947 ,0,0,0}, {3441,3442,3439 ,2948,2949,2946 ,0,0,0}, - {3441,3439,3434 ,2948,2946,2941 ,0,0,0}, {3443,3444,3445 ,2950,2951,2952 ,0,0,0}, - {3442,3441,3443 ,2949,2948,2950 ,0,0,0}, {3443,3445,3442 ,2950,2952,2949 ,0,0,0}, - {3444,3446,3445 ,2951,2953,2952 ,0,0,0}, {3437,3436,3440 ,2944,2943,2947 ,0,0,0}, - {3444,3447,3446 ,2951,2954,2953 ,0,0,0}, {3448,3449,3450 ,2955,2956,2957 ,0,0,0}, - {3448,3450,3447 ,2955,2957,2954 ,0,0,0}, {3449,3448,3451 ,2956,2955,2958 ,0,0,0}, - {3452,3453,3451 ,2959,2960,2958 ,0,0,0}, {3453,3449,3451 ,2960,2956,2958 ,0,0,0}, - {3454,3455,3456 ,2961,2962,2963 ,0,0,0}, {3453,3452,3457 ,2960,2959,2964 ,0,0,0}, - {3458,3459,3457 ,2965,2966,2964 ,0,0,0}, {3455,3454,3459 ,2962,2961,2966 ,0,0,0}, - {3455,3459,3458 ,2962,2966,2965 ,0,0,0}, {3454,3456,3460 ,2961,2963,2967 ,0,0,0}, - {3452,3458,3457 ,2959,2965,2964 ,0,0,0}, {3461,3460,3462 ,2968,2967,2969 ,0,0,0}, - {3461,3462,3463 ,2968,2969,2970 ,0,0,0}, {3462,3460,3456 ,2969,2967,2963 ,0,0,0}, - {3464,3465,3466 ,2971,2972,2973 ,0,0,0}, {3450,3446,3447 ,2957,2953,2954 ,0,0,0}, - {3464,3467,3463 ,2971,2974,2970 ,0,0,0}, {3467,3464,3466 ,2974,2971,2973 ,0,0,0}, - {3465,3468,3469 ,2972,2975,2976 ,0,0,0}, {3469,3466,3465 ,2976,2973,2972 ,0,0,0}, - {3470,3471,3468 ,2977,2978,2975 ,0,0,0}, {3469,3468,3471 ,2976,2975,2978 ,0,0,0}, - {3470,3432,3429 ,2977,2979,2979 ,0,0,0}, {3470,3429,3471 ,2977,2979,2978 ,0,0,0}, - {3463,3467,3461 ,2970,2974,2968 ,0,0,0}, {3472,3438,3473 ,2980,2945,2981 ,0,0,0}, - {3437,3473,3438 ,2944,2981,2945 ,0,0,0}, {3474,3475,3472 ,2982,2983,2980 ,0,0,0}, - {3472,3473,3474 ,2980,2981,2982 ,0,0,0}, {3475,3476,3477 ,2983,2984,2985 ,0,0,0}, - {3476,3475,3474 ,2984,2983,2982 ,0,0,0}, {3478,3477,3479 ,2986,2985,2987 ,0,0,0}, - {3476,3479,3477 ,2984,2987,2985 ,0,0,0}, {3480,3481,3478 ,2988,2989,2986 ,0,0,0}, - {3478,3479,3480 ,2986,2987,2988 ,0,0,0}, {3481,3482,3483 ,2989,2990,2991 ,0,0,0}, - {3482,3481,3480 ,2990,2989,2988 ,0,0,0}, {3484,3483,3485 ,2992,2991,2993 ,0,0,0}, - {3482,3485,3483 ,2990,2993,2991 ,0,0,0}, {3486,3487,3484 ,2994,2995,2992 ,0,0,0}, - {3484,3485,3486 ,2992,2993,2994 ,0,0,0}, {3487,3488,3489 ,2995,2996,2997 ,0,0,0}, - {3488,3487,3486 ,2996,2995,2994 ,0,0,0}, {3490,3489,3491 ,2998,2997,2999 ,0,0,0}, - {3488,3491,3489 ,2996,2999,2997 ,0,0,0}, {3492,3493,3490 ,3000,3001,2998 ,0,0,0}, - {3490,3491,3492 ,2998,2999,3000 ,0,0,0}, {3493,3494,3495 ,3001,3002,3003 ,0,0,0}, - {3494,3493,3492 ,3002,3001,3000 ,0,0,0}, {3496,3495,3497 ,3004,3003,3005 ,0,0,0}, - {3494,3497,3495 ,3002,3005,3003 ,0,0,0}, {3498,3499,3496 ,3006,3007,3004 ,0,0,0}, - {3496,3497,3498 ,3004,3005,3006 ,0,0,0}, {3499,3500,3501 ,3007,3008,3009 ,0,0,0}, - {3500,3499,3498 ,3008,3007,3006 ,0,0,0}, {3502,3501,3503 ,3010,3009,3011 ,0,0,0}, - {3500,3503,3501 ,3008,3011,3009 ,0,0,0}, {3504,3505,3502 ,3012,3013,3010 ,0,0,0}, - {3502,3503,3504 ,3010,3011,3012 ,0,0,0}, {3505,3506,3507 ,3013,3014,3015 ,0,0,0}, - {3506,3505,3504 ,3014,3013,3012 ,0,0,0}, {3508,3507,3509 ,3016,3015,3017 ,0,0,0}, - {3506,3509,3507 ,3014,3017,3015 ,0,0,0}, {3508,3509,3510 ,3016,3017,3018 ,0,0,0}, - {3511,3512,3513 ,3019,3020,3021 ,0,0,0}, {3514,3515,3513 ,3022,3023,3021 ,0,0,0}, - {3511,3513,3515 ,3019,3021,3023 ,0,0,0}, {3514,3516,3517 ,3022,3024,3025 ,0,0,0}, - {3517,3515,3514 ,3025,3023,3022 ,0,0,0}, {3518,3516,3519 ,3026,3024,3027 ,0,0,0}, - {3516,3518,3517 ,3024,3026,3025 ,0,0,0}, {3520,3521,3519 ,3028,3029,3027 ,0,0,0}, - {3518,3519,3521 ,3026,3027,3029 ,0,0,0}, {3520,3522,3523 ,3028,3030,3031 ,0,0,0}, - {3523,3521,3520 ,3031,3029,3028 ,0,0,0}, {3524,3522,3525 ,3032,3030,3033 ,0,0,0}, - {3522,3524,3523 ,3030,3032,3031 ,0,0,0}, {3526,3527,3525 ,3034,3035,3033 ,0,0,0}, - {3524,3525,3527 ,3032,3033,3035 ,0,0,0}, {3526,3528,3529 ,3034,3036,3037 ,0,0,0}, - {3529,3527,3526 ,3037,3035,3034 ,0,0,0}, {3530,3528,3531 ,3038,3036,3039 ,0,0,0}, - {3528,3530,3529 ,3036,3038,3037 ,0,0,0}, {3532,3533,3531 ,3040,3041,3039 ,0,0,0}, - {3530,3531,3533 ,3038,3039,3041 ,0,0,0}, {3532,3534,3535 ,3040,3042,3043 ,0,0,0}, - {3535,3533,3532 ,3043,3041,3040 ,0,0,0}, {3536,3534,3537 ,3044,3042,3045 ,0,0,0}, - {3534,3536,3535 ,3042,3044,3043 ,0,0,0}, {3538,3539,3537 ,3046,3047,3045 ,0,0,0}, - {3536,3537,3539 ,3044,3045,3047 ,0,0,0}, {3538,3540,3541 ,3046,3048,3049 ,0,0,0}, - {3541,3539,3538 ,3049,3047,3046 ,0,0,0}, {3542,3540,3543 ,3050,3048,3051 ,0,0,0}, - {3540,3542,3541 ,3048,3050,3049 ,0,0,0}, {3544,3545,3543 ,3052,3053,3051 ,0,0,0}, - {3542,3543,3545 ,3050,3051,3053 ,0,0,0}, {3544,3546,3547 ,3052,3054,3055 ,0,0,0}, - {3547,3545,3544 ,3055,3053,3052 ,0,0,0}, {3548,3546,3549 ,3056,3054,3057 ,0,0,0}, - {3546,3548,3547 ,3054,3056,3055 ,0,0,0}, {3550,3551,3549 ,3058,3059,3057 ,0,0,0}, - {3548,3549,3551 ,3056,3057,3059 ,0,0,0}, {3550,3552,3553 ,3058,3060,3061 ,0,0,0}, - {3553,3551,3550 ,3061,3059,3058 ,0,0,0}, {3554,3552,3555 ,3062,3060,3063 ,0,0,0}, - {3552,3554,3553 ,3060,3062,3061 ,0,0,0}, {3556,3557,3555 ,3064,3065,3063 ,0,0,0}, - {3554,3555,3557 ,3062,3063,3065 ,0,0,0}, {3556,3558,3559 ,3064,3066,3067 ,0,0,0}, - {3559,3557,3556 ,3067,3065,3064 ,0,0,0}, {3560,3558,3561 ,3068,3066,3069 ,0,0,0}, - {3558,3560,3559 ,3066,3068,3067 ,0,0,0}, {3562,3563,3561 ,3070,3071,3069 ,0,0,0}, - {3560,3561,3563 ,3068,3069,3071 ,0,0,0}, {3562,3564,3565 ,3070,3072,3073 ,0,0,0}, - {3565,3563,3562 ,3073,3071,3070 ,0,0,0}, {3566,3564,3567 ,3074,3072,3075 ,0,0,0}, - {3564,3566,3565 ,3072,3074,3073 ,0,0,0}, {3508,3568,3567 ,3076,3077,3075 ,0,0,0}, - {3566,3567,3568 ,3074,3075,3077 ,0,0,0}, {3510,3568,3508 ,3078,3077,3076 ,0,0,0}, - {3569,3512,3511 ,3079,3020,3019 ,0,0,0}, {3570,3569,3571 ,3080,3079,3081 ,0,0,0}, - {3569,3570,3512 ,3079,3080,3020 ,0,0,0}, {3572,3573,3571 ,3082,3083,3081 ,0,0,0}, - {3570,3571,3573 ,3080,3081,3083 ,0,0,0}, {3572,3574,3575 ,3082,3084,3085 ,0,0,0}, - {3575,3573,3572 ,3085,3083,3082 ,0,0,0}, {3576,3574,3577 ,3086,3084,3087 ,0,0,0}, - {3574,3576,3575 ,3084,3086,3085 ,0,0,0}, {3578,3579,3577 ,3088,3089,3087 ,0,0,0}, - {3576,3577,3579 ,3086,3087,3089 ,0,0,0}, {3578,3580,3581 ,3088,3090,3091 ,0,0,0}, - {3581,3579,3578 ,3091,3089,3088 ,0,0,0}, {3582,3580,3583 ,3092,3090,3093 ,0,0,0}, - {3580,3582,3581 ,3090,3092,3091 ,0,0,0}, {3584,3585,3583 ,3094,3095,3093 ,0,0,0}, - {3582,3583,3585 ,3092,3093,3095 ,0,0,0}, {3584,3586,3587 ,3094,3096,3097 ,0,0,0}, - {3587,3585,3584 ,3097,3095,3094 ,0,0,0}, {3588,3586,3589 ,3098,3096,3099 ,0,0,0}, - {3586,3588,3587 ,3096,3098,3097 ,0,0,0}, {3590,3591,3589 ,3100,3101,3099 ,0,0,0}, - {3588,3589,3591 ,3098,3099,3101 ,0,0,0}, {3590,3592,3593 ,3100,3102,3103 ,0,0,0}, - {3593,3591,3590 ,3103,3101,3100 ,0,0,0}, {3594,3592,3595 ,3104,3102,3105 ,0,0,0}, - {3592,3594,3593 ,3102,3104,3103 ,0,0,0}, {3596,3597,3595 ,3106,3107,3105 ,0,0,0}, - {3594,3595,3597 ,3104,3105,3107 ,0,0,0}, {3596,3598,3599 ,3106,3108,3109 ,0,0,0}, - {3599,3597,3596 ,3109,3107,3106 ,0,0,0}, {3600,3598,3601 ,3110,3108,3111 ,0,0,0}, - {3598,3600,3599 ,3108,3110,3109 ,0,0,0}, {3602,3603,3601 ,3112,3113,3111 ,0,0,0}, - {3600,3601,3603 ,3110,3111,3113 ,0,0,0}, {3602,3604,3605 ,3112,3114,3115 ,0,0,0}, - {3605,3603,3602 ,3115,3113,3112 ,0,0,0}, {3606,3604,3607 ,3116,3114,3117 ,0,0,0}, - {3604,3606,3605 ,3114,3116,3115 ,0,0,0}, {3608,3609,3607 ,3118,3119,3117 ,0,0,0}, - {3606,3607,3609 ,3116,3117,3119 ,0,0,0}, {3608,3610,3611 ,3118,3120,3121 ,0,0,0}, - {3611,3609,3608 ,3121,3119,3118 ,0,0,0}, {3612,3610,3613 ,3122,3120,3123 ,0,0,0}, - {3610,3612,3611 ,3120,3122,3121 ,0,0,0}, {3614,3615,3613 ,3124,3125,3123 ,0,0,0}, - {3612,3613,3615 ,3122,3123,3125 ,0,0,0}, {3614,3616,3617 ,3124,3126,3127 ,0,0,0}, - {3617,3615,3614 ,3127,3125,3124 ,0,0,0}, {3618,3616,3619 ,3128,3126,3129 ,0,0,0}, - {3616,3618,3617 ,3126,3128,3127 ,0,0,0}, {3620,3621,3619 ,3130,3131,3129 ,0,0,0}, - {3618,3619,3621 ,3128,3129,3131 ,0,0,0}, {3620,3622,3623 ,3130,3132,3133 ,0,0,0}, - {3623,3621,3620 ,3133,3131,3130 ,0,0,0}, {3624,3622,3625 ,3134,3132,126 ,0,0,0}, - {3622,3624,3623 ,3132,3134,3133 ,0,0,0}, {3624,3625,3626 ,3134,126,3135 ,0,0,0}, - {3627,3628,3629 ,3136,3137,3138 ,0,0,0}, {3630,3631,3632 ,3139,3140,3141 ,0,0,0}, - {3628,3633,3629 ,3137,3142,3138 ,0,0,0}, {3627,3629,3634 ,3136,3138,3143 ,0,0,0}, - {3630,3627,3634 ,3139,3136,3143 ,0,0,0}, {3635,3636,3633 ,3144,3145,3142 ,0,0,0}, - {3635,3633,3628 ,3144,3142,3137 ,0,0,0}, {3637,3638,3639 ,3146,3147,3148 ,0,0,0}, - {3636,3635,3637 ,3145,3144,3146 ,0,0,0}, {3637,3639,3636 ,3146,3148,3145 ,0,0,0}, - {3638,3640,3639 ,3147,3149,3148 ,0,0,0}, {3631,3630,3634 ,3140,3139,3143 ,0,0,0}, - {3638,3641,3640 ,3147,3150,3149 ,0,0,0}, {3642,3643,3644 ,3151,3152,3153 ,0,0,0}, - {3642,3644,3641 ,3151,3153,3150 ,0,0,0}, {3643,3642,3645 ,3152,3151,3154 ,0,0,0}, - {3646,3647,3645 ,3155,3156,3154 ,0,0,0}, {3647,3643,3645 ,3156,3152,3154 ,0,0,0}, - {3648,3649,3650 ,3157,3158,3159 ,0,0,0}, {3647,3646,3651 ,3156,3155,3160 ,0,0,0}, - {3652,3653,3651 ,3161,3162,3160 ,0,0,0}, {3649,3648,3653 ,3158,3157,3162 ,0,0,0}, - {3649,3653,3652 ,3158,3162,3161 ,0,0,0}, {3648,3650,3654 ,3157,3159,3163 ,0,0,0}, - {3646,3652,3651 ,3155,3161,3160 ,0,0,0}, {3655,3654,3656 ,3164,3163,3165 ,0,0,0}, - {3655,3656,3657 ,3164,3165,3166 ,0,0,0}, {3656,3654,3650 ,3165,3163,3159 ,0,0,0}, - {3658,3659,3660 ,3167,3168,3169 ,0,0,0}, {3644,3640,3641 ,3153,3149,3150 ,0,0,0}, - {3658,3661,3657 ,3167,3170,3166 ,0,0,0}, {3661,3658,3660 ,3170,3167,3169 ,0,0,0}, - {3659,3662,3663 ,3168,3171,3172 ,0,0,0}, {3663,3660,3659 ,3172,3169,3168 ,0,0,0}, - {3664,3665,3662 ,3173,3174,3171 ,0,0,0}, {3663,3662,3665 ,3172,3171,3174 ,0,0,0}, - {3664,3626,3625 ,3173,3175,3176 ,0,0,0}, {3664,3625,3665 ,3173,3176,3174 ,0,0,0}, - {3657,3661,3655 ,3166,3170,3164 ,0,0,0}, {3666,3632,3667 ,3177,3141,3178 ,0,0,0}, - {3631,3667,3632 ,3140,3178,3141 ,0,0,0}, {3668,3669,3666 ,3179,3180,3177 ,0,0,0}, - {3666,3667,3668 ,3177,3178,3179 ,0,0,0}, {3669,3670,3671 ,3180,3181,3182 ,0,0,0}, - {3670,3669,3668 ,3181,3180,3179 ,0,0,0}, {3672,3671,3673 ,3183,3182,3184 ,0,0,0}, - {3670,3673,3671 ,3181,3184,3182 ,0,0,0}, {3674,3675,3672 ,3185,3186,3183 ,0,0,0}, - {3672,3673,3674 ,3183,3184,3185 ,0,0,0}, {3675,3676,3677 ,3186,3187,3188 ,0,0,0}, - {3676,3675,3674 ,3187,3186,3185 ,0,0,0}, {3678,3677,3679 ,3189,3188,3190 ,0,0,0}, - {3676,3679,3677 ,3187,3190,3188 ,0,0,0}, {3680,3681,3678 ,3191,3192,3189 ,0,0,0}, - {3678,3679,3680 ,3189,3190,3191 ,0,0,0}, {3681,3682,3683 ,3192,3193,3194 ,0,0,0}, - {3682,3681,3680 ,3193,3192,3191 ,0,0,0}, {3684,3683,3685 ,3195,3194,3196 ,0,0,0}, - {3682,3685,3683 ,3193,3196,3194 ,0,0,0}, {3686,3687,3684 ,3197,3198,3195 ,0,0,0}, - {3684,3685,3686 ,3195,3196,3197 ,0,0,0}, {3687,3688,3689 ,3198,3199,3200 ,0,0,0}, - {3688,3687,3686 ,3199,3198,3197 ,0,0,0}, {3690,3689,3691 ,3201,3200,3202 ,0,0,0}, - {3688,3691,3689 ,3199,3202,3200 ,0,0,0}, {3692,3693,3690 ,3203,3204,3201 ,0,0,0}, - {3690,3691,3692 ,3201,3202,3203 ,0,0,0}, {3693,3694,3695 ,3204,3205,3206 ,0,0,0}, - {3694,3693,3692 ,3205,3204,3203 ,0,0,0}, {3696,3695,3697 ,3207,3206,3208 ,0,0,0}, - {3694,3697,3695 ,3205,3208,3206 ,0,0,0}, {3698,3699,3696 ,3209,3210,3207 ,0,0,0}, - {3696,3697,3698 ,3207,3208,3209 ,0,0,0}, {3699,3700,3701 ,3210,3211,3212 ,0,0,0}, - {3700,3699,3698 ,3211,3210,3209 ,0,0,0}, {3702,3701,3703 ,3213,3212,3214 ,0,0,0}, - {3700,3703,3701 ,3211,3214,3212 ,0,0,0}, {3702,3703,3704 ,3213,3214,3213 ,0,0,0}, - {3705,3702,3704 ,2197,2197,2197 ,0,0,0}, {3702,3705,3706 ,2197,2197,2197 ,0,0,0}, - {3707,3708,3709 ,3215,3216,3217 ,0,0,0}, {3710,3711,3707 ,3218,3219,3215 ,0,0,0}, - {3707,3709,3710 ,3215,3217,3218 ,0,0,0}, {3711,3712,3713 ,3219,3220,3221 ,0,0,0}, - {3712,3711,3710 ,3220,3219,3218 ,0,0,0}, {3714,3713,3715 ,3222,3221,3223 ,0,0,0}, - {3712,3715,3713 ,3220,3223,3221 ,0,0,0}, {3716,3717,3714 ,3224,3225,3222 ,0,0,0}, - {3714,3715,3716 ,3222,3223,3224 ,0,0,0}, {3717,3718,3719 ,3225,3226,3227 ,0,0,0}, - {3718,3717,3716 ,3226,3225,3224 ,0,0,0}, {3720,3719,3721 ,3228,3227,3229 ,0,0,0}, - {3718,3721,3719 ,3226,3229,3227 ,0,0,0}, {3722,3723,3720 ,3230,3231,3228 ,0,0,0}, - {3720,3721,3722 ,3228,3229,3230 ,0,0,0}, {3723,3724,3725 ,3231,3232,3233 ,0,0,0}, - {3724,3723,3722 ,3232,3231,3230 ,0,0,0}, {3726,3725,3727 ,3234,3233,3235 ,0,0,0}, - {3724,3727,3725 ,3232,3235,3233 ,0,0,0}, {3728,3729,3726 ,3236,3237,3234 ,0,0,0}, - {3726,3727,3728 ,3234,3235,3236 ,0,0,0}, {3729,3730,3731 ,3237,3238,3239 ,0,0,0}, - {3730,3729,3728 ,3238,3237,3236 ,0,0,0}, {3732,3731,3733 ,3240,3239,3241 ,0,0,0}, - {3730,3733,3731 ,3238,3241,3239 ,0,0,0}, {3734,3735,3732 ,3242,3243,3240 ,0,0,0}, - {3732,3733,3734 ,3240,3241,3242 ,0,0,0}, {3735,3736,3737 ,3243,3244,3245 ,0,0,0}, - {3736,3735,3734 ,3244,3243,3242 ,0,0,0}, {3738,3737,3739 ,3246,3245,3247 ,0,0,0}, - {3736,3739,3737 ,3244,3247,3245 ,0,0,0}, {3740,3741,3738 ,3248,3249,3246 ,0,0,0}, - {3738,3739,3740 ,3246,3247,3248 ,0,0,0}, {3741,3742,3743 ,3249,3250,3251 ,0,0,0}, - {3742,3741,3740 ,3250,3249,3248 ,0,0,0}, {3744,3743,3745 ,3252,3251,3253 ,0,0,0}, - {3742,3745,3743 ,3250,3253,3251 ,0,0,0}, {3706,3705,3744 ,3254,3254,3252 ,0,0,0}, - {3744,3745,3706 ,3252,3253,3254 ,0,0,0}, {3709,3708,3746 ,3217,3216,3255 ,0,0,0}, - {3747,3746,3748 ,3256,3255,3257 ,0,0,0}, {3708,3748,3746 ,3216,3257,3255 ,0,0,0}, - {3749,3750,3747 ,3258,3259,3256 ,0,0,0}, {3747,3748,3749 ,3256,3257,3258 ,0,0,0}, - {3750,3751,3752 ,3259,3260,3261 ,0,0,0}, {3751,3750,3749 ,3260,3259,3258 ,0,0,0}, - {3753,3752,3754 ,3262,3261,3263 ,0,0,0}, {3751,3754,3752 ,3260,3263,3261 ,0,0,0}, - {3755,3756,3753 ,3264,3265,3262 ,0,0,0}, {3753,3754,3755 ,3262,3263,3264 ,0,0,0}, - {3756,3757,3758 ,3265,3266,3267 ,0,0,0}, {3757,3756,3755 ,3266,3265,3264 ,0,0,0}, - {3759,3758,3760 ,3268,3267,3269 ,0,0,0}, {3757,3760,3758 ,3266,3269,3267 ,0,0,0}, - {3761,3762,3759 ,3270,3271,3268 ,0,0,0}, {3759,3760,3761 ,3268,3269,3270 ,0,0,0}, - {3762,3763,3764 ,3271,3272,3273 ,0,0,0}, {3763,3762,3761 ,3272,3271,3270 ,0,0,0}, - {3765,3764,3766 ,3274,3273,3275 ,0,0,0}, {3763,3766,3764 ,3272,3275,3273 ,0,0,0}, - {3767,3768,3765 ,3276,3277,3274 ,0,0,0}, {3765,3766,3767 ,3274,3275,3276 ,0,0,0}, - {3768,3769,3770 ,3277,3278,3279 ,0,0,0}, {3769,3768,3767 ,3278,3277,3276 ,0,0,0}, - {3771,3770,3772 ,3280,3279,3281 ,0,0,0}, {3769,3772,3770 ,3278,3281,3279 ,0,0,0}, - {3773,3774,3771 ,3282,3283,3280 ,0,0,0}, {3771,3772,3773 ,3280,3281,3282 ,0,0,0}, - {3774,3775,3776 ,3283,3284,3285 ,0,0,0}, {3775,3774,3773 ,3284,3283,3282 ,0,0,0}, - {3777,3776,3778 ,3286,3285,3287 ,0,0,0}, {3775,3778,3776 ,3284,3287,3285 ,0,0,0}, - {3779,3780,3777 ,3288,3289,3286 ,0,0,0}, {3777,3778,3779 ,3286,3287,3288 ,0,0,0}, - {3780,3781,3782 ,3289,3290,3291 ,0,0,0}, {3781,3780,3779 ,3290,3289,3288 ,0,0,0}, - {3781,3431,3782 ,3290,3292,3291 ,0,0,0}, {3782,3431,3430 ,3291,3292,3292 ,0,0,0}, - {3132,3428,3133 ,1433,3293,1433 ,0,0,0}, {3428,3132,3426 ,3293,1433,3293 ,0,0,0}, - {3653,3155,3154 ,3294,3294,3294 ,0,0,0}, {3431,3781,3354 ,3294,726,726 ,0,0,0}, - {3775,3384,3778 ,726,726,726 ,0,0,0}, {3471,3429,3351 ,726,726,726 ,0,0,0}, - {3372,3376,3766 ,726,726,726 ,0,0,0}, {3380,3772,3769 ,726,726,726 ,0,0,0}, - {3751,3362,3754 ,726,726,726 ,0,0,0}, {3760,3757,3369 ,726,726,726 ,0,0,0}, - {3748,3356,3355 ,726,726,726 ,0,0,0}, {3749,3748,3355 ,726,726,726 ,0,0,0}, - {3148,3145,3644 ,3294,726,3294 ,0,0,0}, {3661,3660,3163 ,3294,726,3294 ,0,0,0}, - {3629,3633,3137 ,3294,3294,726 ,0,0,0}, {3139,3633,3636 ,726,3294,726 ,0,0,0}, - {3667,3093,3097 ,726,726,726 ,0,0,0}, {3093,3631,3094 ,726,3294,3294 ,0,0,0}, - {3670,3100,3673 ,3294,726,726 ,0,0,0}, {3099,3670,3668 ,3294,3294,3294 ,0,0,0}, - {3109,3680,3679 ,3295,3294,3294 ,0,0,0}, {3105,3676,3674 ,726,3294,3294 ,0,0,0}, - {3682,3680,3111 ,3294,3294,3294 ,0,0,0}, {3109,3111,3680 ,3295,3294,3294 ,0,0,0}, - {3686,3685,3115 ,3294,3295,726 ,0,0,0}, {3682,3111,3112 ,3294,3294,3294 ,0,0,0}, - {3688,3686,3117 ,3294,3294,3294 ,0,0,0}, {3115,3685,3112 ,726,3295,3294 ,0,0,0}, - {3118,3691,3688 ,3294,726,3294 ,0,0,0}, {3688,3117,3118 ,3294,3294,3294 ,0,0,0}, - {3691,3121,3692 ,726,726,726 ,0,0,0}, {3121,3691,3118 ,726,726,3294 ,0,0,0}, - {3694,3692,3123 ,726,726,726 ,0,0,0}, {3124,3694,3123 ,726,726,726 ,0,0,0}, - {3129,3698,3127 ,726,3294,3294 ,0,0,0}, {3697,3694,3124 ,726,726,726 ,0,0,0}, - {3130,3133,3700 ,726,726,726 ,0,0,0}, {3127,3698,3697 ,3294,3294,726 ,0,0,0}, - {3133,3703,3700 ,726,3294,726 ,0,0,0}, {3698,3130,3700 ,3294,726,726 ,0,0,0}, - {3723,3404,3720 ,726,726,726 ,0,0,0}, {3133,3704,3703 ,726,726,3294 ,0,0,0}, - {3654,3157,3648 ,3294,726,726 ,0,0,0}, {3668,3097,3099 ,3294,726,3294 ,0,0,0}, - {3676,3105,3106 ,3294,726,3294 ,0,0,0}, {3679,3106,3109 ,3294,3294,3295 ,0,0,0}, - {3103,3105,3674 ,3294,726,3294 ,0,0,0}, {3673,3100,3103 ,726,726,3294 ,0,0,0}, - {3631,3093,3667 ,3294,726,726 ,0,0,0}, {3667,3097,3668 ,726,726,3294 ,0,0,0}, - {3629,3136,3634 ,3294,3294,3294 ,0,0,0}, {3634,3094,3631 ,3294,3294,3294 ,0,0,0}, - {3297,3476,3295 ,726,726,3294 ,0,0,0}, {3136,3094,3634 ,3294,3294,3294 ,0,0,0}, - {3639,3143,3142 ,3294,3294,726 ,0,0,0}, {3636,3142,3139 ,726,726,726 ,0,0,0}, - {3640,3145,3143 ,726,726,3294 ,0,0,0}, {3639,3142,3636 ,3294,726,726 ,0,0,0}, - {3647,3151,3149 ,3294,3294,3294 ,0,0,0}, {3148,3644,3643 ,3294,3294,726 ,0,0,0}, - {3648,3155,3653 ,726,3294,3294 ,0,0,0}, {3151,3651,3154 ,3294,3294,3294 ,0,0,0}, - {3161,3160,3655 ,726,726,726 ,0,0,0}, {3157,3155,3648 ,726,3294,726 ,0,0,0}, - {3655,3160,3654 ,726,726,3294 ,0,0,0}, {3503,3500,3283 ,3294,726,726 ,0,0,0}, - {3663,3167,3166 ,3295,726,726 ,0,0,0}, {3080,3062,3082 ,3294,3295,726 ,0,0,0}, - {3169,3665,3171 ,3294,726,3294 ,0,0,0}, {3087,3089,3054 ,726,3294,726 ,0,0,0}, - {3051,3089,3090 ,726,3294,3294 ,0,0,0}, {3250,3247,3043 ,726,726,726 ,0,0,0}, - {3250,3034,3036 ,726,726,3294 ,0,0,0}, {3553,3225,3551 ,726,3294,3294 ,0,0,0}, - {3244,3239,3506 ,3294,726,726 ,0,0,0}, {3613,3610,3783 ,726,726,726 ,0,0,0}, - {3524,3208,3523 ,726,3294,3294 ,0,0,0}, {3784,3785,3574 ,3294,3294,726 ,0,0,0}, - {3029,3786,3787 ,3294,726,726 ,0,0,0}, {3580,3578,3788 ,726,3294,726 ,0,0,0}, - {3788,3578,3785 ,726,3294,3294 ,0,0,0}, {3002,2999,3071 ,726,726,3294 ,0,0,0}, - {3788,3071,3583 ,726,3294,3294 ,0,0,0}, {3069,3067,3000 ,3294,3294,3294 ,0,0,0}, - {3000,3067,3009 ,3294,3294,3294 ,0,0,0}, {3590,3589,2998 ,3294,726,726 ,0,0,0}, - {3577,3574,3785 ,3294,726,3294 ,0,0,0}, {3215,3784,3572 ,726,3294,726 ,0,0,0}, - {3190,3789,3186 ,726,3294,3294 ,0,0,0}, {3790,3791,3786 ,3294,3294,726 ,0,0,0}, - {3181,3792,3793 ,726,3294,3294 ,0,0,0}, {3569,3214,3215 ,3294,726,726 ,0,0,0}, - {3215,3572,3571 ,726,726,3294 ,0,0,0}, {3511,3214,3569 ,3294,726,3294 ,0,0,0}, - {3608,3607,3794 ,726,3294,3294 ,0,0,0}, {3213,3214,3515 ,3294,726,726 ,0,0,0}, - {3515,3517,3213 ,726,726,3294 ,0,0,0}, {3614,3613,3795 ,3294,726,3294 ,0,0,0}, - {3210,3213,3518 ,726,3294,726 ,0,0,0}, {3616,3796,3619 ,726,3294,3294 ,0,0,0}, - {3521,3210,3518 ,3294,726,726 ,0,0,0}, {3173,3620,3176 ,3294,726,3294 ,0,0,0}, - {3210,3523,3208 ,726,3294,3294 ,0,0,0}, {3533,3204,3203 ,3294,726,726 ,0,0,0}, - {3529,3203,3206 ,3294,726,3294 ,0,0,0}, {3220,3219,3541 ,3295,726,3294 ,0,0,0}, - {3204,3533,3535 ,726,3294,3294 ,0,0,0}, {3548,3222,3547 ,3294,3294,3294 ,0,0,0}, - {3222,3220,3545 ,3294,3295,3294 ,0,0,0}, {3231,3228,3559 ,3294,726,726 ,0,0,0}, - {3191,3797,3195 ,3294,726,3294 ,0,0,0}, {3798,3799,3800 ,3294,3294,3294 ,0,0,0}, - {3232,3563,3565 ,726,726,726 ,0,0,0}, {3234,3238,3510 ,3294,3294,3294 ,0,0,0}, - {3801,3252,3802 ,726,726,726 ,0,0,0}, {3803,3262,3252 ,3294,3294,726 ,0,0,0}, - {3255,3251,3804 ,726,726,726 ,0,0,0}, {3254,3805,3802 ,726,3294,726 ,0,0,0}, - {3092,3033,3032 ,726,726,3294 ,0,0,0}, {3076,3075,3056 ,3294,726,726 ,0,0,0}, - {3805,3254,3255 ,3294,726,726 ,0,0,0}, {3622,3173,3625 ,3294,3294,3294 ,0,0,0}, - {3079,3057,3060 ,726,3294,726 ,0,0,0}, {3280,3278,3503 ,3294,3294,3294 ,0,0,0}, - {3665,3625,3171 ,726,3294,3294 ,0,0,0}, {3318,3284,3500 ,3295,726,726 ,0,0,0}, - {3169,3167,3665 ,3294,726,726 ,0,0,0}, {3755,3365,3366 ,726,726,726 ,0,0,0}, - {3711,3392,3707 ,726,726,726 ,0,0,0}, {3394,3711,3713 ,726,726,726 ,0,0,0}, - {3473,3292,3474 ,3294,726,726 ,0,0,0}, {3148,3643,3149 ,3294,726,3294 ,0,0,0}, - {3665,3167,3663 ,726,726,3295 ,0,0,0}, {3660,3663,3166 ,726,3295,726 ,0,0,0}, - {3161,3661,3163 ,726,3294,3294 ,0,0,0}, {3163,3660,3166 ,3294,726,726 ,0,0,0}, - {3151,3647,3651 ,3294,3294,3294 ,0,0,0}, {3157,3654,3160 ,726,3294,726 ,0,0,0}, - {3161,3655,3661 ,726,726,3294 ,0,0,0}, {3653,3154,3651 ,3294,3294,3294 ,0,0,0}, - {3643,3647,3149 ,726,3294,3294 ,0,0,0}, {3644,3145,3640 ,3294,726,726 ,0,0,0}, - {3476,3297,3479 ,726,726,726 ,0,0,0}, {3639,3640,3143 ,3294,726,3294 ,0,0,0}, - {3707,3392,3360 ,726,726,726 ,0,0,0}, {3360,3708,3707 ,726,726,726 ,0,0,0}, - {3708,3360,3356 ,726,726,726 ,0,0,0}, {3362,3749,3355 ,726,726,726 ,0,0,0}, - {3356,3748,3708 ,726,726,726 ,0,0,0}, {3291,3292,3473 ,3294,726,3294 ,0,0,0}, - {3755,3754,3365 ,726,726,726 ,0,0,0}, {3754,3362,3365 ,726,726,726 ,0,0,0}, - {3446,3450,3327 ,726,3294,3294 ,0,0,0}, {3757,3755,3366 ,726,726,726 ,0,0,0}, - {3373,3760,3369 ,726,726,726 ,0,0,0}, {3761,3373,3375 ,726,726,726 ,0,0,0}, - {3373,3761,3760 ,726,726,726 ,0,0,0}, {3372,3763,3375 ,726,726,726 ,0,0,0}, - {3761,3375,3763 ,726,726,726 ,0,0,0}, {3763,3372,3766 ,726,726,726 ,0,0,0}, - {3376,3379,3767 ,726,726,726 ,0,0,0}, {3328,3327,3450 ,726,3294,3294 ,0,0,0}, - {3769,3379,3380 ,726,726,726 ,0,0,0}, {3379,3769,3767 ,726,726,726 ,0,0,0}, - {3773,3772,3382 ,726,726,726 ,0,0,0}, {3467,3345,3342 ,726,3294,3294 ,0,0,0}, - {3380,3382,3772 ,726,726,726 ,0,0,0}, {3386,3775,3773 ,726,726,726 ,0,0,0}, - {3773,3382,3386 ,726,726,726 ,0,0,0}, {3775,3386,3384 ,726,726,726 ,0,0,0}, - {3384,3389,3778 ,726,726,726 ,0,0,0}, {3778,3389,3779 ,726,726,726 ,0,0,0}, - {3779,3391,3781 ,726,726,726 ,0,0,0}, {3469,3348,3346 ,3294,726,3295 ,0,0,0}, - {3391,3779,3389 ,726,726,726 ,0,0,0}, {3270,3506,3504 ,726,726,3295 ,0,0,0}, - {3046,3047,3245 ,3295,726,726 ,0,0,0}, {3316,3318,3498 ,726,3295,726 ,0,0,0}, - {3504,3278,3277 ,3295,3294,3294 ,0,0,0}, {3315,3316,3497 ,3294,726,726 ,0,0,0}, - {3313,3315,3494 ,726,3294,726 ,0,0,0}, {3500,3284,3283 ,726,726,726 ,0,0,0}, - {3310,3313,3492 ,3294,726,3294 ,0,0,0}, {3500,3498,3318 ,726,726,3295 ,0,0,0}, - {3309,3310,3491 ,726,3294,3294 ,0,0,0}, {3498,3497,3316 ,726,726,726 ,0,0,0}, - {3307,3309,3488 ,3294,726,3294 ,0,0,0}, {3497,3494,3315 ,726,726,3294 ,0,0,0}, - {3304,3486,3485 ,3294,726,726 ,0,0,0}, {3494,3492,3313 ,726,3294,726 ,0,0,0}, - {3303,3485,3482 ,726,726,3294 ,0,0,0}, {3492,3491,3310 ,3294,3294,3294 ,0,0,0}, - {3301,3482,3480 ,3294,3294,726 ,0,0,0}, {3479,3298,3480 ,726,3294,726 ,0,0,0}, - {3304,3307,3486 ,3294,3294,726 ,0,0,0}, {3476,3474,3295 ,726,726,3294 ,0,0,0}, - {3304,3485,3303 ,3294,726,726 ,0,0,0}, {3713,3714,3397 ,726,726,726 ,0,0,0}, - {3482,3301,3303 ,3294,3294,726 ,0,0,0}, {3714,3717,3398 ,726,726,726 ,0,0,0}, - {3480,3298,3301 ,726,3294,3294 ,0,0,0}, {3717,3719,3400 ,726,726,726 ,0,0,0}, - {3136,3629,3137 ,3294,3294,726 ,0,0,0}, {3137,3633,3139 ,726,3294,726 ,0,0,0}, - {3474,3292,3295 ,726,726,3294 ,0,0,0}, {3403,3400,3719 ,726,726,726 ,0,0,0}, - {3394,3392,3711 ,726,726,726 ,0,0,0}, {3403,3720,3404 ,726,726,726 ,0,0,0}, - {3397,3394,3713 ,726,726,726 ,0,0,0}, {3723,3406,3404 ,726,726,726 ,0,0,0}, - {3398,3397,3714 ,726,726,726 ,0,0,0}, {3725,3409,3406 ,726,726,726 ,0,0,0}, - {3400,3398,3717 ,726,726,726 ,0,0,0}, {3100,3670,3099 ,726,3294,3294 ,0,0,0}, - {3410,3409,3726 ,726,726,726 ,0,0,0}, {3719,3720,3403 ,726,726,726 ,0,0,0}, - {3412,3410,3729 ,726,726,726 ,0,0,0}, {3412,3729,3731 ,726,726,726 ,0,0,0}, - {3103,3674,3673 ,3294,3294,726 ,0,0,0}, {3723,3725,3406 ,726,726,726 ,0,0,0}, - {3106,3679,3676 ,3294,3294,3294 ,0,0,0}, {3732,3415,3731 ,726,726,726 ,0,0,0}, - {3725,3726,3409 ,726,726,726 ,0,0,0}, {3416,3732,3735 ,726,726,726 ,0,0,0}, - {3726,3729,3410 ,726,726,726 ,0,0,0}, {3112,3685,3682 ,3294,3295,3294 ,0,0,0}, - {3731,3415,3412 ,726,726,726 ,0,0,0}, {3735,3737,3418 ,726,726,726 ,0,0,0}, - {3416,3415,3732 ,726,726,726 ,0,0,0}, {3738,3421,3737 ,726,726,726 ,0,0,0}, - {3115,3117,3686 ,726,3294,3294 ,0,0,0}, {3741,3422,3738 ,726,726,726 ,0,0,0}, - {3418,3416,3735 ,726,726,726 ,0,0,0}, {3121,3123,3692 ,726,726,726 ,0,0,0}, - {3737,3421,3418 ,726,726,726 ,0,0,0}, {3424,3741,3743 ,726,726,726 ,0,0,0}, - {3124,3127,3697 ,726,3294,726 ,0,0,0}, {3738,3422,3421 ,726,726,726 ,0,0,0}, - {3427,3424,3743 ,3294,726,726 ,0,0,0}, {3428,3427,3744 ,726,3294,726 ,0,0,0}, - {3129,3130,3698 ,726,726,3294 ,0,0,0}, {3427,3743,3744 ,3294,726,726 ,0,0,0}, - {3705,3704,3428 ,3294,726,726 ,0,0,0}, {3704,3133,3428 ,726,726,726 ,0,0,0}, - {3744,3705,3428 ,726,3294,726 ,0,0,0}, {3741,3424,3422 ,726,726,726 ,0,0,0}, - {3291,3473,3437 ,3294,3294,3294 ,0,0,0}, {3289,3437,3440 ,3294,3294,3294 ,0,0,0}, - {3285,3440,3435 ,3294,3294,3294 ,0,0,0}, {3319,3435,3439 ,726,3294,726 ,0,0,0}, - {3439,3442,3321 ,726,3294,3294 ,0,0,0}, {3362,3751,3749 ,726,726,726 ,0,0,0}, - {3437,3289,3291 ,3294,3294,3294 ,0,0,0}, {3442,3445,3322 ,3294,3294,726 ,0,0,0}, - {3440,3285,3289 ,3294,3294,3294 ,0,0,0}, {3366,3369,3757 ,726,726,726 ,0,0,0}, - {3285,3435,3319 ,3294,3294,726 ,0,0,0}, {3446,3324,3445 ,726,726,3294 ,0,0,0}, - {3439,3321,3319 ,726,3294,726 ,0,0,0}, {3328,3450,3449 ,726,3294,3294 ,0,0,0}, - {3442,3322,3321 ,3294,726,3294 ,0,0,0}, {3330,3328,3449 ,3294,726,3294 ,0,0,0}, - {3445,3324,3322 ,3294,726,726 ,0,0,0}, {3453,3333,3330 ,726,3294,3294 ,0,0,0}, - {3446,3327,3324 ,726,3294,726 ,0,0,0}, {3457,3334,3333 ,726,726,3294 ,0,0,0}, - {3459,3336,3334 ,3294,726,726 ,0,0,0}, {3766,3376,3767 ,726,726,726 ,0,0,0}, - {3330,3449,3453 ,3294,3294,726 ,0,0,0}, {3454,3339,3336 ,726,3294,726 ,0,0,0}, - {3333,3453,3457 ,3294,726,726 ,0,0,0}, {3339,3460,3340 ,3294,726,3294 ,0,0,0}, - {3334,3457,3459 ,726,726,3294 ,0,0,0}, {3342,3340,3461 ,3294,3294,726 ,0,0,0}, - {3339,3454,3460 ,3294,726,726 ,0,0,0}, {3345,3467,3466 ,3294,726,3294 ,0,0,0}, - {3340,3460,3461 ,3294,726,726 ,0,0,0}, {3469,3346,3466 ,3294,3295,3294 ,0,0,0}, - {3342,3461,3467 ,3294,726,726 ,0,0,0}, {3469,3351,3348 ,3294,726,726 ,0,0,0}, - {3346,3345,3466 ,3295,3294,3294 ,0,0,0}, {3351,3429,3354 ,726,726,726 ,0,0,0}, - {3431,3354,3429 ,3294,726,726 ,0,0,0}, {3781,3391,3354 ,726,726,726 ,0,0,0}, - {3469,3471,3351 ,3294,726,726 ,0,0,0}, {3336,3459,3454 ,726,3294,726 ,0,0,0}, - {3298,3479,3297 ,3294,726,726 ,0,0,0}, {3309,3491,3488 ,726,3294,3294 ,0,0,0}, - {3307,3488,3486 ,3294,3294,726 ,0,0,0}, {3226,3553,3554 ,3294,726,3294 ,0,0,0}, - {3280,3503,3283 ,3294,3294,726 ,0,0,0}, {3241,3232,3566 ,3294,726,726 ,0,0,0}, - {3504,3503,3278 ,3295,3294,3294 ,0,0,0}, {3268,3271,3806 ,726,3294,3294 ,0,0,0}, - {3270,3504,3277 ,726,3295,3294 ,0,0,0}, {3807,3260,3259 ,3294,3294,726 ,0,0,0}, - {3251,3082,3063 ,726,726,726 ,0,0,0}, {3262,3808,3259 ,3294,726,726 ,0,0,0}, - {3251,3063,3804 ,726,726,726 ,0,0,0}, {3509,3239,3235 ,726,726,3294 ,0,0,0}, - {3231,3559,3560 ,3294,726,726 ,0,0,0}, {3793,3191,3179 ,3294,3294,3294 ,0,0,0}, - {3548,3551,3225 ,3294,3294,3294 ,0,0,0}, {3220,3541,3542 ,3295,3294,3295 ,0,0,0}, - {3529,3530,3203 ,3294,3294,726 ,0,0,0}, {3583,3071,3584 ,3294,3294,3294 ,0,0,0}, - {3206,3524,3527 ,3294,726,3294 ,0,0,0}, {3536,3219,3204 ,726,726,726 ,0,0,0}, - {3219,3536,3539 ,726,726,3294 ,0,0,0}, {3222,3545,3547 ,3294,3294,3294 ,0,0,0}, - {3557,3226,3554 ,726,3294,3294 ,0,0,0}, {3557,3228,3226 ,726,726,3294 ,0,0,0}, - {3232,3231,3563 ,726,3294,726 ,0,0,0}, {3566,3568,3241 ,726,726,3294 ,0,0,0}, - {3241,3510,3238 ,3294,3294,3294 ,0,0,0}, {3235,3234,3509 ,3294,3294,726 ,0,0,0}, - {3807,3809,3260 ,3294,726,3294 ,0,0,0}, {3810,3811,3274 ,726,3294,726 ,0,0,0}, - {3811,3812,3274 ,3294,726,726 ,0,0,0}, {3813,3806,3271 ,726,3294,3294 ,0,0,0}, - {3806,3814,3268 ,3294,726,726 ,0,0,0}, {3239,3509,3506 ,726,726,726 ,0,0,0}, - {3510,3509,3234 ,3294,726,3294 ,0,0,0}, {3510,3241,3568 ,3294,3294,726 ,0,0,0}, - {3566,3232,3565 ,726,726,726 ,0,0,0}, {3563,3231,3560 ,726,3294,726 ,0,0,0}, - {3559,3228,3557 ,726,726,726 ,0,0,0}, {3226,3225,3553 ,3294,3294,726 ,0,0,0}, - {3225,3222,3548 ,3294,3294,3294 ,0,0,0}, {3220,3542,3545 ,3295,3295,3294 ,0,0,0}, - {3219,3539,3541 ,726,3294,3294 ,0,0,0}, {3204,3535,3536 ,726,3294,726 ,0,0,0}, - {3203,3530,3533 ,726,3294,3294 ,0,0,0}, {3206,3527,3529 ,3294,3294,3294 ,0,0,0}, - {3206,3208,3524 ,3294,3294,726 ,0,0,0}, {3210,3521,3523 ,726,3294,3294 ,0,0,0}, - {3213,3517,3518 ,3294,726,726 ,0,0,0}, {3214,3511,3515 ,726,3294,726 ,0,0,0}, - {3215,3571,3569 ,726,3294,3294 ,0,0,0}, {3784,3574,3572 ,3294,726,726 ,0,0,0}, - {3785,3578,3577 ,3294,3294,3294 ,0,0,0}, {3788,3583,3580 ,726,3294,726 ,0,0,0}, - {3002,3069,3000 ,726,3294,3294 ,0,0,0}, {3006,3009,3067 ,3294,3294,3294 ,0,0,0}, - {3586,3584,2999 ,3294,3294,726 ,0,0,0}, {3066,3008,3006 ,3294,726,3294 ,0,0,0}, - {3012,3073,3200 ,3294,726,3294 ,0,0,0}, {3815,3800,3816 ,726,3294,3294 ,0,0,0}, - {3185,3817,3183 ,726,3294,3294 ,0,0,0}, {3818,3185,3186 ,726,726,3294 ,0,0,0}, - {3180,3792,3181 ,3294,3294,726 ,0,0,0}, {3180,3183,3819 ,3294,3294,726 ,0,0,0}, - {3820,3190,3799 ,726,726,3294 ,0,0,0}, {3821,3196,3195 ,3294,3294,3294 ,0,0,0}, - {3815,3791,3790 ,726,3294,3294 ,0,0,0}, {3022,3595,3020 ,3294,3294,3294 ,0,0,0}, - {3017,3592,3590 ,3294,3294,3294 ,0,0,0}, {3026,3028,3601 ,3294,3294,726 ,0,0,0}, - {3023,3598,3596 ,726,726,726 ,0,0,0}, {3607,3029,3787 ,3294,3294,726 ,0,0,0}, - {3787,3794,3607 ,726,3294,3294 ,0,0,0}, {3604,3029,3607 ,726,3294,3294 ,0,0,0}, - {3604,3602,3028 ,726,726,3294 ,0,0,0}, {3610,3608,3794 ,726,726,3294 ,0,0,0}, - {3795,3613,3783 ,3294,726,726 ,0,0,0}, {3783,3610,3794 ,726,726,3294 ,0,0,0}, - {3795,3616,3614 ,3294,726,3294 ,0,0,0}, {3796,3176,3619 ,3294,3294,3294 ,0,0,0}, - {3795,3796,3616 ,3294,3294,726 ,0,0,0}, {3620,3619,3176 ,726,3294,3294 ,0,0,0}, - {3620,3173,3622 ,726,3294,3294 ,0,0,0}, {3625,3173,3171 ,3294,3294,3294 ,0,0,0}, - {3245,3042,3247 ,726,3294,726 ,0,0,0}, {3804,3805,3255 ,726,3294,726 ,0,0,0}, - {3036,3033,3092 ,3294,726,726 ,0,0,0}, {3802,3252,3254 ,726,726,726 ,0,0,0}, - {3803,3252,3801 ,3294,726,726 ,0,0,0}, {3808,3262,3803 ,726,3294,3294 ,0,0,0}, - {3807,3259,3808 ,3294,726,726 ,0,0,0}, {3264,3260,3809 ,3294,3294,726 ,0,0,0}, - {3264,3822,3274 ,3294,3294,726 ,0,0,0}, {3822,3264,3809 ,3294,3294,726 ,0,0,0}, - {3822,3810,3274 ,3294,726,726 ,0,0,0}, {3271,3812,3813 ,3294,726,726 ,0,0,0}, - {3812,3271,3274 ,726,3294,726 ,0,0,0}, {3270,3049,3506 ,726,726,726 ,0,0,0}, - {3814,3049,3270 ,726,726,726 ,0,0,0}, {3814,3270,3268 ,726,726,726 ,0,0,0}, - {3049,3046,3506 ,726,3295,726 ,0,0,0}, {3244,3046,3245 ,3294,3295,726 ,0,0,0}, - {3046,3244,3506 ,3295,3294,726 ,0,0,0}, {3047,3042,3245 ,726,3294,726 ,0,0,0}, - {3040,3043,3247 ,726,726,726 ,0,0,0}, {3042,3040,3247 ,3294,726,726 ,0,0,0}, - {3043,3034,3250 ,726,726,726 ,0,0,0}, {3036,3092,3250 ,3294,726,726 ,0,0,0}, - {3090,3092,3032 ,3294,726,3294 ,0,0,0}, {3054,3089,3051 ,726,3294,726 ,0,0,0}, - {3051,3090,3032 ,726,3294,3294 ,0,0,0}, {3056,3087,3054 ,726,726,726 ,0,0,0}, - {3056,3057,3076 ,726,3294,3294 ,0,0,0}, {3056,3075,3087 ,726,726,726 ,0,0,0}, - {3079,3060,3080 ,726,726,3294 ,0,0,0}, {3076,3057,3079 ,3294,3294,726 ,0,0,0}, - {3082,3062,3063 ,726,3295,726 ,0,0,0}, {3080,3060,3062 ,3294,726,3295 ,0,0,0}, - {3196,3823,3198 ,3294,726,3294 ,0,0,0}, {3787,3786,3791 ,726,726,3294 ,0,0,0}, - {3200,3198,3015 ,3294,3294,3294 ,0,0,0}, {3815,3816,3791 ,726,3294,3294 ,0,0,0}, - {3800,3799,3816 ,3294,3294,3294 ,0,0,0}, {3820,3799,3798 ,726,3294,3294 ,0,0,0}, - {3789,3190,3820 ,3294,726,726 ,0,0,0}, {3818,3186,3789 ,726,3294,3294 ,0,0,0}, - {3817,3185,3818 ,3294,726,726 ,0,0,0}, {3819,3183,3817 ,726,3294,3294 ,0,0,0}, - {3792,3180,3819 ,3294,3294,726 ,0,0,0}, {3179,3181,3793 ,3294,726,3294 ,0,0,0}, - {3797,3191,3793 ,726,3294,3294 ,0,0,0}, {3821,3195,3797 ,3294,3294,726 ,0,0,0}, - {3823,3196,3821 ,726,3294,3294 ,0,0,0}, {3015,3198,3823 ,3294,3294,726 ,0,0,0}, - {3012,3200,3015 ,3294,3294,3294 ,0,0,0}, {3013,3073,3012 ,3294,726,3294 ,0,0,0}, - {3066,3013,3008 ,3294,3294,726 ,0,0,0}, {3013,3066,3073 ,3294,3294,726 ,0,0,0}, - {3006,3067,3066 ,3294,3294,3294 ,0,0,0}, {3071,3069,3002 ,3294,3294,726 ,0,0,0}, - {3586,2999,2998 ,3294,726,726 ,0,0,0}, {2999,3584,3071 ,726,3294,3294 ,0,0,0}, - {3017,3590,2998 ,3294,3294,726 ,0,0,0}, {3589,3586,2998 ,726,3294,726 ,0,0,0}, - {3020,3592,3017 ,3294,3294,3294 ,0,0,0}, {3022,3596,3595 ,3294,726,3294 ,0,0,0}, - {3020,3595,3592 ,3294,3294,3294 ,0,0,0}, {3023,3026,3598 ,726,3294,726 ,0,0,0}, - {3022,3023,3596 ,3294,726,726 ,0,0,0}, {3601,3028,3602 ,726,3294,726 ,0,0,0}, - {3598,3026,3601 ,726,3294,726 ,0,0,0}, {3604,3028,3029 ,726,3294,3294 ,0,0,0}, - {3352,3470,3468 ,730,730,730 ,0,0,0}, {3134,3630,3095 ,730,730,730 ,0,0,0}, - {3205,3538,3537 ,730,730,730 ,0,0,0}, {3464,3347,3465 ,730,730,730 ,0,0,0}, - {3338,3341,3456 ,730,730,730 ,0,0,0}, {3343,3344,3463 ,730,730,730 ,0,0,0}, - {3329,3331,3448 ,730,730,730 ,0,0,0}, {3332,3335,3452 ,730,730,730 ,0,0,0}, - {3433,3436,3287 ,730,730,730 ,0,0,0}, {3323,3325,3443 ,730,730,730 ,0,0,0}, - {3632,3096,3095 ,730,730,730 ,0,0,0}, {3477,3294,3475 ,730,730,730 ,0,0,0}, - {3104,3672,3675 ,730,730,730 ,0,0,0}, {3678,3681,3110 ,730,730,730 ,0,0,0}, - {3666,3669,3098 ,730,730,730 ,0,0,0}, {3672,3104,3102 ,730,730,730 ,0,0,0}, - {3135,3628,3627 ,730,730,730 ,0,0,0}, {3096,3632,3666 ,730,730,730 ,0,0,0}, - {3140,3141,3637 ,730,730,730 ,0,0,0}, {3710,3393,3712 ,730,730,730 ,0,0,0}, - {3638,3144,3641 ,730,730,730 ,0,0,0}, {3141,3638,3637 ,730,730,730 ,0,0,0}, - {3153,3652,3152 ,730,730,730 ,0,0,0}, {3146,3642,3641 ,730,730,730 ,0,0,0}, - {3659,3658,3164 ,730,730,730 ,0,0,0}, {3657,3656,3159 ,730,730,730 ,0,0,0}, - {3165,3168,3662 ,730,730,730 ,0,0,0}, {3824,3576,3579 ,730,730,730 ,0,0,0}, - {3211,3209,3520 ,730,730,730 ,0,0,0}, {3014,3074,3072 ,730,730,730 ,0,0,0}, - {3024,3599,3600 ,730,730,730 ,0,0,0}, {3174,3624,3626 ,730,730,730 ,0,0,0}, - {3664,3172,3626 ,730,730,730 ,0,0,0}, {3825,3826,3618 ,730,730,730 ,0,0,0}, - {3027,3025,3603 ,730,730,730 ,0,0,0}, {3825,3618,3621 ,730,730,730 ,0,0,0}, - {3615,3617,3826 ,730,730,730 ,0,0,0}, {3177,3827,3178 ,730,730,730 ,0,0,0}, - {3626,3172,3174 ,730,730,730 ,0,0,0}, {3538,3205,3218 ,730,730,730 ,0,0,0}, - {3828,3217,3575 ,730,730,730 ,0,0,0}, {3516,3514,3212 ,730,730,730 ,0,0,0}, - {3024,3600,3025 ,730,730,730 ,0,0,0}, {3070,3585,3587 ,730,730,730 ,0,0,0}, - {3168,3170,3664 ,730,730,730 ,0,0,0}, {3068,3001,3065 ,730,730,730 ,0,0,0}, - {3004,3005,3065 ,730,730,730 ,0,0,0}, {3829,3193,3194 ,730,730,730 ,0,0,0}, - {3825,3621,3175 ,730,730,730 ,0,0,0}, {3174,3175,3623 ,730,730,730 ,0,0,0}, - {3830,3615,3826 ,730,730,730 ,0,0,0}, {3611,3612,3831 ,730,730,730 ,0,0,0}, - {3831,3612,3830 ,730,730,730 ,0,0,0}, {3830,3612,3615 ,730,730,730 ,0,0,0}, - {3826,3617,3618 ,730,730,730 ,0,0,0}, {3832,3833,3834 ,730,730,730 ,0,0,0}, - {3083,3084,3061 ,730,730,730 ,0,0,0}, {3621,3623,3175 ,730,730,730 ,0,0,0}, - {3605,3027,3603 ,730,730,730 ,0,0,0}, {3624,3174,3623 ,730,730,730 ,0,0,0}, - {3835,3189,3187 ,730,730,730 ,0,0,0}, {3194,3197,3836 ,730,730,730 ,0,0,0}, - {3199,3074,3011 ,730,730,730 ,0,0,0}, {3197,3199,3010 ,730,730,730 ,0,0,0}, - {3664,3170,3172 ,730,730,730 ,0,0,0}, {3178,3837,3182 ,730,730,730 ,0,0,0}, - {3838,3192,3193 ,730,730,730 ,0,0,0}, {3070,3587,2997 ,730,730,730 ,0,0,0}, - {3182,3839,3184 ,730,730,730 ,0,0,0}, {3021,3599,3024 ,730,730,730 ,0,0,0}, - {3599,3021,3597 ,730,730,730 ,0,0,0}, {3512,3216,3513 ,730,730,730 ,0,0,0}, - {3528,3202,3531 ,730,730,730 ,0,0,0}, {3525,3522,3207 ,730,730,730 ,0,0,0}, - {3546,3544,3221 ,730,730,730 ,0,0,0}, {3534,3201,3205 ,730,730,730 ,0,0,0}, - {3546,3221,3223 ,730,730,730 ,0,0,0}, {3164,3165,3659 ,730,730,730 ,0,0,0}, - {3168,3664,3662 ,730,730,730 ,0,0,0}, {3662,3659,3165 ,730,730,730 ,0,0,0}, - {3678,3108,3677 ,730,730,730 ,0,0,0}, {3657,3159,3162 ,730,730,730 ,0,0,0}, - {3658,3162,3164 ,730,730,730 ,0,0,0}, {3158,3159,3656 ,730,730,730 ,0,0,0}, - {3657,3162,3658 ,730,730,730 ,0,0,0}, {3158,3650,3156 ,730,730,730 ,0,0,0}, - {3649,3153,3156 ,730,730,730 ,0,0,0}, {3656,3650,3158 ,730,730,730 ,0,0,0}, - {3153,3649,3652 ,730,730,730 ,0,0,0}, {3156,3650,3649 ,730,730,730 ,0,0,0}, - {3487,3306,3305 ,730,730,730 ,0,0,0}, {3646,3150,3152 ,730,730,730 ,0,0,0}, - {3150,3645,3147 ,730,730,730 ,0,0,0}, {3645,3642,3147 ,730,730,730 ,0,0,0}, - {3642,3146,3147 ,730,730,730 ,0,0,0}, {3641,3144,3146 ,730,730,730 ,0,0,0}, - {3638,3141,3144 ,730,730,730 ,0,0,0}, {3138,3635,3628 ,730,730,730 ,0,0,0}, - {3140,3637,3635 ,730,730,730 ,0,0,0}, {3135,3627,3134 ,730,730,730 ,0,0,0}, - {3630,3632,3095 ,730,730,730 ,0,0,0}, {3098,3669,3101 ,730,730,730 ,0,0,0}, - {3102,3101,3671 ,730,730,730 ,0,0,0}, {3104,3675,3107 ,730,730,730 ,0,0,0}, - {3102,3671,3672 ,730,730,730 ,0,0,0}, {3107,3677,3108 ,730,730,730 ,0,0,0}, - {3107,3675,3677 ,730,730,730 ,0,0,0}, {3113,3681,3683 ,730,730,730 ,0,0,0}, - {3110,3108,3678 ,730,730,730 ,0,0,0}, {3114,3113,3683 ,730,730,730 ,0,0,0}, - {3114,3683,3684 ,730,730,730 ,0,0,0}, {3116,3684,3687 ,730,730,730 ,0,0,0}, - {3114,3684,3116 ,730,730,730 ,0,0,0}, {3687,3119,3116 ,730,730,730 ,0,0,0}, - {3687,3689,3119 ,730,730,730 ,0,0,0}, {3119,3689,3120 ,730,730,730 ,0,0,0}, - {3101,3669,3671 ,730,730,730 ,0,0,0}, {3122,3120,3690 ,730,730,730 ,0,0,0}, - {3120,3689,3690 ,730,730,730 ,0,0,0}, {3693,3125,3122 ,730,730,730 ,0,0,0}, - {3693,3122,3690 ,730,730,730 ,0,0,0}, {3125,3695,3126 ,730,730,730 ,0,0,0}, - {3126,3696,3128 ,730,730,730 ,0,0,0}, {3696,3126,3695 ,730,730,730 ,0,0,0}, - {3696,3699,3131 ,730,730,730 ,0,0,0}, {3423,3742,3740 ,730,730,730 ,0,0,0}, - {3132,3131,3699 ,730,730,730 ,0,0,0}, {3702,3706,3426 ,730,730,730 ,0,0,0}, - {3425,3745,3742 ,730,730,730 ,0,0,0}, {3098,3096,3666 ,730,730,730 ,0,0,0}, - {3359,3746,3357 ,730,730,730 ,0,0,0}, {3745,3425,3426 ,730,730,730 ,0,0,0}, - {3627,3630,3134 ,730,730,730 ,0,0,0}, {3481,3299,3478 ,730,730,730 ,0,0,0}, - {3302,3300,3483 ,730,730,730 ,0,0,0}, {3300,3299,3481 ,730,730,730 ,0,0,0}, - {3296,3294,3477 ,730,730,730 ,0,0,0}, {3477,3478,3296 ,730,730,730 ,0,0,0}, - {3475,3293,3472 ,730,730,730 ,0,0,0}, {3475,3294,3293 ,730,730,730 ,0,0,0}, - {3438,3472,3290 ,730,730,730 ,0,0,0}, {3293,3290,3472 ,730,730,730 ,0,0,0}, - {3288,3436,3438 ,730,730,730 ,0,0,0}, {3438,3290,3288 ,730,730,730 ,0,0,0}, - {3434,3286,3320 ,730,730,730 ,0,0,0}, {3287,3436,3288 ,730,730,730 ,0,0,0}, - {3320,3323,3441 ,730,730,730 ,0,0,0}, {3286,3434,3433 ,730,730,730 ,0,0,0}, - {3434,3320,3441 ,730,730,730 ,0,0,0}, {3447,3444,3326 ,730,730,730 ,0,0,0}, - {3368,3758,3759 ,730,730,730 ,0,0,0}, {3329,3447,3326 ,730,730,730 ,0,0,0}, - {3325,3326,3444 ,730,730,730 ,0,0,0}, {3451,3332,3452 ,730,730,730 ,0,0,0}, - {3448,3447,3329 ,730,730,730 ,0,0,0}, {3335,3458,3452 ,730,730,730 ,0,0,0}, - {3332,3451,3331 ,730,730,730 ,0,0,0}, {3338,3455,3337 ,730,730,730 ,0,0,0}, - {3337,3455,3458 ,730,730,730 ,0,0,0}, {3462,3456,3341 ,730,730,730 ,0,0,0}, - {3456,3455,3338 ,730,730,730 ,0,0,0}, {3344,3464,3463 ,730,730,730 ,0,0,0}, - {3343,3463,3462 ,730,730,730 ,0,0,0}, {3468,3349,3350 ,730,730,730 ,0,0,0}, - {3349,3465,3347 ,730,730,730 ,0,0,0}, {3468,3350,3352 ,730,730,730 ,0,0,0}, - {3699,3701,3132 ,730,730,730 ,0,0,0}, {3702,3132,3701 ,730,730,730 ,0,0,0}, - {3420,3739,3419 ,730,730,730 ,0,0,0}, {3131,3128,3696 ,730,730,730 ,0,0,0}, - {3425,3742,3423 ,730,730,730 ,0,0,0}, {3125,3693,3695 ,730,730,730 ,0,0,0}, - {3417,3419,3736 ,730,730,730 ,0,0,0}, {3740,3739,3420 ,730,730,730 ,0,0,0}, - {3414,3417,3734 ,730,730,730 ,0,0,0}, {3739,3736,3419 ,730,730,730 ,0,0,0}, - {3733,3413,3414 ,730,730,730 ,0,0,0}, {3730,3411,3413 ,730,730,730 ,0,0,0}, - {3734,3417,3736 ,730,730,730 ,0,0,0}, {3728,3408,3411 ,730,730,730 ,0,0,0}, - {3733,3414,3734 ,730,730,730 ,0,0,0}, {3110,3681,3113 ,730,730,730 ,0,0,0}, - {3733,3730,3413 ,730,730,730 ,0,0,0}, {3727,3724,3407 ,730,730,730 ,0,0,0}, - {3730,3728,3411 ,730,730,730 ,0,0,0}, {3724,3722,3405 ,730,730,730 ,0,0,0}, - {3722,3721,3402 ,730,730,730 ,0,0,0}, {3721,3718,3401 ,730,730,730 ,0,0,0}, - {3408,3727,3407 ,730,730,730 ,0,0,0}, {3718,3716,3399 ,730,730,730 ,0,0,0}, - {3407,3724,3405 ,730,730,730 ,0,0,0}, {3715,3396,3716 ,730,730,730 ,0,0,0}, - {3405,3722,3402 ,730,730,730 ,0,0,0}, {3395,3715,3712 ,730,730,730 ,0,0,0}, - {3402,3721,3401 ,730,730,730 ,0,0,0}, {3393,3710,3358 ,730,730,730 ,0,0,0}, - {3401,3718,3399 ,730,730,730 ,0,0,0}, {3359,3358,3709 ,730,730,730 ,0,0,0}, - {3716,3396,3399 ,730,730,730 ,0,0,0}, {3357,3747,3361 ,730,730,730 ,0,0,0}, - {3395,3396,3715 ,730,730,730 ,0,0,0}, {3484,3302,3483 ,730,730,730 ,0,0,0}, - {3140,3635,3138 ,730,730,730 ,0,0,0}, {3138,3628,3135 ,730,730,730 ,0,0,0}, - {3358,3710,3709 ,730,730,730 ,0,0,0}, {3484,3487,3305 ,730,730,730 ,0,0,0}, - {3359,3709,3746 ,730,730,730 ,0,0,0}, {3487,3489,3306 ,730,730,730 ,0,0,0}, - {3357,3746,3747 ,730,730,730 ,0,0,0}, {3489,3490,3308 ,730,730,730 ,0,0,0}, - {3490,3493,3311 ,730,730,730 ,0,0,0}, {3481,3483,3300 ,730,730,730 ,0,0,0}, - {3493,3495,3312 ,730,730,730 ,0,0,0}, {3305,3302,3484 ,730,730,730 ,0,0,0}, - {3495,3496,3314 ,730,730,730 ,0,0,0}, {3152,3652,3646 ,730,730,730 ,0,0,0}, - {3150,3646,3645 ,730,730,730 ,0,0,0}, {3489,3308,3306 ,730,730,730 ,0,0,0}, - {3281,3499,3501 ,730,730,730 ,0,0,0}, {3490,3311,3308 ,730,730,730 ,0,0,0}, - {3273,3840,3841 ,730,730,730 ,0,0,0}, {3493,3312,3311 ,730,730,730 ,0,0,0}, - {3078,3081,3058 ,730,730,730 ,0,0,0}, {3052,3086,3053 ,730,730,730 ,0,0,0}, - {3317,3499,3282 ,730,730,730 ,0,0,0}, {3236,3505,3507 ,730,730,730 ,0,0,0}, - {3242,3240,3508 ,730,730,730 ,0,0,0}, {3055,3077,3078 ,730,730,730 ,0,0,0}, - {3230,3564,3562 ,730,730,730 ,0,0,0}, {3842,3256,3843 ,730,730,730 ,0,0,0}, - {3505,3236,3243 ,730,730,730 ,0,0,0}, {3224,3555,3552 ,730,730,730 ,0,0,0}, - {3606,3030,3027 ,730,730,730 ,0,0,0}, {3844,3609,3831 ,730,730,730 ,0,0,0}, - {3611,3831,3609 ,730,730,730 ,0,0,0}, {3609,3844,3030 ,730,730,730 ,0,0,0}, - {3845,3846,3847 ,730,730,730 ,0,0,0}, {3609,3030,3606 ,730,730,730 ,0,0,0}, - {3605,3606,3027 ,730,730,730 ,0,0,0}, {3007,3072,3005 ,730,730,730 ,0,0,0}, - {3838,3827,3192 ,730,730,730 ,0,0,0}, {3848,3849,3850 ,730,730,730 ,0,0,0}, - {3512,3570,3216 ,730,730,730 ,0,0,0}, {3202,3526,3207 ,730,730,730 ,0,0,0}, - {3543,3218,3221 ,730,730,730 ,0,0,0}, {3556,3227,3229 ,730,730,730 ,0,0,0}, - {3556,3555,3227 ,730,730,730 ,0,0,0}, {3558,3229,3561 ,730,730,730 ,0,0,0}, - {3552,3550,3224 ,730,730,730 ,0,0,0}, {3550,3549,3223 ,730,730,730 ,0,0,0}, - {3218,3543,3540 ,730,730,730 ,0,0,0}, {3534,3532,3201 ,730,730,730 ,0,0,0}, - {3201,3531,3202 ,730,730,730 ,0,0,0}, {3526,3525,3207 ,730,730,730 ,0,0,0}, - {3520,3519,3211 ,730,730,730 ,0,0,0}, {3516,3212,3211 ,730,730,730 ,0,0,0}, - {3561,3230,3562 ,730,730,730 ,0,0,0}, {3514,3513,3212 ,730,730,730 ,0,0,0}, - {3570,3217,3216 ,730,730,730 ,0,0,0}, {3573,3575,3217 ,730,730,730 ,0,0,0}, - {3581,3851,3824 ,730,730,730 ,0,0,0}, {3851,3581,3582 ,730,730,730 ,0,0,0}, - {3070,3851,3585 ,730,730,730 ,0,0,0}, {3016,3588,3591 ,730,730,730 ,0,0,0}, - {3019,3018,3594 ,730,730,730 ,0,0,0}, {3016,2997,3588 ,730,730,730 ,0,0,0}, - {3582,3585,3851 ,730,730,730 ,0,0,0}, {3579,3581,3824 ,730,730,730 ,0,0,0}, - {3575,3576,3828 ,730,730,730 ,0,0,0}, {3576,3824,3828 ,730,730,730 ,0,0,0}, - {3570,3573,3217 ,730,730,730 ,0,0,0}, {3513,3216,3212 ,730,730,730 ,0,0,0}, - {3516,3211,3519 ,730,730,730 ,0,0,0}, {3209,3207,3522 ,730,730,730 ,0,0,0}, - {3209,3522,3520 ,730,730,730 ,0,0,0}, {3202,3528,3526 ,730,730,730 ,0,0,0}, - {3201,3532,3531 ,730,730,730 ,0,0,0}, {3205,3537,3534 ,730,730,730 ,0,0,0}, - {3218,3540,3538 ,730,730,730 ,0,0,0}, {3221,3544,3543 ,730,730,730 ,0,0,0}, - {3223,3549,3546 ,730,730,730 ,0,0,0}, {3223,3224,3550 ,730,730,730 ,0,0,0}, - {3224,3227,3555 ,730,730,730 ,0,0,0}, {3229,3558,3556 ,730,730,730 ,0,0,0}, - {3229,3230,3561 ,730,730,730 ,0,0,0}, {3230,3242,3564 ,730,730,730 ,0,0,0}, - {3242,3508,3567 ,730,730,730 ,0,0,0}, {3564,3242,3567 ,730,730,730 ,0,0,0}, - {3508,3240,3237 ,730,730,730 ,0,0,0}, {3237,3233,3507 ,730,730,730 ,0,0,0}, - {3507,3508,3237 ,730,730,730 ,0,0,0}, {3059,3058,3081 ,730,730,730 ,0,0,0}, - {3236,3507,3233 ,730,730,730 ,0,0,0}, {3038,3248,3249 ,730,730,730 ,0,0,0}, - {3059,3081,3083 ,730,730,730 ,0,0,0}, {3084,3257,3064 ,730,730,730 ,0,0,0}, - {3083,3061,3059 ,730,730,730 ,0,0,0}, {3084,3064,3061 ,730,730,730 ,0,0,0}, - {3265,3852,3258 ,730,730,730 ,0,0,0}, {3261,3853,3253 ,730,730,730 ,0,0,0}, - {3854,3266,3855 ,730,730,730 ,0,0,0}, {3273,3856,3855 ,730,730,730 ,0,0,0}, - {3088,3050,3091 ,730,730,730 ,0,0,0}, {3857,3272,3858 ,730,730,730 ,0,0,0}, - {3052,3050,3088 ,730,730,730 ,0,0,0}, {3501,3276,3279 ,730,730,730 ,0,0,0}, - {3502,3275,3276 ,730,730,730 ,0,0,0}, {3041,3248,3039 ,730,730,730 ,0,0,0}, - {3249,3035,3038 ,730,730,730 ,0,0,0}, {3041,3048,3246 ,730,730,730 ,0,0,0}, - {3269,3275,3502 ,730,730,730 ,0,0,0}, {3269,3502,3505 ,730,730,730 ,0,0,0}, - {3276,3501,3502 ,730,730,730 ,0,0,0}, {3281,3501,3279 ,730,730,730 ,0,0,0}, - {3282,3499,3281 ,730,730,730 ,0,0,0}, {3496,3499,3317 ,730,730,730 ,0,0,0}, - {3314,3496,3317 ,730,730,730 ,0,0,0}, {3312,3495,3314 ,730,730,730 ,0,0,0}, - {3361,3750,3363 ,730,730,730 ,0,0,0}, {3753,3363,3752 ,730,730,730 ,0,0,0}, - {3296,3478,3299 ,730,730,730 ,0,0,0}, {3756,3364,3753 ,730,730,730 ,0,0,0}, - {3756,3367,3364 ,730,730,730 ,0,0,0}, {3758,3368,3367 ,730,730,730 ,0,0,0}, - {3750,3361,3747 ,730,730,730 ,0,0,0}, {3759,3374,3368 ,730,730,730 ,0,0,0}, - {3752,3363,3750 ,730,730,730 ,0,0,0}, {3286,3433,3287 ,730,730,730 ,0,0,0}, - {3370,3374,3762 ,730,730,730 ,0,0,0}, {3364,3363,3753 ,730,730,730 ,0,0,0}, - {3371,3370,3764 ,730,730,730 ,0,0,0}, {3756,3758,3367 ,730,730,730 ,0,0,0}, - {3377,3371,3765 ,730,730,730 ,0,0,0}, {3325,3444,3443 ,730,730,730 ,0,0,0}, - {3323,3443,3441 ,730,730,730 ,0,0,0}, {3374,3759,3762 ,730,730,730 ,0,0,0}, - {3378,3377,3768 ,730,730,730 ,0,0,0}, {3378,3768,3770 ,730,730,730 ,0,0,0}, - {3762,3764,3370 ,730,730,730 ,0,0,0}, {3331,3451,3448 ,730,730,730 ,0,0,0}, - {3371,3764,3765 ,730,730,730 ,0,0,0}, {3770,3771,3381 ,730,730,730 ,0,0,0}, - {3774,3387,3771 ,730,730,730 ,0,0,0}, {3765,3768,3377 ,730,730,730 ,0,0,0}, - {3381,3378,3770 ,730,730,730 ,0,0,0}, {3776,3385,3774 ,730,730,730 ,0,0,0}, - {3335,3337,3458 ,730,730,730 ,0,0,0}, {3777,3383,3776 ,730,730,730 ,0,0,0}, - {3387,3381,3771 ,730,730,730 ,0,0,0}, {3341,3343,3462 ,730,730,730 ,0,0,0}, - {3774,3385,3387 ,730,730,730 ,0,0,0}, {3777,3780,3388 ,730,730,730 ,0,0,0}, - {3344,3347,3464 ,730,730,730 ,0,0,0}, {3776,3383,3385 ,730,730,730 ,0,0,0}, - {3390,3388,3780 ,730,730,730 ,0,0,0}, {3390,3782,3353 ,730,730,730 ,0,0,0}, - {3465,3349,3468 ,730,730,730 ,0,0,0}, {3390,3780,3782 ,730,730,730 ,0,0,0}, - {3432,3352,3353 ,730,730,730 ,0,0,0}, {3470,3352,3432 ,730,730,730 ,0,0,0}, - {3782,3430,3353 ,730,730,730 ,0,0,0}, {3432,3353,3430 ,730,730,730 ,0,0,0}, - {3777,3388,3383 ,730,730,730 ,0,0,0}, {3393,3395,3712 ,730,730,730 ,0,0,0}, - {3727,3408,3728 ,730,730,730 ,0,0,0}, {3740,3420,3423 ,730,730,730 ,0,0,0}, - {3702,3426,3132 ,730,730,730 ,0,0,0}, {3706,3745,3426 ,730,730,730 ,0,0,0}, - {3053,3085,3055 ,730,730,730 ,0,0,0}, {3859,3261,3263 ,730,730,730 ,0,0,0}, - {3265,3854,3852 ,730,730,730 ,0,0,0}, {3055,3078,3058 ,730,730,730 ,0,0,0}, - {3055,3085,3077 ,730,730,730 ,0,0,0}, {3053,3086,3085 ,730,730,730 ,0,0,0}, - {3052,3088,3086 ,730,730,730 ,0,0,0}, {3267,3269,3860 ,730,730,730 ,0,0,0}, - {3031,3037,3091 ,730,730,730 ,0,0,0}, {3031,3091,3050 ,730,730,730 ,0,0,0}, - {3249,3037,3035 ,730,730,730 ,0,0,0}, {3037,3249,3091 ,730,730,730 ,0,0,0}, - {3044,3269,3505 ,730,730,730 ,0,0,0}, {3041,3246,3248 ,730,730,730 ,0,0,0}, - {3038,3039,3248 ,730,730,730 ,0,0,0}, {3045,3246,3048 ,730,730,730 ,0,0,0}, - {3505,3045,3044 ,730,730,730 ,0,0,0}, {3243,3045,3505 ,730,730,730 ,0,0,0}, - {3045,3243,3246 ,730,730,730 ,0,0,0}, {3044,3860,3269 ,730,730,730 ,0,0,0}, - {3267,3858,3272 ,730,730,730 ,0,0,0}, {3860,3858,3267 ,730,730,730 ,0,0,0}, - {3272,3840,3273 ,730,730,730 ,0,0,0}, {3857,3840,3272 ,730,730,730 ,0,0,0}, - {3841,3856,3273 ,730,730,730 ,0,0,0}, {3855,3266,3273 ,730,730,730 ,0,0,0}, - {3854,3265,3266 ,730,730,730 ,0,0,0}, {3861,3258,3852 ,730,730,730 ,0,0,0}, - {3263,3861,3859 ,730,730,730 ,0,0,0}, {3861,3263,3258 ,730,730,730 ,0,0,0}, - {3859,3862,3261 ,730,730,730 ,0,0,0}, {3853,3843,3253 ,730,730,730 ,0,0,0}, - {3862,3853,3261 ,730,730,730 ,0,0,0}, {3256,3842,3257 ,730,730,730 ,0,0,0}, - {3253,3843,3256 ,730,730,730 ,0,0,0}, {3064,3257,3842 ,730,730,730 ,0,0,0}, - {3068,3070,3003 ,730,730,730 ,0,0,0}, {3600,3603,3025 ,730,730,730 ,0,0,0}, - {3187,3184,3863 ,730,730,730 ,0,0,0}, {3019,3594,3597 ,730,730,730 ,0,0,0}, - {3597,3021,3019 ,730,730,730 ,0,0,0}, {3593,3594,3018 ,730,730,730 ,0,0,0}, - {3593,3016,3591 ,730,730,730 ,0,0,0}, {3016,3593,3018 ,730,730,730 ,0,0,0}, - {3588,2997,3587 ,730,730,730 ,0,0,0}, {2997,3003,3070 ,730,730,730 ,0,0,0}, - {3003,3001,3068 ,730,730,730 ,0,0,0}, {3001,3004,3065 ,730,730,730 ,0,0,0}, - {3005,3072,3065 ,730,730,730 ,0,0,0}, {3014,3072,3007 ,730,730,730 ,0,0,0}, - {3011,3074,3014 ,730,730,730 ,0,0,0}, {3010,3199,3011 ,730,730,730 ,0,0,0}, - {3836,3197,3010 ,730,730,730 ,0,0,0}, {3829,3194,3836 ,730,730,730 ,0,0,0}, - {3838,3193,3829 ,730,730,730 ,0,0,0}, {3177,3192,3827 ,730,730,730 ,0,0,0}, - {3837,3178,3827 ,730,730,730 ,0,0,0}, {3839,3182,3837 ,730,730,730 ,0,0,0}, - {3863,3184,3839 ,730,730,730 ,0,0,0}, {3864,3189,3835 ,730,730,730 ,0,0,0}, - {3835,3187,3863 ,730,730,730 ,0,0,0}, {3188,3864,3850 ,730,730,730 ,0,0,0}, - {3864,3188,3189 ,730,730,730 ,0,0,0}, {3848,3833,3849 ,730,730,730 ,0,0,0}, - {3188,3850,3849 ,730,730,730 ,0,0,0}, {3832,3834,3845 ,730,730,730 ,0,0,0}, - {3849,3833,3832 ,730,730,730 ,0,0,0}, {3845,3847,3844 ,730,730,730 ,0,0,0}, - {3845,3834,3846 ,730,730,730 ,0,0,0}, {3030,3844,3847 ,730,730,730 ,0,0,0}, - {3844,3831,3794 ,3296,3297,3298 ,0,0,0}, {3845,3787,3791 ,3299,3300,3301 ,0,0,0}, - {3787,3844,3794 ,3300,3296,3298 ,0,0,0}, {3844,3787,3845 ,3296,3300,3299 ,0,0,0}, - {3849,3816,3799 ,3302,3303,3304 ,0,0,0}, {3845,3791,3832 ,3299,3301,3305 ,0,0,0}, - {3849,3832,3816 ,3302,3305,3303 ,0,0,0}, {3799,3190,3188 ,3304,2732,2732 ,0,0,0}, - {3799,3188,3849 ,3304,2732,3302 ,0,0,0}, {3816,3832,3791 ,3303,3305,3301 ,0,0,0}, - {3831,3783,3794 ,3297,3306,3298 ,0,0,0}, {3795,3783,3830 ,3307,3306,3308 ,0,0,0}, - {3831,3830,3783 ,3297,3308,3306 ,0,0,0}, {3826,3796,3795 ,3309,3310,3307 ,0,0,0}, - {3795,3830,3826 ,3307,3308,3309 ,0,0,0}, {3796,3825,3176 ,3310,3311,2722 ,0,0,0}, - {3825,3796,3826 ,3311,3310,3309 ,0,0,0}, {3825,3175,3176 ,3311,2722,2722 ,0,0,0}, - {3071,3788,3851 ,2635,3312,3312 ,0,0,0}, {3784,3217,3828 ,3313,2758,3314 ,0,0,0}, - {3828,3824,3785 ,3314,3315,3315 ,0,0,0}, {3215,3217,3784 ,2758,2758,3313 ,0,0,0}, - {3788,3824,3851 ,3312,3315,3312 ,0,0,0}, {3824,3788,3785 ,3315,3312,3315 ,0,0,0}, - {3784,3828,3785 ,3313,3314,3315 ,0,0,0}, {3851,3070,3071 ,3312,2635,2635 ,0,0,0}, - {3049,3814,3860 ,3316,795,3317 ,0,0,0}, {3812,3840,3813 ,3318,3319,3320 ,0,0,0}, - {3857,3858,3806 ,3321,3322,857 ,0,0,0}, {3855,3822,3854 ,3323,3324,21 ,0,0,0}, - {3811,3810,3856 ,3325,3326,3327 ,0,0,0}, {3808,3859,3861 ,3328,3329,3330 ,0,0,0}, - {3807,3852,3809 ,3331,3332,3333 ,0,0,0}, {3801,3853,3862 ,3334,3335,3336 ,0,0,0}, - {3862,3859,3803 ,3336,3329,3337 ,0,0,0}, {3853,3802,3843 ,3335,3338,3339 ,0,0,0}, - {3802,3853,3801 ,3338,3335,3334 ,0,0,0}, {3842,3843,3805 ,3340,3339,3341 ,0,0,0}, - {3802,3805,3843 ,3338,3341,3339 ,0,0,0}, {3804,3064,3842 ,3342,82,3340 ,0,0,0}, - {3842,3805,3804 ,3340,3341,3342 ,0,0,0}, {3063,3064,3804 ,3343,82,3342 ,0,0,0}, - {3807,3808,3861 ,3331,3328,3330 ,0,0,0}, {3859,3808,3803 ,3329,3328,3337 ,0,0,0}, - {3801,3862,3803 ,3334,3336,3337 ,0,0,0}, {3807,3861,3852 ,3331,3330,3332 ,0,0,0}, - {3809,3852,3854 ,3333,3332,21 ,0,0,0}, {3822,3855,3810 ,3324,3323,3326 ,0,0,0}, - {3822,3809,3854 ,3324,3333,21 ,0,0,0}, {3811,3856,3841 ,3325,3327,3344 ,0,0,0}, - {3856,3810,3855 ,3327,3326,3323 ,0,0,0}, {3841,3840,3812 ,3344,3319,3318 ,0,0,0}, - {3841,3812,3811 ,3344,3318,3325 ,0,0,0}, {3806,3813,3857 ,857,3320,3321 ,0,0,0}, - {3840,3857,3813 ,3319,3321,3320 ,0,0,0}, {3858,3814,3806 ,3322,795,857 ,0,0,0}, - {3049,3860,3044 ,3316,3317,3345 ,0,0,0}, {3814,3858,3860 ,795,3322,3317 ,0,0,0}, - {3015,3823,3836 ,3346,3347,3348 ,0,0,0}, {3793,3827,3797 ,3349,3350,3351 ,0,0,0}, - {3838,3829,3821 ,3321,801,857 ,0,0,0}, {3863,3817,3835 ,3352,3353,21 ,0,0,0}, - {3792,3819,3839 ,3354,807,3355 ,0,0,0}, {3820,3848,3850 ,3356,3357,3358 ,0,0,0}, - {3789,3864,3818 ,3359,3360,21 ,0,0,0}, {3800,3834,3833 ,3361,3362,3363 ,0,0,0}, - {3833,3848,3798 ,3363,3357,3364 ,0,0,0}, {3834,3815,3846 ,3362,3365,3366 ,0,0,0}, - {3815,3834,3800 ,3365,3362,3361 ,0,0,0}, {3847,3846,3790 ,3367,3366,3368 ,0,0,0}, - {3815,3790,3846 ,3365,3368,3366 ,0,0,0}, {3786,3030,3847 ,3369,3370,3367 ,0,0,0}, - {3847,3790,3786 ,3367,3368,3369 ,0,0,0}, {3029,3030,3786 ,3371,3370,3369 ,0,0,0}, - {3789,3820,3850 ,3359,3356,3358 ,0,0,0}, {3848,3820,3798 ,3357,3356,3364 ,0,0,0}, - {3800,3833,3798 ,3361,3363,3364 ,0,0,0}, {3789,3850,3864 ,3359,3358,3360 ,0,0,0}, - {3818,3864,3835 ,21,3360,21 ,0,0,0}, {3817,3863,3819 ,3353,3352,807 ,0,0,0}, - {3817,3818,3835 ,3353,21,21 ,0,0,0}, {3792,3839,3837 ,3354,3355,3372 ,0,0,0}, - {3839,3819,3863 ,3355,807,3352 ,0,0,0}, {3837,3827,3793 ,3372,3350,3349 ,0,0,0}, - {3837,3793,3792 ,3372,3349,3354 ,0,0,0}, {3821,3797,3838 ,857,3351,3321 ,0,0,0}, - {3827,3838,3797 ,3350,3321,3351 ,0,0,0}, {3829,3823,3821 ,801,3347,857 ,0,0,0}, - {3015,3836,3010 ,3346,3348,126 ,0,0,0}, {3823,3829,3836 ,3347,801,3348 ,0,0,0} -// BladeProtector2.prt - , {3865,3866,3867 ,21,3324,3333 ,0,0,0}, {3868,3869,3870 ,3328,3330,3331 ,0,0,0}, - {3871,3865,3867 ,3332,21,3333 ,0,0,0}, {3870,3869,3871 ,3331,3330,3332 ,0,0,0}, - {3869,3868,3872 ,3330,3328,3329 ,0,0,0}, {3867,3870,3871 ,3333,3331,3332 ,0,0,0}, - {3873,3874,3875 ,3336,3334,3335 ,0,0,0}, {3874,3876,3875 ,3334,3338,3335 ,0,0,0}, - {3872,3877,3873 ,3329,3337,3336 ,0,0,0}, {3874,3873,3877 ,3334,3336,3337 ,0,0,0}, - {3878,3879,3880 ,82,3340,3342 ,0,0,0}, {3881,3882,3876 ,3341,3339,3338 ,0,0,0}, - {3879,3882,3881 ,3340,3339,3341 ,0,0,0}, {3879,3881,3880 ,3340,3341,3342 ,0,0,0}, - {3880,3883,3878 ,3342,3343,82 ,0,0,0}, {3875,3876,3882 ,3335,3338,3339 ,0,0,0}, - {3872,3868,3877 ,3329,3328,3337 ,0,0,0}, {3865,3884,3866 ,21,3323,3324 ,0,0,0}, - {3885,3884,3886 ,3326,3323,3327 ,0,0,0}, {3884,3885,3866 ,3323,3326,3324 ,0,0,0}, - {3887,3888,3886 ,3344,3325,3327 ,0,0,0}, {3885,3886,3888 ,3326,3327,3325 ,0,0,0}, - {3887,3889,3890 ,3344,3319,3318 ,0,0,0}, {3890,3888,3887 ,3318,3325,3344 ,0,0,0}, - {3891,3889,3892 ,3320,3319,3321 ,0,0,0}, {3889,3891,3890 ,3319,3320,3318 ,0,0,0}, - {3893,3894,3892 ,3322,857,3321 ,0,0,0}, {3891,3892,3894 ,3320,3321,857 ,0,0,0}, - {3893,3895,3896 ,3322,3317,795 ,0,0,0}, {3896,3894,3893 ,795,857,3322 ,0,0,0}, - {3897,3895,3898 ,3316,3317,3345 ,0,0,0}, {3895,3897,3896 ,3317,3316,795 ,0,0,0}, - {3899,3900,3901 ,21,3353,21 ,0,0,0}, {3902,3903,3904 ,3356,3358,3359 ,0,0,0}, - {3905,3899,3901 ,3360,21,21 ,0,0,0}, {3904,3903,3905 ,3359,3358,3360 ,0,0,0}, - {3903,3902,3906 ,3358,3356,3357 ,0,0,0}, {3901,3904,3905 ,21,3359,3360 ,0,0,0}, - {3907,3908,3909 ,3363,3361,3362 ,0,0,0}, {3908,3910,3909 ,3361,3365,3362 ,0,0,0}, - {3906,3911,3907 ,3357,3364,3363 ,0,0,0}, {3908,3907,3911 ,3361,3363,3364 ,0,0,0}, - {3912,3913,3914 ,3370,3367,3369 ,0,0,0}, {3915,3916,3910 ,3368,3366,3365 ,0,0,0}, - {3913,3916,3915 ,3367,3366,3368 ,0,0,0}, {3913,3915,3914 ,3367,3368,3369 ,0,0,0}, - {3914,3917,3912 ,3369,3371,3370 ,0,0,0}, {3909,3910,3916 ,3362,3365,3366 ,0,0,0}, - {3906,3902,3911 ,3357,3356,3364 ,0,0,0}, {3899,3918,3900 ,21,3352,3353 ,0,0,0}, - {3919,3918,3920 ,807,3352,3355 ,0,0,0}, {3918,3919,3900 ,3352,807,3353 ,0,0,0}, - {3921,3922,3920 ,3372,3354,3355 ,0,0,0}, {3919,3920,3922 ,807,3355,3354 ,0,0,0}, - {3921,3923,3924 ,3372,3350,3349 ,0,0,0}, {3924,3922,3921 ,3349,3354,3372 ,0,0,0}, - {3925,3923,3926 ,3351,3350,3321 ,0,0,0}, {3923,3925,3924 ,3350,3351,3349 ,0,0,0}, - {3927,3928,3926 ,801,857,3321 ,0,0,0}, {3925,3926,3928 ,3351,3321,857 ,0,0,0}, - {3927,3929,3930 ,801,3348,3347 ,0,0,0}, {3930,3928,3927 ,3347,857,801 ,0,0,0}, - {3931,3929,3932 ,3346,3348,126 ,0,0,0}, {3929,3931,3930 ,3348,3346,3347 ,0,0,0}, - {3933,3934,3935 ,3373,3374,3373 ,0,0,0}, {3936,3937,3938 ,3375,3376,3377 ,0,0,0}, - {3936,3935,3937 ,3375,3373,3376 ,0,0,0}, {3938,3937,3939 ,3377,3376,3377 ,0,0,0}, - {3935,3936,3933 ,3373,3375,3373 ,0,0,0}, {3940,3934,3933 ,3374,3374,3373 ,0,0,0}, - {3941,3940,3942 ,3378,3374,3378 ,0,0,0}, {3940,3941,3934 ,3374,3378,3374 ,0,0,0}, - {3943,3944,3945 ,2038,2043,2038 ,0,0,0}, {3946,3944,3947 ,2043,2043,2041 ,0,0,0}, - {3944,3946,3945 ,2043,2043,2038 ,0,0,0}, {3948,3949,3947 ,2042,2041,2041 ,0,0,0}, - {3946,3947,3949 ,2043,2041,2041 ,0,0,0}, {3948,3950,3951 ,2042,3379,2042 ,0,0,0}, - {3951,3949,3948 ,2042,2041,2042 ,0,0,0}, {3950,3952,3951 ,3379,3380,2042 ,0,0,0}, - {3953,3943,3945 ,2039,2038,2038 ,0,0,0}, {3954,3955,3953 ,2040,2039,2039 ,0,0,0}, - {3943,3953,3955 ,2038,2039,2039 ,0,0,0}, {3954,3956,3957 ,2040,2035,2040 ,0,0,0}, - {3957,3955,3954 ,2040,2039,2040 ,0,0,0}, {3958,3956,3959 ,2035,2035,3381 ,0,0,0}, - {3956,3958,3957 ,2035,2035,2040 ,0,0,0}, {3958,3959,3960 ,2035,3381,3382 ,0,0,0}, - {3961,3962,3963 ,3383,3384,3385 ,0,0,0}, {3964,3965,3961 ,3386,3387,3383 ,0,0,0}, - {3961,3963,3964 ,3383,3385,3386 ,0,0,0}, {3965,3966,3967 ,3387,3388,3389 ,0,0,0}, - {3966,3965,3964 ,3388,3387,3386 ,0,0,0}, {3968,3967,3969 ,3390,3389,3391 ,0,0,0}, - {3966,3969,3967 ,3388,3391,3389 ,0,0,0}, {3970,3971,3968 ,3392,3393,3390 ,0,0,0}, - {3968,3969,3970 ,3390,3391,3392 ,0,0,0}, {3971,3972,3973 ,3393,3394,3395 ,0,0,0}, - {3972,3971,3970 ,3394,3393,3392 ,0,0,0}, {3974,3973,3975 ,3396,3395,3397 ,0,0,0}, - {3972,3975,3973 ,3394,3397,3395 ,0,0,0}, {3976,3977,3974 ,3398,3399,3396 ,0,0,0}, - {3974,3975,3976 ,3396,3397,3398 ,0,0,0}, {3977,3978,3979 ,3399,3400,3401 ,0,0,0}, - {3978,3977,3976 ,3400,3399,3398 ,0,0,0}, {3980,3979,3981 ,3402,3401,3403 ,0,0,0}, - {3978,3981,3979 ,3400,3403,3401 ,0,0,0}, {3982,3983,3980 ,3404,3405,3402 ,0,0,0}, - {3980,3981,3982 ,3402,3403,3404 ,0,0,0}, {3983,3984,3985 ,3405,3406,3407 ,0,0,0}, - {3984,3983,3982 ,3406,3405,3404 ,0,0,0}, {3986,3985,3987 ,3408,3407,3409 ,0,0,0}, - {3984,3987,3985 ,3406,3409,3407 ,0,0,0}, {3988,3989,3986 ,3410,3411,3408 ,0,0,0}, - {3986,3987,3988 ,3408,3409,3410 ,0,0,0}, {3989,3990,3991 ,3411,3412,3413 ,0,0,0}, - {3990,3989,3988 ,3412,3411,3410 ,0,0,0}, {3992,3991,3993 ,3414,3413,3415 ,0,0,0}, - {3990,3993,3991 ,3412,3415,3413 ,0,0,0}, {3994,3995,3992 ,3416,3417,3414 ,0,0,0}, - {3992,3993,3994 ,3414,3415,3416 ,0,0,0}, {3995,3996,3997 ,3417,3418,3419 ,0,0,0}, - {3996,3995,3994 ,3418,3417,3416 ,0,0,0}, {3998,3997,3999 ,3420,3419,3421 ,0,0,0}, - {3996,3999,3997 ,3418,3421,3419 ,0,0,0}, {4000,4001,3998 ,3422,3422,3420 ,0,0,0}, - {3998,3999,4000 ,3420,3421,3422 ,0,0,0}, {3963,3962,4002 ,3385,3384,3423 ,0,0,0}, - {4003,4002,4004 ,3424,3423,3425 ,0,0,0}, {3962,4004,4002 ,3384,3425,3423 ,0,0,0}, - {4005,4006,4003 ,3426,3427,3424 ,0,0,0}, {4003,4004,4005 ,3424,3425,3426 ,0,0,0}, - {4006,4007,4008 ,3427,3428,3429 ,0,0,0}, {4007,4006,4005 ,3428,3427,3426 ,0,0,0}, - {4009,4008,4010 ,3430,3429,3431 ,0,0,0}, {4007,4010,4008 ,3428,3431,3429 ,0,0,0}, - {4011,4012,4009 ,3432,3433,3430 ,0,0,0}, {4009,4010,4011 ,3430,3431,3432 ,0,0,0}, - {4012,4013,4014 ,3433,3434,3435 ,0,0,0}, {4013,4012,4011 ,3434,3433,3432 ,0,0,0}, - {4015,4014,4016 ,3436,3435,3437 ,0,0,0}, {4013,4016,4014 ,3434,3437,3435 ,0,0,0}, - {4017,4018,4015 ,3438,3439,3436 ,0,0,0}, {4015,4016,4017 ,3436,3437,3438 ,0,0,0}, - {4018,4019,4020 ,3439,3440,3441 ,0,0,0}, {4019,4018,4017 ,3440,3439,3438 ,0,0,0}, - {4021,4020,4022 ,3442,3441,3443 ,0,0,0}, {4019,4022,4020 ,3440,3443,3441 ,0,0,0}, - {4023,4024,4021 ,3444,3445,3442 ,0,0,0}, {4021,4022,4023 ,3442,3443,3444 ,0,0,0}, - {4024,4025,4026 ,3445,3446,3447 ,0,0,0}, {4025,4024,4023 ,3446,3445,3444 ,0,0,0}, - {4027,4026,4028 ,3448,3447,3449 ,0,0,0}, {4025,4028,4026 ,3446,3449,3447 ,0,0,0}, - {4029,4030,4027 ,3450,3451,3448 ,0,0,0}, {4027,4028,4029 ,3448,3449,3450 ,0,0,0}, - {4030,4031,4032 ,3451,3452,3453 ,0,0,0}, {4031,4030,4029 ,3452,3451,3450 ,0,0,0}, - {4033,4032,4034 ,3454,3453,3455 ,0,0,0}, {4031,4034,4032 ,3452,3455,3453 ,0,0,0}, - {4035,4036,4033 ,3456,3457,3454 ,0,0,0}, {4033,4034,4035 ,3454,3455,3456 ,0,0,0}, - {4036,4037,4038 ,3457,3458,3459 ,0,0,0}, {4037,4036,4035 ,3458,3457,3456 ,0,0,0}, - {4037,4039,4038 ,3458,3460,3459 ,0,0,0}, {4038,4039,4040 ,3459,3460,3461 ,0,0,0}, - {4041,4042,4039 ,3462,3462,3463 ,0,0,0}, {4041,4043,4042 ,3462,3464,3462 ,0,0,0}, - {4043,4041,4044 ,3464,3462,3464 ,0,0,0}, {4040,4039,4042 ,126,3463,3462 ,0,0,0}, - {4045,4046,4047 ,1273,3465,1273 ,0,0,0}, {4048,4049,4046 ,3466,3467,3465 ,0,0,0}, - {4046,4049,4047 ,3465,3467,1273 ,0,0,0}, {4050,4051,4048 ,3468,3469,3466 ,0,0,0}, - {4048,4046,4050 ,3466,3465,3468 ,0,0,0}, {4051,4052,4053 ,3469,3470,3471 ,0,0,0}, - {4052,4051,4050 ,3470,3469,3468 ,0,0,0}, {4054,4053,4055 ,3472,3471,3473 ,0,0,0}, - {4052,4055,4053 ,3470,3473,3471 ,0,0,0}, {4056,4054,4057 ,3474,3472,3475 ,0,0,0}, - {4054,4055,4057 ,3472,3473,3475 ,0,0,0}, {4058,4054,4056 ,3474,3472,3474 ,0,0,0}, - {4059,4045,4047 ,3476,1273,1273 ,0,0,0}, {4060,4059,4061 ,3477,3476,3478 ,0,0,0}, - {4060,4045,4059 ,3477,1273,3476 ,0,0,0}, {4062,4061,4063 ,3479,3478,3480 ,0,0,0}, - {4059,4063,4061 ,3476,3480,3478 ,0,0,0}, {4064,4065,4062 ,3481,3482,3479 ,0,0,0}, - {4062,4063,4064 ,3479,3480,3481 ,0,0,0}, {4065,4066,4067 ,3482,3483,3484 ,0,0,0}, - {4066,4065,4064 ,3483,3482,3481 ,0,0,0}, {4067,4068,3941 ,3484,3485,3378 ,0,0,0}, - {4066,4068,4067 ,3483,3485,3484 ,0,0,0}, {4067,3941,3942 ,3484,3378,3378 ,0,0,0}, - {4069,4070,4071 ,3486,3487,3488 ,0,0,0}, {4069,4072,4073 ,3486,3489,3490 ,0,0,0}, - {4071,4070,4074 ,3488,3487,3491 ,0,0,0}, {4074,4070,4075 ,3491,3487,3492 ,0,0,0}, - {4074,4075,4076 ,3491,3492,3493 ,0,0,0}, {4077,4076,4075 ,3494,3493,3492 ,0,0,0}, - {4076,4077,4078 ,3493,3494,3495 ,0,0,0}, {4079,4078,4077 ,3496,3495,3494 ,0,0,0}, - {4079,4080,4081 ,3496,3497,3498 ,0,0,0}, {4078,4079,4081 ,3495,3496,3498 ,0,0,0}, - {4071,4072,4069 ,3488,3489,3486 ,0,0,0}, {4081,4080,4082 ,3498,3497,3499 ,0,0,0}, - {4083,4082,4084 ,3500,3499,3501 ,0,0,0}, {4084,4082,4080 ,3501,3499,3497 ,0,0,0}, - {4083,4084,4085 ,3500,3501,3500 ,0,0,0}, {4086,4073,4087 ,3502,3490,3503 ,0,0,0}, - {4072,4087,4073 ,3489,3503,3490 ,0,0,0}, {4088,4089,4086 ,3504,3505,3502 ,0,0,0}, - {4086,4087,4088 ,3502,3503,3504 ,0,0,0}, {4089,4090,4091 ,3505,3506,3507 ,0,0,0}, - {4090,4089,4088 ,3506,3505,3504 ,0,0,0}, {4092,4091,4093 ,3508,3507,3509 ,0,0,0}, - {4090,4093,4091 ,3506,3509,3507 ,0,0,0}, {4094,4095,4092 ,3510,3511,3508 ,0,0,0}, - {4092,4093,4094 ,3508,3509,3510 ,0,0,0}, {4095,4096,4097 ,3511,3512,3513 ,0,0,0}, - {4096,4095,4094 ,3512,3511,3510 ,0,0,0}, {4098,4097,4099 ,3514,3513,3515 ,0,0,0}, - {4096,4099,4097 ,3512,3515,3513 ,0,0,0}, {4098,4099,4100 ,3514,3515,3514 ,0,0,0}, - {4101,4102,4103 ,3516,3517,3516 ,0,0,0}, {4103,4104,4101 ,3516,3518,3516 ,0,0,0}, - {4105,4106,4102 ,3517,3519,3517 ,0,0,0}, {4107,4104,4103 ,3518,3518,3516 ,0,0,0}, - {4101,4105,4102 ,3516,3517,3517 ,0,0,0}, {4105,4108,4106 ,3517,3519,3519 ,0,0,0}, - {4109,4108,4110 ,3520,3519,3520 ,0,0,0}, {4110,4098,4100 ,3520,3514,3514 ,0,0,0}, - {4109,4106,4108 ,3520,3519,3519 ,0,0,0}, {4110,4100,4109 ,3520,3514,3520 ,0,0,0}, - {4111,4107,4112 ,3521,3518,3521 ,0,0,0}, {4107,4111,4104 ,3518,3521,3518 ,0,0,0}, - {4113,4114,4112 ,3522,3522,3521 ,0,0,0}, {4111,4112,4114 ,3521,3521,3522 ,0,0,0}, - {4113,4115,4116 ,3522,3523,3523 ,0,0,0}, {4116,4114,4113 ,3523,3522,3522 ,0,0,0}, - {4117,4115,4118 ,3524,3523,3524 ,0,0,0}, {4115,4117,4116 ,3523,3524,3523 ,0,0,0}, - {4117,4118,3959 ,3524,3524,3525 ,0,0,0}, {3959,4118,3960 ,3525,3524,3526 ,0,0,0}, - {4119,3952,3950 ,1122,3527,3528 ,0,0,0}, {4120,4121,4122 ,1114,1120,1120 ,0,0,0}, - {4123,4124,4125 ,1121,1121,1122 ,0,0,0}, {4126,4127,4128 ,1116,1116,1117 ,0,0,0}, - {4129,4130,4131 ,1114,1115,1115 ,0,0,0}, {4132,4133,4128 ,3529,1117,1117 ,0,0,0}, - {4126,4128,4133 ,1116,1117,1117 ,0,0,0}, {4134,4133,4132 ,3530,1117,3529 ,0,0,0}, - {4130,4127,4131 ,1115,1116,1115 ,0,0,0}, {4131,4127,4126 ,1115,1116,1116 ,0,0,0}, - {4129,4121,4120 ,1114,1120,1114 ,0,0,0}, {4129,4120,4130 ,1114,1114,1115 ,0,0,0}, - {4122,4124,4123 ,1120,1121,1121 ,0,0,0}, {4121,4124,4122 ,1120,1121,1120 ,0,0,0}, - {4119,4125,3952 ,1122,1122,3527 ,0,0,0}, {4123,4125,4119 ,1121,1122,1122 ,0,0,0}, - {4135,4136,4137 ,3531,3531,3532 ,0,0,0}, {4137,4136,4138 ,3532,3531,3532 ,0,0,0}, - {4136,4135,4139 ,3531,3531,3533 ,0,0,0}, {4140,4139,4135 ,3534,3533,3531 ,0,0,0}, - {4141,4142,4140 ,3535,3535,3534 ,0,0,0}, {4143,4137,4138 ,3536,3532,3532 ,0,0,0}, - {4134,4132,4141 ,3537,3538,3535 ,0,0,0}, {4142,4141,4132 ,3535,3535,3538 ,0,0,0}, - {4140,4142,4139 ,3534,3535,3533 ,0,0,0}, {4144,4143,4145 ,3539,3536,3536 ,0,0,0}, - {4138,4145,4143 ,3532,3536,3536 ,0,0,0}, {4146,4147,4144 ,3539,3540,3539 ,0,0,0}, - {4144,4145,4146 ,3539,3536,3539 ,0,0,0}, {4147,4148,4149 ,3540,3540,3541 ,0,0,0}, - {4148,4147,4146 ,3540,3540,3539 ,0,0,0}, {4150,4149,4151 ,3542,3541,3541 ,0,0,0}, - {4148,4151,4149 ,3540,3541,3541 ,0,0,0}, {4150,4151,4152 ,3542,3541,3542 ,0,0,0}, - {4153,4154,4155 ,3543,3543,3544 ,0,0,0}, {4156,4157,4155 ,3545,3546,3544 ,0,0,0}, - {4153,4155,4157 ,3543,3544,3546 ,0,0,0}, {4156,4158,4159 ,3545,3547,3548 ,0,0,0}, - {4159,4157,4156 ,3548,3546,3545 ,0,0,0}, {4160,4158,4161 ,3549,3547,3550 ,0,0,0}, - {4158,4160,4159 ,3547,3549,3548 ,0,0,0}, {4162,4163,4161 ,3551,3552,3550 ,0,0,0}, - {4160,4161,4163 ,3549,3550,3552 ,0,0,0}, {4162,4164,4165 ,3551,3553,3554 ,0,0,0}, - {4165,4163,4162 ,3554,3552,3551 ,0,0,0}, {4166,4164,4167 ,3555,3553,3556 ,0,0,0}, - {4164,4166,4165 ,3553,3555,3554 ,0,0,0}, {4168,4169,4167 ,3557,3558,3556 ,0,0,0}, - {4166,4167,4169 ,3555,3556,3558 ,0,0,0}, {4168,4170,4171 ,3557,3559,3560 ,0,0,0}, - {4171,4169,4168 ,3560,3558,3557 ,0,0,0}, {4172,4170,4173 ,3561,3559,3562 ,0,0,0}, - {4170,4172,4171 ,3559,3561,3560 ,0,0,0}, {4174,4175,4173 ,3563,3564,3562 ,0,0,0}, - {4172,4173,4175 ,3561,3562,3564 ,0,0,0}, {4174,4176,4177 ,3563,3565,3566 ,0,0,0}, - {4177,4175,4174 ,3566,3564,3563 ,0,0,0}, {4178,4176,4179 ,3567,3565,3568 ,0,0,0}, - {4176,4178,4177 ,3565,3567,3566 ,0,0,0}, {4180,4181,4179 ,3569,3570,3568 ,0,0,0}, - {4178,4179,4181 ,3567,3568,3570 ,0,0,0}, {4180,4182,4183 ,3569,3571,3572 ,0,0,0}, - {4183,4181,4180 ,3572,3570,3569 ,0,0,0}, {4184,4182,4185 ,3573,3571,3574 ,0,0,0}, - {4182,4184,4183 ,3571,3573,3572 ,0,0,0}, {4150,4186,4185 ,3542,3575,3574 ,0,0,0}, - {4184,4185,4186 ,3573,3574,3575 ,0,0,0}, {4152,4186,4150 ,3542,3575,3542 ,0,0,0}, - {4187,4154,4153 ,3576,3543,3543 ,0,0,0}, {4188,4187,4189 ,3577,3576,3578 ,0,0,0}, - {4187,4188,4154 ,3576,3577,3543 ,0,0,0}, {4190,4191,4189 ,3579,3580,3578 ,0,0,0}, - {4188,4189,4191 ,3577,3578,3580 ,0,0,0}, {4190,4192,4193 ,3579,3581,3582 ,0,0,0}, - {4193,4191,4190 ,3582,3580,3579 ,0,0,0}, {4194,4192,4195 ,3583,3581,3584 ,0,0,0}, - {4192,4194,4193 ,3581,3583,3582 ,0,0,0}, {4196,4197,4195 ,3585,3586,3584 ,0,0,0}, - {4194,4195,4197 ,3583,3584,3586 ,0,0,0}, {4196,4198,4199 ,3585,3587,3588 ,0,0,0}, - {4199,4197,4196 ,3588,3586,3585 ,0,0,0}, {4200,4198,4201 ,3589,3587,3590 ,0,0,0}, - {4198,4200,4199 ,3587,3589,3588 ,0,0,0}, {4202,4203,4201 ,3591,3592,3590 ,0,0,0}, - {4200,4201,4203 ,3589,3590,3592 ,0,0,0}, {4202,4204,4205 ,3591,3593,3594 ,0,0,0}, - {4205,4203,4202 ,3594,3592,3591 ,0,0,0}, {4206,4204,4207 ,3595,3593,3596 ,0,0,0}, - {4204,4206,4205 ,3593,3595,3594 ,0,0,0}, {4208,4209,4207 ,3597,3598,3596 ,0,0,0}, - {4206,4207,4209 ,3595,3596,3598 ,0,0,0}, {4208,4210,4211 ,3597,3599,3600 ,0,0,0}, - {4211,4209,4208 ,3600,3598,3597 ,0,0,0}, {4212,4210,4213 ,3601,3599,3602 ,0,0,0}, - {4210,4212,4211 ,3599,3601,3600 ,0,0,0}, {4214,4215,4213 ,3603,3604,3602 ,0,0,0}, - {4212,4213,4215 ,3601,3602,3604 ,0,0,0}, {4214,4216,4217 ,3603,3605,3606 ,0,0,0}, - {4217,4215,4214 ,3606,3604,3603 ,0,0,0}, {4218,4216,4219 ,3607,3605,3608 ,0,0,0}, - {4216,4218,4217 ,3605,3607,3606 ,0,0,0}, {4218,4219,4220 ,3607,3608,3608 ,0,0,0}, - {4221,4219,4222 ,1398,3609,1398 ,0,0,0}, {4219,4221,4220 ,3609,1398,3609 ,0,0,0}, - {4223,4224,4225 ,3610,3611,3612 ,0,0,0}, {4226,4227,4228 ,3613,3614,3615 ,0,0,0}, - {4229,4223,4225 ,3616,3610,3612 ,0,0,0}, {4227,4225,4224 ,3614,3612,3611 ,0,0,0}, - {4230,4223,4229 ,3617,3610,3616 ,0,0,0}, {4231,4232,4233 ,3618,3619,3620 ,0,0,0}, - {4230,4229,4231 ,3617,3616,3618 ,0,0,0}, {4234,4232,4235 ,3621,3619,3622 ,0,0,0}, - {4231,4233,4230 ,3618,3620,3617 ,0,0,0}, {4232,4234,4233 ,3619,3621,3620 ,0,0,0}, - {4235,4236,4237 ,3622,3623,3624 ,0,0,0}, {4224,4228,4227 ,3611,3615,3614 ,0,0,0}, - {4238,4239,4240 ,3625,3626,3627 ,0,0,0}, {4241,4237,4236 ,3628,3624,3623 ,0,0,0}, - {4241,4242,4243 ,3628,3629,3630 ,0,0,0}, {4238,4240,4243 ,3625,3627,3630 ,0,0,0}, - {4238,4243,4242 ,3625,3630,3629 ,0,0,0}, {4240,4239,4244 ,3627,3626,3631 ,0,0,0}, - {4245,4246,4247 ,3632,3633,3634 ,0,0,0}, {4244,4245,4247 ,3631,3632,3634 ,0,0,0}, - {4245,4244,4239 ,3632,3631,3626 ,0,0,0}, {4246,4248,4247 ,3633,3635,3634 ,0,0,0}, - {4242,4241,4236 ,3629,3628,3623 ,0,0,0}, {4248,4249,4250 ,3635,3636,3637 ,0,0,0}, - {4248,4246,4249 ,3635,3633,3636 ,0,0,0}, {4251,4252,4253 ,3638,3639,3640 ,0,0,0}, - {4254,4253,4252 ,3641,3640,3639 ,0,0,0}, {4254,4255,4253 ,3641,3642,3640 ,0,0,0}, - {4255,4250,4249 ,3642,3637,3636 ,0,0,0}, {4255,4254,4250 ,3642,3641,3637 ,0,0,0}, - {4237,4234,4235 ,3624,3621,3622 ,0,0,0}, {4256,4257,4251 ,3643,3644,3638 ,0,0,0}, - {4258,4259,4256 ,3645,3646,3643 ,0,0,0}, {4222,4259,4258 ,1435,3646,3645 ,0,0,0}, - {4252,4251,4257 ,3639,3638,3644 ,0,0,0}, {4259,4257,4256 ,3646,3644,3643 ,0,0,0}, - {4221,4222,4258 ,1435,1435,3645 ,0,0,0}, {4260,4261,4226 ,3647,3648,3613 ,0,0,0}, - {4226,4228,4260 ,3613,3615,3647 ,0,0,0}, {4261,4262,4263 ,3648,3649,3650 ,0,0,0}, - {4262,4261,4260 ,3649,3648,3647 ,0,0,0}, {4264,4263,4265 ,3651,3650,3652 ,0,0,0}, - {4262,4265,4263 ,3649,3652,3650 ,0,0,0}, {4266,4267,4264 ,3653,3654,3651 ,0,0,0}, - {4264,4265,4266 ,3651,3652,3653 ,0,0,0}, {4267,4268,4269 ,3654,3655,3656 ,0,0,0}, - {4268,4267,4266 ,3655,3654,3653 ,0,0,0}, {4270,4269,4271 ,3657,3656,3658 ,0,0,0}, - {4268,4271,4269 ,3655,3658,3656 ,0,0,0}, {4272,4273,4270 ,3659,3660,3657 ,0,0,0}, - {4270,4271,4272 ,3657,3658,3659 ,0,0,0}, {4273,4274,4275 ,3660,3661,3662 ,0,0,0}, - {4274,4273,4272 ,3661,3660,3659 ,0,0,0}, {4276,4275,4277 ,3663,3662,3664 ,0,0,0}, - {4274,4277,4275 ,3661,3664,3662 ,0,0,0}, {4278,4279,4276 ,3665,3666,3663 ,0,0,0}, - {4276,4277,4278 ,3663,3664,3665 ,0,0,0}, {4279,4280,4281 ,3666,3667,3668 ,0,0,0}, - {4280,4279,4278 ,3667,3666,3665 ,0,0,0}, {4282,4281,4283 ,3669,3668,3670 ,0,0,0}, - {4280,4283,4281 ,3667,3670,3668 ,0,0,0}, {4284,4285,4282 ,3671,3672,3669 ,0,0,0}, - {4282,4283,4284 ,3669,3670,3671 ,0,0,0}, {4285,4286,4287 ,3672,3673,3674 ,0,0,0}, - {4286,4285,4284 ,3673,3672,3671 ,0,0,0}, {4288,4287,4289 ,3675,3674,3676 ,0,0,0}, - {4286,4289,4287 ,3673,3676,3674 ,0,0,0}, {4290,4291,4288 ,3677,3678,3675 ,0,0,0}, - {4288,4289,4290 ,3675,3676,3677 ,0,0,0}, {4291,4292,4293 ,3678,3679,3680 ,0,0,0}, - {4292,4291,4290 ,3679,3678,3677 ,0,0,0}, {4294,4293,4295 ,1790,3680,3681 ,0,0,0}, - {4292,4295,4293 ,3679,3681,3680 ,0,0,0}, {4294,4295,4296 ,1790,3681,1790 ,0,0,0}, - {4297,4298,4299 ,2162,2162,2162 ,0,0,0}, {4298,4297,4300 ,2162,2162,2162 ,0,0,0}, - {4301,4302,4303 ,3682,3683,3684 ,0,0,0}, {4304,4305,4306 ,3685,3686,3687 ,0,0,0}, - {4302,4307,4303 ,3683,3688,3684 ,0,0,0}, {4301,4303,4308 ,3682,3684,3689 ,0,0,0}, - {4304,4301,4308 ,3685,3682,3689 ,0,0,0}, {4309,4310,4307 ,3690,3691,3688 ,0,0,0}, - {4309,4307,4302 ,3690,3688,3683 ,0,0,0}, {4311,4312,4313 ,3692,3693,3694 ,0,0,0}, - {4310,4309,4311 ,3691,3690,3692 ,0,0,0}, {4311,4313,4310 ,3692,3694,3691 ,0,0,0}, - {4312,4314,4313 ,3693,3695,3694 ,0,0,0}, {4305,4304,4308 ,3686,3685,3689 ,0,0,0}, - {4312,4315,4314 ,3693,3696,3695 ,0,0,0}, {4316,4317,4318 ,3697,3698,3699 ,0,0,0}, - {4316,4318,4315 ,3697,3699,3696 ,0,0,0}, {4317,4316,4319 ,3698,3697,3700 ,0,0,0}, - {4320,4321,4319 ,3701,3702,3700 ,0,0,0}, {4321,4317,4319 ,3702,3698,3700 ,0,0,0}, - {4322,4323,4324 ,3703,3704,3705 ,0,0,0}, {4321,4320,4325 ,3702,3701,3706 ,0,0,0}, - {4326,4327,4325 ,3707,3708,3706 ,0,0,0}, {4323,4322,4327 ,3704,3703,3708 ,0,0,0}, - {4323,4327,4326 ,3704,3708,3707 ,0,0,0}, {4322,4324,4328 ,3703,3705,3709 ,0,0,0}, - {4320,4326,4325 ,3701,3707,3706 ,0,0,0}, {4329,4328,4330 ,3710,3709,3711 ,0,0,0}, - {4329,4330,4331 ,3710,3711,3712 ,0,0,0}, {4330,4328,4324 ,3711,3709,3705 ,0,0,0}, - {4332,4333,4334 ,3713,3714,3715 ,0,0,0}, {4318,4314,4315 ,3699,3695,3696 ,0,0,0}, - {4332,4335,4331 ,3713,3716,3712 ,0,0,0}, {4335,4332,4334 ,3716,3713,3715 ,0,0,0}, - {4333,4336,4337 ,3714,3717,3718 ,0,0,0}, {4337,4334,4333 ,3718,3715,3714 ,0,0,0}, - {4338,4339,4336 ,3719,3720,3717 ,0,0,0}, {4337,4336,4339 ,3718,3717,3720 ,0,0,0}, - {4338,4300,4297 ,3719,3721,3721 ,0,0,0}, {4338,4297,4339 ,3719,3721,3720 ,0,0,0}, - {4331,4335,4329 ,3712,3716,3710 ,0,0,0}, {4340,4306,4341 ,3722,3687,3723 ,0,0,0}, - {4305,4341,4306 ,3686,3723,3687 ,0,0,0}, {4342,4343,4340 ,3724,3725,3722 ,0,0,0}, - {4340,4341,4342 ,3722,3723,3724 ,0,0,0}, {4343,4344,4345 ,3725,3726,3727 ,0,0,0}, - {4344,4343,4342 ,3726,3725,3724 ,0,0,0}, {4346,4345,4347 ,3728,3727,3729 ,0,0,0}, - {4344,4347,4345 ,3726,3729,3727 ,0,0,0}, {4348,4349,4346 ,3730,3731,3728 ,0,0,0}, - {4346,4347,4348 ,3728,3729,3730 ,0,0,0}, {4349,4350,4351 ,3731,3732,3733 ,0,0,0}, - {4350,4349,4348 ,3732,3731,3730 ,0,0,0}, {4352,4351,4353 ,3734,3733,3735 ,0,0,0}, - {4350,4353,4351 ,3732,3735,3733 ,0,0,0}, {4354,4355,4352 ,3736,3737,3734 ,0,0,0}, - {4352,4353,4354 ,3734,3735,3736 ,0,0,0}, {4355,4356,4357 ,3737,3738,3739 ,0,0,0}, - {4356,4355,4354 ,3738,3737,3736 ,0,0,0}, {4358,4357,4359 ,3740,3739,3741 ,0,0,0}, - {4356,4359,4357 ,3738,3741,3739 ,0,0,0}, {4360,4361,4358 ,3742,3743,3740 ,0,0,0}, - {4358,4359,4360 ,3740,3741,3742 ,0,0,0}, {4361,4362,4363 ,3743,3744,3745 ,0,0,0}, - {4362,4361,4360 ,3744,3743,3742 ,0,0,0}, {4364,4363,4365 ,3746,3745,3747 ,0,0,0}, - {4362,4365,4363 ,3744,3747,3745 ,0,0,0}, {4366,4367,4364 ,3748,3749,3746 ,0,0,0}, - {4364,4365,4366 ,3746,3747,3748 ,0,0,0}, {4367,4368,4369 ,3749,3750,3751 ,0,0,0}, - {4368,4367,4366 ,3750,3749,3748 ,0,0,0}, {4370,4369,4371 ,3752,3751,3753 ,0,0,0}, - {4368,4371,4369 ,3750,3753,3751 ,0,0,0}, {4372,4373,4370 ,3754,3755,3752 ,0,0,0}, - {4370,4371,4372 ,3752,3753,3754 ,0,0,0}, {4373,4374,4375 ,3755,3756,3757 ,0,0,0}, - {4374,4373,4372 ,3756,3755,3754 ,0,0,0}, {4376,4375,4377 ,3758,3757,3759 ,0,0,0}, - {4374,4377,4375 ,3756,3759,3757 ,0,0,0}, {4376,4377,4378 ,3758,3759,3760 ,0,0,0}, - {4379,4380,4381 ,3761,3762,3763 ,0,0,0}, {4382,4383,4381 ,3764,3765,3763 ,0,0,0}, - {4379,4381,4383 ,3761,3763,3765 ,0,0,0}, {4382,4384,4385 ,3764,3766,3767 ,0,0,0}, - {4385,4383,4382 ,3767,3765,3764 ,0,0,0}, {4386,4384,4387 ,3768,3766,3769 ,0,0,0}, - {4384,4386,4385 ,3766,3768,3767 ,0,0,0}, {4388,4389,4387 ,3770,3771,3769 ,0,0,0}, - {4386,4387,4389 ,3768,3769,3771 ,0,0,0}, {4388,4390,4391 ,3770,3772,3773 ,0,0,0}, - {4391,4389,4388 ,3773,3771,3770 ,0,0,0}, {4392,4390,4393 ,3774,3772,3775 ,0,0,0}, - {4390,4392,4391 ,3772,3774,3773 ,0,0,0}, {4394,4395,4393 ,3776,3777,3775 ,0,0,0}, - {4392,4393,4395 ,3774,3775,3777 ,0,0,0}, {4394,4396,4397 ,3776,3778,3779 ,0,0,0}, - {4397,4395,4394 ,3779,3777,3776 ,0,0,0}, {4398,4396,4399 ,3780,3778,3781 ,0,0,0}, - {4396,4398,4397 ,3778,3780,3779 ,0,0,0}, {4400,4401,4399 ,3782,3783,3781 ,0,0,0}, - {4398,4399,4401 ,3780,3781,3783 ,0,0,0}, {4400,4402,4403 ,3782,3784,3785 ,0,0,0}, - {4403,4401,4400 ,3785,3783,3782 ,0,0,0}, {4404,4402,4405 ,3786,3784,3787 ,0,0,0}, - {4402,4404,4403 ,3784,3786,3785 ,0,0,0}, {4406,4407,4405 ,3788,3789,3787 ,0,0,0}, - {4404,4405,4407 ,3786,3787,3789 ,0,0,0}, {4406,4408,4409 ,3788,3790,3791 ,0,0,0}, - {4409,4407,4406 ,3791,3789,3788 ,0,0,0}, {4410,4408,4411 ,3792,3790,3793 ,0,0,0}, - {4408,4410,4409 ,3790,3792,3791 ,0,0,0}, {4412,4413,4411 ,3794,3795,3793 ,0,0,0}, - {4410,4411,4413 ,3792,3793,3795 ,0,0,0}, {4412,4414,4415 ,3794,3796,3797 ,0,0,0}, - {4415,4413,4412 ,3797,3795,3794 ,0,0,0}, {4416,4414,4417 ,3798,3796,3799 ,0,0,0}, - {4414,4416,4415 ,3796,3798,3797 ,0,0,0}, {4418,4419,4417 ,3800,3801,3799 ,0,0,0}, - {4416,4417,4419 ,3798,3799,3801 ,0,0,0}, {4418,4420,4421 ,3800,3802,3803 ,0,0,0}, - {4421,4419,4418 ,3803,3801,3800 ,0,0,0}, {4422,4420,4423 ,3804,3802,3805 ,0,0,0}, - {4420,4422,4421 ,3802,3804,3803 ,0,0,0}, {4424,4425,4423 ,3806,3807,3805 ,0,0,0}, - {4422,4423,4425 ,3804,3805,3807 ,0,0,0}, {4424,4426,4427 ,3806,3808,3809 ,0,0,0}, - {4427,4425,4424 ,3809,3807,3806 ,0,0,0}, {4428,4426,4429 ,3810,3808,3811 ,0,0,0}, - {4426,4428,4427 ,3808,3810,3809 ,0,0,0}, {4430,4431,4429 ,3812,3813,3811 ,0,0,0}, - {4428,4429,4431 ,3810,3811,3813 ,0,0,0}, {4430,4432,4433 ,3812,3814,3815 ,0,0,0}, - {4433,4431,4430 ,3815,3813,3812 ,0,0,0}, {4434,4432,4435 ,3816,3814,3817 ,0,0,0}, - {4432,4434,4433 ,3814,3816,3815 ,0,0,0}, {4376,4436,4435 ,3818,3819,3817 ,0,0,0}, - {4434,4435,4436 ,3816,3817,3819 ,0,0,0}, {4378,4436,4376 ,3820,3819,3818 ,0,0,0}, - {4437,4380,4379 ,3821,3762,3761 ,0,0,0}, {4438,4437,4439 ,3822,3821,3823 ,0,0,0}, - {4437,4438,4380 ,3821,3822,3762 ,0,0,0}, {4440,4441,4439 ,3824,3825,3823 ,0,0,0}, - {4438,4439,4441 ,3822,3823,3825 ,0,0,0}, {4440,4442,4443 ,3824,3826,3827 ,0,0,0}, - {4443,4441,4440 ,3827,3825,3824 ,0,0,0}, {4444,4442,4445 ,3828,3826,3829 ,0,0,0}, - {4442,4444,4443 ,3826,3828,3827 ,0,0,0}, {4446,4447,4445 ,3830,3831,3829 ,0,0,0}, - {4444,4445,4447 ,3828,3829,3831 ,0,0,0}, {4446,4448,4449 ,3830,3832,3833 ,0,0,0}, - {4449,4447,4446 ,3833,3831,3830 ,0,0,0}, {4450,4448,4451 ,3834,3832,3835 ,0,0,0}, - {4448,4450,4449 ,3832,3834,3833 ,0,0,0}, {4452,4453,4451 ,3836,3837,3835 ,0,0,0}, - {4450,4451,4453 ,3834,3835,3837 ,0,0,0}, {4452,4454,4455 ,3836,3838,3839 ,0,0,0}, - {4455,4453,4452 ,3839,3837,3836 ,0,0,0}, {4456,4454,4457 ,3840,3838,3841 ,0,0,0}, - {4454,4456,4455 ,3838,3840,3839 ,0,0,0}, {4458,4459,4457 ,3842,3843,3841 ,0,0,0}, - {4456,4457,4459 ,3840,3841,3843 ,0,0,0}, {4458,4460,4461 ,3842,3844,3845 ,0,0,0}, - {4461,4459,4458 ,3845,3843,3842 ,0,0,0}, {4462,4460,4463 ,3846,3844,3847 ,0,0,0}, - {4460,4462,4461 ,3844,3846,3845 ,0,0,0}, {4464,4465,4463 ,3848,3849,3847 ,0,0,0}, - {4462,4463,4465 ,3846,3847,3849 ,0,0,0}, {4464,4466,4467 ,3848,3850,3851 ,0,0,0}, - {4467,4465,4464 ,3851,3849,3848 ,0,0,0}, {4468,4466,4469 ,3852,3850,3853 ,0,0,0}, - {4466,4468,4467 ,3850,3852,3851 ,0,0,0}, {4470,4471,4469 ,3854,3855,3853 ,0,0,0}, - {4468,4469,4471 ,3852,3853,3855 ,0,0,0}, {4470,4472,4473 ,3854,3856,3857 ,0,0,0}, - {4473,4471,4470 ,3857,3855,3854 ,0,0,0}, {4474,4472,4475 ,3858,3856,3859 ,0,0,0}, - {4472,4474,4473 ,3856,3858,3857 ,0,0,0}, {4476,4477,4475 ,3860,3861,3859 ,0,0,0}, - {4474,4475,4477 ,3858,3859,3861 ,0,0,0}, {4476,4478,4479 ,3860,3862,3863 ,0,0,0}, - {4479,4477,4476 ,3863,3861,3860 ,0,0,0}, {4480,4478,4481 ,3864,3862,3865 ,0,0,0}, - {4478,4480,4479 ,3862,3864,3863 ,0,0,0}, {4482,4483,4481 ,3866,3867,3865 ,0,0,0}, - {4480,4481,4483 ,3864,3865,3867 ,0,0,0}, {4482,4484,4485 ,3866,3868,3869 ,0,0,0}, - {4485,4483,4482 ,3869,3867,3866 ,0,0,0}, {4486,4484,4487 ,3870,3868,3871 ,0,0,0}, - {4484,4486,4485 ,3868,3870,3869 ,0,0,0}, {4488,4489,4487 ,3872,3873,3871 ,0,0,0}, - {4486,4487,4489 ,3870,3871,3873 ,0,0,0}, {4488,4490,4491 ,3872,3874,3875 ,0,0,0}, - {4491,4489,4488 ,3875,3873,3872 ,0,0,0}, {4492,4490,4493 ,3876,3874,82 ,0,0,0}, - {4490,4492,4491 ,3874,3876,3875 ,0,0,0}, {4492,4493,4494 ,3876,82,3877 ,0,0,0}, - {4495,4496,4497 ,3878,3879,3880 ,0,0,0}, {4498,4499,4500 ,3881,3882,3883 ,0,0,0}, - {4496,4501,4497 ,3879,3884,3880 ,0,0,0}, {4495,4497,4502 ,3878,3880,3885 ,0,0,0}, - {4498,4495,4502 ,3881,3878,3885 ,0,0,0}, {4503,4504,4501 ,3886,3887,3884 ,0,0,0}, - {4503,4501,4496 ,3886,3884,3879 ,0,0,0}, {4505,4506,4507 ,3888,3889,3890 ,0,0,0}, - {4504,4503,4505 ,3887,3886,3888 ,0,0,0}, {4505,4507,4504 ,3888,3890,3887 ,0,0,0}, - {4506,4508,4507 ,3889,3891,3890 ,0,0,0}, {4499,4498,4502 ,3882,3881,3885 ,0,0,0}, - {4506,4509,4508 ,3889,3892,3891 ,0,0,0}, {4510,4511,4512 ,3893,3894,3895 ,0,0,0}, - {4510,4512,4509 ,3893,3895,3892 ,0,0,0}, {4511,4510,4513 ,3894,3893,3896 ,0,0,0}, - {4514,4515,4513 ,3897,3898,3896 ,0,0,0}, {4515,4511,4513 ,3898,3894,3896 ,0,0,0}, - {4516,4517,4518 ,3899,3900,3901 ,0,0,0}, {4515,4514,4519 ,3898,3897,3902 ,0,0,0}, - {4520,4521,4519 ,3903,3904,3902 ,0,0,0}, {4517,4516,4521 ,3900,3899,3904 ,0,0,0}, - {4517,4521,4520 ,3900,3904,3903 ,0,0,0}, {4516,4518,4522 ,3899,3901,3905 ,0,0,0}, - {4514,4520,4519 ,3897,3903,3902 ,0,0,0}, {4523,4522,4524 ,3906,3905,3907 ,0,0,0}, - {4523,4524,4525 ,3906,3907,3908 ,0,0,0}, {4524,4522,4518 ,3907,3905,3901 ,0,0,0}, - {4526,4527,4528 ,3909,3910,3911 ,0,0,0}, {4512,4508,4509 ,3895,3891,3892 ,0,0,0}, - {4526,4529,4525 ,3909,3912,3908 ,0,0,0}, {4529,4526,4528 ,3912,3909,3911 ,0,0,0}, - {4527,4530,4531 ,3910,3913,3914 ,0,0,0}, {4531,4528,4527 ,3914,3911,3910 ,0,0,0}, - {4532,4533,4530 ,3915,3916,3913 ,0,0,0}, {4531,4530,4533 ,3914,3913,3916 ,0,0,0}, - {4532,4494,4493 ,3915,3917,3918 ,0,0,0}, {4532,4493,4533 ,3915,3918,3916 ,0,0,0}, - {4525,4529,4523 ,3908,3912,3906 ,0,0,0}, {4534,4500,4535 ,3919,3883,3920 ,0,0,0}, - {4499,4535,4500 ,3882,3920,3883 ,0,0,0}, {4536,4537,4534 ,3921,3922,3919 ,0,0,0}, - {4534,4535,4536 ,3919,3920,3921 ,0,0,0}, {4537,4538,4539 ,3922,3923,3924 ,0,0,0}, - {4538,4537,4536 ,3923,3922,3921 ,0,0,0}, {4540,4539,4541 ,3925,3924,3926 ,0,0,0}, - {4538,4541,4539 ,3923,3926,3924 ,0,0,0}, {4542,4543,4540 ,3927,3928,3925 ,0,0,0}, - {4540,4541,4542 ,3925,3926,3927 ,0,0,0}, {4543,4544,4545 ,3928,3929,3930 ,0,0,0}, - {4544,4543,4542 ,3929,3928,3927 ,0,0,0}, {4546,4545,4547 ,3931,3930,3932 ,0,0,0}, - {4544,4547,4545 ,3929,3932,3930 ,0,0,0}, {4548,4549,4546 ,3933,3934,3931 ,0,0,0}, - {4546,4547,4548 ,3931,3932,3933 ,0,0,0}, {4549,4550,4551 ,3934,3935,3936 ,0,0,0}, - {4550,4549,4548 ,3935,3934,3933 ,0,0,0}, {4552,4551,4553 ,3937,3936,3938 ,0,0,0}, - {4550,4553,4551 ,3935,3938,3936 ,0,0,0}, {4554,4555,4552 ,3939,3940,3937 ,0,0,0}, - {4552,4553,4554 ,3937,3938,3939 ,0,0,0}, {4555,4556,4557 ,3940,3941,3942 ,0,0,0}, - {4556,4555,4554 ,3941,3940,3939 ,0,0,0}, {4558,4557,4559 ,3943,3942,3944 ,0,0,0}, - {4556,4559,4557 ,3941,3944,3942 ,0,0,0}, {4560,4561,4558 ,3945,3946,3943 ,0,0,0}, - {4558,4559,4560 ,3943,3944,3945 ,0,0,0}, {4561,4562,4563 ,3946,3947,3948 ,0,0,0}, - {4562,4561,4560 ,3947,3946,3945 ,0,0,0}, {4564,4563,4565 ,3949,3948,3950 ,0,0,0}, - {4562,4565,4563 ,3947,3950,3948 ,0,0,0}, {4566,4567,4564 ,3951,3952,3949 ,0,0,0}, - {4564,4565,4566 ,3949,3950,3951 ,0,0,0}, {4567,4568,4569 ,3952,3953,3954 ,0,0,0}, - {4568,4567,4566 ,3953,3952,3951 ,0,0,0}, {4570,4569,4571 ,3955,3954,3956 ,0,0,0}, - {4568,4571,4569 ,3953,3956,3954 ,0,0,0}, {4570,4571,4572 ,3955,3956,3955 ,0,0,0}, - {4573,4570,4572 ,1433,1433,1433 ,0,0,0}, {4570,4573,4574 ,1433,1433,1433 ,0,0,0}, - {4575,4576,4577 ,3957,3958,3959 ,0,0,0}, {4578,4579,4575 ,3960,3961,3957 ,0,0,0}, - {4575,4577,4578 ,3957,3959,3960 ,0,0,0}, {4579,4580,4581 ,3961,3962,3963 ,0,0,0}, - {4580,4579,4578 ,3962,3961,3960 ,0,0,0}, {4582,4581,4583 ,3964,3963,3965 ,0,0,0}, - {4580,4583,4581 ,3962,3965,3963 ,0,0,0}, {4584,4585,4582 ,3966,3967,3964 ,0,0,0}, - {4582,4583,4584 ,3964,3965,3966 ,0,0,0}, {4585,4586,4587 ,3967,3968,3969 ,0,0,0}, - {4586,4585,4584 ,3968,3967,3966 ,0,0,0}, {4588,4587,4589 ,3970,3969,3971 ,0,0,0}, - {4586,4589,4587 ,3968,3971,3969 ,0,0,0}, {4590,4591,4588 ,3972,3973,3970 ,0,0,0}, - {4588,4589,4590 ,3970,3971,3972 ,0,0,0}, {4591,4592,4593 ,3973,3974,3975 ,0,0,0}, - {4592,4591,4590 ,3974,3973,3972 ,0,0,0}, {4594,4593,4595 ,3976,3975,3977 ,0,0,0}, - {4592,4595,4593 ,3974,3977,3975 ,0,0,0}, {4596,4597,4594 ,3978,3979,3976 ,0,0,0}, - {4594,4595,4596 ,3976,3977,3978 ,0,0,0}, {4597,4598,4599 ,3979,3980,3981 ,0,0,0}, - {4598,4597,4596 ,3980,3979,3978 ,0,0,0}, {4600,4599,4601 ,3982,3981,3983 ,0,0,0}, - {4598,4601,4599 ,3980,3983,3981 ,0,0,0}, {4602,4603,4600 ,3984,3985,3982 ,0,0,0}, - {4600,4601,4602 ,3982,3983,3984 ,0,0,0}, {4603,4604,4605 ,3985,3986,3987 ,0,0,0}, - {4604,4603,4602 ,3986,3985,3984 ,0,0,0}, {4606,4605,4607 ,3988,3987,3989 ,0,0,0}, - {4604,4607,4605 ,3986,3989,3987 ,0,0,0}, {4608,4609,4606 ,3990,3991,3988 ,0,0,0}, - {4606,4607,4608 ,3988,3989,3990 ,0,0,0}, {4609,4610,4611 ,3991,3992,3993 ,0,0,0}, - {4610,4609,4608 ,3992,3991,3990 ,0,0,0}, {4612,4611,4613 ,3994,3993,3995 ,0,0,0}, - {4610,4613,4611 ,3992,3995,3993 ,0,0,0}, {4574,4573,4612 ,3996,3996,3994 ,0,0,0}, - {4612,4613,4574 ,3994,3995,3996 ,0,0,0}, {4577,4576,4614 ,3959,3958,3997 ,0,0,0}, - {4615,4614,4616 ,3998,3997,3999 ,0,0,0}, {4576,4616,4614 ,3958,3999,3997 ,0,0,0}, - {4617,4618,4615 ,4000,4001,3998 ,0,0,0}, {4615,4616,4617 ,3998,3999,4000 ,0,0,0}, - {4618,4619,4620 ,4001,4002,4003 ,0,0,0}, {4619,4618,4617 ,4002,4001,4000 ,0,0,0}, - {4621,4620,4622 ,4004,4003,4005 ,0,0,0}, {4619,4622,4620 ,4002,4005,4003 ,0,0,0}, - {4623,4624,4621 ,4006,4007,4004 ,0,0,0}, {4621,4622,4623 ,4004,4005,4006 ,0,0,0}, - {4624,4625,4626 ,4007,4008,4009 ,0,0,0}, {4625,4624,4623 ,4008,4007,4006 ,0,0,0}, - {4627,4626,4628 ,4010,4009,4011 ,0,0,0}, {4625,4628,4626 ,4008,4011,4009 ,0,0,0}, - {4629,4630,4627 ,4012,4013,4010 ,0,0,0}, {4627,4628,4629 ,4010,4011,4012 ,0,0,0}, - {4630,4631,4632 ,4013,4014,4015 ,0,0,0}, {4631,4630,4629 ,4014,4013,4012 ,0,0,0}, - {4633,4632,4634 ,4016,4015,4017 ,0,0,0}, {4631,4634,4632 ,4014,4017,4015 ,0,0,0}, - {4635,4636,4633 ,4018,4019,4016 ,0,0,0}, {4633,4634,4635 ,4016,4017,4018 ,0,0,0}, - {4636,4637,4638 ,4019,4020,4021 ,0,0,0}, {4637,4636,4635 ,4020,4019,4018 ,0,0,0}, - {4639,4638,4640 ,4022,4021,4023 ,0,0,0}, {4637,4640,4638 ,4020,4023,4021 ,0,0,0}, - {4641,4642,4639 ,4024,4025,4022 ,0,0,0}, {4639,4640,4641 ,4022,4023,4024 ,0,0,0}, - {4642,4643,4644 ,4025,4026,4027 ,0,0,0}, {4643,4642,4641 ,4026,4025,4024 ,0,0,0}, - {4645,4644,4646 ,4028,4027,4029 ,0,0,0}, {4643,4646,4644 ,4026,4029,4027 ,0,0,0}, - {4647,4648,4645 ,4030,4031,4028 ,0,0,0}, {4645,4646,4647 ,4028,4029,4030 ,0,0,0}, - {4648,4649,4650 ,4031,4032,4033 ,0,0,0}, {4649,4648,4647 ,4032,4031,4030 ,0,0,0}, - {4649,4299,4650 ,4032,4034,4033 ,0,0,0}, {4650,4299,4298 ,4033,4034,4034 ,0,0,0}, - {4000,4296,4001 ,2197,4035,2197 ,0,0,0}, {4296,4000,4294 ,4035,2197,4035 ,0,0,0}, - {4521,4023,4022 ,3295,3295,3295 ,0,0,0}, {4299,4649,4222 ,3295,726,726 ,0,0,0}, - {4643,4252,4646 ,726,726,726 ,0,0,0}, {4339,4297,4219 ,726,726,726 ,0,0,0}, - {4240,4244,4634 ,726,726,726 ,0,0,0}, {4248,4640,4637 ,726,726,726 ,0,0,0}, - {4619,4230,4622 ,726,726,726 ,0,0,0}, {4628,4625,4237 ,726,726,726 ,0,0,0}, - {4616,4224,4223 ,726,726,726 ,0,0,0}, {4617,4616,4223 ,726,726,726 ,0,0,0}, - {4016,4013,4512 ,3295,726,3295 ,0,0,0}, {4529,4528,4031 ,3295,726,3295 ,0,0,0}, - {4497,4501,4005 ,3295,3295,726 ,0,0,0}, {4007,4501,4504 ,726,3295,726 ,0,0,0}, - {4535,3961,3965 ,726,726,726 ,0,0,0}, {3961,4499,3962 ,726,3295,3295 ,0,0,0}, - {4538,3968,4541 ,3295,726,726 ,0,0,0}, {3967,4538,4536 ,3295,3295,3295 ,0,0,0}, - {3977,4548,4547 ,3294,3295,3295 ,0,0,0}, {3973,4544,4542 ,726,3295,3295 ,0,0,0}, - {4550,4548,3979 ,3295,3295,3295 ,0,0,0}, {3977,3979,4548 ,3294,3295,3295 ,0,0,0}, - {4554,4553,3983 ,3295,3294,726 ,0,0,0}, {4550,3979,3980 ,3295,3295,3295 ,0,0,0}, - {4556,4554,3985 ,3295,3295,3295 ,0,0,0}, {3983,4553,3980 ,726,3294,3295 ,0,0,0}, - {3986,4559,4556 ,3295,726,3295 ,0,0,0}, {4556,3985,3986 ,3295,3295,3295 ,0,0,0}, - {4559,3989,4560 ,726,726,726 ,0,0,0}, {3989,4559,3986 ,726,726,3295 ,0,0,0}, - {4562,4560,3991 ,726,726,726 ,0,0,0}, {3992,4562,3991 ,726,726,726 ,0,0,0}, - {3997,4566,3995 ,726,3295,3295 ,0,0,0}, {4565,4562,3992 ,726,726,726 ,0,0,0}, - {3998,4001,4568 ,726,726,726 ,0,0,0}, {3995,4566,4565 ,3295,3295,726 ,0,0,0}, - {4001,4571,4568 ,726,3295,726 ,0,0,0}, {4566,3998,4568 ,3295,726,726 ,0,0,0}, - {4591,4272,4588 ,726,726,726 ,0,0,0}, {4001,4572,4571 ,726,726,3295 ,0,0,0}, - {4522,4025,4516 ,3295,726,726 ,0,0,0}, {4536,3965,3967 ,3295,726,3295 ,0,0,0}, - {4544,3973,3974 ,3295,726,3295 ,0,0,0}, {4547,3974,3977 ,3295,3295,3294 ,0,0,0}, - {3971,3973,4542 ,3295,726,3295 ,0,0,0}, {4541,3968,3971 ,726,726,3295 ,0,0,0}, - {4499,3961,4535 ,3295,726,726 ,0,0,0}, {4535,3965,4536 ,726,726,3295 ,0,0,0}, - {4497,4004,4502 ,3295,3295,3295 ,0,0,0}, {4502,3962,4499 ,3295,3295,3295 ,0,0,0}, - {4165,4344,4163 ,726,726,3295 ,0,0,0}, {4004,3962,4502 ,3295,3295,3295 ,0,0,0}, - {4507,4011,4010 ,3295,3295,726 ,0,0,0}, {4504,4010,4007 ,726,726,726 ,0,0,0}, - {4508,4013,4011 ,726,726,3295 ,0,0,0}, {4507,4010,4504 ,3295,726,726 ,0,0,0}, - {4515,4019,4017 ,3295,3295,3295 ,0,0,0}, {4016,4512,4511 ,3295,3295,726 ,0,0,0}, - {4516,4023,4521 ,726,3295,3295 ,0,0,0}, {4019,4519,4022 ,3295,3295,3295 ,0,0,0}, - {4029,4028,4523 ,726,726,726 ,0,0,0}, {4025,4023,4516 ,726,3295,726 ,0,0,0}, - {4523,4028,4522 ,726,726,3295 ,0,0,0}, {4371,4368,4151 ,3295,726,726 ,0,0,0}, - {4531,4035,4034 ,3294,726,726 ,0,0,0}, {3948,3930,3950 ,3295,3294,726 ,0,0,0}, - {4037,4533,4039 ,3295,726,3295 ,0,0,0}, {3955,3957,3922 ,726,3295,726 ,0,0,0}, - {3919,3957,3958 ,726,3295,3295 ,0,0,0}, {4118,4115,3911 ,726,726,726 ,0,0,0}, - {4118,3902,3904 ,726,726,3295 ,0,0,0}, {4421,4093,4419 ,726,3295,3295 ,0,0,0}, - {4112,4107,4374 ,3295,726,726 ,0,0,0}, {4481,4478,4651 ,726,726,726 ,0,0,0}, - {4392,4076,4391 ,726,3295,3295 ,0,0,0}, {4652,4653,4442 ,3295,3295,726 ,0,0,0}, - {3897,4654,4655 ,3295,726,726 ,0,0,0}, {4448,4446,4656 ,726,3295,726 ,0,0,0}, - {4656,4446,4653 ,726,3295,3295 ,0,0,0}, {3870,3867,3939 ,726,726,3295 ,0,0,0}, - {4656,3939,4451 ,726,3295,3295 ,0,0,0}, {3937,3935,3868 ,3295,3295,3295 ,0,0,0}, - {3868,3935,3877 ,3295,3295,3295 ,0,0,0}, {4458,4457,3866 ,3295,726,726 ,0,0,0}, - {4445,4442,4653 ,3295,726,3295 ,0,0,0}, {4083,4652,4440 ,726,3295,726 ,0,0,0}, - {4058,4657,4054 ,726,3295,3295 ,0,0,0}, {4658,4659,4654 ,3295,3295,726 ,0,0,0}, - {4049,4660,4661 ,726,3295,3295 ,0,0,0}, {4437,4082,4083 ,3295,726,726 ,0,0,0}, - {4083,4440,4439 ,726,726,3295 ,0,0,0}, {4379,4082,4437 ,3295,726,3295 ,0,0,0}, - {4476,4475,4662 ,726,3295,3295 ,0,0,0}, {4081,4082,4383 ,3295,726,726 ,0,0,0}, - {4383,4385,4081 ,726,726,3295 ,0,0,0}, {4482,4481,4663 ,3295,726,3295 ,0,0,0}, - {4078,4081,4386 ,726,3295,726 ,0,0,0}, {4484,4664,4487 ,726,3295,3295 ,0,0,0}, - {4389,4078,4386 ,3295,726,726 ,0,0,0}, {4041,4488,4044 ,3295,726,3295 ,0,0,0}, - {4078,4391,4076 ,726,3295,3295 ,0,0,0}, {4401,4072,4071 ,3295,726,726 ,0,0,0}, - {4397,4071,4074 ,3295,726,3295 ,0,0,0}, {4088,4087,4409 ,3294,726,3295 ,0,0,0}, - {4072,4401,4403 ,726,3295,3295 ,0,0,0}, {4416,4090,4415 ,3295,3295,3295 ,0,0,0}, - {4090,4088,4413 ,3295,3294,3295 ,0,0,0}, {4099,4096,4427 ,3295,726,726 ,0,0,0}, - {4059,4665,4063 ,3295,726,3295 ,0,0,0}, {4666,4667,4668 ,3295,3295,3295 ,0,0,0}, - {4100,4431,4433 ,726,726,726 ,0,0,0}, {4102,4106,4378 ,3295,3295,3295 ,0,0,0}, - {4669,4120,4670 ,726,726,726 ,0,0,0}, {4671,4130,4120 ,3295,3295,726 ,0,0,0}, - {4123,4119,4672 ,726,726,726 ,0,0,0}, {4122,4673,4670 ,726,3295,726 ,0,0,0}, - {3960,3901,3900 ,726,726,3295 ,0,0,0}, {3944,3943,3924 ,3295,726,726 ,0,0,0}, - {4673,4122,4123 ,3295,726,726 ,0,0,0}, {4490,4041,4493 ,3295,3295,3295 ,0,0,0}, - {3947,3925,3928 ,726,3295,726 ,0,0,0}, {4148,4146,4371 ,3295,3295,3295 ,0,0,0}, - {4533,4493,4039 ,726,3295,3295 ,0,0,0}, {4186,4152,4368 ,3294,726,726 ,0,0,0}, - {4037,4035,4533 ,3295,726,726 ,0,0,0}, {4623,4233,4234 ,726,726,726 ,0,0,0}, - {4579,4260,4575 ,726,726,726 ,0,0,0}, {4262,4579,4581 ,726,726,726 ,0,0,0}, - {4341,4160,4342 ,3295,726,726 ,0,0,0}, {4016,4511,4017 ,3295,726,3295 ,0,0,0}, - {4533,4035,4531 ,726,726,3294 ,0,0,0}, {4528,4531,4034 ,726,3294,726 ,0,0,0}, - {4029,4529,4031 ,726,3295,3295 ,0,0,0}, {4031,4528,4034 ,3295,726,726 ,0,0,0}, - {4019,4515,4519 ,3295,3295,3295 ,0,0,0}, {4025,4522,4028 ,726,3295,726 ,0,0,0}, - {4029,4523,4529 ,726,726,3295 ,0,0,0}, {4521,4022,4519 ,3295,3295,3295 ,0,0,0}, - {4511,4515,4017 ,726,3295,3295 ,0,0,0}, {4512,4013,4508 ,3295,726,726 ,0,0,0}, - {4344,4165,4347 ,726,726,726 ,0,0,0}, {4507,4508,4011 ,3295,726,3295 ,0,0,0}, - {4575,4260,4228 ,726,726,726 ,0,0,0}, {4228,4576,4575 ,726,726,726 ,0,0,0}, - {4576,4228,4224 ,726,726,726 ,0,0,0}, {4230,4617,4223 ,726,726,726 ,0,0,0}, - {4224,4616,4576 ,726,726,726 ,0,0,0}, {4159,4160,4341 ,3295,726,3295 ,0,0,0}, - {4623,4622,4233 ,726,726,726 ,0,0,0}, {4622,4230,4233 ,726,726,726 ,0,0,0}, - {4314,4318,4195 ,726,3295,3295 ,0,0,0}, {4625,4623,4234 ,726,726,726 ,0,0,0}, - {4241,4628,4237 ,726,726,726 ,0,0,0}, {4629,4241,4243 ,726,726,726 ,0,0,0}, - {4241,4629,4628 ,726,726,726 ,0,0,0}, {4240,4631,4243 ,726,726,726 ,0,0,0}, - {4629,4243,4631 ,726,726,726 ,0,0,0}, {4631,4240,4634 ,726,726,726 ,0,0,0}, - {4244,4247,4635 ,726,726,726 ,0,0,0}, {4196,4195,4318 ,726,3295,3295 ,0,0,0}, - {4637,4247,4248 ,726,726,726 ,0,0,0}, {4247,4637,4635 ,726,726,726 ,0,0,0}, - {4641,4640,4250 ,726,726,726 ,0,0,0}, {4335,4213,4210 ,726,3295,3295 ,0,0,0}, - {4248,4250,4640 ,726,726,726 ,0,0,0}, {4254,4643,4641 ,726,726,726 ,0,0,0}, - {4641,4250,4254 ,726,726,726 ,0,0,0}, {4643,4254,4252 ,726,726,726 ,0,0,0}, - {4252,4257,4646 ,726,726,726 ,0,0,0}, {4646,4257,4647 ,726,726,726 ,0,0,0}, - {4647,4259,4649 ,726,726,726 ,0,0,0}, {4337,4216,4214 ,3295,726,3294 ,0,0,0}, - {4259,4647,4257 ,726,726,726 ,0,0,0}, {4138,4374,4372 ,726,726,3294 ,0,0,0}, - {3914,3915,4113 ,3294,726,726 ,0,0,0}, {4184,4186,4366 ,726,3294,726 ,0,0,0}, - {4372,4146,4145 ,3294,3295,3295 ,0,0,0}, {4183,4184,4365 ,3295,726,726 ,0,0,0}, - {4181,4183,4362 ,726,3295,726 ,0,0,0}, {4368,4152,4151 ,726,726,726 ,0,0,0}, - {4178,4181,4360 ,3295,726,3295 ,0,0,0}, {4368,4366,4186 ,726,726,3294 ,0,0,0}, - {4177,4178,4359 ,726,3295,3295 ,0,0,0}, {4366,4365,4184 ,726,726,726 ,0,0,0}, - {4175,4177,4356 ,3295,726,3295 ,0,0,0}, {4365,4362,4183 ,726,726,3295 ,0,0,0}, - {4172,4354,4353 ,3295,726,726 ,0,0,0}, {4362,4360,4181 ,726,3295,726 ,0,0,0}, - {4171,4353,4350 ,726,726,3295 ,0,0,0}, {4360,4359,4178 ,3295,3295,3295 ,0,0,0}, - {4169,4350,4348 ,3295,3295,726 ,0,0,0}, {4347,4166,4348 ,726,3295,726 ,0,0,0}, - {4172,4175,4354 ,3295,3295,726 ,0,0,0}, {4344,4342,4163 ,726,726,3295 ,0,0,0}, - {4172,4353,4171 ,3295,726,726 ,0,0,0}, {4581,4582,4265 ,726,726,726 ,0,0,0}, - {4350,4169,4171 ,3295,3295,726 ,0,0,0}, {4582,4585,4266 ,726,726,726 ,0,0,0}, - {4348,4166,4169 ,726,3295,3295 ,0,0,0}, {4585,4587,4268 ,726,726,726 ,0,0,0}, - {4004,4497,4005 ,3295,3295,726 ,0,0,0}, {4005,4501,4007 ,726,3295,726 ,0,0,0}, - {4342,4160,4163 ,726,726,3295 ,0,0,0}, {4271,4268,4587 ,726,726,726 ,0,0,0}, - {4262,4260,4579 ,726,726,726 ,0,0,0}, {4271,4588,4272 ,726,726,726 ,0,0,0}, - {4265,4262,4581 ,726,726,726 ,0,0,0}, {4591,4274,4272 ,726,726,726 ,0,0,0}, - {4266,4265,4582 ,726,726,726 ,0,0,0}, {4593,4277,4274 ,726,726,726 ,0,0,0}, - {4268,4266,4585 ,726,726,726 ,0,0,0}, {3968,4538,3967 ,726,3295,3295 ,0,0,0}, - {4278,4277,4594 ,726,726,726 ,0,0,0}, {4587,4588,4271 ,726,726,726 ,0,0,0}, - {4280,4278,4597 ,726,726,726 ,0,0,0}, {4280,4597,4599 ,726,726,726 ,0,0,0}, - {3971,4542,4541 ,3295,3295,726 ,0,0,0}, {4591,4593,4274 ,726,726,726 ,0,0,0}, - {3974,4547,4544 ,3295,3295,3295 ,0,0,0}, {4600,4283,4599 ,726,726,726 ,0,0,0}, - {4593,4594,4277 ,726,726,726 ,0,0,0}, {4284,4600,4603 ,726,726,726 ,0,0,0}, - {4594,4597,4278 ,726,726,726 ,0,0,0}, {3980,4553,4550 ,3295,3294,3295 ,0,0,0}, - {4599,4283,4280 ,726,726,726 ,0,0,0}, {4603,4605,4286 ,726,726,726 ,0,0,0}, - {4284,4283,4600 ,726,726,726 ,0,0,0}, {4606,4289,4605 ,726,726,726 ,0,0,0}, - {3983,3985,4554 ,726,3295,3295 ,0,0,0}, {4609,4290,4606 ,726,726,726 ,0,0,0}, - {4286,4284,4603 ,726,726,726 ,0,0,0}, {3989,3991,4560 ,726,726,726 ,0,0,0}, - {4605,4289,4286 ,726,726,726 ,0,0,0}, {4292,4609,4611 ,726,726,726 ,0,0,0}, - {3992,3995,4565 ,726,3295,726 ,0,0,0}, {4606,4290,4289 ,726,726,726 ,0,0,0}, - {4295,4292,4611 ,3295,726,726 ,0,0,0}, {4296,4295,4612 ,726,3295,726 ,0,0,0}, - {3997,3998,4566 ,726,726,3295 ,0,0,0}, {4295,4611,4612 ,3295,726,726 ,0,0,0}, - {4573,4572,4296 ,3295,726,726 ,0,0,0}, {4572,4001,4296 ,726,726,726 ,0,0,0}, - {4612,4573,4296 ,726,3295,726 ,0,0,0}, {4609,4292,4290 ,726,726,726 ,0,0,0}, - {4159,4341,4305 ,3295,3295,3295 ,0,0,0}, {4157,4305,4308 ,3295,3295,3295 ,0,0,0}, - {4153,4308,4303 ,3295,3295,3295 ,0,0,0}, {4187,4303,4307 ,726,3295,726 ,0,0,0}, - {4307,4310,4189 ,726,3295,3295 ,0,0,0}, {4230,4619,4617 ,726,726,726 ,0,0,0}, - {4305,4157,4159 ,3295,3295,3295 ,0,0,0}, {4310,4313,4190 ,3295,3295,726 ,0,0,0}, - {4308,4153,4157 ,3295,3295,3295 ,0,0,0}, {4234,4237,4625 ,726,726,726 ,0,0,0}, - {4153,4303,4187 ,3295,3295,726 ,0,0,0}, {4314,4192,4313 ,726,726,3295 ,0,0,0}, - {4307,4189,4187 ,726,3295,726 ,0,0,0}, {4196,4318,4317 ,726,3295,3295 ,0,0,0}, - {4310,4190,4189 ,3295,726,3295 ,0,0,0}, {4198,4196,4317 ,3295,726,3295 ,0,0,0}, - {4313,4192,4190 ,3295,726,726 ,0,0,0}, {4321,4201,4198 ,726,3295,3295 ,0,0,0}, - {4314,4195,4192 ,726,3295,726 ,0,0,0}, {4325,4202,4201 ,726,726,3295 ,0,0,0}, - {4327,4204,4202 ,3295,726,726 ,0,0,0}, {4634,4244,4635 ,726,726,726 ,0,0,0}, - {4198,4317,4321 ,3295,3295,726 ,0,0,0}, {4322,4207,4204 ,726,3295,726 ,0,0,0}, - {4201,4321,4325 ,3295,726,726 ,0,0,0}, {4207,4328,4208 ,3295,726,3295 ,0,0,0}, - {4202,4325,4327 ,726,726,3295 ,0,0,0}, {4210,4208,4329 ,3295,3295,726 ,0,0,0}, - {4207,4322,4328 ,3295,726,726 ,0,0,0}, {4213,4335,4334 ,3295,726,3295 ,0,0,0}, - {4208,4328,4329 ,3295,726,726 ,0,0,0}, {4337,4214,4334 ,3295,3294,3295 ,0,0,0}, - {4210,4329,4335 ,3295,726,726 ,0,0,0}, {4337,4219,4216 ,3295,726,726 ,0,0,0}, - {4214,4213,4334 ,3294,3295,3295 ,0,0,0}, {4219,4297,4222 ,726,726,726 ,0,0,0}, - {4299,4222,4297 ,3295,726,726 ,0,0,0}, {4649,4259,4222 ,726,726,726 ,0,0,0}, - {4337,4339,4219 ,3295,726,726 ,0,0,0}, {4204,4327,4322 ,726,3295,726 ,0,0,0}, - {4166,4347,4165 ,3295,726,726 ,0,0,0}, {4177,4359,4356 ,726,3295,3295 ,0,0,0}, - {4175,4356,4354 ,3295,3295,726 ,0,0,0}, {4094,4421,4422 ,3295,726,3295 ,0,0,0}, - {4148,4371,4151 ,3295,3295,726 ,0,0,0}, {4109,4100,4434 ,3295,726,726 ,0,0,0}, - {4372,4371,4146 ,3294,3295,3295 ,0,0,0}, {4136,4139,4674 ,726,3295,3295 ,0,0,0}, - {4138,4372,4145 ,726,3294,3295 ,0,0,0}, {4675,4128,4127 ,3295,3295,726 ,0,0,0}, - {4119,3950,3931 ,726,726,726 ,0,0,0}, {4130,4676,4127 ,3295,726,726 ,0,0,0}, - {4119,3931,4672 ,726,726,726 ,0,0,0}, {4377,4107,4103 ,726,726,3295 ,0,0,0}, - {4099,4427,4428 ,3295,726,726 ,0,0,0}, {4661,4059,4047 ,3295,3295,3295 ,0,0,0}, - {4416,4419,4093 ,3295,3295,3295 ,0,0,0}, {4088,4409,4410 ,3294,3295,3294 ,0,0,0}, - {4397,4398,4071 ,3295,3295,726 ,0,0,0}, {4451,3939,4452 ,3295,3295,3295 ,0,0,0}, - {4074,4392,4395 ,3295,726,3295 ,0,0,0}, {4404,4087,4072 ,726,726,726 ,0,0,0}, - {4087,4404,4407 ,726,726,3295 ,0,0,0}, {4090,4413,4415 ,3295,3295,3295 ,0,0,0}, - {4425,4094,4422 ,726,3295,3295 ,0,0,0}, {4425,4096,4094 ,726,726,3295 ,0,0,0}, - {4100,4099,4431 ,726,3295,726 ,0,0,0}, {4434,4436,4109 ,726,726,3295 ,0,0,0}, - {4109,4378,4106 ,3295,3295,3295 ,0,0,0}, {4103,4102,4377 ,3295,3295,726 ,0,0,0}, - {4675,4677,4128 ,3295,726,3295 ,0,0,0}, {4678,4679,4142 ,726,3295,726 ,0,0,0}, - {4679,4680,4142 ,3295,726,726 ,0,0,0}, {4681,4674,4139 ,726,3295,3295 ,0,0,0}, - {4674,4682,4136 ,3295,726,726 ,0,0,0}, {4107,4377,4374 ,726,726,726 ,0,0,0}, - {4378,4377,4102 ,3295,726,3295 ,0,0,0}, {4378,4109,4436 ,3295,3295,726 ,0,0,0}, - {4434,4100,4433 ,726,726,726 ,0,0,0}, {4431,4099,4428 ,726,3295,726 ,0,0,0}, - {4427,4096,4425 ,726,726,726 ,0,0,0}, {4094,4093,4421 ,3295,3295,726 ,0,0,0}, - {4093,4090,4416 ,3295,3295,3295 ,0,0,0}, {4088,4410,4413 ,3294,3294,3295 ,0,0,0}, - {4087,4407,4409 ,726,3295,3295 ,0,0,0}, {4072,4403,4404 ,726,3295,726 ,0,0,0}, - {4071,4398,4401 ,726,3295,3295 ,0,0,0}, {4074,4395,4397 ,3295,3295,3295 ,0,0,0}, - {4074,4076,4392 ,3295,3295,726 ,0,0,0}, {4078,4389,4391 ,726,3295,3295 ,0,0,0}, - {4081,4385,4386 ,3295,726,726 ,0,0,0}, {4082,4379,4383 ,726,3295,726 ,0,0,0}, - {4083,4439,4437 ,726,3295,3295 ,0,0,0}, {4652,4442,4440 ,3295,726,726 ,0,0,0}, - {4653,4446,4445 ,3295,3295,3295 ,0,0,0}, {4656,4451,4448 ,726,3295,726 ,0,0,0}, - {3870,3937,3868 ,726,3295,3295 ,0,0,0}, {3874,3877,3935 ,3295,3295,3295 ,0,0,0}, - {4454,4452,3867 ,3295,3295,726 ,0,0,0}, {3934,3876,3874 ,3295,726,3295 ,0,0,0}, - {3880,3941,4068 ,3295,726,3295 ,0,0,0}, {4683,4668,4684 ,726,3295,3295 ,0,0,0}, - {4053,4685,4051 ,726,3295,3295 ,0,0,0}, {4686,4053,4054 ,726,726,3295 ,0,0,0}, - {4048,4660,4049 ,3295,3295,726 ,0,0,0}, {4048,4051,4687 ,3295,3295,726 ,0,0,0}, - {4688,4058,4667 ,726,726,3295 ,0,0,0}, {4689,4064,4063 ,3295,3295,3295 ,0,0,0}, - {4683,4659,4658 ,726,3295,3295 ,0,0,0}, {3890,4463,3888 ,3295,3295,3295 ,0,0,0}, - {3885,4460,4458 ,3295,3295,3295 ,0,0,0}, {3894,3896,4469 ,3295,3295,726 ,0,0,0}, - {3891,4466,4464 ,726,726,726 ,0,0,0}, {4475,3897,4655 ,3295,3295,726 ,0,0,0}, - {4655,4662,4475 ,726,3295,3295 ,0,0,0}, {4472,3897,4475 ,726,3295,3295 ,0,0,0}, - {4472,4470,3896 ,726,726,3295 ,0,0,0}, {4478,4476,4662 ,726,726,3295 ,0,0,0}, - {4663,4481,4651 ,3295,726,726 ,0,0,0}, {4651,4478,4662 ,726,726,3295 ,0,0,0}, - {4663,4484,4482 ,3295,726,3295 ,0,0,0}, {4664,4044,4487 ,3295,3295,3295 ,0,0,0}, - {4663,4664,4484 ,3295,3295,726 ,0,0,0}, {4488,4487,4044 ,726,3295,3295 ,0,0,0}, - {4488,4041,4490 ,726,3295,3295 ,0,0,0}, {4493,4041,4039 ,3295,3295,3295 ,0,0,0}, - {4113,3910,4115 ,726,3295,726 ,0,0,0}, {4672,4673,4123 ,726,3295,726 ,0,0,0}, - {3904,3901,3960 ,3295,726,726 ,0,0,0}, {4670,4120,4122 ,726,726,726 ,0,0,0}, - {4671,4120,4669 ,3295,726,726 ,0,0,0}, {4676,4130,4671 ,726,3295,3295 ,0,0,0}, - {4675,4127,4676 ,3295,726,726 ,0,0,0}, {4132,4128,4677 ,3295,3295,726 ,0,0,0}, - {4132,4690,4142 ,3295,3295,726 ,0,0,0}, {4690,4132,4677 ,3295,3295,726 ,0,0,0}, - {4690,4678,4142 ,3295,726,726 ,0,0,0}, {4139,4680,4681 ,3295,726,726 ,0,0,0}, - {4680,4139,4142 ,726,3295,726 ,0,0,0}, {4138,3917,4374 ,726,726,726 ,0,0,0}, - {4682,3917,4138 ,726,726,726 ,0,0,0}, {4682,4138,4136 ,726,726,726 ,0,0,0}, - {3917,3914,4374 ,726,3294,726 ,0,0,0}, {4112,3914,4113 ,3295,3294,726 ,0,0,0}, - {3914,4112,4374 ,3294,3295,726 ,0,0,0}, {3915,3910,4113 ,726,3295,726 ,0,0,0}, - {3908,3911,4115 ,726,726,726 ,0,0,0}, {3910,3908,4115 ,3295,726,726 ,0,0,0}, - {3911,3902,4118 ,726,726,726 ,0,0,0}, {3904,3960,4118 ,3295,726,726 ,0,0,0}, - {3958,3960,3900 ,3295,726,3295 ,0,0,0}, {3922,3957,3919 ,726,3295,726 ,0,0,0}, - {3919,3958,3900 ,726,3295,3295 ,0,0,0}, {3924,3955,3922 ,726,726,726 ,0,0,0}, - {3924,3925,3944 ,726,3295,3295 ,0,0,0}, {3924,3943,3955 ,726,726,726 ,0,0,0}, - {3947,3928,3948 ,726,726,3295 ,0,0,0}, {3944,3925,3947 ,3295,3295,726 ,0,0,0}, - {3950,3930,3931 ,726,3294,726 ,0,0,0}, {3948,3928,3930 ,3295,726,3294 ,0,0,0}, - {4064,4691,4066 ,3295,726,3295 ,0,0,0}, {4655,4654,4659 ,726,726,3295 ,0,0,0}, - {4068,4066,3883 ,3295,3295,3295 ,0,0,0}, {4683,4684,4659 ,726,3295,3295 ,0,0,0}, - {4668,4667,4684 ,3295,3295,3295 ,0,0,0}, {4688,4667,4666 ,726,3295,3295 ,0,0,0}, - {4657,4058,4688 ,3295,726,726 ,0,0,0}, {4686,4054,4657 ,726,3295,3295 ,0,0,0}, - {4685,4053,4686 ,3295,726,726 ,0,0,0}, {4687,4051,4685 ,726,3295,3295 ,0,0,0}, - {4660,4048,4687 ,3295,3295,726 ,0,0,0}, {4047,4049,4661 ,3295,726,3295 ,0,0,0}, - {4665,4059,4661 ,726,3295,3295 ,0,0,0}, {4689,4063,4665 ,3295,3295,726 ,0,0,0}, - {4691,4064,4689 ,726,3295,3295 ,0,0,0}, {3883,4066,4691 ,3295,3295,726 ,0,0,0}, - {3880,4068,3883 ,3295,3295,3295 ,0,0,0}, {3881,3941,3880 ,3295,726,3295 ,0,0,0}, - {3934,3881,3876 ,3295,3295,726 ,0,0,0}, {3881,3934,3941 ,3295,3295,726 ,0,0,0}, - {3874,3935,3934 ,3295,3295,3295 ,0,0,0}, {3939,3937,3870 ,3295,3295,726 ,0,0,0}, - {4454,3867,3866 ,3295,726,726 ,0,0,0}, {3867,4452,3939 ,726,3295,3295 ,0,0,0}, - {3885,4458,3866 ,3295,3295,726 ,0,0,0}, {4457,4454,3866 ,726,3295,726 ,0,0,0}, - {3888,4460,3885 ,3295,3295,3295 ,0,0,0}, {3890,4464,4463 ,3295,726,3295 ,0,0,0}, - {3888,4463,4460 ,3295,3295,3295 ,0,0,0}, {3891,3894,4466 ,726,3295,726 ,0,0,0}, - {3890,3891,4464 ,3295,726,726 ,0,0,0}, {4469,3896,4470 ,726,3295,726 ,0,0,0}, - {4466,3894,4469 ,726,3295,726 ,0,0,0}, {4472,3896,3897 ,726,3295,3295 ,0,0,0}, - {4220,4338,4336 ,730,730,730 ,0,0,0}, {4002,4498,3963 ,730,730,730 ,0,0,0}, - {4073,4406,4405 ,730,730,730 ,0,0,0}, {4332,4215,4333 ,730,730,730 ,0,0,0}, - {4206,4209,4324 ,730,730,730 ,0,0,0}, {4211,4212,4331 ,730,730,730 ,0,0,0}, - {4197,4199,4316 ,730,730,730 ,0,0,0}, {4200,4203,4320 ,730,730,730 ,0,0,0}, - {4301,4304,4155 ,730,730,730 ,0,0,0}, {4191,4193,4311 ,730,730,730 ,0,0,0}, - {4500,3964,3963 ,730,730,730 ,0,0,0}, {4345,4162,4343 ,730,730,730 ,0,0,0}, - {3972,4540,4543 ,730,730,730 ,0,0,0}, {4546,4549,3978 ,730,730,730 ,0,0,0}, - {4534,4537,3966 ,730,730,730 ,0,0,0}, {4540,3972,3970 ,730,730,730 ,0,0,0}, - {4003,4496,4495 ,730,730,730 ,0,0,0}, {3964,4500,4534 ,730,730,730 ,0,0,0}, - {4008,4009,4505 ,730,730,730 ,0,0,0}, {4578,4261,4580 ,730,730,730 ,0,0,0}, - {4506,4012,4509 ,730,730,730 ,0,0,0}, {4009,4506,4505 ,730,730,730 ,0,0,0}, - {4021,4520,4020 ,730,730,730 ,0,0,0}, {4014,4510,4509 ,730,730,730 ,0,0,0}, - {4527,4526,4032 ,730,730,730 ,0,0,0}, {4525,4524,4027 ,730,730,730 ,0,0,0}, - {4033,4036,4530 ,730,730,730 ,0,0,0}, {4692,4444,4447 ,730,730,730 ,0,0,0}, - {4079,4077,4388 ,730,730,730 ,0,0,0}, {3882,3942,3940 ,730,730,730 ,0,0,0}, - {3892,4467,4468 ,730,730,730 ,0,0,0}, {4042,4492,4494 ,730,730,730 ,0,0,0}, - {4532,4040,4494 ,730,730,730 ,0,0,0}, {4693,4694,4486 ,730,730,730 ,0,0,0}, - {3895,3893,4471 ,730,730,730 ,0,0,0}, {4693,4486,4489 ,730,730,730 ,0,0,0}, - {4483,4485,4694 ,730,730,730 ,0,0,0}, {4045,4695,4046 ,730,730,730 ,0,0,0}, - {4494,4040,4042 ,730,730,730 ,0,0,0}, {4406,4073,4086 ,730,730,730 ,0,0,0}, - {4696,4085,4443 ,730,730,730 ,0,0,0}, {4384,4382,4080 ,730,730,730 ,0,0,0}, - {3892,4468,3893 ,730,730,730 ,0,0,0}, {3938,4453,4455 ,730,730,730 ,0,0,0}, - {4036,4038,4532 ,730,730,730 ,0,0,0}, {3936,3869,3933 ,730,730,730 ,0,0,0}, - {3872,3873,3933 ,730,730,730 ,0,0,0}, {4697,4061,4062 ,730,730,730 ,0,0,0}, - {4693,4489,4043 ,730,730,730 ,0,0,0}, {4042,4043,4491 ,730,730,730 ,0,0,0}, - {4698,4483,4694 ,730,730,730 ,0,0,0}, {4479,4480,4699 ,730,730,730 ,0,0,0}, - {4699,4480,4698 ,730,730,730 ,0,0,0}, {4698,4480,4483 ,730,730,730 ,0,0,0}, - {4694,4485,4486 ,730,730,730 ,0,0,0}, {4700,4701,4702 ,730,730,730 ,0,0,0}, - {3951,3952,3929 ,730,730,730 ,0,0,0}, {4489,4491,4043 ,730,730,730 ,0,0,0}, - {4473,3895,4471 ,730,730,730 ,0,0,0}, {4492,4042,4491 ,730,730,730 ,0,0,0}, - {4703,4057,4055 ,730,730,730 ,0,0,0}, {4062,4065,4704 ,730,730,730 ,0,0,0}, - {4067,3942,3879 ,730,730,730 ,0,0,0}, {4065,4067,3878 ,730,730,730 ,0,0,0}, - {4532,4038,4040 ,730,730,730 ,0,0,0}, {4046,4705,4050 ,730,730,730 ,0,0,0}, - {4706,4060,4061 ,730,730,730 ,0,0,0}, {3938,4455,3865 ,730,730,730 ,0,0,0}, - {4050,4707,4052 ,730,730,730 ,0,0,0}, {3889,4467,3892 ,730,730,730 ,0,0,0}, - {4467,3889,4465 ,730,730,730 ,0,0,0}, {4380,4084,4381 ,730,730,730 ,0,0,0}, - {4396,4070,4399 ,730,730,730 ,0,0,0}, {4393,4390,4075 ,730,730,730 ,0,0,0}, - {4414,4412,4089 ,730,730,730 ,0,0,0}, {4402,4069,4073 ,730,730,730 ,0,0,0}, - {4414,4089,4091 ,730,730,730 ,0,0,0}, {4032,4033,4527 ,730,730,730 ,0,0,0}, - {4036,4532,4530 ,730,730,730 ,0,0,0}, {4530,4527,4033 ,730,730,730 ,0,0,0}, - {4546,3976,4545 ,730,730,730 ,0,0,0}, {4525,4027,4030 ,730,730,730 ,0,0,0}, - {4526,4030,4032 ,730,730,730 ,0,0,0}, {4026,4027,4524 ,730,730,730 ,0,0,0}, - {4525,4030,4526 ,730,730,730 ,0,0,0}, {4026,4518,4024 ,730,730,730 ,0,0,0}, - {4517,4021,4024 ,730,730,730 ,0,0,0}, {4524,4518,4026 ,730,730,730 ,0,0,0}, - {4021,4517,4520 ,730,730,730 ,0,0,0}, {4024,4518,4517 ,730,730,730 ,0,0,0}, - {4355,4174,4173 ,730,730,730 ,0,0,0}, {4514,4018,4020 ,730,730,730 ,0,0,0}, - {4018,4513,4015 ,730,730,730 ,0,0,0}, {4513,4510,4015 ,730,730,730 ,0,0,0}, - {4510,4014,4015 ,730,730,730 ,0,0,0}, {4509,4012,4014 ,730,730,730 ,0,0,0}, - {4506,4009,4012 ,730,730,730 ,0,0,0}, {4006,4503,4496 ,730,730,730 ,0,0,0}, - {4008,4505,4503 ,730,730,730 ,0,0,0}, {4003,4495,4002 ,730,730,730 ,0,0,0}, - {4498,4500,3963 ,730,730,730 ,0,0,0}, {3966,4537,3969 ,730,730,730 ,0,0,0}, - {3970,3969,4539 ,730,730,730 ,0,0,0}, {3972,4543,3975 ,730,730,730 ,0,0,0}, - {3970,4539,4540 ,730,730,730 ,0,0,0}, {3975,4545,3976 ,730,730,730 ,0,0,0}, - {3975,4543,4545 ,730,730,730 ,0,0,0}, {3981,4549,4551 ,730,730,730 ,0,0,0}, - {3978,3976,4546 ,730,730,730 ,0,0,0}, {3982,3981,4551 ,730,730,730 ,0,0,0}, - {3982,4551,4552 ,730,730,730 ,0,0,0}, {3984,4552,4555 ,730,730,730 ,0,0,0}, - {3982,4552,3984 ,730,730,730 ,0,0,0}, {4555,3987,3984 ,730,730,730 ,0,0,0}, - {4555,4557,3987 ,730,730,730 ,0,0,0}, {3987,4557,3988 ,730,730,730 ,0,0,0}, - {3969,4537,4539 ,730,730,730 ,0,0,0}, {3990,3988,4558 ,730,730,730 ,0,0,0}, - {3988,4557,4558 ,730,730,730 ,0,0,0}, {4561,3993,3990 ,730,730,730 ,0,0,0}, - {4561,3990,4558 ,730,730,730 ,0,0,0}, {3993,4563,3994 ,730,730,730 ,0,0,0}, - {3994,4564,3996 ,730,730,730 ,0,0,0}, {4564,3994,4563 ,730,730,730 ,0,0,0}, - {4564,4567,3999 ,730,730,730 ,0,0,0}, {4291,4610,4608 ,730,730,730 ,0,0,0}, - {4000,3999,4567 ,730,730,730 ,0,0,0}, {4570,4574,4294 ,730,730,730 ,0,0,0}, - {4293,4613,4610 ,730,730,730 ,0,0,0}, {3966,3964,4534 ,730,730,730 ,0,0,0}, - {4227,4614,4225 ,730,730,730 ,0,0,0}, {4613,4293,4294 ,730,730,730 ,0,0,0}, - {4495,4498,4002 ,730,730,730 ,0,0,0}, {4349,4167,4346 ,730,730,730 ,0,0,0}, - {4170,4168,4351 ,730,730,730 ,0,0,0}, {4168,4167,4349 ,730,730,730 ,0,0,0}, - {4164,4162,4345 ,730,730,730 ,0,0,0}, {4345,4346,4164 ,730,730,730 ,0,0,0}, - {4343,4161,4340 ,730,730,730 ,0,0,0}, {4343,4162,4161 ,730,730,730 ,0,0,0}, - {4306,4340,4158 ,730,730,730 ,0,0,0}, {4161,4158,4340 ,730,730,730 ,0,0,0}, - {4156,4304,4306 ,730,730,730 ,0,0,0}, {4306,4158,4156 ,730,730,730 ,0,0,0}, - {4302,4154,4188 ,730,730,730 ,0,0,0}, {4155,4304,4156 ,730,730,730 ,0,0,0}, - {4188,4191,4309 ,730,730,730 ,0,0,0}, {4154,4302,4301 ,730,730,730 ,0,0,0}, - {4302,4188,4309 ,730,730,730 ,0,0,0}, {4315,4312,4194 ,730,730,730 ,0,0,0}, - {4236,4626,4627 ,730,730,730 ,0,0,0}, {4197,4315,4194 ,730,730,730 ,0,0,0}, - {4193,4194,4312 ,730,730,730 ,0,0,0}, {4319,4200,4320 ,730,730,730 ,0,0,0}, - {4316,4315,4197 ,730,730,730 ,0,0,0}, {4203,4326,4320 ,730,730,730 ,0,0,0}, - {4200,4319,4199 ,730,730,730 ,0,0,0}, {4206,4323,4205 ,730,730,730 ,0,0,0}, - {4205,4323,4326 ,730,730,730 ,0,0,0}, {4330,4324,4209 ,730,730,730 ,0,0,0}, - {4324,4323,4206 ,730,730,730 ,0,0,0}, {4212,4332,4331 ,730,730,730 ,0,0,0}, - {4211,4331,4330 ,730,730,730 ,0,0,0}, {4336,4217,4218 ,730,730,730 ,0,0,0}, - {4217,4333,4215 ,730,730,730 ,0,0,0}, {4336,4218,4220 ,730,730,730 ,0,0,0}, - {4567,4569,4000 ,730,730,730 ,0,0,0}, {4570,4000,4569 ,730,730,730 ,0,0,0}, - {4288,4607,4287 ,730,730,730 ,0,0,0}, {3999,3996,4564 ,730,730,730 ,0,0,0}, - {4293,4610,4291 ,730,730,730 ,0,0,0}, {3993,4561,4563 ,730,730,730 ,0,0,0}, - {4285,4287,4604 ,730,730,730 ,0,0,0}, {4608,4607,4288 ,730,730,730 ,0,0,0}, - {4282,4285,4602 ,730,730,730 ,0,0,0}, {4607,4604,4287 ,730,730,730 ,0,0,0}, - {4601,4281,4282 ,730,730,730 ,0,0,0}, {4598,4279,4281 ,730,730,730 ,0,0,0}, - {4602,4285,4604 ,730,730,730 ,0,0,0}, {4596,4276,4279 ,730,730,730 ,0,0,0}, - {4601,4282,4602 ,730,730,730 ,0,0,0}, {3978,4549,3981 ,730,730,730 ,0,0,0}, - {4601,4598,4281 ,730,730,730 ,0,0,0}, {4595,4592,4275 ,730,730,730 ,0,0,0}, - {4598,4596,4279 ,730,730,730 ,0,0,0}, {4592,4590,4273 ,730,730,730 ,0,0,0}, - {4590,4589,4270 ,730,730,730 ,0,0,0}, {4589,4586,4269 ,730,730,730 ,0,0,0}, - {4276,4595,4275 ,730,730,730 ,0,0,0}, {4586,4584,4267 ,730,730,730 ,0,0,0}, - {4275,4592,4273 ,730,730,730 ,0,0,0}, {4583,4264,4584 ,730,730,730 ,0,0,0}, - {4273,4590,4270 ,730,730,730 ,0,0,0}, {4263,4583,4580 ,730,730,730 ,0,0,0}, - {4270,4589,4269 ,730,730,730 ,0,0,0}, {4261,4578,4226 ,730,730,730 ,0,0,0}, - {4269,4586,4267 ,730,730,730 ,0,0,0}, {4227,4226,4577 ,730,730,730 ,0,0,0}, - {4584,4264,4267 ,730,730,730 ,0,0,0}, {4225,4615,4229 ,730,730,730 ,0,0,0}, - {4263,4264,4583 ,730,730,730 ,0,0,0}, {4352,4170,4351 ,730,730,730 ,0,0,0}, - {4008,4503,4006 ,730,730,730 ,0,0,0}, {4006,4496,4003 ,730,730,730 ,0,0,0}, - {4226,4578,4577 ,730,730,730 ,0,0,0}, {4352,4355,4173 ,730,730,730 ,0,0,0}, - {4227,4577,4614 ,730,730,730 ,0,0,0}, {4355,4357,4174 ,730,730,730 ,0,0,0}, - {4225,4614,4615 ,730,730,730 ,0,0,0}, {4357,4358,4176 ,730,730,730 ,0,0,0}, - {4358,4361,4179 ,730,730,730 ,0,0,0}, {4349,4351,4168 ,730,730,730 ,0,0,0}, - {4361,4363,4180 ,730,730,730 ,0,0,0}, {4173,4170,4352 ,730,730,730 ,0,0,0}, - {4363,4364,4182 ,730,730,730 ,0,0,0}, {4020,4520,4514 ,730,730,730 ,0,0,0}, - {4018,4514,4513 ,730,730,730 ,0,0,0}, {4357,4176,4174 ,730,730,730 ,0,0,0}, - {4149,4367,4369 ,730,730,730 ,0,0,0}, {4358,4179,4176 ,730,730,730 ,0,0,0}, - {4141,4708,4709 ,730,730,730 ,0,0,0}, {4361,4180,4179 ,730,730,730 ,0,0,0}, - {3946,3949,3926 ,730,730,730 ,0,0,0}, {3920,3954,3921 ,730,730,730 ,0,0,0}, - {4185,4367,4150 ,730,730,730 ,0,0,0}, {4104,4373,4375 ,730,730,730 ,0,0,0}, - {4110,4108,4376 ,730,730,730 ,0,0,0}, {3923,3945,3946 ,730,730,730 ,0,0,0}, - {4098,4432,4430 ,730,730,730 ,0,0,0}, {4710,4124,4711 ,730,730,730 ,0,0,0}, - {4373,4104,4111 ,730,730,730 ,0,0,0}, {4092,4423,4420 ,730,730,730 ,0,0,0}, - {4474,3898,3895 ,730,730,730 ,0,0,0}, {4712,4477,4699 ,730,730,730 ,0,0,0}, - {4479,4699,4477 ,730,730,730 ,0,0,0}, {4477,4712,3898 ,730,730,730 ,0,0,0}, - {4713,4714,4715 ,730,730,730 ,0,0,0}, {4477,3898,4474 ,730,730,730 ,0,0,0}, - {4473,4474,3895 ,730,730,730 ,0,0,0}, {3875,3940,3873 ,730,730,730 ,0,0,0}, - {4706,4695,4060 ,730,730,730 ,0,0,0}, {4716,4717,4718 ,730,730,730 ,0,0,0}, - {4380,4438,4084 ,730,730,730 ,0,0,0}, {4070,4394,4075 ,730,730,730 ,0,0,0}, - {4411,4086,4089 ,730,730,730 ,0,0,0}, {4424,4095,4097 ,730,730,730 ,0,0,0}, - {4424,4423,4095 ,730,730,730 ,0,0,0}, {4426,4097,4429 ,730,730,730 ,0,0,0}, - {4420,4418,4092 ,730,730,730 ,0,0,0}, {4418,4417,4091 ,730,730,730 ,0,0,0}, - {4086,4411,4408 ,730,730,730 ,0,0,0}, {4402,4400,4069 ,730,730,730 ,0,0,0}, - {4069,4399,4070 ,730,730,730 ,0,0,0}, {4394,4393,4075 ,730,730,730 ,0,0,0}, - {4388,4387,4079 ,730,730,730 ,0,0,0}, {4384,4080,4079 ,730,730,730 ,0,0,0}, - {4429,4098,4430 ,730,730,730 ,0,0,0}, {4382,4381,4080 ,730,730,730 ,0,0,0}, - {4438,4085,4084 ,730,730,730 ,0,0,0}, {4441,4443,4085 ,730,730,730 ,0,0,0}, - {4449,4719,4692 ,730,730,730 ,0,0,0}, {4719,4449,4450 ,730,730,730 ,0,0,0}, - {3938,4719,4453 ,730,730,730 ,0,0,0}, {3884,4456,4459 ,730,730,730 ,0,0,0}, - {3887,3886,4462 ,730,730,730 ,0,0,0}, {3884,3865,4456 ,730,730,730 ,0,0,0}, - {4450,4453,4719 ,730,730,730 ,0,0,0}, {4447,4449,4692 ,730,730,730 ,0,0,0}, - {4443,4444,4696 ,730,730,730 ,0,0,0}, {4444,4692,4696 ,730,730,730 ,0,0,0}, - {4438,4441,4085 ,730,730,730 ,0,0,0}, {4381,4084,4080 ,730,730,730 ,0,0,0}, - {4384,4079,4387 ,730,730,730 ,0,0,0}, {4077,4075,4390 ,730,730,730 ,0,0,0}, - {4077,4390,4388 ,730,730,730 ,0,0,0}, {4070,4396,4394 ,730,730,730 ,0,0,0}, - {4069,4400,4399 ,730,730,730 ,0,0,0}, {4073,4405,4402 ,730,730,730 ,0,0,0}, - {4086,4408,4406 ,730,730,730 ,0,0,0}, {4089,4412,4411 ,730,730,730 ,0,0,0}, - {4091,4417,4414 ,730,730,730 ,0,0,0}, {4091,4092,4418 ,730,730,730 ,0,0,0}, - {4092,4095,4423 ,730,730,730 ,0,0,0}, {4097,4426,4424 ,730,730,730 ,0,0,0}, - {4097,4098,4429 ,730,730,730 ,0,0,0}, {4098,4110,4432 ,730,730,730 ,0,0,0}, - {4110,4376,4435 ,730,730,730 ,0,0,0}, {4432,4110,4435 ,730,730,730 ,0,0,0}, - {4376,4108,4105 ,730,730,730 ,0,0,0}, {4105,4101,4375 ,730,730,730 ,0,0,0}, - {4375,4376,4105 ,730,730,730 ,0,0,0}, {3927,3926,3949 ,730,730,730 ,0,0,0}, - {4104,4375,4101 ,730,730,730 ,0,0,0}, {3906,4116,4117 ,730,730,730 ,0,0,0}, - {3927,3949,3951 ,730,730,730 ,0,0,0}, {3952,4125,3932 ,730,730,730 ,0,0,0}, - {3951,3929,3927 ,730,730,730 ,0,0,0}, {3952,3932,3929 ,730,730,730 ,0,0,0}, - {4133,4720,4126 ,730,730,730 ,0,0,0}, {4129,4721,4121 ,730,730,730 ,0,0,0}, - {4722,4134,4723 ,730,730,730 ,0,0,0}, {4141,4724,4723 ,730,730,730 ,0,0,0}, - {3956,3918,3959 ,730,730,730 ,0,0,0}, {4725,4140,4726 ,730,730,730 ,0,0,0}, - {3920,3918,3956 ,730,730,730 ,0,0,0}, {4369,4144,4147 ,730,730,730 ,0,0,0}, - {4370,4143,4144 ,730,730,730 ,0,0,0}, {3909,4116,3907 ,730,730,730 ,0,0,0}, - {4117,3903,3906 ,730,730,730 ,0,0,0}, {3909,3916,4114 ,730,730,730 ,0,0,0}, - {4137,4143,4370 ,730,730,730 ,0,0,0}, {4137,4370,4373 ,730,730,730 ,0,0,0}, - {4144,4369,4370 ,730,730,730 ,0,0,0}, {4149,4369,4147 ,730,730,730 ,0,0,0}, - {4150,4367,4149 ,730,730,730 ,0,0,0}, {4364,4367,4185 ,730,730,730 ,0,0,0}, - {4182,4364,4185 ,730,730,730 ,0,0,0}, {4180,4363,4182 ,730,730,730 ,0,0,0}, - {4229,4618,4231 ,730,730,730 ,0,0,0}, {4621,4231,4620 ,730,730,730 ,0,0,0}, - {4164,4346,4167 ,730,730,730 ,0,0,0}, {4624,4232,4621 ,730,730,730 ,0,0,0}, - {4624,4235,4232 ,730,730,730 ,0,0,0}, {4626,4236,4235 ,730,730,730 ,0,0,0}, - {4618,4229,4615 ,730,730,730 ,0,0,0}, {4627,4242,4236 ,730,730,730 ,0,0,0}, - {4620,4231,4618 ,730,730,730 ,0,0,0}, {4154,4301,4155 ,730,730,730 ,0,0,0}, - {4238,4242,4630 ,730,730,730 ,0,0,0}, {4232,4231,4621 ,730,730,730 ,0,0,0}, - {4239,4238,4632 ,730,730,730 ,0,0,0}, {4624,4626,4235 ,730,730,730 ,0,0,0}, - {4245,4239,4633 ,730,730,730 ,0,0,0}, {4193,4312,4311 ,730,730,730 ,0,0,0}, - {4191,4311,4309 ,730,730,730 ,0,0,0}, {4242,4627,4630 ,730,730,730 ,0,0,0}, - {4246,4245,4636 ,730,730,730 ,0,0,0}, {4246,4636,4638 ,730,730,730 ,0,0,0}, - {4630,4632,4238 ,730,730,730 ,0,0,0}, {4199,4319,4316 ,730,730,730 ,0,0,0}, - {4239,4632,4633 ,730,730,730 ,0,0,0}, {4638,4639,4249 ,730,730,730 ,0,0,0}, - {4642,4255,4639 ,730,730,730 ,0,0,0}, {4633,4636,4245 ,730,730,730 ,0,0,0}, - {4249,4246,4638 ,730,730,730 ,0,0,0}, {4644,4253,4642 ,730,730,730 ,0,0,0}, - {4203,4205,4326 ,730,730,730 ,0,0,0}, {4645,4251,4644 ,730,730,730 ,0,0,0}, - {4255,4249,4639 ,730,730,730 ,0,0,0}, {4209,4211,4330 ,730,730,730 ,0,0,0}, - {4642,4253,4255 ,730,730,730 ,0,0,0}, {4645,4648,4256 ,730,730,730 ,0,0,0}, - {4212,4215,4332 ,730,730,730 ,0,0,0}, {4644,4251,4253 ,730,730,730 ,0,0,0}, - {4258,4256,4648 ,730,730,730 ,0,0,0}, {4258,4650,4221 ,730,730,730 ,0,0,0}, - {4333,4217,4336 ,730,730,730 ,0,0,0}, {4258,4648,4650 ,730,730,730 ,0,0,0}, - {4300,4220,4221 ,730,730,730 ,0,0,0}, {4338,4220,4300 ,730,730,730 ,0,0,0}, - {4650,4298,4221 ,730,730,730 ,0,0,0}, {4300,4221,4298 ,730,730,730 ,0,0,0}, - {4645,4256,4251 ,730,730,730 ,0,0,0}, {4261,4263,4580 ,730,730,730 ,0,0,0}, - {4595,4276,4596 ,730,730,730 ,0,0,0}, {4608,4288,4291 ,730,730,730 ,0,0,0}, - {4570,4294,4000 ,730,730,730 ,0,0,0}, {4574,4613,4294 ,730,730,730 ,0,0,0}, - {3921,3953,3923 ,730,730,730 ,0,0,0}, {4727,4129,4131 ,730,730,730 ,0,0,0}, - {4133,4722,4720 ,730,730,730 ,0,0,0}, {3923,3946,3926 ,730,730,730 ,0,0,0}, - {3923,3953,3945 ,730,730,730 ,0,0,0}, {3921,3954,3953 ,730,730,730 ,0,0,0}, - {3920,3956,3954 ,730,730,730 ,0,0,0}, {4135,4137,4728 ,730,730,730 ,0,0,0}, - {3899,3905,3959 ,730,730,730 ,0,0,0}, {3899,3959,3918 ,730,730,730 ,0,0,0}, - {4117,3905,3903 ,730,730,730 ,0,0,0}, {3905,4117,3959 ,730,730,730 ,0,0,0}, - {3912,4137,4373 ,730,730,730 ,0,0,0}, {3909,4114,4116 ,730,730,730 ,0,0,0}, - {3906,3907,4116 ,730,730,730 ,0,0,0}, {3913,4114,3916 ,730,730,730 ,0,0,0}, - {4373,3913,3912 ,730,730,730 ,0,0,0}, {4111,3913,4373 ,730,730,730 ,0,0,0}, - {3913,4111,4114 ,730,730,730 ,0,0,0}, {3912,4728,4137 ,730,730,730 ,0,0,0}, - {4135,4726,4140 ,730,730,730 ,0,0,0}, {4728,4726,4135 ,730,730,730 ,0,0,0}, - {4140,4708,4141 ,730,730,730 ,0,0,0}, {4725,4708,4140 ,730,730,730 ,0,0,0}, - {4709,4724,4141 ,730,730,730 ,0,0,0}, {4723,4134,4141 ,730,730,730 ,0,0,0}, - {4722,4133,4134 ,730,730,730 ,0,0,0}, {4729,4126,4720 ,730,730,730 ,0,0,0}, - {4131,4729,4727 ,730,730,730 ,0,0,0}, {4729,4131,4126 ,730,730,730 ,0,0,0}, - {4727,4730,4129 ,730,730,730 ,0,0,0}, {4721,4711,4121 ,730,730,730 ,0,0,0}, - {4730,4721,4129 ,730,730,730 ,0,0,0}, {4124,4710,4125 ,730,730,730 ,0,0,0}, - {4121,4711,4124 ,730,730,730 ,0,0,0}, {3932,4125,4710 ,730,730,730 ,0,0,0}, - {3936,3938,3871 ,730,730,730 ,0,0,0}, {4468,4471,3893 ,730,730,730 ,0,0,0}, - {4055,4052,4731 ,730,730,730 ,0,0,0}, {3887,4462,4465 ,730,730,730 ,0,0,0}, - {4465,3889,3887 ,730,730,730 ,0,0,0}, {4461,4462,3886 ,730,730,730 ,0,0,0}, - {4461,3884,4459 ,730,730,730 ,0,0,0}, {3884,4461,3886 ,730,730,730 ,0,0,0}, - {4456,3865,4455 ,730,730,730 ,0,0,0}, {3865,3871,3938 ,730,730,730 ,0,0,0}, - {3871,3869,3936 ,730,730,730 ,0,0,0}, {3869,3872,3933 ,730,730,730 ,0,0,0}, - {3873,3940,3933 ,730,730,730 ,0,0,0}, {3882,3940,3875 ,730,730,730 ,0,0,0}, - {3879,3942,3882 ,730,730,730 ,0,0,0}, {3878,4067,3879 ,730,730,730 ,0,0,0}, - {4704,4065,3878 ,730,730,730 ,0,0,0}, {4697,4062,4704 ,730,730,730 ,0,0,0}, - {4706,4061,4697 ,730,730,730 ,0,0,0}, {4045,4060,4695 ,730,730,730 ,0,0,0}, - {4705,4046,4695 ,730,730,730 ,0,0,0}, {4707,4050,4705 ,730,730,730 ,0,0,0}, - {4731,4052,4707 ,730,730,730 ,0,0,0}, {4732,4057,4703 ,730,730,730 ,0,0,0}, - {4703,4055,4731 ,730,730,730 ,0,0,0}, {4056,4732,4718 ,730,730,730 ,0,0,0}, - {4732,4056,4057 ,730,730,730 ,0,0,0}, {4716,4701,4717 ,730,730,730 ,0,0,0}, - {4056,4718,4717 ,730,730,730 ,0,0,0}, {4700,4702,4713 ,730,730,730 ,0,0,0}, - {4717,4701,4700 ,730,730,730 ,0,0,0}, {4713,4715,4712 ,730,730,730 ,0,0,0}, - {4713,4702,4714 ,730,730,730 ,0,0,0}, {3898,4712,4715 ,730,730,730 ,0,0,0}, - {4712,4699,4662 ,4036,4037,4038 ,0,0,0}, {4713,4655,4659 ,4039,4040,4041 ,0,0,0}, - {4655,4712,4662 ,4040,4036,4038 ,0,0,0}, {4712,4655,4713 ,4036,4040,4039 ,0,0,0}, - {4717,4684,4667 ,4042,4043,4044 ,0,0,0}, {4713,4659,4700 ,4039,4041,4045 ,0,0,0}, - {4717,4700,4684 ,4042,4045,4043 ,0,0,0}, {4667,4058,4056 ,4044,3474,3474 ,0,0,0}, - {4667,4056,4717 ,4044,3474,4042 ,0,0,0}, {4684,4700,4659 ,4043,4045,4041 ,0,0,0}, - {4699,4651,4662 ,4037,4046,4038 ,0,0,0}, {4663,4651,4698 ,4047,4046,4048 ,0,0,0}, - {4699,4698,4651 ,4037,4048,4046 ,0,0,0}, {4694,4664,4663 ,4049,4050,4047 ,0,0,0}, - {4663,4698,4694 ,4047,4048,4049 ,0,0,0}, {4664,4693,4044 ,4050,4051,3464 ,0,0,0}, - {4693,4664,4694 ,4051,4050,4049 ,0,0,0}, {4693,4043,4044 ,4051,3464,3464 ,0,0,0}, - {3939,4656,4719 ,3377,4052,4052 ,0,0,0}, {4652,4085,4696 ,4053,3500,4054 ,0,0,0}, - {4696,4692,4653 ,4054,4055,4055 ,0,0,0}, {4083,4085,4652 ,3500,3500,4053 ,0,0,0}, - {4656,4692,4719 ,4052,4055,4052 ,0,0,0}, {4692,4656,4653 ,4055,4052,4055 ,0,0,0}, - {4652,4696,4653 ,4053,4054,4055 ,0,0,0}, {4719,3938,3939 ,4052,3377,3377 ,0,0,0}, - {3917,4682,4728 ,2601,53,2600 ,0,0,0}, {4680,4708,4681 ,2596,2595,2597 ,0,0,0}, - {4725,4726,4674 ,2598,2599,139 ,0,0,0}, {4723,4690,4722 ,2590,2573,324 ,0,0,0}, - {4679,4678,4724 ,2594,2591,2592 ,0,0,0}, {4676,4727,4729 ,2575,2579,2576 ,0,0,0}, - {4675,4720,4677 ,2577,2578,2574 ,0,0,0}, {4669,4721,4730 ,2581,2582,2580 ,0,0,0}, - {4730,4727,4671 ,2580,2579,2584 ,0,0,0}, {4721,4670,4711 ,2582,2583,2588 ,0,0,0}, - {4670,4721,4669 ,2583,2582,2581 ,0,0,0}, {4710,4711,4673 ,2585,2588,2587 ,0,0,0}, - {4670,4673,4711 ,2583,2587,2588 ,0,0,0}, {4672,3932,4710 ,2586,126,2585 ,0,0,0}, - {4710,4673,4672 ,2585,2587,2586 ,0,0,0}, {3931,3932,4672 ,2589,126,2586 ,0,0,0}, - {4675,4676,4729 ,2577,2575,2576 ,0,0,0}, {4727,4676,4671 ,2579,2575,2584 ,0,0,0}, - {4669,4730,4671 ,2581,2580,2584 ,0,0,0}, {4675,4729,4720 ,2577,2576,2578 ,0,0,0}, - {4677,4720,4722 ,2574,2578,324 ,0,0,0}, {4690,4723,4678 ,2573,2590,2591 ,0,0,0}, - {4690,4677,4722 ,2573,2574,324 ,0,0,0}, {4679,4724,4709 ,2594,2592,2593 ,0,0,0}, - {4724,4678,4723 ,2592,2591,2590 ,0,0,0}, {4709,4708,4680 ,2593,2595,2596 ,0,0,0}, - {4709,4680,4679 ,2593,2596,2594 ,0,0,0}, {4674,4681,4725 ,139,2597,2598 ,0,0,0}, - {4708,4725,4681 ,2595,2598,2597 ,0,0,0}, {4726,4682,4674 ,2599,53,139 ,0,0,0}, - {3917,4728,3912 ,2601,2600,2602 ,0,0,0}, {4682,4726,4728 ,53,2599,2600 ,0,0,0}, - {3883,4691,4704 ,2630,2629,2628 ,0,0,0}, {4661,4695,4665 ,2626,2625,2627 ,0,0,0}, - {4706,4697,4689 ,2598,111,139 ,0,0,0}, {4731,4685,4703 ,2620,2603,324 ,0,0,0}, - {4660,4687,4707 ,2624,2621,2622 ,0,0,0}, {4688,4716,4718 ,2604,2608,2605 ,0,0,0}, - {4657,4732,4686 ,2606,2607,324 ,0,0,0}, {4668,4702,4701 ,2610,2611,2609 ,0,0,0}, - {4701,4716,4666 ,2609,2608,2613 ,0,0,0}, {4702,4683,4714 ,2611,2612,2618 ,0,0,0}, - {4683,4702,4668 ,2612,2611,2610 ,0,0,0}, {4715,4714,4658 ,2615,2618,2617 ,0,0,0}, - {4683,4658,4714 ,2612,2617,2618 ,0,0,0}, {4654,3898,4715 ,2616,2614,2615 ,0,0,0}, - {4715,4658,4654 ,2615,2617,2616 ,0,0,0}, {3897,3898,4654 ,2619,2614,2616 ,0,0,0}, - {4657,4688,4718 ,2606,2604,2605 ,0,0,0}, {4716,4688,4666 ,2608,2604,2613 ,0,0,0}, - {4668,4701,4666 ,2610,2609,2613 ,0,0,0}, {4657,4718,4732 ,2606,2605,2607 ,0,0,0}, - {4686,4732,4703 ,324,2607,324 ,0,0,0}, {4685,4731,4687 ,2603,2620,2621 ,0,0,0}, - {4685,4686,4703 ,2603,324,324 ,0,0,0}, {4660,4707,4705 ,2624,2622,2623 ,0,0,0}, - {4707,4687,4731 ,2622,2621,2620 ,0,0,0}, {4705,4695,4661 ,2623,2625,2626 ,0,0,0}, - {4705,4661,4660 ,2623,2626,2624 ,0,0,0}, {4689,4665,4706 ,139,2627,2598 ,0,0,0}, - {4695,4706,4665 ,2625,2598,2627 ,0,0,0}, {4697,4691,4689 ,111,2629,139 ,0,0,0}, - {3883,4704,3878 ,2630,2628,82 ,0,0,0}, {4691,4697,4704 ,2629,111,2628 ,0,0,0} -// MotorHacker.prt - , {4733,4734,4735 ,4056,4057,4058 ,0,0,0}, {4736,4737,4735 ,4059,4060,4058 ,0,0,0}, - {4733,4735,4737 ,4056,4058,4060 ,0,0,0}, {4738,4736,4739 ,4061,4059,4062 ,0,0,0}, - {4738,4737,4736 ,4061,4060,4059 ,0,0,0}, {4740,4739,4741 ,4063,4062,4064 ,0,0,0}, - {4736,4741,4739 ,4059,4064,4062 ,0,0,0}, {4742,4743,4740 ,4065,4066,4063 ,0,0,0}, - {4740,4741,4742 ,4063,4064,4065 ,0,0,0}, {4743,4744,4745 ,4066,4067,4068 ,0,0,0}, - {4744,4743,4742 ,4067,4066,4065 ,0,0,0}, {4746,4745,4747 ,4069,4068,4070 ,0,0,0}, - {4744,4747,4745 ,4067,4070,4068 ,0,0,0}, {4748,4749,4746 ,4071,4072,4069 ,0,0,0}, - {4746,4747,4748 ,4069,4070,4071 ,0,0,0}, {4750,4751,4749 ,4073,81,4072 ,0,0,0}, - {4750,4749,4748 ,4073,4072,4071 ,0,0,0}, {4751,4752,4749 ,81,81,4072 ,0,0,0}, - {4753,4734,4733 ,4074,4057,4056 ,0,0,0}, {4753,4754,4755 ,4074,4075,4076 ,0,0,0}, - {4755,4734,4753 ,4076,4057,4074 ,0,0,0}, {4756,4757,4754 ,4077,4078,4075 ,0,0,0}, - {4754,4757,4755 ,4075,4078,4076 ,0,0,0}, {4758,4759,4756 ,4079,4080,4077 ,0,0,0}, - {4756,4754,4758 ,4077,4075,4079 ,0,0,0}, {4759,4760,4761 ,4080,4081,4082 ,0,0,0}, - {4760,4759,4758 ,4081,4080,4079 ,0,0,0}, {4762,4761,4763 ,4083,4082,4084 ,0,0,0}, - {4760,4763,4761 ,4081,4084,4082 ,0,0,0}, {4764,4765,4762 ,4085,4086,4083 ,0,0,0}, - {4762,4763,4764 ,4083,4084,4085 ,0,0,0}, {4765,4766,4767 ,4086,4087,4088 ,0,0,0}, - {4766,4765,4764 ,4087,4086,4085 ,0,0,0}, {4767,4768,4769 ,4088,4089,4090 ,0,0,0}, - {4766,4768,4767 ,4087,4089,4088 ,0,0,0}, {4767,4769,4770 ,4088,4090,4091 ,0,0,0}, - {4771,4772,4773 ,2394,2394,4092 ,0,0,0}, {4774,4775,4773 ,4093,4094,4092 ,0,0,0}, - {4771,4773,4775 ,2394,4092,4094 ,0,0,0}, {4774,4776,4777 ,4093,4095,4096 ,0,0,0}, - {4777,4775,4774 ,4096,4094,4093 ,0,0,0}, {4778,4776,4779 ,4097,4095,4098 ,0,0,0}, - {4776,4778,4777 ,4095,4097,4096 ,0,0,0}, {4780,4781,4779 ,4099,4100,4098 ,0,0,0}, - {4778,4779,4781 ,4097,4098,4100 ,0,0,0}, {4780,4782,4783 ,4099,4101,4102 ,0,0,0}, - {4783,4781,4780 ,4102,4100,4099 ,0,0,0}, {4784,4782,4785 ,4103,4101,4104 ,0,0,0}, - {4782,4784,4783 ,4101,4103,4102 ,0,0,0}, {4786,4787,4785 ,4105,4106,4104 ,0,0,0}, - {4784,4785,4787 ,4103,4104,4106 ,0,0,0}, {4786,4788,4789 ,4105,4107,4108 ,0,0,0}, - {4789,4787,4786 ,4108,4106,4105 ,0,0,0}, {4790,4791,4788 ,4109,4110,4107 ,0,0,0}, - {4788,4791,4789 ,4107,4110,4108 ,0,0,0}, {4792,4793,4790 ,4111,4112,4109 ,0,0,0}, - {4790,4788,4792 ,4109,4107,4111 ,0,0,0}, {4793,4794,4795 ,4112,4113,4114 ,0,0,0}, - {4794,4793,4792 ,4113,4112,4111 ,0,0,0}, {4794,4796,4795 ,4113,4114,4114 ,0,0,0}, - {4797,4772,4771 ,4115,2394,2394 ,0,0,0}, {4797,4798,4799 ,4115,4116,4117 ,0,0,0}, - {4799,4772,4797 ,4117,2394,4115 ,0,0,0}, {4800,4798,4801 ,4118,4116,4119 ,0,0,0}, - {4798,4800,4799 ,4116,4118,4117 ,0,0,0}, {4802,4803,4801 ,4120,4121,4119 ,0,0,0}, - {4800,4801,4803 ,4118,4119,4121 ,0,0,0}, {4802,4804,4805 ,4120,4122,4123 ,0,0,0}, - {4805,4803,4802 ,4123,4121,4120 ,0,0,0}, {4806,4804,4807 ,4124,4122,4125 ,0,0,0}, - {4804,4806,4805 ,4122,4124,4123 ,0,0,0}, {4808,4809,4807 ,4126,4127,4125 ,0,0,0}, - {4806,4807,4809 ,4124,4125,4127 ,0,0,0}, {4808,4810,4811 ,4126,4128,4129 ,0,0,0}, - {4811,4809,4808 ,4129,4127,4126 ,0,0,0}, {4812,4810,4813 ,4130,4128,4131 ,0,0,0}, - {4810,4812,4811 ,4128,4130,4129 ,0,0,0}, {4813,4814,4815 ,4131,4132,4133 ,0,0,0}, - {4812,4813,4815 ,4130,4131,4133 ,0,0,0}, {4814,4816,4817 ,4132,4134,4135 ,0,0,0}, - {4816,4814,4813 ,4134,4132,4131 ,0,0,0}, {4818,4817,4819 ,126,4135,4136 ,0,0,0}, - {4816,4819,4817 ,4134,4136,4135 ,0,0,0}, {4818,4819,4820 ,126,4136,126 ,0,0,0}, - {4821,4822,4823 ,4137,4138,4139 ,0,0,0}, {4821,4824,4825 ,4137,4140,4141 ,0,0,0}, - {4824,4826,4825 ,4140,4142,4141 ,0,0,0}, {4823,4824,4821 ,4139,4140,4137 ,0,0,0}, - {4827,4828,4829 ,4143,4144,4145 ,0,0,0}, {4826,4827,4829 ,4142,4143,4145 ,0,0,0}, - {4828,4830,4831 ,4144,4146,4147 ,0,0,0}, {4830,4828,4827 ,4146,4144,4143 ,0,0,0}, - {4831,4830,4832 ,4147,4146,4148 ,0,0,0}, {4833,4831,4832 ,4149,4147,4148 ,0,0,0}, - {4833,4834,4835 ,4149,4150,4151 ,0,0,0}, {4833,4832,4834 ,4149,4148,4150 ,0,0,0}, - {4829,4825,4826 ,4145,4141,4142 ,0,0,0}, {4836,4837,4838 ,4152,1711,1711 ,0,0,0}, - {4836,4838,4835 ,4152,1711,4151 ,0,0,0}, {4834,4836,4835 ,4150,4152,4151 ,0,0,0}, - {4823,4822,4839 ,4139,4138,4153 ,0,0,0}, {4840,4839,4841 ,4154,4153,4155 ,0,0,0}, - {4822,4841,4839 ,4138,4155,4153 ,0,0,0}, {4842,4843,4840 ,4156,4157,4154 ,0,0,0}, - {4840,4841,4842 ,4154,4155,4156 ,0,0,0}, {4843,4844,4845 ,4157,4158,4159 ,0,0,0}, - {4844,4843,4842 ,4158,4157,4156 ,0,0,0}, {4846,4845,4847 ,4160,4159,4161 ,0,0,0}, - {4844,4847,4845 ,4158,4161,4159 ,0,0,0}, {4848,4849,4846 ,4162,4163,4160 ,0,0,0}, - {4846,4847,4848 ,4160,4161,4162 ,0,0,0}, {4849,4850,4851 ,4163,4164,1790 ,0,0,0}, - {4850,4849,4848 ,4164,4163,4162 ,0,0,0}, {4850,4852,4851 ,4164,1790,1790 ,0,0,0}, - {4853,4854,4855 ,4165,4166,4167 ,0,0,0}, {4856,4857,4858 ,4168,4169,4170 ,0,0,0}, - {4857,4853,4855 ,4169,4165,4167 ,0,0,0}, {4859,4856,4858 ,4171,4168,4170 ,0,0,0}, - {4857,4856,4853 ,4169,4168,4165 ,0,0,0}, {4859,4858,4860 ,4171,4170,4172 ,0,0,0}, - {4860,4861,4862 ,4172,4173,4174 ,0,0,0}, {4863,4862,4861 ,4175,4174,4173 ,0,0,0}, - {4864,4865,4866 ,4176,4177,4178 ,0,0,0}, {4861,4867,4863 ,4173,4179,4175 ,0,0,0}, - {4866,4868,4869 ,4178,4180,4181 ,0,0,0}, {4868,4867,4869 ,4180,4179,4181 ,0,0,0}, - {4863,4867,4868 ,4175,4179,4180 ,0,0,0}, {4866,4869,4864 ,4178,4181,4176 ,0,0,0}, - {4865,4864,4870 ,4177,4176,4182 ,0,0,0}, {4865,4870,4871 ,4177,4182,4183 ,0,0,0}, - {4872,4871,4870 ,4184,4183,4182 ,0,0,0}, {4873,4874,4875 ,4185,1711,4186 ,0,0,0}, - {4875,4871,4872 ,4186,4183,4184 ,0,0,0}, {4873,4875,4872 ,4185,4186,4184 ,0,0,0}, - {4873,4876,4874 ,4185,1711,1711 ,0,0,0}, {4859,4860,4862 ,4171,4172,4174 ,0,0,0}, - {4855,4854,4877 ,4167,4166,4187 ,0,0,0}, {4878,4877,4879 ,4188,4187,4189 ,0,0,0}, - {4854,4879,4877 ,4166,4189,4187 ,0,0,0}, {4880,4881,4878 ,4190,4191,4188 ,0,0,0}, - {4878,4879,4880 ,4188,4189,4190 ,0,0,0}, {4881,4882,4883 ,4191,4192,4193 ,0,0,0}, - {4882,4881,4880 ,4192,4191,4190 ,0,0,0}, {4884,4883,4885 ,4194,4193,4195 ,0,0,0}, - {4882,4885,4883 ,4192,4195,4193 ,0,0,0}, {4886,4887,4884 ,4196,4197,4194 ,0,0,0}, - {4884,4885,4886 ,4194,4195,4196 ,0,0,0}, {4887,4888,4889 ,4197,4198,4199 ,0,0,0}, - {4888,4887,4886 ,4198,4197,4196 ,0,0,0}, {4890,4889,4891 ,4200,4199,4201 ,0,0,0}, - {4888,4891,4889 ,4198,4201,4199 ,0,0,0}, {4892,4893,4890 ,4202,4203,4200 ,0,0,0}, - {4890,4891,4892 ,4200,4201,4202 ,0,0,0}, {4893,4894,4895 ,4203,4204,1790 ,0,0,0}, - {4894,4893,4892 ,4204,4203,4202 ,0,0,0}, {4894,4896,4895 ,4204,1790,1790 ,0,0,0}, - {4897,4898,4899 ,4205,4206,4207 ,0,0,0}, {4897,4900,4901 ,4205,4208,4209 ,0,0,0}, - {4900,4902,4901 ,4208,4210,4209 ,0,0,0}, {4899,4900,4897 ,4207,4208,4205 ,0,0,0}, - {4903,4904,4905 ,4211,4212,4213 ,0,0,0}, {4902,4903,4905 ,4210,4211,4213 ,0,0,0}, - {4904,4906,4907 ,4212,4214,4215 ,0,0,0}, {4906,4904,4903 ,4214,4212,4211 ,0,0,0}, - {4907,4906,4908 ,4215,4214,4216 ,0,0,0}, {4909,4907,4908 ,4217,4215,4216 ,0,0,0}, - {4909,4910,4911 ,4217,4218,4219 ,0,0,0}, {4909,4908,4910 ,4217,4216,4218 ,0,0,0}, - {4905,4901,4902 ,4213,4209,4210 ,0,0,0}, {4912,4913,4914 ,4220,1359,1359 ,0,0,0}, - {4912,4914,4911 ,4220,1359,4219 ,0,0,0}, {4910,4912,4911 ,4218,4220,4219 ,0,0,0}, - {4899,4898,4915 ,4207,4206,4221 ,0,0,0}, {4916,4915,4917 ,4222,4221,4223 ,0,0,0}, - {4898,4917,4915 ,4206,4223,4221 ,0,0,0}, {4918,4919,4916 ,4224,4225,4222 ,0,0,0}, - {4916,4917,4918 ,4222,4223,4224 ,0,0,0}, {4919,4920,4921 ,4225,4226,4227 ,0,0,0}, - {4920,4919,4918 ,4226,4225,4224 ,0,0,0}, {4922,4921,4923 ,4228,4227,4229 ,0,0,0}, - {4920,4923,4921 ,4226,4229,4227 ,0,0,0}, {4924,4925,4922 ,4230,4231,4228 ,0,0,0}, - {4922,4923,4924 ,4228,4229,4230 ,0,0,0}, {4925,4926,4927 ,4231,4232,1435 ,0,0,0}, - {4926,4925,4924 ,4232,4231,4230 ,0,0,0}, {4926,4928,4927 ,4232,1435,1435 ,0,0,0}, - {4929,4930,4931 ,4233,4234,4235 ,0,0,0}, {4932,4933,4934 ,4236,4237,4238 ,0,0,0}, - {4933,4929,4931 ,4237,4233,4235 ,0,0,0}, {4935,4932,4934 ,4239,4236,4238 ,0,0,0}, - {4933,4932,4929 ,4237,4236,4233 ,0,0,0}, {4935,4934,4936 ,4239,4238,4240 ,0,0,0}, - {4936,4937,4938 ,4240,4241,4242 ,0,0,0}, {4939,4938,4937 ,4243,4242,4241 ,0,0,0}, - {4940,4941,4942 ,4244,4245,4246 ,0,0,0}, {4937,4943,4939 ,4241,4247,4243 ,0,0,0}, - {4942,4944,4945 ,4246,4248,4249 ,0,0,0}, {4944,4943,4945 ,4248,4247,4249 ,0,0,0}, - {4939,4943,4944 ,4243,4247,4248 ,0,0,0}, {4942,4945,4940 ,4246,4249,4244 ,0,0,0}, - {4941,4940,4946 ,4245,4244,4250 ,0,0,0}, {4941,4946,4947 ,4245,4250,4251 ,0,0,0}, - {4948,4947,4946 ,4252,4251,4250 ,0,0,0}, {4949,4950,4951 ,4253,1359,4254 ,0,0,0}, - {4951,4947,4948 ,4254,4251,4252 ,0,0,0}, {4949,4951,4948 ,4253,4254,4252 ,0,0,0}, - {4949,4952,4950 ,4253,1359,1359 ,0,0,0}, {4935,4936,4938 ,4239,4240,4242 ,0,0,0}, - {4931,4930,4953 ,4235,4234,4255 ,0,0,0}, {4954,4953,4955 ,4256,4255,4257 ,0,0,0}, - {4930,4955,4953 ,4234,4257,4255 ,0,0,0}, {4956,4957,4954 ,4258,4259,4256 ,0,0,0}, - {4954,4955,4956 ,4256,4257,4258 ,0,0,0}, {4957,4958,4959 ,4259,4260,4261 ,0,0,0}, - {4958,4957,4956 ,4260,4259,4258 ,0,0,0}, {4960,4959,4961 ,4262,4261,4263 ,0,0,0}, - {4958,4961,4959 ,4260,4263,4261 ,0,0,0}, {4962,4963,4960 ,4264,4265,4262 ,0,0,0}, - {4960,4961,4962 ,4262,4263,4264 ,0,0,0}, {4963,4964,4965 ,4265,4266,4267 ,0,0,0}, - {4964,4963,4962 ,4266,4265,4264 ,0,0,0}, {4966,4965,4967 ,4268,4267,4269 ,0,0,0}, - {4964,4967,4965 ,4266,4269,4267 ,0,0,0}, {4968,4969,4966 ,4270,4271,4268 ,0,0,0}, - {4966,4967,4968 ,4268,4269,4270 ,0,0,0}, {4969,4970,4971 ,4271,4272,1435 ,0,0,0}, - {4970,4969,4968 ,4272,4271,4270 ,0,0,0}, {4970,4972,4971 ,4272,1435,1435 ,0,0,0}, - {4973,4974,4975 ,4273,4274,4275 ,0,0,0}, {4973,4976,4977 ,4273,4276,4277 ,0,0,0}, - {4976,4978,4977 ,4276,4278,4277 ,0,0,0}, {4975,4976,4973 ,4275,4276,4273 ,0,0,0}, - {4979,4980,4981 ,4279,4280,4281 ,0,0,0}, {4978,4979,4981 ,4278,4279,4281 ,0,0,0}, - {4980,4982,4983 ,4280,4282,4283 ,0,0,0}, {4982,4980,4979 ,4282,4280,4279 ,0,0,0}, - {4983,4982,4984 ,4283,4282,4284 ,0,0,0}, {4985,4983,4984 ,4285,4283,4284 ,0,0,0}, - {4985,4986,4987 ,4285,4286,4287 ,0,0,0}, {4985,4984,4986 ,4285,4284,4286 ,0,0,0}, - {4981,4977,4978 ,4281,4277,4278 ,0,0,0}, {4988,4989,4990 ,4288,126,4289 ,0,0,0}, - {4988,4990,4987 ,4288,4289,4287 ,0,0,0}, {4986,4988,4987 ,4286,4288,4287 ,0,0,0}, - {4975,4974,4991 ,4275,4274,4290 ,0,0,0}, {4992,4991,4993 ,4291,4290,4292 ,0,0,0}, - {4974,4993,4991 ,4274,4292,4290 ,0,0,0}, {4994,4995,4992 ,4293,4294,4291 ,0,0,0}, - {4992,4993,4994 ,4291,4292,4293 ,0,0,0}, {4995,4996,4997 ,4294,4295,4296 ,0,0,0}, - {4996,4995,4994 ,4295,4294,4293 ,0,0,0}, {4998,4997,4999 ,4297,4296,4298 ,0,0,0}, - {4996,4999,4997 ,4295,4298,4296 ,0,0,0}, {5000,5001,4998 ,4299,4300,4297 ,0,0,0}, - {4998,4999,5000 ,4297,4298,4299 ,0,0,0}, {5001,5002,5003 ,4300,4301,4302 ,0,0,0}, - {5002,5001,5000 ,4301,4300,4299 ,0,0,0}, {5002,5004,5003 ,4301,4303,4302 ,0,0,0}, - {5005,5006,5007 ,4304,4305,4306 ,0,0,0}, {5008,5009,5010 ,4307,4308,4309 ,0,0,0}, - {5009,5005,5007 ,4308,4304,4306 ,0,0,0}, {5011,5008,5010 ,4310,4307,4309 ,0,0,0}, - {5009,5008,5005 ,4308,4307,4304 ,0,0,0}, {5011,5010,5012 ,4310,4309,4311 ,0,0,0}, - {5012,5013,5014 ,4311,4312,4313 ,0,0,0}, {5015,5014,5013 ,4314,4313,4312 ,0,0,0}, - {5016,5017,5018 ,4315,4316,4317 ,0,0,0}, {5013,5019,5015 ,4312,4318,4314 ,0,0,0}, - {5018,5020,5021 ,4317,4319,4320 ,0,0,0}, {5020,5019,5021 ,4319,4318,4320 ,0,0,0}, - {5015,5019,5020 ,4314,4318,4319 ,0,0,0}, {5018,5021,5016 ,4317,4320,4315 ,0,0,0}, - {5017,5016,5022 ,4316,4315,4321 ,0,0,0}, {5017,5022,5023 ,4316,4321,4322 ,0,0,0}, - {5024,5023,5022 ,4323,4322,4321 ,0,0,0}, {5025,5026,5027 ,4324,126,4325 ,0,0,0}, - {5027,5023,5024 ,4325,4322,4323 ,0,0,0}, {5025,5027,5024 ,4324,4325,4323 ,0,0,0}, - {5025,5028,5026 ,4324,4326,126 ,0,0,0}, {5011,5012,5014 ,4310,4311,4313 ,0,0,0}, - {5007,5006,5029 ,4306,4305,4327 ,0,0,0}, {5030,5029,5031 ,4328,4327,4329 ,0,0,0}, - {5006,5031,5029 ,4305,4329,4327 ,0,0,0}, {5032,5033,5030 ,4330,4331,4328 ,0,0,0}, - {5030,5031,5032 ,4328,4329,4330 ,0,0,0}, {5033,5034,5035 ,4331,4332,4333 ,0,0,0}, - {5034,5033,5032 ,4332,4331,4330 ,0,0,0}, {5036,5035,5037 ,4334,4333,4335 ,0,0,0}, - {5034,5037,5035 ,4332,4335,4333 ,0,0,0}, {5038,5039,5036 ,4336,4337,4334 ,0,0,0}, - {5036,5037,5038 ,4334,4335,4336 ,0,0,0}, {5039,5040,5041 ,4337,4338,4339 ,0,0,0}, - {5040,5039,5038 ,4338,4337,4336 ,0,0,0}, {5042,5041,5043 ,4340,4339,4341 ,0,0,0}, - {5040,5043,5041 ,4338,4341,4339 ,0,0,0}, {5044,5045,5042 ,4342,4343,4340 ,0,0,0}, - {5042,5043,5044 ,4340,4341,4342 ,0,0,0}, {5045,5046,5047 ,4343,4344,4345 ,0,0,0}, - {5046,5045,5044 ,4344,4343,4342 ,0,0,0}, {5046,5048,5047 ,4344,4346,4345 ,0,0,0}, - {5049,5050,5051 ,4347,4348,4349 ,0,0,0}, {5049,5052,5053 ,4347,4350,4351 ,0,0,0}, - {5052,5054,5053 ,4350,4352,4351 ,0,0,0}, {5051,5052,5049 ,4349,4350,4347 ,0,0,0}, - {5055,5056,5057 ,4353,4354,4355 ,0,0,0}, {5054,5055,5057 ,4352,4353,4355 ,0,0,0}, - {5056,5058,5059 ,4354,4356,4357 ,0,0,0}, {5058,5056,5055 ,4356,4354,4353 ,0,0,0}, - {5059,5058,5060 ,4357,4356,4358 ,0,0,0}, {5061,5059,5060 ,4359,4357,4358 ,0,0,0}, - {5061,5062,5063 ,4359,4360,4361 ,0,0,0}, {5061,5060,5062 ,4359,4358,4360 ,0,0,0}, - {5057,5053,5054 ,4355,4351,4352 ,0,0,0}, {5064,5065,5066 ,4362,1790,1790 ,0,0,0}, - {5064,5066,5063 ,4362,1790,4361 ,0,0,0}, {5062,5064,5063 ,4360,4362,4361 ,0,0,0}, - {5051,5050,5067 ,4349,4348,4363 ,0,0,0}, {5068,5067,5069 ,4364,4363,4365 ,0,0,0}, - {5050,5069,5067 ,4348,4365,4363 ,0,0,0}, {5070,5071,5068 ,4366,4367,4364 ,0,0,0}, - {5068,5069,5070 ,4364,4365,4366 ,0,0,0}, {5071,5072,5073 ,4367,4368,4369 ,0,0,0}, - {5072,5071,5070 ,4368,4367,4366 ,0,0,0}, {5074,5073,5075 ,4370,4369,4371 ,0,0,0}, - {5072,5075,5073 ,4368,4371,4369 ,0,0,0}, {5076,5077,5074 ,4372,4373,4370 ,0,0,0}, - {5074,5075,5076 ,4370,4371,4372 ,0,0,0}, {5077,5078,5079 ,4373,4374,1711 ,0,0,0}, - {5078,5077,5076 ,4374,4373,4372 ,0,0,0}, {5078,5080,5079 ,4374,1711,1711 ,0,0,0}, - {5081,5082,5083 ,4375,4376,4377 ,0,0,0}, {5084,5085,5086 ,4378,4379,4380 ,0,0,0}, - {5085,5081,5083 ,4379,4375,4377 ,0,0,0}, {5087,5084,5086 ,4381,4378,4380 ,0,0,0}, - {5085,5084,5081 ,4379,4378,4375 ,0,0,0}, {5087,5086,5088 ,4381,4380,4382 ,0,0,0}, - {5088,5089,5090 ,4382,4383,4384 ,0,0,0}, {5091,5090,5089 ,4385,4384,4383 ,0,0,0}, - {5092,5093,5094 ,4386,4387,4388 ,0,0,0}, {5089,5095,5091 ,4383,4389,4385 ,0,0,0}, - {5094,5096,5097 ,4388,4390,4391 ,0,0,0}, {5096,5095,5097 ,4390,4389,4391 ,0,0,0}, - {5091,5095,5096 ,4385,4389,4390 ,0,0,0}, {5094,5097,5092 ,4388,4391,4386 ,0,0,0}, - {5093,5092,5098 ,4387,4386,4392 ,0,0,0}, {5093,5098,5099 ,4387,4392,4393 ,0,0,0}, - {5100,5099,5098 ,4394,4393,4392 ,0,0,0}, {5101,5102,5103 ,4395,1790,4396 ,0,0,0}, - {5103,5099,5100 ,4396,4393,4394 ,0,0,0}, {5101,5103,5100 ,4395,4396,4394 ,0,0,0}, - {5101,5104,5102 ,4395,1790,1790 ,0,0,0}, {5087,5088,5090 ,4381,4382,4384 ,0,0,0}, - {5083,5082,5105 ,4377,4376,4397 ,0,0,0}, {5106,5105,5107 ,4398,4397,4399 ,0,0,0}, - {5082,5107,5105 ,4376,4399,4397 ,0,0,0}, {5108,5109,5106 ,4400,4401,4398 ,0,0,0}, - {5106,5107,5108 ,4398,4399,4400 ,0,0,0}, {5109,5110,5111 ,4401,4402,4403 ,0,0,0}, - {5110,5109,5108 ,4402,4401,4400 ,0,0,0}, {5112,5111,5113 ,4404,4403,4405 ,0,0,0}, - {5110,5113,5111 ,4402,4405,4403 ,0,0,0}, {5114,5115,5112 ,4406,4407,4404 ,0,0,0}, - {5112,5113,5114 ,4404,4405,4406 ,0,0,0}, {5115,5116,5117 ,4407,4408,4409 ,0,0,0}, - {5116,5115,5114 ,4408,4407,4406 ,0,0,0}, {5118,5117,5119 ,4410,4409,4411 ,0,0,0}, - {5116,5119,5117 ,4408,4411,4409 ,0,0,0}, {5120,5121,5118 ,4412,4413,4410 ,0,0,0}, - {5118,5119,5120 ,4410,4411,4412 ,0,0,0}, {5121,5122,5123 ,4413,4414,1711 ,0,0,0}, - {5122,5121,5120 ,4414,4413,4412 ,0,0,0}, {5122,5124,5123 ,4414,1711,1711 ,0,0,0}, - {5125,5126,5127 ,4415,4416,4417 ,0,0,0}, {5125,5128,5129 ,4415,4418,4419 ,0,0,0}, - {5128,5130,5129 ,4418,4420,4419 ,0,0,0}, {5127,5128,5125 ,4417,4418,4415 ,0,0,0}, - {5131,5132,5133 ,4421,4422,4423 ,0,0,0}, {5130,5131,5133 ,4420,4421,4423 ,0,0,0}, - {5132,5134,5135 ,4422,4424,4425 ,0,0,0}, {5134,5132,5131 ,4424,4422,4421 ,0,0,0}, - {5135,5134,5136 ,4425,4424,4426 ,0,0,0}, {5137,5135,5136 ,4427,4425,4426 ,0,0,0}, - {5137,5138,5139 ,4427,4428,4429 ,0,0,0}, {5137,5136,5138 ,4427,4426,4428 ,0,0,0}, - {5133,5129,5130 ,4423,4419,4420 ,0,0,0}, {5140,5141,5142 ,4430,1435,1435 ,0,0,0}, - {5140,5142,5139 ,4430,1435,4429 ,0,0,0}, {5138,5140,5139 ,4428,4430,4429 ,0,0,0}, - {5127,5126,5143 ,4417,4416,4431 ,0,0,0}, {5144,5143,5145 ,4432,4431,4433 ,0,0,0}, - {5126,5145,5143 ,4416,4433,4431 ,0,0,0}, {5146,5147,5144 ,4434,4435,4432 ,0,0,0}, - {5144,5145,5146 ,4432,4433,4434 ,0,0,0}, {5147,5148,5149 ,4435,4436,4437 ,0,0,0}, - {5148,5147,5146 ,4436,4435,4434 ,0,0,0}, {5150,5149,5151 ,4438,4437,4439 ,0,0,0}, - {5148,5151,5149 ,4436,4439,4437 ,0,0,0}, {5152,5153,5150 ,4440,4441,4438 ,0,0,0}, - {5150,5151,5152 ,4438,4439,4440 ,0,0,0}, {5153,5154,5155 ,4441,4442,1359 ,0,0,0}, - {5154,5153,5152 ,4442,4441,4440 ,0,0,0}, {5154,5156,5155 ,4442,1359,1359 ,0,0,0}, - {5157,5158,5159 ,4443,4444,4445 ,0,0,0}, {5160,5161,5162 ,4446,4447,4448 ,0,0,0}, - {5161,5157,5159 ,4447,4443,4445 ,0,0,0}, {5163,5160,5162 ,4449,4446,4448 ,0,0,0}, - {5161,5160,5157 ,4447,4446,4443 ,0,0,0}, {5163,5162,5164 ,4449,4448,4450 ,0,0,0}, - {5164,5165,5166 ,4450,4451,4452 ,0,0,0}, {5167,5166,5165 ,4453,4452,4451 ,0,0,0}, - {5168,5169,5170 ,4454,4455,4456 ,0,0,0}, {5165,5171,5167 ,4451,4457,4453 ,0,0,0}, - {5170,5172,5173 ,4456,4458,4459 ,0,0,0}, {5172,5171,5173 ,4458,4457,4459 ,0,0,0}, - {5167,5171,5172 ,4453,4457,4458 ,0,0,0}, {5170,5173,5168 ,4456,4459,4454 ,0,0,0}, - {5169,5168,5174 ,4455,4454,4460 ,0,0,0}, {5169,5174,5175 ,4455,4460,4461 ,0,0,0}, - {5176,5175,5174 ,4462,4461,4460 ,0,0,0}, {5177,5178,5179 ,4463,1435,4464 ,0,0,0}, - {5179,5175,5176 ,4464,4461,4462 ,0,0,0}, {5177,5179,5176 ,4463,4464,4462 ,0,0,0}, - {5177,5180,5178 ,4463,1435,1435 ,0,0,0}, {5163,5164,5166 ,4449,4450,4452 ,0,0,0}, - {5159,5158,5181 ,4445,4444,4465 ,0,0,0}, {5182,5181,5183 ,4466,4465,4467 ,0,0,0}, - {5158,5183,5181 ,4444,4467,4465 ,0,0,0}, {5184,5185,5182 ,4468,4469,4466 ,0,0,0}, - {5182,5183,5184 ,4466,4467,4468 ,0,0,0}, {5185,5186,5187 ,4469,4470,4471 ,0,0,0}, - {5186,5185,5184 ,4470,4469,4468 ,0,0,0}, {5188,5187,5189 ,4472,4471,4473 ,0,0,0}, - {5186,5189,5187 ,4470,4473,4471 ,0,0,0}, {5190,5191,5188 ,4474,4475,4472 ,0,0,0}, - {5188,5189,5190 ,4472,4473,4474 ,0,0,0}, {5191,5192,5193 ,4475,4476,4477 ,0,0,0}, - {5192,5191,5190 ,4476,4475,4474 ,0,0,0}, {5194,5193,5195 ,4478,4477,4479 ,0,0,0}, - {5192,5195,5193 ,4476,4479,4477 ,0,0,0}, {5196,5197,5194 ,4480,4481,4478 ,0,0,0}, - {5194,5195,5196 ,4478,4479,4480 ,0,0,0}, {5197,5198,5199 ,4481,4482,1359 ,0,0,0}, - {5198,5197,5196 ,4482,4481,4480 ,0,0,0}, {5198,5200,5199 ,4482,1359,1359 ,0,0,0}, - {5201,5202,5203 ,4483,4484,4485 ,0,0,0}, {5201,5204,5205 ,4483,4486,4487 ,0,0,0}, - {5204,5206,5205 ,4486,4488,4487 ,0,0,0}, {5203,5204,5201 ,4485,4486,4483 ,0,0,0}, - {5207,5208,5209 ,4489,4490,4491 ,0,0,0}, {5206,5207,5209 ,4488,4489,4491 ,0,0,0}, - {5208,5210,5211 ,4490,4492,4493 ,0,0,0}, {5210,5208,5207 ,4492,4490,4489 ,0,0,0}, - {5211,5210,5212 ,4493,4492,4494 ,0,0,0}, {5213,5211,5212 ,4495,4493,4494 ,0,0,0}, - {5213,5214,5215 ,4495,4496,4497 ,0,0,0}, {5213,5212,5214 ,4495,4494,4496 ,0,0,0}, - {5209,5205,5206 ,4491,4487,4488 ,0,0,0}, {5216,5217,5218 ,4498,4499,82 ,0,0,0}, - {5216,5218,5215 ,4498,82,4497 ,0,0,0}, {5214,5216,5215 ,4496,4498,4497 ,0,0,0}, - {5203,5202,5219 ,4485,4484,4500 ,0,0,0}, {5220,5219,5221 ,4501,4500,4502 ,0,0,0}, - {5202,5221,5219 ,4484,4502,4500 ,0,0,0}, {5222,5223,5220 ,4503,4504,4501 ,0,0,0}, - {5220,5221,5222 ,4501,4502,4503 ,0,0,0}, {5223,5224,5225 ,4504,4505,4506 ,0,0,0}, - {5224,5223,5222 ,4505,4504,4503 ,0,0,0}, {5226,5225,5227 ,4507,4506,4508 ,0,0,0}, - {5224,5227,5225 ,4505,4508,4506 ,0,0,0}, {5228,5229,5226 ,4509,4510,4507 ,0,0,0}, - {5226,5227,5228 ,4507,4508,4509 ,0,0,0}, {5229,5230,5231 ,4510,4511,4512 ,0,0,0}, - {5230,5229,5228 ,4511,4510,4509 ,0,0,0}, {5230,5232,5231 ,4511,4513,4512 ,0,0,0}, - {5233,5234,5235 ,4514,4515,4516 ,0,0,0}, {5236,5237,5238 ,4517,4518,4519 ,0,0,0}, - {5237,5233,5235 ,4518,4514,4516 ,0,0,0}, {5239,5236,5238 ,4520,4517,4519 ,0,0,0}, - {5237,5236,5233 ,4518,4517,4514 ,0,0,0}, {5239,5238,5240 ,4520,4519,4521 ,0,0,0}, - {5240,5241,5242 ,4521,4522,4523 ,0,0,0}, {5243,5242,5241 ,4524,4523,4522 ,0,0,0}, - {5244,5245,5246 ,4525,4526,4527 ,0,0,0}, {5241,5247,5243 ,4522,4528,4524 ,0,0,0}, - {5246,5248,5249 ,4527,4529,4530 ,0,0,0}, {5248,5247,5249 ,4529,4528,4530 ,0,0,0}, - {5243,5247,5248 ,4524,4528,4529 ,0,0,0}, {5246,5249,5244 ,4527,4530,4525 ,0,0,0}, - {5245,5244,5250 ,4526,4525,4531 ,0,0,0}, {5245,5250,5251 ,4526,4531,4532 ,0,0,0}, - {5252,5251,5250 ,4533,4532,4531 ,0,0,0}, {5253,5254,5255 ,4534,4535,4536 ,0,0,0}, - {5255,5251,5252 ,4536,4532,4533 ,0,0,0}, {5253,5255,5252 ,4534,4536,4533 ,0,0,0}, - {5253,5256,5254 ,4534,4537,4535 ,0,0,0}, {5239,5240,5242 ,4520,4521,4523 ,0,0,0}, - {5235,5234,5257 ,4516,4515,4538 ,0,0,0}, {5258,5257,5259 ,4539,4538,4540 ,0,0,0}, - {5234,5259,5257 ,4515,4540,4538 ,0,0,0}, {5260,5261,5258 ,4541,4542,4539 ,0,0,0}, - {5258,5259,5260 ,4539,4540,4541 ,0,0,0}, {5261,5262,5263 ,4542,4543,4544 ,0,0,0}, - {5262,5261,5260 ,4543,4542,4541 ,0,0,0}, {5264,5263,5265 ,4545,4544,4546 ,0,0,0}, - {5262,5265,5263 ,4543,4546,4544 ,0,0,0}, {5266,5267,5264 ,4547,4548,4545 ,0,0,0}, - {5264,5265,5266 ,4545,4546,4547 ,0,0,0}, {5267,5268,5269 ,4548,4549,4550 ,0,0,0}, - {5268,5267,5266 ,4549,4548,4547 ,0,0,0}, {5270,5269,5271 ,4551,4550,4552 ,0,0,0}, - {5268,5271,5269 ,4549,4552,4550 ,0,0,0}, {5272,5273,5270 ,4553,4554,4551 ,0,0,0}, - {5270,5271,5272 ,4551,4552,4553 ,0,0,0}, {5273,5274,5275 ,4554,4555,4556 ,0,0,0}, - {5274,5273,5272 ,4555,4554,4553 ,0,0,0}, {5274,5276,5275 ,4555,126,4556 ,0,0,0}, - {5277,5278,5279 ,4557,4558,4559 ,0,0,0}, {5280,5281,5279 ,4560,4561,4559 ,0,0,0}, - {5277,5279,5281 ,4557,4559,4561 ,0,0,0}, {5282,5280,5283 ,4562,4560,4563 ,0,0,0}, - {5282,5281,5280 ,4562,4561,4560 ,0,0,0}, {5284,5283,5285 ,4564,4563,4565 ,0,0,0}, - {5280,5285,5283 ,4560,4565,4563 ,0,0,0}, {5286,5287,5284 ,4081,4566,4564 ,0,0,0}, - {5284,5285,5286 ,4564,4565,4081 ,0,0,0}, {5287,5288,5289 ,4566,4567,4568 ,0,0,0}, - {5288,5287,5286 ,4567,4566,4081 ,0,0,0}, {5290,5289,5291 ,4569,4568,4570 ,0,0,0}, - {5288,5291,5289 ,4567,4570,4568 ,0,0,0}, {5292,5293,5290 ,4571,4572,4569 ,0,0,0}, - {5290,5291,5292 ,4569,4570,4571 ,0,0,0}, {5294,5295,5293 ,4573,763,4572 ,0,0,0}, - {5294,5293,5292 ,4573,4572,4571 ,0,0,0}, {5295,5296,5293 ,763,763,4572 ,0,0,0}, - {5297,5278,5277 ,4574,4558,4557 ,0,0,0}, {5297,5298,5299 ,4574,4575,4576 ,0,0,0}, - {5299,5278,5297 ,4576,4558,4574 ,0,0,0}, {5300,5301,5298 ,4577,4578,4575 ,0,0,0}, - {5298,5301,5299 ,4575,4578,4576 ,0,0,0}, {5302,5303,5300 ,4579,4580,4577 ,0,0,0}, - {5300,5298,5302 ,4577,4575,4579 ,0,0,0}, {5303,5304,5305 ,4580,4065,4581 ,0,0,0}, - {5304,5303,5302 ,4065,4580,4579 ,0,0,0}, {5306,5305,5307 ,4582,4581,4583 ,0,0,0}, - {5304,5307,5305 ,4065,4583,4581 ,0,0,0}, {5308,5309,5306 ,4584,4585,4582 ,0,0,0}, - {5306,5307,5308 ,4582,4583,4584 ,0,0,0}, {5309,5310,5311 ,4585,4586,4587 ,0,0,0}, - {5310,5309,5308 ,4586,4585,4584 ,0,0,0}, {5311,5312,5313 ,4587,4588,54 ,0,0,0}, - {5310,5312,5311 ,4586,4588,4587 ,0,0,0}, {5311,5313,5314 ,4587,54,4589 ,0,0,0}, - {5315,5316,5317 ,4590,4591,4557 ,0,0,0}, {5318,5316,5319 ,4592,4591,4593 ,0,0,0}, - {5316,5318,5317 ,4591,4592,4557 ,0,0,0}, {5320,5321,5319 ,4594,4595,4593 ,0,0,0}, - {5318,5319,5321 ,4592,4593,4595 ,0,0,0}, {5320,5322,5323 ,4594,4596,4597 ,0,0,0}, - {5323,5321,5320 ,4597,4595,4594 ,0,0,0}, {5324,5322,5325 ,4598,4596,4599 ,0,0,0}, - {5322,5324,5323 ,4596,4598,4597 ,0,0,0}, {5326,5327,5325 ,4600,4601,4599 ,0,0,0}, - {5324,5325,5327 ,4598,4599,4601 ,0,0,0}, {5326,5328,5329 ,4600,4602,4603 ,0,0,0}, - {5329,5327,5326 ,4603,4601,4600 ,0,0,0}, {5330,5328,5331 ,4604,4602,4605 ,0,0,0}, - {5328,5330,5329 ,4602,4604,4603 ,0,0,0}, {5332,5333,5331 ,4606,4607,4605 ,0,0,0}, - {5330,5331,5333 ,4604,4605,4607 ,0,0,0}, {5332,5334,5335 ,4606,4608,4609 ,0,0,0}, - {5335,5333,5332 ,4609,4607,4606 ,0,0,0}, {5336,5334,5337 ,4610,4608,4611 ,0,0,0}, - {5334,5336,5335 ,4608,4610,4609 ,0,0,0}, {5338,5339,5337 ,4612,4613,4611 ,0,0,0}, - {5336,5337,5339 ,4610,4611,4613 ,0,0,0}, {5338,5340,5341 ,4612,4614,4615 ,0,0,0}, - {5341,5339,5338 ,4615,4613,4612 ,0,0,0}, {5342,5340,5343 ,4616,4614,4617 ,0,0,0}, - {5340,5342,5341 ,4614,4616,4615 ,0,0,0}, {5344,5345,5343 ,4618,4619,4617 ,0,0,0}, - {5342,5343,5345 ,4616,4617,4619 ,0,0,0}, {5344,5346,5347 ,4618,4620,4621 ,0,0,0}, - {5347,5345,5344 ,4621,4619,4618 ,0,0,0}, {5346,5348,5347 ,4620,4620,4621 ,0,0,0}, - {5349,5315,5317 ,4622,4590,4557 ,0,0,0}, {5350,5351,5349 ,4623,4624,4622 ,0,0,0}, - {5315,5349,5351 ,4590,4622,4624 ,0,0,0}, {5350,5352,5353 ,4623,4625,4626 ,0,0,0}, - {5353,5351,5350 ,4626,4624,4623 ,0,0,0}, {5354,5352,5355 ,4627,4625,4628 ,0,0,0}, - {5352,5354,5353 ,4625,4627,4626 ,0,0,0}, {5356,5357,5355 ,4629,4630,4628 ,0,0,0}, - {5354,5355,5357 ,4627,4628,4630 ,0,0,0}, {5356,5358,5359 ,4629,4631,4632 ,0,0,0}, - {5359,5357,5356 ,4632,4630,4629 ,0,0,0}, {5360,5358,5361 ,4633,4631,4634 ,0,0,0}, - {5358,5360,5359 ,4631,4633,4632 ,0,0,0}, {5362,5363,5361 ,4635,4636,4634 ,0,0,0}, - {5360,5361,5363 ,4633,4634,4636 ,0,0,0}, {5362,5364,5365 ,4635,4637,4638 ,0,0,0}, - {5365,5363,5362 ,4638,4636,4635 ,0,0,0}, {5366,5364,5367 ,4639,4637,4640 ,0,0,0}, - {5364,5366,5365 ,4637,4639,4638 ,0,0,0}, {5368,5369,5367 ,4641,4642,4640 ,0,0,0}, - {5366,5367,5369 ,4639,4640,4642 ,0,0,0}, {5368,5370,5371 ,4641,4643,4644 ,0,0,0}, - {5371,5369,5368 ,4644,4642,4641 ,0,0,0}, {5372,5370,5373 ,4645,4643,4646 ,0,0,0}, - {5370,5372,5371 ,4643,4645,4644 ,0,0,0}, {5374,5375,5373 ,4647,4648,4646 ,0,0,0}, - {5372,5373,5375 ,4645,4646,4648 ,0,0,0}, {5374,5376,5377 ,4647,4649,4650 ,0,0,0}, - {5377,5375,5374 ,4650,4648,4647 ,0,0,0}, {5378,5376,5379 ,4651,4649,82 ,0,0,0}, - {5376,5378,5377 ,4649,4651,4650 ,0,0,0}, {5378,5379,5380 ,4651,82,4652 ,0,0,0}, - {5381,5382,5383 ,4653,4654,4655 ,0,0,0}, {5384,5385,5386 ,4656,4657,4658 ,0,0,0}, - {5383,5386,5385 ,4655,4658,4657 ,0,0,0}, {5387,5388,5389 ,4659,4660,4661 ,0,0,0}, - {5390,5391,5384 ,4662,4663,4656 ,0,0,0}, {5387,5391,5390 ,4659,4663,4662 ,0,0,0}, - {5390,5388,5387 ,4662,4660,4659 ,0,0,0}, {5391,5385,5384 ,4663,4657,4656 ,0,0,0}, - {5392,5393,5394 ,4664,4665,4666 ,0,0,0}, {5393,5395,5394 ,4665,4667,4666 ,0,0,0}, - {5396,5397,5398 ,4668,4669,4670 ,0,0,0}, {5396,5398,5395 ,4668,4670,4667 ,0,0,0}, - {5393,5396,5395 ,4665,4668,4667 ,0,0,0}, {5388,5392,5389 ,4660,4664,4661 ,0,0,0}, - {5392,5394,5389 ,4664,4666,4661 ,0,0,0}, {5399,5400,5401 ,4671,4672,4673 ,0,0,0}, - {5402,5403,5404 ,4674,4675,4676 ,0,0,0}, {5401,5400,5402 ,4673,4672,4674 ,0,0,0}, - {5405,5406,5407 ,4677,4678,4679 ,0,0,0}, {5401,5402,5404 ,4673,4674,4676 ,0,0,0}, - {5407,5406,5403 ,4679,4678,4675 ,0,0,0}, {5406,5404,5403 ,4678,4676,4675 ,0,0,0}, - {5397,5400,5399 ,4669,4672,4671 ,0,0,0}, {5408,5405,5407 ,4677,4677,4679 ,0,0,0}, - {5398,5397,5399 ,4670,4669,4671 ,0,0,0}, {5382,5386,5383 ,4654,4658,4655 ,0,0,0}, - {5409,5382,5381 ,4680,4654,4653 ,0,0,0}, {5409,5410,5411 ,4680,4681,4682 ,0,0,0}, - {5410,5409,5381 ,4681,4680,4653 ,0,0,0}, {5412,5411,5413 ,4683,4682,4684 ,0,0,0}, - {5410,5413,5411 ,4681,4684,4682 ,0,0,0}, {5414,5415,5412 ,4685,4686,4683 ,0,0,0}, - {5412,5413,5414 ,4683,4684,4685 ,0,0,0}, {5415,5416,5417 ,4686,4687,4688 ,0,0,0}, - {5416,5415,5414 ,4687,4686,4685 ,0,0,0}, {5418,5417,5419 ,4689,4688,4690 ,0,0,0}, - {5416,5419,5417 ,4687,4690,4688 ,0,0,0}, {5420,5421,5418 ,4691,4692,4689 ,0,0,0}, - {5418,5419,5420 ,4689,4690,4691 ,0,0,0}, {5421,5422,5423 ,4692,4693,4694 ,0,0,0}, - {5422,5421,5420 ,4693,4692,4691 ,0,0,0}, {5424,5423,5425 ,4695,4694,4696 ,0,0,0}, - {5422,5425,5423 ,4693,4696,4694 ,0,0,0}, {5426,5427,5424 ,4697,4698,4695 ,0,0,0}, - {5424,5425,5426 ,4695,4696,4697 ,0,0,0}, {5427,5428,5429 ,4698,4699,4700 ,0,0,0}, - {5428,5427,5426 ,4699,4698,4697 ,0,0,0}, {5428,5430,5429 ,4699,4701,4700 ,0,0,0}, - {5431,5432,5433 ,4702,4703,4704 ,0,0,0}, {5434,5435,5436 ,4705,4706,4707 ,0,0,0}, - {5432,5436,5435 ,4703,4707,4706 ,0,0,0}, {5437,5438,5439 ,4708,4709,4710 ,0,0,0}, - {5440,5434,5441 ,4711,4705,4712 ,0,0,0}, {5437,5440,5441 ,4708,4711,4712 ,0,0,0}, - {5440,5437,5439 ,4711,4708,4710 ,0,0,0}, {5441,5434,5436 ,4712,4705,4707 ,0,0,0}, - {5442,5443,5444 ,4713,4714,4715 ,0,0,0}, {5444,5443,5445 ,4715,4714,4716 ,0,0,0}, - {5446,5447,5448 ,4717,4718,4719 ,0,0,0}, {5446,5445,5447 ,4717,4716,4718 ,0,0,0}, - {5444,5445,5446 ,4715,4716,4717 ,0,0,0}, {5439,5438,5442 ,4710,4709,4713 ,0,0,0}, - {5442,5438,5443 ,4713,4709,4714 ,0,0,0}, {5449,5450,5451 ,4720,4721,4722 ,0,0,0}, - {5452,5453,5454 ,4723,4724,4725 ,0,0,0}, {5450,5452,5451 ,4721,4723,4722 ,0,0,0}, - {5455,5456,5457 ,4726,4727,4728 ,0,0,0}, {5450,5453,5452 ,4721,4724,4723 ,0,0,0}, - {5456,5454,5457 ,4727,4725,4728 ,0,0,0}, {5457,5454,5453 ,4728,4725,4724 ,0,0,0}, - {5448,5449,5451 ,4719,4720,4722 ,0,0,0}, {5458,5456,5455 ,4726,4727,4726 ,0,0,0}, - {5447,5449,5448 ,4718,4720,4719 ,0,0,0}, {5433,5432,5435 ,4704,4703,4706 ,0,0,0}, - {5459,5431,5433 ,4729,4702,4704 ,0,0,0}, {5459,5460,5461 ,4729,4730,4731 ,0,0,0}, - {5461,5431,5459 ,4731,4702,4729 ,0,0,0}, {5462,5463,5460 ,4732,4733,4730 ,0,0,0}, - {5461,5460,5463 ,4731,4730,4733 ,0,0,0}, {5464,5462,5465 ,4734,4732,4735 ,0,0,0}, - {5462,5464,5463 ,4732,4734,4733 ,0,0,0}, {5465,5466,5467 ,4735,4736,4737 ,0,0,0}, - {5467,5464,5465 ,4737,4734,4735 ,0,0,0}, {5468,5469,5466 ,4738,4739,4736 ,0,0,0}, - {5467,5466,5469 ,4737,4736,4739 ,0,0,0}, {5470,5468,5471 ,4740,4738,4741 ,0,0,0}, - {5468,5470,5469 ,4738,4740,4739 ,0,0,0}, {5471,5472,5473 ,4741,4742,4743 ,0,0,0}, - {5473,5470,5471 ,4743,4740,4741 ,0,0,0}, {5474,5475,5472 ,4744,4745,4742 ,0,0,0}, - {5473,5472,5475 ,4743,4742,4745 ,0,0,0}, {5476,5474,5477 ,4746,4744,4747 ,0,0,0}, - {5474,5476,5475 ,4744,4746,4745 ,0,0,0}, {5477,5478,5479 ,4747,4748,4749 ,0,0,0}, - {5479,5476,5477 ,4749,4746,4747 ,0,0,0}, {5479,5478,5480 ,4749,4748,4750 ,0,0,0}, - {5481,5482,5483 ,4751,4752,4753 ,0,0,0}, {5484,5485,5486 ,4754,4755,4756 ,0,0,0}, - {5482,5486,5485 ,4752,4756,4755 ,0,0,0}, {5487,5488,5489 ,4757,4758,4759 ,0,0,0}, - {5490,5484,5491 ,4760,4754,4761 ,0,0,0}, {5490,5491,5487 ,4760,4761,4757 ,0,0,0}, - {5487,5489,5490 ,4757,4759,4760 ,0,0,0}, {5484,5486,5491 ,4754,4756,4761 ,0,0,0}, - {5492,5493,5494 ,4762,4763,4764 ,0,0,0}, {5495,5493,5492 ,4765,4763,4762 ,0,0,0}, - {5496,5497,5498 ,4766,4767,4768 ,0,0,0}, {5496,5498,5495 ,4766,4768,4765 ,0,0,0}, - {5495,5498,5493 ,4765,4768,4763 ,0,0,0}, {5488,5494,5489 ,4758,4764,4759 ,0,0,0}, - {5492,5494,5488 ,4762,4764,4758 ,0,0,0}, {5499,5500,5501 ,4769,4770,4771 ,0,0,0}, - {5502,5503,5504 ,4772,4773,4774 ,0,0,0}, {5501,5500,5504 ,4771,4770,4774 ,0,0,0}, - {5505,5506,5507 ,4775,4776,4777 ,0,0,0}, {5500,5502,5504 ,4770,4772,4774 ,0,0,0}, - {5505,5503,5506 ,4775,4773,4776 ,0,0,0}, {5503,5502,5506 ,4773,4772,4776 ,0,0,0}, - {5499,5501,5497 ,4769,4771,4767 ,0,0,0}, {5508,5505,5507 ,4777,4775,4777 ,0,0,0}, - {5496,5499,5497 ,4766,4769,4767 ,0,0,0}, {5482,5485,5483 ,4752,4755,4753 ,0,0,0}, - {5481,5483,5509 ,4751,4753,4778 ,0,0,0}, {5509,5510,5511 ,4778,4779,4780 ,0,0,0}, - {5511,5481,5509 ,4780,4751,4778 ,0,0,0}, {5512,5510,5513 ,4781,4779,4782 ,0,0,0}, - {5510,5512,5511 ,4779,4781,4780 ,0,0,0}, {5514,5515,5513 ,4783,4784,4782 ,0,0,0}, - {5512,5513,5515 ,4781,4782,4784 ,0,0,0}, {5514,5516,5517 ,4783,4785,4786 ,0,0,0}, - {5517,5515,5514 ,4786,4784,4783 ,0,0,0}, {5518,5516,5519 ,4787,4785,4788 ,0,0,0}, - {5516,5518,5517 ,4785,4787,4786 ,0,0,0}, {5520,5521,5519 ,4789,4790,4788 ,0,0,0}, - {5518,5519,5521 ,4787,4788,4790 ,0,0,0}, {5520,5522,5523 ,4789,4791,4792 ,0,0,0}, - {5523,5521,5520 ,4792,4790,4789 ,0,0,0}, {5524,5522,5525 ,4793,4791,4794 ,0,0,0}, - {5522,5524,5523 ,4791,4793,4792 ,0,0,0}, {5526,5527,5525 ,4795,4796,4794 ,0,0,0}, - {5524,5525,5527 ,4793,4794,4796 ,0,0,0}, {5526,5528,5529 ,4795,4797,4798 ,0,0,0}, - {5529,5527,5526 ,4798,4796,4795 ,0,0,0}, {5528,5530,5529 ,4797,4799,4798 ,0,0,0}, - {5528,5531,5530 ,4797,324,4799 ,0,0,0}, {5532,5533,5534 ,82,4800,4801 ,0,0,0}, - {5534,5535,5536 ,4801,4802,4803 ,0,0,0}, {5535,5537,5536 ,4802,4804,4803 ,0,0,0}, - {5534,5536,5532 ,4801,4803,82 ,0,0,0}, {5538,5539,5540 ,4805,4806,4807 ,0,0,0}, - {5540,5539,5537 ,4807,4806,4804 ,0,0,0}, {5538,5541,5542 ,4805,4808,4809 ,0,0,0}, - {5542,5539,5538 ,4809,4806,4805 ,0,0,0}, {5542,5541,5543 ,4809,4808,4810 ,0,0,0}, - {5543,5541,5544 ,4810,4808,4811 ,0,0,0}, {5544,5545,5546 ,4811,4812,4813 ,0,0,0}, - {5543,5544,5546 ,4810,4811,4813 ,0,0,0}, {5537,5535,5540 ,4804,4802,4807 ,0,0,0}, - {5547,5548,5549 ,4814,4815,4816 ,0,0,0}, {5547,5549,5545 ,4814,4816,4812 ,0,0,0}, - {5545,5549,5546 ,4812,4816,4813 ,0,0,0}, {5532,5550,5533 ,82,4817,4800 ,0,0,0}, - {5551,5550,5552 ,4818,4817,4819 ,0,0,0}, {5550,5551,5533 ,4817,4818,4800 ,0,0,0}, - {5553,5554,5552 ,4820,4821,4819 ,0,0,0}, {5551,5552,5554 ,4818,4819,4821 ,0,0,0}, - {5553,5555,5556 ,4820,4822,4823 ,0,0,0}, {5556,5554,5553 ,4823,4821,4820 ,0,0,0}, - {5557,5555,5558 ,4824,4822,4825 ,0,0,0}, {5555,5557,5556 ,4822,4824,4823 ,0,0,0}, - {5559,5560,5558 ,4826,4827,4825 ,0,0,0}, {5557,5558,5560 ,4824,4825,4827 ,0,0,0}, - {5559,5561,5562 ,4826,4828,4829 ,0,0,0}, {5562,5560,5559 ,4829,4827,4826 ,0,0,0}, - {5563,5561,5564 ,4830,4828,4831 ,0,0,0}, {5561,5563,5562 ,4828,4830,4829 ,0,0,0}, - {5559,5558,5565 ,4832,4833,4834 ,0,0,0}, {5565,5561,5559 ,4834,4835,4832 ,0,0,0}, - {5565,5564,5561 ,4834,4836,4835 ,0,0,0}, {5565,5555,5553 ,4834,4837,4838 ,0,0,0}, - {5558,5555,5565 ,4833,4837,4834 ,0,0,0}, {5565,5552,5550 ,4834,4839,4840 ,0,0,0}, - {5553,5552,5565 ,4838,4839,4834 ,0,0,0}, {5550,5532,5565 ,4840,4841,4834 ,0,0,0}, - {5537,5565,5536 ,4842,4834,4843 ,0,0,0}, {5565,5532,5536 ,4834,4841,4843 ,0,0,0}, - {5542,5565,5539 ,4844,4834,4845 ,0,0,0}, {5565,5537,5539 ,4834,4842,4845 ,0,0,0}, - {5546,5565,5543 ,4846,4834,4847 ,0,0,0}, {5565,5542,5543 ,4834,4844,4847 ,0,0,0}, - {5548,5565,5549 ,4848,4834,4849 ,0,0,0}, {5565,5546,5549 ,4834,4846,4849 ,0,0,0}, - {5566,5567,5568 ,82,4850,4851 ,0,0,0}, {5568,5569,5570 ,4851,4852,4853 ,0,0,0}, - {5569,5571,5570 ,4852,4854,4853 ,0,0,0}, {5568,5570,5566 ,4851,4853,82 ,0,0,0}, - {5572,5573,5574 ,4855,4856,4857 ,0,0,0}, {5574,5573,5571 ,4857,4856,4854 ,0,0,0}, - {5572,5575,5576 ,4855,4858,4859 ,0,0,0}, {5576,5573,5572 ,4859,4856,4855 ,0,0,0}, - {5576,5575,5577 ,4859,4858,4860 ,0,0,0}, {5577,5575,5578 ,4860,4858,4861 ,0,0,0}, - {5578,5579,5580 ,4861,4862,4863 ,0,0,0}, {5577,5578,5580 ,4860,4861,4863 ,0,0,0}, - {5571,5569,5574 ,4854,4852,4857 ,0,0,0}, {5581,5582,5583 ,4864,4865,4866 ,0,0,0}, - {5581,5583,5579 ,4864,4866,4862 ,0,0,0}, {5579,5583,5580 ,4862,4866,4863 ,0,0,0}, - {5566,5584,5567 ,82,4867,4850 ,0,0,0}, {5585,5584,5586 ,4868,4867,4869 ,0,0,0}, - {5584,5585,5567 ,4867,4868,4850 ,0,0,0}, {5587,5588,5586 ,4870,4871,4869 ,0,0,0}, - {5585,5586,5588 ,4868,4869,4871 ,0,0,0}, {5587,5589,5590 ,4870,4872,4873 ,0,0,0}, - {5590,5588,5587 ,4873,4871,4870 ,0,0,0}, {5591,5589,5592 ,4874,4872,4875 ,0,0,0}, - {5589,5591,5590 ,4872,4874,4873 ,0,0,0}, {5593,5594,5592 ,4876,4877,4875 ,0,0,0}, - {5591,5592,5594 ,4874,4875,4877 ,0,0,0}, {5593,5595,5596 ,4876,4878,4829 ,0,0,0}, - {5596,5594,5593 ,4829,4877,4876 ,0,0,0}, {5597,5595,5598 ,4879,4878,4831 ,0,0,0}, - {5595,5597,5596 ,4878,4879,4829 ,0,0,0}, {5593,5592,5599 ,4832,4833,4880 ,0,0,0}, - {5599,5595,5593 ,4880,4835,4832 ,0,0,0}, {5599,5598,5595 ,4880,4881,4835 ,0,0,0}, - {5599,5589,5587 ,4880,4837,4838 ,0,0,0}, {5592,5589,5599 ,4833,4837,4880 ,0,0,0}, - {5599,5586,5584 ,4880,4839,4840 ,0,0,0}, {5587,5586,5599 ,4838,4839,4880 ,0,0,0}, - {5584,5566,5599 ,4840,4882,4880 ,0,0,0}, {5571,5599,5570 ,4842,4880,4843 ,0,0,0}, - {5599,5566,5570 ,4880,4882,4843 ,0,0,0}, {5576,5599,5573 ,4844,4880,4845 ,0,0,0}, - {5599,5571,5573 ,4880,4842,4845 ,0,0,0}, {5580,5599,5577 ,4846,4880,4847 ,0,0,0}, - {5599,5576,5577 ,4880,4844,4847 ,0,0,0}, {5582,5599,5583 ,4883,4880,4849 ,0,0,0}, - {5599,5580,5583 ,4880,4846,4849 ,0,0,0}, {5600,5601,5602 ,4884,4885,4886 ,0,0,0}, - {5602,5603,5604 ,4886,4887,4888 ,0,0,0}, {5603,5605,5604 ,4887,4889,4888 ,0,0,0}, - {5602,5604,5600 ,4886,4888,4884 ,0,0,0}, {5606,5607,5608 ,4890,4891,4857 ,0,0,0}, - {5608,5607,5605 ,4857,4891,4889 ,0,0,0}, {5606,5609,5610 ,4890,4892,4893 ,0,0,0}, - {5610,5607,5606 ,4893,4891,4890 ,0,0,0}, {5610,5609,5611 ,4893,4892,4894 ,0,0,0}, - {5611,5609,5612 ,4894,4892,4895 ,0,0,0}, {5612,5613,5614 ,4895,4896,4897 ,0,0,0}, - {5611,5612,5614 ,4894,4895,4897 ,0,0,0}, {5605,5603,5608 ,4889,4887,4857 ,0,0,0}, - {5615,5616,5617 ,4898,4899,4900 ,0,0,0}, {5615,5617,5613 ,4898,4900,4896 ,0,0,0}, - {5613,5617,5614 ,4896,4900,4897 ,0,0,0}, {5600,5618,5601 ,4884,4901,4885 ,0,0,0}, - {5619,5618,5620 ,4868,4901,4902 ,0,0,0}, {5618,5619,5601 ,4901,4868,4885 ,0,0,0}, - {5621,5622,5620 ,4820,4903,4902 ,0,0,0}, {5619,5620,5622 ,4868,4902,4903 ,0,0,0}, - {5621,5623,5624 ,4820,4904,4905 ,0,0,0}, {5624,5622,5621 ,4905,4903,4820 ,0,0,0}, - {5625,5623,5626 ,4906,4904,4907 ,0,0,0}, {5623,5625,5624 ,4904,4906,4905 ,0,0,0}, - {5627,5628,5626 ,4826,4877,4907 ,0,0,0}, {5625,5626,5628 ,4906,4907,4877 ,0,0,0}, - {5627,5629,5630 ,4826,4828,4908 ,0,0,0}, {5630,5628,5627 ,4908,4877,4826 ,0,0,0}, - {5631,5629,5632 ,4909,4828,4910 ,0,0,0}, {5629,5631,5630 ,4828,4909,4908 ,0,0,0}, - {5627,5626,5633 ,4832,4833,4880 ,0,0,0}, {5633,5629,5627 ,4880,4835,4832 ,0,0,0}, - {5633,5632,5629 ,4880,4911,4835 ,0,0,0}, {5633,5623,5621 ,4880,4837,4838 ,0,0,0}, - {5626,5623,5633 ,4833,4837,4880 ,0,0,0}, {5633,5620,5618 ,4880,4839,4840 ,0,0,0}, - {5621,5620,5633 ,4838,4839,4880 ,0,0,0}, {5618,5600,5633 ,4840,4912,4880 ,0,0,0}, - {5605,5633,5604 ,4842,4880,4843 ,0,0,0}, {5633,5600,5604 ,4880,4912,4843 ,0,0,0}, - {5610,5633,5607 ,4844,4880,4845 ,0,0,0}, {5633,5605,5607 ,4880,4842,4845 ,0,0,0}, - {5614,5633,5611 ,4846,4880,4847 ,0,0,0}, {5633,5610,5611 ,4880,4844,4847 ,0,0,0}, - {5616,5633,5617 ,4913,4880,4849 ,0,0,0}, {5633,5614,5617 ,4880,4846,4849 ,0,0,0}, - {5634,5635,5636 ,4914,4915,4916 ,0,0,0}, {5636,5637,5638 ,4916,4917,4918 ,0,0,0}, - {5637,5639,5638 ,4917,4919,4918 ,0,0,0}, {5636,5638,5634 ,4916,4918,4914 ,0,0,0}, - {5640,5641,5642 ,4920,4921,4922 ,0,0,0}, {5642,5641,5639 ,4922,4921,4919 ,0,0,0}, - {5640,5643,5644 ,4920,4923,4924 ,0,0,0}, {5644,5641,5640 ,4924,4921,4920 ,0,0,0}, - {5644,5643,5645 ,4924,4923,4925 ,0,0,0}, {5645,5643,5646 ,4925,4923,4926 ,0,0,0}, - {5646,5647,5648 ,4926,4927,4928 ,0,0,0}, {5645,5646,5648 ,4925,4926,4928 ,0,0,0}, - {5639,5637,5642 ,4919,4917,4922 ,0,0,0}, {5649,5650,5651 ,4929,4815,4930 ,0,0,0}, - {5649,5651,5647 ,4929,4930,4927 ,0,0,0}, {5647,5651,5648 ,4927,4930,4928 ,0,0,0}, - {5634,5652,5635 ,4914,4931,4915 ,0,0,0}, {5653,5652,5654 ,4932,4931,4933 ,0,0,0}, - {5652,5653,5635 ,4931,4932,4915 ,0,0,0}, {5655,5656,5654 ,4934,4821,4933 ,0,0,0}, - {5653,5654,5656 ,4932,4933,4821 ,0,0,0}, {5655,5657,5658 ,4934,4935,4936 ,0,0,0}, - {5658,5656,5655 ,4936,4821,4934 ,0,0,0}, {5659,5657,5660 ,4937,4935,4938 ,0,0,0}, - {5657,5659,5658 ,4935,4937,4936 ,0,0,0}, {5661,5662,5660 ,4826,4877,4938 ,0,0,0}, - {5659,5660,5662 ,4937,4938,4877 ,0,0,0}, {5661,5663,5664 ,4826,4939,4940 ,0,0,0}, - {5664,5662,5661 ,4940,4877,4826 ,0,0,0}, {5665,5663,5666 ,4941,4939,4942 ,0,0,0}, - {5663,5665,5664 ,4939,4941,4940 ,0,0,0}, {5661,5660,5667 ,4832,4833,4943 ,0,0,0}, - {5667,5663,5661 ,4943,4835,4832 ,0,0,0}, {5667,5666,5663 ,4943,4944,4835 ,0,0,0}, - {5667,5657,5655 ,4943,4837,4838 ,0,0,0}, {5660,5657,5667 ,4833,4837,4943 ,0,0,0}, - {5667,5654,5652 ,4943,4839,4840 ,0,0,0}, {5655,5654,5667 ,4838,4839,4943 ,0,0,0}, - {5652,5634,5667 ,4840,4945,4943 ,0,0,0}, {5639,5667,5638 ,4842,4943,4843 ,0,0,0}, - {5667,5634,5638 ,4943,4945,4843 ,0,0,0}, {5644,5667,5641 ,4844,4943,4845 ,0,0,0}, - {5667,5639,5641 ,4943,4842,4845 ,0,0,0}, {5648,5667,5645 ,4846,4943,4847 ,0,0,0}, - {5667,5644,5645 ,4943,4844,4847 ,0,0,0}, {5650,5667,5651 ,4946,4943,4849 ,0,0,0}, - {5667,5648,5651 ,4943,4846,4849 ,0,0,0}, {5668,5669,5670 ,4947,4948,4949 ,0,0,0}, - {5671,5672,5673 ,4950,4951,4952 ,0,0,0}, {5670,5673,5672 ,4949,4952,4951 ,0,0,0}, - {5674,5675,5676 ,4953,4954,4955 ,0,0,0}, {5677,5678,5671 ,4956,4957,4950 ,0,0,0}, - {5674,5678,5677 ,4953,4957,4956 ,0,0,0}, {5677,5675,5674 ,4956,4954,4953 ,0,0,0}, - {5678,5672,5671 ,4957,4951,4950 ,0,0,0}, {5679,5680,5681 ,4958,4959,4960 ,0,0,0}, - {5680,5682,5681 ,4959,4961,4960 ,0,0,0}, {5683,5684,5685 ,4962,4963,4964 ,0,0,0}, - {5683,5685,5682 ,4962,4964,4961 ,0,0,0}, {5680,5683,5682 ,4959,4962,4961 ,0,0,0}, - {5675,5679,5676 ,4954,4958,4955 ,0,0,0}, {5679,5681,5676 ,4958,4960,4955 ,0,0,0}, - {5686,5687,5688 ,4965,4966,4967 ,0,0,0}, {5689,5690,5691 ,4968,4969,4970 ,0,0,0}, - {5688,5687,5689 ,4967,4966,4968 ,0,0,0}, {5692,5693,5694 ,4726,4971,4972 ,0,0,0}, - {5688,5689,5691 ,4967,4968,4970 ,0,0,0}, {5694,5693,5690 ,4972,4971,4969 ,0,0,0}, - {5693,5691,5690 ,4971,4970,4969 ,0,0,0}, {5684,5687,5686 ,4963,4966,4965 ,0,0,0}, - {5695,5692,5694 ,4726,4726,4972 ,0,0,0}, {5685,5684,5686 ,4964,4963,4965 ,0,0,0}, - {5669,5673,5670 ,4948,4952,4949 ,0,0,0}, {5696,5669,5668 ,4973,4948,4947 ,0,0,0}, - {5696,5697,5698 ,4973,4974,4975 ,0,0,0}, {5697,5696,5668 ,4974,4973,4947 ,0,0,0}, - {5699,5698,5700 ,4976,4975,4977 ,0,0,0}, {5697,5700,5698 ,4974,4977,4975 ,0,0,0}, - {5701,5702,5699 ,4978,4979,4976 ,0,0,0}, {5699,5700,5701 ,4976,4977,4978 ,0,0,0}, - {5702,5703,5704 ,4979,4980,4981 ,0,0,0}, {5703,5702,5701 ,4980,4979,4978 ,0,0,0}, - {5705,5704,5706 ,4982,4981,4983 ,0,0,0}, {5703,5706,5704 ,4980,4983,4981 ,0,0,0}, - {5707,5708,5705 ,4984,4985,4982 ,0,0,0}, {5705,5706,5707 ,4982,4983,4984 ,0,0,0}, - {5708,5709,5710 ,4985,4986,4987 ,0,0,0}, {5709,5708,5707 ,4986,4985,4984 ,0,0,0}, - {5711,5710,5712 ,4988,4987,4989 ,0,0,0}, {5709,5712,5710 ,4986,4989,4987 ,0,0,0}, - {5713,5714,5711 ,4990,4991,4988 ,0,0,0}, {5711,5712,5713 ,4988,4989,4990 ,0,0,0}, - {5714,5715,5716 ,4991,4992,4748 ,0,0,0}, {5715,5714,5713 ,4992,4991,4990 ,0,0,0}, - {5715,5717,5716 ,4992,4750,4748 ,0,0,0}, {5718,5719,5720 ,4993,4994,4995 ,0,0,0}, - {5721,5722,5723 ,4996,4997,4998 ,0,0,0}, {5719,5724,5725 ,4994,4999,5000 ,0,0,0}, - {5724,5719,5718 ,4999,4994,4993 ,0,0,0}, {5724,5726,5725 ,4999,5001,5000 ,0,0,0}, - {5720,5727,5718 ,4995,5002,4993 ,0,0,0}, {5721,5727,5728 ,4996,5002,5003 ,0,0,0}, - {5720,5728,5727 ,4995,5003,5002 ,0,0,0}, {5729,5730,5731 ,5004,5005,5006 ,0,0,0}, - {5721,5728,5722 ,4996,5003,4997 ,0,0,0}, {5732,5733,5734 ,5007,5008,5009 ,0,0,0}, - {5735,5736,5737 ,5010,5011,5012 ,0,0,0}, {5738,5739,5740 ,5013,5014,5015 ,0,0,0}, - {5741,5742,5743 ,5016,5017,5018 ,0,0,0}, {5744,5745,5746 ,5019,5020,5021 ,0,0,0}, - {5747,5748,5739 ,5022,5023,5014 ,0,0,0}, {5749,5750,5751 ,5024,5025,5026 ,0,0,0}, - {5750,5745,5752 ,5025,5020,5027 ,0,0,0}, {5753,5754,5755 ,5028,5029,5030 ,0,0,0}, - {5756,5757,5749 ,5031,5032,5024 ,0,0,0}, {5758,5759,5760 ,5033,5034,5035 ,0,0,0}, - {5761,5755,5762 ,5036,5030,5037 ,0,0,0}, {5763,5764,5765 ,5038,5039,5040 ,0,0,0}, - {5766,5764,5767 ,5041,5039,5042 ,0,0,0}, {5768,5769,5770 ,5043,5044,5045 ,0,0,0}, - {5765,5771,5768 ,5040,5046,5043 ,0,0,0}, {5772,5773,5774 ,5047,5048,5049 ,0,0,0}, - {5772,5775,5776 ,5047,5050,5051 ,0,0,0}, {5777,5778,5779 ,5052,5053,5054 ,0,0,0}, - {5780,5781,5779 ,5055,5056,5054 ,0,0,0}, {5782,5783,5784 ,5057,5058,5059 ,0,0,0}, - {5783,5777,5785 ,5058,5052,5060 ,0,0,0}, {5786,5787,5788 ,5061,5062,5063 ,0,0,0}, - {5782,5789,5786 ,5057,5064,5061 ,0,0,0}, {5790,5791,5792 ,5065,5066,5067 ,0,0,0}, - {5790,5793,5794 ,5065,5068,5069 ,0,0,0}, {5795,5796,5797 ,5070,5071,5072 ,0,0,0}, - {5795,5798,5791 ,5070,5073,5066 ,0,0,0}, {5799,5796,5800 ,5074,5071,5075 ,0,0,0}, - {5796,5799,5797 ,5071,5074,5072 ,0,0,0}, {5801,5802,5800 ,5076,5077,5075 ,0,0,0}, - {5799,5800,5802 ,5074,5075,5077 ,0,0,0}, {5803,5804,5802 ,5078,5079,5077 ,0,0,0}, - {5802,5801,5803 ,5077,5076,5078 ,0,0,0}, {5804,5805,5806 ,5079,5080,5081 ,0,0,0}, - {5805,5804,5803 ,5080,5079,5078 ,0,0,0}, {5807,5806,5808 ,5082,5081,5083 ,0,0,0}, - {5805,5808,5806 ,5080,5083,5081 ,0,0,0}, {5809,5810,5807 ,5084,5085,5082 ,0,0,0}, - {5807,5808,5809 ,5082,5083,5084 ,0,0,0}, {5810,5811,5812 ,5085,5086,5087 ,0,0,0}, - {5811,5810,5809 ,5086,5085,5084 ,0,0,0}, {5813,5812,5814 ,5088,5087,5089 ,0,0,0}, - {5811,5814,5812 ,5086,5089,5087 ,0,0,0}, {5815,5813,5816 ,5090,5088,5091 ,0,0,0}, - {5813,5814,5816 ,5088,5089,5091 ,0,0,0}, {5815,5817,5818 ,5090,5092,5093 ,0,0,0}, - {5818,5813,5815 ,5093,5088,5090 ,0,0,0}, {5819,5817,5820 ,5094,5092,5095 ,0,0,0}, - {5817,5819,5818 ,5092,5094,5093 ,0,0,0}, {5821,5822,5820 ,126,5096,5095 ,0,0,0}, - {5819,5820,5822 ,5094,5095,5096 ,0,0,0}, {5823,5822,5821 ,126,5096,126 ,0,0,0}, - {5792,5791,5798 ,5067,5066,5073 ,0,0,0}, {5795,5797,5798 ,5070,5072,5073 ,0,0,0}, - {5788,5793,5786 ,5063,5068,5061 ,0,0,0}, {5790,5792,5793 ,5065,5067,5068 ,0,0,0}, - {5788,5794,5793 ,5063,5069,5068 ,0,0,0}, {5784,5789,5782 ,5059,5064,5057 ,0,0,0}, - {5786,5789,5787 ,5061,5064,5062 ,0,0,0}, {5778,5777,5783 ,5053,5052,5058 ,0,0,0}, - {5783,5785,5784 ,5058,5060,5059 ,0,0,0}, {5780,5773,5781 ,5055,5048,5056 ,0,0,0}, - {5778,5780,5779 ,5053,5055,5054 ,0,0,0}, {5772,5774,5775 ,5047,5049,5050 ,0,0,0}, - {5773,5780,5774 ,5048,5055,5049 ,0,0,0}, {5769,5776,5770 ,5044,5051,5045 ,0,0,0}, - {5776,5775,5770 ,5051,5050,5045 ,0,0,0}, {5765,5768,5763 ,5040,5043,5038 ,0,0,0}, - {5771,5769,5768 ,5046,5044,5043 ,0,0,0}, {5758,5766,5759 ,5033,5041,5034 ,0,0,0}, - {5767,5764,5763 ,5042,5039,5038 ,0,0,0}, {5759,5766,5767 ,5034,5041,5042 ,0,0,0}, - {5760,5761,5762 ,5035,5036,5037 ,0,0,0}, {5759,5761,5760 ,5034,5036,5035 ,0,0,0}, - {5755,5757,5753 ,5030,5032,5028 ,0,0,0}, {5762,5755,5754 ,5037,5030,5029 ,0,0,0}, - {5824,5756,5749 ,5097,5031,5024 ,0,0,0}, {5756,5753,5757 ,5031,5028,5032 ,0,0,0}, - {5825,5750,5752 ,5098,5025,5027 ,0,0,0}, {5749,5751,5824 ,5024,5026,5097 ,0,0,0}, - {5750,5825,5751 ,5025,5098,5026 ,0,0,0}, {5746,5747,5744 ,5021,5022,5019 ,0,0,0}, - {5752,5745,5744 ,5027,5020,5019 ,0,0,0}, {5740,5743,5738 ,5015,5018,5013 ,0,0,0}, - {5747,5746,5748 ,5022,5021,5023 ,0,0,0}, {5739,5748,5740 ,5014,5023,5015 ,0,0,0}, - {5732,5741,5743 ,5007,5016,5018 ,0,0,0}, {5742,5738,5743 ,5017,5013,5018 ,0,0,0}, - {5733,5737,5734 ,5008,5012,5009 ,0,0,0}, {5732,5734,5741 ,5007,5009,5016 ,0,0,0}, - {5735,5729,5736 ,5010,5004,5011 ,0,0,0}, {5733,5735,5737 ,5008,5010,5012 ,0,0,0}, - {5731,5730,5723 ,5006,5005,4998 ,0,0,0}, {5736,5729,5731 ,5011,5004,5006 ,0,0,0}, - {5721,5723,5730 ,4996,4998,5005 ,0,0,0}, {5826,5827,5828 ,5099,5100,5101 ,0,0,0}, - {5829,5830,5831 ,5102,5103,5104 ,0,0,0}, {5832,5830,5829 ,5105,5103,5102 ,0,0,0}, - {5833,5829,5831 ,5106,5102,5104 ,0,0,0}, {5834,5835,5836 ,5107,5108,5109 ,0,0,0}, - {5837,5838,5833 ,5110,5108,5106 ,0,0,0}, {5835,5839,5836 ,5108,5111,5109 ,0,0,0}, - {5835,5838,5839 ,5108,5108,5111 ,0,0,0}, {5839,5840,5841 ,5111,5112,5113 ,0,0,0}, - {5840,5842,5841 ,5112,5114,5113 ,0,0,0}, {5841,5842,5843 ,5113,5114,5115 ,0,0,0}, - {5842,5844,5843 ,5114,5116,5115 ,0,0,0}, {5845,5846,5844 ,5117,5118,5116 ,0,0,0}, - {5845,5847,5848 ,5117,5119,5120 ,0,0,0}, {5849,5848,5847 ,5121,5120,5119 ,0,0,0}, - {5849,5847,5850 ,5121,5119,5122 ,0,0,0}, {5850,5851,5849 ,5122,5123,5121 ,0,0,0}, - {5846,5843,5844 ,5118,5115,5116 ,0,0,0}, {5848,5846,5845 ,5120,5118,5117 ,0,0,0}, - {5851,5852,5853 ,5123,5124,5125 ,0,0,0}, {5852,5851,5850 ,5124,5123,5122 ,0,0,0}, - {5430,5853,5852 ,5126,5125,5124 ,0,0,0}, {5832,5829,5854 ,5105,5102,5127 ,0,0,0}, - {5855,5856,5857 ,5128,5129,5130 ,0,0,0}, {5855,5854,5856 ,5128,5127,5129 ,0,0,0}, - {5856,5858,5857 ,5129,5131,5130 ,0,0,0}, {5858,5856,5859 ,5131,5129,5132 ,0,0,0}, - {5860,5861,5862 ,5133,5134,5135 ,0,0,0}, {5860,5859,5861 ,5133,5132,5134 ,0,0,0}, - {5863,5862,5861 ,5136,5135,5134 ,0,0,0}, {5862,5863,5864 ,5135,5136,5137 ,0,0,0}, - {5865,5866,5867 ,5138,5139,5140 ,0,0,0}, {5868,5869,5863 ,5141,5142,5136 ,0,0,0}, - {5870,5871,5868 ,5143,5144,5141 ,0,0,0}, {5871,5870,5872 ,5144,5143,5145 ,0,0,0}, - {5873,5874,5870 ,5146,5147,5143 ,0,0,0}, {5827,5826,5875 ,5100,5099,5148 ,0,0,0}, - {5876,5877,5873 ,5149,5150,5146 ,0,0,0}, {5878,5879,5880 ,5151,5152,5153 ,0,0,0}, - {5881,5882,5883 ,5154,5155,5156 ,0,0,0}, {5884,5885,5886 ,5157,5158,5159 ,0,0,0}, - {5887,5888,5889 ,5160,5161,5162 ,0,0,0}, {5890,5891,5892 ,5163,5164,5165 ,0,0,0}, - {5893,5894,5895 ,5166,5167,5168 ,0,0,0}, {5893,5896,5897 ,5166,5169,5170 ,0,0,0}, - {5898,5899,5900 ,5171,5172,5173 ,0,0,0}, {5901,5902,5903 ,5174,5175,5176 ,0,0,0}, - {5904,5905,5906 ,5177,5178,5179 ,0,0,0}, {5907,5899,5898 ,5180,5172,5171 ,0,0,0}, - {5908,5909,5910 ,5179,5181,5182 ,0,0,0}, {5908,5906,5905 ,5179,5179,5178 ,0,0,0}, - {5911,5912,5913 ,5183,5184,5185 ,0,0,0}, {5914,5911,5910 ,5186,5183,5182 ,0,0,0}, - {5915,5916,5917 ,5187,5188,5189 ,0,0,0}, {5918,5915,5913 ,5190,5187,5185 ,0,0,0}, - {5919,5920,5921 ,5191,5192,5193 ,0,0,0}, {5920,5919,5917 ,5192,5191,5189 ,0,0,0}, - {5922,5923,5921 ,5194,5195,5193 ,0,0,0}, {5919,5921,5923 ,5191,5193,5195 ,0,0,0}, - {5922,5924,5925 ,5194,5196,5197 ,0,0,0}, {5925,5923,5922 ,5197,5195,5194 ,0,0,0}, - {5918,5916,5915 ,5190,5188,5187 ,0,0,0}, {5916,5920,5917 ,5188,5192,5189 ,0,0,0}, - {5912,5918,5913 ,5184,5190,5185 ,0,0,0}, {5914,5912,5911 ,5186,5184,5183 ,0,0,0}, - {5909,5914,5910 ,5181,5186,5182 ,0,0,0}, {5909,5908,5905 ,5181,5179,5178 ,0,0,0}, - {5905,5926,5909 ,5178,5198,5181 ,0,0,0}, {5898,5926,5907 ,5171,5198,5180 ,0,0,0}, - {5926,5905,5907 ,5198,5178,5180 ,0,0,0}, {5927,5928,5929 ,5199,5200,5201 ,0,0,0}, - {5900,5899,5901 ,5173,5172,5174 ,0,0,0}, {5927,5930,5931 ,5199,5202,5203 ,0,0,0}, - {5931,5928,5927 ,5203,5200,5199 ,0,0,0}, {5932,5930,5933 ,5204,5202,5205 ,0,0,0}, - {5930,5932,5931 ,5202,5204,5203 ,0,0,0}, {5934,5528,5933 ,5206,5207,5205 ,0,0,0}, - {5932,5933,5528 ,5204,5205,5207 ,0,0,0}, {5531,5528,5934 ,5197,5207,5206 ,0,0,0}, - {5929,5928,5935 ,5201,5200,5208 ,0,0,0}, {5936,5937,5938 ,5209,5210,5211 ,0,0,0}, - {5929,5935,5938 ,5201,5208,5211 ,0,0,0}, {5936,5939,5937 ,5209,5212,5210 ,0,0,0}, - {5938,5935,5936 ,5211,5208,5209 ,0,0,0}, {5902,5894,5903 ,5175,5167,5176 ,0,0,0}, - {5939,5940,5937 ,5212,5213,5210 ,0,0,0}, {5906,5940,5904 ,5179,5213,5177 ,0,0,0}, - {5939,5904,5940 ,5212,5177,5213 ,0,0,0}, {5901,5903,5900 ,5174,5176,5173 ,0,0,0}, - {5892,5881,5890 ,5165,5154,5163 ,0,0,0}, {5893,5895,5896 ,5166,5168,5169 ,0,0,0}, - {5894,5902,5895 ,5167,5175,5168 ,0,0,0}, {5896,5889,5897 ,5169,5162,5170 ,0,0,0}, - {5891,5888,5887 ,5164,5161,5160 ,0,0,0}, {5888,5897,5889 ,5161,5170,5162 ,0,0,0}, - {5892,5891,5887 ,5165,5164,5160 ,0,0,0}, {5878,5885,5884 ,5151,5158,5157 ,0,0,0}, - {5881,5883,5890 ,5154,5156,5163 ,0,0,0}, {5882,5886,5883 ,5155,5159,5156 ,0,0,0}, - {5880,5885,5878 ,5153,5158,5151 ,0,0,0}, {5882,5884,5886 ,5155,5157,5159 ,0,0,0}, - {5828,5880,5879 ,5101,5153,5152 ,0,0,0}, {5879,5480,5876 ,5152,5214,5149 ,0,0,0}, - {5834,5941,5835 ,5107,5215,5108 ,0,0,0}, {5840,5839,5838 ,5112,5111,5108 ,0,0,0}, - {5837,5942,5838 ,5110,5216,5108 ,0,0,0}, {5840,5838,5942 ,5112,5108,5216 ,0,0,0}, - {5943,5941,5944 ,5217,5215,5218 ,0,0,0}, {5831,5837,5833 ,5104,5110,5106 ,0,0,0}, - {5945,5943,5946 ,5219,5217,5220 ,0,0,0}, {5945,5947,5943 ,5219,5221,5217 ,0,0,0}, - {5948,5947,5949 ,5222,5221,5223 ,0,0,0}, {5855,5832,5854 ,5128,5105,5127 ,0,0,0}, - {5950,5948,5951 ,5224,5222,5225 ,0,0,0}, {5950,5952,5948 ,5224,5226,5222 ,0,0,0}, - {5953,5952,5954 ,5227,5226,5228 ,0,0,0}, {5860,5858,5859 ,5133,5131,5132 ,0,0,0}, - {5955,5956,5953 ,5229,5230,5227 ,0,0,0}, {5957,5956,5955 ,5231,5230,5229 ,0,0,0}, - {5958,5956,5959 ,5232,5230,5233 ,0,0,0}, {5869,5864,5863 ,5142,5137,5136 ,0,0,0}, - {5867,5958,5865 ,5140,5232,5138 ,0,0,0}, {5871,5869,5868 ,5144,5142,5141 ,0,0,0}, - {5960,5867,5961 ,5234,5140,5235 ,0,0,0}, {5874,5872,5870 ,5147,5145,5143 ,0,0,0}, - {5826,5960,5875 ,5099,5234,5148 ,0,0,0}, {5877,5874,5873 ,5150,5147,5146 ,0,0,0}, - {5877,5876,5480 ,5150,5149,5214 ,0,0,0}, {5879,5876,5828 ,5152,5149,5101 ,0,0,0}, - {5828,5876,5826 ,5101,5149,5099 ,0,0,0}, {5961,5875,5960 ,5235,5148,5234 ,0,0,0}, - {5866,5961,5867 ,5139,5235,5140 ,0,0,0}, {5959,5865,5958 ,5233,5138,5232 ,0,0,0}, - {5957,5959,5956 ,5231,5233,5230 ,0,0,0}, {5954,5955,5953 ,5228,5229,5227 ,0,0,0}, - {5950,5954,5952 ,5224,5228,5226 ,0,0,0}, {5949,5951,5948 ,5223,5225,5222 ,0,0,0}, - {5945,5949,5947 ,5219,5223,5221 ,0,0,0}, {5944,5946,5943 ,5218,5220,5217 ,0,0,0}, - {5834,5944,5941 ,5107,5218,5215 ,0,0,0}, {5962,5963,5964 ,5236,5237,5238 ,0,0,0}, - {5965,5966,5964 ,5239,5240,5238 ,0,0,0}, {5962,5964,5966 ,5236,5238,5240 ,0,0,0}, - {5965,5967,5968 ,5239,5241,5242 ,0,0,0}, {5968,5966,5965 ,5242,5240,5239 ,0,0,0}, - {5969,5967,5970 ,5243,5241,5244 ,0,0,0}, {5967,5969,5968 ,5241,5243,5242 ,0,0,0}, - {5971,5972,5970 ,5245,5246,5244 ,0,0,0}, {5969,5970,5972 ,5243,5244,5246 ,0,0,0}, - {5971,5973,5974 ,5245,5247,5248 ,0,0,0}, {5974,5972,5971 ,5248,5246,5245 ,0,0,0}, - {5975,5973,5976 ,5249,5247,5250 ,0,0,0}, {5973,5975,5974 ,5247,5249,5248 ,0,0,0}, - {5977,5978,5976 ,5251,5252,5250 ,0,0,0}, {5975,5976,5978 ,5249,5250,5252 ,0,0,0}, - {5977,5979,5980 ,5251,5253,5254 ,0,0,0}, {5980,5978,5977 ,5254,5252,5251 ,0,0,0}, - {5981,5979,5982 ,5255,5253,5256 ,0,0,0}, {5979,5981,5980 ,5253,5255,5254 ,0,0,0}, - {5983,5984,5982 ,5257,5258,5256 ,0,0,0}, {5981,5982,5984 ,5255,5256,5258 ,0,0,0}, - {5983,5985,5986 ,5257,5259,5260 ,0,0,0}, {5986,5984,5983 ,5260,5258,5257 ,0,0,0}, - {5987,5985,5988 ,5261,5259,5262 ,0,0,0}, {5985,5987,5986 ,5259,5261,5260 ,0,0,0}, - {5989,5990,5988 ,5263,5264,5262 ,0,0,0}, {5987,5988,5990 ,5261,5262,5264 ,0,0,0}, - {5989,5991,5992 ,5263,5265,5266 ,0,0,0}, {5992,5990,5989 ,5266,5264,5263 ,0,0,0}, - {5993,5991,5994 ,5267,5265,5268 ,0,0,0}, {5991,5993,5992 ,5265,5267,5266 ,0,0,0}, - {5995,5996,5994 ,5269,5270,5268 ,0,0,0}, {5993,5994,5996 ,5267,5268,5270 ,0,0,0}, - {5995,5997,5998 ,5269,5271,5272 ,0,0,0}, {5998,5996,5995 ,5272,5270,5269 ,0,0,0}, - {5999,5997,6000 ,5273,5271,5274 ,0,0,0}, {5997,5999,5998 ,5271,5273,5272 ,0,0,0}, - {6001,6002,6000 ,5275,5276,5274 ,0,0,0}, {5999,6000,6002 ,5273,5274,5276 ,0,0,0}, - {6001,6003,6004 ,5275,5277,5278 ,0,0,0}, {6004,6002,6001 ,5278,5276,5275 ,0,0,0}, - {6005,6003,6006 ,5279,5277,5280 ,0,0,0}, {6003,6005,6004 ,5277,5279,5278 ,0,0,0}, - {6007,6008,6006 ,5281,5282,5280 ,0,0,0}, {6005,6006,6008 ,5279,5280,5282 ,0,0,0}, - {6009,6007,6010 ,5283,5281,5284 ,0,0,0}, {6009,6008,6007 ,5283,5282,5281 ,0,0,0}, - {6011,6010,6012 ,5285,5284,5286 ,0,0,0}, {6007,6012,6010 ,5281,5286,5284 ,0,0,0}, - {6013,6011,6014 ,5287,5285,5288 ,0,0,0}, {6011,6012,6014 ,5285,5286,5288 ,0,0,0}, - {6013,6015,6016 ,5287,5289,5290 ,0,0,0}, {6016,6011,6013 ,5290,5285,5287 ,0,0,0}, - {6015,6017,6016 ,5289,5291,5290 ,0,0,0}, {6018,5963,5962 ,5292,5237,5236 ,0,0,0}, - {6018,6019,6020 ,5292,5293,5294 ,0,0,0}, {6020,5963,6018 ,5294,5237,5292 ,0,0,0}, - {6021,6019,6022 ,5295,5293,5296 ,0,0,0}, {6019,6021,6020 ,5293,5295,5294 ,0,0,0}, - {6023,6024,6022 ,5297,5298,5296 ,0,0,0}, {6021,6022,6024 ,5295,5296,5298 ,0,0,0}, - {6023,6025,6026 ,5297,5299,5300 ,0,0,0}, {6026,6024,6023 ,5300,5298,5297 ,0,0,0}, - {6027,6025,6028 ,5301,5299,5302 ,0,0,0}, {6025,6027,6026 ,5299,5301,5300 ,0,0,0}, - {6029,6030,6028 ,5303,5304,5302 ,0,0,0}, {6027,6028,6030 ,5301,5302,5304 ,0,0,0}, - {6029,6031,6032 ,5303,5305,5306 ,0,0,0}, {6032,6030,6029 ,5306,5304,5303 ,0,0,0}, - {6033,6031,6034 ,5307,5305,5308 ,0,0,0}, {6031,6033,6032 ,5305,5307,5306 ,0,0,0}, - {6035,6036,6034 ,5309,5310,5308 ,0,0,0}, {6033,6034,6036 ,5307,5308,5310 ,0,0,0}, - {6035,6037,6038 ,5309,5311,5312 ,0,0,0}, {6038,6036,6035 ,5312,5310,5309 ,0,0,0}, - {6039,6037,6040 ,5313,5311,5314 ,0,0,0}, {6037,6039,6038 ,5311,5313,5312 ,0,0,0}, - {6041,6042,6040 ,5315,5316,5314 ,0,0,0}, {6039,6040,6042 ,5313,5314,5316 ,0,0,0}, - {6041,6043,6044 ,5315,5317,5318 ,0,0,0}, {6044,6042,6041 ,5318,5316,5315 ,0,0,0}, - {6045,6043,6046 ,5319,5317,5320 ,0,0,0}, {6043,6045,6044 ,5317,5319,5318 ,0,0,0}, - {6047,6048,6046 ,5321,5322,5320 ,0,0,0}, {6045,6046,6048 ,5319,5320,5322 ,0,0,0}, - {6047,6049,6050 ,5321,5323,5324 ,0,0,0}, {6050,6048,6047 ,5324,5322,5321 ,0,0,0}, - {6051,6049,6052 ,5325,5323,5326 ,0,0,0}, {6049,6051,6050 ,5323,5325,5324 ,0,0,0}, - {6053,6054,6052 ,5327,5328,5326 ,0,0,0}, {6051,6052,6054 ,5325,5326,5328 ,0,0,0}, - {6053,6055,6056 ,5327,5329,5330 ,0,0,0}, {6056,6054,6053 ,5330,5328,5327 ,0,0,0}, - {6057,6055,6058 ,5331,5329,5332 ,0,0,0}, {6055,6057,6056 ,5329,5331,5330 ,0,0,0}, - {6059,6060,6058 ,5333,5334,5332 ,0,0,0}, {6057,6058,6060 ,5331,5332,5334 ,0,0,0}, - {6059,6061,6062 ,5333,5335,5336 ,0,0,0}, {6062,6060,6059 ,5336,5334,5333 ,0,0,0}, - {6063,6064,6061 ,5337,5338,5335 ,0,0,0}, {6061,6064,6062 ,5335,5338,5336 ,0,0,0}, - {6065,6066,6063 ,5339,5340,5337 ,0,0,0}, {6063,6061,6065 ,5337,5335,5339 ,0,0,0}, - {6067,6068,6066 ,5341,5342,5340 ,0,0,0}, {6067,6066,6065 ,5341,5340,5339 ,0,0,0}, - {6069,6068,6070 ,5343,5342,5344 ,0,0,0}, {6068,6069,6066 ,5342,5343,5340 ,0,0,0}, - {6069,6070,6071 ,5343,5344,5345 ,0,0,0}, {6072,6073,6074 ,5346,5347,5348 ,0,0,0}, - {6075,6076,6074 ,5349,5350,5348 ,0,0,0}, {6072,6074,6076 ,5346,5348,5350 ,0,0,0}, - {6075,6077,6078 ,5349,5351,5352 ,0,0,0}, {6078,6076,6075 ,5352,5350,5349 ,0,0,0}, - {6079,6077,6080 ,5353,5351,5354 ,0,0,0}, {6077,6079,6078 ,5351,5353,5352 ,0,0,0}, - {6081,6082,6080 ,5355,5356,5354 ,0,0,0}, {6079,6080,6082 ,5353,5354,5356 ,0,0,0}, - {6081,6083,6084 ,5355,5357,5358 ,0,0,0}, {6084,6082,6081 ,5358,5356,5355 ,0,0,0}, - {6085,6083,6086 ,5359,5357,5360 ,0,0,0}, {6083,6085,6084 ,5357,5359,5358 ,0,0,0}, - {6087,6088,6086 ,5361,5362,5360 ,0,0,0}, {6085,6086,6088 ,5359,5360,5362 ,0,0,0}, - {6087,6089,6090 ,5361,5363,5364 ,0,0,0}, {6090,6088,6087 ,5364,5362,5361 ,0,0,0}, - {6091,6089,6092 ,5365,5363,5366 ,0,0,0}, {6089,6091,6090 ,5363,5365,5364 ,0,0,0}, - {6093,6094,6092 ,5367,5368,5366 ,0,0,0}, {6091,6092,6094 ,5365,5366,5368 ,0,0,0}, - {6093,6095,6096 ,5367,5369,5370 ,0,0,0}, {6096,6094,6093 ,5370,5368,5367 ,0,0,0}, - {6097,6095,6098 ,5371,5369,5372 ,0,0,0}, {6095,6097,6096 ,5369,5371,5370 ,0,0,0}, - {6099,6100,6098 ,5373,5374,5372 ,0,0,0}, {6097,6098,6100 ,5371,5372,5374 ,0,0,0}, - {6099,6101,6102 ,5373,5375,5376 ,0,0,0}, {6102,6100,6099 ,5376,5374,5373 ,0,0,0}, - {6103,6101,6104 ,5377,5375,5378 ,0,0,0}, {6101,6103,6102 ,5375,5377,5376 ,0,0,0}, - {6105,6106,6104 ,5379,5380,5378 ,0,0,0}, {6103,6104,6106 ,5377,5378,5380 ,0,0,0}, - {6105,6107,6108 ,5379,5381,5382 ,0,0,0}, {6108,6106,6105 ,5382,5380,5379 ,0,0,0}, - {6109,6107,6110 ,5383,5381,5384 ,0,0,0}, {6107,6109,6108 ,5381,5383,5382 ,0,0,0}, - {6111,6112,6110 ,5385,5386,5384 ,0,0,0}, {6109,6110,6112 ,5383,5384,5386 ,0,0,0}, - {6111,6113,6114 ,5385,5387,5388 ,0,0,0}, {6114,6112,6111 ,5388,5386,5385 ,0,0,0}, - {6115,6113,6116 ,5389,5387,5390 ,0,0,0}, {6113,6115,6114 ,5387,5389,5388 ,0,0,0}, - {6117,6118,6116 ,5391,5392,5390 ,0,0,0}, {6115,6116,6118 ,5389,5390,5392 ,0,0,0}, - {6117,6119,6120 ,5391,5393,5394 ,0,0,0}, {6120,6118,6117 ,5394,5392,5391 ,0,0,0}, - {6121,6119,6122 ,5395,5393,5396 ,0,0,0}, {6119,6121,6120 ,5393,5395,5394 ,0,0,0}, - {6123,6124,6122 ,5397,5398,5396 ,0,0,0}, {6121,6122,6124 ,5395,5396,5398 ,0,0,0}, - {6123,6125,6126 ,5397,5399,5400 ,0,0,0}, {6126,6124,6123 ,5400,5398,5397 ,0,0,0}, - {6127,6125,6128 ,5401,5399,5402 ,0,0,0}, {6125,6127,6126 ,5399,5401,5400 ,0,0,0}, - {6129,6130,6128 ,5403,5404,5402 ,0,0,0}, {6127,6128,6130 ,5401,5402,5404 ,0,0,0}, - {6129,6131,6132 ,5403,5405,5406 ,0,0,0}, {6132,6130,6129 ,5406,5404,5403 ,0,0,0}, - {6131,6133,6132 ,5405,5407,5406 ,0,0,0}, {6134,6073,6072 ,5408,5347,5346 ,0,0,0}, - {6134,6135,6136 ,5408,5409,5410 ,0,0,0}, {6136,6073,6134 ,5410,5347,5408 ,0,0,0}, - {6137,6135,6138 ,5411,5409,5412 ,0,0,0}, {6135,6137,6136 ,5409,5411,5410 ,0,0,0}, - {6139,6140,6138 ,5413,5414,5412 ,0,0,0}, {6137,6138,6140 ,5411,5412,5414 ,0,0,0}, - {6139,6141,6142 ,5413,5415,5416 ,0,0,0}, {6142,6140,6139 ,5416,5414,5413 ,0,0,0}, - {6143,6141,6144 ,5417,5415,5418 ,0,0,0}, {6141,6143,6142 ,5415,5417,5416 ,0,0,0}, - {6145,6146,6144 ,5419,5420,5418 ,0,0,0}, {6143,6144,6146 ,5417,5418,5420 ,0,0,0}, - {6145,6147,6148 ,5419,5421,5422 ,0,0,0}, {6148,6146,6145 ,5422,5420,5419 ,0,0,0}, - {6149,6147,6150 ,5423,5421,5424 ,0,0,0}, {6147,6149,6148 ,5421,5423,5422 ,0,0,0}, - {6151,6152,6150 ,5425,5426,5424 ,0,0,0}, {6149,6150,6152 ,5423,5424,5426 ,0,0,0}, - {6151,6153,6154 ,5425,5427,5428 ,0,0,0}, {6154,6152,6151 ,5428,5426,5425 ,0,0,0}, - {6155,6153,6156 ,5429,5427,5430 ,0,0,0}, {6153,6155,6154 ,5427,5429,5428 ,0,0,0}, - {6157,6158,6156 ,5431,5432,5430 ,0,0,0}, {6155,6156,6158 ,5429,5430,5432 ,0,0,0}, - {6157,6159,6160 ,5431,5433,5434 ,0,0,0}, {6160,6158,6157 ,5434,5432,5431 ,0,0,0}, - {6161,6159,6162 ,5435,5433,5436 ,0,0,0}, {6159,6161,6160 ,5433,5435,5434 ,0,0,0}, - {6163,6164,6162 ,5437,5438,5436 ,0,0,0}, {6161,6162,6164 ,5435,5436,5438 ,0,0,0}, - {6163,6165,6166 ,5437,5439,5440 ,0,0,0}, {6166,6164,6163 ,5440,5438,5437 ,0,0,0}, - {6167,6165,6168 ,5441,5439,5442 ,0,0,0}, {6165,6167,6166 ,5439,5441,5440 ,0,0,0}, - {6169,6170,6168 ,5443,5444,5442 ,0,0,0}, {6167,6168,6170 ,5441,5442,5444 ,0,0,0}, - {6169,6171,6172 ,5443,5445,5446 ,0,0,0}, {6172,6170,6169 ,5446,5444,5443 ,0,0,0}, - {6173,6171,6174 ,5447,5445,5448 ,0,0,0}, {6171,6173,6172 ,5445,5447,5446 ,0,0,0}, - {6175,6176,6174 ,5449,5450,5448 ,0,0,0}, {6173,6174,6176 ,5447,5448,5450 ,0,0,0}, - {6175,6177,6178 ,5449,5451,5452 ,0,0,0}, {6178,6176,6175 ,5452,5450,5449 ,0,0,0}, - {6179,6177,6180 ,5453,5451,5454 ,0,0,0}, {6177,6179,6178 ,5451,5453,5452 ,0,0,0}, - {6181,6182,6180 ,5455,5456,5454 ,0,0,0}, {6179,6180,6182 ,5453,5454,5456 ,0,0,0}, - {6181,6183,6184 ,5455,5457,5458 ,0,0,0}, {6184,6182,6181 ,5458,5456,5455 ,0,0,0}, - {6185,6183,6186 ,5459,5457,5460 ,0,0,0}, {6183,6185,6184 ,5457,5459,5458 ,0,0,0}, - {6187,6188,6186 ,5461,5462,5460 ,0,0,0}, {6185,6186,6188 ,5459,5460,5462 ,0,0,0}, - {6187,6189,6190 ,5461,5463,5464 ,0,0,0}, {6190,6188,6187 ,5464,5462,5461 ,0,0,0}, - {6191,6189,6192 ,5465,5463,5466 ,0,0,0}, {6189,6191,6190 ,5463,5465,5464 ,0,0,0}, - {6191,6192,6193 ,5465,5466,5467 ,0,0,0}, {6194,5228,5227 ,5468,5469,5469 ,0,0,0}, - {6195,6196,6197 ,726,726,726 ,0,0,0}, {6198,4961,4958 ,726,5470,726 ,0,0,0}, - {6199,6200,6201 ,5471,726,726 ,0,0,0}, {6202,6203,6204 ,726,726,726 ,0,0,0}, - {6205,5183,6206 ,5468,5471,5469 ,0,0,0}, {6207,6208,6209 ,5470,726,726 ,0,0,0}, - {6210,6211,6212 ,5471,5469,5469 ,0,0,0}, {6213,6212,5156 ,5468,5469,5469 ,0,0,0}, - {6214,6215,5262 ,5469,5472,5468 ,0,0,0}, {6216,6217,6218 ,5469,5468,5471 ,0,0,0}, - {6219,6220,6221 ,5473,5474,726 ,0,0,0}, {6222,6223,6224 ,5475,5476,5471 ,0,0,0}, - {6225,6226,6227 ,5477,5478,5469 ,0,0,0}, {6220,6219,6228 ,5474,5473,5479 ,0,0,0}, - {6229,6230,6231 ,5471,5469,726 ,0,0,0}, {6232,6233,5221 ,5468,5469,5471 ,0,0,0}, - {6234,6235,6236 ,726,5480,5481 ,0,0,0}, {6227,6237,6238 ,5469,726,5468 ,0,0,0}, - {6239,6240,6241 ,5475,5475,5482 ,0,0,0}, {6242,4896,6239 ,5468,5483,5475 ,0,0,0}, - {6241,6243,6244 ,5482,5482,5482 ,0,0,0}, {6240,6243,6241 ,5475,5482,5482 ,0,0,0}, - {6244,6245,6241 ,5482,5475,5482 ,0,0,0}, {6236,6230,6246 ,5481,5469,5475 ,0,0,0}, - {6247,5276,6248 ,726,5471,5484 ,0,0,0}, {6220,6228,6238 ,5474,5479,5468 ,0,0,0}, - {6249,6250,6251 ,5475,5485,5468 ,0,0,0}, {6252,6253,6254 ,5486,5483,5468 ,0,0,0}, - {6237,6220,6238 ,726,5474,5468 ,0,0,0}, {5221,6233,5222 ,5471,5469,726 ,0,0,0}, - {5228,6194,5230 ,5469,5468,726 ,0,0,0}, {5234,5233,6255 ,5471,5471,726 ,0,0,0}, - {5262,5232,6214 ,5468,5468,5469 ,0,0,0}, {5260,5232,5262 ,5471,5468,5468 ,0,0,0}, - {5234,6256,5259 ,5471,5471,5469 ,0,0,0}, {6257,5266,5265 ,5468,5478,726 ,0,0,0}, - {5233,6258,6255 ,5471,726,726 ,0,0,0}, {5189,6259,6260 ,5471,5468,726 ,0,0,0}, - {6261,5276,5274 ,5475,5471,726 ,0,0,0}, {6262,6263,6264 ,5469,5482,5483 ,0,0,0}, - {6265,6263,6266 ,5468,5482,5475 ,0,0,0}, {6267,6268,6269 ,726,5468,5468 ,0,0,0}, - {6270,6218,6271 ,726,5471,5469 ,0,0,0}, {6272,6273,6274 ,5475,5475,726 ,0,0,0}, - {6268,6267,6275 ,5468,726,5483 ,0,0,0}, {6276,6277,6278 ,5480,5487,5475 ,0,0,0}, - {6275,6279,6262 ,5483,5478,5469 ,0,0,0}, {6280,6281,6282 ,5475,5479,5474 ,0,0,0}, - {6282,6248,6280 ,5474,5484,5475 ,0,0,0}, {6283,6284,6282 ,5473,726,5474 ,0,0,0}, - {6283,6282,6281 ,5473,5474,5479 ,0,0,0}, {6265,6264,6263 ,5468,5483,5482 ,0,0,0}, - {6277,6272,6285 ,5487,5475,726 ,0,0,0}, {6263,6262,6279 ,5482,5469,5478 ,0,0,0}, - {6286,6287,6247 ,5486,5478,726 ,0,0,0}, {6270,6271,6269 ,726,5469,5468 ,0,0,0}, - {5186,6259,5189 ,726,5468,5471 ,0,0,0}, {6280,6248,5276 ,5475,5484,5471 ,0,0,0}, - {6288,6289,6290 ,726,726,726 ,0,0,0}, {6291,6292,5192 ,5468,5469,726 ,0,0,0}, - {6261,5274,6293 ,5475,726,5482 ,0,0,0}, {6294,5198,6295 ,726,726,5470 ,0,0,0}, - {5271,6296,6297 ,5475,5485,5475 ,0,0,0}, {6298,6299,5116 ,5471,726,5471 ,0,0,0}, - {5020,6300,5015 ,726,5470,726 ,0,0,0}, {6301,6302,6303 ,5470,5471,5471 ,0,0,0}, - {6304,6305,6306 ,726,726,5470 ,0,0,0}, {6306,6207,6304 ,5470,5470,726 ,0,0,0}, - {6288,6209,6289 ,726,726,726 ,0,0,0}, {6307,6308,6309 ,726,726,5470 ,0,0,0}, - {6201,6301,6303 ,726,5470,5471 ,0,0,0}, {6305,6310,6311 ,726,726,726 ,0,0,0}, - {5200,6312,6313 ,726,5470,726 ,0,0,0}, {6314,6315,6316 ,5470,726,726 ,0,0,0}, - {6289,6209,6208 ,726,726,726 ,0,0,0}, {6312,6317,6318 ,5470,726,5468 ,0,0,0}, - {6289,6319,6290 ,726,726,726 ,0,0,0}, {6318,6320,6321 ,5468,5468,726 ,0,0,0}, - {6317,6320,6318 ,726,5468,5468 ,0,0,0}, {6321,6322,6318 ,726,5471,5468 ,0,0,0}, - {6323,6324,6325 ,726,726,5471 ,0,0,0}, {5200,6317,6312 ,726,726,5470 ,0,0,0}, - {6313,6326,6327 ,726,726,726 ,0,0,0}, {6328,6329,6330 ,726,5488,5489 ,0,0,0}, - {5158,6331,6332 ,5471,5470,726 ,0,0,0}, {5186,6212,6259 ,726,5469,5468 ,0,0,0}, - {6333,5113,5110 ,726,726,5471 ,0,0,0}, {6334,5037,5034 ,726,726,726 ,0,0,0}, - {6335,4970,6336 ,726,5470,726 ,0,0,0}, {6337,5113,6333 ,726,726,726 ,0,0,0}, - {6338,6339,6340 ,726,726,726 ,0,0,0}, {6341,6342,6343 ,5489,726,726 ,0,0,0}, - {5107,6344,5108 ,726,5471,726 ,0,0,0}, {6345,6339,6346 ,726,726,726 ,0,0,0}, - {6347,6348,6349 ,726,726,5489 ,0,0,0}, {6350,6351,6352 ,726,726,726 ,0,0,0}, - {6353,6339,6345 ,726,726,726 ,0,0,0}, {6195,6197,6352 ,726,726,726 ,0,0,0}, - {6354,6355,6356 ,726,726,5489 ,0,0,0}, {6196,6338,6340 ,726,726,726 ,0,0,0}, - {6357,6358,6359 ,726,726,726 ,0,0,0}, {6355,6360,6357 ,726,5488,726 ,0,0,0}, - {6353,6340,6339 ,726,726,726 ,0,0,0}, {6204,6341,5124 ,726,5489,726 ,0,0,0}, - {6361,6362,6363 ,5489,726,726 ,0,0,0}, {6361,6364,6362 ,5489,5488,726 ,0,0,0}, - {6365,6366,6367 ,726,5471,726 ,0,0,0}, {6362,6364,6368 ,726,5488,726 ,0,0,0}, - {6369,6362,6368 ,726,726,726 ,0,0,0}, {6370,5082,6371 ,726,726,726 ,0,0,0}, - {5040,6372,6373 ,726,726,726 ,0,0,0}, {5198,5196,6295 ,726,726,5470 ,0,0,0}, - {6204,5120,6374 ,726,726,726 ,0,0,0}, {6366,6375,6376 ,5471,5471,726 ,0,0,0}, - {6377,4938,6378 ,726,5470,726 ,0,0,0}, {6367,6379,6365 ,726,5471,726 ,0,0,0}, - {5048,6380,6381 ,5489,726,726 ,0,0,0}, {6382,6383,6384 ,726,726,726 ,0,0,0}, - {6385,6386,6384 ,726,5471,726 ,0,0,0}, {6349,6348,6387 ,5489,726,5488 ,0,0,0}, - {6334,6388,5037 ,726,726,726 ,0,0,0}, {6342,6204,6363 ,726,726,726 ,0,0,0}, - {6389,6334,6387 ,726,726,5488 ,0,0,0}, {4964,6390,6391 ,726,5471,726 ,0,0,0}, - {6392,6393,6383 ,726,5488,726 ,0,0,0}, {6384,6394,6395 ,726,5471,726 ,0,0,0}, - {6396,6397,6398 ,726,726,5488 ,0,0,0}, {6399,6400,6396 ,726,726,726 ,0,0,0}, - {6401,6400,6402 ,726,726,726 ,0,0,0}, {6403,5048,6381 ,726,5489,726 ,0,0,0}, - {6404,6384,6405 ,726,726,726 ,0,0,0}, {6381,6380,6406 ,726,726,726 ,0,0,0}, - {6383,6407,6392 ,726,726,726 ,0,0,0}, {6408,6406,6380 ,726,726,726 ,0,0,0}, - {6383,6393,6384 ,726,5488,726 ,0,0,0}, {6408,6409,6406 ,726,5488,726 ,0,0,0}, - {6410,6407,6383 ,726,726,726 ,0,0,0}, {6406,6409,6411 ,726,5488,726 ,0,0,0}, - {6384,6412,6394 ,726,726,5471 ,0,0,0}, {5243,6413,5242 ,5469,5468,5468 ,0,0,0}, - {5243,5248,6414 ,5469,726,726 ,0,0,0}, {6415,4955,6416 ,726,5471,5471 ,0,0,0}, - {6417,4862,6418 ,5470,5468,5468 ,0,0,0}, {4972,6419,6420 ,5470,726,726 ,0,0,0}, - {6421,6422,6423 ,5468,726,5469 ,0,0,0}, {6424,6425,6426 ,5471,5468,726 ,0,0,0}, - {6427,6421,6428 ,5468,5468,726 ,0,0,0}, {6429,6430,6431 ,726,5470,5469 ,0,0,0}, - {6432,6433,6434 ,726,5469,726 ,0,0,0}, {6435,6436,6437 ,5471,5469,726 ,0,0,0}, - {6438,5259,6439 ,726,5469,5470 ,0,0,0}, {6403,6440,6441 ,726,5489,726 ,0,0,0}, - {6384,6386,6442 ,726,5471,726 ,0,0,0}, {6443,5146,5145 ,5468,726,5469 ,0,0,0}, - {6444,6445,6334 ,5470,5471,726 ,0,0,0}, {6198,6446,4961 ,726,726,5470 ,0,0,0}, - {6447,5006,5005 ,5471,726,726 ,0,0,0}, {6448,5248,5246 ,726,726,5468 ,0,0,0}, - {6449,6450,6451 ,726,5470,5471 ,0,0,0}, {6452,6453,6454 ,5471,726,5470 ,0,0,0}, - {6455,6456,6457 ,726,5470,726 ,0,0,0}, {6419,6458,6420 ,726,726,726 ,0,0,0}, - {6458,6419,6459 ,726,726,726 ,0,0,0}, {6420,6450,4972 ,726,5470,5470 ,0,0,0}, - {6458,6459,6460 ,726,726,726 ,0,0,0}, {6432,6426,6425 ,726,726,5468 ,0,0,0}, - {6458,6460,6461 ,726,726,726 ,0,0,0}, {6462,6463,6464 ,5471,5471,5468 ,0,0,0}, - {6430,6437,6431 ,5470,726,5469 ,0,0,0}, {6465,6429,6466 ,726,726,726 ,0,0,0}, - {6467,6468,6436 ,5468,5469,5469 ,0,0,0}, {6436,6435,6467 ,5469,5471,5468 ,0,0,0}, - {6469,6470,6467 ,5471,726,5468 ,0,0,0}, {6467,6470,6468 ,5468,726,5469 ,0,0,0}, - {5266,6471,5268 ,5478,5487,5468 ,0,0,0}, {5200,5198,6294 ,726,726,726 ,0,0,0}, - {6293,5274,5272 ,5482,726,5468 ,0,0,0}, {6292,5195,5192 ,5469,726,726 ,0,0,0}, - {6213,6210,6212 ,5468,5471,5469 ,0,0,0}, {6472,6211,6210 ,5468,5469,5471 ,0,0,0}, - {6217,6216,6473 ,5468,5469,5469 ,0,0,0}, {6211,6472,6474 ,5469,5468,5470 ,0,0,0}, - {6216,6218,6270 ,5469,5471,726 ,0,0,0}, {6473,6474,6475 ,5469,5470,5469 ,0,0,0}, - {6269,6271,6267 ,5468,5469,726 ,0,0,0}, {6275,6262,6268 ,5483,5469,5468 ,0,0,0}, - {6273,6279,6274 ,5475,5478,726 ,0,0,0}, {6279,6275,6274 ,5478,5483,726 ,0,0,0}, - {6286,6276,6287 ,5486,5480,5478 ,0,0,0}, {6277,6273,6272 ,5487,5475,5475 ,0,0,0}, - {6276,6278,6287 ,5480,5475,5478 ,0,0,0}, {6278,6277,6285 ,5475,5487,726 ,0,0,0}, - {6248,6286,6247 ,5484,5486,726 ,0,0,0}, {6261,6280,5276 ,5475,5475,5471 ,0,0,0}, - {6293,5272,6297 ,5482,5468,5475 ,0,0,0}, {6297,5272,5271 ,5475,5468,5475 ,0,0,0}, - {5268,6471,6296 ,5468,5487,5485 ,0,0,0}, {6296,5271,5268 ,5485,5475,5468 ,0,0,0}, - {6257,6471,5266 ,5468,5487,5478 ,0,0,0}, {6215,6257,5265 ,5472,5468,726 ,0,0,0}, - {6439,5259,6256 ,5470,5469,5471 ,0,0,0}, {5262,6215,5265 ,5468,5472,726 ,0,0,0}, - {6476,6477,5242 ,5471,5470,5468 ,0,0,0}, {5239,6477,6478 ,726,5470,726 ,0,0,0}, - {6224,6479,6222 ,5471,5468,5475 ,0,0,0}, {6233,6480,5222 ,5469,5469,726 ,0,0,0}, - {6481,6482,6242 ,5472,5482,5468 ,0,0,0}, {5205,4874,5201 ,5468,5468,5468 ,0,0,0}, - {4882,4880,6421 ,5471,726,5468 ,0,0,0}, {5137,4784,5135 ,5471,726,5469 ,0,0,0}, - {5148,6483,5151 ,5471,726,726 ,0,0,0}, {6333,5110,6199 ,726,5471,5471 ,0,0,0}, - {4804,6484,6485 ,726,726,5470 ,0,0,0}, {6486,6487,5046 ,726,726,726 ,0,0,0}, - {6488,5166,6489 ,726,726,5471 ,0,0,0}, {4781,6490,4778 ,5471,5471,5471 ,0,0,0}, - {4793,6491,6492 ,726,5469,5469 ,0,0,0}, {5132,5245,5251 ,5471,5469,5469 ,0,0,0}, - {5239,5242,6477 ,726,5468,5470 ,0,0,0}, {5255,5133,5251 ,5468,726,5469 ,0,0,0}, - {5245,4789,5246 ,5469,5471,5468 ,0,0,0}, {6448,6414,5248 ,726,726,726 ,0,0,0}, - {6414,6413,5243 ,726,5468,5469 ,0,0,0}, {6413,6476,5242 ,5468,5471,5468 ,0,0,0}, - {5236,5239,6478 ,726,726,726 ,0,0,0}, {5232,5260,6438 ,5468,5471,726 ,0,0,0}, - {5236,6258,5233 ,726,726,5471 ,0,0,0}, {6258,5236,6478 ,726,726,726 ,0,0,0}, - {6255,6256,5234 ,726,5471,5471 ,0,0,0}, {5259,6438,5260 ,5469,726,5471 ,0,0,0}, - {5230,6493,5232 ,726,5468,5468 ,0,0,0}, {6223,6214,6494 ,5476,5469,5468 ,0,0,0}, - {6493,6214,5232 ,5468,5469,5468 ,0,0,0}, {5222,6480,5224 ,726,5469,5470 ,0,0,0}, - {5227,5224,6495 ,5469,5470,726 ,0,0,0}, {6480,6495,5224 ,5469,726,5470 ,0,0,0}, - {6226,6225,6250 ,5478,5477,5485 ,0,0,0}, {5202,4874,6232 ,726,5468,5468 ,0,0,0}, - {5202,6232,5221 ,726,5468,5471 ,0,0,0}, {6496,6497,4894 ,5470,5470,5468 ,0,0,0}, - {4896,6240,6239 ,5483,5475,5475 ,0,0,0}, {6498,4880,4879 ,5468,726,5468 ,0,0,0}, - {6499,4854,6500 ,5469,5468,5471 ,0,0,0}, {4968,6336,4970 ,726,726,5470 ,0,0,0}, - {6501,6502,4930 ,5471,5471,5471 ,0,0,0}, {6503,5018,6504 ,726,726,5471 ,0,0,0}, - {6505,6506,6507 ,5471,5470,5471 ,0,0,0}, {5014,5015,6508 ,726,726,726 ,0,0,0}, - {4958,6375,6198 ,726,5471,726 ,0,0,0}, {6388,6334,6509 ,726,726,726 ,0,0,0}, - {5254,6510,5126 ,726,5468,5469 ,0,0,0}, {5151,6511,5152 ,726,726,5468 ,0,0,0}, - {5120,6204,5122 ,726,726,726 ,0,0,0}, {6299,5119,5116 ,726,5471,5471 ,0,0,0}, - {5080,6200,6199 ,726,726,5471 ,0,0,0}, {6201,6200,6301 ,726,726,5470 ,0,0,0}, - {6310,6323,6311 ,726,726,726 ,0,0,0}, {6325,6512,6302 ,5471,726,5471 ,0,0,0}, - {6303,6302,6512 ,5471,5471,726 ,0,0,0}, {6324,6323,6310 ,726,726,726 ,0,0,0}, - {6324,6512,6325 ,726,726,5471 ,0,0,0}, {6311,6306,6305 ,726,5470,726 ,0,0,0}, - {6207,6209,6304 ,5470,726,726 ,0,0,0}, {6308,6208,6309 ,726,726,5470 ,0,0,0}, - {6208,6207,6309 ,726,5470,5470 ,0,0,0}, {6315,6327,6326 ,726,726,726 ,0,0,0}, - {6307,6316,6513 ,726,726,5471 ,0,0,0}, {6513,6308,6307 ,5471,726,726 ,0,0,0}, - {6315,6314,6327 ,726,5470,726 ,0,0,0}, {6316,6315,6513 ,726,726,5471 ,0,0,0}, - {6312,6326,6313 ,5470,726,726 ,0,0,0}, {6294,6317,5200 ,726,726,726 ,0,0,0}, - {5186,5184,6212 ,726,726,5469 ,0,0,0}, {6295,5196,6514 ,5470,726,5470 ,0,0,0}, - {5195,6292,6514 ,726,5469,5470 ,0,0,0}, {6514,5196,5195 ,5470,726,726 ,0,0,0}, - {6291,5190,6260 ,5468,726,726 ,0,0,0}, {5190,6291,5192 ,726,5468,726 ,0,0,0}, - {5189,6260,5190 ,5471,726,726 ,0,0,0}, {6332,5183,5158 ,726,5471,5471 ,0,0,0}, - {5158,5157,6331 ,5471,5471,5470 ,0,0,0}, {6206,5183,6332 ,5469,5471,726 ,0,0,0}, - {6515,6516,5160 ,5470,5470,726 ,0,0,0}, {6488,5163,5166 ,726,5470,726 ,0,0,0}, - {6516,5157,5160 ,5470,5471,726 ,0,0,0}, {5167,5172,6517 ,726,726,726 ,0,0,0}, - {5167,6518,5166 ,726,5470,726 ,0,0,0}, {6519,5172,5170 ,726,726,5470 ,0,0,0}, - {5059,5061,4798 ,726,726,726 ,0,0,0}, {5175,5056,5169 ,726,726,5471 ,0,0,0}, - {5072,6520,5075 ,726,726,5470 ,0,0,0}, {5146,6521,5148 ,726,5471,5471 ,0,0,0}, - {6522,4904,4907 ,5471,5470,726 ,0,0,0}, {6523,4777,6524 ,726,726,5470 ,0,0,0}, - {5094,4808,6525 ,5471,5470,5470 ,0,0,0}, {6526,6527,5090 ,726,5471,726 ,0,0,0}, - {4784,5137,4783 ,726,5471,726 ,0,0,0}, {5255,5254,5129 ,5468,726,5471 ,0,0,0}, - {5179,5057,5175 ,5470,5471,726 ,0,0,0}, {5070,5069,6528 ,726,726,726 ,0,0,0}, - {4797,4771,5169 ,5470,5471,5471 ,0,0,0}, {6519,6517,5172 ,726,726,726 ,0,0,0}, - {6517,6518,5167 ,726,5470,726 ,0,0,0}, {6518,6489,5166 ,5470,5471,726 ,0,0,0}, - {5163,6515,5160 ,5470,5470,726 ,0,0,0}, {6515,5163,6488 ,5470,5470,726 ,0,0,0}, - {6213,5156,5154 ,5468,5469,726 ,0,0,0}, {6516,6331,5157 ,5470,5470,5471 ,0,0,0}, - {5184,5156,6212 ,726,5469,5469 ,0,0,0}, {6205,5184,5183 ,5468,726,5471 ,0,0,0}, - {6205,5156,5184 ,5468,5469,726 ,0,0,0}, {5154,5152,6511 ,726,5468,726 ,0,0,0}, - {5154,6511,6213 ,726,726,5468 ,0,0,0}, {5151,6483,6511 ,726,726,726 ,0,0,0}, - {5148,6521,6483 ,5471,5471,726 ,0,0,0}, {5145,6510,6443 ,5469,5468,5468 ,0,0,0}, - {5146,6443,6521 ,726,5468,5471 ,0,0,0}, {5126,5125,5254 ,5469,5468,726 ,0,0,0}, - {5145,5126,6510 ,5469,5469,5468 ,0,0,0}, {5129,5133,5255 ,5471,726,5468 ,0,0,0}, - {5125,5129,5254 ,5468,5471,726 ,0,0,0}, {5133,5132,5251 ,726,5471,5469 ,0,0,0}, - {4784,4787,5135 ,726,726,5469 ,0,0,0}, {4783,5137,5139 ,726,5471,5470 ,0,0,0}, - {6490,6524,4778 ,5471,5470,5471 ,0,0,0}, {4781,4783,5139 ,5471,726,5470 ,0,0,0}, - {6523,6519,4775 ,726,726,5470 ,0,0,0}, {5178,6529,5050 ,5470,5470,726 ,0,0,0}, - {5075,6530,5076 ,5470,5470,5470 ,0,0,0}, {6487,5048,5046 ,726,5489,726 ,0,0,0}, - {6373,5043,5040 ,726,726,726 ,0,0,0}, {6531,6387,6334 ,5489,5488,726 ,0,0,0}, - {6387,6531,6349 ,5488,5489,5489 ,0,0,0}, {6350,6328,6351 ,726,726,726 ,0,0,0}, - {6330,6532,6347 ,5489,726,726 ,0,0,0}, {6348,6347,6532 ,726,726,726 ,0,0,0}, - {6329,6328,6350 ,5488,726,726 ,0,0,0}, {6329,6532,6330 ,5488,726,5489 ,0,0,0}, - {6351,6195,6352 ,726,726,726 ,0,0,0}, {6196,6340,6197 ,726,726,726 ,0,0,0}, - {6356,6338,6354 ,5489,726,726 ,0,0,0}, {6338,6196,6354 ,726,726,726 ,0,0,0}, - {6342,6359,6343 ,726,726,726 ,0,0,0}, {6357,6356,6355 ,726,5489,726 ,0,0,0}, - {6359,6358,6343 ,726,726,726 ,0,0,0}, {6358,6357,6360 ,726,726,5488 ,0,0,0}, - {6342,6341,6204 ,726,5489,726 ,0,0,0}, {6363,6204,6361 ,726,726,5489 ,0,0,0}, - {5110,5108,6199 ,5471,726,5471 ,0,0,0}, {6204,6374,6202 ,726,726,726 ,0,0,0}, - {5119,6299,6374 ,5471,726,726 ,0,0,0}, {6374,5120,5119 ,726,726,5471 ,0,0,0}, - {6298,5114,6337 ,5471,726,726 ,0,0,0}, {5114,6298,5116 ,726,5471,5471 ,0,0,0}, - {5113,6337,5114 ,726,726,726 ,0,0,0}, {6533,5082,6370 ,5471,726,726 ,0,0,0}, - {5082,5081,6371 ,726,726,726 ,0,0,0}, {5107,5082,6533 ,726,726,5471 ,0,0,0}, - {6534,6535,5084 ,726,726,726 ,0,0,0}, {6527,5087,5090 ,5471,726,726 ,0,0,0}, - {6535,5081,5084 ,726,726,726 ,0,0,0}, {5091,5096,6536 ,726,726,726 ,0,0,0}, - {5091,6537,5090 ,726,5471,726 ,0,0,0}, {6525,5096,5094 ,5470,726,5471 ,0,0,0}, - {4813,4980,4983 ,5471,5471,726 ,0,0,0}, {5099,4980,5093 ,726,5471,726 ,0,0,0}, - {6538,4808,4807 ,5471,5470,726 ,0,0,0}, {5072,5070,6539 ,726,726,726 ,0,0,0}, - {4813,4810,5093 ,5471,726,726 ,0,0,0}, {4994,6540,4996 ,726,5470,726 ,0,0,0}, - {4901,5027,5026 ,5470,726,726 ,0,0,0}, {5014,6541,5011 ,726,726,5471 ,0,0,0}, - {5061,4801,4798 ,726,726,726 ,0,0,0}, {5179,5178,5053 ,5470,5470,726 ,0,0,0}, - {5103,4981,5099 ,5471,726,726 ,0,0,0}, {6503,5020,5018 ,726,726,726 ,0,0,0}, - {5093,4810,5094 ,726,726,5471 ,0,0,0}, {6525,6536,5096 ,5470,726,726 ,0,0,0}, - {6536,6537,5091 ,726,5471,726 ,0,0,0}, {6537,6526,5090 ,5471,726,726 ,0,0,0}, - {5087,6534,5084 ,726,726,726 ,0,0,0}, {6534,5087,6527 ,726,726,5471 ,0,0,0}, - {6542,5080,5078 ,5470,726,726 ,0,0,0}, {6535,6371,5081 ,726,726,726 ,0,0,0}, - {5108,5080,6199 ,726,726,5471 ,0,0,0}, {5080,5108,6344 ,726,726,5471 ,0,0,0}, - {6533,6344,5107 ,5471,5471,726 ,0,0,0}, {5080,6542,6200 ,726,5470,726 ,0,0,0}, - {5078,5076,6530 ,726,5470,5470 ,0,0,0}, {5078,6530,6542 ,726,5470,5470 ,0,0,0}, - {5075,6520,6530 ,5470,726,5470 ,0,0,0}, {5072,6539,6520 ,726,726,726 ,0,0,0}, - {5069,6529,6528 ,726,5470,726 ,0,0,0}, {5070,6528,6539 ,726,726,726 ,0,0,0}, - {5050,5049,5178 ,726,5470,5470 ,0,0,0}, {5069,5050,6529 ,726,726,5470 ,0,0,0}, - {5053,5057,5179 ,726,5471,5470 ,0,0,0}, {5049,5053,5178 ,5470,726,5470 ,0,0,0}, - {5057,5056,5175 ,5471,726,726 ,0,0,0}, {4798,4797,5059 ,726,5470,726 ,0,0,0}, - {4801,5063,4802 ,726,726,5471 ,0,0,0}, {4804,4802,6484 ,726,5471,726 ,0,0,0}, - {5061,5063,4801 ,726,726,726 ,0,0,0}, {6525,4808,6538 ,5470,5470,5471 ,0,0,0}, - {5044,6486,5046 ,5488,726,726 ,0,0,0}, {5246,4791,6448 ,5468,5470,726 ,0,0,0}, - {4970,6335,4972 ,5470,726,5470 ,0,0,0}, {6391,4967,4964 ,726,726,726 ,0,0,0}, - {6375,6543,6376 ,5471,726,726 ,0,0,0}, {6366,6376,6367 ,5471,726,726 ,0,0,0}, - {6412,6544,6379 ,726,5471,5471 ,0,0,0}, {6365,6379,6544 ,726,5471,5471 ,0,0,0}, - {6384,6442,6412 ,726,726,726 ,0,0,0}, {6442,6544,6412 ,726,5471,726 ,0,0,0}, - {6395,6405,6384 ,726,726,726 ,0,0,0}, {6545,6385,6384 ,726,726,726 ,0,0,0}, - {6382,6384,6397 ,726,726,726 ,0,0,0}, {6398,6397,6384 ,5488,726,726 ,0,0,0}, - {6440,6401,6441 ,5489,726,726 ,0,0,0}, {6400,6397,6396 ,726,726,726 ,0,0,0}, - {6401,6402,6441 ,726,726,726 ,0,0,0}, {6402,6400,6399 ,726,726,726 ,0,0,0}, - {6381,6440,6403 ,726,5489,726 ,0,0,0}, {6487,6380,5048 ,726,726,5489 ,0,0,0}, - {5032,5031,6334 ,726,5471,726 ,0,0,0}, {5043,6546,5044 ,726,726,5488 ,0,0,0}, - {6486,5044,6546 ,726,5488,726 ,0,0,0}, {6372,5038,6388 ,726,726,726 ,0,0,0}, - {6373,6546,5043 ,726,726,726 ,0,0,0}, {5038,6372,5040 ,726,726,726 ,0,0,0}, - {5037,6388,5038 ,726,726,726 ,0,0,0}, {6444,6334,6547 ,5470,726,5471 ,0,0,0}, - {6547,5006,6447 ,5471,726,5471 ,0,0,0}, {6547,6334,5006 ,5471,726,726 ,0,0,0}, - {5008,6548,5005 ,5471,726,726 ,0,0,0}, {5014,6549,6541 ,726,726,726 ,0,0,0}, - {5008,6550,6548 ,5471,726,726 ,0,0,0}, {6551,4999,4996 ,5471,726,726 ,0,0,0}, - {4999,6552,5000 ,726,726,726 ,0,0,0}, {6553,4994,4993 ,726,726,5471 ,0,0,0}, - {5102,6554,4974 ,5471,5471,5471 ,0,0,0}, {4977,5103,5102 ,726,5471,5471 ,0,0,0}, - {4813,5093,4980 ,5471,726,5471 ,0,0,0}, {6555,6556,6557 ,5470,726,726 ,0,0,0}, - {6558,4820,4990 ,726,5470,5471 ,0,0,0}, {5026,6559,4898 ,726,726,726 ,0,0,0}, - {6560,4924,4923 ,5471,5470,5471 ,0,0,0}, {4923,4920,6561 ,5471,726,726 ,0,0,0}, - {5023,4904,5017 ,726,5470,726 ,0,0,0}, {4816,4983,4985 ,5471,726,726 ,0,0,0}, - {5027,4905,5023 ,726,5471,726 ,0,0,0}, {4917,6562,4918 ,726,726,5471 ,0,0,0}, - {5017,6563,5018 ,726,726,726 ,0,0,0}, {6503,6300,5020 ,726,5470,726 ,0,0,0}, - {6300,6508,5015 ,5470,726,726 ,0,0,0}, {6508,6549,5014 ,726,726,726 ,0,0,0}, - {5011,6550,5008 ,5471,726,5471 ,0,0,0}, {6550,5011,6541 ,726,5471,726 ,0,0,0}, - {6552,6564,5002 ,726,726,726 ,0,0,0}, {5002,6564,6334 ,726,726,726 ,0,0,0}, - {6548,6447,5005 ,726,5471,726 ,0,0,0}, {5034,5032,6334 ,726,726,726 ,0,0,0}, - {6334,5031,5006 ,726,5471,726 ,0,0,0}, {5004,6334,6445 ,5471,726,5471 ,0,0,0}, - {6564,6531,6334 ,726,5489,726 ,0,0,0}, {5002,5000,6552 ,726,726,726 ,0,0,0}, - {4999,6551,6552 ,726,5471,726 ,0,0,0}, {4996,6540,6551 ,726,5470,5471 ,0,0,0}, - {4993,6554,6553 ,5471,5471,726 ,0,0,0}, {4994,6553,6540 ,726,726,5470 ,0,0,0}, - {4974,4973,5102 ,5471,726,5471 ,0,0,0}, {4993,4974,6554 ,5471,5471,5471 ,0,0,0}, - {4977,4981,5103 ,726,726,5471 ,0,0,0}, {4973,4977,5102 ,726,726,5471 ,0,0,0}, - {4981,4980,5099 ,726,5471,726 ,0,0,0}, {4816,4813,4983 ,5471,5471,726 ,0,0,0}, - {4816,4985,4819 ,5471,726,726 ,0,0,0}, {4987,4820,4819 ,726,5470,726 ,0,0,0}, - {4987,4819,4985 ,726,726,726 ,0,0,0}, {4987,4990,4820 ,726,5471,5470 ,0,0,0}, - {6565,4863,4868 ,5468,5469,5470 ,0,0,0}, {6421,6433,6428 ,5468,5469,726 ,0,0,0}, - {5208,4871,5209 ,5468,5471,5469 ,0,0,0}, {4891,4888,6421 ,5469,5471,5468 ,0,0,0}, - {4852,6434,6433 ,5469,726,5469 ,0,0,0}, {6432,6434,6426 ,726,726,726 ,0,0,0}, - {6466,6463,6465 ,726,5471,726 ,0,0,0}, {6462,6566,6424 ,5471,5468,5471 ,0,0,0}, - {6425,6424,6566 ,5468,5471,5468 ,0,0,0}, {6464,6463,6466 ,5468,5471,726 ,0,0,0}, - {6464,6566,6462 ,5468,5468,5471 ,0,0,0}, {6465,6430,6429 ,726,5470,726 ,0,0,0}, - {6437,6436,6431 ,726,5469,5469 ,0,0,0}, {6456,6435,6457 ,5470,5471,726 ,0,0,0}, - {6435,6437,6457 ,5471,726,726 ,0,0,0}, {6453,6449,6451 ,726,726,5471 ,0,0,0}, - {6455,6454,6567 ,726,5470,726 ,0,0,0}, {6567,6456,6455 ,726,5470,726 ,0,0,0}, - {6453,6452,6449 ,726,5471,726 ,0,0,0}, {6454,6453,6567 ,5470,726,726 ,0,0,0}, - {6420,6451,6450 ,726,5471,5470 ,0,0,0}, {6335,6419,4972 ,726,726,5470 ,0,0,0}, - {4958,4956,6375 ,726,5470,5471 ,0,0,0}, {4967,6568,4968 ,726,726,726 ,0,0,0}, - {6336,4968,6568 ,726,726,726 ,0,0,0}, {6390,4962,6446 ,5471,5470,726 ,0,0,0}, - {6391,6568,4967 ,726,726,726 ,0,0,0}, {4962,6390,4964 ,5470,5471,726 ,0,0,0}, - {4961,6446,4962 ,5470,726,5470 ,0,0,0}, {6502,4955,4930 ,5471,5471,5471 ,0,0,0}, - {4930,4929,6501 ,5471,726,5471 ,0,0,0}, {6416,4955,6502 ,5471,5471,5471 ,0,0,0}, - {6569,6570,4932 ,5471,726,726 ,0,0,0}, {6377,4935,4938 ,726,5470,5470 ,0,0,0}, - {6570,4929,4932 ,726,726,726 ,0,0,0}, {4939,4944,6571 ,5470,726,726 ,0,0,0}, - {4939,6572,4938 ,5470,726,5470 ,0,0,0}, {6573,4944,4942 ,726,726,726 ,0,0,0}, - {4831,4833,6574 ,726,5471,5471 ,0,0,0}, {4918,6575,4920 ,5471,726,726 ,0,0,0}, - {6576,6577,6578 ,5471,726,726 ,0,0,0}, {4866,6576,6579 ,5471,5471,5471 ,0,0,0}, - {6448,4791,6580 ,726,5470,5469 ,0,0,0}, {5208,5211,6581 ,5468,5468,5470 ,0,0,0}, - {4847,6582,4848 ,726,726,5471 ,0,0,0}, {4866,6579,4868 ,5471,5471,5470 ,0,0,0}, - {4947,4828,4941 ,726,5470,5470 ,0,0,0}, {4909,6583,6584 ,5470,5471,726 ,0,0,0}, - {4951,4829,4947 ,726,5471,726 ,0,0,0}, {6585,6574,4833 ,5471,5471,5471 ,0,0,0}, - {6586,6587,4941 ,726,5471,5470 ,0,0,0}, {6573,6571,4944 ,726,726,726 ,0,0,0}, - {6571,6572,4939 ,726,726,5470 ,0,0,0}, {6572,6378,4938 ,726,726,5470 ,0,0,0}, - {4935,6569,4932 ,5470,5471,726 ,0,0,0}, {6569,4935,6377 ,5471,5470,726 ,0,0,0}, - {4926,6560,6543 ,5471,5471,726 ,0,0,0}, {6543,4928,4926 ,726,726,5471 ,0,0,0}, - {6570,6501,4929 ,726,5471,726 ,0,0,0}, {4956,4928,6375 ,5470,726,5471 ,0,0,0}, - {6415,4956,4955 ,726,5470,5471 ,0,0,0}, {6415,4928,4956 ,726,726,5470 ,0,0,0}, - {6375,4928,6543 ,5471,726,726 ,0,0,0}, {4926,4924,6560 ,5471,5470,5471 ,0,0,0}, - {4923,6561,6560 ,5471,726,5471 ,0,0,0}, {4920,6575,6561 ,726,726,726 ,0,0,0}, - {4917,6559,6562 ,726,726,726 ,0,0,0}, {4918,6562,6575 ,5471,726,726 ,0,0,0}, - {4898,4897,5026 ,726,5471,726 ,0,0,0}, {4917,4898,6559 ,726,726,726 ,0,0,0}, - {4901,4905,5027 ,5470,5471,726 ,0,0,0}, {4897,4901,5026 ,5471,5470,726 ,0,0,0}, - {4905,4904,5023 ,5471,5470,726 ,0,0,0}, {6584,6522,4907 ,726,5471,726 ,0,0,0}, - {5017,4904,6522 ,726,5470,5471 ,0,0,0}, {4914,6588,6589 ,726,726,726 ,0,0,0}, - {6583,4911,6589 ,5471,726,726 ,0,0,0}, {6590,6591,6592 ,5470,5470,5471 ,0,0,0}, - {4894,6497,4896 ,5468,5470,5483 ,0,0,0}, {5202,5201,4874 ,726,5468,5468 ,0,0,0}, - {4894,4892,6496 ,5468,5469,5470 ,0,0,0}, {5230,6194,6493 ,726,5468,5468 ,0,0,0}, - {5227,6495,6194 ,5469,726,5468 ,0,0,0}, {6493,6494,6214 ,5468,5468,5469 ,0,0,0}, - {6223,6494,6224 ,5476,5468,5471 ,0,0,0}, {6251,6254,6249 ,5468,5468,5475 ,0,0,0}, - {6253,6593,6479 ,5483,726,5468 ,0,0,0}, {6222,6479,6593 ,5475,5468,726 ,0,0,0}, - {6252,6254,6251 ,5486,5468,5468 ,0,0,0}, {6252,6593,6253 ,5486,726,5483 ,0,0,0}, - {6249,6226,6250 ,5475,5478,5485 ,0,0,0}, {6227,6238,6225 ,5469,5468,5477 ,0,0,0}, - {6231,6237,6229 ,726,726,5471 ,0,0,0}, {6237,6227,6229 ,726,5469,5471 ,0,0,0}, - {6481,6235,6482 ,5472,5480,5482 ,0,0,0}, {6236,6231,6230 ,5481,726,5469 ,0,0,0}, - {6235,6234,6482 ,5480,726,5482 ,0,0,0}, {6234,6236,6246 ,726,5481,5475 ,0,0,0}, - {6239,6481,6242 ,5475,5472,5468 ,0,0,0}, {6497,6240,4896 ,5470,5475,5483 ,0,0,0}, - {6421,4880,6498 ,5468,726,5468 ,0,0,0}, {4891,6423,4892 ,5469,5469,5469 ,0,0,0}, - {6496,4892,6423 ,5470,5469,5469 ,0,0,0}, {6594,6422,6421 ,5468,726,5468 ,0,0,0}, - {6423,4891,6421 ,5469,5469,5468 ,0,0,0}, {6421,4888,4886 ,5468,5471,5470 ,0,0,0}, - {6421,4885,4882 ,5468,5469,5471 ,0,0,0}, {6595,4854,6499 ,5469,5468,5469 ,0,0,0}, - {4854,4853,6500 ,5468,5471,5471 ,0,0,0}, {4879,4854,6595 ,5468,5468,5469 ,0,0,0}, - {6596,6597,4856 ,5470,5471,5468 ,0,0,0}, {6417,4859,4862 ,5470,726,5468 ,0,0,0}, - {6597,4853,4856 ,5471,5471,5468 ,0,0,0}, {5211,5213,6598 ,5468,5468,5468 ,0,0,0}, - {4825,4951,4950 ,5471,726,726 ,0,0,0}, {4863,6599,4862 ,5469,5469,5468 ,0,0,0}, - {6600,4842,4841 ,726,5471,726 ,0,0,0}, {6601,4847,4844 ,726,726,5470 ,0,0,0}, - {6602,4822,4950 ,726,5470,726 ,0,0,0}, {6603,4844,4842 ,726,5470,5471 ,0,0,0}, - {5208,4865,4871 ,5468,5469,5471 ,0,0,0}, {5211,6598,6581 ,5468,5468,5470 ,0,0,0}, - {4871,4875,5209 ,5471,726,5469 ,0,0,0}, {4874,5205,4875 ,5468,5468,726 ,0,0,0}, - {5209,4875,5205 ,5469,726,5468 ,0,0,0}, {4790,6492,6580 ,5469,5469,5469 ,0,0,0}, - {5215,4795,6604 ,5471,5470,726 ,0,0,0}, {4795,6491,4793 ,5470,5469,726 ,0,0,0}, - {4865,6605,4866 ,5469,5471,5471 ,0,0,0}, {6579,6565,4868 ,5471,5468,5470 ,0,0,0}, - {6565,6599,4863 ,5468,5469,5469 ,0,0,0}, {6599,6418,4862 ,5469,5468,5468 ,0,0,0}, - {4859,6596,4856 ,726,5470,5468 ,0,0,0}, {6596,4859,6417 ,5470,726,5470 ,0,0,0}, - {4850,6582,6606 ,726,726,5471 ,0,0,0}, {6606,4852,4850 ,5471,5469,726 ,0,0,0}, - {6597,6500,4853 ,5471,5471,5471 ,0,0,0}, {4852,6433,6421 ,5469,5469,5468 ,0,0,0}, - {6421,6498,4852 ,5468,5468,5469 ,0,0,0}, {6595,6498,4879 ,5469,5468,5468 ,0,0,0}, - {4852,6606,6434 ,5469,5471,726 ,0,0,0}, {4850,4848,6582 ,726,5471,726 ,0,0,0}, - {4847,6601,6582 ,726,726,726 ,0,0,0}, {4844,6603,6601 ,5470,726,726 ,0,0,0}, - {4841,6602,6600 ,726,726,726 ,0,0,0}, {4842,6600,6603 ,5471,726,726 ,0,0,0}, - {4822,4821,4950 ,5470,726,726 ,0,0,0}, {4841,4822,6602 ,726,5470,726 ,0,0,0}, - {4825,4829,4951 ,5471,5471,726 ,0,0,0}, {4821,4825,4950 ,726,5471,726 ,0,0,0}, - {4829,4828,4947 ,5471,5470,726 ,0,0,0}, {6574,6586,4831 ,5471,726,726 ,0,0,0}, - {6585,4835,6607 ,5471,726,726 ,0,0,0}, {6505,6607,6506 ,5471,726,5470 ,0,0,0}, - {4833,4835,6585 ,5471,726,5471 ,0,0,0}, {6579,6576,6578 ,5471,5471,726 ,0,0,0}, - {6573,4942,6608 ,726,726,5471 ,0,0,0}, {6519,5170,4775 ,726,5470,5470 ,0,0,0}, - {6573,6608,6590 ,726,5471,5470 ,0,0,0}, {4810,4808,5094 ,726,5470,5471 ,0,0,0}, - {4804,6485,4807 ,726,5470,726 ,0,0,0}, {6538,4807,6485 ,5471,726,5470 ,0,0,0}, - {5170,5169,4771 ,5470,5471,5471 ,0,0,0}, {5066,4802,5063 ,726,5471,726 ,0,0,0}, - {5066,6484,4802 ,726,726,5471 ,0,0,0}, {4797,5169,5056 ,5470,5471,726 ,0,0,0}, - {5056,5059,4797 ,726,726,5470 ,0,0,0}, {5170,4771,4775 ,5470,5471,5470 ,0,0,0}, - {6523,4775,4777 ,726,5470,726 ,0,0,0}, {4789,5245,4787 ,5471,5469,726 ,0,0,0}, - {6524,4777,4778 ,5470,726,5471 ,0,0,0}, {5142,4781,5139 ,726,5471,5470 ,0,0,0}, - {5142,6490,4781 ,726,5471,5471 ,0,0,0}, {5245,5132,4787 ,5469,5471,726 ,0,0,0}, - {5132,5135,4787 ,5471,5469,726 ,0,0,0}, {4789,4791,5246 ,5471,5470,5468 ,0,0,0}, - {6580,4791,4790 ,5469,5470,5469 ,0,0,0}, {6605,4865,6581 ,5471,5469,5470 ,0,0,0}, - {6492,4790,4793 ,5469,5469,726 ,0,0,0}, {5218,4795,5215 ,5469,5470,5471 ,0,0,0}, - {5218,6491,4795 ,5469,5469,5470 ,0,0,0}, {6581,4865,5208 ,5470,5469,5468 ,0,0,0}, - {6604,6598,5213 ,726,5468,5468 ,0,0,0}, {6604,5213,5215 ,726,5468,5471 ,0,0,0}, - {6605,6576,4866 ,5471,5471,5471 ,0,0,0}, {6505,6507,6577 ,5471,5471,726 ,0,0,0}, - {6578,6577,6507 ,726,726,5471 ,0,0,0}, {4942,4941,6587 ,726,5470,5471 ,0,0,0}, - {4838,6607,4835 ,726,726,726 ,0,0,0}, {4838,6506,6607 ,726,5470,726 ,0,0,0}, - {6586,4941,4828 ,726,5470,5470 ,0,0,0}, {4828,4831,6586 ,5470,726,726 ,0,0,0}, - {4942,6587,6608 ,726,5471,5471 ,0,0,0}, {6592,6591,6609 ,5471,5470,726 ,0,0,0}, - {6590,6608,6591 ,5470,5471,5470 ,0,0,0}, {6609,6589,6588 ,726,726,726 ,0,0,0}, - {6588,6592,6609 ,726,5471,726 ,0,0,0}, {6589,4911,4914 ,726,726,726 ,0,0,0}, - {6583,4909,4911 ,5471,5470,726 ,0,0,0}, {6584,4907,4909 ,726,726,5470 ,0,0,0}, - {5017,6522,6563 ,726,5471,726 ,0,0,0}, {6504,6610,6503 ,5471,5471,726 ,0,0,0}, - {5018,6563,6504 ,726,726,5471 ,0,0,0}, {6556,6610,6557 ,726,5471,726 ,0,0,0}, - {6504,6557,6610 ,5471,726,5471 ,0,0,0}, {6556,6555,6558 ,726,5470,726 ,0,0,0}, - {4820,6558,6555 ,5470,726,5470 ,0,0,0}, {6594,6421,6427 ,5468,5468,5468 ,0,0,0}, - {4886,4885,6421 ,5470,5469,5468 ,0,0,0}, {6384,6404,6398 ,726,726,5488 ,0,0,0}, - {6393,6545,6384 ,5488,726,726 ,0,0,0}, {6334,5004,5002 ,726,5471,726 ,0,0,0}, - {6509,6334,6389 ,726,726,726 ,0,0,0}, {6475,6474,6472 ,5469,5470,5468 ,0,0,0}, - {6475,6217,6473 ,5469,5468,5469 ,0,0,0}, {6361,6204,6203 ,5489,726,726 ,0,0,0}, - {5124,5122,6204 ,726,726,726 ,0,0,0}, {6611,6612,6613 ,5490,5491,5492 ,0,0,0}, - {6614,6615,6616 ,5493,5494,5495 ,0,0,0}, {6617,6615,6618 ,5496,5494,5497 ,0,0,0}, - {6619,6620,6621 ,5498,5499,5500 ,0,0,0}, {6622,6623,6624 ,5501,5502,5503 ,0,0,0}, - {6625,6626,6627 ,5504,5505,5506 ,0,0,0}, {6628,6629,6630 ,5507,5508,5509 ,0,0,0}, - {6241,6245,6625 ,5510,5511,5504 ,0,0,0}, {6631,6632,6633 ,5512,5513,5514 ,0,0,0}, - {6622,6627,6626 ,5501,5506,5505 ,0,0,0}, {6634,6635,6632 ,5515,5516,5513 ,0,0,0}, - {6636,6634,6632 ,5517,5515,5513 ,0,0,0}, {6636,6637,6634 ,5517,5518,5515 ,0,0,0}, - {6637,6636,6638 ,5518,5517,5519 ,0,0,0}, {6639,6635,6640 ,5520,5516,5521 ,0,0,0}, - {6641,6642,6643 ,5522,5523,5524 ,0,0,0}, {6632,6635,6639 ,5513,5516,5520 ,0,0,0}, - {6643,6642,6638 ,5524,5523,5519 ,0,0,0}, {6644,6641,6645 ,5525,5522,5526 ,0,0,0}, - {6646,6647,6648 ,5527,5528,5529 ,0,0,0}, {6646,6639,6640 ,5527,5520,5521 ,0,0,0}, - {6649,6650,6651 ,5530,5531,5532 ,0,0,0}, {6646,6640,6647 ,5527,5521,5528 ,0,0,0}, - {6647,6649,6648 ,5528,5530,5529 ,0,0,0}, {6652,6653,6651 ,5533,5534,5532 ,0,0,0}, - {6629,6654,6630 ,5508,5535,5509 ,0,0,0}, {6651,6650,6652 ,5532,5531,5533 ,0,0,0}, - {6655,6614,6656 ,5536,5493,5537 ,0,0,0}, {6650,6657,6652 ,5531,5538,5533 ,0,0,0}, - {6629,6633,6654 ,5508,5514,5535 ,0,0,0}, {6658,6633,6639 ,5539,5514,5520 ,0,0,0}, - {6659,6660,6661 ,5540,5541,5542 ,0,0,0}, {6662,6659,6663 ,5543,5540,5544 ,0,0,0}, - {6220,6237,6612 ,5545,5546,5491 ,0,0,0}, {6664,6665,6666 ,5547,5548,5549 ,0,0,0}, - {6220,6611,6221 ,5545,5490,726 ,0,0,0}, {6667,6221,6611 ,5550,726,5490 ,0,0,0}, - {6668,6653,6669 ,5551,5534,5552 ,0,0,0}, {6649,6651,6648 ,5530,5532,5529 ,0,0,0}, - {6651,6653,6668 ,5532,5534,5551 ,0,0,0}, {6669,6670,6668 ,5552,5553,5551 ,0,0,0}, - {6671,6648,6668 ,5554,5529,5551 ,0,0,0}, {6633,6658,6654 ,5514,5539,5535 ,0,0,0}, - {6671,6658,6646 ,5554,5539,5527 ,0,0,0}, {6636,6672,6638 ,5517,5555,5519 ,0,0,0}, - {6646,6658,6639 ,5527,5539,5520 ,0,0,0}, {6673,6674,6643 ,5556,5557,5524 ,0,0,0}, - {6632,6639,6633 ,5513,5520,5514 ,0,0,0}, {6672,6636,6631 ,5555,5517,5512 ,0,0,0}, - {6641,6643,6645 ,5522,5524,5526 ,0,0,0}, {6637,6638,6642 ,5518,5519,5523 ,0,0,0}, - {6638,6672,6673 ,5519,5555,5556 ,0,0,0}, {6675,6645,6643 ,5558,5526,5524 ,0,0,0}, - {6651,6668,6648 ,5532,5551,5529 ,0,0,0}, {6676,6670,6669 ,5559,5553,5552 ,0,0,0}, - {6676,6663,6670 ,5559,5544,5553 ,0,0,0}, {6648,6671,6646 ,5529,5554,5527 ,0,0,0}, - {6670,6677,6671 ,5553,5560,5554 ,0,0,0}, {6629,6618,6631 ,5508,5497,5512 ,0,0,0}, - {6677,6654,6658 ,5560,5535,5539 ,0,0,0}, {6614,6674,6673 ,5493,5557,5556 ,0,0,0}, - {6655,6674,6614 ,5536,5557,5493 ,0,0,0}, {6632,6631,6636 ,5513,5512,5517 ,0,0,0}, - {6633,6629,6631 ,5514,5508,5512 ,0,0,0}, {6638,6673,6643 ,5519,5556,5524 ,0,0,0}, - {6618,6615,6672 ,5497,5494,5555 ,0,0,0}, {6643,6674,6675 ,5524,5557,5558 ,0,0,0}, - {6673,6615,6614 ,5556,5494,5493 ,0,0,0}, {6678,6675,6674 ,5561,5558,5557 ,0,0,0}, - {6668,6670,6671 ,5551,5553,5554 ,0,0,0}, {6662,6663,6676 ,5543,5544,5559 ,0,0,0}, - {6679,6661,6680 ,5562,5542,5563 ,0,0,0}, {6671,6677,6658 ,5554,5560,5539 ,0,0,0}, - {6681,6677,6663 ,5564,5560,5544 ,0,0,0}, {6618,6629,6628 ,5497,5508,5507 ,0,0,0}, - {6681,6630,6654 ,5564,5509,5535 ,0,0,0}, {6682,6656,6616 ,5565,5537,5495 ,0,0,0}, - {6672,6615,6673 ,5555,5494,5556 ,0,0,0}, {6631,6618,6672 ,5512,5497,5555 ,0,0,0}, - {6618,6628,6617 ,5497,5507,5496 ,0,0,0}, {6655,6656,6683 ,5536,5537,5566 ,0,0,0}, - {6617,6616,6615 ,5496,5495,5494 ,0,0,0}, {6674,6655,6678 ,5557,5536,5561 ,0,0,0}, - {6614,6616,6656 ,5493,5495,5537 ,0,0,0}, {6684,6678,6655 ,5567,5561,5536 ,0,0,0}, - {6670,6663,6677 ,5553,5544,5560 ,0,0,0}, {6660,6659,6662 ,5541,5540,5543 ,0,0,0}, - {6630,6685,6628 ,5509,5568,5507 ,0,0,0}, {6677,6681,6654 ,5560,5564,5535 ,0,0,0}, - {6686,6681,6659 ,5569,5564,5540 ,0,0,0}, {6628,6687,6617 ,5507,5570,5496 ,0,0,0}, - {6686,6685,6630 ,5569,5568,5509 ,0,0,0}, {6617,6688,6616 ,5496,5571,5495 ,0,0,0}, - {6687,6628,6685 ,5570,5507,5568 ,0,0,0}, {6656,6619,6683 ,5537,5498,5566 ,0,0,0}, - {6688,6617,6687 ,5571,5496,5570 ,0,0,0}, {6689,6683,6621 ,5572,5566,5500 ,0,0,0}, - {6682,6616,6688 ,5565,5495,5571 ,0,0,0}, {6655,6683,6684 ,5536,5566,5567 ,0,0,0}, - {6656,6682,6619 ,5537,5565,5498 ,0,0,0}, {6689,6684,6683 ,5572,5567,5566 ,0,0,0}, - {6663,6659,6681 ,5544,5540,5564 ,0,0,0}, {6680,6661,6660 ,5563,5542,5541 ,0,0,0}, - {6685,6665,6687 ,5568,5548,5570 ,0,0,0}, {6681,6686,6630 ,5564,5569,5509 ,0,0,0}, - {6661,6690,6686 ,5542,5573,5569 ,0,0,0}, {6687,6664,6688 ,5570,5547,5571 ,0,0,0}, - {6690,6665,6685 ,5573,5548,5568 ,0,0,0}, {6688,6691,6682 ,5571,5574,5565 ,0,0,0}, - {6665,6664,6687 ,5548,5547,5570 ,0,0,0}, {6692,6619,6682 ,5575,5498,5565 ,0,0,0}, - {6691,6688,6664 ,5574,5571,5547 ,0,0,0}, {6693,6621,6624 ,5576,5500,5503 ,0,0,0}, - {6682,6691,6692 ,5565,5574,5575 ,0,0,0}, {6692,6620,6619 ,5575,5499,5498 ,0,0,0}, - {6689,6621,6693 ,5572,5500,5576 ,0,0,0}, {6683,6619,6621 ,5566,5498,5500 ,0,0,0}, - {6659,6661,6686 ,5540,5542,5569 ,0,0,0}, {6694,6679,6680 ,5577,5562,5563 ,0,0,0}, - {6695,6691,6664 ,5578,5574,5547 ,0,0,0}, {6686,6690,6685 ,5569,5573,5568 ,0,0,0}, - {6679,6613,6690 ,5562,5492,5573 ,0,0,0}, {6696,6692,6691 ,5579,5575,5574 ,0,0,0}, - {6613,6666,6665 ,5492,5549,5548 ,0,0,0}, {6697,6620,6692 ,5580,5499,5575 ,0,0,0}, - {6666,6695,6664 ,5549,5578,5547 ,0,0,0}, {6627,6622,6698 ,5506,5501,5581 ,0,0,0}, - {6695,6696,6691 ,5578,5579,5574 ,0,0,0}, {6624,6620,6699 ,5503,5499,5582 ,0,0,0}, - {6697,6692,6696 ,5580,5575,5579 ,0,0,0}, {6699,6620,6697 ,5582,5499,5580 ,0,0,0}, - {6693,6624,6623 ,5576,5503,5502 ,0,0,0}, {6621,6620,6624 ,5500,5499,5503 ,0,0,0}, - {6661,6679,6690 ,5542,5562,5573 ,0,0,0}, {6611,6694,6667 ,5490,5577,5550 ,0,0,0}, - {6612,6700,6666 ,5491,5583,5549 ,0,0,0}, {6690,6613,6665 ,5573,5492,5548 ,0,0,0}, - {6612,6666,6613 ,5491,5549,5492 ,0,0,0}, {6700,6701,6695 ,5583,5584,5578 ,0,0,0}, - {6700,6695,6666 ,5583,5578,5549 ,0,0,0}, {6701,6702,6696 ,5584,5585,5579 ,0,0,0}, - {6701,6696,6695 ,5584,5579,5578 ,0,0,0}, {6702,6703,6697 ,5585,5586,5580 ,0,0,0}, - {6702,6697,6696 ,5585,5580,5579 ,0,0,0}, {6703,6698,6699 ,5586,5581,5582 ,0,0,0}, - {6699,6697,6703 ,5582,5580,5586 ,0,0,0}, {6698,6622,6699 ,5581,5501,5582 ,0,0,0}, - {6623,6622,6626 ,5502,5501,5505 ,0,0,0}, {6624,6699,6622 ,5503,5582,5501 ,0,0,0}, - {6694,6611,6679 ,5577,5490,5562 ,0,0,0}, {6613,6679,6611 ,5492,5562,5490 ,0,0,0}, - {6700,6237,6231 ,5583,5546,5587 ,0,0,0}, {6220,6612,6611 ,5545,5491,5490 ,0,0,0}, - {6701,6231,6236 ,5584,5587,5588 ,0,0,0}, {6237,6700,6612 ,5546,5583,5491 ,0,0,0}, - {6702,6236,6235 ,5585,5588,5589 ,0,0,0}, {6231,6701,6700 ,5587,5584,5583 ,0,0,0}, - {6703,6235,6481 ,5586,5589,5590 ,0,0,0}, {6236,6702,6701 ,5588,5585,5584 ,0,0,0}, - {6698,6481,6239 ,5581,5590,5591 ,0,0,0}, {6235,6703,6702 ,5589,5586,5585 ,0,0,0}, - {6627,6239,6241 ,5506,5591,5510 ,0,0,0}, {6481,6698,6703 ,5590,5581,5586 ,0,0,0}, - {6241,6625,6627 ,5510,5504,5506 ,0,0,0}, {6239,6627,6698 ,5591,5506,5581 ,0,0,0}, - {6704,6705,6706 ,5592,5593,5594 ,0,0,0}, {6707,6708,6709 ,5595,5596,5597 ,0,0,0}, - {6705,6710,6706 ,5593,5598,5594 ,0,0,0}, {6711,6709,6708 ,5599,5597,5596 ,0,0,0}, - {6712,6713,6714 ,5600,5601,5602 ,0,0,0}, {6715,6716,6713 ,5603,5604,5601 ,0,0,0}, - {6717,6718,6719 ,5605,5606,5607 ,0,0,0}, {6720,6716,6715 ,5608,5604,5603 ,0,0,0}, - {6716,6714,6713 ,5604,5602,5601 ,0,0,0}, {6721,6713,6707 ,5609,5601,5595 ,0,0,0}, - {6722,6723,6724 ,5610,5611,5612 ,0,0,0}, {6725,6726,6727 ,5613,5614,5615 ,0,0,0}, - {6728,6723,6729 ,5616,5611,5617 ,0,0,0}, {6730,6731,6704 ,5618,5619,5592 ,0,0,0}, - {6718,6467,6435 ,5606,5620,5621 ,0,0,0}, {6732,6733,6734 ,5622,5623,5624 ,0,0,0}, - {6735,6469,6717 ,5625,5626,5605 ,0,0,0}, {6467,6717,6469 ,5620,5605,5626 ,0,0,0}, - {6736,6737,6738 ,5627,5628,5629 ,0,0,0}, {6710,6739,6706 ,5598,5630,5594 ,0,0,0}, - {6740,6741,6742 ,5631,5632,5633 ,0,0,0}, {6743,6744,6745 ,5634,5635,5636 ,0,0,0}, - {6734,6737,6746 ,5624,5628,5637 ,0,0,0}, {6747,6748,6749 ,5638,5639,5640 ,0,0,0}, - {6750,6704,6751 ,5641,5592,5642 ,0,0,0}, {6748,6743,6749 ,5639,5634,5640 ,0,0,0}, - {6730,6711,6708 ,5618,5599,5596 ,0,0,0}, {6458,6461,6747 ,5643,5644,5638 ,0,0,0}, - {6711,6730,6752 ,5599,5618,5645 ,0,0,0}, {6752,6730,6750 ,5645,5618,5641 ,0,0,0}, - {6753,6754,6750 ,5646,5647,5641 ,0,0,0}, {6730,6708,6731 ,5618,5596,5619 ,0,0,0}, - {6753,6755,6756 ,5646,5648,5649 ,0,0,0}, {6756,6754,6753 ,5649,5647,5646 ,0,0,0}, - {6757,6758,6759 ,5650,5651,5652 ,0,0,0}, {6758,6757,6755 ,5651,5650,5648 ,0,0,0}, - {6715,6713,6721 ,5603,5601,5609 ,0,0,0}, {6760,6712,6714 ,5653,5600,5602 ,0,0,0}, - {6760,6761,6712 ,5653,5654,5600 ,0,0,0}, {6721,6707,6709 ,5609,5595,5597 ,0,0,0}, - {6762,6707,6712 ,5655,5595,5600 ,0,0,0}, {6704,6731,6705 ,5592,5619,5593 ,0,0,0}, - {6762,6731,6708 ,5655,5619,5596 ,0,0,0}, {6753,6763,6755 ,5646,5656,5648 ,0,0,0}, - {6764,6758,6765 ,5657,5651,5658 ,0,0,0}, {6752,6750,6754 ,5645,5641,5647 ,0,0,0}, - {6750,6730,6704 ,5641,5618,5592 ,0,0,0}, {6756,6755,6757 ,5649,5648,5650 ,0,0,0}, - {6751,6763,6753 ,5642,5656,5646 ,0,0,0}, {6758,6766,6759 ,5651,5659,5652 ,0,0,0}, - {6755,6763,6765 ,5648,5656,5658 ,0,0,0}, {6767,6766,6758 ,5660,5659,5651 ,0,0,0}, - {6713,6712,6707 ,5601,5600,5595 ,0,0,0}, {6768,6761,6760 ,5661,5654,5653 ,0,0,0}, - {6768,6724,6761 ,5661,5612,5654 ,0,0,0}, {6707,6762,6708 ,5595,5655,5596 ,0,0,0}, - {6761,6769,6762 ,5654,5662,5655 ,0,0,0}, {6706,6738,6751 ,5594,5629,5642 ,0,0,0}, - {6769,6705,6731 ,5662,5593,5619 ,0,0,0}, {6734,6764,6765 ,5624,5657,5658 ,0,0,0}, - {6733,6764,6734 ,5623,5657,5624 ,0,0,0}, {6750,6751,6753 ,5641,5642,5646 ,0,0,0}, - {6704,6706,6751 ,5592,5594,5642 ,0,0,0}, {6755,6765,6758 ,5648,5658,5651 ,0,0,0}, - {6738,6737,6763 ,5629,5628,5656 ,0,0,0}, {6758,6764,6767 ,5651,5657,5660 ,0,0,0}, - {6765,6737,6734 ,5658,5628,5624 ,0,0,0}, {6770,6767,6764 ,5663,5660,5657 ,0,0,0}, - {6712,6761,6762 ,5600,5654,5655 ,0,0,0}, {6722,6724,6768 ,5610,5612,5661 ,0,0,0}, - {6771,6728,6772 ,5664,5616,5665 ,0,0,0}, {6762,6769,6731 ,5655,5662,5619 ,0,0,0}, - {6773,6769,6724 ,5666,5662,5612 ,0,0,0}, {6738,6706,6739 ,5629,5594,5630 ,0,0,0}, - {6773,6710,6705 ,5666,5598,5593 ,0,0,0}, {6774,6732,6746 ,5667,5622,5637 ,0,0,0}, - {6763,6737,6765 ,5656,5628,5658 ,0,0,0}, {6751,6738,6763 ,5642,5629,5656 ,0,0,0}, - {6738,6739,6736 ,5629,5630,5627 ,0,0,0}, {6733,6732,6775 ,5623,5622,5668 ,0,0,0}, - {6736,6746,6737 ,5627,5637,5628 ,0,0,0}, {6764,6733,6770 ,5657,5623,5663 ,0,0,0}, - {6734,6746,6732 ,5624,5637,5622 ,0,0,0}, {6776,6770,6733 ,5669,5663,5623 ,0,0,0}, - {6761,6724,6769 ,5654,5612,5662 ,0,0,0}, {6729,6723,6722 ,5617,5611,5610 ,0,0,0}, - {6710,6777,6739 ,5598,5670,5630 ,0,0,0}, {6769,6773,6705 ,5662,5666,5593 ,0,0,0}, - {6778,6773,6723 ,5671,5666,5611 ,0,0,0}, {6739,6779,6736 ,5630,5672,5627 ,0,0,0}, - {6778,6777,6710 ,5671,5670,5598 ,0,0,0}, {6736,6780,6746 ,5627,5673,5637 ,0,0,0}, - {6779,6739,6777 ,5672,5630,5670 ,0,0,0}, {6732,6741,6775 ,5622,5632,5668 ,0,0,0}, - {6780,6736,6779 ,5673,5627,5672 ,0,0,0}, {6781,6775,6740 ,5674,5668,5631 ,0,0,0}, - {6774,6746,6780 ,5667,5637,5673 ,0,0,0}, {6733,6775,6776 ,5623,5668,5669 ,0,0,0}, - {6732,6774,6741 ,5622,5667,5632 ,0,0,0}, {6781,6776,6775 ,5674,5669,5668 ,0,0,0}, - {6724,6723,6773 ,5612,5611,5666 ,0,0,0}, {6772,6728,6729 ,5665,5616,5617 ,0,0,0}, - {6777,6725,6779 ,5670,5613,5672 ,0,0,0}, {6773,6778,6710 ,5666,5671,5598 ,0,0,0}, - {6728,6782,6778 ,5616,5675,5671 ,0,0,0}, {6779,6727,6780 ,5672,5615,5673 ,0,0,0}, - {6782,6725,6777 ,5675,5613,5670 ,0,0,0}, {6780,6783,6774 ,5673,5676,5667 ,0,0,0}, - {6725,6727,6779 ,5613,5615,5672 ,0,0,0}, {6784,6741,6774 ,5677,5632,5667 ,0,0,0}, - {6783,6780,6727 ,5676,5673,5615 ,0,0,0}, {6785,6740,6745 ,5678,5631,5636 ,0,0,0}, - {6774,6783,6784 ,5667,5676,5677 ,0,0,0}, {6784,6742,6741 ,5677,5633,5632 ,0,0,0}, - {6781,6740,6785 ,5674,5631,5678 ,0,0,0}, {6775,6741,6740 ,5668,5632,5631 ,0,0,0}, - {6723,6728,6778 ,5611,5616,5671 ,0,0,0}, {6786,6771,6772 ,5679,5664,5665 ,0,0,0}, - {6787,6783,6727 ,5680,5676,5615 ,0,0,0}, {6778,6782,6777 ,5671,5675,5670 ,0,0,0}, - {6771,6719,6782 ,5664,5607,5675 ,0,0,0}, {6788,6784,6783 ,5681,5677,5676 ,0,0,0}, - {6719,6726,6725 ,5607,5614,5613 ,0,0,0}, {6789,6742,6784 ,5682,5633,5677 ,0,0,0}, - {6726,6787,6727 ,5614,5680,5615 ,0,0,0}, {6749,6743,6790 ,5640,5634,5683 ,0,0,0}, - {6787,6788,6783 ,5680,5681,5676 ,0,0,0}, {6745,6742,6791 ,5636,5633,5684 ,0,0,0}, - {6789,6784,6788 ,5682,5677,5681 ,0,0,0}, {6791,6742,6789 ,5684,5633,5682 ,0,0,0}, - {6785,6745,6744 ,5678,5636,5635 ,0,0,0}, {6740,6742,6745 ,5631,5633,5636 ,0,0,0}, - {6728,6771,6782 ,5616,5664,5675 ,0,0,0}, {6717,6786,6735 ,5605,5679,5625 ,0,0,0}, - {6718,6792,6726 ,5606,5685,5614 ,0,0,0}, {6782,6719,6725 ,5675,5607,5613 ,0,0,0}, - {6718,6726,6719 ,5606,5614,5607 ,0,0,0}, {6792,6793,6787 ,5685,5686,5680 ,0,0,0}, - {6792,6787,6726 ,5685,5680,5614 ,0,0,0}, {6793,6794,6788 ,5686,5687,5681 ,0,0,0}, - {6793,6788,6787 ,5686,5681,5680 ,0,0,0}, {6794,6795,6789 ,5687,5688,5682 ,0,0,0}, - {6794,6789,6788 ,5687,5682,5681 ,0,0,0}, {6795,6790,6791 ,5688,5683,5684 ,0,0,0}, - {6791,6789,6795 ,5684,5682,5688 ,0,0,0}, {6790,6743,6791 ,5683,5634,5684 ,0,0,0}, - {6744,6743,6748 ,5635,5634,5639 ,0,0,0}, {6745,6791,6743 ,5636,5684,5634 ,0,0,0}, - {6786,6717,6771 ,5679,5605,5664 ,0,0,0}, {6719,6771,6717 ,5607,5664,5605 ,0,0,0}, - {6792,6435,6456 ,5685,5621,5689 ,0,0,0}, {6467,6718,6717 ,5620,5606,5605 ,0,0,0}, - {6793,6456,6567 ,5686,5689,5690 ,0,0,0}, {6435,6792,6718 ,5621,5685,5606 ,0,0,0}, - {6794,6567,6453 ,5687,5690,5691 ,0,0,0}, {6456,6793,6792 ,5689,5686,5685 ,0,0,0}, - {6795,6453,6451 ,5688,5691,5692 ,0,0,0}, {6567,6794,6793 ,5690,5687,5686 ,0,0,0}, - {6790,6451,6420 ,5683,5692,5693 ,0,0,0}, {6453,6795,6794 ,5691,5688,5687 ,0,0,0}, - {6749,6420,6458 ,5640,5693,5643 ,0,0,0}, {6451,6790,6795 ,5692,5683,5688 ,0,0,0}, - {6458,6747,6749 ,5643,5638,5640 ,0,0,0}, {6420,6749,6790 ,5693,5640,5683 ,0,0,0}, - {6796,6797,6798 ,5694,5695,5696 ,0,0,0}, {6799,6800,6801 ,5697,5698,5699 ,0,0,0}, - {6798,6802,6803 ,5696,5700,5701 ,0,0,0}, {6802,6804,6803 ,5700,5702,5701 ,0,0,0}, - {6805,6806,6807 ,5703,5704,5705 ,0,0,0}, {6807,6808,6805 ,5705,5706,5703 ,0,0,0}, - {6809,6810,6811 ,5707,5708,5709 ,0,0,0}, {6812,6806,6813 ,5710,5704,5711 ,0,0,0}, - {6812,6807,6806 ,5710,5705,5704 ,0,0,0}, {6813,6814,6812 ,5711,5712,5710 ,0,0,0}, - {6815,6801,6816 ,5713,5699,5714 ,0,0,0}, {6817,6818,6819 ,5715,5716,5717 ,0,0,0}, - {6809,6383,6382 ,5707,5718,5719 ,0,0,0}, {6820,6821,6822 ,5720,5721,5722 ,0,0,0}, - {6823,6410,6811 ,5723,5724,5709 ,0,0,0}, {6824,6825,6818 ,5725,5726,5716 ,0,0,0}, - {6383,6811,6410 ,5718,5709,5724 ,0,0,0}, {6826,6827,6828 ,5727,5728,5729 ,0,0,0}, - {6829,6803,6804 ,5730,5701,5702 ,0,0,0}, {6830,6831,6832 ,5731,5732,5733 ,0,0,0}, - {6833,6834,6798 ,5734,5735,5696 ,0,0,0}, {6835,6836,6837 ,5736,5737,5738 ,0,0,0}, - {6828,6838,6839 ,5729,5739,5740 ,0,0,0}, {6840,6838,6841 ,5741,5739,5742 ,0,0,0}, - {6842,6843,6844 ,5743,5744,5745 ,0,0,0}, {6796,6800,6799 ,5694,5698,5697 ,0,0,0}, - {6843,6830,6844 ,5744,5731,5745 ,0,0,0}, {6834,6845,6796 ,5735,5746,5694 ,0,0,0}, - {6406,6411,6842 ,5747,5748,5743 ,0,0,0}, {6846,6847,6834 ,5749,5750,5735 ,0,0,0}, - {6845,6800,6796 ,5746,5698,5694 ,0,0,0}, {6846,6848,6849 ,5749,5751,5752 ,0,0,0}, - {6834,6847,6845 ,5735,5750,5746 ,0,0,0}, {6850,6851,6852 ,5753,5754,5755 ,0,0,0}, - {6847,6846,6849 ,5750,5749,5752 ,0,0,0}, {6853,6852,6854 ,5756,5755,5757 ,0,0,0}, - {6851,6850,6848 ,5754,5753,5751 ,0,0,0}, {6816,6806,6815 ,5714,5704,5713 ,0,0,0}, - {6806,6816,6813 ,5704,5714,5711 ,0,0,0}, {6808,6855,6805 ,5706,5758,5703 ,0,0,0}, - {6815,6799,6801 ,5713,5697,5699 ,0,0,0}, {6856,6815,6805 ,5759,5713,5703 ,0,0,0}, - {6798,6797,6802 ,5696,5695,5700 ,0,0,0}, {6856,6797,6799 ,5759,5695,5697 ,0,0,0}, - {6846,6857,6848 ,5749,5760,5751 ,0,0,0}, {6799,6797,6796 ,5697,5695,5694 ,0,0,0}, - {6858,6859,6851 ,5761,5762,5754 ,0,0,0}, {6834,6796,6798 ,5735,5694,5696 ,0,0,0}, - {6857,6846,6833 ,5760,5749,5734 ,0,0,0}, {6852,6851,6854 ,5755,5754,5757 ,0,0,0}, - {6849,6848,6850 ,5752,5751,5753 ,0,0,0}, {6848,6857,6858 ,5751,5760,5761 ,0,0,0}, - {6860,6854,6851 ,5763,5757,5754 ,0,0,0}, {6806,6805,6815 ,5704,5703,5713 ,0,0,0}, - {6861,6855,6808 ,5764,5758,5706 ,0,0,0}, {6861,6824,6855 ,5764,5725,5758 ,0,0,0}, - {6815,6856,6799 ,5713,5759,5697 ,0,0,0}, {6855,6862,6856 ,5758,5765,5759 ,0,0,0}, - {6803,6841,6833 ,5701,5742,5734 ,0,0,0}, {6862,6802,6797 ,5765,5700,5695 ,0,0,0}, - {6828,6859,6858 ,5729,5762,5761 ,0,0,0}, {6827,6859,6828 ,5728,5762,5729 ,0,0,0}, - {6834,6833,6846 ,5735,5734,5749 ,0,0,0}, {6798,6803,6833 ,5696,5701,5734 ,0,0,0}, - {6848,6858,6851 ,5751,5761,5754 ,0,0,0}, {6841,6838,6857 ,5742,5739,5760 ,0,0,0}, - {6851,6859,6860 ,5754,5762,5763 ,0,0,0}, {6858,6838,6828 ,5761,5739,5729 ,0,0,0}, - {6863,6860,6859 ,5766,5763,5762 ,0,0,0}, {6805,6855,6856 ,5703,5758,5759 ,0,0,0}, - {6825,6824,6861 ,5726,5725,5764 ,0,0,0}, {6864,6817,6865 ,5767,5715,5768 ,0,0,0}, - {6856,6862,6797 ,5759,5765,5695 ,0,0,0}, {6866,6862,6824 ,5769,5765,5725 ,0,0,0}, - {6841,6803,6829 ,5742,5701,5730 ,0,0,0}, {6866,6804,6802 ,5769,5702,5700 ,0,0,0}, - {6867,6826,6839 ,5770,5727,5740 ,0,0,0}, {6857,6838,6858 ,5760,5739,5761 ,0,0,0}, - {6833,6841,6857 ,5734,5742,5760 ,0,0,0}, {6841,6829,6840 ,5742,5730,5741 ,0,0,0}, - {6827,6826,6868 ,5728,5727,5771 ,0,0,0}, {6840,6839,6838 ,5741,5740,5739 ,0,0,0}, - {6859,6827,6863 ,5762,5728,5766 ,0,0,0}, {6828,6839,6826 ,5729,5740,5727 ,0,0,0}, - {6869,6863,6827 ,5772,5766,5728 ,0,0,0}, {6855,6824,6862 ,5758,5725,5765 ,0,0,0}, - {6819,6818,6825 ,5717,5716,5726 ,0,0,0}, {6804,6870,6829 ,5702,5773,5730 ,0,0,0}, - {6862,6866,6802 ,5765,5769,5700 ,0,0,0}, {6871,6866,6818 ,5774,5769,5716 ,0,0,0}, - {6829,6872,6840 ,5730,5775,5741 ,0,0,0}, {6871,6870,6804 ,5774,5773,5702 ,0,0,0}, - {6840,6873,6839 ,5741,5776,5740 ,0,0,0}, {6872,6829,6870 ,5775,5730,5773 ,0,0,0}, - {6826,6836,6868 ,5727,5737,5771 ,0,0,0}, {6873,6840,6872 ,5776,5741,5775 ,0,0,0}, - {6874,6868,6835 ,5777,5771,5736 ,0,0,0}, {6867,6839,6873 ,5770,5740,5776 ,0,0,0}, - {6827,6868,6869 ,5728,5771,5772 ,0,0,0}, {6826,6867,6836 ,5727,5770,5737 ,0,0,0}, - {6874,6869,6868 ,5777,5772,5771 ,0,0,0}, {6824,6818,6866 ,5725,5716,5769 ,0,0,0}, - {6865,6817,6819 ,5768,5715,5717 ,0,0,0}, {6870,6821,6872 ,5773,5721,5775 ,0,0,0}, - {6866,6871,6804 ,5769,5774,5702 ,0,0,0}, {6817,6875,6871 ,5715,5778,5774 ,0,0,0}, - {6872,6820,6873 ,5775,5720,5776 ,0,0,0}, {6875,6821,6870 ,5778,5721,5773 ,0,0,0}, - {6873,6876,6867 ,5776,5779,5770 ,0,0,0}, {6821,6820,6872 ,5721,5720,5775 ,0,0,0}, - {6877,6836,6867 ,5780,5737,5770 ,0,0,0}, {6876,6873,6820 ,5779,5776,5720 ,0,0,0}, - {6878,6835,6832 ,5781,5736,5733 ,0,0,0}, {6867,6876,6877 ,5770,5779,5780 ,0,0,0}, - {6877,6837,6836 ,5780,5738,5737 ,0,0,0}, {6874,6835,6878 ,5777,5736,5781 ,0,0,0}, - {6868,6836,6835 ,5771,5737,5736 ,0,0,0}, {6818,6817,6871 ,5716,5715,5774 ,0,0,0}, - {6879,6864,6865 ,5782,5767,5768 ,0,0,0}, {6880,6876,6820 ,5783,5779,5720 ,0,0,0}, - {6871,6875,6870 ,5774,5778,5773 ,0,0,0}, {6864,6810,6875 ,5767,5708,5778 ,0,0,0}, - {6881,6877,6876 ,5784,5780,5779 ,0,0,0}, {6810,6822,6821 ,5708,5722,5721 ,0,0,0}, - {6882,6837,6877 ,5785,5738,5780 ,0,0,0}, {6822,6880,6820 ,5722,5783,5720 ,0,0,0}, - {6844,6830,6883 ,5745,5731,5786 ,0,0,0}, {6880,6881,6876 ,5783,5784,5779 ,0,0,0}, - {6832,6837,6884 ,5733,5738,5787 ,0,0,0}, {6882,6877,6881 ,5785,5780,5784 ,0,0,0}, - {6884,6837,6882 ,5787,5738,5785 ,0,0,0}, {6878,6832,6831 ,5781,5733,5732 ,0,0,0}, - {6835,6837,6832 ,5736,5738,5733 ,0,0,0}, {6817,6864,6875 ,5715,5767,5778 ,0,0,0}, - {6811,6879,6823 ,5709,5782,5723 ,0,0,0}, {6809,6885,6822 ,5707,5788,5722 ,0,0,0}, - {6875,6810,6821 ,5778,5708,5721 ,0,0,0}, {6809,6822,6810 ,5707,5722,5708 ,0,0,0}, - {6885,6886,6880 ,5788,5789,5783 ,0,0,0}, {6885,6880,6822 ,5788,5783,5722 ,0,0,0}, - {6886,6887,6881 ,5789,5790,5784 ,0,0,0}, {6886,6881,6880 ,5789,5784,5783 ,0,0,0}, - {6887,6888,6882 ,5790,5791,5785 ,0,0,0}, {6887,6882,6881 ,5790,5785,5784 ,0,0,0}, - {6888,6883,6884 ,5791,5786,5787 ,0,0,0}, {6884,6882,6888 ,5787,5785,5791 ,0,0,0}, - {6883,6830,6884 ,5786,5731,5787 ,0,0,0}, {6831,6830,6843 ,5732,5731,5744 ,0,0,0}, - {6832,6884,6830 ,5733,5787,5731 ,0,0,0}, {6879,6811,6864 ,5782,5709,5767 ,0,0,0}, - {6810,6864,6811 ,5708,5767,5709 ,0,0,0}, {6885,6382,6397 ,5788,5719,5792 ,0,0,0}, - {6383,6809,6811 ,5718,5707,5709 ,0,0,0}, {6886,6397,6400 ,5789,5792,5793 ,0,0,0}, - {6382,6885,6809 ,5719,5788,5707 ,0,0,0}, {6887,6400,6401 ,5790,5793,5794 ,0,0,0}, - {6397,6886,6885 ,5792,5789,5788 ,0,0,0}, {6888,6401,6440 ,5791,5794,5795 ,0,0,0}, - {6400,6887,6886 ,5793,5790,5789 ,0,0,0}, {6883,6440,6381 ,5786,5795,5796 ,0,0,0}, - {6401,6888,6887 ,5794,5791,5790 ,0,0,0}, {6844,6381,6406 ,5745,5796,5747 ,0,0,0}, - {6440,6883,6888 ,5795,5786,5791 ,0,0,0}, {6406,6842,6844 ,5747,5743,5745 ,0,0,0}, - {6381,6844,6883 ,5796,5745,5786 ,0,0,0}, {6889,6890,6891 ,5797,5798,5799 ,0,0,0}, - {6892,5806,5807 ,5800,5801,5802 ,0,0,0}, {6891,6893,6894 ,5799,5803,5804 ,0,0,0}, - {6893,6895,6894 ,5803,5805,5804 ,0,0,0}, {6896,6897,6898 ,5806,5807,5808 ,0,0,0}, - {6898,6899,6896 ,5808,5809,5806 ,0,0,0}, {6900,6901,6902 ,5810,5811,5812 ,0,0,0}, - {6903,6897,5812 ,5813,5807,5814 ,0,0,0}, {6903,6898,6897 ,5813,5808,5807 ,0,0,0}, - {5812,5813,6903 ,5814,5815,5813 ,0,0,0}, {6904,5807,5810 ,5816,5802,5817 ,0,0,0}, - {6905,6906,6907 ,5818,5819,5820 ,0,0,0}, {6900,6339,6338 ,5810,5821,5822 ,0,0,0}, - {6908,6909,6910 ,5823,5824,5825 ,0,0,0}, {6911,6346,6902 ,5826,5827,5812 ,0,0,0}, - {6912,6913,6906 ,5828,5829,5819 ,0,0,0}, {6339,6902,6346 ,5821,5812,5827 ,0,0,0}, - {6914,6915,6916 ,5830,5831,5832 ,0,0,0}, {6917,6894,6895 ,5833,5804,5805 ,0,0,0}, - {6918,6919,6920 ,5834,5835,5836 ,0,0,0}, {6921,6922,6891 ,5837,5838,5799 ,0,0,0}, - {6923,6924,6925 ,5839,5840,5841 ,0,0,0}, {6916,6926,6927 ,5832,5842,5843 ,0,0,0}, - {6928,6926,6929 ,5844,5842,5845 ,0,0,0}, {6930,6931,6932 ,5846,5847,5848 ,0,0,0}, - {6889,5806,6892 ,5797,5801,5800 ,0,0,0}, {6931,6918,6932 ,5847,5834,5848 ,0,0,0}, - {6922,5804,6889 ,5838,5849,5797 ,0,0,0}, {6362,6369,6930 ,5850,5851,5846 ,0,0,0}, - {6933,5802,6922 ,5852,5853,5838 ,0,0,0}, {5804,5806,6889 ,5849,5801,5797 ,0,0,0}, - {6933,6934,5799 ,5852,5854,5855 ,0,0,0}, {6922,5802,5804 ,5838,5853,5849 ,0,0,0}, - {5797,6935,5798 ,5856,5857,5858 ,0,0,0}, {5802,6933,5799 ,5853,5852,5855 ,0,0,0}, - {5792,5798,6936 ,5067,5858,5859 ,0,0,0}, {6935,5797,6934 ,5857,5856,5854 ,0,0,0}, - {5810,6897,6904 ,5817,5807,5816 ,0,0,0}, {6897,5810,5812 ,5807,5817,5814 ,0,0,0}, - {6899,6937,6896 ,5809,5860,5806 ,0,0,0}, {6904,6892,5807 ,5816,5800,5802 ,0,0,0}, - {6938,6904,6896 ,5861,5816,5806 ,0,0,0}, {6891,6890,6893 ,5799,5798,5803 ,0,0,0}, - {6938,6890,6892 ,5861,5798,5800 ,0,0,0}, {6933,6939,6934 ,5852,5862,5854 ,0,0,0}, - {6892,6890,6889 ,5800,5798,5797 ,0,0,0}, {6940,6941,6935 ,5863,5864,5857 ,0,0,0}, - {6922,6889,6891 ,5838,5797,5799 ,0,0,0}, {6939,6933,6921 ,5862,5852,5837 ,0,0,0}, - {5798,6935,6936 ,5858,5857,5859 ,0,0,0}, {5799,6934,5797 ,5855,5854,5856 ,0,0,0}, - {6934,6939,6940 ,5854,5862,5863 ,0,0,0}, {6942,6936,6935 ,5865,5859,5857 ,0,0,0}, - {6897,6896,6904 ,5807,5806,5816 ,0,0,0}, {6943,6937,6899 ,5866,5860,5809 ,0,0,0}, - {6943,6912,6937 ,5866,5828,5860 ,0,0,0}, {6904,6938,6892 ,5816,5861,5800 ,0,0,0}, - {6937,6944,6938 ,5860,5867,5861 ,0,0,0}, {6894,6929,6921 ,5804,5845,5837 ,0,0,0}, - {6944,6893,6890 ,5867,5803,5798 ,0,0,0}, {6916,6941,6940 ,5832,5864,5863 ,0,0,0}, - {6915,6941,6916 ,5831,5864,5832 ,0,0,0}, {6922,6921,6933 ,5838,5837,5852 ,0,0,0}, - {6891,6894,6921 ,5799,5804,5837 ,0,0,0}, {6934,6940,6935 ,5854,5863,5857 ,0,0,0}, - {6929,6926,6939 ,5845,5842,5862 ,0,0,0}, {6935,6941,6942 ,5857,5864,5865 ,0,0,0}, - {6940,6926,6916 ,5863,5842,5832 ,0,0,0}, {6945,6942,6941 ,5868,5865,5864 ,0,0,0}, - {6896,6937,6938 ,5806,5860,5861 ,0,0,0}, {6913,6912,6943 ,5829,5828,5866 ,0,0,0}, - {6946,6905,6947 ,5869,5818,5870 ,0,0,0}, {6938,6944,6890 ,5861,5867,5798 ,0,0,0}, - {6948,6944,6912 ,5871,5867,5828 ,0,0,0}, {6929,6894,6917 ,5845,5804,5833 ,0,0,0}, - {6948,6895,6893 ,5871,5805,5803 ,0,0,0}, {6949,6914,6927 ,5872,5830,5843 ,0,0,0}, - {6939,6926,6940 ,5862,5842,5863 ,0,0,0}, {6921,6929,6939 ,5837,5845,5862 ,0,0,0}, - {6929,6917,6928 ,5845,5833,5844 ,0,0,0}, {6915,6914,6950 ,5831,5830,5873 ,0,0,0}, - {6928,6927,6926 ,5844,5843,5842 ,0,0,0}, {6941,6915,6945 ,5864,5831,5868 ,0,0,0}, - {6916,6927,6914 ,5832,5843,5830 ,0,0,0}, {6951,6945,6915 ,5874,5868,5831 ,0,0,0}, - {6937,6912,6944 ,5860,5828,5867 ,0,0,0}, {6907,6906,6913 ,5820,5819,5829 ,0,0,0}, - {6895,6952,6917 ,5805,5875,5833 ,0,0,0}, {6944,6948,6893 ,5867,5871,5803 ,0,0,0}, - {6953,6948,6906 ,5876,5871,5819 ,0,0,0}, {6917,6954,6928 ,5833,5877,5844 ,0,0,0}, - {6953,6952,6895 ,5876,5875,5805 ,0,0,0}, {6928,6955,6927 ,5844,5878,5843 ,0,0,0}, - {6954,6917,6952 ,5877,5833,5875 ,0,0,0}, {6914,6924,6950 ,5830,5840,5873 ,0,0,0}, - {6955,6928,6954 ,5878,5844,5877 ,0,0,0}, {6956,6950,6923 ,5879,5873,5839 ,0,0,0}, - {6949,6927,6955 ,5872,5843,5878 ,0,0,0}, {6915,6950,6951 ,5831,5873,5874 ,0,0,0}, - {6914,6949,6924 ,5830,5872,5840 ,0,0,0}, {6956,6951,6950 ,5879,5874,5873 ,0,0,0}, - {6912,6906,6948 ,5828,5819,5871 ,0,0,0}, {6947,6905,6907 ,5870,5818,5820 ,0,0,0}, - {6952,6909,6954 ,5875,5824,5877 ,0,0,0}, {6948,6953,6895 ,5871,5876,5805 ,0,0,0}, - {6905,6957,6953 ,5818,5880,5876 ,0,0,0}, {6954,6908,6955 ,5877,5823,5878 ,0,0,0}, - {6957,6909,6952 ,5880,5824,5875 ,0,0,0}, {6955,6958,6949 ,5878,5881,5872 ,0,0,0}, - {6909,6908,6954 ,5824,5823,5877 ,0,0,0}, {6959,6924,6949 ,5882,5840,5872 ,0,0,0}, - {6958,6955,6908 ,5881,5878,5823 ,0,0,0}, {6960,6923,6920 ,5883,5839,5836 ,0,0,0}, - {6949,6958,6959 ,5872,5881,5882 ,0,0,0}, {6959,6925,6924 ,5882,5841,5840 ,0,0,0}, - {6956,6923,6960 ,5879,5839,5883 ,0,0,0}, {6950,6924,6923 ,5873,5840,5839 ,0,0,0}, - {6906,6905,6953 ,5819,5818,5876 ,0,0,0}, {6961,6946,6947 ,5884,5869,5870 ,0,0,0}, - {6962,6958,6908 ,5885,5881,5823 ,0,0,0}, {6953,6957,6952 ,5876,5880,5875 ,0,0,0}, - {6946,6901,6957 ,5869,5811,5880 ,0,0,0}, {6963,6959,6958 ,5886,5882,5881 ,0,0,0}, - {6901,6910,6909 ,5811,5825,5824 ,0,0,0}, {6964,6925,6959 ,5887,5841,5882 ,0,0,0}, - {6910,6962,6908 ,5825,5885,5823 ,0,0,0}, {6932,6918,6965 ,5848,5834,5888 ,0,0,0}, - {6962,6963,6958 ,5885,5886,5881 ,0,0,0}, {6920,6925,6966 ,5836,5841,5889 ,0,0,0}, - {6964,6959,6963 ,5887,5882,5886 ,0,0,0}, {6966,6925,6964 ,5889,5841,5887 ,0,0,0}, - {6960,6920,6919 ,5883,5836,5835 ,0,0,0}, {6923,6925,6920 ,5839,5841,5836 ,0,0,0}, - {6905,6946,6957 ,5818,5869,5880 ,0,0,0}, {6902,6961,6911 ,5812,5884,5826 ,0,0,0}, - {6900,6967,6910 ,5810,5890,5825 ,0,0,0}, {6957,6901,6909 ,5880,5811,5824 ,0,0,0}, - {6900,6910,6901 ,5810,5825,5811 ,0,0,0}, {6967,6968,6962 ,5890,5891,5885 ,0,0,0}, - {6967,6962,6910 ,5890,5885,5825 ,0,0,0}, {6968,6969,6963 ,5891,5892,5886 ,0,0,0}, - {6968,6963,6962 ,5891,5886,5885 ,0,0,0}, {6969,6970,6964 ,5892,5893,5887 ,0,0,0}, - {6969,6964,6963 ,5892,5887,5886 ,0,0,0}, {6970,6965,6966 ,5893,5888,5889 ,0,0,0}, - {6966,6964,6970 ,5889,5887,5893 ,0,0,0}, {6965,6918,6966 ,5888,5834,5889 ,0,0,0}, - {6919,6918,6931 ,5835,5834,5847 ,0,0,0}, {6920,6966,6918 ,5836,5889,5834 ,0,0,0}, - {6961,6902,6946 ,5884,5812,5869 ,0,0,0}, {6901,6946,6902 ,5811,5869,5812 ,0,0,0}, - {6967,6338,6356 ,5890,5822,5894 ,0,0,0}, {6339,6900,6902 ,5821,5810,5812 ,0,0,0}, - {6968,6356,6357 ,5891,5894,5895 ,0,0,0}, {6338,6967,6900 ,5822,5890,5810 ,0,0,0}, - {6969,6357,6359 ,5892,5895,5896 ,0,0,0}, {6356,6968,6967 ,5894,5891,5890 ,0,0,0}, - {6970,6359,6342 ,5893,5896,5897 ,0,0,0}, {6357,6969,6968 ,5895,5892,5891 ,0,0,0}, - {6965,6342,6363 ,5888,5897,5898 ,0,0,0}, {6359,6970,6969 ,5896,5893,5892 ,0,0,0}, - {6932,6363,6362 ,5848,5898,5850 ,0,0,0}, {6342,6965,6970 ,5897,5888,5893 ,0,0,0}, - {6362,6930,6932 ,5850,5846,5848 ,0,0,0}, {6363,6932,6965 ,5898,5848,5888 ,0,0,0}, - {6971,6972,6973 ,5899,5900,5901 ,0,0,0}, {6974,6975,5775 ,5902,5903,5904 ,0,0,0}, - {6972,6976,6973 ,5900,5905,5901 ,0,0,0}, {5770,5775,6975 ,5906,5904,5903 ,0,0,0}, - {6977,6978,6979 ,5907,5908,5909 ,0,0,0}, {5780,6980,6978 ,5910,5911,5908 ,0,0,0}, - {6981,6982,6983 ,5912,5913,5914 ,0,0,0}, {5778,6980,5780 ,5915,5911,5910 ,0,0,0}, - {6980,6979,6978 ,5911,5909,5908 ,0,0,0}, {5774,6978,6974 ,5916,5908,5902 ,0,0,0}, - {6984,6985,6986 ,5917,5918,5919 ,0,0,0}, {6987,6988,6989 ,5920,5921,5922 ,0,0,0}, - {6990,6985,6991 ,5923,5918,5924 ,0,0,0}, {6992,6993,6971 ,5925,5926,5899 ,0,0,0}, - {6982,6289,6208 ,5913,5927,5928 ,0,0,0}, {6994,6995,6996 ,5929,5930,5931 ,0,0,0}, - {6997,6319,6981 ,5932,5933,5912 ,0,0,0}, {6289,6981,6319 ,5927,5912,5933 ,0,0,0}, - {6998,6999,7000 ,5934,5935,5936 ,0,0,0}, {6976,7001,6973 ,5905,5937,5901 ,0,0,0}, - {7002,7003,7004 ,5938,5939,5940 ,0,0,0}, {7005,7006,7007 ,5941,5942,5943 ,0,0,0}, - {6996,6999,7008 ,5931,5935,5944 ,0,0,0}, {7009,7010,7011 ,5945,5946,5947 ,0,0,0}, - {7012,6971,7013 ,5948,5899,5949 ,0,0,0}, {7010,7005,7011 ,5946,5941,5947 ,0,0,0}, - {6992,5770,6975 ,5925,5906,5903 ,0,0,0}, {6318,6322,7009 ,5950,5951,5945 ,0,0,0}, - {5770,6992,5768 ,5906,5925,5952 ,0,0,0}, {5768,6992,7012 ,5952,5925,5948 ,0,0,0}, - {7014,5763,7012 ,5953,5954,5948 ,0,0,0}, {6992,6975,6993 ,5925,5903,5926 ,0,0,0}, - {7014,7015,5767 ,5953,5955,5956 ,0,0,0}, {5767,5763,7014 ,5956,5954,5953 ,0,0,0}, - {5759,7016,5761 ,5957,5958,5959 ,0,0,0}, {7016,5759,7015 ,5958,5957,5955 ,0,0,0}, - {5780,6978,5774 ,5910,5908,5916 ,0,0,0}, {7017,6977,6979 ,5960,5907,5909 ,0,0,0}, - {7017,7018,6977 ,5960,5961,5907 ,0,0,0}, {5774,6974,5775 ,5916,5902,5904 ,0,0,0}, - {7019,6974,6977 ,5962,5902,5907 ,0,0,0}, {6971,6993,6972 ,5899,5926,5900 ,0,0,0}, - {7019,6993,6975 ,5962,5926,5903 ,0,0,0}, {7014,7020,7015 ,5953,5963,5955 ,0,0,0}, - {7021,7016,7022 ,5964,5958,5965 ,0,0,0}, {5768,7012,5763 ,5952,5948,5954 ,0,0,0}, - {7012,6992,6971 ,5948,5925,5899 ,0,0,0}, {5767,7015,5759 ,5956,5955,5957 ,0,0,0}, - {7013,7020,7014 ,5949,5963,5953 ,0,0,0}, {7016,7023,5761 ,5958,5966,5959 ,0,0,0}, - {7015,7020,7022 ,5955,5963,5965 ,0,0,0}, {7024,7023,7016 ,5967,5966,5958 ,0,0,0}, - {6978,6977,6974 ,5908,5907,5902 ,0,0,0}, {7025,7018,7017 ,5968,5961,5960 ,0,0,0}, - {7025,6986,7018 ,5968,5919,5961 ,0,0,0}, {6974,7019,6975 ,5902,5962,5903 ,0,0,0}, - {7018,7026,7019 ,5961,5969,5962 ,0,0,0}, {6973,7000,7013 ,5901,5936,5949 ,0,0,0}, - {7026,6972,6993 ,5969,5900,5926 ,0,0,0}, {6996,7021,7022 ,5931,5964,5965 ,0,0,0}, - {6995,7021,6996 ,5930,5964,5931 ,0,0,0}, {7012,7013,7014 ,5948,5949,5953 ,0,0,0}, - {6971,6973,7013 ,5899,5901,5949 ,0,0,0}, {7015,7022,7016 ,5955,5965,5958 ,0,0,0}, - {7000,6999,7020 ,5936,5935,5963 ,0,0,0}, {7016,7021,7024 ,5958,5964,5967 ,0,0,0}, - {7022,6999,6996 ,5965,5935,5931 ,0,0,0}, {7027,7024,7021 ,5970,5967,5964 ,0,0,0}, - {6977,7018,7019 ,5907,5961,5962 ,0,0,0}, {6984,6986,7025 ,5917,5919,5968 ,0,0,0}, - {7028,6990,7029 ,5971,5923,5972 ,0,0,0}, {7019,7026,6993 ,5962,5969,5926 ,0,0,0}, - {7030,7026,6986 ,5973,5969,5919 ,0,0,0}, {7000,6973,7001 ,5936,5901,5937 ,0,0,0}, - {7030,6976,6972 ,5973,5905,5900 ,0,0,0}, {7031,6994,7008 ,5974,5929,5944 ,0,0,0}, - {7020,6999,7022 ,5963,5935,5965 ,0,0,0}, {7013,7000,7020 ,5949,5936,5963 ,0,0,0}, - {7000,7001,6998 ,5936,5937,5934 ,0,0,0}, {6995,6994,7032 ,5930,5929,5975 ,0,0,0}, - {6998,7008,6999 ,5934,5944,5935 ,0,0,0}, {7021,6995,7027 ,5964,5930,5970 ,0,0,0}, - {6996,7008,6994 ,5931,5944,5929 ,0,0,0}, {7033,7027,6995 ,5976,5970,5930 ,0,0,0}, - {7018,6986,7026 ,5961,5919,5969 ,0,0,0}, {6991,6985,6984 ,5924,5918,5917 ,0,0,0}, - {6976,7034,7001 ,5905,5977,5937 ,0,0,0}, {7026,7030,6972 ,5969,5973,5900 ,0,0,0}, - {7035,7030,6985 ,5978,5973,5918 ,0,0,0}, {7001,7036,6998 ,5937,5979,5934 ,0,0,0}, - {7035,7034,6976 ,5978,5977,5905 ,0,0,0}, {6998,7037,7008 ,5934,5980,5944 ,0,0,0}, - {7036,7001,7034 ,5979,5937,5977 ,0,0,0}, {6994,7003,7032 ,5929,5939,5975 ,0,0,0}, - {7037,6998,7036 ,5980,5934,5979 ,0,0,0}, {7038,7032,7002 ,5981,5975,5938 ,0,0,0}, - {7031,7008,7037 ,5974,5944,5980 ,0,0,0}, {6995,7032,7033 ,5930,5975,5976 ,0,0,0}, - {6994,7031,7003 ,5929,5974,5939 ,0,0,0}, {7038,7033,7032 ,5981,5976,5975 ,0,0,0}, - {6986,6985,7030 ,5919,5918,5973 ,0,0,0}, {7029,6990,6991 ,5972,5923,5924 ,0,0,0}, - {7034,6987,7036 ,5977,5920,5979 ,0,0,0}, {7030,7035,6976 ,5973,5978,5905 ,0,0,0}, - {6990,7039,7035 ,5923,5982,5978 ,0,0,0}, {7036,6989,7037 ,5979,5922,5980 ,0,0,0}, - {7039,6987,7034 ,5982,5920,5977 ,0,0,0}, {7037,7040,7031 ,5980,5983,5974 ,0,0,0}, - {6987,6989,7036 ,5920,5922,5979 ,0,0,0}, {7041,7003,7031 ,5984,5939,5974 ,0,0,0}, - {7040,7037,6989 ,5983,5980,5922 ,0,0,0}, {7042,7002,7007 ,5985,5938,5943 ,0,0,0}, - {7031,7040,7041 ,5974,5983,5984 ,0,0,0}, {7041,7004,7003 ,5984,5940,5939 ,0,0,0}, - {7038,7002,7042 ,5981,5938,5985 ,0,0,0}, {7032,7003,7002 ,5975,5939,5938 ,0,0,0}, - {6985,6990,7035 ,5918,5923,5978 ,0,0,0}, {7043,7028,7029 ,5986,5971,5972 ,0,0,0}, - {7044,7040,6989 ,5987,5983,5922 ,0,0,0}, {7035,7039,7034 ,5978,5982,5977 ,0,0,0}, - {7028,6983,7039 ,5971,5914,5982 ,0,0,0}, {7045,7041,7040 ,5988,5984,5983 ,0,0,0}, - {6983,6988,6987 ,5914,5921,5920 ,0,0,0}, {7046,7004,7041 ,5989,5940,5984 ,0,0,0}, - {6988,7044,6989 ,5921,5987,5922 ,0,0,0}, {7011,7005,7047 ,5947,5941,5990 ,0,0,0}, - {7044,7045,7040 ,5987,5988,5983 ,0,0,0}, {7007,7004,7048 ,5943,5940,5991 ,0,0,0}, - {7046,7041,7045 ,5989,5984,5988 ,0,0,0}, {7048,7004,7046 ,5991,5940,5989 ,0,0,0}, - {7042,7007,7006 ,5985,5943,5942 ,0,0,0}, {7002,7004,7007 ,5938,5940,5943 ,0,0,0}, - {6990,7028,7039 ,5923,5971,5982 ,0,0,0}, {6981,7043,6997 ,5912,5986,5932 ,0,0,0}, - {6982,7049,6988 ,5913,5992,5921 ,0,0,0}, {7039,6983,6987 ,5982,5914,5920 ,0,0,0}, - {6982,6988,6983 ,5913,5921,5914 ,0,0,0}, {7049,7050,7044 ,5992,5993,5987 ,0,0,0}, - {7049,7044,6988 ,5992,5987,5921 ,0,0,0}, {7050,7051,7045 ,5993,5994,5988 ,0,0,0}, - {7050,7045,7044 ,5993,5988,5987 ,0,0,0}, {7051,7052,7046 ,5994,5995,5989 ,0,0,0}, - {7051,7046,7045 ,5994,5989,5988 ,0,0,0}, {7052,7047,7048 ,5995,5990,5991 ,0,0,0}, - {7048,7046,7052 ,5991,5989,5995 ,0,0,0}, {7047,7005,7048 ,5990,5941,5991 ,0,0,0}, - {7006,7005,7010 ,5942,5941,5946 ,0,0,0}, {7007,7048,7005 ,5943,5991,5941 ,0,0,0}, - {7043,6981,7028 ,5986,5912,5971 ,0,0,0}, {6983,7028,6981 ,5914,5971,5912 ,0,0,0}, - {7049,6208,6308 ,5992,5928,5996 ,0,0,0}, {6289,6982,6981 ,5927,5913,5912 ,0,0,0}, - {7050,6308,6513 ,5993,5996,5997 ,0,0,0}, {6208,7049,6982 ,5928,5992,5913 ,0,0,0}, - {7051,6513,6315 ,5994,5997,5998 ,0,0,0}, {6308,7050,7049 ,5996,5993,5992 ,0,0,0}, - {7052,6315,6326 ,5995,5998,5999 ,0,0,0}, {6513,7051,7050 ,5997,5994,5993 ,0,0,0}, - {7047,6326,6312 ,5990,5999,6000 ,0,0,0}, {6315,7052,7051 ,5998,5995,5994 ,0,0,0}, - {7011,6312,6318 ,5947,6000,5950 ,0,0,0}, {6326,7047,7052 ,5999,5990,5995 ,0,0,0}, - {6318,7009,7011 ,5950,5945,5947 ,0,0,0}, {6312,7011,7047 ,6000,5947,5990 ,0,0,0}, - {7053,7054,7055 ,6001,6002,6003 ,0,0,0}, {7056,5743,5740 ,6004,6005,6006 ,0,0,0}, - {7055,7057,7058 ,6003,6007,6008 ,0,0,0}, {7057,7059,7058 ,6007,6009,6008 ,0,0,0}, - {7060,7061,7062 ,6010,6011,6012 ,0,0,0}, {7062,7063,7060 ,6012,6013,6010 ,0,0,0}, - {7064,7065,7066 ,6014,6015,6016 ,0,0,0}, {7067,7061,5746 ,6017,6011,6018 ,0,0,0}, - {7067,7062,7061 ,6017,6012,6011 ,0,0,0}, {5746,5745,7067 ,6018,5020,6017 ,0,0,0}, - {7068,5740,5748 ,6019,6006,6020 ,0,0,0}, {7069,7070,7071 ,6021,6022,6023 ,0,0,0}, - {7064,6263,6279 ,6014,6024,6025 ,0,0,0}, {7072,7073,7074 ,6026,6027,6028 ,0,0,0}, - {7075,6266,7066 ,6029,6030,6016 ,0,0,0}, {7076,7077,7070 ,6031,6032,6022 ,0,0,0}, - {6263,7066,6266 ,6024,6016,6030 ,0,0,0}, {7078,7079,7080 ,6033,6034,6035 ,0,0,0}, - {7081,7058,7059 ,6036,6008,6009 ,0,0,0}, {7082,7083,7084 ,6037,6038,6039 ,0,0,0}, - {7085,7086,7055 ,6040,6041,6003 ,0,0,0}, {7087,7088,7089 ,6042,6043,6044 ,0,0,0}, - {7080,7090,7091 ,6035,6045,6046 ,0,0,0}, {7092,7090,7093 ,6047,6045,6048 ,0,0,0}, - {7094,7095,7096 ,6049,6050,6051 ,0,0,0}, {7053,5743,7056 ,6001,6005,6004 ,0,0,0}, - {7095,7082,7096 ,6050,6037,6051 ,0,0,0}, {7086,5732,7053 ,6041,6052,6001 ,0,0,0}, - {6282,6284,7094 ,6053,6054,6049 ,0,0,0}, {7097,5733,7086 ,6055,6056,6041 ,0,0,0}, - {5732,5743,7053 ,6052,6005,6001 ,0,0,0}, {7097,7098,5735 ,6055,6057,6058 ,0,0,0}, - {7086,5733,5732 ,6041,6056,6052 ,0,0,0}, {5729,7099,5730 ,6059,6060,6061 ,0,0,0}, - {5733,7097,5735 ,6056,6055,6058 ,0,0,0}, {5721,5730,7100 ,6062,6061,6063 ,0,0,0}, - {7099,5729,7098 ,6060,6059,6057 ,0,0,0}, {5748,7061,7068 ,6020,6011,6019 ,0,0,0}, - {7061,5748,5746 ,6011,6020,6018 ,0,0,0}, {7063,7101,7060 ,6013,6064,6010 ,0,0,0}, - {7068,7056,5740 ,6019,6004,6006 ,0,0,0}, {7102,7068,7060 ,6065,6019,6010 ,0,0,0}, - {7055,7054,7057 ,6003,6002,6007 ,0,0,0}, {7102,7054,7056 ,6065,6002,6004 ,0,0,0}, - {7097,7103,7098 ,6055,6066,6057 ,0,0,0}, {7056,7054,7053 ,6004,6002,6001 ,0,0,0}, - {7104,7105,7099 ,6067,6068,6060 ,0,0,0}, {7086,7053,7055 ,6041,6001,6003 ,0,0,0}, - {7103,7097,7085 ,6066,6055,6040 ,0,0,0}, {5730,7099,7100 ,6061,6060,6063 ,0,0,0}, - {5735,7098,5729 ,6058,6057,6059 ,0,0,0}, {7098,7103,7104 ,6057,6066,6067 ,0,0,0}, - {7106,7100,7099 ,6069,6063,6060 ,0,0,0}, {7061,7060,7068 ,6011,6010,6019 ,0,0,0}, - {7107,7101,7063 ,6070,6064,6013 ,0,0,0}, {7107,7076,7101 ,6070,6031,6064 ,0,0,0}, - {7068,7102,7056 ,6019,6065,6004 ,0,0,0}, {7101,7108,7102 ,6064,6071,6065 ,0,0,0}, - {7058,7093,7085 ,6008,6048,6040 ,0,0,0}, {7108,7057,7054 ,6071,6007,6002 ,0,0,0}, - {7080,7105,7104 ,6035,6068,6067 ,0,0,0}, {7079,7105,7080 ,6034,6068,6035 ,0,0,0}, - {7086,7085,7097 ,6041,6040,6055 ,0,0,0}, {7055,7058,7085 ,6003,6008,6040 ,0,0,0}, - {7098,7104,7099 ,6057,6067,6060 ,0,0,0}, {7093,7090,7103 ,6048,6045,6066 ,0,0,0}, - {7099,7105,7106 ,6060,6068,6069 ,0,0,0}, {7104,7090,7080 ,6067,6045,6035 ,0,0,0}, - {7109,7106,7105 ,6072,6069,6068 ,0,0,0}, {7060,7101,7102 ,6010,6064,6065 ,0,0,0}, - {7077,7076,7107 ,6032,6031,6070 ,0,0,0}, {7110,7069,7111 ,6073,6021,6074 ,0,0,0}, - {7102,7108,7054 ,6065,6071,6002 ,0,0,0}, {7112,7108,7076 ,6075,6071,6031 ,0,0,0}, - {7093,7058,7081 ,6048,6008,6036 ,0,0,0}, {7112,7059,7057 ,6075,6009,6007 ,0,0,0}, - {7113,7078,7091 ,6076,6033,6046 ,0,0,0}, {7103,7090,7104 ,6066,6045,6067 ,0,0,0}, - {7085,7093,7103 ,6040,6048,6066 ,0,0,0}, {7093,7081,7092 ,6048,6036,6047 ,0,0,0}, - {7079,7078,7114 ,6034,6033,6077 ,0,0,0}, {7092,7091,7090 ,6047,6046,6045 ,0,0,0}, - {7105,7079,7109 ,6068,6034,6072 ,0,0,0}, {7080,7091,7078 ,6035,6046,6033 ,0,0,0}, - {7115,7109,7079 ,6078,6072,6034 ,0,0,0}, {7101,7076,7108 ,6064,6031,6071 ,0,0,0}, - {7071,7070,7077 ,6023,6022,6032 ,0,0,0}, {7059,7116,7081 ,6009,6079,6036 ,0,0,0}, - {7108,7112,7057 ,6071,6075,6007 ,0,0,0}, {7117,7112,7070 ,6080,6075,6022 ,0,0,0}, - {7081,7118,7092 ,6036,6081,6047 ,0,0,0}, {7117,7116,7059 ,6080,6079,6009 ,0,0,0}, - {7092,7119,7091 ,6047,6082,6046 ,0,0,0}, {7118,7081,7116 ,6081,6036,6079 ,0,0,0}, - {7078,7088,7114 ,6033,6043,6077 ,0,0,0}, {7119,7092,7118 ,6082,6047,6081 ,0,0,0}, - {7120,7114,7087 ,6083,6077,6042 ,0,0,0}, {7113,7091,7119 ,6076,6046,6082 ,0,0,0}, - {7079,7114,7115 ,6034,6077,6078 ,0,0,0}, {7078,7113,7088 ,6033,6076,6043 ,0,0,0}, - {7120,7115,7114 ,6083,6078,6077 ,0,0,0}, {7076,7070,7112 ,6031,6022,6075 ,0,0,0}, - {7111,7069,7071 ,6074,6021,6023 ,0,0,0}, {7116,7073,7118 ,6079,6027,6081 ,0,0,0}, - {7112,7117,7059 ,6075,6080,6009 ,0,0,0}, {7069,7121,7117 ,6021,6084,6080 ,0,0,0}, - {7118,7072,7119 ,6081,6026,6082 ,0,0,0}, {7121,7073,7116 ,6084,6027,6079 ,0,0,0}, - {7119,7122,7113 ,6082,6085,6076 ,0,0,0}, {7073,7072,7118 ,6027,6026,6081 ,0,0,0}, - {7123,7088,7113 ,6086,6043,6076 ,0,0,0}, {7122,7119,7072 ,6085,6082,6026 ,0,0,0}, - {7124,7087,7084 ,6087,6042,6039 ,0,0,0}, {7113,7122,7123 ,6076,6085,6086 ,0,0,0}, - {7123,7089,7088 ,6086,6044,6043 ,0,0,0}, {7120,7087,7124 ,6083,6042,6087 ,0,0,0}, - {7114,7088,7087 ,6077,6043,6042 ,0,0,0}, {7070,7069,7117 ,6022,6021,6080 ,0,0,0}, - {7125,7110,7111 ,6088,6073,6074 ,0,0,0}, {7126,7122,7072 ,6089,6085,6026 ,0,0,0}, - {7117,7121,7116 ,6080,6084,6079 ,0,0,0}, {7110,7065,7121 ,6073,6015,6084 ,0,0,0}, - {7127,7123,7122 ,6090,6086,6085 ,0,0,0}, {7065,7074,7073 ,6015,6028,6027 ,0,0,0}, - {7128,7089,7123 ,6091,6044,6086 ,0,0,0}, {7074,7126,7072 ,6028,6089,6026 ,0,0,0}, - {7096,7082,7129 ,6051,6037,6092 ,0,0,0}, {7126,7127,7122 ,6089,6090,6085 ,0,0,0}, - {7084,7089,7130 ,6039,6044,6093 ,0,0,0}, {7128,7123,7127 ,6091,6086,6090 ,0,0,0}, - {7130,7089,7128 ,6093,6044,6091 ,0,0,0}, {7124,7084,7083 ,6087,6039,6038 ,0,0,0}, - {7087,7089,7084 ,6042,6044,6039 ,0,0,0}, {7069,7110,7121 ,6021,6073,6084 ,0,0,0}, - {7066,7125,7075 ,6016,6088,6029 ,0,0,0}, {7064,7131,7074 ,6014,6094,6028 ,0,0,0}, - {7121,7065,7073 ,6084,6015,6027 ,0,0,0}, {7064,7074,7065 ,6014,6028,6015 ,0,0,0}, - {7131,7132,7126 ,6094,6095,6089 ,0,0,0}, {7131,7126,7074 ,6094,6089,6028 ,0,0,0}, - {7132,7133,7127 ,6095,6096,6090 ,0,0,0}, {7132,7127,7126 ,6095,6090,6089 ,0,0,0}, - {7133,7134,7128 ,6096,6097,6091 ,0,0,0}, {7133,7128,7127 ,6096,6091,6090 ,0,0,0}, - {7134,7129,7130 ,6097,6092,6093 ,0,0,0}, {7130,7128,7134 ,6093,6091,6097 ,0,0,0}, - {7129,7082,7130 ,6092,6037,6093 ,0,0,0}, {7083,7082,7095 ,6038,6037,6050 ,0,0,0}, - {7084,7130,7082 ,6039,6093,6037 ,0,0,0}, {7125,7066,7110 ,6088,6016,6073 ,0,0,0}, - {7065,7110,7066 ,6015,6073,6016 ,0,0,0}, {7131,6279,6273 ,6094,6025,6098 ,0,0,0}, - {6263,7064,7066 ,6024,6014,6016 ,0,0,0}, {7132,6273,6277 ,6095,6098,6099 ,0,0,0}, - {6279,7131,7064 ,6025,6094,6014 ,0,0,0}, {7133,6277,6276 ,6096,6099,6100 ,0,0,0}, - {6273,7132,7131 ,6098,6095,6094 ,0,0,0}, {7134,6276,6286 ,6097,6100,6101 ,0,0,0}, - {6277,7133,7132 ,6099,6096,6095 ,0,0,0}, {7129,6286,6248 ,6092,6101,6102 ,0,0,0}, - {6276,7134,7133 ,6100,6097,6096 ,0,0,0}, {7096,6248,6282 ,6051,6102,6053 ,0,0,0}, - {6286,7129,7134 ,6101,6092,6097 ,0,0,0}, {6282,7094,7096 ,6053,6049,6051 ,0,0,0}, - {6248,7096,7129 ,6102,6051,6092 ,0,0,0}, {7135,7136,7137 ,730,6103,6103 ,0,0,0}, - {5365,5307,5304 ,6103,730,730 ,0,0,0}, {7138,7136,7139 ,6104,6103,6105 ,0,0,0}, - {7138,7140,7141 ,6104,6106,6103 ,0,0,0}, {7142,7137,7143 ,6107,6103,6108 ,0,0,0}, - {7140,7144,7145 ,6106,6109,6110 ,0,0,0}, {7146,7147,7143 ,6103,6111,6108 ,0,0,0}, - {7145,7148,7149 ,6110,6112,6110 ,0,0,0}, {7150,7146,7151 ,6111,6103,6103 ,0,0,0}, - {7149,7152,7153 ,6110,6113,6112 ,0,0,0}, {7153,7154,7155 ,6112,6109,6110 ,0,0,0}, - {7155,7156,7157 ,6110,6106,6114 ,0,0,0}, {7151,7158,7159 ,6103,730,6115 ,0,0,0}, - {7160,7157,7161 ,6105,6114,6104 ,0,0,0}, {7162,7163,7164 ,6111,730,6111 ,0,0,0}, - {7165,7157,7160 ,6111,6114,6105 ,0,0,0}, {7164,7166,7167 ,6111,6110,6114 ,0,0,0}, - {7168,7169,7170 ,730,6114,6108 ,0,0,0}, {5313,5378,5380 ,6110,6111,6110 ,0,0,0}, - {7171,7172,7173 ,6115,730,6111 ,0,0,0}, {5377,5312,5375 ,730,730,6114 ,0,0,0}, - {7174,7175,5296 ,6111,6110,6110 ,0,0,0}, {5308,5371,5310 ,730,6114,6103 ,0,0,0}, - {5293,5343,5340 ,730,730,6114 ,0,0,0}, {5307,5366,5369 ,730,730,6103 ,0,0,0}, - {5337,5289,5338 ,6114,730,730 ,0,0,0}, {5363,5365,5304 ,730,6103,730 ,0,0,0}, - {5287,5331,5284 ,6103,6103,730 ,0,0,0}, {5357,5359,5298 ,730,730,730 ,0,0,0}, - {5325,5322,5283 ,730,730,730 ,0,0,0}, {5351,5297,5277 ,730,730,730 ,0,0,0}, - {5281,5320,5319 ,730,730,730 ,0,0,0}, {5281,5282,5320 ,730,730,730 ,0,0,0}, - {5283,5322,5282 ,730,730,730 ,0,0,0}, {5351,5277,5315 ,730,730,730 ,0,0,0}, - {5277,5281,5316 ,730,730,730 ,0,0,0}, {5326,5284,5328 ,6103,730,730 ,0,0,0}, - {5283,5284,5326 ,730,730,6103 ,0,0,0}, {5297,5354,5298 ,730,730,730 ,0,0,0}, - {5297,5353,5354 ,730,730,730 ,0,0,0}, {5287,5289,5334 ,6103,730,6103 ,0,0,0}, - {5287,5334,5332 ,6103,6103,730 ,0,0,0}, {5304,5302,5360 ,730,730,6103 ,0,0,0}, - {5359,5302,5298 ,730,730,730 ,0,0,0}, {5293,5340,5290 ,730,6114,6103 ,0,0,0}, - {5289,5290,5338 ,730,6103,730 ,0,0,0}, {5307,5365,5366 ,730,6103,730 ,0,0,0}, - {5346,5344,5296 ,6110,6111,6110 ,0,0,0}, {5293,5296,5344 ,730,6110,6111 ,0,0,0}, - {5308,5369,5371 ,730,6103,6114 ,0,0,0}, {5307,5369,5308 ,730,6103,730 ,0,0,0}, - {7173,7176,7174 ,6111,6111,6111 ,0,0,0}, {7177,7174,7176 ,6114,6111,6111 ,0,0,0}, - {5371,5372,5310 ,6114,730,6103 ,0,0,0}, {5310,5375,5312 ,6103,6114,730 ,0,0,0}, - {5372,5375,5310 ,730,6114,6103 ,0,0,0}, {5377,5378,5312 ,730,6111,730 ,0,0,0}, - {7178,7170,7169 ,6107,6108,6114 ,0,0,0}, {5313,5312,5378 ,6110,730,6111 ,0,0,0}, - {5380,7166,5313 ,6110,6110,6110 ,0,0,0}, {7169,7165,7179 ,6114,6111,730 ,0,0,0}, - {7180,7181,7168 ,6111,6110,730 ,0,0,0}, {7181,7171,7173 ,6110,6115,6111 ,0,0,0}, - {7154,7156,7155 ,6109,6106,6110 ,0,0,0}, {5363,5304,5360 ,730,730,6103 ,0,0,0}, - {5360,5302,5359 ,6103,730,730 ,0,0,0}, {5357,5298,5354 ,730,730,730 ,0,0,0}, - {5353,5297,5351 ,730,730,730 ,0,0,0}, {5315,5277,5316 ,730,730,730 ,0,0,0}, - {5316,5281,5319 ,730,730,730 ,0,0,0}, {5320,5282,5322 ,730,730,730 ,0,0,0}, - {5325,5283,5326 ,730,730,6103 ,0,0,0}, {5328,5284,5331 ,730,730,6103 ,0,0,0}, - {5331,5287,5332 ,6103,6103,730 ,0,0,0}, {5334,5289,5337 ,6103,730,6114 ,0,0,0}, - {5338,5290,5340 ,730,6103,6114 ,0,0,0}, {5343,5293,5344 ,730,730,6111 ,0,0,0}, - {5346,5296,7175 ,6110,6110,6110 ,0,0,0}, {7175,7174,7177 ,6110,6111,6114 ,0,0,0}, - {7176,7173,7172 ,6111,6111,730 ,0,0,0}, {7171,7181,7180 ,6115,6110,6111 ,0,0,0}, - {7182,7168,7170 ,6111,730,6108 ,0,0,0}, {7168,7182,7180 ,730,6111,6111 ,0,0,0}, - {7178,7169,7179 ,6107,6114,730 ,0,0,0}, {7179,7165,7160 ,730,6111,6105 ,0,0,0}, - {7161,7157,7156 ,6104,6114,6106 ,0,0,0}, {7155,7149,7153 ,6110,6110,6112 ,0,0,0}, - {7152,7149,7148 ,6113,6110,6112 ,0,0,0}, {7148,7145,7144 ,6112,6110,6109 ,0,0,0}, - {7140,7145,7141 ,6106,6110,6103 ,0,0,0}, {7138,7141,7136 ,6104,6103,6103 ,0,0,0}, - {7135,7139,7136 ,730,6105,6103 ,0,0,0}, {7142,7135,7137 ,6107,730,6103 ,0,0,0}, - {7146,7143,7137 ,6103,6108,6103 ,0,0,0}, {7146,7150,7147 ,6103,6111,6111 ,0,0,0}, - {7151,7159,7150 ,6103,6115,6111 ,0,0,0}, {7151,7163,7158 ,6103,730,730 ,0,0,0}, - {7162,7164,7167 ,6111,6111,6114 ,0,0,0}, {7158,7163,7162 ,730,730,6111 ,0,0,0}, - {7166,7164,5313 ,6110,6111,6110 ,0,0,0}, {5349,5317,7183 ,6116,6117,6118 ,0,0,0}, - {5352,7184,7185 ,6119,6120,6121 ,0,0,0}, {7186,7187,5504 ,6122,6123,6124 ,0,0,0}, - {5594,5364,5591 ,6125,6126,6127 ,0,0,0}, {5520,5519,5931 ,6128,6129,6130 ,0,0,0}, - {5450,5453,5374 ,6131,6132,6122 ,0,0,0}, {7188,5455,7189 ,6133,6134,6135 ,0,0,0}, - {7190,7191,7192 ,6136,6137,6138 ,0,0,0}, {5321,5401,5404 ,6122,6120,6139 ,0,0,0}, - {7187,5489,5494 ,6123,6140,6141 ,0,0,0}, {7193,5572,5574 ,6139,6142,6143 ,0,0,0}, - {5844,7194,5845 ,6144,6145,6146 ,0,0,0}, {5902,7195,5895 ,6147,6148,6149 ,0,0,0}, - {5422,7196,5425 ,6150,6144,6150 ,0,0,0}, {7197,5480,5879 ,6151,6134,6152 ,0,0,0}, - {7198,5381,7199 ,6145,6153,6154 ,0,0,0}, {7197,5879,7200 ,6151,6152,6155 ,0,0,0}, - {7201,5879,5878 ,6156,6152,6157 ,0,0,0}, {7202,7203,7204 ,6158,6144,6159 ,0,0,0}, - {7205,7206,7207 ,6160,6161,6162 ,0,0,0}, {5878,7208,7201 ,6157,6163,6156 ,0,0,0}, - {7209,7210,5878 ,6158,6164,6157 ,0,0,0}, {5884,7211,7209 ,6155,6165,6158 ,0,0,0}, - {7212,5889,7213 ,6166,6167,6116 ,0,0,0}, {5884,7209,5878 ,6155,6158,6157 ,0,0,0}, - {5896,7213,5889 ,6168,6116,6167 ,0,0,0}, {7204,7192,7191 ,6159,6138,6137 ,0,0,0}, - {7214,7215,7216 ,6122,6169,6170 ,0,0,0}, {7217,5884,5882 ,6171,6155,6172 ,0,0,0}, - {5882,7218,7217 ,6172,6118,6171 ,0,0,0}, {7219,7220,5892 ,6173,6174,6175 ,0,0,0}, - {5882,5881,7218 ,6172,6176,6118 ,0,0,0}, {5881,7220,7221 ,6176,6174,6177 ,0,0,0}, - {7222,5545,5544 ,6120,6146,6154 ,0,0,0}, {5881,5892,7220 ,6176,6175,6174 ,0,0,0}, - {7219,5892,5887 ,6173,6175,6178 ,0,0,0}, {7199,5383,7223 ,6154,6120,6145 ,0,0,0}, - {7224,7225,7226 ,6177,6179,6180 ,0,0,0}, {7227,7219,5887 ,6181,6173,6178 ,0,0,0}, - {7225,7228,7214 ,6179,6182,6122 ,0,0,0}, {7202,7229,7203 ,6158,6183,6144 ,0,0,0}, - {7216,7215,7230 ,6170,6169,6184 ,0,0,0}, {5896,5895,7231 ,6168,6149,6185 ,0,0,0}, - {7232,5329,7233 ,6186,6187,6119 ,0,0,0}, {5425,7234,5426 ,6150,6144,6188 ,0,0,0}, - {7235,5847,7236 ,6145,6144,6150 ,0,0,0}, {7229,5612,7237 ,6183,6189,6190 ,0,0,0}, - {5842,7238,7239 ,6154,6120,6127 ,0,0,0}, {5579,5578,5942 ,6191,6142,6192 ,0,0,0}, - {7184,5352,5350 ,6120,6119,6122 ,0,0,0}, {5936,5510,5509 ,6193,6194,6195 ,0,0,0}, - {5581,5837,5831 ,6196,6186,6197 ,0,0,0}, {5457,5379,5376 ,6196,6134,6138 ,0,0,0}, - {7187,5608,5603 ,6123,6198,6199 ,0,0,0}, {5374,5453,5376 ,6122,6132,6138 ,0,0,0}, - {5449,5450,5373 ,6157,6131,6137 ,0,0,0}, {5449,5373,5370 ,6157,6137,6131 ,0,0,0}, - {5368,5447,5370 ,6200,6143,6131 ,0,0,0}, {5356,5567,5585 ,6117,6201,6202 ,0,0,0}, - {7190,7240,7241 ,6136,6200,6156 ,0,0,0}, {5441,7242,5436 ,6118,6203,6132 ,0,0,0}, - {7243,5443,5445 ,6133,6204,6133 ,0,0,0}, {5373,5450,5374 ,6137,6131,6122 ,0,0,0}, - {5453,5457,5376 ,6132,6196,6138 ,0,0,0}, {5443,7244,5438 ,6204,6153,6201 ,0,0,0}, - {7245,5436,7242 ,6201,6132,6203 ,0,0,0}, {5358,5356,5585 ,6187,6117,6202 ,0,0,0}, - {5370,5447,5449 ,6131,6143,6157 ,0,0,0}, {5432,5862,5864 ,6132,6144,6205 ,0,0,0}, - {5445,5597,7243 ,6133,6201,6133 ,0,0,0}, {5368,5597,5447 ,6200,6201,6143 ,0,0,0}, - {5869,5431,5864 ,6206,6116,6205 ,0,0,0}, {5463,5869,5871 ,6207,6206,6204 ,0,0,0}, - {7246,7247,5437 ,6132,6119,6207 ,0,0,0}, {5862,5432,5436 ,6144,6132,6132 ,0,0,0}, - {5431,5869,5461 ,6116,6206,6121 ,0,0,0}, {5431,5432,5864 ,6116,6132,6205 ,0,0,0}, - {5872,5467,5871 ,6208,6207,6204 ,0,0,0}, {5463,5461,5869 ,6207,6121,6206 ,0,0,0}, - {5464,5463,5871 ,6209,6207,6204 ,0,0,0}, {5872,5874,5470 ,6208,6142,6196 ,0,0,0}, - {5467,5464,5871 ,6207,6209,6204 ,0,0,0}, {5469,5467,5872 ,6133,6207,6208 ,0,0,0}, - {5872,5470,5469 ,6208,6196,6133 ,0,0,0}, {5874,5473,5470 ,6142,6134,6196 ,0,0,0}, - {5877,5475,5874 ,6148,6131,6142 ,0,0,0}, {5874,5475,5473 ,6142,6131,6134 ,0,0,0}, - {5877,5476,5475 ,6148,6205,6131 ,0,0,0}, {5476,5877,5479 ,6205,6148,6204 ,0,0,0}, - {5877,5480,5479 ,6148,6134,6204 ,0,0,0}, {7201,7200,5879 ,6156,6155,6152 ,0,0,0}, - {7217,7211,5884 ,6171,6165,6155 ,0,0,0}, {7210,7208,5878 ,6164,6163,6157 ,0,0,0}, - {7218,5881,7221 ,6118,6176,6177 ,0,0,0}, {7212,7248,5887 ,6166,6210,6178 ,0,0,0}, - {7249,5901,7250 ,6157,6190,6211 ,0,0,0}, {7227,7251,7252 ,6181,6212,6182 ,0,0,0}, - {5493,7187,5494 ,6174,6123,6141 ,0,0,0}, {7253,7254,7187 ,6213,6214,6123 ,0,0,0}, - {5939,5936,5483 ,6215,6193,6216 ,0,0,0}, {5622,5624,5484 ,6217,6218,6219 ,0,0,0}, - {5509,5483,5936 ,6195,6216,6193 ,0,0,0}, {5514,5513,5928 ,6220,6221,6222 ,0,0,0}, - {5510,5935,5513 ,6194,6223,6221 ,0,0,0}, {5931,5519,5516 ,6130,6129,6181 ,0,0,0}, - {5516,5928,5931 ,6181,6222,6130 ,0,0,0}, {5525,5932,5526 ,6224,6225,6226 ,0,0,0}, - {5522,5931,5932 ,6227,6130,6225 ,0,0,0}, {5602,7187,5603 ,6212,6123,6199 ,0,0,0}, - {5533,7255,5534 ,6203,6228,6201 ,0,0,0}, {5624,5485,5484 ,6218,6229,6219 ,0,0,0}, - {7256,7257,7258 ,6230,6231,6232 ,0,0,0}, {5624,5625,5904 ,6218,6200,6233 ,0,0,0}, - {5525,5522,5932 ,6224,6227,6225 ,0,0,0}, {5932,5528,5526 ,6225,6234,6226 ,0,0,0}, - {5522,5520,5931 ,6227,6128,6130 ,0,0,0}, {5602,5601,7187 ,6212,6235,6123 ,0,0,0}, - {5514,5928,5516 ,6220,6222,6181 ,0,0,0}, {5935,5928,5513 ,6223,6222,6221 ,0,0,0}, - {5936,5935,5510 ,6193,6223,6194 ,0,0,0}, {5485,5939,5483 ,6229,6215,6216 ,0,0,0}, - {5939,5485,5904 ,6215,6229,6233 ,0,0,0}, {7254,5609,7187 ,6214,6236,6123 ,0,0,0}, - {5612,5609,7237 ,6189,6236,6190 ,0,0,0}, {7187,7259,7260 ,6123,6170,6214 ,0,0,0}, - {5501,7187,5497 ,6237,6123,6167 ,0,0,0}, {7186,7259,7187 ,6122,6170,6123 ,0,0,0}, - {5503,7261,7262 ,6238,6180,6179 ,0,0,0}, {7263,5540,7264 ,6197,6165,6196 ,0,0,0}, - {7265,5345,7266 ,6131,6122,6132 ,0,0,0}, {5508,7267,7261 ,6239,6240,6180 ,0,0,0}, - {7268,7269,7207 ,6171,6152,6162 ,0,0,0}, {5336,7270,5335 ,6204,6208,6126 ,0,0,0}, - {7271,7230,7272 ,6241,6184,6136 ,0,0,0}, {7273,5551,5554 ,6179,6179,6202 ,0,0,0}, - {5563,7270,5562 ,6127,6208,6242 ,0,0,0}, {5688,7274,7275 ,6156,6200,6136 ,0,0,0}, - {5691,5693,7276 ,6137,6135,6133 ,0,0,0}, {7277,7278,7279 ,6207,6133,6208 ,0,0,0}, - {5649,5682,5685 ,6196,6158,6159 ,0,0,0}, {5672,5642,5637 ,6181,6243,6139 ,0,0,0}, - {5656,5658,7280 ,6244,6245,6246 ,0,0,0}, {5635,7281,7282 ,6247,6190,6136 ,0,0,0}, - {7283,7257,7284 ,6248,6231,6170 ,0,0,0}, {7285,7286,5664 ,6152,6249,6250 ,0,0,0}, - {7287,7257,7283 ,6251,6231,6248 ,0,0,0}, {7288,7289,7290 ,6252,6253,6254 ,0,0,0}, - {7289,7256,7290 ,6253,6230,6254 ,0,0,0}, {7291,7292,7293 ,6255,6256,6257 ,0,0,0}, - {7294,7295,7296 ,6258,6259,6260 ,0,0,0}, {7289,7288,7296 ,6253,6252,6260 ,0,0,0}, - {7296,7295,7289 ,6260,6259,6253 ,0,0,0}, {7295,7294,7297 ,6259,6258,6261 ,0,0,0}, - {7298,7293,7299 ,6262,6257,6263 ,0,0,0}, {7297,7299,7295 ,6261,6263,6259 ,0,0,0}, - {7293,7292,7299 ,6257,6256,6263 ,0,0,0}, {7300,7301,7292 ,6264,6265,6256 ,0,0,0}, - {7297,7298,7299 ,6261,6262,6263 ,0,0,0}, {7291,7300,7292 ,6255,6264,6256 ,0,0,0}, - {7290,7256,7258 ,6254,6230,6232 ,0,0,0}, {7302,7303,5665 ,6138,6134,6266 ,0,0,0}, - {7258,7257,7287 ,6232,6231,6251 ,0,0,0}, {7284,7303,7302 ,6170,6134,6138 ,0,0,0}, - {7304,5658,5659 ,6267,6245,6268 ,0,0,0}, {5636,7282,7305 ,6167,6136,6199 ,0,0,0}, - {5653,5656,7281 ,6235,6244,6190 ,0,0,0}, {7306,5707,7307 ,6197,6164,6191 ,0,0,0}, - {5701,5700,7308 ,6171,6118,6269 ,0,0,0}, {5646,5643,5676 ,6270,6270,6174 ,0,0,0}, - {7306,5709,5707 ,6197,6163,6164 ,0,0,0}, {5681,5646,5676 ,6127,6270,6174 ,0,0,0}, - {7309,7241,7240 ,6137,6156,6200 ,0,0,0}, {7310,7311,7312 ,6213,6271,6169 ,0,0,0}, - {5670,5672,7313 ,6173,6181,6272 ,0,0,0}, {5712,5709,7306 ,6156,6163,6197 ,0,0,0}, - {7302,7314,7284 ,6138,6273,6170 ,0,0,0}, {7315,5713,5712 ,6201,6155,6156 ,0,0,0}, - {7315,5717,5715 ,6201,6134,6151 ,0,0,0}, {7316,7270,7317 ,6214,6208,6133 ,0,0,0}, - {7316,5330,5333 ,6214,6208,6117 ,0,0,0}, {7318,7319,7320 ,6190,6214,6199 ,0,0,0}, - {5707,5706,7307 ,6164,6158,6191 ,0,0,0}, {5701,7308,7307 ,6171,6269,6191 ,0,0,0}, - {7321,7322,7323 ,6274,6118,6183 ,0,0,0}, {7324,7325,7326 ,6149,6275,6214 ,0,0,0}, - {7327,7283,7314 ,6243,6248,6273 ,0,0,0}, {7327,7314,7328 ,6243,6273,6276 ,0,0,0}, - {7326,7216,7230 ,6214,6170,6184 ,0,0,0}, {7214,7228,7215 ,6122,6182,6169 ,0,0,0}, - {7226,7329,7224 ,6180,6244,6177 ,0,0,0}, {7225,7224,7228 ,6179,6177,6182 ,0,0,0}, - {7202,7330,5613 ,6158,6127,6249 ,0,0,0}, {5508,7329,7267 ,6239,6244,6240 ,0,0,0}, - {7226,7267,7329 ,6180,6240,6244 ,0,0,0}, {5508,7261,5505 ,6239,6180,6277 ,0,0,0}, - {7202,5613,5612 ,6158,6249,6189 ,0,0,0}, {5504,5503,7262 ,6124,6238,6179 ,0,0,0}, - {5503,5505,7261 ,6238,6277,6180 ,0,0,0}, {5631,5899,5907 ,6278,6279,6280 ,0,0,0}, - {5899,7250,5901 ,6279,6211,6190 ,0,0,0}, {7186,5504,7262 ,6122,6124,6179 ,0,0,0}, - {7331,7187,7260 ,6275,6123,6214 ,0,0,0}, {5504,7187,5501 ,6124,6123,6237 ,0,0,0}, - {5905,5628,5907 ,6281,6282,6280 ,0,0,0}, {5615,7330,7332 ,6283,6127,6174 ,0,0,0}, - {5613,7330,5615 ,6249,6127,6283 ,0,0,0}, {7203,7192,7204 ,6144,6138,6159 ,0,0,0}, - {7190,7241,7191 ,6136,6156,6137 ,0,0,0}, {7309,7188,7189 ,6137,6133,6135 ,0,0,0}, - {7188,7309,7240 ,6133,6137,6200 ,0,0,0}, {7188,5379,5455 ,6133,6134,6134 ,0,0,0}, - {5862,7245,5860 ,6144,6201,6209 ,0,0,0}, {5455,5379,5457 ,6134,6134,6196 ,0,0,0}, - {5597,5368,5596 ,6201,6200,6158 ,0,0,0}, {5361,5358,5588 ,6208,6187,6284 ,0,0,0}, - {5594,5596,5367 ,6125,6158,6204 ,0,0,0}, {7333,5857,5858 ,6191,6165,6179 ,0,0,0}, - {5855,7334,5832 ,6142,6172,6197 ,0,0,0}, {5579,5837,5581 ,6191,6186,6196 ,0,0,0}, - {5942,5837,5579 ,6192,6186,6191 ,0,0,0}, {5942,5578,5840 ,6192,6142,6285 ,0,0,0}, - {7335,5575,5572 ,6192,6228,6142 ,0,0,0}, {5401,5321,5323 ,6120,6122,6119 ,0,0,0}, - {5324,5399,5323 ,6171,6202,6119 ,0,0,0}, {7336,5852,5850 ,6150,6144,6150 ,0,0,0}, - {7196,5422,5420 ,6144,6150,6187 ,0,0,0}, {5428,5426,7234 ,6150,6188,6144 ,0,0,0}, - {5420,7337,7196 ,6187,6144,6144 ,0,0,0}, {5394,7232,7338 ,6165,6186,6286 ,0,0,0}, - {7337,5416,7339 ,6144,6192,6144 ,0,0,0}, {5414,5413,7339 ,6145,6145,6144 ,0,0,0}, - {7340,7341,7270 ,6143,6133,6208 ,0,0,0}, {7222,7342,5545 ,6120,6176,6146 ,0,0,0}, - {7265,5342,5345 ,6131,6137,6122 ,0,0,0}, {5348,5693,5692 ,6134,6135,6134 ,0,0,0}, - {7264,5535,5534 ,6196,6139,6201 ,0,0,0}, {7263,5541,5538 ,6197,6286,6165 ,0,0,0}, - {7273,5554,7343 ,6179,6202,6139 ,0,0,0}, {5557,7343,5556 ,6203,6139,6228 ,0,0,0}, - {5691,7276,7274 ,6137,6133,6200 ,0,0,0}, {7274,5688,5691 ,6200,6156,6137 ,0,0,0}, - {7344,7345,7346 ,6209,6207,6166 ,0,0,0}, {7347,5686,7275 ,6138,6137,6136 ,0,0,0}, - {7342,5547,5545 ,6176,6191,6146 ,0,0,0}, {7348,7349,7350 ,6186,6228,6287 ,0,0,0}, - {5541,7263,7222 ,6286,6197,6120 ,0,0,0}, {5541,7222,5544 ,6286,6120,6154 ,0,0,0}, - {5540,7263,5538 ,6165,6197,6165 ,0,0,0}, {5535,7264,5540 ,6139,6196,6165 ,0,0,0}, - {7255,5533,5551 ,6228,6203,6179 ,0,0,0}, {7255,7264,5534 ,6228,6196,6201 ,0,0,0}, - {5339,7270,5336 ,6200,6208,6204 ,0,0,0}, {7273,7255,5551 ,6179,6228,6179 ,0,0,0}, - {7351,7343,5557 ,6133,6139,6203 ,0,0,0}, {5556,7343,5554 ,6228,6139,6202 ,0,0,0}, - {5339,5341,7270 ,6200,6131,6208 ,0,0,0}, {7270,7352,5562 ,6208,6207,6242 ,0,0,0}, - {5347,5692,7353 ,6138,6134,6196 ,0,0,0}, {7270,5341,5342 ,6208,6131,6137 ,0,0,0}, - {7270,5333,5335 ,6208,6117,6126 ,0,0,0}, {5330,7316,7233 ,6208,6214,6119 ,0,0,0}, - {7270,7316,5333 ,6208,6214,6117 ,0,0,0}, {7198,5410,5381 ,6145,6120,6153 ,0,0,0}, - {7354,7355,5385 ,6201,6121,6288 ,0,0,0}, {5329,5330,7233 ,6187,6208,6119 ,0,0,0}, - {7356,5387,5389 ,6139,6192,6131 ,0,0,0}, {7223,5385,7355 ,6145,6288,6121 ,0,0,0}, - {5420,5419,7337 ,6187,6145,6144 ,0,0,0}, {5419,5416,7337 ,6145,6192,6144 ,0,0,0}, - {5413,5410,7198 ,6145,6120,6145 ,0,0,0}, {7355,7357,7223 ,6121,6289,6145 ,0,0,0}, - {7348,7357,7358 ,6186,6289,6191 ,0,0,0}, {7355,7358,7357 ,6121,6191,6289 ,0,0,0}, - {7348,7350,7342 ,6186,6287,6176 ,0,0,0}, {7348,7358,7349 ,6186,6191,6228 ,0,0,0}, - {5547,7342,7350 ,6191,6176,6287 ,0,0,0}, {7359,5350,5349 ,6202,6122,6116 ,0,0,0}, - {7360,7361,5830 ,6165,6191,6187 ,0,0,0}, {7362,5858,5860 ,6126,6179,6209 ,0,0,0}, - {7363,7238,5840 ,6154,6120,6285 ,0,0,0}, {5567,5356,7364 ,6201,6117,6120 ,0,0,0}, - {7365,7366,5569 ,6197,6201,6207 ,0,0,0}, {7185,7364,5355 ,6121,6120,6171 ,0,0,0}, - {5318,5406,5405 ,6116,6120,6201 ,0,0,0}, {7185,5355,5352 ,6121,6171,6119 ,0,0,0}, - {5358,5585,5588 ,6187,6202,6284 ,0,0,0}, {5588,5590,5361 ,6284,6140,6208 ,0,0,0}, - {5362,5590,5591 ,6117,6140,6127 ,0,0,0}, {5362,5591,5364 ,6117,6127,6126 ,0,0,0}, - {5364,5594,5367 ,6126,6125,6204 ,0,0,0}, {5368,5367,5596 ,6200,6204,6158 ,0,0,0}, - {5445,5447,5597 ,6133,6143,6201 ,0,0,0}, {5441,5437,7247 ,6118,6207,6119 ,0,0,0}, - {5443,7243,7244 ,6204,6133,6153 ,0,0,0}, {7246,5437,5438 ,6132,6207,6201 ,0,0,0}, - {7246,5438,7244 ,6132,6201,6153 ,0,0,0}, {7242,5441,7247 ,6203,6118,6119 ,0,0,0}, - {5436,7245,5862 ,6132,6201,6144 ,0,0,0}, {7362,5860,7245 ,6126,6209,6201 ,0,0,0}, - {7367,5857,7333 ,6242,6165,6191 ,0,0,0}, {7333,5858,7362 ,6191,6179,6126 ,0,0,0}, - {5855,7367,7368 ,6142,6242,6197 ,0,0,0}, {7367,5855,5857 ,6242,6142,6165 ,0,0,0}, - {7334,7360,5832 ,6172,6165,6197 ,0,0,0}, {7368,7334,5855 ,6197,6172,6142 ,0,0,0}, - {5830,7361,5831 ,6187,6191,6197 ,0,0,0}, {5832,7360,5830 ,6197,6165,6187 ,0,0,0}, - {5581,5831,7369 ,6196,6197,6202 ,0,0,0}, {5831,7361,7369 ,6197,6191,6202 ,0,0,0}, - {7229,7202,5612 ,6183,6158,6189 ,0,0,0}, {7332,7370,7371 ,6174,6118,6273 ,0,0,0}, - {5606,7187,5609 ,6290,6123,6236 ,0,0,0}, {7254,7237,5609 ,6214,6190,6236 ,0,0,0}, - {5606,5608,7187 ,6290,6198,6123 ,0,0,0}, {5498,7187,5493 ,6152,6123,6174 ,0,0,0}, - {5619,5622,5490 ,6124,6217,6291 ,0,0,0}, {5601,5489,7187 ,6235,6140,6123 ,0,0,0}, - {5619,5490,5489 ,6124,6291,6140 ,0,0,0}, {5619,5489,5601 ,6124,6140,6235 ,0,0,0}, - {5622,5484,5490 ,6217,6219,6291 ,0,0,0}, {5624,5904,5485 ,6218,6233,6229 ,0,0,0}, - {5625,5628,5905 ,6200,6282,6281 ,0,0,0}, {5625,5905,5904 ,6200,6281,6233 ,0,0,0}, - {5630,5631,5907 ,6269,6278,6280 ,0,0,0}, {5628,5630,5907 ,6282,6269,6280 ,0,0,0}, - {5899,5631,7372 ,6279,6278,6292 ,0,0,0}, {7372,7250,5899 ,6292,6211,6279 ,0,0,0}, - {7373,5901,7249 ,6293,6190,6157 ,0,0,0}, {5902,7373,7374 ,6147,6293,6266 ,0,0,0}, - {7373,5902,5901 ,6293,6147,6190 ,0,0,0}, {7195,7375,5895 ,6148,6273,6149 ,0,0,0}, - {7374,7195,5902 ,6266,6148,6147 ,0,0,0}, {7231,7376,5896 ,6185,6294,6168 ,0,0,0}, - {7375,7231,5895 ,6273,6185,6149 ,0,0,0}, {5887,5889,7212 ,6178,6167,6166 ,0,0,0}, - {7376,7213,5896 ,6294,6116,6168 ,0,0,0}, {7248,7227,5887 ,6210,6181,6178 ,0,0,0}, - {7252,7251,7370 ,6182,6212,6118 ,0,0,0}, {7248,7251,7227 ,6210,6212,6181 ,0,0,0}, - {7332,7371,5615 ,6174,6273,6283 ,0,0,0}, {7370,7251,7371 ,6118,6212,6273 ,0,0,0}, - {5637,7305,7313 ,6139,6199,6272 ,0,0,0}, {5668,7377,5697 ,6174,6295,6177 ,0,0,0}, - {7268,7327,7328 ,6171,6243,6276 ,0,0,0}, {5703,5701,7307 ,6165,6171,6191 ,0,0,0}, - {7377,5668,7378 ,6295,6174,6162 ,0,0,0}, {7313,5672,5637 ,6272,6181,6139 ,0,0,0}, - {5636,7305,5637 ,6167,6199,6139 ,0,0,0}, {5635,7282,5636 ,6247,6136,6167 ,0,0,0}, - {5653,7281,5635 ,6235,6190,6247 ,0,0,0}, {7280,7281,5656 ,6246,6190,6244 ,0,0,0}, - {7304,7280,5658 ,6267,6246,6245 ,0,0,0}, {5659,5662,7286 ,6268,6185,6249 ,0,0,0}, - {7286,7304,5659 ,6249,6267,6268 ,0,0,0}, {5665,7285,5664 ,6266,6152,6250 ,0,0,0}, - {5664,7286,5662 ,6250,6249,6185 ,0,0,0}, {5665,7303,7285 ,6266,6134,6152 ,0,0,0}, - {7283,7284,7314 ,6248,6170,6273 ,0,0,0}, {7271,7379,7230 ,6241,6296,6184 ,0,0,0}, - {7268,7328,7269 ,6171,6276,6152 ,0,0,0}, {7271,7272,7380 ,6241,6136,6200 ,0,0,0}, - {7380,7206,7205 ,6200,6161,6160 ,0,0,0}, {7205,7207,7269 ,6160,6162,6152 ,0,0,0}, - {7380,7272,7206 ,6200,6136,6161 ,0,0,0}, {7379,7324,7326 ,6296,6149,6214 ,0,0,0}, - {7326,7230,7379 ,6214,6184,6296 ,0,0,0}, {7311,7325,7324 ,6271,6275,6149 ,0,0,0}, - {7312,7319,7310 ,6169,6214,6213 ,0,0,0}, {7311,7310,7325 ,6271,6213,6275 ,0,0,0}, - {7320,7321,7318 ,6199,6274,6190 ,0,0,0}, {7312,7320,7319 ,6169,6199,6214 ,0,0,0}, - {7323,7322,7381 ,6183,6118,6144 ,0,0,0}, {7318,7321,7323 ,6190,6274,6183 ,0,0,0}, - {5649,7381,7322 ,6196,6144,6118 ,0,0,0}, {5324,5327,5398 ,6171,6117,6139 ,0,0,0}, - {7234,5430,5428 ,6144,6150,6150 ,0,0,0}, {7234,5425,7196 ,6144,6150,6144 ,0,0,0}, - {5395,5398,5327 ,6197,6139,6117 ,0,0,0}, {5329,7232,5395 ,6187,6186,6197 ,0,0,0}, - {7198,7339,5413 ,6145,6144,6145 ,0,0,0}, {5416,5414,7339 ,6192,6145,6144 ,0,0,0}, - {5383,5385,7223 ,6120,6288,6145 ,0,0,0}, {5381,5383,7199 ,6153,6120,6154 ,0,0,0}, - {5389,5394,7338 ,6131,6165,6286 ,0,0,0}, {5391,7382,7354 ,6144,6242,6201 ,0,0,0}, - {7354,5385,5391 ,6201,6288,6144 ,0,0,0}, {7338,7356,5389 ,6286,6139,6131 ,0,0,0}, - {5387,7356,7382 ,6192,6139,6242 ,0,0,0}, {5387,7382,5391 ,6192,6242,6144 ,0,0,0}, - {5394,5395,7232 ,6165,6197,6186 ,0,0,0}, {5327,5329,5395 ,6117,6187,6197 ,0,0,0}, - {5324,5398,5399 ,6171,6139,6202 ,0,0,0}, {5323,5399,5401 ,6119,6202,6120 ,0,0,0}, - {5406,5318,5404 ,6120,6116,6139 ,0,0,0}, {5321,5404,5318 ,6122,6139,6116 ,0,0,0}, - {5318,5405,5317 ,6116,6201,6117 ,0,0,0}, {5350,7359,7184 ,6122,6202,6120 ,0,0,0}, - {5317,5405,7183 ,6117,6201,6118 ,0,0,0}, {7359,5349,7183 ,6202,6116,6118 ,0,0,0}, - {7364,5356,5355 ,6120,6117,6171 ,0,0,0}, {7365,5568,7364 ,6197,6197,6120 ,0,0,0}, - {5567,7364,5568 ,6201,6120,6197 ,0,0,0}, {5575,7383,5578 ,6228,6145,6142 ,0,0,0}, - {5574,5569,7366 ,6143,6207,6201 ,0,0,0}, {5569,5568,7365 ,6207,6197,6197 ,0,0,0}, - {7335,5572,7193 ,6192,6142,6139 ,0,0,0}, {7193,5574,7366 ,6139,6143,6201 ,0,0,0}, - {5575,7335,7383 ,6228,6192,6145 ,0,0,0}, {7363,5840,5578 ,6154,6285,6142 ,0,0,0}, - {7363,5578,7383 ,6154,6142,6145 ,0,0,0}, {7238,5842,5840 ,6120,6154,6285 ,0,0,0}, - {5844,7239,7384 ,6144,6127,6187 ,0,0,0}, {7239,5844,5842 ,6127,6144,6154 ,0,0,0}, - {7384,7194,5844 ,6187,6145,6144 ,0,0,0}, {5845,7385,7236 ,6146,6145,6150 ,0,0,0}, - {7194,7385,5845 ,6145,6145,6146 ,0,0,0}, {5845,7236,5847 ,6146,6150,6144 ,0,0,0}, - {5850,5847,7386 ,6150,6144,6146 ,0,0,0}, {7235,7386,5847 ,6145,6146,6144 ,0,0,0}, - {5850,7387,7336 ,6150,6144,6150 ,0,0,0}, {5850,7386,7387 ,6150,6146,6144 ,0,0,0}, - {7388,5852,7389 ,6150,6144,6150 ,0,0,0}, {5852,7336,7389 ,6144,6150,6150 ,0,0,0}, - {5430,5852,7388 ,6150,6144,6150 ,0,0,0}, {7390,7391,7392 ,6131,6203,6207 ,0,0,0}, - {7347,7381,5685 ,6138,6144,6159 ,0,0,0}, {7315,5712,7306 ,6201,6156,6197 ,0,0,0}, - {7315,5715,5713 ,6201,6151,6155 ,0,0,0}, {7381,5649,5685 ,6144,6196,6159 ,0,0,0}, - {5670,7378,5668 ,6173,6162,6174 ,0,0,0}, {5697,7377,5700 ,6177,6295,6118 ,0,0,0}, - {5706,5703,7307 ,6158,6165,6191 ,0,0,0}, {7377,7308,5700 ,6295,6269,6118 ,0,0,0}, - {7378,5670,7313 ,6162,6173,6272 ,0,0,0}, {5672,5678,5642 ,6181,6182,6243 ,0,0,0}, - {5681,5682,5647 ,6127,6158,6297 ,0,0,0}, {5674,5640,5678 ,6118,6155,6182 ,0,0,0}, - {5642,5678,5640 ,6243,6182,6155 ,0,0,0}, {5674,5676,5643 ,6118,6174,6270 ,0,0,0}, - {5643,5640,5674 ,6270,6155,6118 ,0,0,0}, {5646,5681,5647 ,6270,6127,6297 ,0,0,0}, - {5649,5647,5682 ,6196,6297,6158 ,0,0,0}, {7347,5685,5686 ,6138,6159,6137 ,0,0,0}, - {7275,5686,5688 ,6136,6137,6156 ,0,0,0}, {7393,7394,7395 ,6205,6132,6116 ,0,0,0}, - {7394,7351,7396 ,6132,6133,6132 ,0,0,0}, {5342,7265,7270 ,6137,6131,6208 ,0,0,0}, - {7276,5693,5348 ,6133,6135,6134 ,0,0,0}, {5347,7353,7266 ,6138,6196,6132 ,0,0,0}, - {5347,5348,5692 ,6138,6134,6134 ,0,0,0}, {7266,5345,5347 ,6132,6122,6138 ,0,0,0}, - {7270,7265,7397 ,6208,6131,6157 ,0,0,0}, {7397,7340,7270 ,6157,6143,6208 ,0,0,0}, - {7396,5560,7398 ,6132,6172,6118 ,0,0,0}, {7399,7400,7270 ,6204,6201,6208 ,0,0,0}, - {7270,7401,7402 ,6208,6172,6214 ,0,0,0}, {7270,7400,7352 ,6208,6201,6207 ,0,0,0}, - {7401,7270,5563 ,6172,6208,6127 ,0,0,0}, {5562,7352,5560 ,6242,6207,6172 ,0,0,0}, - {7398,5560,7352 ,6118,6172,6207 ,0,0,0}, {7396,7351,5557 ,6132,6133,6203 ,0,0,0}, - {5557,5560,7396 ,6203,6172,6132 ,0,0,0}, {7394,7393,7351 ,6132,6205,6133 ,0,0,0}, - {7344,7395,7403 ,6209,6116,6121 ,0,0,0}, {7395,7344,7393 ,6116,6209,6205 ,0,0,0}, - {7403,7345,7344 ,6121,6207,6209 ,0,0,0}, {7346,7404,7277 ,6166,6209,6207 ,0,0,0}, - {7345,7404,7346 ,6207,6209,6166 ,0,0,0}, {7346,7277,7279 ,6166,6207,6208 ,0,0,0}, - {7392,7279,7405 ,6207,6208,6196 ,0,0,0}, {7278,7405,7279 ,6133,6196,6208 ,0,0,0}, - {7392,7406,7390 ,6207,6134,6131 ,0,0,0}, {7392,7405,7406 ,6207,6196,6134 ,0,0,0}, - {7407,7391,7408 ,6204,6203,6205 ,0,0,0}, {7391,7390,7408 ,6203,6131,6205 ,0,0,0}, - {5717,7391,7407 ,6134,6203,6204 ,0,0,0}, {7187,5498,5497 ,6123,6152,6167 ,0,0,0}, - {7187,7331,7253 ,6123,6275,6213 ,0,0,0}, {5590,5362,5361 ,6140,6117,6208 ,0,0,0}, - {7270,7341,7399 ,6208,6133,6204 ,0,0,0}, {7270,7402,7317 ,6208,6214,6133 ,0,0,0}, - {7409,6093,6092 ,6298,6299,6299 ,0,0,0}, {6098,7410,6099 ,6298,6298,6300 ,0,0,0}, - {7411,7412,5790 ,6301,6302,6302 ,0,0,0}, {6092,6089,7413 ,6299,6300,6303 ,0,0,0}, - {5787,7414,7415 ,6304,6304,6305 ,0,0,0}, {6083,7416,6086 ,6301,6299,6306 ,0,0,0}, - {5785,7417,7418 ,6305,6307,6308 ,0,0,0}, {7419,6080,6077 ,6298,6298,6309 ,0,0,0}, - {7420,5773,7421 ,6310,6311,6312 ,0,0,0}, {7422,7423,5779 ,6308,6313,6314 ,0,0,0}, - {5769,6193,7424 ,6315,6316,6317 ,0,0,0}, {7424,7425,5776 ,6317,6318,6319 ,0,0,0}, - {5764,6188,6190 ,6320,6321,6322 ,0,0,0}, {6148,5731,6146 ,6299,6303,6323 ,0,0,0}, - {6152,6154,5734 ,6324,6298,6306 ,0,0,0}, {5754,6178,6179 ,6325,6326,6327 ,0,0,0}, - {6155,6158,5742 ,6298,6328,6324 ,0,0,0}, {6170,6172,5751 ,6301,6329,6330 ,0,0,0}, - {6170,5825,6167 ,6301,6324,6331 ,0,0,0}, {5744,6164,6166 ,6332,6328,6333 ,0,0,0}, - {6164,5747,6161 ,6328,6334,6335 ,0,0,0}, {6173,5824,6172 ,6336,6298,6329 ,0,0,0}, - {6167,5752,6166 ,6331,6337,6333 ,0,0,0}, {5753,6176,6178 ,6338,6339,6326 ,0,0,0}, - {6173,6176,5756 ,6336,6339,6324 ,0,0,0}, {6158,6160,5738 ,6328,6328,6299 ,0,0,0}, - {6160,6161,5739 ,6328,6335,6340 ,0,0,0}, {5760,6182,6184 ,6341,6342,6343 ,0,0,0}, - {5762,6179,6182 ,6344,6327,6342 ,0,0,0}, {6184,6185,5758 ,6343,6345,6346 ,0,0,0}, - {6154,6155,5741 ,6298,6298,6347 ,0,0,0}, {6149,6152,5737 ,6348,6324,6316 ,0,0,0}, - {5766,6185,6188 ,6349,6345,6321 ,0,0,0}, {5765,6190,6191 ,6350,6322,6351 ,0,0,0}, - {5736,6149,5737 ,6324,6348,6316 ,0,0,0}, {5722,6143,5723 ,6300,6352,6353 ,0,0,0}, - {5771,6191,6193 ,6354,6351,6316 ,0,0,0}, {5719,6137,5720 ,6355,6299,6298 ,0,0,0}, - {6142,5728,6140 ,6299,6356,6357 ,0,0,0}, {7422,5781,7420 ,6308,6358,6310 ,0,0,0}, - {7425,7421,5772 ,6318,6312,6359 ,0,0,0}, {6075,6074,7426 ,6316,6306,6360 ,0,0,0}, - {7426,6074,5725 ,6360,6306,6299 ,0,0,0}, {7426,7427,6075 ,6360,6298,6316 ,0,0,0}, - {7423,7417,5777 ,6313,6307,6304 ,0,0,0}, {5784,7418,7428 ,6336,6308,6311 ,0,0,0}, - {5731,6148,5736 ,6303,6299,6324 ,0,0,0}, {7428,7414,5789 ,6311,6304,6314 ,0,0,0}, - {6083,6081,7429 ,6301,6300,6340 ,0,0,0}, {7430,6081,6080 ,6301,6300,6298 ,0,0,0}, - {7431,7411,5794 ,6301,6301,6333 ,0,0,0}, {5788,7415,7431 ,6361,6305,6301 ,0,0,0}, - {7432,6089,6087 ,6300,6300,6357 ,0,0,0}, {6086,7433,6087 ,6306,6355,6357 ,0,0,0}, - {7434,7435,5795 ,6353,6311,6301 ,0,0,0}, {5791,7412,7434 ,6362,6302,6353 ,0,0,0}, - {6095,6093,7436 ,6300,6299,6300 ,0,0,0}, {5796,7435,7437 ,6300,6311,6363 ,0,0,0}, - {5800,7437,7438 ,6301,6363,6353 ,0,0,0}, {5801,7438,7439 ,6300,6353,6328 ,0,0,0}, - {6095,7440,6098 ,6300,6300,6298 ,0,0,0}, {7441,5803,7439 ,6303,6352,6328 ,0,0,0}, - {7441,7442,5805 ,6303,6352,6340 ,0,0,0}, {7443,6101,6099 ,6299,6316,6300 ,0,0,0}, - {7444,5808,7442 ,6300,6340,6352 ,0,0,0}, {7445,6104,6101 ,6298,6364,6316 ,0,0,0}, - {5809,7444,7446 ,6316,6300,6306 ,0,0,0}, {7447,6105,6104 ,6364,6298,6364 ,0,0,0}, - {7446,7448,5811 ,6306,6340,6340 ,0,0,0}, {7449,6107,6105 ,6300,6300,6298 ,0,0,0}, - {7450,5814,7448 ,6323,6340,6340 ,0,0,0}, {7451,6110,6107 ,6298,6300,6300 ,0,0,0}, - {5816,7450,7452 ,6300,6323,6340 ,0,0,0}, {7453,6111,6110 ,6364,6300,6300 ,0,0,0}, - {7452,7454,5815 ,6340,6303,6303 ,0,0,0}, {7455,6113,6111 ,6300,6365,6300 ,0,0,0}, - {7456,5817,7454 ,6300,6300,6303 ,0,0,0}, {7457,6116,6113 ,6366,6300,6365 ,0,0,0}, - {5820,7456,7458 ,6300,6300,6316 ,0,0,0}, {7459,6117,6116 ,6367,6367,6300 ,0,0,0}, - {7458,7460,5821 ,6316,6300,6300 ,0,0,0}, {7461,6119,6117 ,6300,6300,6367 ,0,0,0}, - {7462,5821,7463 ,6301,6300,6300 ,0,0,0}, {7464,6122,6119 ,6368,6300,6300 ,0,0,0}, - {7465,7462,7466 ,6300,6301,6300 ,0,0,0}, {7467,6123,6122 ,6369,6367,6300 ,0,0,0}, - {7468,7465,7469 ,6316,6300,6300 ,0,0,0}, {6123,7470,6125 ,6367,6367,6300 ,0,0,0}, - {6128,6125,7471 ,6364,6300,6370 ,0,0,0}, {7472,6131,6129 ,6300,6316,6300 ,0,0,0}, - {7473,7468,7474 ,6300,6316,6316 ,0,0,0}, {7475,7476,7477 ,6300,6371,6300 ,0,0,0}, - {7478,7479,7480 ,6306,6300,6303 ,0,0,0}, {7481,7482,7483 ,6369,6300,6367 ,0,0,0}, - {7484,7485,7486 ,6301,6301,6300 ,0,0,0}, {7487,7488,7489 ,6300,6369,6367 ,0,0,0}, - {7490,7491,7492 ,6316,6316,6300 ,0,0,0}, {7493,7494,7495 ,6364,6300,6300 ,0,0,0}, - {7496,7487,7497 ,6364,6300,6316 ,0,0,0}, {7498,7499,7500 ,6300,6364,6316 ,0,0,0}, - {7495,7501,7500 ,6300,6316,6316 ,0,0,0}, {7502,7503,7504 ,6364,6372,6364 ,0,0,0}, - {7503,7496,7505 ,6372,6364,6300 ,0,0,0}, {7490,7499,7506 ,6316,6364,6367 ,0,0,0}, - {7507,7493,7502 ,6370,6364,6364 ,0,0,0}, {7483,7508,7509 ,6367,6367,6316 ,0,0,0}, - {7510,7488,7509 ,6316,6369,6316 ,0,0,0}, {7511,7484,7512 ,6306,6301,6303 ,0,0,0}, - {7512,7492,7513 ,6303,6300,6340 ,0,0,0}, {7514,7515,7477 ,6371,6300,6300 ,0,0,0}, - {7516,7481,7515 ,6300,6369,6300 ,0,0,0}, {7517,7478,7518 ,6300,6306,6300 ,0,0,0}, - {7517,7518,7486 ,6300,6300,6300 ,0,0,0}, {7519,7520,6131 ,6300,6300,6316 ,0,0,0}, - {7475,7520,7521 ,6300,6300,6316 ,0,0,0}, {7473,7522,7523 ,6300,6303,6301 ,0,0,0}, - {7479,7523,7524 ,6300,6301,6301 ,0,0,0}, {6129,6128,7525 ,6300,6364,6369 ,0,0,0}, - {6074,6073,5725 ,6306,6298,6299 ,0,0,0}, {5725,6073,6136 ,6299,6298,6340 ,0,0,0}, - {7427,7419,6077 ,6298,6298,6309 ,0,0,0}, {7427,6077,6075 ,6298,6309,6316 ,0,0,0}, - {7419,7430,6080 ,6298,6301,6298 ,0,0,0}, {7430,7429,6081 ,6301,6340,6300 ,0,0,0}, - {7429,7416,6083 ,6340,6299,6301 ,0,0,0}, {7416,7433,6086 ,6299,6355,6306 ,0,0,0}, - {7433,7432,6087 ,6355,6300,6357 ,0,0,0}, {7432,7413,6089 ,6300,6303,6300 ,0,0,0}, - {7413,7409,6092 ,6303,6298,6299 ,0,0,0}, {7409,7436,6093 ,6298,6300,6299 ,0,0,0}, - {7436,7440,6095 ,6300,6300,6300 ,0,0,0}, {7440,7410,6098 ,6300,6298,6298 ,0,0,0}, - {7410,7443,6099 ,6298,6299,6300 ,0,0,0}, {7443,7445,6101 ,6299,6298,6316 ,0,0,0}, - {7445,7447,6104 ,6298,6364,6364 ,0,0,0}, {7447,7449,6105 ,6364,6300,6298 ,0,0,0}, - {7449,7451,6107 ,6300,6298,6300 ,0,0,0}, {7451,7453,6110 ,6298,6364,6300 ,0,0,0}, - {7453,7455,6111 ,6364,6300,6300 ,0,0,0}, {7455,7457,6113 ,6300,6366,6365 ,0,0,0}, - {7457,7459,6116 ,6366,6367,6300 ,0,0,0}, {7459,7461,6117 ,6367,6300,6367 ,0,0,0}, - {7461,7464,6119 ,6300,6368,6300 ,0,0,0}, {7464,7467,6122 ,6368,6369,6300 ,0,0,0}, - {7467,7470,6123 ,6369,6367,6367 ,0,0,0}, {7470,7471,6125 ,6367,6370,6300 ,0,0,0}, - {7471,7525,6128 ,6370,6369,6364 ,0,0,0}, {7525,7472,6129 ,6369,6300,6300 ,0,0,0}, - {7472,7519,6131 ,6300,6300,6316 ,0,0,0}, {7519,7521,7520 ,6300,6316,6300 ,0,0,0}, - {7521,7476,7475 ,6316,6371,6300 ,0,0,0}, {7476,7514,7477 ,6371,6371,6300 ,0,0,0}, - {7514,7516,7515 ,6371,6300,6300 ,0,0,0}, {7516,7482,7481 ,6300,6300,6369 ,0,0,0}, - {7482,7508,7483 ,6300,6367,6367 ,0,0,0}, {7508,7510,7509 ,6367,6316,6316 ,0,0,0}, - {7510,7489,7488 ,6316,6367,6369 ,0,0,0}, {7489,7497,7487 ,6367,6316,6300 ,0,0,0}, - {7497,7505,7496 ,6316,6300,6364 ,0,0,0}, {7505,7504,7503 ,6300,6364,6372 ,0,0,0}, - {7504,7507,7502 ,6364,6370,6364 ,0,0,0}, {7507,7494,7493 ,6370,6300,6364 ,0,0,0}, - {7494,7501,7495 ,6300,6316,6300 ,0,0,0}, {7501,7498,7500 ,6316,6300,6316 ,0,0,0}, - {7498,7506,7499 ,6300,6367,6364 ,0,0,0}, {7506,7491,7490 ,6367,6316,6316 ,0,0,0}, - {7491,7513,7492 ,6316,6340,6300 ,0,0,0}, {7513,7511,7512 ,6340,6306,6303 ,0,0,0}, - {7511,7485,7484 ,6306,6301,6301 ,0,0,0}, {7485,7517,7486 ,6301,6300,6300 ,0,0,0}, - {7478,7480,7518 ,6306,6303,6300 ,0,0,0}, {7479,7524,7480 ,6300,6301,6303 ,0,0,0}, - {7523,7522,7524 ,6301,6303,6301 ,0,0,0}, {7473,7474,7522 ,6300,6316,6303 ,0,0,0}, - {7468,7469,7474 ,6316,6300,6316 ,0,0,0}, {7465,7466,7469 ,6300,6300,6300 ,0,0,0}, - {7462,7463,7466 ,6301,6300,6300 ,0,0,0}, {5821,7460,7463 ,6300,6300,6300 ,0,0,0}, - {5821,5820,7458 ,6300,6300,6316 ,0,0,0}, {5820,5817,7456 ,6300,6300,6300 ,0,0,0}, - {5817,5815,7454 ,6300,6303,6303 ,0,0,0}, {5815,5816,7452 ,6303,6300,6340 ,0,0,0}, - {5816,5814,7450 ,6300,6340,6323 ,0,0,0}, {5814,5811,7448 ,6340,6340,6340 ,0,0,0}, - {5811,5809,7446 ,6340,6316,6306 ,0,0,0}, {5809,5808,7444 ,6316,6340,6300 ,0,0,0}, - {5808,5805,7442 ,6340,6340,6352 ,0,0,0}, {5805,5803,7441 ,6340,6352,6303 ,0,0,0}, - {5803,5801,7439 ,6352,6300,6328 ,0,0,0}, {5801,5800,7438 ,6300,6301,6353 ,0,0,0}, - {5800,5796,7437 ,6301,6300,6363 ,0,0,0}, {5796,5795,7435 ,6300,6301,6311 ,0,0,0}, - {5795,5791,7434 ,6301,6362,6353 ,0,0,0}, {5791,5790,7412 ,6362,6302,6302 ,0,0,0}, - {5790,5794,7411 ,6302,6333,6301 ,0,0,0}, {5794,5788,7431 ,6333,6361,6301 ,0,0,0}, - {5788,5787,7415 ,6361,6304,6305 ,0,0,0}, {5787,5789,7414 ,6304,6314,6304 ,0,0,0}, - {5789,5784,7428 ,6314,6336,6311 ,0,0,0}, {5784,5785,7418 ,6336,6305,6308 ,0,0,0}, - {5785,5777,7417 ,6305,6304,6307 ,0,0,0}, {5777,5779,7423 ,6304,6314,6313 ,0,0,0}, - {5779,5781,7422 ,6314,6358,6308 ,0,0,0}, {5781,5773,7420 ,6358,6311,6310 ,0,0,0}, - {5773,5772,7421 ,6311,6359,6312 ,0,0,0}, {5772,5776,7425 ,6359,6319,6318 ,0,0,0}, - {5776,5769,7424 ,6319,6315,6317 ,0,0,0}, {5769,5771,6193 ,6315,6354,6316 ,0,0,0}, - {5771,5765,6191 ,6354,6350,6351 ,0,0,0}, {5765,5764,6190 ,6350,6320,6322 ,0,0,0}, - {5764,5766,6188 ,6320,6349,6321 ,0,0,0}, {5766,5758,6185 ,6349,6346,6345 ,0,0,0}, - {5758,5760,6184 ,6346,6341,6343 ,0,0,0}, {5760,5762,6182 ,6341,6344,6342 ,0,0,0}, - {5762,5754,6179 ,6344,6325,6327 ,0,0,0}, {5754,5753,6178 ,6325,6338,6326 ,0,0,0}, - {5753,5756,6176 ,6338,6324,6339 ,0,0,0}, {5756,5824,6173 ,6324,6298,6336 ,0,0,0}, - {5824,5751,6172 ,6298,6330,6329 ,0,0,0}, {5751,5825,6170 ,6330,6324,6301 ,0,0,0}, - {5825,5752,6167 ,6324,6337,6331 ,0,0,0}, {5752,5744,6166 ,6337,6332,6333 ,0,0,0}, - {5744,5747,6164 ,6332,6334,6328 ,0,0,0}, {5747,5739,6161 ,6334,6340,6335 ,0,0,0}, - {5739,5738,6160 ,6340,6299,6328 ,0,0,0}, {5738,5742,6158 ,6299,6324,6328 ,0,0,0}, - {5742,5741,6155 ,6324,6347,6298 ,0,0,0}, {5741,5734,6154 ,6347,6306,6298 ,0,0,0}, - {5734,5737,6152 ,6306,6316,6324 ,0,0,0}, {5736,6148,6149 ,6324,6299,6348 ,0,0,0}, - {5723,6146,5731 ,6353,6323,6303 ,0,0,0}, {5722,6142,6143 ,6300,6299,6352 ,0,0,0}, - {5723,6143,6146 ,6353,6352,6323 ,0,0,0}, {5728,5720,6140 ,6356,6298,6357 ,0,0,0}, - {5722,5728,6142 ,6300,6356,6299 ,0,0,0}, {6137,5719,6136 ,6299,6355,6340 ,0,0,0}, - {6140,5720,6137 ,6357,6298,6299 ,0,0,0}, {5725,6136,5719 ,6299,6340,6355 ,0,0,0}, - {7520,6133,6131 ,6373,6374,6375 ,0,0,0}, {7526,7527,7515 ,6376,6377,6378 ,0,0,0}, - {7477,7528,7475 ,6379,6380,6381 ,0,0,0}, {7509,7488,7529 ,6382,6383,6384 ,0,0,0}, - {7481,7483,7530 ,6385,6386,6387 ,0,0,0}, {7531,7532,7503 ,6388,6389,6390 ,0,0,0}, - {7533,7534,7487 ,6391,6392,6393 ,0,0,0}, {7495,7500,7535 ,6394,6395,6396 ,0,0,0}, - {7502,7493,7536 ,6397,6398,6399 ,0,0,0}, {7537,7538,7492 ,6400,6401,6402 ,0,0,0}, - {7539,7540,7499 ,6403,6404,6405 ,0,0,0}, {7486,7518,7541 ,6406,6407,6408 ,0,0,0}, - {7512,7484,7542 ,6409,6410,6411 ,0,0,0}, {7543,7544,7522 ,6412,6413,6414 ,0,0,0}, - {7545,7546,7480 ,6415,6416,6417 ,0,0,0}, {7547,7466,7548 ,6418,6419,6420 ,0,0,0}, - {7474,7469,7549 ,6421,6422,6423 ,0,0,0}, {7458,7550,7551 ,6424,6425,6426 ,0,0,0}, - {7460,7552,7463 ,6427,6428,6429 ,0,0,0}, {7553,7554,7452 ,6430,6431,6432 ,0,0,0}, - {7555,7456,7454 ,6433,6434,6435 ,0,0,0}, {7556,7448,7446 ,6436,6437,6438 ,0,0,0}, - {7450,7448,7557 ,6439,6437,6440 ,0,0,0}, {7558,7442,7559 ,6441,6442,6443 ,0,0,0}, - {7444,7558,7560 ,6444,6441,6445 ,0,0,0}, {7439,7438,7561 ,6446,6447,6448 ,0,0,0}, - {7441,7562,7559 ,6449,6450,6443 ,0,0,0}, {7437,7435,7563 ,6451,6452,6453 ,0,0,0}, - {7437,7564,7438 ,6451,6454,6447 ,0,0,0}, {7434,7412,7565 ,6455,6456,6457 ,0,0,0}, - {7434,7566,7435 ,6455,6458,6452 ,0,0,0}, {7567,7412,7411 ,6459,6456,6460 ,0,0,0}, - {7412,7567,7565 ,6456,6459,6457 ,0,0,0}, {7431,7568,7411 ,6461,6462,6460 ,0,0,0}, - {7567,7411,7568 ,6459,6460,6462 ,0,0,0}, {7431,7415,7569 ,6461,6463,6464 ,0,0,0}, - {7569,7568,7431 ,6464,6462,6461 ,0,0,0}, {7570,7415,7414 ,6465,6463,6466 ,0,0,0}, - {7415,7570,7569 ,6463,6465,6464 ,0,0,0}, {7428,7571,7414 ,6467,6468,6466 ,0,0,0}, - {7570,7414,7571 ,6465,6466,6468 ,0,0,0}, {7428,7418,7572 ,6467,6469,6470 ,0,0,0}, - {7572,7571,7428 ,6470,6468,6467 ,0,0,0}, {7573,7418,7417 ,6471,6469,6472 ,0,0,0}, - {7418,7573,7572 ,6469,6471,6470 ,0,0,0}, {7423,7574,7417 ,6473,6474,6472 ,0,0,0}, - {7573,7417,7574 ,6471,6472,6474 ,0,0,0}, {7423,7422,7575 ,6473,6475,6476 ,0,0,0}, - {7575,7574,7423 ,6476,6474,6473 ,0,0,0}, {7576,7422,7420 ,6477,6475,6478 ,0,0,0}, - {7422,7576,7575 ,6475,6477,6476 ,0,0,0}, {7421,7577,7420 ,6479,6480,6478 ,0,0,0}, - {7576,7420,7577 ,6477,6478,6480 ,0,0,0}, {7421,7425,7578 ,6479,6481,6482 ,0,0,0}, - {7578,7577,7421 ,6482,6480,6479 ,0,0,0}, {7579,7425,7424 ,6483,6481,6484 ,0,0,0}, - {7425,7579,7578 ,6481,6483,6482 ,0,0,0}, {6193,7580,7424 ,6485,6486,6484 ,0,0,0}, - {7579,7424,7580 ,6483,6484,6486 ,0,0,0}, {6192,7580,6193 ,6487,6486,6485 ,0,0,0}, - {7566,7563,7435 ,6458,6453,6452 ,0,0,0}, {7434,7565,7566 ,6455,6457,6458 ,0,0,0}, - {7564,7561,7438 ,6454,6448,6447 ,0,0,0}, {7437,7563,7564 ,6451,6453,6454 ,0,0,0}, - {7441,7439,7562 ,6449,6446,6450 ,0,0,0}, {7439,7561,7562 ,6446,6448,6450 ,0,0,0}, - {7442,7558,7444 ,6442,6441,6444 ,0,0,0}, {7442,7441,7559 ,6442,6449,6443 ,0,0,0}, - {7556,7446,7560 ,6436,6438,6445 ,0,0,0}, {7446,7444,7560 ,6438,6444,6445 ,0,0,0}, - {7450,7557,7553 ,6439,6440,6430 ,0,0,0}, {7557,7448,7556 ,6440,6437,6436 ,0,0,0}, - {7554,7454,7452 ,6431,6435,6432 ,0,0,0}, {7553,7452,7450 ,6430,6432,6439 ,0,0,0}, - {7555,7550,7456 ,6433,6425,6434 ,0,0,0}, {7554,7555,7454 ,6431,6433,6435 ,0,0,0}, - {7458,7551,7460 ,6424,6426,6427 ,0,0,0}, {7456,7550,7458 ,6434,6425,6424 ,0,0,0}, - {7463,7552,7548 ,6429,6428,6420 ,0,0,0}, {7460,7551,7552 ,6427,6426,6428 ,0,0,0}, - {7469,7466,7547 ,6422,6419,6418 ,0,0,0}, {7466,7463,7548 ,6419,6429,6420 ,0,0,0}, - {7543,7474,7549 ,6412,6421,6423 ,0,0,0}, {7549,7469,7547 ,6423,6422,6418 ,0,0,0}, - {7544,7524,7522 ,6413,6488,6414 ,0,0,0}, {7543,7522,7474 ,6412,6414,6421 ,0,0,0}, - {7480,7524,7545 ,6417,6488,6415 ,0,0,0}, {7544,7545,7524 ,6413,6415,6488 ,0,0,0}, - {7518,7546,7541 ,6407,6416,6408 ,0,0,0}, {7480,7546,7518 ,6417,6416,6407 ,0,0,0}, - {7484,7486,7581 ,6410,6406,6489 ,0,0,0}, {7486,7541,7581 ,6406,6408,6489 ,0,0,0}, - {7537,7512,7542 ,6400,6409,6411 ,0,0,0}, {7542,7484,7581 ,6411,6410,6489 ,0,0,0}, - {7538,7490,7492 ,6401,6490,6402 ,0,0,0}, {7537,7492,7512 ,6400,6402,6409 ,0,0,0}, - {7499,7490,7539 ,6405,6490,6403 ,0,0,0}, {7538,7539,7490 ,6401,6403,6490 ,0,0,0}, - {7500,7540,7535 ,6395,6404,6396 ,0,0,0}, {7499,7540,7500 ,6405,6404,6395 ,0,0,0}, - {7493,7495,7582 ,6398,6394,6491 ,0,0,0}, {7495,7535,7582 ,6394,6396,6491 ,0,0,0}, - {7531,7502,7536 ,6388,6397,6399 ,0,0,0}, {7536,7493,7582 ,6399,6398,6491 ,0,0,0}, - {7532,7496,7503 ,6389,6492,6390 ,0,0,0}, {7531,7503,7502 ,6388,6390,6397 ,0,0,0}, - {7487,7496,7533 ,6393,6492,6391 ,0,0,0}, {7532,7533,7496 ,6389,6391,6492 ,0,0,0}, - {7488,7534,7529 ,6383,6392,6384 ,0,0,0}, {7487,7534,7488 ,6393,6392,6383 ,0,0,0}, - {7483,7509,7583 ,6386,6382,6493 ,0,0,0}, {7509,7529,7583 ,6382,6384,6493 ,0,0,0}, - {7526,7481,7530 ,6376,6385,6387 ,0,0,0}, {7530,7483,7583 ,6387,6386,6493 ,0,0,0}, - {7527,7477,7515 ,6377,6379,6378 ,0,0,0}, {7526,7515,7481 ,6376,6378,6385 ,0,0,0}, - {7528,7584,7475 ,6380,6494,6381 ,0,0,0}, {7527,7528,7477 ,6377,6380,6379 ,0,0,0}, - {6133,7520,7584 ,6374,6373,6494 ,0,0,0}, {7475,7584,7520 ,6381,6494,6373 ,0,0,0}, - {6144,6030,6145 ,6495,6495,6496 ,0,0,0}, {6151,6150,6036 ,6497,6496,6496 ,0,0,0}, - {7539,7538,7585 ,6498,6499,6500 ,0,0,0}, {6027,6144,6141 ,6501,6495,6501 ,0,0,0}, - {7536,7582,7586 ,6502,6503,6503 ,0,0,0}, {6138,6021,6024 ,6496,6504,6501 ,0,0,0}, - {7587,7529,7534 ,6498,6505,6506 ,0,0,0}, {5963,6072,6076 ,6507,6495,6495 ,0,0,0}, - {5973,5971,6085 ,6508,6509,6504 ,0,0,0}, {7588,7527,7526 ,6510,6511,6512 ,0,0,0}, - {6132,6015,6013 ,6513,6500,6514 ,0,0,0}, {6133,6015,6132 ,6515,6500,6513 ,0,0,0}, - {6127,6130,6014 ,6516,6517,6518 ,0,0,0}, {6094,6096,5979 ,6519,6520,6497 ,0,0,0}, - {6100,6102,5985 ,6521,6522,6523 ,0,0,0}, {6124,6007,6006 ,6524,6525,6526 ,0,0,0}, - {6103,5989,5988 ,6527,6500,6498 ,0,0,0}, {6120,6001,6118 ,6528,6522,6529 ,0,0,0}, - {6118,6000,6115 ,6529,6530,6531 ,0,0,0}, {5995,6112,5997 ,6532,6533,6502 ,0,0,0}, - {6109,5995,5994 ,6534,6532,6495 ,0,0,0}, {6121,6003,6120 ,6535,6502,6528 ,0,0,0}, - {6114,6115,5997 ,6533,6531,6502 ,0,0,0}, {6124,6006,6121 ,6524,6526,6535 ,0,0,0}, - {6003,6121,6006 ,6502,6535,6526 ,0,0,0}, {6106,5991,5989 ,6503,6514,6500 ,0,0,0}, - {5994,5991,6108 ,6495,6514,6530 ,0,0,0}, {6012,6007,6126 ,6536,6525,6537 ,0,0,0}, - {6007,6124,6126 ,6525,6524,6537 ,0,0,0}, {6012,6126,6127 ,6536,6537,6516 ,0,0,0}, - {6103,5988,6102 ,6527,6498,6522 ,0,0,0}, {6100,5983,6097 ,6521,6501,6509 ,0,0,0}, - {6127,6014,6012 ,6516,6518,6536 ,0,0,0}, {6014,6130,6013 ,6518,6517,6514 ,0,0,0}, - {6097,5982,6096 ,6509,6500,6520 ,0,0,0}, {5977,6091,5979 ,6508,6509,6497 ,0,0,0}, - {6132,6013,6130 ,6513,6514,6517 ,0,0,0}, {5973,6088,5976 ,6508,6508,6495 ,0,0,0}, - {5976,6090,5977 ,6495,6530,6508 ,0,0,0}, {7589,7528,7590 ,6538,6539,6540 ,0,0,0}, - {7584,6015,6133 ,6541,6500,6515 ,0,0,0}, {6084,5970,6082 ,6495,6496,6542 ,0,0,0}, - {5971,5970,6084 ,6509,6496,6495 ,0,0,0}, {6078,6079,5965 ,6542,6504,6507 ,0,0,0}, - {7583,7529,7591 ,6543,6505,6500 ,0,0,0}, {7592,7533,7593 ,6503,6533,6500 ,0,0,0}, - {6076,6078,5964 ,6495,6542,6495 ,0,0,0}, {7594,7593,7531 ,6508,6500,6538 ,0,0,0}, - {6021,6135,6020 ,6504,6542,6501 ,0,0,0}, {5963,6020,6134 ,6507,6501,6495 ,0,0,0}, - {7540,7595,7596 ,6527,6530,6498 ,0,0,0}, {7582,7535,7597 ,6503,6527,6499 ,0,0,0}, - {6027,6141,6026 ,6501,6501,6544 ,0,0,0}, {6139,6024,6026 ,6504,6501,6544 ,0,0,0}, - {7542,7598,7599 ,6508,6530,6544 ,0,0,0}, {7600,7537,7599 ,6498,6500,6544 ,0,0,0}, - {6032,6147,6145 ,6495,6495,6496 ,0,0,0}, {7581,7541,7598 ,6523,6504,6530 ,0,0,0}, - {7546,7601,7541 ,6500,6504,6504 ,0,0,0}, {7546,7545,7602 ,6500,6522,6500 ,0,0,0}, - {6150,6147,6033 ,6496,6495,6496 ,0,0,0}, {7603,7545,7544 ,6515,6522,6504 ,0,0,0}, - {7543,7604,7544 ,6508,6500,6504 ,0,0,0}, {6153,6036,6038 ,6495,6496,6508 ,0,0,0}, - {7604,7543,7605 ,6500,6508,6498 ,0,0,0}, {6156,6038,6039 ,6504,6508,6507 ,0,0,0}, - {7606,7605,7549 ,6515,6498,6545 ,0,0,0}, {6157,6039,6042 ,6507,6507,6495 ,0,0,0}, - {7607,7606,7547 ,6498,6515,6504 ,0,0,0}, {6159,6042,6044 ,6504,6495,6495 ,0,0,0}, - {7608,7607,7548 ,6504,6498,6504 ,0,0,0}, {6044,6045,6162 ,6495,6504,6504 ,0,0,0}, - {7609,7608,7552 ,6504,6504,6498 ,0,0,0}, {6163,6162,6045 ,6504,6504,6504 ,0,0,0}, - {7609,7551,7550 ,6504,6504,6504 ,0,0,0}, {6165,6163,6048 ,6546,6504,6504 ,0,0,0}, - {7610,7550,7555 ,6508,6504,6504 ,0,0,0}, {6168,6165,6050 ,6507,6546,6504 ,0,0,0}, - {7611,7555,7554 ,6508,6504,6508 ,0,0,0}, {6169,6168,6051 ,6547,6507,6548 ,0,0,0}, - {7612,7554,7553 ,6498,6508,6498 ,0,0,0}, {6171,6169,6054 ,6546,6547,6548 ,0,0,0}, - {7613,7553,7557 ,6504,6498,6498 ,0,0,0}, {6056,6174,6054 ,6549,6547,6548 ,0,0,0}, - {7557,7614,7613 ,6498,6504,6504 ,0,0,0}, {6175,6056,6057 ,6549,6549,6550 ,0,0,0}, - {7614,7556,7615 ,6504,6504,6498 ,0,0,0}, {6057,6060,6177 ,6550,6549,6504 ,0,0,0}, - {6180,6060,6062 ,6549,6549,6545 ,0,0,0}, {6183,6181,6064 ,6549,6504,6504 ,0,0,0}, - {7615,7560,7616 ,6498,6504,6504 ,0,0,0}, {6189,6187,6069 ,6551,6504,6515 ,0,0,0}, - {7561,7617,7562 ,6504,6508,6515 ,0,0,0}, {7618,7579,7619 ,6504,6545,6515 ,0,0,0}, - {7620,7563,7566 ,6508,6552,6504 ,0,0,0}, {7576,7621,7622 ,6553,6504,6554 ,0,0,0}, - {7623,7624,7567 ,6555,6504,6515 ,0,0,0}, {7571,7572,7625 ,6504,6504,6504 ,0,0,0}, - {7576,7622,7575 ,6553,6554,6504 ,0,0,0}, {7569,7626,7627 ,6504,6504,6515 ,0,0,0}, - {7625,7626,7570 ,6504,6504,6515 ,0,0,0}, {7574,7628,7573 ,6548,6504,6504 ,0,0,0}, - {7574,7575,7629 ,6548,6504,6549 ,0,0,0}, {7623,7568,7627 ,6555,6504,6515 ,0,0,0}, - {7630,7572,7573 ,6504,6504,6504 ,0,0,0}, {7631,7578,7618 ,6504,6548,6504 ,0,0,0}, - {7621,7577,7631 ,6504,6548,6504 ,0,0,0}, {7565,7632,7566 ,6504,6544,6504 ,0,0,0}, - {7565,7624,7632 ,6504,6504,6544 ,0,0,0}, {6192,6189,6071 ,6515,6551,6554 ,0,0,0}, - {6071,7619,7580 ,6554,6515,6545 ,0,0,0}, {7564,7633,7561 ,6515,6504,6504 ,0,0,0}, - {7634,7564,7563 ,6508,6515,6552 ,0,0,0}, {6186,6183,6063 ,6504,6549,6549 ,0,0,0}, - {6066,6187,6186 ,6545,6504,6504 ,0,0,0}, {7558,7635,7616 ,6508,6498,6504 ,0,0,0}, - {7617,7635,7559 ,6508,6498,6498 ,0,0,0}, {6181,6062,6064 ,6504,6545,6504 ,0,0,0}, - {6079,6082,5967 ,6504,6542,6504 ,0,0,0}, {7636,7530,7637 ,6556,6557,6558 ,0,0,0}, - {7585,7538,7600 ,6500,6499,6498 ,0,0,0}, {6001,6120,6003 ,6522,6528,6502 ,0,0,0}, - {6000,6118,6001 ,6530,6529,6522 ,0,0,0}, {5997,6115,6000 ,6502,6531,6530 ,0,0,0}, - {5997,6112,6114 ,6502,6533,6533 ,0,0,0}, {5995,6109,6112 ,6532,6534,6533 ,0,0,0}, - {5994,6108,6109 ,6495,6530,6534 ,0,0,0}, {5991,6106,6108 ,6514,6503,6530 ,0,0,0}, - {5989,6103,6106 ,6500,6527,6503 ,0,0,0}, {5985,6102,5988 ,6523,6522,6498 ,0,0,0}, - {5983,6100,5985 ,6501,6521,6523 ,0,0,0}, {5982,6097,5983 ,6500,6509,6501 ,0,0,0}, - {5979,6096,5982 ,6497,6520,6500 ,0,0,0}, {5979,6091,6094 ,6497,6509,6519 ,0,0,0}, - {5977,6090,6091 ,6508,6530,6509 ,0,0,0}, {5976,6088,6090 ,6495,6508,6530 ,0,0,0}, - {5973,6085,6088 ,6508,6504,6508 ,0,0,0}, {5971,6084,6085 ,6509,6495,6504 ,0,0,0}, - {5967,6082,5970 ,6504,6542,6496 ,0,0,0}, {5965,6079,5967 ,6507,6504,6504 ,0,0,0}, - {5964,6078,5965 ,6495,6542,6507 ,0,0,0}, {5963,6076,5964 ,6507,6495,6495 ,0,0,0}, - {5963,6134,6072 ,6507,6495,6495 ,0,0,0}, {6020,6135,6134 ,6501,6542,6495 ,0,0,0}, - {6021,6138,6135 ,6504,6496,6542 ,0,0,0}, {6024,6139,6138 ,6501,6504,6496 ,0,0,0}, - {6026,6141,6139 ,6544,6501,6504 ,0,0,0}, {6030,6144,6027 ,6495,6495,6501 ,0,0,0}, - {6032,6145,6030 ,6495,6496,6495 ,0,0,0}, {6033,6147,6032 ,6496,6495,6495 ,0,0,0}, - {6036,6150,6033 ,6496,6496,6496 ,0,0,0}, {6036,6153,6151 ,6496,6495,6497 ,0,0,0}, - {6038,6156,6153 ,6508,6504,6495 ,0,0,0}, {6039,6157,6156 ,6507,6507,6504 ,0,0,0}, - {6042,6159,6157 ,6495,6504,6507 ,0,0,0}, {6044,6162,6159 ,6495,6504,6504 ,0,0,0}, - {6048,6163,6045 ,6504,6504,6504 ,0,0,0}, {6050,6165,6048 ,6504,6546,6504 ,0,0,0}, - {6051,6168,6050 ,6548,6507,6504 ,0,0,0}, {6054,6169,6051 ,6548,6547,6548 ,0,0,0}, - {6054,6174,6171 ,6548,6547,6546 ,0,0,0}, {6056,6175,6174 ,6549,6549,6547 ,0,0,0}, - {6057,6177,6175 ,6550,6504,6549 ,0,0,0}, {6060,6180,6177 ,6549,6549,6504 ,0,0,0}, - {6062,6181,6180 ,6545,6504,6549 ,0,0,0}, {6063,6183,6064 ,6549,6549,6504 ,0,0,0}, - {6066,6186,6063 ,6545,6504,6549 ,0,0,0}, {6069,6187,6066 ,6515,6504,6545 ,0,0,0}, - {6071,6189,6069 ,6554,6551,6515 ,0,0,0}, {6071,7580,6192 ,6554,6545,6515 ,0,0,0}, - {7619,7579,7580 ,6515,6545,6545 ,0,0,0}, {7618,7578,7579 ,6504,6548,6545 ,0,0,0}, - {7631,7577,7578 ,6504,6548,6548 ,0,0,0}, {7621,7576,7577 ,6504,6553,6548 ,0,0,0}, - {7629,7575,7622 ,6549,6504,6554 ,0,0,0}, {7628,7574,7629 ,6504,6548,6549 ,0,0,0}, - {7630,7573,7628 ,6504,6504,6504 ,0,0,0}, {7625,7572,7630 ,6504,6504,6504 ,0,0,0}, - {7625,7570,7571 ,6504,6515,6504 ,0,0,0}, {7626,7569,7570 ,6504,6504,6515 ,0,0,0}, - {7627,7568,7569 ,6515,6504,6504 ,0,0,0}, {7623,7567,7568 ,6555,6515,6504 ,0,0,0}, - {7624,7565,7567 ,6504,6504,6515 ,0,0,0}, {7620,7566,7632 ,6508,6504,6544 ,0,0,0}, - {7634,7563,7620 ,6508,6552,6508 ,0,0,0}, {7633,7564,7634 ,6504,6515,6508 ,0,0,0}, - {7617,7561,7633 ,6508,6504,6504 ,0,0,0}, {7617,7559,7562 ,6508,6498,6515 ,0,0,0}, - {7635,7558,7559 ,6498,6508,6498 ,0,0,0}, {7616,7560,7558 ,6504,6504,6508 ,0,0,0}, - {7615,7556,7560 ,6498,6504,6504 ,0,0,0}, {7614,7557,7556 ,6504,6498,6504 ,0,0,0}, - {7612,7553,7613 ,6498,6498,6504 ,0,0,0}, {7611,7554,7612 ,6508,6508,6498 ,0,0,0}, - {7610,7555,7611 ,6508,6504,6508 ,0,0,0}, {7609,7550,7610 ,6504,6504,6508 ,0,0,0}, - {7609,7552,7551 ,6504,6498,6504 ,0,0,0}, {7608,7548,7552 ,6504,6504,6498 ,0,0,0}, - {7607,7547,7548 ,6498,6504,6504 ,0,0,0}, {7606,7549,7547 ,6515,6545,6504 ,0,0,0}, - {7605,7543,7549 ,6498,6508,6545 ,0,0,0}, {7603,7544,7604 ,6515,6504,6500 ,0,0,0}, - {7602,7545,7603 ,6500,6522,6515 ,0,0,0}, {7601,7546,7602 ,6504,6500,6500 ,0,0,0}, - {7598,7541,7601 ,6530,6504,6504 ,0,0,0}, {7598,7542,7581 ,6530,6508,6523 ,0,0,0}, - {7599,7537,7542 ,6544,6500,6508 ,0,0,0}, {7600,7538,7537 ,6498,6499,6500 ,0,0,0}, - {7595,7539,7585 ,6530,6498,6500 ,0,0,0}, {7596,7535,7540 ,6498,6527,6527 ,0,0,0}, - {7595,7540,7539 ,6530,6527,6498 ,0,0,0}, {7597,7586,7582 ,6499,6503,6503 ,0,0,0}, - {7596,7597,7535 ,6498,6499,6527 ,0,0,0}, {7586,7594,7536 ,6503,6508,6502 ,0,0,0}, - {7531,7593,7532 ,6538,6500,6559 ,0,0,0}, {7536,7594,7531 ,6502,6508,6538 ,0,0,0}, - {7534,7533,7592 ,6506,6533,6503 ,0,0,0}, {7533,7532,7593 ,6533,6559,6500 ,0,0,0}, - {7591,7529,7587 ,6500,6505,6498 ,0,0,0}, {7587,7534,7592 ,6498,6506,6503 ,0,0,0}, - {7637,7583,7591 ,6558,6543,6500 ,0,0,0}, {7636,7526,7530 ,6556,6512,6557 ,0,0,0}, - {7637,7530,7583 ,6558,6557,6543 ,0,0,0}, {7588,7590,7527 ,6510,6540,6511 ,0,0,0}, - {7636,7588,7526 ,6556,6510,6512 ,0,0,0}, {7528,7589,7584 ,6539,6538,6541 ,0,0,0}, - {7527,7590,7528 ,6511,6540,6539 ,0,0,0}, {6015,7584,7589 ,6500,6541,6538 ,0,0,0}, - {7589,6017,6015 ,6560,6561,6562 ,0,0,0}, {7636,7638,7588 ,6563,6564,6565 ,0,0,0}, - {7590,7639,7640 ,6566,6567,6568 ,0,0,0}, {7587,7592,7641 ,6569,6570,6571 ,0,0,0}, - {7637,7591,7642 ,6572,6573,6574 ,0,0,0}, {7643,7644,7586 ,6575,6576,6577 ,0,0,0}, - {7645,7646,7593 ,6578,6579,6580 ,0,0,0}, {7595,7585,7647 ,6581,6582,6583 ,0,0,0}, - {7597,7596,7648 ,6584,6585,6586 ,0,0,0}, {7649,7650,7598 ,6587,6588,6589 ,0,0,0}, - {7651,7600,7599 ,6590,6591,6592 ,0,0,0}, {7603,7604,7652 ,6593,6594,6595 ,0,0,0}, - {7602,7653,7654 ,6596,6597,6598 ,0,0,0}, {7655,7656,7607 ,6599,6600,6601 ,0,0,0}, - {7657,7658,7605 ,6602,6603,6604 ,0,0,0}, {7659,7610,7660 ,6605,6606,6607 ,0,0,0}, - {7608,7609,7661 ,6608,6609,6610 ,0,0,0}, {7612,7613,7662 ,6611,6612,6613 ,0,0,0}, - {7612,7663,7611 ,6611,6614,6615 ,0,0,0}, {7616,7664,7615 ,6616,6617,6618 ,0,0,0}, - {7665,7666,7614 ,6619,6620,6621 ,0,0,0}, {7617,7667,7635 ,6622,6623,6624 ,0,0,0}, - {7668,7616,7635 ,6625,6616,6624 ,0,0,0}, {7669,7670,7634 ,6626,6627,6628 ,0,0,0}, - {7671,7633,7670 ,6629,6630,6627 ,0,0,0}, {7672,7673,7632 ,6631,6632,6633 ,0,0,0}, - {7669,7620,7673 ,6626,6634,6632 ,0,0,0}, {7623,7674,7624 ,6635,6636,6637 ,0,0,0}, - {7672,7624,7674 ,6631,6637,6636 ,0,0,0}, {7623,7627,7675 ,6635,6638,6639 ,0,0,0}, - {7675,7674,7623 ,6639,6636,6635 ,0,0,0}, {7676,7627,7626 ,6640,6638,6641 ,0,0,0}, - {7627,7676,7675 ,6638,6640,6639 ,0,0,0}, {7625,7677,7626 ,6642,6643,6641 ,0,0,0}, - {7676,7626,7677 ,6640,6641,6643 ,0,0,0}, {7625,7630,7678 ,6642,6644,6645 ,0,0,0}, - {7678,7677,7625 ,6645,6643,6642 ,0,0,0}, {7679,7630,7628 ,6646,6644,6647 ,0,0,0}, - {7630,7679,7678 ,6644,6646,6645 ,0,0,0}, {7629,7680,7628 ,6648,6649,6647 ,0,0,0}, - {7679,7628,7680 ,6646,6647,6649 ,0,0,0}, {7629,7622,7681 ,6648,6650,6651 ,0,0,0}, - {7681,7680,7629 ,6651,6649,6648 ,0,0,0}, {7682,7622,7621 ,6652,6650,6653 ,0,0,0}, - {7622,7682,7681 ,6650,6652,6651 ,0,0,0}, {7621,7683,7684 ,6653,6654,6655 ,0,0,0}, - {7682,7621,7684 ,6652,6653,6655 ,0,0,0}, {7683,7631,7685 ,6654,6656,6657 ,0,0,0}, - {7631,7683,7621 ,6656,6654,6653 ,0,0,0}, {7685,7618,7619 ,6657,6658,6659 ,0,0,0}, - {7631,7618,7685 ,6656,6658,6657 ,0,0,0}, {6071,7686,7619 ,6660,6661,6659 ,0,0,0}, - {7685,7619,7686 ,6657,6659,6661 ,0,0,0}, {6070,7686,6071 ,6660,6661,6660 ,0,0,0}, - {7620,7632,7673 ,6634,6633,6632 ,0,0,0}, {7672,7632,7624 ,6631,6633,6637 ,0,0,0}, - {7633,7634,7670 ,6630,6628,6627 ,0,0,0}, {7669,7634,7620 ,6626,6628,6634 ,0,0,0}, - {7671,7667,7617 ,6629,6623,6622 ,0,0,0}, {7671,7617,7633 ,6629,6622,6630 ,0,0,0}, - {7664,7616,7668 ,6617,6616,6625 ,0,0,0}, {7667,7668,7635 ,6623,6625,6624 ,0,0,0}, - {7615,7665,7614 ,6618,6619,6621 ,0,0,0}, {7664,7665,7615 ,6617,6619,6618 ,0,0,0}, - {7613,7666,7662 ,6612,6620,6613 ,0,0,0}, {7614,7666,7613 ,6621,6620,6612 ,0,0,0}, - {7663,7660,7611 ,6614,6607,6615 ,0,0,0}, {7612,7662,7663 ,6611,6613,6614 ,0,0,0}, - {7609,7610,7659 ,6609,6606,6605 ,0,0,0}, {7610,7611,7660 ,6606,6615,6607 ,0,0,0}, - {7655,7608,7661 ,6599,6608,6610 ,0,0,0}, {7661,7609,7659 ,6610,6609,6605 ,0,0,0}, - {7656,7606,7607 ,6600,6662,6601 ,0,0,0}, {7655,7607,7608 ,6599,6601,6608 ,0,0,0}, - {7605,7606,7657 ,6604,6662,6602 ,0,0,0}, {7656,7657,7606 ,6600,6602,6662 ,0,0,0}, - {7604,7658,7652 ,6594,6603,6595 ,0,0,0}, {7605,7658,7604 ,6604,6603,6594 ,0,0,0}, - {7602,7603,7653 ,6596,6593,6597 ,0,0,0}, {7603,7652,7653 ,6593,6595,6597 ,0,0,0}, - {7649,7601,7654 ,6587,6663,6598 ,0,0,0}, {7601,7602,7654 ,6663,6596,6598 ,0,0,0}, - {7650,7599,7598 ,6588,6592,6589 ,0,0,0}, {7649,7598,7601 ,6587,6589,6663 ,0,0,0}, - {7651,7687,7600 ,6590,6664,6591 ,0,0,0}, {7650,7651,7599 ,6588,6590,6592 ,0,0,0}, - {7647,7585,7687 ,6583,6582,6664 ,0,0,0}, {7600,7687,7585 ,6591,6664,6582 ,0,0,0}, - {7596,7595,7688 ,6585,6581,6665 ,0,0,0}, {7595,7647,7688 ,6581,6583,6665 ,0,0,0}, - {7643,7597,7648 ,6575,6584,6586 ,0,0,0}, {7648,7596,7688 ,6586,6585,6665 ,0,0,0}, - {7644,7594,7586 ,6576,6666,6577 ,0,0,0}, {7643,7586,7597 ,6575,6577,6584 ,0,0,0}, - {7593,7594,7645 ,6580,6666,6578 ,0,0,0}, {7644,7645,7594 ,6576,6578,6666 ,0,0,0}, - {7592,7646,7641 ,6570,6579,6571 ,0,0,0}, {7593,7646,7592 ,6580,6579,6570 ,0,0,0}, - {7591,7587,7689 ,6573,6569,6667 ,0,0,0}, {7587,7641,7689 ,6569,6571,6667 ,0,0,0}, - {7638,7637,7642 ,6564,6572,6574 ,0,0,0}, {7642,7591,7689 ,6574,6573,6667 ,0,0,0}, - {7638,7639,7588 ,6564,6567,6565 ,0,0,0}, {7638,7636,7637 ,6564,6563,6572 ,0,0,0}, - {7640,7690,7590 ,6568,6668,6566 ,0,0,0}, {7588,7639,7590 ,6565,6567,6566 ,0,0,0}, - {6017,7589,7690 ,6561,6560,6668 ,0,0,0}, {7590,7690,7589 ,6566,6668,6560 ,0,0,0}, - {5981,5984,5888 ,6669,6670,6671 ,0,0,0}, {7643,7648,7691 ,6672,6671,6671 ,0,0,0}, - {5894,5990,5903 ,6673,6674,6671 ,0,0,0}, {5984,5986,5897 ,6670,6669,6675 ,0,0,0}, - {5996,5926,5898 ,6670,6676,6677 ,0,0,0}, {7692,7693,7661 ,6324,6298,6672 ,0,0,0}, - {7694,7653,7652 ,6671,6672,6671 ,0,0,0}, {7695,7696,7657 ,6672,6671,6671 ,0,0,0}, - {6009,5920,5916 ,6678,6671,6679 ,0,0,0}, {7654,7653,7697 ,6671,6672,6680 ,0,0,0}, - {5922,6016,5924 ,6679,6671,6671 ,0,0,0}, {7698,7699,7651 ,6672,6672,6672 ,0,0,0}, - {7700,7701,7638 ,6672,6681,6672 ,0,0,0}, {7690,7640,7702 ,6671,6681,6672 ,0,0,0}, - {7703,7645,7644 ,6672,6672,6681 ,0,0,0}, {7641,7704,7705 ,6672,6672,6672 ,0,0,0}, - {7706,7689,7705 ,6672,6671,6672 ,0,0,0}, {7643,7707,7644 ,6672,6671,6681 ,0,0,0}, - {7646,7703,7704 ,6672,6672,6672 ,0,0,0}, {7700,7642,7706 ,6672,6672,6672 ,0,0,0}, - {7708,7709,7688 ,6671,6672,6672 ,0,0,0}, {7640,7639,7710 ,6681,6671,6671 ,0,0,0}, - {7647,7711,7708 ,6671,6681,6671 ,0,0,0}, {6017,7690,5924 ,6671,6671,6671 ,0,0,0}, - {7687,7699,7711 ,6672,6672,6681 ,0,0,0}, {5920,6010,5921 ,6671,6682,6672 ,0,0,0}, - {5922,5921,6011 ,6679,6672,6298 ,0,0,0}, {7654,7712,7649 ,6671,6671,6672 ,0,0,0}, - {7712,7698,7650 ,6671,6672,6672 ,0,0,0}, {6004,6005,5912 ,6672,6681,6670 ,0,0,0}, - {5916,5918,6008 ,6679,6669,6669 ,0,0,0}, {7696,7713,7658 ,6671,6672,6671 ,0,0,0}, - {6002,6004,5914 ,6671,6672,6681 ,0,0,0}, {5909,5926,5998 ,6669,6676,6298 ,0,0,0}, - {5909,5999,6002 ,6669,6669,6671 ,0,0,0}, {7714,7655,7693 ,6672,6671,6298 ,0,0,0}, - {7714,7695,7656 ,6672,6672,6672 ,0,0,0}, {5992,5900,5903 ,6683,6669,6671 ,0,0,0}, - {5898,5900,5993 ,6677,6669,6684 ,0,0,0}, {7663,7715,7660 ,6671,6685,6686 ,0,0,0}, - {7692,7659,7660 ,6324,6687,6686 ,0,0,0}, {7663,7662,7716 ,6671,6688,6688 ,0,0,0}, - {5986,5987,5893 ,6669,6689,6684 ,0,0,0}, {7717,7718,7665 ,6672,6690,6671 ,0,0,0}, - {7718,7719,7666 ,6690,6686,6690 ,0,0,0}, {7720,7717,7664 ,6691,6672,6691 ,0,0,0}, - {5888,5891,5980 ,6671,6692,6672 ,0,0,0}, {5890,5978,5891 ,6693,6673,6692 ,0,0,0}, - {5883,5975,5890 ,6672,6689,6693 ,0,0,0}, {7668,7721,7720 ,6686,6690,6691 ,0,0,0}, - {5974,5883,5886 ,6694,6672,6695 ,0,0,0}, {7667,7722,7721 ,6690,6691,6690 ,0,0,0}, - {5886,5885,5972 ,6695,6696,6697 ,0,0,0}, {7722,7671,7670 ,6691,6672,6688 ,0,0,0}, - {5880,5968,5969 ,6698,6699,6700 ,0,0,0}, {7723,7724,7669 ,6672,6688,6688 ,0,0,0}, - {7673,7672,7725 ,6688,6691,6701 ,0,0,0}, {7726,7674,7675 ,6686,6672,6671 ,0,0,0}, - {5966,5968,5828 ,6676,6699,6702 ,0,0,0}, {7676,7727,7728 ,6672,6671,6671 ,0,0,0}, - {5966,5827,5962 ,6676,6687,6703 ,0,0,0}, {7729,7677,7678 ,6686,6704,6672 ,0,0,0}, - {5827,5875,6018 ,6687,6705,6676 ,0,0,0}, {7680,7730,7679 ,6686,6706,6672 ,0,0,0}, - {5961,6019,5875 ,6698,6699,6705 ,0,0,0}, {6023,5866,5865 ,6697,6707,6708 ,0,0,0}, - {6022,5961,5866 ,6709,6698,6707 ,0,0,0}, {7731,7683,7685 ,6690,6671,6701 ,0,0,0}, - {5865,5959,6025 ,6708,6672,6694 ,0,0,0}, {7686,5853,7732 ,6690,6690,6686 ,0,0,0}, - {6029,6028,5957 ,6673,6689,6710 ,0,0,0}, {5851,5853,6068 ,6711,6690,6690 ,0,0,0}, - {6031,6029,5955 ,6686,6673,6692 ,0,0,0}, {6065,5849,6067 ,6712,6713,6685 ,0,0,0}, - {5950,5951,6037 ,6714,6684,6669 ,0,0,0}, {6061,5846,5848 ,6715,6716,6717 ,0,0,0}, - {5946,6043,5945 ,6718,6719,6691 ,0,0,0}, {6049,6047,5834 ,6298,6670,6676 ,0,0,0}, - {6055,5839,5841 ,6686,6704,6720 ,0,0,0}, {5841,5843,6058 ,6720,6669,6715 ,0,0,0}, - {6049,5836,6052 ,6298,6718,6669 ,0,0,0}, {5836,5839,6053 ,6718,6704,6691 ,0,0,0}, - {7724,7670,7669 ,6688,6688,6688 ,0,0,0}, {5944,6047,6046 ,6676,6670,6684 ,0,0,0}, - {6061,6059,5846 ,6715,6669,6716 ,0,0,0}, {5848,5849,6065 ,6717,6713,6712 ,0,0,0}, - {5848,6065,6061 ,6717,6712,6715 ,0,0,0}, {5949,6040,5951 ,6673,6721,6684 ,0,0,0}, - {5949,5945,6041 ,6673,6691,6670 ,0,0,0}, {5851,6068,6067 ,6711,6690,6685 ,0,0,0}, - {5851,6067,5849 ,6711,6685,6713 ,0,0,0}, {5954,6034,6031 ,6691,6669,6686 ,0,0,0}, - {6035,5954,5950 ,6720,6691,6714 ,0,0,0}, {6070,6068,5853 ,6671,6690,6690 ,0,0,0}, - {7684,7733,7734 ,6686,6722,6688 ,0,0,0}, {7681,7682,7735 ,6691,6723,6706 ,0,0,0}, - {6059,6058,5843 ,6669,6715,6669 ,0,0,0}, {6059,5843,5846 ,6669,6669,6716 ,0,0,0}, - {6058,6055,5841 ,6715,6686,6720 ,0,0,0}, {6055,6053,5839 ,6686,6691,6704 ,0,0,0}, - {6053,6052,5836 ,6691,6669,6718 ,0,0,0}, {6049,5834,5836 ,6298,6676,6718 ,0,0,0}, - {6047,5944,5834 ,6670,6676,6676 ,0,0,0}, {6046,6043,5946 ,6684,6719,6718 ,0,0,0}, - {6046,5946,5944 ,6684,6718,6676 ,0,0,0}, {6043,6041,5945 ,6719,6670,6691 ,0,0,0}, - {6041,6040,5949 ,6670,6721,6673 ,0,0,0}, {6040,6037,5951 ,6721,6669,6684 ,0,0,0}, - {6037,6035,5950 ,6669,6720,6714 ,0,0,0}, {6035,6034,5954 ,6720,6669,6691 ,0,0,0}, - {6031,5955,5954 ,6686,6692,6691 ,0,0,0}, {6029,5957,5955 ,6673,6710,6692 ,0,0,0}, - {6028,6025,5959 ,6689,6694,6672 ,0,0,0}, {6028,5959,5957 ,6689,6672,6710 ,0,0,0}, - {6025,6023,5865 ,6694,6697,6708 ,0,0,0}, {6023,6022,5866 ,6697,6709,6707 ,0,0,0}, - {6022,6019,5961 ,6709,6699,6698 ,0,0,0}, {6019,6018,5875 ,6699,6676,6705 ,0,0,0}, - {6018,5962,5827 ,6676,6703,6687 ,0,0,0}, {5966,5828,5827 ,6676,6702,6687 ,0,0,0}, - {5968,5880,5828 ,6699,6698,6702 ,0,0,0}, {5969,5972,5885 ,6700,6697,6696 ,0,0,0}, - {5969,5885,5880 ,6700,6696,6698 ,0,0,0}, {5972,5974,5886 ,6697,6694,6695 ,0,0,0}, - {5974,5975,5883 ,6694,6689,6672 ,0,0,0}, {5975,5978,5890 ,6689,6673,6693 ,0,0,0}, - {5978,5980,5891 ,6673,6672,6692 ,0,0,0}, {5980,5981,5888 ,6672,6669,6671 ,0,0,0}, - {5984,5897,5888 ,6670,6675,6671 ,0,0,0}, {5986,5893,5897 ,6669,6684,6675 ,0,0,0}, - {5987,5990,5894 ,6689,6674,6673 ,0,0,0}, {5987,5894,5893 ,6689,6673,6684 ,0,0,0}, - {5990,5992,5903 ,6674,6683,6671 ,0,0,0}, {5992,5993,5900 ,6683,6684,6669 ,0,0,0}, - {5993,5996,5898 ,6684,6670,6677 ,0,0,0}, {5996,5998,5926 ,6670,6298,6676 ,0,0,0}, - {5998,5999,5909 ,6298,6669,6669 ,0,0,0}, {6002,5914,5909 ,6671,6681,6669 ,0,0,0}, - {6004,5912,5914 ,6672,6670,6681 ,0,0,0}, {6005,6008,5918 ,6681,6669,6669 ,0,0,0}, - {6005,5918,5912 ,6681,6669,6670 ,0,0,0}, {6008,6009,5916 ,6669,6678,6679 ,0,0,0}, - {6009,6010,5920 ,6678,6682,6671 ,0,0,0}, {6010,6011,5921 ,6682,6298,6672 ,0,0,0}, - {6011,6016,5922 ,6298,6671,6679 ,0,0,0}, {6016,6017,5924 ,6671,6671,6671 ,0,0,0}, - {7690,7702,5924 ,6671,6672,6671 ,0,0,0}, {7640,7710,7702 ,6681,6671,6672 ,0,0,0}, - {7639,7638,7701 ,6671,6672,6681 ,0,0,0}, {7639,7701,7710 ,6671,6681,6671 ,0,0,0}, - {7638,7642,7700 ,6672,6672,6672 ,0,0,0}, {7642,7689,7706 ,6672,6671,6672 ,0,0,0}, - {7689,7641,7705 ,6671,6672,6672 ,0,0,0}, {7641,7646,7704 ,6672,6672,6672 ,0,0,0}, - {7646,7645,7703 ,6672,6672,6672 ,0,0,0}, {7644,7707,7703 ,6681,6671,6672 ,0,0,0}, - {7643,7691,7707 ,6672,6671,6671 ,0,0,0}, {7648,7688,7709 ,6671,6672,6672 ,0,0,0}, - {7648,7709,7691 ,6671,6672,6671 ,0,0,0}, {7688,7647,7708 ,6672,6671,6671 ,0,0,0}, - {7647,7687,7711 ,6671,6672,6681 ,0,0,0}, {7687,7651,7699 ,6672,6672,6672 ,0,0,0}, - {7651,7650,7698 ,6672,6672,6672 ,0,0,0}, {7650,7649,7712 ,6672,6672,6671 ,0,0,0}, - {7654,7697,7712 ,6671,6680,6671 ,0,0,0}, {7653,7694,7697 ,6672,6671,6680 ,0,0,0}, - {7652,7658,7713 ,6671,6671,6672 ,0,0,0}, {7652,7713,7694 ,6671,6672,6671 ,0,0,0}, - {7658,7657,7696 ,6671,6671,6671 ,0,0,0}, {7657,7656,7695 ,6671,6672,6672 ,0,0,0}, - {7656,7655,7714 ,6672,6671,6672 ,0,0,0}, {7655,7661,7693 ,6671,6672,6298 ,0,0,0}, - {7661,7659,7692 ,6672,6687,6324 ,0,0,0}, {7660,7715,7692 ,6686,6685,6324 ,0,0,0}, - {7663,7716,7715 ,6671,6688,6685 ,0,0,0}, {7662,7666,7719 ,6688,6690,6686 ,0,0,0}, - {7662,7719,7716 ,6688,6686,6688 ,0,0,0}, {7666,7665,7718 ,6690,6671,6690 ,0,0,0}, - {7665,7664,7717 ,6671,6691,6672 ,0,0,0}, {7664,7668,7720 ,6691,6686,6691 ,0,0,0}, - {7668,7667,7721 ,6686,6690,6690 ,0,0,0}, {7667,7671,7722 ,6690,6672,6691 ,0,0,0}, - {7670,7724,7722 ,6688,6688,6691 ,0,0,0}, {7673,7723,7669 ,6688,6672,6688 ,0,0,0}, - {7672,7736,7725 ,6691,6691,6701 ,0,0,0}, {7673,7725,7723 ,6688,6701,6672 ,0,0,0}, - {7726,7736,7674 ,6686,6691,6672 ,0,0,0}, {7672,7674,7736 ,6691,6672,6691 ,0,0,0}, - {7726,7675,7728 ,6686,6671,6671 ,0,0,0}, {7727,7676,7677 ,6671,6672,6704 ,0,0,0}, - {7728,7675,7676 ,6671,6671,6672 ,0,0,0}, {7729,7678,7679 ,6686,6672,6672 ,0,0,0}, - {7729,7727,7677 ,6686,6671,6704 ,0,0,0}, {7737,7730,7680 ,6688,6706,6686 ,0,0,0}, - {7730,7729,7679 ,6706,6686,6672 ,0,0,0}, {7737,7681,7735 ,6688,6691,6706 ,0,0,0}, - {7681,7737,7680 ,6691,6688,6686 ,0,0,0}, {7682,7734,7735 ,6723,6688,6706 ,0,0,0}, - {7684,7683,7733 ,6686,6671,6722 ,0,0,0}, {7682,7684,7734 ,6723,6686,6688 ,0,0,0}, - {7731,7685,7732 ,6690,6701,6686 ,0,0,0}, {7733,7683,7731 ,6722,6671,6690 ,0,0,0}, - {5853,7686,6070 ,6690,6690,6671 ,0,0,0}, {7732,7685,7686 ,6686,6701,6690 ,0,0,0}, - {7732,5430,7234 ,6724,6725,6726 ,0,0,0}, {7196,7733,7731 ,6727,6728,6729 ,0,0,0}, - {7735,7198,7737 ,6730,6731,6732 ,0,0,0}, {7339,7734,7337 ,6733,6734,6735 ,0,0,0}, - {7738,7348,7739 ,6736,6737,6738 ,0,0,0}, {7223,7738,7740 ,6739,6736,6736 ,0,0,0}, - {7264,7741,7742 ,6740,6741,6742 ,0,0,0}, {7263,7743,7222 ,6743,6744,6745 ,0,0,0}, - {7346,7744,7745 ,6746,6747,6748 ,0,0,0}, {7393,7746,7351 ,6749,6750,6751 ,0,0,0}, - {7747,7748,7391 ,6752,6753,6754 ,0,0,0}, {7744,7279,7392 ,6747,6755,6756 ,0,0,0}, - {7714,7315,7306 ,6757,6758,6759 ,0,0,0}, {5717,7315,7747 ,6760,6758,6752 ,0,0,0}, - {7696,7308,7713 ,6761,6762,6763 ,0,0,0}, {7307,7696,7695 ,6764,6761,6765 ,0,0,0}, - {7378,7313,7697 ,6766,6767,6768 ,0,0,0}, {7378,7694,7377 ,6766,6769,6770 ,0,0,0}, - {7712,7305,7698 ,6771,6772,6773 ,0,0,0}, {7305,7712,7313 ,6772,6771,6767 ,0,0,0}, - {7699,7698,7282 ,6774,6773,6775 ,0,0,0}, {7305,7282,7698 ,6772,6775,6773 ,0,0,0}, - {7280,7711,7281 ,6776,6777,6778 ,0,0,0}, {7699,7282,7281 ,6774,6775,6778 ,0,0,0}, - {7286,7709,7304 ,6779,6780,6781 ,0,0,0}, {7708,7280,7304 ,6782,6776,6781 ,0,0,0}, - {7285,7707,7691 ,6783,6784,6785 ,0,0,0}, {7704,7703,7749 ,6786,6787,6788 ,0,0,0}, - {7749,7303,7750 ,6788,6789,6788 ,0,0,0}, {7703,7707,7303 ,6787,6784,6789 ,0,0,0}, - {7751,7284,7257 ,6790,6791,6792 ,0,0,0}, {7284,7751,7750 ,6791,6790,6788 ,0,0,0}, - {7256,7752,7257 ,6793,6794,6792 ,0,0,0}, {7751,7257,7752 ,6790,6792,6794 ,0,0,0}, - {7256,7289,7753 ,6793,6795,6796 ,0,0,0}, {7753,7752,7256 ,6796,6794,6793 ,0,0,0}, - {7754,7289,7295 ,6797,6795,6798 ,0,0,0}, {7289,7754,7753 ,6795,6797,6796 ,0,0,0}, - {7299,7755,7295 ,6799,6800,6798 ,0,0,0}, {7754,7295,7755 ,6797,6798,6800 ,0,0,0}, - {7299,7292,7756 ,6799,6801,6802 ,0,0,0}, {7756,7755,7299 ,6802,6800,6799 ,0,0,0}, - {7757,7292,7301 ,6803,6801,6804 ,0,0,0}, {7292,7757,7756 ,6801,6803,6802 ,0,0,0}, - {5531,5934,7301 ,6805,6806,6804 ,0,0,0}, {7757,7301,5934 ,6803,6804,6806 ,0,0,0}, - {7701,7758,7759 ,6807,6808,6809 ,0,0,0}, {7703,7303,7749 ,6787,6789,6788 ,0,0,0}, - {7750,7303,7284 ,6788,6789,6791 ,0,0,0}, {7285,7303,7707 ,6783,6789,6784 ,0,0,0}, - {7286,7285,7691 ,6779,6783,6785 ,0,0,0}, {7691,7709,7286 ,6785,6780,6779 ,0,0,0}, - {7304,7709,7708 ,6781,6780,6782 ,0,0,0}, {7280,7708,7711 ,6776,6782,6777 ,0,0,0}, - {7711,7699,7281 ,6777,6774,6778 ,0,0,0}, {7749,7760,7704 ,6788,6810,6786 ,0,0,0}, - {7758,7701,7700 ,6808,6807,6811 ,0,0,0}, {7760,7705,7704 ,6810,6812,6786 ,0,0,0}, - {7759,7761,7710 ,6809,6813,6814 ,0,0,0}, {7710,7701,7759 ,6814,6807,6809 ,0,0,0}, - {7710,7762,7702 ,6814,6815,6816 ,0,0,0}, {7762,7710,7761 ,6815,6814,6813 ,0,0,0}, - {5924,7702,5925 ,6817,6816,6818 ,0,0,0}, {7762,5925,7702 ,6815,6818,6816 ,0,0,0}, - {7700,7763,7758 ,6811,6819,6808 ,0,0,0}, {7313,7712,7697 ,6767,6771,6768 ,0,0,0}, - {7763,7700,7706 ,6819,6811,6820 ,0,0,0}, {7764,7763,7706 ,6821,6819,6820 ,0,0,0}, - {7705,7760,7764 ,6812,6810,6821 ,0,0,0}, {7705,7764,7706 ,6812,6821,6820 ,0,0,0}, - {7697,7694,7378 ,6768,6769,6766 ,0,0,0}, {7344,7745,7746 ,6822,6748,6750 ,0,0,0}, - {7377,7713,7308 ,6770,6763,6762 ,0,0,0}, {7713,7377,7694 ,6763,6770,6769 ,0,0,0}, - {7696,7307,7308 ,6761,6764,6762 ,0,0,0}, {7306,7307,7695 ,6759,6764,6765 ,0,0,0}, - {7693,7315,7714 ,6823,6758,6757 ,0,0,0}, {7695,7714,7306 ,6765,6757,6759 ,0,0,0}, - {5717,7747,7391 ,6760,6752,6754 ,0,0,0}, {7693,7747,7315 ,6823,6752,6758 ,0,0,0}, - {7744,7346,7279 ,6747,6746,6755 ,0,0,0}, {7748,7744,7392 ,6753,6747,6756 ,0,0,0}, - {7746,7393,7344 ,6750,6749,6822 ,0,0,0}, {7765,7343,7766 ,6824,6825,6826 ,0,0,0}, - {7746,7766,7351 ,6750,6826,6751 ,0,0,0}, {7765,7741,7273 ,6824,6741,6827 ,0,0,0}, - {7343,7765,7273 ,6825,6824,6827 ,0,0,0}, {7742,7743,7263 ,6742,6744,6743 ,0,0,0}, - {7273,7741,7255 ,6827,6741,6828 ,0,0,0}, {7736,7726,7767 ,6829,6830,6831 ,0,0,0}, - {7727,7729,7740 ,6832,6833,6736 ,0,0,0}, {7743,7739,7342 ,6744,6738,6834 ,0,0,0}, - {7731,7234,7196 ,6729,6726,6727 ,0,0,0}, {7735,7734,7339 ,6730,6734,6733 ,0,0,0}, - {7199,7223,7730 ,6835,6739,6836 ,0,0,0}, {7357,7738,7223 ,6837,6736,6739 ,0,0,0}, - {7737,7199,7730 ,6732,6835,6836 ,0,0,0}, {7339,7198,7735 ,6733,6731,6730 ,0,0,0}, - {7737,7198,7199 ,6732,6731,6835 ,0,0,0}, {7733,7337,7734 ,6728,6735,6734 ,0,0,0}, - {7337,7733,7196 ,6735,6728,6727 ,0,0,0}, {7234,7731,7732 ,6726,6729,6724 ,0,0,0}, - {5430,7732,5853 ,6725,6724,6838 ,0,0,0}, {7715,7768,7692 ,6839,6840,6841 ,0,0,0}, - {7693,7692,7768 ,6823,6841,6840 ,0,0,0}, {7768,7715,7769 ,6840,6839,6842 ,0,0,0}, - {7693,7768,7747 ,6823,6840,6752 ,0,0,0}, {7770,7769,7716 ,6843,6842,6844 ,0,0,0}, - {7392,7391,7748 ,6756,6754,6753 ,0,0,0}, {7718,7770,7719 ,6845,6843,6846 ,0,0,0}, - {7718,7771,7770 ,6845,6847,6843 ,0,0,0}, {7772,7771,7717 ,6848,6847,6849 ,0,0,0}, - {7344,7346,7745 ,6822,6746,6748 ,0,0,0}, {7721,7772,7720 ,6850,6848,6851 ,0,0,0}, - {7721,7773,7772 ,6850,6852,6848 ,0,0,0}, {7774,7773,7722 ,6853,6852,6854 ,0,0,0}, - {7343,7351,7766 ,6825,6751,6826 ,0,0,0}, {7724,7775,7774 ,6855,6856,6853 ,0,0,0}, - {7723,7775,7724 ,6857,6856,6855 ,0,0,0}, {7776,7775,7725 ,6858,6856,6859 ,0,0,0}, - {7264,7255,7741 ,6740,6828,6741 ,0,0,0}, {7767,7776,7736 ,6831,6858,6829 ,0,0,0}, - {7263,7264,7742 ,6743,6740,6742 ,0,0,0}, {7777,7767,7728 ,6860,6831,6861 ,0,0,0}, - {7342,7222,7743 ,6834,6745,6744 ,0,0,0}, {7740,7777,7727 ,6736,6860,6832 ,0,0,0}, - {7348,7342,7739 ,6737,6834,6738 ,0,0,0}, {7730,7223,7740 ,6836,6739,6736 ,0,0,0}, - {7348,7738,7357 ,6737,6736,6837 ,0,0,0}, {7730,7740,7729 ,6836,6736,6833 ,0,0,0}, - {7728,7727,7777 ,6861,6832,6860 ,0,0,0}, {7726,7728,7767 ,6830,6861,6831 ,0,0,0}, - {7725,7736,7776 ,6859,6829,6858 ,0,0,0}, {7723,7725,7775 ,6857,6859,6856 ,0,0,0}, - {7722,7724,7774 ,6854,6855,6853 ,0,0,0}, {7721,7722,7773 ,6850,6854,6852 ,0,0,0}, - {7717,7720,7772 ,6849,6851,6848 ,0,0,0}, {7718,7717,7771 ,6845,6849,6847 ,0,0,0}, - {7716,7719,7770 ,6844,6846,6843 ,0,0,0}, {7715,7716,7769 ,6839,6844,6842 ,0,0,0}, - {7778,5725,5726 ,6862,6863,6864 ,0,0,0}, {7430,7419,6657 ,6865,6866,6867 ,0,0,0}, - {7779,7427,7426 ,6868,6869,6870 ,0,0,0}, {7429,6650,7416 ,6871,6872,6873 ,0,0,0}, - {6635,7409,7413 ,6874,6875,6876 ,0,0,0}, {6647,7432,7433 ,6877,6878,6879 ,0,0,0}, - {7443,6642,6641 ,6880,6881,6882 ,0,0,0}, {7440,6634,6637 ,6883,6884,6885 ,0,0,0}, - {7780,7453,7451 ,6886,6887,6888 ,0,0,0}, {7781,7447,6644 ,6889,6890,5525 ,0,0,0}, - {7464,7461,6720 ,6891,6892,6893 ,0,0,0}, {7457,7782,7783 ,6894,6895,6896 ,0,0,0}, - {7471,6709,7525 ,6897,6898,6899 ,0,0,0}, {7467,6715,7470 ,6900,6901,6902 ,0,0,0}, - {6756,7476,6754 ,6903,6904,6905 ,0,0,0}, {7519,7472,6752 ,6906,6907,6908 ,0,0,0}, - {7508,7784,7510 ,6909,6910,6911 ,0,0,0}, {7516,6757,7482 ,6912,6913,6914 ,0,0,0}, - {7785,7497,7489 ,6915,6916,6917 ,0,0,0}, {7507,7786,7494 ,6918,6919,6920 ,0,0,0}, - {7787,7504,7505 ,6921,6922,6923 ,0,0,0}, {6813,6816,7498 ,6924,6925,6926 ,0,0,0}, - {6813,7501,6814 ,6924,6927,5712 ,0,0,0}, {6801,6800,7491 ,6928,6929,6930 ,0,0,0}, - {6801,7506,6816 ,6928,6931,6925 ,0,0,0}, {7511,7513,6800 ,6932,6933,6929 ,0,0,0}, - {6800,7513,7491 ,6929,6933,6930 ,0,0,0}, {7511,6800,6845 ,6932,6929,6934 ,0,0,0}, - {6845,6847,7485 ,6934,6935,6936 ,0,0,0}, {7485,7511,6845 ,6936,6932,6934 ,0,0,0}, - {7517,6847,6849 ,6937,6935,6938 ,0,0,0}, {6847,7517,7485 ,6935,6937,6936 ,0,0,0}, - {7517,6849,7478 ,6937,6938,6939 ,0,0,0}, {6850,7479,7478 ,6940,6941,6939 ,0,0,0}, - {7478,6849,6850 ,6939,6938,6940 ,0,0,0}, {7479,6852,7523 ,6941,6942,6943 ,0,0,0}, - {6852,7479,6850 ,6942,6941,6940 ,0,0,0}, {7473,7523,6853 ,6944,6943,6945 ,0,0,0}, - {6852,6853,7523 ,6942,6945,6943 ,0,0,0}, {6853,7788,7468 ,6945,6946,6947 ,0,0,0}, - {7468,7473,6853 ,6947,6944,6945 ,0,0,0}, {7465,7788,7789 ,6948,6946,6949 ,0,0,0}, - {7788,7465,7468 ,6946,6948,6947 ,0,0,0}, {7790,7462,7789 ,6950,6951,6949 ,0,0,0}, - {7465,7789,7462 ,6948,6949,6951 ,0,0,0}, {7790,5823,5821 ,6950,126,3135 ,0,0,0}, - {5821,7462,7790 ,3135,6951,6950 ,0,0,0}, {6816,7506,7498 ,6925,6931,6926 ,0,0,0}, - {6801,7491,7506 ,6928,6930,6931 ,0,0,0}, {7501,7494,6814 ,6927,6920,5712 ,0,0,0}, - {6813,7498,7501 ,6924,6926,6927 ,0,0,0}, {7786,7507,7504 ,6919,6918,6922 ,0,0,0}, - {7786,6814,7494 ,6919,5712,6920 ,0,0,0}, {7787,7505,7497 ,6921,6923,6916 ,0,0,0}, - {7787,7786,7504 ,6921,6919,6922 ,0,0,0}, {7784,7785,7489 ,6910,6915,6917 ,0,0,0}, - {7785,7787,7497 ,6915,6921,6916 ,0,0,0}, {6759,7784,7508 ,6952,6910,6909 ,0,0,0}, - {7510,7784,7489 ,6911,6910,6917 ,0,0,0}, {6759,7482,6757 ,6952,6914,6913 ,0,0,0}, - {7482,6759,7508 ,6914,6952,6909 ,0,0,0}, {7514,6756,6757 ,6953,6903,6913 ,0,0,0}, - {7514,6757,7516 ,6953,6913,6912 ,0,0,0}, {7476,7521,6754 ,6904,6954,6905 ,0,0,0}, - {7514,7476,6756 ,6953,6904,6903 ,0,0,0}, {7519,6752,7521 ,6906,6908,6954 ,0,0,0}, - {6754,7521,6752 ,6905,6954,6908 ,0,0,0}, {6711,7472,7525 ,6955,6907,6899 ,0,0,0}, - {6752,7472,6711 ,6908,6907,6955 ,0,0,0}, {6721,6709,7471 ,6956,6898,6897 ,0,0,0}, - {6709,6711,7525 ,6898,6955,6899 ,0,0,0}, {6721,7470,6715 ,6956,6902,6901 ,0,0,0}, - {7470,6721,7471 ,6902,6956,6897 ,0,0,0}, {7464,6720,6715 ,6891,6893,6901 ,0,0,0}, - {7464,6715,7467 ,6891,6901,6900 ,0,0,0}, {7461,7459,7783 ,6892,6957,6896 ,0,0,0}, - {7461,7783,6720 ,6892,6896,6893 ,0,0,0}, {7457,7455,7782 ,6894,6958,6895 ,0,0,0}, - {7459,7457,7783 ,6957,6894,6896 ,0,0,0}, {7453,7780,7455 ,6887,6886,6958 ,0,0,0}, - {7782,7455,7780 ,6895,6958,6886 ,0,0,0}, {7781,7451,7449 ,6889,6888,6959 ,0,0,0}, - {7780,7451,7781 ,6886,6888,6889 ,0,0,0}, {6644,7447,7445 ,5525,6890,6960 ,0,0,0}, - {7781,7449,7447 ,6889,6959,6890 ,0,0,0}, {7445,7443,6641 ,6960,6880,6882 ,0,0,0}, - {6641,6644,7445 ,6882,5525,6960 ,0,0,0}, {7410,6637,6642 ,6961,6885,6881 ,0,0,0}, - {7410,6642,7443 ,6961,6881,6880 ,0,0,0}, {7440,7436,6634 ,6883,6962,6884 ,0,0,0}, - {7410,7440,6637 ,6961,6883,6885 ,0,0,0}, {6635,6634,7409 ,6874,6884,6875 ,0,0,0}, - {7436,7409,6634 ,6962,6875,6884 ,0,0,0}, {6640,7413,7432 ,6963,6876,6878 ,0,0,0}, - {6635,7413,6640 ,6874,6876,6963 ,0,0,0}, {6649,6647,7433 ,6964,6877,6879 ,0,0,0}, - {6647,6640,7432 ,6877,6963,6878 ,0,0,0}, {6649,7416,6650 ,6964,6873,6872 ,0,0,0}, - {7416,6649,7433 ,6873,6964,6879 ,0,0,0}, {7429,7430,6657 ,6871,6865,6867 ,0,0,0}, - {7429,6657,6650 ,6871,6867,6872 ,0,0,0}, {7419,7427,7791 ,6866,6869,6965 ,0,0,0}, - {7419,7791,6657 ,6866,6965,6867 ,0,0,0}, {7779,7426,7778 ,6868,6870,6862 ,0,0,0}, - {7791,7427,7779 ,6965,6869,6868 ,0,0,0}, {5725,7778,7426 ,6863,6862,6870 ,0,0,0}, - {5695,7792,7353 ,6966,6967,6968 ,0,0,0}, {7793,7397,7794 ,6969,6970,6971 ,0,0,0}, - {7265,7266,7795 ,6972,6973,6974 ,0,0,0}, {7399,7796,7400 ,6975,6976,6977 ,0,0,0}, - {7797,7798,7341 ,6978,6979,6980 ,0,0,0}, {7799,7396,7800 ,6981,6982,6983 ,0,0,0}, - {7398,7352,7801 ,6984,6985,6986 ,0,0,0}, {7403,7802,7803 ,6987,6988,6989 ,0,0,0}, - {7394,7804,7395 ,6990,6991,6992 ,0,0,0}, {7404,7805,7277 ,6993,6994,6995 ,0,0,0}, - {7806,7404,7345 ,6996,6993,6997 ,0,0,0}, {7278,7807,7405 ,6998,6999,7000 ,0,0,0}, - {7808,7278,7277 ,7001,6998,6995 ,0,0,0}, {7406,7405,7809 ,7002,7000,7003 ,0,0,0}, - {7807,7809,7405 ,6999,7003,7000 ,0,0,0}, {7810,7390,7406 ,7004,7005,7002 ,0,0,0}, - {7406,7809,7810 ,7002,7003,7004 ,0,0,0}, {7390,7811,7408 ,7005,7006,7007 ,0,0,0}, - {7811,7390,7810 ,7006,7005,7004 ,0,0,0}, {7407,7408,7812 ,7008,7007,7009 ,0,0,0}, - {7811,7812,7408 ,7006,7009,7007 ,0,0,0}, {7813,5717,7407 ,7010,82,7008 ,0,0,0}, - {7407,7812,7813 ,7008,7009,7010 ,0,0,0}, {5716,5717,7813 ,7011,82,7010 ,0,0,0}, - {7345,7803,7806 ,6997,6989,6996 ,0,0,0}, {7805,7808,7277 ,6994,7001,6995 ,0,0,0}, - {7808,7807,7278 ,7001,6999,6998 ,0,0,0}, {7805,7404,7806 ,6994,6993,6996 ,0,0,0}, - {7802,7403,7395 ,6988,6987,6992 ,0,0,0}, {7803,7345,7403 ,6989,6997,6987 ,0,0,0}, - {7395,7804,7802 ,6992,6991,6988 ,0,0,0}, {7799,7804,7394 ,6981,6991,6990 ,0,0,0}, - {7814,7400,7796 ,7012,6977,6976 ,0,0,0}, {7398,7800,7396 ,6984,6983,6982 ,0,0,0}, - {7394,7396,7799 ,6990,6982,6981 ,0,0,0}, {7352,7400,7814 ,6985,6977,7012 ,0,0,0}, - {7352,7814,7801 ,6985,7012,6986 ,0,0,0}, {7800,7398,7801 ,6983,6984,6986 ,0,0,0}, - {7397,7265,7794 ,6970,6972,6971 ,0,0,0}, {7796,7399,7798 ,6976,6975,6979 ,0,0,0}, - {7797,7341,7340 ,6978,6980,7013 ,0,0,0}, {7341,7798,7399 ,6980,6979,6975 ,0,0,0}, - {7340,7397,7793 ,7013,6970,6969 ,0,0,0}, {7340,7793,7797 ,7013,6969,6978 ,0,0,0}, - {7266,7792,7795 ,6973,6967,6974 ,0,0,0}, {7794,7265,7795 ,6971,6972,6974 ,0,0,0}, - {5695,7353,5692 ,6966,6968,7014 ,0,0,0}, {7792,7266,7353 ,6967,6973,6968 ,0,0,0}, - {7814,5710,7801 ,730,730,730 ,0,0,0}, {7809,7807,7805 ,730,730,730 ,0,0,0}, - {7807,7808,7805 ,730,730,730 ,0,0,0}, {7805,7806,7810 ,730,730,730 ,0,0,0}, - {7810,7809,7805 ,730,730,730 ,0,0,0}, {7811,7806,7803 ,730,730,730 ,0,0,0}, - {7806,7811,7810 ,730,730,730 ,0,0,0}, {7802,7812,7803 ,730,730,730 ,0,0,0}, - {7811,7803,7812 ,730,730,730 ,0,0,0}, {7813,7802,5716 ,730,730,730 ,0,0,0}, - {7813,7812,7802 ,730,730,730 ,0,0,0}, {7804,7799,5714 ,730,730,730 ,0,0,0}, - {7802,7804,5716 ,730,730,730 ,0,0,0}, {7796,5705,5708 ,730,730,7015 ,0,0,0}, - {5711,5714,7800 ,730,730,730 ,0,0,0}, {7793,5699,5702 ,7016,7015,7017 ,0,0,0}, - {7798,5702,5704 ,730,7017,7017 ,0,0,0}, {5696,5698,7795 ,730,730,730 ,0,0,0}, - {5695,5671,5673 ,730,730,730 ,0,0,0}, {5669,5696,7792 ,7015,730,730 ,0,0,0}, - {5675,5689,5687 ,730,730,7017 ,0,0,0}, {5671,5690,5677 ,730,7017,7015 ,0,0,0}, - {5683,5679,5684 ,730,730,730 ,0,0,0}, {5679,5687,5684 ,730,7017,730 ,0,0,0}, - {5680,5679,5683 ,730,730,730 ,0,0,0}, {5675,5677,5689 ,730,7015,730 ,0,0,0}, - {5679,5675,5687 ,730,730,7017 ,0,0,0}, {5690,5671,5694 ,7017,730,730 ,0,0,0}, - {5689,5677,5690 ,730,7015,7017 ,0,0,0}, {5695,5694,5671 ,730,730,730 ,0,0,0}, - {7792,5673,5669 ,730,730,7015 ,0,0,0}, {7792,5695,5673 ,730,730,730 ,0,0,0}, - {5698,7794,7795 ,730,7016,730 ,0,0,0}, {7795,7792,5696 ,730,730,730 ,0,0,0}, - {7793,7794,5699 ,7016,7016,7015 ,0,0,0}, {5698,5699,7794 ,730,7015,7016 ,0,0,0}, - {5702,7798,7797 ,7017,730,730 ,0,0,0}, {5702,7797,7793 ,7017,730,7016 ,0,0,0}, - {5704,5705,7796 ,7017,730,730 ,0,0,0}, {7798,5704,7796 ,730,7017,730 ,0,0,0}, - {5708,5710,7814 ,7015,730,730 ,0,0,0}, {7796,5708,7814 ,730,7015,730 ,0,0,0}, - {7801,5711,7800 ,730,730,730 ,0,0,0}, {7801,5710,5711 ,730,730,730 ,0,0,0}, - {7804,5714,5716 ,730,730,730 ,0,0,0}, {7799,7800,5714 ,730,730,730 ,0,0,0}, - {7815,7816,5667 ,7018,7019,7020 ,0,0,0}, {5667,7817,7815 ,7020,7021,7018 ,0,0,0}, - {5667,5650,7817 ,7020,7022,7021 ,0,0,0}, {5667,7818,7819 ,7020,7023,7024 ,0,0,0}, - {7816,7818,5667 ,7019,7023,7020 ,0,0,0}, {5667,7820,7821 ,7020,7025,7026 ,0,0,0}, - {7819,7820,5667 ,7024,7025,7020 ,0,0,0}, {7821,7822,5667 ,7026,7027,7020 ,0,0,0}, - {7823,5667,7824 ,7028,7020,7029 ,0,0,0}, {5667,7822,7824 ,7020,7027,7029 ,0,0,0}, - {7825,5667,7826 ,7030,7020,7031 ,0,0,0}, {5667,7823,7826 ,7020,7028,7031 ,0,0,0}, - {7827,5667,7828 ,7032,7020,7033 ,0,0,0}, {5667,7825,7828 ,7020,7030,7033 ,0,0,0}, - {5666,5667,7827 ,7034,7020,7032 ,0,0,0}, {5649,7322,7817 ,7035,7036,7037 ,0,0,0}, - {7819,7818,7312 ,7038,7039,7040 ,0,0,0}, {7816,7815,7321 ,7041,7042,7043 ,0,0,0}, - {7821,7379,7822 ,7044,7045,7046 ,0,0,0}, {7311,7324,7820 ,7047,7048,7049 ,0,0,0}, - {7380,7205,7823 ,7050,7051,7052 ,0,0,0}, {7380,7824,7271 ,7050,7053,7054 ,0,0,0}, - {7269,7328,7825 ,7055,7056,7057 ,0,0,0}, {7825,7826,7269 ,7057,7058,7055 ,0,0,0}, - {7828,7328,7314 ,7059,7056,7060 ,0,0,0}, {7328,7828,7825 ,7056,7059,7057 ,0,0,0}, - {7302,7827,7314 ,7061,7062,7060 ,0,0,0}, {7828,7314,7827 ,7059,7060,7062 ,0,0,0}, - {7302,5665,5666 ,7061,7063,4910 ,0,0,0}, {5666,7827,7302 ,4910,7062,7061 ,0,0,0}, - {7379,7821,7324 ,7045,7044,7048 ,0,0,0}, {7205,7826,7823 ,7051,7058,7052 ,0,0,0}, - {7269,7826,7205 ,7055,7058,7051 ,0,0,0}, {7312,7818,7320 ,7040,7039,7064 ,0,0,0}, - {7271,7824,7822 ,7054,7053,7046 ,0,0,0}, {7380,7823,7824 ,7050,7052,7053 ,0,0,0}, - {7379,7271,7822 ,7045,7054,7046 ,0,0,0}, {7820,7324,7821 ,7049,7048,7044 ,0,0,0}, - {7819,7312,7311 ,7038,7040,7047 ,0,0,0}, {7311,7820,7819 ,7047,7049,7038 ,0,0,0}, - {7815,7322,7321 ,7042,7036,7043 ,0,0,0}, {7320,7816,7321 ,7064,7041,7043 ,0,0,0}, - {7818,7816,7320 ,7039,7041,7064 ,0,0,0}, {5649,7817,5650 ,7035,7037,4929 ,0,0,0}, - {7322,7815,7817 ,7036,7042,7037 ,0,0,0}, {7829,7830,5633 ,7018,7019,7065 ,0,0,0}, - {5633,7831,7829 ,7065,7021,7018 ,0,0,0}, {5633,5616,7831 ,7065,7066,7021 ,0,0,0}, - {5633,7832,7833 ,7065,7023,7024 ,0,0,0}, {7830,7832,5633 ,7019,7023,7065 ,0,0,0}, - {5633,7834,7835 ,7065,7025,7026 ,0,0,0}, {7833,7834,5633 ,7024,7025,7065 ,0,0,0}, - {7835,7836,5633 ,7026,7027,7065 ,0,0,0}, {7837,5633,7838 ,7028,7065,7029 ,0,0,0}, - {5633,7836,7838 ,7065,7027,7029 ,0,0,0}, {7839,5633,7840 ,7030,7065,7031 ,0,0,0}, - {5633,7837,7840 ,7065,7028,7031 ,0,0,0}, {7841,5633,7842 ,7032,7065,7033 ,0,0,0}, - {5633,7839,7842 ,7065,7030,7033 ,0,0,0}, {5632,5633,7841 ,7067,7065,7032 ,0,0,0}, - {5615,7371,7831 ,7068,7069,7070 ,0,0,0}, {7833,7832,7212 ,7071,7072,7073 ,0,0,0}, - {7830,7829,7251 ,7074,7075,7076 ,0,0,0}, {7835,7231,7836 ,7077,7078,7079 ,0,0,0}, - {7213,7376,7834 ,7047,7080,7081 ,0,0,0}, {7195,7374,7837 ,7082,7083,7084 ,0,0,0}, - {7195,7838,7375 ,7082,7085,7086 ,0,0,0}, {7373,7249,7839 ,7087,7088,7089 ,0,0,0}, - {7839,7840,7373 ,7089,7090,7087 ,0,0,0}, {7842,7249,7250 ,7091,7088,7092 ,0,0,0}, - {7249,7842,7839 ,7088,7091,7089 ,0,0,0}, {7372,7841,7250 ,7093,7094,7092 ,0,0,0}, - {7842,7250,7841 ,7091,7092,7094 ,0,0,0}, {7372,5631,5632 ,7093,4831,4942 ,0,0,0}, - {5632,7841,7372 ,4942,7094,7093 ,0,0,0}, {7231,7835,7376 ,7078,7077,7080 ,0,0,0}, - {7374,7840,7837 ,7083,7090,7084 ,0,0,0}, {7373,7840,7374 ,7087,7090,7083 ,0,0,0}, - {7212,7832,7248 ,7073,7072,7095 ,0,0,0}, {7375,7838,7836 ,7086,7085,7079 ,0,0,0}, - {7195,7837,7838 ,7082,7084,7085 ,0,0,0}, {7231,7375,7836 ,7078,7086,7079 ,0,0,0}, - {7834,7376,7835 ,7081,7080,7077 ,0,0,0}, {7833,7212,7213 ,7071,7073,7047 ,0,0,0}, - {7213,7834,7833 ,7047,7081,7071 ,0,0,0}, {7829,7371,7251 ,7075,7069,7076 ,0,0,0}, - {7248,7830,7251 ,7095,7074,7076 ,0,0,0}, {7832,7830,7248 ,7072,7074,7095 ,0,0,0}, - {5615,7831,5616 ,7068,7070,4899 ,0,0,0}, {7371,7829,7831 ,7069,7075,7070 ,0,0,0}, - {7843,7844,5599 ,7018,7019,7065 ,0,0,0}, {5599,7845,7843 ,7065,7021,7018 ,0,0,0}, - {5599,5582,7845 ,7065,7096,7021 ,0,0,0}, {5599,7846,7847 ,7065,7023,7024 ,0,0,0}, - {7844,7846,5599 ,7019,7023,7065 ,0,0,0}, {5599,7848,7849 ,7065,7025,7026 ,0,0,0}, - {7847,7848,5599 ,7024,7025,7065 ,0,0,0}, {7849,7850,5599 ,7026,7027,7065 ,0,0,0}, - {7851,5599,7852 ,7028,7065,7029 ,0,0,0}, {5599,7850,7852 ,7065,7027,7029 ,0,0,0}, - {7853,5599,7854 ,7030,7065,7031 ,0,0,0}, {5599,7851,7854 ,7065,7028,7031 ,0,0,0}, - {7855,5599,7856 ,7032,7065,7033 ,0,0,0}, {5599,7853,7856 ,7065,7030,7033 ,0,0,0}, - {5598,5599,7855 ,7097,7065,7032 ,0,0,0}, {5581,7369,7845 ,7098,7099,7100 ,0,0,0}, - {7847,7846,7334 ,7101,7102,7103 ,0,0,0}, {7844,7843,7361 ,7104,7105,7076 ,0,0,0}, - {7849,7333,7850 ,7106,7107,7108 ,0,0,0}, {7368,7367,7848 ,7109,7110,7111 ,0,0,0}, - {7245,7242,7851 ,7112,7113,7114 ,0,0,0}, {7245,7852,7362 ,7112,7115,7116 ,0,0,0}, - {7247,7246,7853 ,7117,7118,7119 ,0,0,0}, {7853,7854,7247 ,7119,7120,7117 ,0,0,0}, - {7856,7246,7244 ,7121,7118,7122 ,0,0,0}, {7246,7856,7853 ,7118,7121,7119 ,0,0,0}, - {7243,7855,7244 ,7123,7124,7122 ,0,0,0}, {7856,7244,7855 ,7121,7122,7124 ,0,0,0}, - {7243,5597,5598 ,7123,4831,4831 ,0,0,0}, {5598,7855,7243 ,4831,7124,7123 ,0,0,0}, - {7333,7849,7367 ,7107,7106,7110 ,0,0,0}, {7242,7854,7851 ,7113,7120,7114 ,0,0,0}, - {7247,7854,7242 ,7117,7120,7113 ,0,0,0}, {7334,7846,7360 ,7103,7102,7125 ,0,0,0}, - {7362,7852,7850 ,7116,7115,7108 ,0,0,0}, {7245,7851,7852 ,7112,7114,7115 ,0,0,0}, - {7333,7362,7850 ,7107,7116,7108 ,0,0,0}, {7848,7367,7849 ,7111,7110,7106 ,0,0,0}, - {7847,7334,7368 ,7101,7103,7109 ,0,0,0}, {7368,7848,7847 ,7109,7111,7101 ,0,0,0}, - {7843,7369,7361 ,7105,7099,7076 ,0,0,0}, {7360,7844,7361 ,7125,7104,7076 ,0,0,0}, - {7846,7844,7360 ,7102,7104,7125 ,0,0,0}, {5581,7845,5582 ,7098,7100,4865 ,0,0,0}, - {7369,7843,7845 ,7099,7105,7100 ,0,0,0}, {7857,7858,5565 ,7018,7019,7126 ,0,0,0}, - {5565,7859,7857 ,7126,7021,7018 ,0,0,0}, {5565,5548,7859 ,7126,7127,7021 ,0,0,0}, - {5565,7860,7861 ,7126,7023,7024 ,0,0,0}, {7858,7860,5565 ,7019,7023,7126 ,0,0,0}, - {5565,7862,7863 ,7126,7025,7026 ,0,0,0}, {7861,7862,5565 ,7024,7025,7126 ,0,0,0}, - {7863,7864,5565 ,7026,7027,7126 ,0,0,0}, {7865,5565,7866 ,7028,7126,7029 ,0,0,0}, - {5565,7864,7866 ,7126,7027,7029 ,0,0,0}, {7867,5565,7868 ,7030,7126,7031 ,0,0,0}, - {5565,7865,7868 ,7126,7028,7031 ,0,0,0}, {7869,5565,7870 ,7032,7126,7033 ,0,0,0}, - {5565,7867,7870 ,7126,7030,7033 ,0,0,0}, {5564,5565,7869 ,7128,7126,7032 ,0,0,0}, - {5547,7350,7859 ,7129,7099,7130 ,0,0,0}, {7861,7860,7355 ,7131,7132,7133 ,0,0,0}, - {7858,7857,7349 ,7041,7075,7134 ,0,0,0}, {7863,7356,7864 ,7135,7107,7136 ,0,0,0}, - {7354,7382,7862 ,7137,7138,7139 ,0,0,0}, {7232,7233,7865 ,7140,7141,7142 ,0,0,0}, - {7232,7866,7338 ,7140,7143,7144 ,0,0,0}, {7316,7317,7867 ,7145,7146,7147 ,0,0,0}, - {7867,7868,7316 ,7147,7148,7145 ,0,0,0}, {7870,7317,7402 ,7149,7146,7150 ,0,0,0}, - {7317,7870,7867 ,7146,7149,7147 ,0,0,0}, {7401,7869,7402 ,7151,7152,7150 ,0,0,0}, - {7870,7402,7869 ,7149,7150,7152 ,0,0,0}, {7401,5563,5564 ,7151,7153,4831 ,0,0,0}, - {5564,7869,7401 ,4831,7152,7151 ,0,0,0}, {7356,7863,7382 ,7107,7135,7138 ,0,0,0}, - {7233,7868,7865 ,7141,7148,7142 ,0,0,0}, {7316,7868,7233 ,7145,7148,7141 ,0,0,0}, - {7355,7860,7358 ,7133,7132,7154 ,0,0,0}, {7338,7866,7864 ,7144,7143,7136 ,0,0,0}, - {7232,7865,7866 ,7140,7142,7143 ,0,0,0}, {7356,7338,7864 ,7107,7144,7136 ,0,0,0}, - {7862,7382,7863 ,7139,7138,7135 ,0,0,0}, {7861,7355,7354 ,7131,7133,7137 ,0,0,0}, - {7354,7862,7861 ,7137,7139,7131 ,0,0,0}, {7857,7350,7349 ,7075,7099,7134 ,0,0,0}, - {7358,7858,7349 ,7154,7041,7134 ,0,0,0}, {7860,7858,7358 ,7132,7041,7154 ,0,0,0}, - {5547,7859,5548 ,7129,7130,4929 ,0,0,0}, {7350,7857,7859 ,7099,7075,7130 ,0,0,0}, - {5508,5507,7871 ,4777,21,7155 ,0,0,0}, {7215,7228,7872 ,7156,7157,7158 ,0,0,0}, - {7224,7873,7874 ,7159,7160,7161 ,0,0,0}, {7875,7876,7206 ,7162,7163,7164 ,0,0,0}, - {7877,7272,7230 ,7165,7166,7167 ,0,0,0}, {7283,7327,7878 ,7168,7169,7170 ,0,0,0}, - {7268,7879,7880 ,7171,7172,7173 ,0,0,0}, {7258,7881,7290 ,7174,7175,7176 ,0,0,0}, - {7882,7883,7287 ,7177,7178,7179 ,0,0,0}, {7884,7885,7296 ,7180,7181,7182 ,0,0,0}, - {7886,7288,7290 ,7183,7184,7176 ,0,0,0}, {7887,7888,7297 ,7185,7186,7187 ,0,0,0}, - {7887,7294,7885 ,7185,7188,7181 ,0,0,0}, {7298,7888,7889 ,7189,7186,7190 ,0,0,0}, - {7888,7298,7297 ,7186,7189,7187 ,0,0,0}, {7890,7293,7889 ,7191,7192,7190 ,0,0,0}, - {7298,7889,7293 ,7189,7190,7192 ,0,0,0}, {7890,7891,7291 ,7191,7193,7194 ,0,0,0}, - {7291,7293,7890 ,7194,7192,7191 ,0,0,0}, {7300,7891,7892 ,7195,7193,7196 ,0,0,0}, - {7891,7300,7291 ,7193,7195,7194 ,0,0,0}, {5530,7301,7892 ,7197,7198,7196 ,0,0,0}, - {7300,7892,7301 ,7195,7196,7198 ,0,0,0}, {5531,7301,5530 ,7199,7198,7197 ,0,0,0}, - {7258,7883,7881 ,7174,7178,7175 ,0,0,0}, {7294,7296,7885 ,7188,7182,7181 ,0,0,0}, - {7887,7297,7294 ,7185,7187,7188 ,0,0,0}, {7288,7886,7884 ,7184,7183,7180 ,0,0,0}, - {7884,7296,7288 ,7180,7182,7184 ,0,0,0}, {7886,7290,7881 ,7183,7176,7175 ,0,0,0}, - {7883,7258,7287 ,7178,7174,7179 ,0,0,0}, {7283,7878,7882 ,7168,7170,7177 ,0,0,0}, - {7283,7882,7287 ,7168,7177,7179 ,0,0,0}, {7272,7875,7206 ,7166,7162,7164 ,0,0,0}, - {7880,7327,7268 ,7173,7169,7171 ,0,0,0}, {7327,7880,7878 ,7169,7173,7170 ,0,0,0}, - {7207,7206,7876 ,7200,7164,7163 ,0,0,0}, {7268,7207,7879 ,7171,7200,7172 ,0,0,0}, - {7879,7207,7876 ,7172,7200,7163 ,0,0,0}, {7877,7875,7272 ,7165,7162,7166 ,0,0,0}, - {7893,7877,7230 ,7201,7165,7167 ,0,0,0}, {7215,7872,7893 ,7156,7158,7201 ,0,0,0}, - {7215,7893,7230 ,7156,7201,7167 ,0,0,0}, {7329,7871,7873 ,7202,7155,7160 ,0,0,0}, - {7874,7228,7224 ,7161,7157,7159 ,0,0,0}, {7228,7874,7872 ,7157,7161,7158 ,0,0,0}, - {7329,7873,7224 ,7202,7160,7159 ,0,0,0}, {7871,7329,5508 ,7155,7202,4777 ,0,0,0}, - {5496,7884,5499 ,730,7015,730 ,0,0,0}, {7874,7873,7879 ,730,730,730 ,0,0,0}, - {5506,5502,7883 ,730,730,730 ,0,0,0}, {5500,7886,7881 ,730,730,7015 ,0,0,0}, - {7880,7879,7873 ,730,730,730 ,0,0,0}, {5507,7882,7871 ,730,730,730 ,0,0,0}, - {7877,7893,7872 ,730,730,730 ,0,0,0}, {7872,7874,7876 ,730,730,730 ,0,0,0}, - {7872,7876,7875 ,730,730,730 ,0,0,0}, {7877,7872,7875 ,730,730,730 ,0,0,0}, - {7873,7871,7880 ,730,730,730 ,0,0,0}, {7876,7874,7879 ,730,730,730 ,0,0,0}, - {7871,7878,7880 ,730,730,730 ,0,0,0}, {7882,5507,7883 ,730,730,730 ,0,0,0}, - {7878,7871,7882 ,730,730,730 ,0,0,0}, {7883,5502,7881 ,730,730,7015 ,0,0,0}, - {7883,5507,5506 ,730,730,730 ,0,0,0}, {7886,5500,5499 ,730,730,730 ,0,0,0}, - {7881,5502,5500 ,7015,730,730 ,0,0,0}, {7885,7884,5496 ,730,7015,730 ,0,0,0}, - {7884,7886,5499 ,7015,730,730 ,0,0,0}, {7887,5496,5495 ,7015,730,730 ,0,0,0}, - {5496,7887,7885 ,730,7015,730 ,0,0,0}, {7887,5495,7888 ,7015,730,730 ,0,0,0}, - {5488,7888,5492 ,730,730,730 ,0,0,0}, {7888,5495,5492 ,730,730,730 ,0,0,0}, - {5488,5487,7889 ,730,730,7015 ,0,0,0}, {7889,7888,5488 ,7015,730,730 ,0,0,0}, - {7889,5487,7890 ,7015,730,7015 ,0,0,0}, {5491,7891,7890 ,730,730,7015 ,0,0,0}, - {7890,5487,5491 ,7015,730,730 ,0,0,0}, {7891,5486,7892 ,730,730,7015 ,0,0,0}, - {5486,7891,5491 ,730,730,730 ,0,0,0}, {5482,5530,5486 ,730,7015,730 ,0,0,0}, - {7892,5486,5530 ,7015,730,7015 ,0,0,0}, {5529,5511,5527 ,7015,7015,730 ,0,0,0}, - {5482,5481,5529 ,730,730,7015 ,0,0,0}, {5523,5518,5521 ,7015,7015,7015 ,0,0,0}, - {5515,5524,5512 ,7015,7015,730 ,0,0,0}, {5523,5515,5517 ,7015,7015,7015 ,0,0,0}, - {5518,5523,5517 ,7015,7015,7015 ,0,0,0}, {5527,5512,5524 ,730,730,7015 ,0,0,0}, - {5524,5515,5523 ,7015,7015,7015 ,0,0,0}, {5529,5481,5511 ,7015,730,7015 ,0,0,0}, - {5527,5511,5512 ,730,7015,730 ,0,0,0}, {5529,5530,5482 ,7015,7015,730 ,0,0,0}, - {5458,7189,7894 ,126,7203,7204 ,0,0,0}, {7895,7896,7191 ,7205,7206,7207 ,0,0,0}, - {7241,7897,7309 ,7208,7209,7210 ,0,0,0}, {7330,7332,7898 ,7211,7212,7213 ,0,0,0}, - {7899,7202,7900 ,7214,7215,7216 ,0,0,0}, {7901,7902,7227 ,7217,7218,7219 ,0,0,0}, - {7252,7903,7370 ,7220,7221,7222 ,0,0,0}, {7221,7904,7905 ,7223,7224,7225 ,0,0,0}, - {7219,7220,7906 ,7226,7227,7228 ,0,0,0}, {7217,7211,7907 ,7229,7230,7231 ,0,0,0}, - {7908,7218,7217 ,7232,7233,7229 ,0,0,0}, {7209,7210,7909 ,7234,7235,7236 ,0,0,0}, - {7910,7211,7209 ,7237,7230,7234 ,0,0,0}, {7208,7911,7210 ,7238,7239,7235 ,0,0,0}, - {7909,7210,7911 ,7236,7235,7239 ,0,0,0}, {7912,7208,7201 ,7240,7238,7241 ,0,0,0}, - {7208,7912,7911 ,7238,7240,7239 ,0,0,0}, {7201,7200,7913 ,7241,7242,7243 ,0,0,0}, - {7913,7912,7201 ,7243,7240,7241 ,0,0,0}, {7197,7914,7200 ,7244,7245,7242 ,0,0,0}, - {7913,7200,7914 ,7243,7242,7245 ,0,0,0}, {7915,7197,5480 ,7246,7244,82 ,0,0,0}, - {7197,7915,7914 ,7244,7246,7245 ,0,0,0}, {5478,7915,5480 ,7011,7246,82 ,0,0,0}, - {7218,7908,7904 ,7233,7232,7224 ,0,0,0}, {7907,7211,7910 ,7231,7230,7237 ,0,0,0}, - {7910,7209,7909 ,7237,7234,7236 ,0,0,0}, {7907,7908,7217 ,7231,7232,7229 ,0,0,0}, - {7905,7220,7221 ,7225,7227,7223 ,0,0,0}, {7904,7221,7218 ,7224,7223,7233 ,0,0,0}, - {7220,7905,7906 ,7227,7225,7228 ,0,0,0}, {7901,7219,7906 ,7217,7226,7228 ,0,0,0}, - {7916,7898,7332 ,7247,7213,7212 ,0,0,0}, {7252,7227,7902 ,7220,7219,7218 ,0,0,0}, - {7219,7901,7227 ,7226,7217,7219 ,0,0,0}, {7370,7916,7332 ,7222,7247,7212 ,0,0,0}, - {7370,7903,7916 ,7222,7221,7247 ,0,0,0}, {7902,7903,7252 ,7218,7221,7220 ,0,0,0}, - {7191,7896,7241 ,7207,7206,7208 ,0,0,0}, {7898,7900,7330 ,7213,7216,7211 ,0,0,0}, - {7899,7204,7202 ,7214,7248,7215 ,0,0,0}, {7202,7330,7900 ,7215,7211,7216 ,0,0,0}, - {7204,7895,7191 ,7248,7205,7207 ,0,0,0}, {7204,7899,7895 ,7248,7214,7205 ,0,0,0}, - {7309,7897,7894 ,7210,7209,7204 ,0,0,0}, {7896,7897,7241 ,7206,7209,7208 ,0,0,0}, - {5458,5455,7189 ,126,4726,7203 ,0,0,0}, {7894,7189,7309 ,7204,7203,7210 ,0,0,0}, - {7909,7907,7910 ,7249,7250,7251 ,0,0,0}, {5460,7896,5462 ,726,726,7252 ,0,0,0}, - {7912,7907,7911 ,7253,7250,7253 ,0,0,0}, {7907,7909,7911 ,7250,7249,7253 ,0,0,0}, - {7908,7912,7913 ,7254,7253,7249 ,0,0,0}, {7912,7908,7907 ,7253,7254,7250 ,0,0,0}, - {7913,7914,7904 ,7249,7249,7255 ,0,0,0}, {7904,7908,7913 ,7255,7254,7249 ,0,0,0}, - {7914,7905,7904 ,7249,7256,7255 ,0,0,0}, {7915,5478,7905 ,7257,7257,7256 ,0,0,0}, - {7915,7905,7914 ,7257,7256,7249 ,0,0,0}, {7906,5477,7901 ,7258,726,7259 ,0,0,0}, - {7905,5478,7906 ,7256,7257,7258 ,0,0,0}, {7916,7903,5472 ,7260,7254,7257 ,0,0,0}, - {5474,7902,5477 ,7252,7261,726 ,0,0,0}, {5465,7900,5466 ,726,7262,7252 ,0,0,0}, - {5471,5468,7898 ,726,7252,7263 ,0,0,0}, {7897,5460,5459 ,7253,726,726 ,0,0,0}, - {7895,5465,5462 ,726,726,7252 ,0,0,0}, {5458,5435,5434 ,726,726,726 ,0,0,0}, - {5433,7894,5459 ,7264,7253,726 ,0,0,0}, {5439,5451,5452 ,726,7257,726 ,0,0,0}, - {5434,5440,5454 ,726,7264,726 ,0,0,0}, {5446,5448,5442 ,7257,726,7257 ,0,0,0}, - {5448,5451,5442 ,726,7257,7257 ,0,0,0}, {5446,5442,5444 ,7257,7257,7257 ,0,0,0}, - {5452,5440,5439 ,726,7264,726 ,0,0,0}, {5451,5439,5442 ,7257,726,7257 ,0,0,0}, - {5456,5434,5454 ,726,726,726 ,0,0,0}, {5454,5440,5452 ,726,7264,726 ,0,0,0}, - {5435,5458,7894 ,726,726,7253 ,0,0,0}, {5434,5456,5458 ,726,726,726 ,0,0,0}, - {5459,7894,7897 ,726,7253,7253 ,0,0,0}, {5435,7894,5433 ,726,7253,7264 ,0,0,0}, - {5462,7896,7895 ,7252,726,726 ,0,0,0}, {7896,5460,7897 ,726,726,7253 ,0,0,0}, - {7900,5465,7899 ,7262,726,7262 ,0,0,0}, {7899,5465,7895 ,7262,726,726 ,0,0,0}, - {5468,5466,7898 ,7252,7252,7263 ,0,0,0}, {5466,7900,7898 ,7252,7262,7263 ,0,0,0}, - {7898,7916,5471 ,7263,7260,726 ,0,0,0}, {5474,5472,7903 ,7252,7257,7254 ,0,0,0}, - {5472,5471,7916 ,7257,726,7260 ,0,0,0}, {5477,7902,7901 ,726,7261,7259 ,0,0,0}, - {5474,7903,7902 ,7252,7254,7261 ,0,0,0}, {5477,7906,5478 ,726,7258,7257 ,0,0,0}, - {5408,7917,7183 ,4799,7265,7266 ,0,0,0}, {7918,7185,7919 ,7267,7268,7269 ,0,0,0}, - {7184,7359,7920 ,7270,7271,7272 ,0,0,0}, {7366,7921,7193 ,7273,7274,7275 ,0,0,0}, - {7922,7923,7365 ,7276,7277,7278 ,0,0,0}, {7924,7363,7925 ,7279,7280,7281 ,0,0,0}, - {7383,7335,7926 ,7282,7283,7284 ,0,0,0}, {7384,7927,7928 ,7285,7286,7287 ,0,0,0}, - {7238,7929,7239 ,7288,7289,7290 ,0,0,0}, {7385,7930,7236 ,7291,7292,7293 ,0,0,0}, - {7931,7385,7194 ,7294,7291,7295 ,0,0,0}, {7235,7932,7386 ,7296,7297,7298 ,0,0,0}, - {7933,7235,7236 ,7299,7296,7293 ,0,0,0}, {7387,7386,7934 ,7300,7298,7301 ,0,0,0}, - {7932,7934,7386 ,7297,7301,7298 ,0,0,0}, {7935,7336,7387 ,7302,7303,7300 ,0,0,0}, - {7387,7934,7935 ,7300,7301,7302 ,0,0,0}, {7336,7936,7389 ,7303,7304,7305 ,0,0,0}, - {7936,7336,7935 ,7304,7303,7302 ,0,0,0}, {7388,7389,7937 ,7306,7305,7307 ,0,0,0}, - {7936,7937,7389 ,7304,7307,7305 ,0,0,0}, {7938,5430,7388 ,7308,21,7306 ,0,0,0}, - {7388,7937,7938 ,7306,7307,7308 ,0,0,0}, {5429,5430,7938 ,7309,21,7308 ,0,0,0}, - {7194,7928,7931 ,7295,7287,7294 ,0,0,0}, {7930,7933,7236 ,7292,7299,7293 ,0,0,0}, - {7933,7932,7235 ,7299,7297,7296 ,0,0,0}, {7930,7385,7931 ,7292,7291,7294 ,0,0,0}, - {7927,7384,7239 ,7286,7285,7290 ,0,0,0}, {7928,7194,7384 ,7287,7295,7285 ,0,0,0}, - {7239,7929,7927 ,7290,7289,7286 ,0,0,0}, {7924,7929,7238 ,7279,7289,7288 ,0,0,0}, - {7939,7193,7921 ,7310,7275,7274 ,0,0,0}, {7383,7925,7363 ,7282,7281,7280 ,0,0,0}, - {7238,7363,7924 ,7288,7280,7279 ,0,0,0}, {7335,7193,7939 ,7283,7275,7310 ,0,0,0}, - {7335,7939,7926 ,7283,7310,7284 ,0,0,0}, {7925,7383,7926 ,7281,7282,7284 ,0,0,0}, - {7185,7184,7919 ,7268,7270,7269 ,0,0,0}, {7921,7366,7923 ,7274,7273,7277 ,0,0,0}, - {7922,7365,7364 ,7276,7278,7311 ,0,0,0}, {7365,7923,7366 ,7278,7277,7273 ,0,0,0}, - {7364,7185,7918 ,7311,7268,7267 ,0,0,0}, {7364,7918,7922 ,7311,7267,7276 ,0,0,0}, - {7359,7917,7920 ,7271,7265,7272 ,0,0,0}, {7919,7184,7920 ,7269,7270,7272 ,0,0,0}, - {5408,7183,5405 ,4799,7266,7199 ,0,0,0}, {7917,7359,7183 ,7265,7271,7266 ,0,0,0}, - {7930,5400,5397 ,730,7312,6103 ,0,0,0}, {5393,7934,5396 ,7313,730,730 ,0,0,0}, - {5403,7927,5407 ,7314,7015,7315 ,0,0,0}, {7931,7928,5402 ,730,730,7316 ,0,0,0}, - {7926,7920,7925 ,730,7317,7313 ,0,0,0}, {7929,7917,5408 ,730,7318,7319 ,0,0,0}, - {7918,7919,7939 ,7320,7316,7316 ,0,0,0}, {7921,7923,7918 ,7320,6103,7320 ,0,0,0}, - {7922,7918,7923 ,6111,7320,6103 ,0,0,0}, {7926,7939,7919 ,730,7316,7316 ,0,0,0}, - {7939,7921,7918 ,7316,7320,7320 ,0,0,0}, {7917,7925,7920 ,7318,7313,7317 ,0,0,0}, - {7920,7926,7919 ,7317,730,7316 ,0,0,0}, {7929,7924,7917 ,730,7316,7318 ,0,0,0}, - {7917,7924,7925 ,7318,7316,7313 ,0,0,0}, {5407,7927,5408 ,7315,7015,7319 ,0,0,0}, - {5408,7927,7929 ,7319,7015,730 ,0,0,0}, {5402,7928,5403 ,7316,730,7314 ,0,0,0}, - {5403,7928,7927 ,7314,730,7015 ,0,0,0}, {7931,5402,5400 ,730,7316,7312 ,0,0,0}, - {5397,7933,7930 ,6103,7017,730 ,0,0,0}, {5400,7930,7931 ,7312,730,730 ,0,0,0}, - {7933,5397,7932 ,7017,6103,7017 ,0,0,0}, {5396,7934,7932 ,730,730,7017 ,0,0,0}, - {7932,5397,5396 ,7017,6103,730 ,0,0,0}, {7934,5393,5392 ,730,7313,730 ,0,0,0}, - {5392,5388,7935 ,730,7316,730 ,0,0,0}, {7935,7934,5392 ,730,730,730 ,0,0,0}, - {7936,5388,5390 ,7016,7316,7313 ,0,0,0}, {5388,7936,7935 ,7316,7016,730 ,0,0,0}, - {5384,7937,5390 ,7015,730,7313 ,0,0,0}, {7936,5390,7937 ,7016,7313,730 ,0,0,0}, - {7938,5384,5429 ,730,7015,730 ,0,0,0}, {7938,7937,5384 ,730,730,7015 ,0,0,0}, - {5384,5386,5429 ,7015,7015,730 ,0,0,0}, {5427,5409,5424 ,730,730,730 ,0,0,0}, - {5386,5382,5427 ,7015,730,730 ,0,0,0}, {5421,5417,5418 ,730,730,7017 ,0,0,0}, - {5412,5423,5411 ,7015,7016,730 ,0,0,0}, {5421,5412,5415 ,730,7015,730 ,0,0,0}, - {5417,5421,5415 ,730,730,730 ,0,0,0}, {5424,5411,5423 ,730,730,7016 ,0,0,0}, - {5423,5412,5421 ,7016,7015,730 ,0,0,0}, {5427,5382,5409 ,730,730,730 ,0,0,0}, - {5424,5409,5411 ,730,730,730 ,0,0,0}, {5427,5429,5386 ,730,730,7015 ,0,0,0}, - {5940,7940,7941 ,7321,1711,7322 ,0,0,0}, {5930,5927,7942 ,7323,7324,7325 ,0,0,0}, - {7943,5929,5938 ,7326,7327,7328 ,0,0,0}, {7756,7944,7755 ,7329,7330,7331 ,0,0,0}, - {7945,7946,5934 ,7332,7333,7334 ,0,0,0}, {7753,7947,7752 ,7335,7336,7337 ,0,0,0}, - {7947,7754,7948 ,7336,7338,7339 ,0,0,0}, {7751,7752,7949 ,7340,7337,7341 ,0,0,0}, - {7947,7949,7752 ,7336,7341,7337 ,0,0,0}, {7950,7750,7751 ,1359,1359,7340 ,0,0,0}, - {7751,7949,7950 ,7340,7341,1359 ,0,0,0}, {7948,7754,7755 ,7339,7338,7331 ,0,0,0}, - {7947,7753,7754 ,7336,7335,7338 ,0,0,0}, {7944,7756,7757 ,7330,7329,7342 ,0,0,0}, - {7944,7948,7755 ,7330,7339,7331 ,0,0,0}, {7757,5934,7946 ,7342,7334,7333 ,0,0,0}, - {7946,7944,7757 ,7333,7330,7342 ,0,0,0}, {5933,7942,7945 ,7343,7325,7332 ,0,0,0}, - {5933,7945,5934 ,7343,7332,7334 ,0,0,0}, {5927,7951,7942 ,7324,7344,7325 ,0,0,0}, - {5933,5930,7942 ,7343,7323,7325 ,0,0,0}, {7943,7951,5929 ,7326,7344,7327 ,0,0,0}, - {5927,5929,7951 ,7324,7327,7344 ,0,0,0}, {7943,5937,7941 ,7326,7345,7322 ,0,0,0}, - {5938,5937,7943 ,7328,7345,7326 ,0,0,0}, {7940,5940,5906 ,1711,7321,1711 ,0,0,0}, - {7941,5937,5940 ,7322,7345,7321 ,0,0,0}, {7940,5908,7952 ,2197,7346,7346 ,0,0,0}, - {5908,7940,5906 ,7346,2197,2197 ,0,0,0}, {7953,7954,7760 ,1435,7347,7348 ,0,0,0}, - {7761,7759,7955 ,7349,7350,7351 ,0,0,0}, {7758,7763,7956 ,7352,7353,7354 ,0,0,0}, - {5919,7957,5917 ,7355,7356,7357 ,0,0,0}, {7958,7959,5925 ,7358,7359,7360 ,0,0,0}, - {5913,7960,5911 ,7361,7362,7363 ,0,0,0}, {5913,5915,7960 ,7361,7364,7362 ,0,0,0}, - {5910,5911,7961 ,7365,7363,7366 ,0,0,0}, {7960,7961,5911 ,7362,7366,7363 ,0,0,0}, - {7952,5908,5910 ,1790,1790,7365 ,0,0,0}, {5910,7961,7952 ,7365,7366,1790 ,0,0,0}, - {5917,7962,5915 ,7357,7367,7364 ,0,0,0}, {7960,5915,7962 ,7362,7364,7367 ,0,0,0}, - {7758,7963,7759 ,7352,7368,7350 ,0,0,0}, {5919,5923,7957 ,7355,7369,7356 ,0,0,0}, - {7957,7962,5917 ,7356,7367,7357 ,0,0,0}, {5923,5925,7959 ,7369,7360,7359 ,0,0,0}, - {7959,7957,5923 ,7359,7356,7369 ,0,0,0}, {7958,5925,7762 ,7358,7360,7370 ,0,0,0}, - {7955,7762,7761 ,7351,7370,7349 ,0,0,0}, {7762,7955,7958 ,7370,7351,7358 ,0,0,0}, - {7963,7955,7759 ,7368,7351,7350 ,0,0,0}, {7956,7764,7954 ,7354,7371,7347 ,0,0,0}, - {7764,7956,7763 ,7371,7354,7353 ,0,0,0}, {7963,7758,7956 ,7368,7352,7354 ,0,0,0}, - {7953,7760,7749 ,1435,7348,1435 ,0,0,0}, {7954,7764,7760 ,7347,7371,7348 ,0,0,0}, - {7749,7950,7953 ,1398,7372,1398 ,0,0,0}, {7950,7749,7750 ,7372,1398,7372 ,0,0,0}, - {7950,7954,7953 ,7373,730,730 ,0,0,0}, {7951,7960,7962 ,730,730,730 ,0,0,0}, - {7948,7955,7963 ,7374,7375,7375 ,0,0,0}, {7963,7956,7947 ,7375,730,7373 ,0,0,0}, - {7946,7959,7958 ,7375,7375,7375 ,0,0,0}, {7958,7955,7944 ,7375,7375,730 ,0,0,0}, - {7962,7957,7942 ,730,730,7376 ,0,0,0}, {7957,7959,7945 ,730,7375,7375 ,0,0,0}, - {7941,7961,7943 ,730,730,730 ,0,0,0}, {7960,7943,7961 ,730,730,730 ,0,0,0}, - {7941,7940,7952 ,730,730,730 ,0,0,0}, {7952,7961,7941 ,730,730,730 ,0,0,0}, - {7962,7942,7951 ,730,7376,730 ,0,0,0}, {7960,7951,7943 ,730,730,730 ,0,0,0}, - {7957,7945,7942 ,730,7375,7376 ,0,0,0}, {7959,7946,7945 ,7375,7375,7375 ,0,0,0}, - {7958,7944,7946 ,7375,730,7375 ,0,0,0}, {7955,7948,7944 ,7375,7374,730 ,0,0,0}, - {7963,7947,7948 ,7375,7373,7374 ,0,0,0}, {7956,7949,7947 ,730,730,7373 ,0,0,0}, - {7950,7949,7954 ,7373,730,730 ,0,0,0}, {7956,7954,7949 ,730,730,730 ,0,0,0}, - {7964,5838,7965 ,7377,1435,1435 ,0,0,0}, {7966,5854,7967 ,7378,7379,7379 ,0,0,0}, - {7968,5829,5833 ,7380,7380,7377 ,0,0,0}, {5861,7969,7970 ,7381,7381,7382 ,0,0,0}, - {5856,7971,5859 ,7378,7383,7383 ,0,0,0}, {5868,7972,5870 ,7384,7385,7385 ,0,0,0}, - {7973,5868,5863 ,7384,7384,7382 ,0,0,0}, {5873,5870,7974 ,7386,7385,7386 ,0,0,0}, - {7972,7974,5870 ,7385,7386,7385 ,0,0,0}, {7975,5876,5873 ,7387,7388,7386 ,0,0,0}, - {5873,7974,7975 ,7386,7386,7387 ,0,0,0}, {7970,7973,5863 ,7382,7384,7382 ,0,0,0}, - {7973,7972,5868 ,7384,7385,7384 ,0,0,0}, {5859,7969,5861 ,7383,7381,7381 ,0,0,0}, - {5861,7970,5863 ,7381,7382,7382 ,0,0,0}, {5856,7966,7971 ,7378,7378,7383 ,0,0,0}, - {5859,7971,7969 ,7383,7383,7381 ,0,0,0}, {5854,5829,7967 ,7379,7380,7379 ,0,0,0}, - {5856,5854,7966 ,7378,7379,7378 ,0,0,0}, {7968,5833,7964 ,7380,7377,7377 ,0,0,0}, - {7967,5829,7968 ,7379,7380,7380 ,0,0,0}, {5838,7964,5833 ,1435,7377,7377 ,0,0,0}, - {7965,5835,7976 ,1398,1398,1398 ,0,0,0}, {5835,7965,5838 ,1398,1398,1398 ,0,0,0}, - {7977,7978,5960 ,7389,7390,7390 ,0,0,0}, {7979,5956,7980 ,7391,7391,7392 ,0,0,0}, - {5958,5867,7981 ,7392,7393,7393 ,0,0,0}, {5948,7982,7983 ,7394,7395,7394 ,0,0,0}, - {5953,7984,5952 ,7396,7396,7395 ,0,0,0}, {5943,7985,7986 ,7397,7398,7397 ,0,0,0}, - {7985,5943,5947 ,7398,7397,7398 ,0,0,0}, {7987,5941,7986 ,7399,7399,7397 ,0,0,0}, - {5943,7986,5941 ,7397,7397,7399 ,0,0,0}, {7987,7976,5835 ,7399,1359,1359 ,0,0,0}, - {5835,5941,7987 ,1359,7399,7399 ,0,0,0}, {7980,5958,7981 ,7392,7392,7393 ,0,0,0}, - {5947,5948,7983 ,7398,7394,7394 ,0,0,0}, {7983,7985,5947 ,7394,7398,7398 ,0,0,0}, - {7982,5948,5952 ,7395,7394,7395 ,0,0,0}, {7979,7984,5953 ,7391,7396,7396 ,0,0,0}, - {5952,7984,7982 ,7395,7396,7395 ,0,0,0}, {5958,7980,5956 ,7392,7392,7391 ,0,0,0}, - {5953,5956,7979 ,7396,7391,7391 ,0,0,0}, {5960,7978,5867 ,7390,7390,7393 ,0,0,0}, - {5867,7978,7981 ,7393,7390,7393 ,0,0,0}, {7977,5960,5826 ,7389,7390,7400 ,0,0,0}, - {7975,7977,5826 ,7401,7402,7402 ,0,0,0}, {7975,5826,5876 ,7401,7402,7401 ,0,0,0}, - {7987,7968,7964 ,7403,7403,7404 ,0,0,0}, {7973,7981,7972 ,7375,7375,730 ,0,0,0}, - {7969,7979,7970 ,7375,730,730 ,0,0,0}, {7980,7973,7970 ,730,7375,730 ,0,0,0}, - {7966,7982,7971 ,7373,7375,7373 ,0,0,0}, {7984,7969,7971 ,730,7375,7373 ,0,0,0}, - {7967,7986,7985 ,7405,7406,730 ,0,0,0}, {7983,7966,7967 ,7373,7373,7405 ,0,0,0}, - {7987,7986,7968 ,7403,7406,7403 ,0,0,0}, {7964,7965,7976 ,7404,730,7407 ,0,0,0}, - {7976,7987,7964 ,7407,7403,7404 ,0,0,0}, {7986,7967,7968 ,7406,7405,7403 ,0,0,0}, - {7983,7967,7985 ,7373,7405,730 ,0,0,0}, {7982,7966,7983 ,7375,7373,7373 ,0,0,0}, - {7984,7971,7982 ,730,7373,7375 ,0,0,0}, {7979,7969,7984 ,730,7375,730 ,0,0,0}, - {7980,7970,7979 ,730,730,730 ,0,0,0}, {7981,7973,7980 ,7375,7375,730 ,0,0,0}, - {7978,7972,7981 ,730,730,7375 ,0,0,0}, {7974,7978,7977 ,7373,730,730 ,0,0,0}, - {7978,7974,7972 ,730,7373,730 ,0,0,0}, {7974,7977,7975 ,7373,730,7405 ,0,0,0}, - {7988,7747,7989 ,7408,7409,7410 ,0,0,0}, {7990,7745,7991 ,7411,7412,7412 ,0,0,0}, - {7992,7744,7748 ,7413,7413,7408 ,0,0,0}, {7765,7993,7994 ,7414,7414,7415 ,0,0,0}, - {7746,7995,7766 ,7411,7416,7416 ,0,0,0}, {7742,7996,7743 ,7417,7418,7418 ,0,0,0}, - {7997,7742,7741 ,7417,7417,7415 ,0,0,0}, {7739,7743,7998 ,7419,7418,7419 ,0,0,0}, - {7996,7998,7743 ,7418,7419,7418 ,0,0,0}, {7999,7738,7739 ,1790,1790,7419 ,0,0,0}, - {7739,7998,7999 ,7419,7419,1790 ,0,0,0}, {7994,7997,7741 ,7415,7417,7415 ,0,0,0}, - {7997,7996,7742 ,7417,7418,7417 ,0,0,0}, {7766,7993,7765 ,7416,7414,7414 ,0,0,0}, - {7765,7994,7741 ,7414,7415,7415 ,0,0,0}, {7746,7990,7995 ,7411,7411,7416 ,0,0,0}, - {7766,7995,7993 ,7416,7416,7414 ,0,0,0}, {7745,7744,7991 ,7412,7413,7412 ,0,0,0}, - {7746,7745,7990 ,7411,7412,7411 ,0,0,0}, {7992,7748,7988 ,7413,7408,7408 ,0,0,0}, - {7991,7744,7992 ,7412,7413,7413 ,0,0,0}, {7747,7988,7748 ,7409,7408,7408 ,0,0,0}, - {7768,8000,7989 ,7420,7420,7421 ,0,0,0}, {7768,7989,7747 ,7420,7421,7421 ,0,0,0}, - {8001,8002,7777 ,1711,7422,7422 ,0,0,0}, {8003,7775,8004 ,7423,7423,7424 ,0,0,0}, - {7776,7767,8005 ,7424,7425,7425 ,0,0,0}, {7772,8006,8007 ,7426,7427,7426 ,0,0,0}, - {7774,8008,7773 ,7428,7428,7427 ,0,0,0}, {7770,8009,8010 ,7429,7430,7429 ,0,0,0}, - {8009,7770,7771 ,7430,7429,7430 ,0,0,0}, {8011,7769,8010 ,7431,7431,7429 ,0,0,0}, - {7770,8010,7769 ,7429,7429,7431 ,0,0,0}, {8011,8000,7768 ,7431,7432,82 ,0,0,0}, - {7768,7769,8011 ,82,7431,7431 ,0,0,0}, {8004,7776,8005 ,7424,7424,7425 ,0,0,0}, - {7771,7772,8007 ,7430,7426,7426 ,0,0,0}, {8007,8009,7771 ,7426,7430,7430 ,0,0,0}, - {8006,7772,7773 ,7427,7426,7427 ,0,0,0}, {8003,8008,7774 ,7423,7428,7428 ,0,0,0}, - {7773,8008,8006 ,7427,7428,7427 ,0,0,0}, {7776,8004,7775 ,7424,7424,7423 ,0,0,0}, - {7774,7775,8003 ,7428,7423,7423 ,0,0,0}, {7777,8002,7767 ,7422,7422,7425 ,0,0,0}, - {7767,8002,8005 ,7425,7422,7425 ,0,0,0}, {8001,7777,7740 ,1711,7422,1711 ,0,0,0}, - {7740,7999,8001 ,2197,2197,2197 ,0,0,0}, {7999,7740,7738 ,2197,2197,2197 ,0,0,0}, - {7999,8002,8001 ,7433,730,730 ,0,0,0}, {7990,7991,8007 ,7375,7375,730 ,0,0,0}, - {7994,8004,7997 ,730,730,730 ,0,0,0}, {8004,8005,7996 ,730,7376,730 ,0,0,0}, - {7995,8008,7993 ,730,730,7376 ,0,0,0}, {8003,7994,7993 ,730,730,7376 ,0,0,0}, - {8006,7995,7990 ,7376,730,7375 ,0,0,0}, {8010,7992,7988 ,7375,7376,7376 ,0,0,0}, - {7991,7992,8009 ,7375,7376,7375 ,0,0,0}, {7989,8011,7988 ,7374,7376,7376 ,0,0,0}, - {8010,7988,8011 ,7375,7376,7376 ,0,0,0}, {8000,8011,7989 ,730,7376,7374 ,0,0,0}, - {8009,7992,8010 ,7375,7376,7375 ,0,0,0}, {8007,7991,8009 ,730,7375,7375 ,0,0,0}, - {8006,7990,8007 ,7376,7375,730 ,0,0,0}, {8008,7995,8006 ,730,730,7376 ,0,0,0}, - {8003,7993,8008 ,730,7376,730 ,0,0,0}, {8004,7994,8003 ,730,730,730 ,0,0,0}, - {8004,7996,7997 ,730,730,730 ,0,0,0}, {8005,7998,7996 ,7376,7433,730 ,0,0,0}, - {7999,7998,8002 ,7433,7433,730 ,0,0,0}, {8005,8002,7998 ,7376,730,7433 ,0,0,0}, - {7175,5348,5346 ,7434,4326,7435 ,0,0,0}, {7347,7275,7172 ,7436,7437,7438 ,0,0,0}, - {7176,7274,7177 ,7439,7440,7441 ,0,0,0}, {7182,7170,7318 ,7442,7443,7444 ,0,0,0}, - {7180,7323,7381 ,7445,7446,7447 ,0,0,0}, {7326,7325,7160 ,7448,7449,7450 ,0,0,0}, - {7310,7178,7179 ,7451,7452,7453 ,0,0,0}, {7154,7153,7225 ,7454,7455,7456 ,0,0,0}, - {7156,7214,7216 ,7457,7458,7459 ,0,0,0}, {7144,7261,7148 ,7460,7461,7462 ,0,0,0}, - {7267,7226,7152 ,7463,7464,7465 ,0,0,0}, {7259,7186,7138 ,7466,7467,7468 ,0,0,0}, - {7262,7140,7186 ,7469,7470,7467 ,0,0,0}, {7331,7135,7142 ,7471,7472,7473 ,0,0,0}, - {7139,7135,7260 ,7474,7472,7475 ,0,0,0}, {7254,7143,7147 ,7476,7477,7478 ,0,0,0}, - {7142,7143,7253 ,7473,7477,7479 ,0,0,0}, {7150,7237,7147 ,7480,7481,7478 ,0,0,0}, - {7254,7147,7237 ,7476,7478,7481 ,0,0,0}, {7150,7159,7229 ,7480,7482,7483 ,0,0,0}, - {7229,7237,7150 ,7483,7481,7480 ,0,0,0}, {7203,7159,7158 ,7484,7482,7485 ,0,0,0}, - {7159,7203,7229 ,7482,7484,7483 ,0,0,0}, {7162,7192,7158 ,7486,7487,7485 ,0,0,0}, - {7203,7158,7192 ,7484,7485,7487 ,0,0,0}, {7162,7167,7190 ,7486,7488,7489 ,0,0,0}, - {7190,7192,7162 ,7489,7487,7486 ,0,0,0}, {7240,7167,7166 ,7490,7488,7491 ,0,0,0}, - {7167,7240,7190 ,7488,7490,7489 ,0,0,0}, {5380,7188,7166 ,82,7492,7491 ,0,0,0}, - {7240,7166,7188 ,7490,7491,7492 ,0,0,0}, {5379,7188,5380 ,82,7492,82 ,0,0,0}, - {7253,7331,7142 ,7479,7471,7473 ,0,0,0}, {7253,7143,7254 ,7479,7477,7476 ,0,0,0}, - {7139,7260,7259 ,7474,7475,7466 ,0,0,0}, {7260,7135,7331 ,7475,7472,7471 ,0,0,0}, - {7186,7140,7138 ,7467,7470,7468 ,0,0,0}, {7259,7138,7139 ,7466,7468,7474 ,0,0,0}, - {7262,7261,7144 ,7469,7461,7460 ,0,0,0}, {7262,7144,7140 ,7469,7460,7470 ,0,0,0}, - {7148,7267,7152 ,7462,7463,7465 ,0,0,0}, {7261,7267,7148 ,7461,7463,7462 ,0,0,0}, - {7153,7226,7225 ,7455,7464,7456 ,0,0,0}, {7152,7226,7153 ,7465,7464,7455 ,0,0,0}, - {7156,7154,7214 ,7457,7454,7458 ,0,0,0}, {7154,7225,7214 ,7454,7456,7458 ,0,0,0}, - {7326,7161,7216 ,7448,7493,7459 ,0,0,0}, {7161,7156,7216 ,7493,7457,7459 ,0,0,0}, - {7325,7179,7160 ,7449,7453,7450 ,0,0,0}, {7326,7160,7161 ,7448,7450,7493 ,0,0,0}, - {7310,7319,7178 ,7451,7494,7452 ,0,0,0}, {7325,7310,7179 ,7449,7451,7453 ,0,0,0}, - {7318,7170,7319 ,7444,7443,7494 ,0,0,0}, {7178,7319,7170 ,7452,7494,7443 ,0,0,0}, - {7180,7182,7323 ,7445,7442,7446 ,0,0,0}, {7182,7318,7323 ,7442,7444,7446 ,0,0,0}, - {7347,7171,7381 ,7436,7495,7447 ,0,0,0}, {7171,7180,7381 ,7495,7445,7447 ,0,0,0}, - {7275,7176,7172 ,7437,7439,7438 ,0,0,0}, {7347,7172,7171 ,7436,7438,7495 ,0,0,0}, - {7274,7276,7177 ,7440,7496,7441 ,0,0,0}, {7275,7274,7176 ,7437,7440,7439 ,0,0,0}, - {5348,7175,7276 ,4326,7434,7496 ,0,0,0}, {7177,7276,7175 ,7441,7496,7434 ,0,0,0}, - {8012,5296,5295 ,7497,763,7498 ,0,0,0}, {8013,7168,8014 ,7499,7500,7501 ,0,0,0}, - {8015,7181,7173 ,7502,7503,7504 ,0,0,0}, {8016,8017,7157 ,7505,7506,7507 ,0,0,0}, - {8018,8019,7165 ,7508,7509,7510 ,0,0,0}, {8020,7145,8021 ,7511,7512,7513 ,0,0,0}, - {7149,8022,8021 ,7514,7515,7513 ,0,0,0}, {8023,7137,8024 ,7516,7517,7518 ,0,0,0}, - {7136,8020,8024 ,7519,7511,7518 ,0,0,0}, {8025,7151,7146 ,7520,7521,7522 ,0,0,0}, - {7146,8023,8025 ,7522,7516,7520 ,0,0,0}, {7151,8026,7163 ,7521,7523,7524 ,0,0,0}, - {8026,7151,8025 ,7523,7521,7520 ,0,0,0}, {7164,7163,8027 ,7525,7524,7526 ,0,0,0}, - {8026,8027,7163 ,7523,7526,7524 ,0,0,0}, {5314,7164,8028 ,761,7525,7527 ,0,0,0}, - {7164,8027,8028 ,7525,7526,7527 ,0,0,0}, {5313,7164,5314 ,761,7525,761 ,0,0,0}, - {7136,8024,7137 ,7519,7518,7517 ,0,0,0}, {7146,7137,8023 ,7522,7517,7516 ,0,0,0}, - {7141,7145,8020 ,7528,7512,7511 ,0,0,0}, {7136,7141,8020 ,7519,7528,7511 ,0,0,0}, - {7155,8022,7149 ,7529,7515,7514 ,0,0,0}, {7145,7149,8021 ,7512,7514,7513 ,0,0,0}, - {7157,8017,7155 ,7507,7506,7529 ,0,0,0}, {8022,7155,8017 ,7515,7529,7506 ,0,0,0}, - {7165,8019,7157 ,7510,7509,7507 ,0,0,0}, {8019,8016,7157 ,7509,7505,7507 ,0,0,0}, - {7169,8013,8018 ,7530,7499,7508 ,0,0,0}, {7169,8018,7165 ,7530,7508,7510 ,0,0,0}, - {7168,7181,8014 ,7500,7503,7501 ,0,0,0}, {7169,7168,8013 ,7530,7500,7499 ,0,0,0}, - {8015,7173,8012 ,7502,7504,7497 ,0,0,0}, {8014,7181,8015 ,7501,7503,7502 ,0,0,0}, - {5296,8012,7174 ,763,7497,7531 ,0,0,0}, {8012,7173,7174 ,7497,7504,7531 ,0,0,0}, - {8027,8026,8025 ,7015,7532,7017 ,0,0,0}, {5300,8014,8015 ,7016,7015,7015 ,0,0,0}, - {8020,8023,8024 ,7533,7534,7535 ,0,0,0}, {8025,8020,8027 ,7017,7533,7015 ,0,0,0}, - {8027,8020,8028 ,7015,7533,7016 ,0,0,0}, {8020,8025,8023 ,7533,7017,7534 ,0,0,0}, - {8021,8028,8020 ,7536,7016,7533 ,0,0,0}, {8028,8022,5314 ,7016,730,7015 ,0,0,0}, - {8022,8028,8021 ,730,7016,7536 ,0,0,0}, {8019,5309,8016 ,7535,730,7320 ,0,0,0}, - {8022,8017,5314 ,730,6104,7015 ,0,0,0}, {8013,5303,8018 ,730,730,7534 ,0,0,0}, - {5306,8019,8018 ,7537,7535,7534 ,0,0,0}, {8012,5295,5299 ,7016,7015,730 ,0,0,0}, - {8015,5301,5300 ,7015,730,7016 ,0,0,0}, {5292,5280,5294 ,730,730,730 ,0,0,0}, - {5294,5278,5295 ,730,7016,7015 ,0,0,0}, {5291,5288,5292 ,730,730,730 ,0,0,0}, - {5280,5286,5285 ,730,7016,7016 ,0,0,0}, {5288,5280,5292 ,730,730,730 ,0,0,0}, - {5280,5279,5294 ,730,730,730 ,0,0,0}, {5280,5288,5286 ,730,730,7016 ,0,0,0}, - {5278,5299,5295 ,7016,730,7015 ,0,0,0}, {5279,5278,5294 ,730,7016,730 ,0,0,0}, - {5301,8015,5299 ,730,7015,730 ,0,0,0}, {5299,8015,8012 ,730,7015,7016 ,0,0,0}, - {5300,5303,8014 ,7016,730,7015 ,0,0,0}, {8018,5303,5305 ,7534,730,7537 ,0,0,0}, - {8014,5303,8013 ,7015,730,730 ,0,0,0}, {8018,5305,5306 ,7534,7537,7537 ,0,0,0}, - {5309,8017,8016 ,730,6104,7320 ,0,0,0}, {8019,5306,5309 ,7535,7537,730 ,0,0,0}, - {5314,8017,5311 ,7015,6104,730 ,0,0,0}, {5309,5311,8017 ,730,730,6104 ,0,0,0}, - {6223,6222,8029 ,7538,7539,7540 ,0,0,0}, {8030,6214,6223 ,7541,7542,7538 ,0,0,0}, - {8030,8031,6214 ,7541,82,7542 ,0,0,0}, {8029,8030,6223 ,7540,7541,7538 ,0,0,0}, - {6222,6593,8032 ,7539,7543,7544 ,0,0,0}, {6252,6251,8033 ,7545,7546,7547 ,0,0,0}, - {8034,8032,6593 ,7548,7544,7543 ,0,0,0}, {6593,6252,8034 ,7543,7545,7548 ,0,0,0}, - {8033,8034,6252 ,7547,7548,7545 ,0,0,0}, {6222,8032,8029 ,7539,7544,7540 ,0,0,0}, - {8033,6251,8035 ,7547,7546,7549 ,0,0,0}, {6250,8036,8035 ,7550,7551,7549 ,0,0,0}, - {8035,6251,6250 ,7549,7546,7550 ,0,0,0}, {8036,6250,6225 ,7551,7550,7552 ,0,0,0}, - {6238,8037,6225 ,7553,7554,7552 ,0,0,0}, {6238,6228,8038 ,7553,7555,7556 ,0,0,0}, - {6238,8038,8037 ,7553,7556,7554 ,0,0,0}, {8039,6219,8040 ,7557,7558,7559 ,0,0,0}, - {8038,6228,8039 ,7556,7555,7557 ,0,0,0}, {8039,6228,6219 ,7557,7555,7558 ,0,0,0}, - {6219,6221,8040 ,7558,7559,7559 ,0,0,0}, {8036,6225,8037 ,7551,7552,7554 ,0,0,0}, - {6215,8031,8041 ,7560,82,7561 ,0,0,0}, {8031,6215,6214 ,82,7560,7542 ,0,0,0}, - {8042,6257,8041 ,7562,7563,7561 ,0,0,0}, {6215,8041,6257 ,7560,7561,7563 ,0,0,0}, - {8042,8043,6471 ,7562,7564,7565 ,0,0,0}, {6471,6257,8042 ,7565,7563,7562 ,0,0,0}, - {6296,8043,8044 ,7566,7564,7567 ,0,0,0}, {8043,6296,6471 ,7564,7566,7565 ,0,0,0}, - {8045,6297,8044 ,7568,7569,7567 ,0,0,0}, {6296,8044,6297 ,7566,7567,7569 ,0,0,0}, - {8045,8046,6293 ,7568,7570,7571 ,0,0,0}, {6293,6297,8045 ,7571,7569,7568 ,0,0,0}, - {6261,8046,8047 ,7572,7570,7573 ,0,0,0}, {8046,6261,6293 ,7570,7572,7571 ,0,0,0}, - {8048,6280,8047 ,7574,7575,7573 ,0,0,0}, {6261,8047,6280 ,7572,7573,7575 ,0,0,0}, - {8048,8049,6281 ,7574,7576,7577 ,0,0,0}, {6281,6280,8048 ,7577,7575,7574 ,0,0,0}, - {6283,8049,8050 ,7578,7576,7579 ,0,0,0}, {8049,6283,6281 ,7576,7578,7577 ,0,0,0}, - {6283,8050,6284 ,7578,7579,7580 ,0,0,0}, {6284,8050,8051 ,7580,7579,7580 ,0,0,0}, - {7109,7115,8051 ,7581,7581,7581 ,0,0,0}, {8051,5721,7100 ,7581,7581,7581 ,0,0,0}, - {7100,7106,8051 ,7581,7581,7581 ,0,0,0}, {7120,8051,7115 ,7581,7581,7581 ,0,0,0}, - {7106,7109,8051 ,7581,7581,7581 ,0,0,0}, {7124,7083,8051 ,7581,7581,7581 ,0,0,0}, - {7124,8051,7120 ,7581,7581,7581 ,0,0,0}, {7083,7095,8051 ,7581,7581,7581 ,0,0,0}, - {6284,8051,7094 ,7581,7581,7581 ,0,0,0}, {7095,7094,8051 ,7581,7581,7581 ,0,0,0}, - {8040,6221,6667 ,7582,7582,7582 ,0,0,0}, {6667,6694,8040 ,7582,7582,7582 ,0,0,0}, - {8040,6680,6660 ,7582,7582,7582 ,0,0,0}, {6694,6680,8040 ,7582,7582,7582 ,0,0,0}, - {8040,6662,6676 ,7582,7582,7582 ,0,0,0}, {6660,6662,8040 ,7582,7582,7582 ,0,0,0}, - {8040,6669,6653 ,7582,7582,7582 ,0,0,0}, {6676,6669,8040 ,7582,7582,7582 ,0,0,0}, - {6657,8040,6652 ,7582,7582,7582 ,0,0,0}, {6653,6652,8040 ,7582,7582,7582 ,0,0,0}, - {8048,5726,5724 ,726,726,726 ,0,0,0}, {8041,8031,5726 ,726,726,726 ,0,0,0}, - {8050,8049,5724 ,726,726,726 ,0,0,0}, {5724,8049,8048 ,726,726,726 ,0,0,0}, - {5724,5718,8051 ,726,726,726 ,0,0,0}, {8051,8050,5724 ,726,726,726 ,0,0,0}, - {5727,5721,8051 ,7583,7583,726 ,0,0,0}, {5727,8051,5718 ,7583,726,726 ,0,0,0}, - {8048,8047,5726 ,726,726,726 ,0,0,0}, {5726,8046,8045 ,726,726,726 ,0,0,0}, - {8047,8046,5726 ,726,726,726 ,0,0,0}, {5726,8044,8043 ,726,726,726 ,0,0,0}, - {8045,8044,5726 ,726,726,726 ,0,0,0}, {5726,8042,8041 ,726,726,726 ,0,0,0}, - {8043,8042,5726 ,726,726,726 ,0,0,0}, {8030,5726,8031 ,726,726,726 ,0,0,0}, - {8029,8032,5726 ,726,726,726 ,0,0,0}, {8029,5726,8030 ,726,726,726 ,0,0,0}, - {8034,8033,5726 ,726,726,726 ,0,0,0}, {8034,5726,8032 ,726,726,726 ,0,0,0}, - {8035,8036,5726 ,726,726,726 ,0,0,0}, {8035,5726,8033 ,726,726,726 ,0,0,0}, - {8037,8038,5726 ,726,726,726 ,0,0,0}, {8037,5726,8036 ,726,726,726 ,0,0,0}, - {5726,8038,7778 ,726,726,726 ,0,0,0}, {8040,7778,8039 ,726,726,726 ,0,0,0}, - {7778,8038,8039 ,726,726,726 ,0,0,0}, {7779,7778,8040 ,726,726,726 ,0,0,0}, - {6657,7791,8040 ,7583,726,726 ,0,0,0}, {7779,8040,7791 ,726,726,726 ,0,0,0}, - {5256,8052,6510 ,7584,7585,7586 ,0,0,0}, {8053,6483,8054 ,7587,7588,7589 ,0,0,0}, - {6521,6443,8055 ,7590,7591,7592 ,0,0,0}, {6210,8056,6472 ,7593,7594,7595 ,0,0,0}, - {8057,8058,6213 ,4334,7596,7597 ,0,0,0}, {8059,6218,8060 ,7598,7599,7600 ,0,0,0}, - {6217,6475,8061 ,7601,7602,7603 ,0,0,0}, {6275,6267,8062 ,7604,7605,7606 ,0,0,0}, - {6271,8063,6267 ,7607,7608,7605 ,0,0,0}, {6272,8064,8065 ,7609,7610,7611 ,0,0,0}, - {6275,8066,6274 ,7604,7612,7613 ,0,0,0}, {8067,6285,8065 ,7614,7615,7611 ,0,0,0}, - {6272,8065,6285 ,7609,7611,7615 ,0,0,0}, {8067,8068,6278 ,7614,7616,7617 ,0,0,0}, - {6278,6285,8067 ,7617,7615,7614 ,0,0,0}, {6287,8068,8069 ,7618,7616,7619 ,0,0,0}, - {8068,6287,6278 ,7616,7618,7617 ,0,0,0}, {8070,6247,8069 ,7620,7621,7619 ,0,0,0}, - {6287,8069,6247 ,7618,7619,7621 ,0,0,0}, {8070,5275,5276 ,7620,7622,4289 ,0,0,0}, - {5276,6247,8070 ,4289,7621,7620 ,0,0,0}, {8062,6267,8063 ,7606,7605,7608 ,0,0,0}, - {8064,6274,8066 ,7610,7613,7612 ,0,0,0}, {6274,8064,6272 ,7613,7610,7609 ,0,0,0}, - {8062,8066,6275 ,7606,7612,7604 ,0,0,0}, {8059,8063,6271 ,7598,7608,7607 ,0,0,0}, - {6217,8061,8060 ,7601,7603,7600 ,0,0,0}, {6217,8060,6218 ,7601,7600,7599 ,0,0,0}, - {6271,6218,8059 ,7607,7599,7598 ,0,0,0}, {6475,8071,8061 ,7602,7623,7603 ,0,0,0}, - {8071,6475,6472 ,7623,7602,7595 ,0,0,0}, {8058,8056,6210 ,7596,7594,7593 ,0,0,0}, - {8056,8071,6472 ,7594,7623,7595 ,0,0,0}, {6213,8058,6210 ,7597,7596,7593 ,0,0,0}, - {6511,8053,8057 ,7624,7587,4334 ,0,0,0}, {6511,8057,6213 ,7624,4334,7597 ,0,0,0}, - {6483,6521,8054 ,7588,7590,7589 ,0,0,0}, {6511,6483,8053 ,7624,7588,7587 ,0,0,0}, - {6443,8052,8055 ,7591,7585,7592 ,0,0,0}, {8054,6521,8055 ,7589,7590,7592 ,0,0,0}, - {5256,6510,5254 ,7584,7586,4535 ,0,0,0}, {8052,6443,6510 ,7585,7591,7586 ,0,0,0}, - {8058,5267,8056 ,726,7625,726 ,0,0,0}, {8067,8065,8068 ,726,726,726 ,0,0,0}, - {8070,8069,8068 ,726,726,726 ,0,0,0}, {8066,8062,8064 ,726,726,726 ,0,0,0}, - {8068,8065,8062 ,726,726,726 ,0,0,0}, {8068,8062,8063 ,726,726,726 ,0,0,0}, - {8064,8062,8065 ,726,726,726 ,0,0,0}, {8063,8059,8070 ,726,726,726 ,0,0,0}, - {8070,8068,8063 ,726,726,726 ,0,0,0}, {8059,8060,5273 ,726,726,7626 ,0,0,0}, - {8059,5275,8070 ,726,726,726 ,0,0,0}, {8071,5269,5270 ,726,726,726 ,0,0,0}, - {5270,5273,8061 ,726,7626,726 ,0,0,0}, {8054,5258,5261 ,726,7627,726 ,0,0,0}, - {5263,5264,8057 ,726,7625,726 ,0,0,0}, {8055,5257,5258 ,7626,7627,7627 ,0,0,0}, - {5253,5238,5237 ,7626,7625,726 ,0,0,0}, {5256,5237,8052 ,726,726,726 ,0,0,0}, - {5249,5240,5250 ,726,7627,7625 ,0,0,0}, {5240,5249,5247 ,7627,726,726 ,0,0,0}, - {5249,5250,5244 ,726,7625,7627 ,0,0,0}, {5250,5253,5252 ,7625,7626,7628 ,0,0,0}, - {5240,5238,5250 ,7627,7625,7625 ,0,0,0}, {5240,5247,5241 ,7627,726,726 ,0,0,0}, - {5256,5253,5237 ,726,7626,726 ,0,0,0}, {5253,5250,5238 ,7626,7625,7625 ,0,0,0}, - {5235,8052,5237 ,726,726,726 ,0,0,0}, {8055,8052,5257 ,7626,726,7627 ,0,0,0}, - {5235,5257,8052 ,726,7627,726 ,0,0,0}, {8054,5261,8053 ,726,726,726 ,0,0,0}, - {5258,8054,8055 ,7627,726,7626 ,0,0,0}, {5263,8057,8053 ,726,726,726 ,0,0,0}, - {8053,5261,5263 ,726,726,726 ,0,0,0}, {5264,5267,8058 ,7625,7625,726 ,0,0,0}, - {8057,5264,8058 ,726,7625,726 ,0,0,0}, {8056,5269,8071 ,726,726,726 ,0,0,0}, - {8056,5267,5269 ,726,7625,726 ,0,0,0}, {5273,8060,8061 ,7626,726,726 ,0,0,0}, - {8061,8071,5270 ,726,726,726 ,0,0,0}, {5273,5275,8059 ,7626,726,726 ,0,0,0}, - {5217,8072,6491 ,4303,7629,7630 ,0,0,0}, {6414,6448,8073 ,7631,7632,7633 ,0,0,0}, - {6580,6492,8074 ,7634,7635,7636 ,0,0,0}, {6476,8075,6477 ,7637,7638,7639 ,0,0,0}, - {8076,8077,6413 ,7640,7641,7642 ,0,0,0}, {8078,8079,6258 ,7643,7644,7645 ,0,0,0}, - {8078,6478,8080 ,7643,7646,7647 ,0,0,0}, {8081,8082,6256 ,7648,7649,7650 ,0,0,0}, - {6256,6255,8081 ,7650,7651,7648 ,0,0,0}, {6439,8082,8083 ,7652,7649,7653 ,0,0,0}, - {8082,6439,6256 ,7649,7652,7650 ,0,0,0}, {8084,6438,8083 ,7654,7655,7653 ,0,0,0}, - {6439,8083,6438 ,7652,7653,7655 ,0,0,0}, {8084,5231,5232 ,7654,126,7656 ,0,0,0}, - {5232,6438,8084 ,7656,7655,7654 ,0,0,0}, {8075,6476,8077 ,7638,7637,7641 ,0,0,0}, - {8079,6255,6258 ,7644,7651,7645 ,0,0,0}, {8081,6255,8079 ,7648,7651,7644 ,0,0,0}, - {8073,6448,8085 ,7633,7632,7657 ,0,0,0}, {8080,6478,6477 ,7647,7646,7639 ,0,0,0}, - {8078,6258,6478 ,7643,7645,7646 ,0,0,0}, {8075,8080,6477 ,7638,7647,7639 ,0,0,0}, - {6413,8077,6476 ,7642,7641,7637 ,0,0,0}, {6414,8073,8076 ,7631,7633,7640 ,0,0,0}, - {8076,6413,6414 ,7640,7642,7631 ,0,0,0}, {6492,8072,8074 ,7635,7629,7636 ,0,0,0}, - {8085,6580,8074 ,7657,7634,7636 ,0,0,0}, {6448,6580,8085 ,7632,7634,7657 ,0,0,0}, - {5217,6491,5218 ,4303,7630,82 ,0,0,0}, {8072,6492,6491 ,7629,7635,7630 ,0,0,0}, - {8079,8078,5214 ,726,7658,7659 ,0,0,0}, {8072,8077,8073 ,7660,7661,726 ,0,0,0}, - {8072,8075,8077 ,7660,7661,7661 ,0,0,0}, {5216,8080,5217 ,7659,726,726 ,0,0,0}, - {8076,8073,8077 ,7661,726,7661 ,0,0,0}, {8074,8072,8073 ,7659,7660,726 ,0,0,0}, - {8075,8072,5217 ,7661,7660,726 ,0,0,0}, {8085,8074,8073 ,726,7659,726 ,0,0,0}, - {8075,5217,8080 ,7661,726,726 ,0,0,0}, {5214,8078,5216 ,7659,7658,7659 ,0,0,0}, - {5216,8078,8080 ,7659,7658,726 ,0,0,0}, {5212,8081,8079 ,726,5488,726 ,0,0,0}, - {5214,5212,8079 ,7659,726,726 ,0,0,0}, {5210,8081,5212 ,726,5488,726 ,0,0,0}, - {5210,8082,8081 ,726,7662,5488 ,0,0,0}, {8083,8082,5207 ,5471,7662,7661 ,0,0,0}, - {5210,5207,8082 ,726,7661,7662 ,0,0,0}, {5206,8083,5207 ,726,5471,7661 ,0,0,0}, - {8084,5206,5204 ,7663,726,7661 ,0,0,0}, {5206,8084,8083 ,726,7663,5471 ,0,0,0}, - {5203,5231,5204 ,7658,726,7661 ,0,0,0}, {8084,5204,5231 ,7663,7661,726 ,0,0,0}, - {5223,5219,5220 ,7658,7664,726 ,0,0,0}, {5223,5229,5219 ,7658,7665,7664 ,0,0,0}, - {5226,5223,5225 ,7666,7658,7667 ,0,0,0}, {5226,5229,5223 ,7666,7665,7658 ,0,0,0}, - {5231,5203,5229 ,726,7658,7665 ,0,0,0}, {5219,5229,5203 ,7664,7665,7658 ,0,0,0}, - {8086,5757,8087 ,726,726,726 ,0,0,0}, {5757,8088,8087 ,726,726,726 ,0,0,0}, - {8089,8090,5757 ,726,726,726 ,0,0,0}, {5757,8086,8089 ,726,726,726 ,0,0,0}, - {8091,8092,5757 ,726,726,726 ,0,0,0}, {8091,5757,8090 ,726,726,726 ,0,0,0}, - {5749,8093,8094 ,7583,726,7661 ,0,0,0}, {5757,8095,8096 ,726,726,726 ,0,0,0}, - {5749,8097,8098 ,7583,7658,7661 ,0,0,0}, {8099,5749,8100 ,726,7583,726 ,0,0,0}, - {8101,8102,5749 ,726,726,7583 ,0,0,0}, {8103,8100,5749 ,726,726,7583 ,0,0,0}, - {5749,8099,8104 ,7583,726,5489 ,0,0,0}, {8101,5749,8105 ,726,7583,7583 ,0,0,0}, - {5749,8102,8103 ,7583,726,726 ,0,0,0}, {5749,8106,8097 ,7583,726,7658 ,0,0,0}, - {8098,8105,5749 ,7661,7583,7583 ,0,0,0}, {8096,8093,5749 ,726,726,7583 ,0,0,0}, - {8106,5749,8094 ,726,7583,7661 ,0,0,0}, {5757,8092,8095 ,726,726,726 ,0,0,0}, - {5757,8096,5749 ,726,726,7583 ,0,0,0}, {5750,8104,5745 ,726,5489,7668 ,0,0,0}, - {8104,5750,5749 ,5489,726,7583 ,0,0,0}, {8088,5757,8107 ,726,726,726 ,0,0,0}, - {8108,5757,5755 ,726,726,726 ,0,0,0}, {5757,8108,8107 ,726,726,726 ,0,0,0}, - {8108,5755,5761 ,726,726,726 ,0,0,0}, {6211,6474,8106 ,7669,7670,7671 ,0,0,0}, - {8094,6212,6211 ,7672,7673,7669 ,0,0,0}, {8094,8093,6212 ,7672,7673,7673 ,0,0,0}, - {8106,8094,6211 ,7671,7672,7669 ,0,0,0}, {6474,6473,8097 ,7670,7674,7675 ,0,0,0}, - {6216,6270,8105 ,7676,7677,7678 ,0,0,0}, {8098,8097,6473 ,7679,7675,7674 ,0,0,0}, - {6473,6216,8098 ,7674,7676,7679 ,0,0,0}, {8105,8098,6216 ,7678,7679,7676 ,0,0,0}, - {6474,8097,8106 ,7670,7675,7671 ,0,0,0}, {8105,6270,8101 ,7678,7677,7680 ,0,0,0}, - {6269,8102,8101 ,7681,7682,7680 ,0,0,0}, {8101,6270,6269 ,7680,7677,7681 ,0,0,0}, - {8102,6269,6268 ,7682,7681,7683 ,0,0,0}, {6262,8103,6268 ,7684,7685,7683 ,0,0,0}, - {6262,6264,8100 ,7684,7686,7687 ,0,0,0}, {6262,8100,8103 ,7684,7687,7685 ,0,0,0}, - {8099,6265,8104 ,7688,7689,7690 ,0,0,0}, {8100,6264,8099 ,7687,7686,7688 ,0,0,0}, - {8099,6264,6265 ,7688,7686,7689 ,0,0,0}, {6265,6266,8104 ,7689,7690,7690 ,0,0,0}, - {8102,6268,8103 ,7682,7683,7685 ,0,0,0}, {6259,8093,8096 ,7691,7673,7692 ,0,0,0}, - {8093,6259,6212 ,7673,7691,7673 ,0,0,0}, {8095,6260,8096 ,7693,7694,7692 ,0,0,0}, - {6259,8096,6260 ,7691,7692,7694 ,0,0,0}, {8095,8092,6291 ,7693,7695,7696 ,0,0,0}, - {6291,6260,8095 ,7696,7694,7693 ,0,0,0}, {6292,8092,8091 ,7697,7695,7698 ,0,0,0}, - {8092,6292,6291 ,7695,7697,7696 ,0,0,0}, {8090,6514,8091 ,7699,7700,7698 ,0,0,0}, - {6292,8091,6514 ,7697,7698,7700 ,0,0,0}, {8090,8089,6295 ,7699,7701,7702 ,0,0,0}, - {6295,6514,8090 ,7702,7700,7699 ,0,0,0}, {6294,8089,8086 ,7703,7701,7704 ,0,0,0}, - {8089,6294,6295 ,7701,7703,7702 ,0,0,0}, {8087,6317,8086 ,7705,7706,7704 ,0,0,0}, - {6294,8086,6317 ,7703,7704,7706 ,0,0,0}, {8087,8088,6320 ,7705,7707,7708 ,0,0,0}, - {6320,6317,8087 ,7708,7706,7705 ,0,0,0}, {6321,8088,8107 ,7709,7707,7710 ,0,0,0}, - {8088,6321,6320 ,7707,7709,7708 ,0,0,0}, {6321,8107,6322 ,7709,7710,7711 ,0,0,0}, - {6322,8107,8108 ,7711,7710,7711 ,0,0,0}, {7023,8108,5761 ,7712,7712,7712 ,0,0,0}, - {8108,7024,7027 ,7712,7712,7712 ,0,0,0}, {7023,7024,8108 ,7712,7712,7712 ,0,0,0}, - {8108,7033,7038 ,7712,7712,7712 ,0,0,0}, {7027,7033,8108 ,7712,7712,7712 ,0,0,0}, - {8108,7042,7006 ,7712,7712,7712 ,0,0,0}, {7038,7042,8108 ,7712,7712,7712 ,0,0,0}, - {8108,7010,7009 ,7712,7712,7712 ,0,0,0}, {7006,7010,8108 ,7712,7712,7712 ,0,0,0}, - {8108,7009,6322 ,7712,7712,7712 ,0,0,0}, {7075,8104,6266 ,7713,7713,7713 ,0,0,0}, - {7075,7125,8104 ,7713,7713,7713 ,0,0,0}, {8104,7125,7111 ,7713,7713,7713 ,0,0,0}, - {7071,7077,8104 ,7713,7713,7713 ,0,0,0}, {7071,8104,7111 ,7713,7713,7713 ,0,0,0}, - {7077,7107,8104 ,7713,7713,7713 ,0,0,0}, {8104,7063,7062 ,7713,7713,7713 ,0,0,0}, - {7107,7063,8104 ,7713,7713,7713 ,0,0,0}, {5745,8104,7067 ,7713,7713,7713 ,0,0,0}, - {7062,7067,8104 ,7713,7713,7713 ,0,0,0}, {5180,8109,6529 ,1435,7714,7715 ,0,0,0}, - {8110,6520,8111 ,7716,7717,7718 ,0,0,0}, {6539,6528,8112 ,7719,7720,7721 ,0,0,0}, - {6200,8113,6301 ,7722,7723,7724 ,0,0,0}, {8114,8115,6542 ,7725,7726,7727 ,0,0,0}, - {8116,6323,8117 ,7728,7729,7730 ,0,0,0}, {6325,6302,8118 ,7731,7732,7733 ,0,0,0}, - {6207,6306,8119 ,7734,7735,7736 ,0,0,0}, {6311,8120,6306 ,7737,7738,7735 ,0,0,0}, - {6307,8121,8122 ,7739,7740,7741 ,0,0,0}, {6207,8123,6309 ,7734,7742,7743 ,0,0,0}, - {8124,6316,8122 ,7744,7745,7741 ,0,0,0}, {6307,8122,6316 ,7739,7741,7745 ,0,0,0}, - {8124,8125,6314 ,7744,7746,7747 ,0,0,0}, {6314,6316,8124 ,7747,7745,7744 ,0,0,0}, - {6327,8125,8126 ,7748,7746,7749 ,0,0,0}, {8125,6327,6314 ,7746,7748,7747 ,0,0,0}, - {8127,6313,8126 ,7750,7751,7749 ,0,0,0}, {6327,8126,6313 ,7748,7749,7751 ,0,0,0}, - {8127,5199,5200 ,7750,1359,1359 ,0,0,0}, {5200,6313,8127 ,1359,7751,7750 ,0,0,0}, - {8119,6306,8120 ,7736,7735,7738 ,0,0,0}, {8121,6309,8123 ,7740,7743,7742 ,0,0,0}, - {6309,8121,6307 ,7743,7740,7739 ,0,0,0}, {8119,8123,6207 ,7736,7742,7734 ,0,0,0}, - {8116,8120,6311 ,7728,7738,7737 ,0,0,0}, {6325,8118,8117 ,7731,7733,7730 ,0,0,0}, - {6325,8117,6323 ,7731,7730,7729 ,0,0,0}, {6311,6323,8116 ,7737,7729,7728 ,0,0,0}, - {6302,8128,8118 ,7732,7752,7733 ,0,0,0}, {8128,6302,6301 ,7752,7732,7724 ,0,0,0}, - {8115,8113,6200 ,7726,7723,7722 ,0,0,0}, {8113,8128,6301 ,7723,7752,7724 ,0,0,0}, - {6542,8115,6200 ,7727,7726,7722 ,0,0,0}, {6530,8110,8114 ,7753,7716,7725 ,0,0,0}, - {6530,8114,6542 ,7753,7725,7727 ,0,0,0}, {6520,6539,8111 ,7717,7719,7718 ,0,0,0}, - {6530,6520,8110 ,7753,7717,7716 ,0,0,0}, {6528,8109,8112 ,7720,7714,7721 ,0,0,0}, - {8111,6539,8112 ,7718,7719,7721 ,0,0,0}, {5180,6529,5178 ,1435,7715,1435 ,0,0,0}, - {8109,6528,6529 ,7714,7720,7715 ,0,0,0}, {8127,8126,8125 ,726,7628,7628 ,0,0,0}, - {5182,8122,5181 ,7627,7628,726 ,0,0,0}, {5161,5159,8123 ,7754,7625,7626 ,0,0,0}, - {8122,8121,5181 ,7628,726,726 ,0,0,0}, {5164,8116,5165 ,7755,726,7756 ,0,0,0}, - {5161,8123,8119 ,7754,7626,7626 ,0,0,0}, {8118,8128,5173 ,726,7628,7757 ,0,0,0}, - {8118,5171,8117 ,726,7758,7626 ,0,0,0}, {5174,5168,8113 ,7759,7760,7628 ,0,0,0}, - {8110,8111,8112 ,7625,7754,726 ,0,0,0}, {5177,5174,8115 ,7628,7759,7627 ,0,0,0}, - {5180,5177,8109 ,7628,7628,7761 ,0,0,0}, {8109,8110,8112 ,7761,7625,726 ,0,0,0}, - {5177,8114,8110 ,7628,7628,7625 ,0,0,0}, {8109,5177,8110 ,7761,7628,7625 ,0,0,0}, - {5177,5176,5174 ,7628,7762,7759 ,0,0,0}, {5177,8115,8114 ,7628,7627,7628 ,0,0,0}, - {5173,8113,5168 ,7757,7628,7760 ,0,0,0}, {8113,8115,5174 ,7628,7627,7759 ,0,0,0}, - {5173,8128,8113 ,7757,7628,7628 ,0,0,0}, {8117,5171,5165 ,7626,7758,7756 ,0,0,0}, - {5173,5171,8118 ,7757,7758,726 ,0,0,0}, {8120,8116,5164 ,7628,726,7755 ,0,0,0}, - {8116,8117,5165 ,726,7626,7756 ,0,0,0}, {8120,5162,8119 ,7628,7628,7626 ,0,0,0}, - {5162,8120,5164 ,7628,7628,7755 ,0,0,0}, {8121,8123,5159 ,726,7626,7625 ,0,0,0}, - {5162,5161,8119 ,7628,7754,7626 ,0,0,0}, {5185,8122,5182 ,7625,7628,7627 ,0,0,0}, - {5159,5181,8121 ,7625,726,726 ,0,0,0}, {8125,8124,5185 ,7628,7628,7625 ,0,0,0}, - {5185,8124,8122 ,7625,7628,7628 ,0,0,0}, {5187,8127,8125 ,7628,726,7628 ,0,0,0}, - {8125,5185,5187 ,7628,7625,7628 ,0,0,0}, {5187,5188,8127 ,7628,7628,726 ,0,0,0}, - {5191,5194,5197 ,7628,7628,7628 ,0,0,0}, {5188,5191,8127 ,7628,7628,726 ,0,0,0}, - {5197,8127,5191 ,7628,726,7628 ,0,0,0}, {5191,5193,5194 ,7628,726,7628 ,0,0,0}, - {8127,5197,5199 ,726,7628,7628 ,0,0,0}, {5141,8129,6490 ,1435,7763,7764 ,0,0,0}, - {6517,6519,8130 ,7765,7766,7767 ,0,0,0}, {6523,6524,8131 ,7768,7769,7770 ,0,0,0}, - {6489,8132,6488 ,7771,7772,7773 ,0,0,0}, {8133,8134,6518 ,7774,4221,7775 ,0,0,0}, - {8135,8136,6516 ,7776,7777,7778 ,0,0,0}, {8135,6515,8137 ,7776,7779,7780 ,0,0,0}, - {8138,8139,6332 ,7781,7782,7783 ,0,0,0}, {6332,6331,8138 ,7783,7784,7781 ,0,0,0}, - {6206,8139,8140 ,7785,7782,7786 ,0,0,0}, {8139,6206,6332 ,7782,7785,7783 ,0,0,0}, - {8141,6205,8140 ,7787,7788,7786 ,0,0,0}, {6206,8140,6205 ,7785,7786,7788 ,0,0,0}, - {8141,5155,5156 ,7787,1359,1359 ,0,0,0}, {5156,6205,8141 ,1359,7788,7787 ,0,0,0}, - {8132,6489,8134 ,7772,7771,4221 ,0,0,0}, {8136,6331,6516 ,7777,7784,7778 ,0,0,0}, - {8138,6331,8136 ,7781,7784,7777 ,0,0,0}, {8130,6519,8142 ,7767,7766,4227 ,0,0,0}, - {8137,6515,6488 ,7780,7779,7773 ,0,0,0}, {8135,6516,6515 ,7776,7778,7779 ,0,0,0}, - {8132,8137,6488 ,7772,7780,7773 ,0,0,0}, {6518,8134,6489 ,7775,4221,7771 ,0,0,0}, - {6517,8130,8133 ,7765,7767,7774 ,0,0,0}, {8133,6518,6517 ,7774,7775,7765 ,0,0,0}, - {6524,8129,8131 ,7769,7763,7770 ,0,0,0}, {8142,6523,8131 ,4227,7768,7770 ,0,0,0}, - {6519,6523,8142 ,7766,7768,4227 ,0,0,0}, {5141,6490,5142 ,1435,7764,1435 ,0,0,0}, - {8129,6524,6490 ,7763,7769,7764 ,0,0,0}, {5140,5149,5141 ,726,5471,7661 ,0,0,0}, - {8132,8135,8137 ,726,726,726 ,0,0,0}, {8138,8136,8135 ,7658,726,726 ,0,0,0}, - {8135,8132,8138 ,726,726,7658 ,0,0,0}, {8138,8134,8139 ,7658,726,7658 ,0,0,0}, - {8134,8138,8132 ,726,7658,726 ,0,0,0}, {8140,8139,8133 ,7658,7658,726 ,0,0,0}, - {8134,8133,8139 ,726,726,7658 ,0,0,0}, {8130,8141,8140 ,7658,7661,7658 ,0,0,0}, - {8140,8133,8130 ,7658,726,7658 ,0,0,0}, {8141,8142,5155 ,7661,7661,7664 ,0,0,0}, - {8142,8141,8130 ,7661,7661,7658 ,0,0,0}, {8142,8131,5155 ,7661,726,7664 ,0,0,0}, - {8131,8129,5153 ,726,726,7662 ,0,0,0}, {5147,5140,5138 ,7789,726,7658 ,0,0,0}, - {5128,5127,5134 ,5488,7668,7661 ,0,0,0}, {5144,5136,5143 ,7790,7664,7791 ,0,0,0}, - {5128,5134,5130 ,5488,7661,7792 ,0,0,0}, {5131,5130,5134 ,5488,7792,7661 ,0,0,0}, - {5136,5134,5143 ,7664,7661,7791 ,0,0,0}, {5143,5134,5127 ,7791,7661,7668 ,0,0,0}, - {5136,5144,5138 ,7664,7790,7658 ,0,0,0}, {5149,5140,5147 ,5471,726,7789 ,0,0,0}, - {5147,5138,5144 ,7789,7658,7790 ,0,0,0}, {5141,5150,8129 ,7661,7583,726 ,0,0,0}, - {5141,5149,5150 ,7661,5471,7583 ,0,0,0}, {8131,5153,5155 ,726,7662,7664 ,0,0,0}, - {5150,5153,8129 ,7583,7662,726 ,0,0,0}, {8143,5786,8144 ,7583,726,726 ,0,0,0}, - {8145,5782,8146 ,7668,726,5470 ,0,0,0}, {8145,8147,5782 ,7668,726,726 ,0,0,0}, - {5782,8148,8146 ,726,726,5470 ,0,0,0}, {8147,8149,5782 ,726,5489,726 ,0,0,0}, - {5782,8150,8151 ,726,7793,7794 ,0,0,0}, {8149,8150,5782 ,5489,7793,726 ,0,0,0}, - {5786,8152,5782 ,726,5470,726 ,0,0,0}, {8152,8148,5782 ,5470,726,726 ,0,0,0}, - {8153,8152,5786 ,726,5470,726 ,0,0,0}, {8154,5782,8151 ,7795,726,7794 ,0,0,0}, - {5786,8155,8153 ,726,5488,726 ,0,0,0}, {8154,8156,5782 ,7795,726,726 ,0,0,0}, - {8157,5782,8158 ,5485,726,7796 ,0,0,0}, {5782,8156,8158 ,726,726,7796 ,0,0,0}, - {5786,8159,8155 ,726,7583,5488 ,0,0,0}, {8160,5782,8157 ,7583,726,5485 ,0,0,0}, - {5786,8161,8159 ,726,726,7583 ,0,0,0}, {5786,8162,8163 ,726,5488,7583 ,0,0,0}, - {5786,8163,8161 ,726,7583,726 ,0,0,0}, {5783,8160,5778 ,5489,7583,7797 ,0,0,0}, - {5786,8143,8162 ,726,7583,5488 ,0,0,0}, {8160,5783,5782 ,7583,5489,726 ,0,0,0}, - {8144,5786,8164 ,726,726,7583 ,0,0,0}, {8165,5786,5793 ,726,726,726 ,0,0,0}, - {5786,8165,8164 ,726,726,7583 ,0,0,0}, {8165,5793,5792 ,726,726,726 ,0,0,0}, - {6201,6303,8145 ,7798,7799,7800 ,0,0,0}, {8146,6199,6201 ,7801,7802,7798 ,0,0,0}, - {8146,8148,6199 ,7801,7802,7802 ,0,0,0}, {8145,8146,6201 ,7800,7801,7798 ,0,0,0}, - {6303,6512,8147 ,7799,7803,7804 ,0,0,0}, {6324,6310,8150 ,7805,7806,7807 ,0,0,0}, - {8149,8147,6512 ,7808,7804,7803 ,0,0,0}, {6512,6324,8149 ,7803,7805,7808 ,0,0,0}, - {8150,8149,6324 ,7807,7808,7805 ,0,0,0}, {6303,8147,8145 ,7799,7804,7800 ,0,0,0}, - {8150,6310,8151 ,7807,7806,7809 ,0,0,0}, {6305,8154,8151 ,7810,7811,7809 ,0,0,0}, - {8151,6310,6305 ,7809,7806,7810 ,0,0,0}, {8154,6305,6304 ,7811,7810,7812 ,0,0,0}, - {6209,8156,6304 ,7813,7814,7812 ,0,0,0}, {6209,6288,8158 ,7813,7815,7816 ,0,0,0}, - {6209,8158,8156 ,7813,7816,7814 ,0,0,0}, {8157,6290,8160 ,7817,7818,7819 ,0,0,0}, - {8158,6288,8157 ,7816,7815,7817 ,0,0,0}, {8157,6288,6290 ,7817,7815,7818 ,0,0,0}, - {6290,6319,8160 ,7818,7819,7819 ,0,0,0}, {8154,6304,8156 ,7811,7812,7814 ,0,0,0}, - {6333,8148,8152 ,7820,7802,7821 ,0,0,0}, {8148,6333,6199 ,7802,7820,7802 ,0,0,0}, - {8153,6337,8152 ,7822,7823,7821 ,0,0,0}, {6333,8152,6337 ,7820,7821,7823 ,0,0,0}, - {8153,8155,6298 ,7822,7824,7825 ,0,0,0}, {6298,6337,8153 ,7825,7823,7822 ,0,0,0}, - {6299,8155,8159 ,7826,7824,7827 ,0,0,0}, {8155,6299,6298 ,7824,7826,7825 ,0,0,0}, - {8161,6374,8159 ,7828,7829,7827 ,0,0,0}, {6299,8159,6374 ,7826,7827,7829 ,0,0,0}, - {8161,8163,6202 ,7828,7830,7831 ,0,0,0}, {6202,6374,8161 ,7831,7829,7828 ,0,0,0}, - {6203,8163,8162 ,7832,7830,7833 ,0,0,0}, {8163,6203,6202 ,7830,7832,7831 ,0,0,0}, - {8143,6361,8162 ,7834,7835,7833 ,0,0,0}, {6203,8162,6361 ,7832,7833,7835 ,0,0,0}, - {8143,8144,6364 ,7834,7836,7837 ,0,0,0}, {6364,6361,8143 ,7837,7835,7834 ,0,0,0}, - {6368,8144,8164 ,7838,7836,7839 ,0,0,0}, {8144,6368,6364 ,7836,7838,7837 ,0,0,0}, - {6368,8164,6369 ,7838,7839,7840 ,0,0,0}, {6369,8164,8165 ,7840,7839,7840 ,0,0,0}, - {6936,8165,5792 ,7841,7841,7841 ,0,0,0}, {8165,6942,6945 ,7841,7841,7841 ,0,0,0}, - {6936,6942,8165 ,7841,7841,7841 ,0,0,0}, {8165,6951,6956 ,7841,7841,7841 ,0,0,0}, - {6945,6951,8165 ,7841,7841,7841 ,0,0,0}, {8165,6960,6919 ,7841,7841,7841 ,0,0,0}, - {6956,6960,8165 ,7841,7841,7841 ,0,0,0}, {8165,6931,6930 ,7841,7841,7841 ,0,0,0}, - {6919,6931,8165 ,7841,7841,7841 ,0,0,0}, {8165,6930,6369 ,7841,7841,7841 ,0,0,0}, - {6997,8160,6319 ,7842,7842,7842 ,0,0,0}, {6997,7043,8160 ,7842,7842,7842 ,0,0,0}, - {8160,7043,7029 ,7842,7842,7842 ,0,0,0}, {6991,6984,8160 ,7842,7842,7842 ,0,0,0}, - {6991,8160,7029 ,7842,7842,7842 ,0,0,0}, {6984,7025,8160 ,7842,7842,7842 ,0,0,0}, - {8160,7017,6979 ,7842,7842,7842 ,0,0,0}, {7025,7017,8160 ,7842,7842,7842 ,0,0,0}, - {5778,8160,6980 ,7842,7842,7842 ,0,0,0}, {6979,6980,8160 ,7842,7842,7842 ,0,0,0}, - {5104,8166,6554 ,1790,7843,4204 ,0,0,0}, {8167,6551,8168 ,7844,4198,4199 ,0,0,0}, - {6540,6553,8169 ,7845,7846,7847 ,0,0,0}, {6531,8170,6349 ,7848,7849,7850 ,0,0,0}, - {8171,8172,6564 ,7851,7852,7853 ,0,0,0}, {8173,6328,8174 ,7854,7855,7856 ,0,0,0}, - {6330,6347,8175 ,7857,7858,7859 ,0,0,0}, {6196,6195,8176 ,7860,7861,7862 ,0,0,0}, - {6351,8177,6195 ,7863,7864,7861 ,0,0,0}, {6355,8178,8179 ,7865,7866,7867 ,0,0,0}, - {6196,8180,6354 ,7860,7868,7869 ,0,0,0}, {8181,6360,8179 ,7870,7871,7867 ,0,0,0}, - {6355,8179,6360 ,7865,7867,7871 ,0,0,0}, {8181,8182,6358 ,7870,7872,7873 ,0,0,0}, - {6358,6360,8181 ,7873,7871,7870 ,0,0,0}, {6343,8182,8183 ,7874,7872,7875 ,0,0,0}, - {8182,6343,6358 ,7872,7874,7873 ,0,0,0}, {8184,6341,8183 ,7876,7877,7875 ,0,0,0}, - {6343,8183,6341 ,7874,7875,7877 ,0,0,0}, {8184,5123,5124 ,7876,1711,1711 ,0,0,0}, - {5124,6341,8184 ,1711,7877,7876 ,0,0,0}, {8176,6195,8177 ,7862,7861,7864 ,0,0,0}, - {8178,6354,8180 ,7866,7869,7868 ,0,0,0}, {6354,8178,6355 ,7869,7866,7865 ,0,0,0}, - {8176,8180,6196 ,7862,7868,7860 ,0,0,0}, {8173,8177,6351 ,7854,7864,7863 ,0,0,0}, - {6330,8175,8174 ,7857,7859,7856 ,0,0,0}, {6330,8174,6328 ,7857,7856,7855 ,0,0,0}, - {6351,6328,8173 ,7863,7855,7854 ,0,0,0}, {6347,8185,8175 ,7858,7878,7859 ,0,0,0}, - {8185,6347,6349 ,7878,7858,7850 ,0,0,0}, {8172,8170,6531 ,7852,7849,7848 ,0,0,0}, - {8170,8185,6349 ,7849,7878,7850 ,0,0,0}, {6564,8172,6531 ,7853,7852,7848 ,0,0,0}, - {6552,8167,8171 ,7879,7844,7851 ,0,0,0}, {6552,8171,6564 ,7879,7851,7853 ,0,0,0}, - {6551,6540,8168 ,4198,7845,4199 ,0,0,0}, {6552,6551,8167 ,7879,4198,7844 ,0,0,0}, - {6553,8166,8169 ,7846,7843,7847 ,0,0,0}, {8168,6540,8169 ,4199,7845,7847 ,0,0,0}, - {5104,6554,5102 ,1790,4204,1790 ,0,0,0}, {8166,6553,6554 ,7843,7846,4204 ,0,0,0}, - {8176,8177,8171 ,726,7880,7881 ,0,0,0}, {8166,8181,8179 ,7882,7627,7625 ,0,0,0}, - {8172,8173,8170 ,7883,7758,726 ,0,0,0}, {8185,8170,8173 ,7884,726,7758 ,0,0,0}, - {8174,8175,8185 ,7880,7761,7884 ,0,0,0}, {8173,8172,8177 ,7758,7883,7880 ,0,0,0}, - {8174,8185,8173 ,7880,7884,7758 ,0,0,0}, {8176,8171,8167 ,726,7881,7885 ,0,0,0}, - {8177,8172,8171 ,7880,7883,7881 ,0,0,0}, {8167,8168,8180 ,7885,7886,7758 ,0,0,0}, - {8180,8176,8167 ,7758,726,7885 ,0,0,0}, {8178,8168,8169 ,726,7886,7887 ,0,0,0}, - {8168,8178,8180 ,7886,726,7758 ,0,0,0}, {8179,8178,8169 ,7625,726,7887 ,0,0,0}, - {5104,8181,8166 ,7758,7627,7882 ,0,0,0}, {8166,8179,8169 ,7882,7625,7887 ,0,0,0}, - {8182,5104,5101 ,7627,7758,7755 ,0,0,0}, {5104,8182,8181 ,7758,7627,7627 ,0,0,0}, - {5100,8183,5101 ,7625,726,7755 ,0,0,0}, {8182,5101,8183 ,7627,7755,726 ,0,0,0}, - {5100,5098,8184 ,7625,7761,726 ,0,0,0}, {8184,8183,5100 ,726,726,7625 ,0,0,0}, - {5123,5098,5092 ,7627,7761,7625 ,0,0,0}, {5098,5123,8184 ,7761,7627,726 ,0,0,0}, - {5089,5117,5095 ,726,7627,7625 ,0,0,0}, {5097,5121,5092 ,7880,726,7625 ,0,0,0}, - {5115,5088,5112 ,7625,726,726 ,0,0,0}, {5109,5085,5106 ,7627,7625,7625 ,0,0,0}, - {5111,5112,5086 ,726,726,7625 ,0,0,0}, {5106,5083,5105 ,7625,7625,726 ,0,0,0}, - {5085,5109,5111 ,7625,7627,726 ,0,0,0}, {5086,5085,5111 ,7625,7625,726 ,0,0,0}, - {5106,5085,5083 ,7625,7625,7625 ,0,0,0}, {5089,5088,5115 ,726,726,7625 ,0,0,0}, - {5086,5112,5088 ,7625,726,726 ,0,0,0}, {5118,5095,5117 ,726,7625,7627 ,0,0,0}, - {5117,5089,5115 ,7627,726,7625 ,0,0,0}, {5097,5118,5121 ,7880,726,726 ,0,0,0}, - {5118,5097,5095 ,726,7880,7625 ,0,0,0}, {5121,5123,5092 ,726,7627,7625 ,0,0,0}, - {5065,8186,6484 ,1790,7888,7889 ,0,0,0}, {6536,6525,8187 ,7890,7891,7892 ,0,0,0}, - {6538,6485,8188 ,7893,7894,7895 ,0,0,0}, {6526,8189,6527 ,7896,7897,4137 ,0,0,0}, - {8190,8191,6537 ,7898,7899,7900 ,0,0,0}, {8192,8193,6535 ,7901,7902,7903 ,0,0,0}, - {8192,6534,8194 ,7901,7904,7905 ,0,0,0}, {8195,8196,6370 ,7906,7907,7908 ,0,0,0}, - {6370,6371,8195 ,7908,7909,7906 ,0,0,0}, {6533,8196,8197 ,7910,7907,7911 ,0,0,0}, - {8196,6533,6370 ,7907,7910,7908 ,0,0,0}, {8198,6344,8197 ,7912,7913,7911 ,0,0,0}, - {6533,8197,6344 ,7910,7911,7913 ,0,0,0}, {8198,5079,5080 ,7912,1711,1711 ,0,0,0}, - {5080,6344,8198 ,1711,7913,7912 ,0,0,0}, {8189,6526,8191 ,7897,7896,7899 ,0,0,0}, - {8193,6371,6535 ,7902,7909,7903 ,0,0,0}, {8195,6371,8193 ,7906,7909,7902 ,0,0,0}, - {8187,6525,8199 ,7892,7891,7914 ,0,0,0}, {8194,6534,6527 ,7905,7904,4137 ,0,0,0}, - {8192,6535,6534 ,7901,7903,7904 ,0,0,0}, {8189,8194,6527 ,7897,7905,4137 ,0,0,0}, - {6537,8191,6526 ,7900,7899,7896 ,0,0,0}, {6536,8187,8190 ,7890,7892,7898 ,0,0,0}, - {8190,6537,6536 ,7898,7900,7890 ,0,0,0}, {6485,8186,8188 ,7894,7888,7895 ,0,0,0}, - {8199,6538,8188 ,7914,7893,7895 ,0,0,0}, {6525,6538,8199 ,7891,7893,7914 ,0,0,0}, - {5065,6484,5066 ,1790,7889,1790 ,0,0,0}, {8186,6485,6484 ,7888,7894,7889 ,0,0,0}, - {8192,5073,8193 ,726,7658,726 ,0,0,0}, {8197,8196,5077 ,726,726,7660 ,0,0,0}, - {5079,8198,8197 ,726,7660,726 ,0,0,0}, {8192,8194,5071 ,726,726,7658 ,0,0,0}, - {5074,5077,8195 ,7660,7660,7659 ,0,0,0}, {8191,8190,5051 ,7659,726,7661 ,0,0,0}, - {8191,5067,8189 ,7659,726,726 ,0,0,0}, {5054,5052,8187 ,7915,7916,726 ,0,0,0}, - {8186,5060,5058 ,7658,7917,5475 ,0,0,0}, {8188,5055,8199 ,7658,726,7659 ,0,0,0}, - {5065,5064,5060 ,7918,7918,7917 ,0,0,0}, {5062,5060,5064 ,7661,7917,7918 ,0,0,0}, - {8188,8186,5058 ,7658,7658,5475 ,0,0,0}, {8186,5065,5060 ,7658,7918,7917 ,0,0,0}, - {5055,8188,5058 ,726,7658,5475 ,0,0,0}, {8199,5055,5054 ,7659,726,7915 ,0,0,0}, - {8187,5052,8190 ,726,7916,726 ,0,0,0}, {8199,5054,8187 ,7659,7915,726 ,0,0,0}, - {8191,5051,5067 ,7659,7661,726 ,0,0,0}, {8190,5052,5051 ,726,7916,7661 ,0,0,0}, - {5068,8194,8189 ,7664,726,726 ,0,0,0}, {5067,5068,8189 ,726,7664,726 ,0,0,0}, - {5073,8192,5071 ,7658,726,7658 ,0,0,0}, {5071,8194,5068 ,7658,726,7664 ,0,0,0}, - {8193,5074,8195 ,726,7660,7659 ,0,0,0}, {8193,5073,5074 ,726,7658,7660 ,0,0,0}, - {8197,5077,5079 ,726,7660,726 ,0,0,0}, {8196,8195,5077 ,726,7659,7660 ,0,0,0}, - {5823,8200,8201 ,726,5469,7919 ,0,0,0}, {8202,5823,8203 ,7920,726,7921 ,0,0,0}, - {5823,8202,8200 ,726,7920,5469 ,0,0,0}, {5823,8204,8203 ,726,726,7921 ,0,0,0}, - {8205,5823,8201 ,7922,726,7919 ,0,0,0}, {8204,5823,8206 ,726,726,7920 ,0,0,0}, - {8205,8207,5823 ,7922,7923,726 ,0,0,0}, {5823,8208,8209 ,726,7924,7925 ,0,0,0}, - {8209,8210,5823 ,7925,7926,726 ,0,0,0}, {8207,8208,5823 ,7923,7924,726 ,0,0,0}, - {8211,8212,5823 ,5472,7927,726 ,0,0,0}, {8211,5823,8210 ,5472,726,7926 ,0,0,0}, - {8213,8214,5823 ,7928,7929,726 ,0,0,0}, {8213,5823,8212 ,7928,726,7927 ,0,0,0}, - {8215,8216,5823 ,726,5489,726 ,0,0,0}, {8215,5823,8214 ,726,726,7929 ,0,0,0}, - {5823,8217,5822 ,726,5488,7583 ,0,0,0}, {8217,5823,8216 ,5488,726,5489 ,0,0,0}, - {5822,8218,8219 ,7583,5470,5489 ,0,0,0}, {8217,8218,5822 ,5488,5470,7583 ,0,0,0}, - {5818,5819,8219 ,5489,5488,5489 ,0,0,0}, {5822,8219,5819 ,7583,5489,5488 ,0,0,0}, - {5813,5818,8219 ,5489,5489,5489 ,0,0,0}, {5823,7790,8206 ,726,5489,7920 ,0,0,0}, - {7790,8220,8221 ,5489,5470,5488 ,0,0,0}, {8206,7790,8221 ,7920,5489,5488 ,0,0,0}, - {8222,7790,7789 ,5489,5489,726 ,0,0,0}, {7790,8222,8220 ,5489,5489,5470 ,0,0,0}, - {6853,8222,7788 ,5489,5489,7583 ,0,0,0}, {7789,7788,8222 ,726,7583,5489 ,0,0,0}, - {6387,6348,8210 ,7930,7931,7932 ,0,0,0}, {8209,6389,6387 ,7933,7934,7930 ,0,0,0}, - {8209,8208,6389 ,7933,7935,7934 ,0,0,0}, {8210,8209,6387 ,7932,7933,7930 ,0,0,0}, - {6348,6532,8211 ,7931,7936,7937 ,0,0,0}, {6329,6350,8213 ,7938,7939,7940 ,0,0,0}, - {8212,8211,6532 ,7941,7937,7936 ,0,0,0}, {6532,6329,8212 ,7936,7938,7941 ,0,0,0}, - {8213,8212,6329 ,7940,7941,7938 ,0,0,0}, {6348,8211,8210 ,7931,7937,7932 ,0,0,0}, - {8213,6350,8214 ,7940,7939,7942 ,0,0,0}, {6352,8215,8214 ,7943,7944,7942 ,0,0,0}, - {8214,6350,6352 ,7942,7939,7943 ,0,0,0}, {8215,6352,6197 ,7944,7943,7945 ,0,0,0}, - {6340,8216,6197 ,7946,7947,7945 ,0,0,0}, {6340,6353,8217 ,7946,7948,7949 ,0,0,0}, - {6340,8217,8216 ,7946,7949,7947 ,0,0,0}, {8218,6345,8219 ,7950,7951,7952 ,0,0,0}, - {8217,6353,8218 ,7949,7948,7950 ,0,0,0}, {8218,6353,6345 ,7950,7948,7951 ,0,0,0}, - {6345,6346,8219 ,7951,7952,7952 ,0,0,0}, {8215,6197,8216 ,7944,7945,7947 ,0,0,0}, - {6509,8208,8207 ,7953,7935,7954 ,0,0,0}, {8208,6509,6389 ,7935,7953,7934 ,0,0,0}, - {8205,6388,8207 ,7955,7956,7954 ,0,0,0}, {6509,8207,6388 ,7953,7954,7956 ,0,0,0}, - {8205,8201,6372 ,7955,7957,7958 ,0,0,0}, {6372,6388,8205 ,7958,7956,7955 ,0,0,0}, - {6373,8201,8200 ,7959,7957,7960 ,0,0,0}, {8201,6373,6372 ,7957,7959,7958 ,0,0,0}, - {8202,6546,8200 ,7961,7962,7960 ,0,0,0}, {6373,8200,6546 ,7959,7960,7962 ,0,0,0}, - {8202,8203,6486 ,7961,7963,7964 ,0,0,0}, {6486,6546,8202 ,7964,7962,7961 ,0,0,0}, - {6487,8203,8204 ,7965,7963,7966 ,0,0,0}, {8203,6487,6486 ,7963,7965,7964 ,0,0,0}, - {8206,6380,8204 ,7967,7968,7966 ,0,0,0}, {6487,8204,6380 ,7965,7966,7968 ,0,0,0}, - {8206,8221,6408 ,7967,7969,7970 ,0,0,0}, {6408,6380,8206 ,7970,7968,7967 ,0,0,0}, - {6409,8221,8220 ,7971,7969,7972 ,0,0,0}, {8221,6409,6408 ,7969,7971,7970 ,0,0,0}, - {6409,8220,6411 ,7971,7972,7973 ,0,0,0}, {6411,8220,8222 ,7973,7972,7973 ,0,0,0}, - {6863,6869,8222 ,7974,7974,7974 ,0,0,0}, {8222,6853,6854 ,7974,7974,7974 ,0,0,0}, - {6854,6860,8222 ,7974,7974,7974 ,0,0,0}, {6874,8222,6869 ,7974,7974,7974 ,0,0,0}, - {6860,6863,8222 ,7974,7974,7974 ,0,0,0}, {6878,6831,8222 ,7974,7974,7974 ,0,0,0}, - {6878,8222,6874 ,7974,7974,7974 ,0,0,0}, {6831,6843,8222 ,7974,7974,7974 ,0,0,0}, - {6411,8222,6842 ,7974,7974,7974 ,0,0,0}, {6843,6842,8222 ,7974,7974,7974 ,0,0,0}, - {8219,6346,6911 ,7975,7975,7975 ,0,0,0}, {6911,6961,8219 ,7975,7975,7975 ,0,0,0}, - {8219,6947,6907 ,7975,7975,7975 ,0,0,0}, {6961,6947,8219 ,7975,7975,7975 ,0,0,0}, - {8219,6913,6943 ,7975,7975,7975 ,0,0,0}, {6907,6913,8219 ,7975,7975,7975 ,0,0,0}, - {8219,6899,6898 ,7975,7975,7975 ,0,0,0}, {6943,6899,8219 ,7975,7975,7975 ,0,0,0}, - {5813,8219,6903 ,7975,7975,7975 ,0,0,0}, {6898,6903,8219 ,7975,7975,7975 ,0,0,0}, - {5028,8223,6559 ,126,7976,7977 ,0,0,0}, {8224,6561,8225 ,7978,7979,7980 ,0,0,0}, - {6575,6562,8226 ,7981,7982,7983 ,0,0,0}, {6376,8227,6367 ,7984,7985,7986 ,0,0,0}, - {8228,8229,6543 ,7987,7988,7989 ,0,0,0}, {8230,6394,8231 ,7990,7991,7992 ,0,0,0}, - {6412,6379,8232 ,7993,7994,7995 ,0,0,0}, {6404,6405,8233 ,7996,7997,7998 ,0,0,0}, - {6395,8234,6405 ,7999,8000,7997 ,0,0,0}, {6396,8235,8236 ,8001,8002,8003 ,0,0,0}, - {6404,8237,6398 ,7996,8004,8005 ,0,0,0}, {8238,6399,8236 ,8006,8007,8003 ,0,0,0}, - {6396,8236,6399 ,8001,8003,8007 ,0,0,0}, {8238,8239,6402 ,8006,8008,8009 ,0,0,0}, - {6402,6399,8238 ,8009,8007,8006 ,0,0,0}, {6441,8239,8240 ,8010,8008,8011 ,0,0,0}, - {8239,6441,6402 ,8008,8010,8009 ,0,0,0}, {8241,6403,8240 ,8012,8013,8011 ,0,0,0}, - {6441,8240,6403 ,8010,8011,8013 ,0,0,0}, {8241,5047,5048 ,8012,8014,4346 ,0,0,0}, - {5048,6403,8241 ,4346,8013,8012 ,0,0,0}, {8233,6405,8234 ,7998,7997,8000 ,0,0,0}, - {8235,6398,8237 ,8002,8005,8004 ,0,0,0}, {6398,8235,6396 ,8005,8002,8001 ,0,0,0}, - {8233,8237,6404 ,7998,8004,7996 ,0,0,0}, {8230,8234,6395 ,7990,8000,7999 ,0,0,0}, - {6412,8232,8231 ,7993,7995,7992 ,0,0,0}, {6412,8231,6394 ,7993,7992,7991 ,0,0,0}, - {6395,6394,8230 ,7999,7991,7990 ,0,0,0}, {6379,8242,8232 ,7994,8015,7995 ,0,0,0}, - {8242,6379,6367 ,8015,7994,7986 ,0,0,0}, {8229,8227,6376 ,7988,7985,7984 ,0,0,0}, - {8227,8242,6367 ,7985,8015,7986 ,0,0,0}, {6543,8229,6376 ,7989,7988,7984 ,0,0,0}, - {6560,8224,8228 ,8016,7978,7987 ,0,0,0}, {6560,8228,6543 ,8016,7987,7989 ,0,0,0}, - {6561,6575,8225 ,7979,7981,7980 ,0,0,0}, {6560,6561,8224 ,8016,7979,7978 ,0,0,0}, - {6562,8223,8226 ,7982,7976,7983 ,0,0,0}, {8225,6575,8226 ,7980,7981,7983 ,0,0,0}, - {5028,6559,5026 ,126,7977,4289 ,0,0,0}, {8223,6562,6559 ,7976,7982,7977 ,0,0,0}, - {8241,8240,8239 ,7625,7880,7758 ,0,0,0}, {5033,8224,8225 ,7626,7880,726 ,0,0,0}, - {8239,8236,8233 ,7758,8017,8018 ,0,0,0}, {8239,8238,8236 ,7758,7758,8017 ,0,0,0}, - {8235,8233,8236 ,8017,8018,8017 ,0,0,0}, {8235,8237,8233 ,8017,7758,8018 ,0,0,0}, - {8234,8239,8233 ,8019,7758,8018 ,0,0,0}, {8234,8230,8241 ,8019,7884,7625 ,0,0,0}, - {8241,8239,8234 ,7625,7758,8019 ,0,0,0}, {8230,8231,5045 ,7884,8020,7625 ,0,0,0}, - {8230,5047,8241 ,7884,7625,7625 ,0,0,0}, {8242,5041,5042 ,8021,7625,726 ,0,0,0}, - {5042,5045,8232 ,726,7625,7257 ,0,0,0}, {5035,5036,8228 ,726,726,8017 ,0,0,0}, - {5039,8227,8229 ,7625,8022,7761 ,0,0,0}, {5030,8226,5029 ,7626,726,7626 ,0,0,0}, - {8225,5030,5033 ,726,7626,7626 ,0,0,0}, {5025,5010,5009 ,7625,726,726 ,0,0,0}, - {5028,5009,8223 ,7625,726,7625 ,0,0,0}, {5021,5012,5022 ,726,726,7625 ,0,0,0}, - {5012,5021,5019 ,726,726,726 ,0,0,0}, {5016,5021,5022 ,7625,726,7625 ,0,0,0}, - {5024,5022,5025 ,7625,7625,7625 ,0,0,0}, {5022,5012,5010 ,7625,726,726 ,0,0,0}, - {5013,5012,5019 ,726,726,726 ,0,0,0}, {5009,5028,5025 ,726,7625,7625 ,0,0,0}, - {5010,5025,5022 ,726,7625,7625 ,0,0,0}, {8223,5007,5029 ,7625,726,7626 ,0,0,0}, - {5007,8223,5009 ,726,7625,726 ,0,0,0}, {8226,5030,8225 ,726,7626,726 ,0,0,0}, - {8223,5029,8226 ,7625,7626,726 ,0,0,0}, {5033,5035,8224 ,7626,726,7880 ,0,0,0}, - {8228,5036,8229 ,8017,726,7761 ,0,0,0}, {8224,5035,8228 ,7880,726,8017 ,0,0,0}, - {8229,5036,5039 ,7761,726,7625 ,0,0,0}, {8227,5041,8242 ,8022,7625,8021 ,0,0,0}, - {8227,5039,5041 ,8022,7625,7625 ,0,0,0}, {5045,8231,8232 ,7625,8020,7257 ,0,0,0}, - {8232,8242,5042 ,7257,8021,726 ,0,0,0}, {5045,5047,8230 ,7625,7625,7884 ,0,0,0}, - {4989,8243,6558 ,8023,8024,8025 ,0,0,0}, {6300,6503,8244 ,8026,8027,8028 ,0,0,0}, - {6610,6556,8245 ,8029,8030,8031 ,0,0,0}, {6549,8246,6541 ,8032,8033,8034 ,0,0,0}, - {8247,8248,6508 ,8035,8036,8037 ,0,0,0}, {8249,8250,6548 ,8038,8039,8040 ,0,0,0}, - {8249,6550,8251 ,8038,8041,8042 ,0,0,0}, {8252,8253,6547 ,8043,8044,8045 ,0,0,0}, - {6547,6447,8252 ,8045,8046,8043 ,0,0,0}, {6444,8253,8254 ,8047,8044,8048 ,0,0,0}, - {8253,6444,6547 ,8044,8047,8045 ,0,0,0}, {8255,6445,8254 ,8049,8050,8048 ,0,0,0}, - {6444,8254,6445 ,8047,8048,8050 ,0,0,0}, {8255,5003,5004 ,8049,82,82 ,0,0,0}, - {5004,6445,8255 ,82,8050,8049 ,0,0,0}, {8246,6549,8248 ,8033,8032,8036 ,0,0,0}, - {8250,6447,6548 ,8039,8046,8040 ,0,0,0}, {8252,6447,8250 ,8043,8046,8039 ,0,0,0}, - {8244,6503,8256 ,8028,8027,8051 ,0,0,0}, {8251,6550,6541 ,8042,8041,8034 ,0,0,0}, - {8249,6548,6550 ,8038,8040,8041 ,0,0,0}, {8246,8251,6541 ,8033,8042,8034 ,0,0,0}, - {6508,8248,6549 ,8037,8036,8032 ,0,0,0}, {6300,8244,8247 ,8026,8028,8035 ,0,0,0}, - {8247,6508,6300 ,8035,8037,8026 ,0,0,0}, {6556,8243,8245 ,8030,8024,8031 ,0,0,0}, - {8256,6610,8245 ,8051,8029,8031 ,0,0,0}, {6503,6610,8256 ,8027,8029,8051 ,0,0,0}, - {4989,6558,4990 ,8023,8025,8052 ,0,0,0}, {8243,6556,6558 ,8024,8030,8025 ,0,0,0}, - {8249,4986,8250 ,726,726,726 ,0,0,0}, {8253,4982,4979 ,726,7661,726 ,0,0,0}, - {8246,8248,8243 ,726,7660,726 ,0,0,0}, {8251,4989,4988 ,726,726,726 ,0,0,0}, - {8245,8243,8244 ,7661,726,726 ,0,0,0}, {8244,8256,8245 ,726,7658,7661 ,0,0,0}, - {8244,8248,8247 ,726,7660,726 ,0,0,0}, {8243,4989,8246 ,726,726,726 ,0,0,0}, - {8248,8244,8243 ,7660,726,726 ,0,0,0}, {8251,4988,8249 ,726,726,726 ,0,0,0}, - {8246,4989,8251 ,726,726,726 ,0,0,0}, {8249,4988,4986 ,726,726,726 ,0,0,0}, - {8250,4984,8252 ,726,7658,726 ,0,0,0}, {8250,4986,4984 ,726,726,7658 ,0,0,0}, - {8253,8252,4982 ,726,726,7661 ,0,0,0}, {4984,4982,8252 ,7658,7661,726 ,0,0,0}, - {8253,4979,8254 ,726,726,726 ,0,0,0}, {4978,8255,8254 ,726,726,726 ,0,0,0}, - {8254,4979,4978 ,726,726,726 ,0,0,0}, {8255,4976,5003 ,726,726,726 ,0,0,0}, - {4976,8255,4978 ,726,726,726 ,0,0,0}, {4976,4975,5003 ,726,726,726 ,0,0,0}, - {4995,4991,4992 ,7659,726,726 ,0,0,0}, {4995,5001,4991 ,7659,726,726 ,0,0,0}, - {4998,4995,4997 ,726,7659,726 ,0,0,0}, {4998,5001,4995 ,726,726,7659 ,0,0,0}, - {5003,4975,5001 ,726,726,726 ,0,0,0}, {4991,5001,4975 ,726,726,726 ,0,0,0}, - {8257,8258,7785 ,726,8053,7583 ,0,0,0}, {7787,8259,7786 ,726,726,726 ,0,0,0}, - {8258,8260,7785 ,8053,7922,7583 ,0,0,0}, {8257,7785,8261 ,726,7583,5472 ,0,0,0}, - {7785,8262,8263 ,7583,7664,5488 ,0,0,0}, {8260,8262,7785 ,7922,7664,7583 ,0,0,0}, - {8264,8265,7785 ,7920,726,7583 ,0,0,0}, {8263,8266,7785 ,5488,5471,7583 ,0,0,0}, - {8267,8268,7787 ,7664,7583,726 ,0,0,0}, {7787,8269,8270 ,726,5488,7664 ,0,0,0}, - {8271,7787,8272 ,726,726,726 ,0,0,0}, {8273,8274,7787 ,7664,7664,726 ,0,0,0}, - {8275,8272,7787 ,726,726,726 ,0,0,0}, {7787,8271,8259 ,726,726,726 ,0,0,0}, - {8273,7787,8276 ,7664,726,7664 ,0,0,0}, {7787,8274,8275 ,726,7664,726 ,0,0,0}, - {7787,8268,8276 ,726,7583,7664 ,0,0,0}, {7787,8270,8277 ,726,7664,726 ,0,0,0}, - {7787,8277,8267 ,726,726,7664 ,0,0,0}, {8265,7787,7785 ,726,726,7583 ,0,0,0}, - {8265,8269,7787 ,726,5488,726 ,0,0,0}, {7785,8266,8264 ,7583,5471,7920 ,0,0,0}, - {6814,7786,8259 ,726,726,726 ,0,0,0}, {8261,7785,8278 ,5472,7583,7793 ,0,0,0}, - {8279,7785,7784 ,5471,7583,7664 ,0,0,0}, {7785,8279,8278 ,7583,5471,7793 ,0,0,0}, - {8279,7784,6759 ,5471,7664,7920 ,0,0,0}, {6366,6365,8277 ,8054,8055,8056 ,0,0,0}, - {8270,6375,6366 ,8057,8058,8054 ,0,0,0}, {8270,8269,6375 ,8057,8058,8058 ,0,0,0}, - {8277,8270,6366 ,8056,8057,8054 ,0,0,0}, {6365,6544,8267 ,8055,8059,8060 ,0,0,0}, - {6442,6386,8276 ,8061,8062,8063 ,0,0,0}, {8268,8267,6544 ,8064,8060,8059 ,0,0,0}, - {6544,6442,8268 ,8059,8061,8064 ,0,0,0}, {8276,8268,6442 ,8063,8064,8061 ,0,0,0}, - {6365,8267,8277 ,8055,8060,8056 ,0,0,0}, {8276,6386,8273 ,8063,8062,8065 ,0,0,0}, - {6385,8274,8273 ,8066,8067,8065 ,0,0,0}, {8273,6386,6385 ,8065,8062,8066 ,0,0,0}, - {8274,6385,6545 ,8067,8066,8068 ,0,0,0}, {6393,8275,6545 ,8069,8070,8068 ,0,0,0}, - {6393,6392,8272 ,8069,8071,8072 ,0,0,0}, {6393,8272,8275 ,8069,8072,8070 ,0,0,0}, - {8271,6407,8259 ,8073,8074,8075 ,0,0,0}, {8272,6392,8271 ,8072,8071,8073 ,0,0,0}, - {8271,6392,6407 ,8073,8071,8074 ,0,0,0}, {6407,6410,8259 ,8074,8075,8075 ,0,0,0}, - {8274,6545,8275 ,8067,8068,8070 ,0,0,0}, {6198,8269,8265 ,8076,8058,8077 ,0,0,0}, - {8269,6198,6375 ,8058,8076,8058 ,0,0,0}, {8264,6446,8265 ,8078,8079,8077 ,0,0,0}, - {6198,8265,6446 ,8076,8077,8079 ,0,0,0}, {8264,8266,6390 ,8078,8080,8081 ,0,0,0}, - {6390,6446,8264 ,8081,8079,8078 ,0,0,0}, {6391,8266,8263 ,8082,8080,8083 ,0,0,0}, - {8266,6391,6390 ,8080,8082,8081 ,0,0,0}, {8262,6568,8263 ,8084,8085,8083 ,0,0,0}, - {6391,8263,6568 ,8082,8083,8085 ,0,0,0}, {8262,8260,6336 ,8084,8086,8087 ,0,0,0}, - {6336,6568,8262 ,8087,8085,8084 ,0,0,0}, {6335,8260,8258 ,8088,8086,8089 ,0,0,0}, - {8260,6335,6336 ,8086,8088,8087 ,0,0,0}, {8257,6419,8258 ,8090,8091,8089 ,0,0,0}, - {6335,8258,6419 ,8088,8089,8091 ,0,0,0}, {8257,8261,6459 ,8090,8092,8093 ,0,0,0}, - {6459,6419,8257 ,8093,8091,8090 ,0,0,0}, {6460,8261,8278 ,8094,8092,8095 ,0,0,0}, - {8261,6460,6459 ,8092,8094,8093 ,0,0,0}, {6460,8278,6461 ,8094,8095,8096 ,0,0,0}, - {6461,8278,8279 ,8096,8095,8096 ,0,0,0}, {6766,8279,6759 ,8097,8098,8097 ,0,0,0}, - {8279,6767,6770 ,8098,8097,8098 ,0,0,0}, {6766,6767,8279 ,8097,8097,8098 ,0,0,0}, - {8279,6776,6781 ,8098,8098,8097 ,0,0,0}, {6770,6776,8279 ,8098,8098,8098 ,0,0,0}, - {8279,6785,6744 ,8098,8098,8097 ,0,0,0}, {6781,6785,8279 ,8097,8098,8098 ,0,0,0}, - {8279,6748,6747 ,8098,8097,8097 ,0,0,0}, {6744,6748,8279 ,8097,8097,8098 ,0,0,0}, - {8279,6747,6461 ,8098,8097,8098 ,0,0,0}, {6823,8259,6410 ,8099,8099,8099 ,0,0,0}, - {6823,6879,8259 ,8099,8099,8099 ,0,0,0}, {8259,6879,6865 ,8099,8099,8099 ,0,0,0}, - {6819,6825,8259 ,8099,8099,8099 ,0,0,0}, {6819,8259,6865 ,8099,8099,8099 ,0,0,0}, - {6825,6861,8259 ,8099,8099,8099 ,0,0,0}, {8259,6808,6807 ,8099,8099,8099 ,0,0,0}, - {6861,6808,8259 ,8099,8099,8099 ,0,0,0}, {6814,8259,6812 ,8099,8099,8099 ,0,0,0}, - {6807,6812,8259 ,8099,8099,8099 ,0,0,0}, {4952,8280,6602 ,1359,8100,4482 ,0,0,0}, - {8281,6601,8282 ,4475,8101,8102 ,0,0,0}, {6603,6600,8283 ,8103,8104,4478 ,0,0,0}, - {6434,8284,6426 ,8105,8106,8107 ,0,0,0}, {8285,8286,6606 ,4472,8108,8109 ,0,0,0}, - {8287,6463,8288 ,8110,8111,8112 ,0,0,0}, {6462,6424,8289 ,8113,8114,8115 ,0,0,0}, - {6437,6430,8290 ,8116,8117,8118 ,0,0,0}, {6465,8291,6430 ,8119,8120,8117 ,0,0,0}, - {6455,8292,8293 ,8121,8122,8123 ,0,0,0}, {6437,8294,6457 ,8116,8124,8125 ,0,0,0}, - {8295,6454,8293 ,8126,8127,8123 ,0,0,0}, {6455,8293,6454 ,8121,8123,8127 ,0,0,0}, - {8295,8296,6452 ,8126,8128,8129 ,0,0,0}, {6452,6454,8295 ,8129,8127,8126 ,0,0,0}, - {6449,8296,8297 ,8130,8128,8131 ,0,0,0}, {8296,6449,6452 ,8128,8130,8129 ,0,0,0}, - {8298,6450,8297 ,8132,8133,8131 ,0,0,0}, {6449,8297,6450 ,8130,8131,8133 ,0,0,0}, - {8298,4971,4972 ,8132,1435,1435 ,0,0,0}, {4972,6450,8298 ,1435,8133,8132 ,0,0,0}, - {8290,6430,8291 ,8118,8117,8120 ,0,0,0}, {8292,6457,8294 ,8122,8125,8124 ,0,0,0}, - {6457,8292,6455 ,8125,8122,8121 ,0,0,0}, {8290,8294,6437 ,8118,8124,8116 ,0,0,0}, - {8287,8291,6465 ,8110,8120,8119 ,0,0,0}, {6462,8289,8288 ,8113,8115,8112 ,0,0,0}, - {6462,8288,6463 ,8113,8112,8111 ,0,0,0}, {6465,6463,8287 ,8119,8111,8110 ,0,0,0}, - {6424,8299,8289 ,8114,8134,8115 ,0,0,0}, {8299,6424,6426 ,8134,8114,8107 ,0,0,0}, - {8286,8284,6434 ,8108,8106,8105 ,0,0,0}, {8284,8299,6426 ,8106,8134,8107 ,0,0,0}, - {6606,8286,6434 ,8109,8108,8105 ,0,0,0}, {6582,8281,8285 ,4474,4475,4472 ,0,0,0}, - {6582,8285,6606 ,4474,4472,8109 ,0,0,0}, {6601,6603,8282 ,8101,8103,8102 ,0,0,0}, - {6582,6601,8281 ,4474,8101,4475 ,0,0,0}, {6600,8280,8283 ,8104,8100,4478 ,0,0,0}, - {8282,6603,8283 ,8102,8103,4478 ,0,0,0}, {4952,6602,4950 ,1359,4482,1359 ,0,0,0}, - {8280,6600,6602 ,8100,8104,4482 ,0,0,0}, {4946,8284,8286 ,726,726,726 ,0,0,0}, - {8292,4953,8293 ,726,7626,7758 ,0,0,0}, {8298,8297,8296 ,7625,7625,726 ,0,0,0}, - {8294,8290,4933 ,8135,7628,7626 ,0,0,0}, {4933,4931,8294 ,7626,7626,8135 ,0,0,0}, - {4943,8288,8289 ,726,7627,726 ,0,0,0}, {4936,8287,4937 ,726,7628,726 ,0,0,0}, - {4940,8284,4946 ,726,726,726 ,0,0,0}, {8289,8299,4945 ,726,726,726 ,0,0,0}, - {8281,8282,8283 ,7628,7628,726 ,0,0,0}, {4949,4946,8286 ,726,726,726 ,0,0,0}, - {4952,4949,8280 ,726,726,726 ,0,0,0}, {8280,8281,8283 ,726,7628,726 ,0,0,0}, - {8280,4949,8281 ,726,726,7628 ,0,0,0}, {8286,8285,4949 ,726,726,726 ,0,0,0}, - {4949,8285,8281 ,726,726,7628 ,0,0,0}, {8284,4940,4945 ,726,726,726 ,0,0,0}, - {4949,4948,4946 ,726,726,726 ,0,0,0}, {4945,4943,8289 ,726,726,726 ,0,0,0}, - {4945,8299,8284 ,726,726,726 ,0,0,0}, {8287,8288,4937 ,7628,7627,726 ,0,0,0}, - {4937,8288,4943 ,726,7627,726 ,0,0,0}, {4934,8291,4936 ,726,726,726 ,0,0,0}, - {4936,8291,8287 ,726,726,7628 ,0,0,0}, {4934,4933,8290 ,726,7626,7628 ,0,0,0}, - {8290,8291,4934 ,7628,726,726 ,0,0,0}, {4931,4953,8292 ,7626,7626,726 ,0,0,0}, - {4931,8292,8294 ,7626,726,8135 ,0,0,0}, {4954,8293,4953 ,7626,7758,7626 ,0,0,0}, - {8295,8293,4957 ,8135,7758,7628 ,0,0,0}, {4954,4957,8293 ,7626,7628,7758 ,0,0,0}, - {4957,4959,8296 ,7628,726,726 ,0,0,0}, {8296,8295,4957 ,726,8135,7628 ,0,0,0}, - {8298,4959,4960 ,7625,726,7626 ,0,0,0}, {4959,8298,8296 ,726,7625,726 ,0,0,0}, - {4963,4966,4969 ,7626,726,7626 ,0,0,0}, {4960,4963,8298 ,7626,7626,7625 ,0,0,0}, - {4969,8298,4963 ,7626,7625,7626 ,0,0,0}, {4963,4965,4966 ,7626,7627,726 ,0,0,0}, - {8298,4969,4971 ,7625,7626,8135 ,0,0,0}, {4913,8300,6588 ,1359,8136,8137 ,0,0,0}, - {6571,6573,8301 ,8138,8139,8140 ,0,0,0}, {6590,6592,8302 ,8141,8142,8143 ,0,0,0}, - {6378,8303,6377 ,8144,8145,8146 ,0,0,0}, {8304,8305,6572 ,8147,8148,8149 ,0,0,0}, - {8306,8307,6570 ,8150,8151,8152 ,0,0,0}, {8306,6569,8308 ,8150,8153,8154 ,0,0,0}, - {8309,8310,6502 ,8155,8156,8157 ,0,0,0}, {6502,6501,8309 ,8157,8158,8155 ,0,0,0}, - {6416,8310,8311 ,8159,8156,8160 ,0,0,0}, {8310,6416,6502 ,8156,8159,8157 ,0,0,0}, - {8312,6415,8311 ,8161,8162,8160 ,0,0,0}, {6416,8311,6415 ,8159,8160,8162 ,0,0,0}, - {8312,4927,4928 ,8161,1435,1435 ,0,0,0}, {4928,6415,8312 ,1435,8162,8161 ,0,0,0}, - {8303,6378,8305 ,8145,8144,8148 ,0,0,0}, {8307,6501,6570 ,8151,8158,8152 ,0,0,0}, - {8309,6501,8307 ,8155,8158,8151 ,0,0,0}, {8301,6573,8313 ,8140,8139,8163 ,0,0,0}, - {8308,6569,6377 ,8154,8153,8146 ,0,0,0}, {8306,6570,6569 ,8150,8152,8153 ,0,0,0}, - {8303,8308,6377 ,8145,8154,8146 ,0,0,0}, {6572,8305,6378 ,8149,8148,8144 ,0,0,0}, - {6571,8301,8304 ,8138,8140,8147 ,0,0,0}, {8304,6572,6571 ,8147,8149,8138 ,0,0,0}, - {6592,8300,8302 ,8142,8136,8143 ,0,0,0}, {8313,6590,8302 ,8163,8141,8143 ,0,0,0}, - {6573,6590,8313 ,8139,8141,8163 ,0,0,0}, {4913,6588,4914 ,1359,8137,1359 ,0,0,0}, - {8300,6592,6588 ,8136,8142,8137 ,0,0,0}, {8310,8305,8304 ,726,7661,7661 ,0,0,0}, - {8306,8308,8309 ,7661,7658,726 ,0,0,0}, {8309,8307,8306 ,726,726,7661 ,0,0,0}, - {8303,8305,8309 ,7658,7661,726 ,0,0,0}, {8303,8309,8308 ,7658,726,7658 ,0,0,0}, - {8304,8311,8310 ,7661,726,726 ,0,0,0}, {8305,8310,8309 ,7661,726,726 ,0,0,0}, - {8311,8304,8301 ,726,7661,7658 ,0,0,0}, {8301,8313,8312 ,7658,7661,726 ,0,0,0}, - {8312,8311,8301 ,726,726,7658 ,0,0,0}, {4927,8313,8302 ,726,7661,7658 ,0,0,0}, - {8313,4927,8312 ,7661,726,726 ,0,0,0}, {4912,4921,4913 ,7658,726,726 ,0,0,0}, - {8300,4925,8302 ,7658,7660,7658 ,0,0,0}, {4919,4912,4910 ,726,7658,726 ,0,0,0}, - {4900,4899,4906 ,726,726,726 ,0,0,0}, {4916,4908,4915 ,726,726,726 ,0,0,0}, - {4906,4903,4902 ,726,726,726 ,0,0,0}, {4906,4899,4915 ,726,726,726 ,0,0,0}, - {4900,4906,4902 ,726,726,726 ,0,0,0}, {4910,4908,4916 ,726,726,726 ,0,0,0}, - {4908,4906,4915 ,726,726,726 ,0,0,0}, {4921,4912,4919 ,726,7658,726 ,0,0,0}, - {4919,4910,4916 ,726,726,726 ,0,0,0}, {4913,4922,8300 ,726,726,7658 ,0,0,0}, - {4913,4921,4922 ,726,726,726 ,0,0,0}, {8302,4925,4927 ,7658,7660,726 ,0,0,0}, - {4922,4925,8300 ,726,7660,7658 ,0,0,0}, {8314,8315,7782 ,726,726,7664 ,0,0,0}, - {8316,8314,7782 ,726,726,7664 ,0,0,0}, {8316,7782,8317 ,726,7664,726 ,0,0,0}, - {8318,7782,8315 ,726,7664,726 ,0,0,0}, {8319,8320,7782 ,726,726,7664 ,0,0,0}, - {8319,7782,8318 ,726,7664,726 ,0,0,0}, {8321,7782,7780 ,726,7664,726 ,0,0,0}, - {8317,7782,8321 ,726,7664,726 ,0,0,0}, {8322,7782,8320 ,726,7664,726 ,0,0,0}, - {7782,8322,8323 ,7664,726,726 ,0,0,0}, {8321,7780,8324 ,726,726,726 ,0,0,0}, - {8325,7782,8323 ,726,7664,726 ,0,0,0}, {8326,8324,7780 ,7583,726,726 ,0,0,0}, - {7780,8327,8326 ,726,7664,7583 ,0,0,0}, {7782,8325,8328 ,7664,726,726 ,0,0,0}, - {7782,8328,8329 ,7664,726,726 ,0,0,0}, {8330,8327,7780 ,726,7664,726 ,0,0,0}, - {8331,8332,7780 ,726,726,726 ,0,0,0}, {8332,8330,7780 ,726,726,726 ,0,0,0}, - {8333,7780,8334 ,726,726,726 ,0,0,0}, {8333,8331,7780 ,726,726,726 ,0,0,0}, - {7783,8329,6720 ,7664,726,726 ,0,0,0}, {8329,7783,7782 ,726,7664,7664 ,0,0,0}, - {8334,7780,8335 ,726,726,726 ,0,0,0}, {8336,7780,7781 ,726,726,7664 ,0,0,0}, - {7780,8336,8335 ,726,726,726 ,0,0,0}, {8336,7781,6644 ,726,7664,5488 ,0,0,0}, - {6432,6425,8314 ,8164,8165,8166 ,0,0,0}, {8316,6433,6432 ,8167,8168,8164 ,0,0,0}, - {8316,8317,6433 ,8167,8168,8168 ,0,0,0}, {8314,8316,6432 ,8166,8167,8164 ,0,0,0}, - {6425,6566,8315 ,8165,8169,8170 ,0,0,0}, {6464,6466,8319 ,8171,8172,8173 ,0,0,0}, - {8318,8315,6566 ,8174,8170,8169 ,0,0,0}, {6566,6464,8318 ,8169,8171,8174 ,0,0,0}, - {8319,8318,6464 ,8173,8174,8171 ,0,0,0}, {6425,8315,8314 ,8165,8170,8166 ,0,0,0}, - {8319,6466,8320 ,8173,8172,8175 ,0,0,0}, {6429,8322,8320 ,8176,8177,8175 ,0,0,0}, - {8320,6466,6429 ,8175,8172,8176 ,0,0,0}, {8322,6429,6431 ,8177,8176,8178 ,0,0,0}, - {6436,8323,6431 ,8179,8180,8178 ,0,0,0}, {6436,6468,8325 ,8179,8181,8182 ,0,0,0}, - {6436,8325,8323 ,8179,8182,8180 ,0,0,0}, {8328,6470,8329 ,8183,8184,8185 ,0,0,0}, - {8325,6468,8328 ,8182,8181,8183 ,0,0,0}, {8328,6468,6470 ,8183,8181,8184 ,0,0,0}, - {6470,6469,8329 ,8184,8185,8185 ,0,0,0}, {8322,6431,8323 ,8177,8178,8180 ,0,0,0}, - {6428,8317,8321 ,8186,8168,8187 ,0,0,0}, {8317,6428,6433 ,8168,8186,8168 ,0,0,0}, - {8324,6427,8321 ,8188,8189,8187 ,0,0,0}, {6428,8321,6427 ,8186,8187,8189 ,0,0,0}, - {8324,8326,6594 ,8188,8190,8191 ,0,0,0}, {6594,6427,8324 ,8191,8189,8188 ,0,0,0}, - {6422,8326,8327 ,8192,8190,8193 ,0,0,0}, {8326,6422,6594 ,8190,8192,8191 ,0,0,0}, - {8330,6423,8327 ,8194,8195,8193 ,0,0,0}, {6422,8327,6423 ,8192,8193,8195 ,0,0,0}, - {8330,8332,6496 ,8194,8196,8197 ,0,0,0}, {6496,6423,8330 ,8197,8195,8194 ,0,0,0}, - {6497,8332,8331 ,8198,8196,8199 ,0,0,0}, {8332,6497,6496 ,8196,8198,8197 ,0,0,0}, - {8333,6240,8331 ,8200,8201,8199 ,0,0,0}, {6497,8331,6240 ,8198,8199,8201 ,0,0,0}, - {8333,8334,6243 ,8200,8202,8203 ,0,0,0}, {6243,6240,8333 ,8203,8201,8200 ,0,0,0}, - {6244,8334,8335 ,8204,8202,8205 ,0,0,0}, {8334,6244,6243 ,8202,8204,8203 ,0,0,0}, - {6244,8335,6245 ,8204,8205,8206 ,0,0,0}, {6245,8335,8336 ,8206,8205,8206 ,0,0,0}, - {6645,8336,6644 ,8207,8207,8207 ,0,0,0}, {8336,6675,6678 ,8207,8207,8207 ,0,0,0}, - {6645,6675,8336 ,8207,8207,8207 ,0,0,0}, {8336,6684,6689 ,8207,8207,8207 ,0,0,0}, - {6678,6684,8336 ,8207,8207,8207 ,0,0,0}, {8336,6693,6623 ,8207,8207,8207 ,0,0,0}, - {6689,6693,8336 ,8207,8207,8207 ,0,0,0}, {8336,6626,6625 ,8207,8207,8207 ,0,0,0}, - {6623,6626,8336 ,8207,8207,8207 ,0,0,0}, {8336,6625,6245 ,8207,8207,8207 ,0,0,0}, - {6735,8329,6469 ,8208,8208,8208 ,0,0,0}, {6735,6786,8329 ,8208,8208,8208 ,0,0,0}, - {8329,6786,6772 ,8208,8208,8208 ,0,0,0}, {6729,6722,8329 ,8208,8208,8208 ,0,0,0}, - {6729,8329,6772 ,8208,8208,8208 ,0,0,0}, {6722,6768,8329 ,8208,8208,8208 ,0,0,0}, - {8329,6760,6714 ,8208,8208,8208 ,0,0,0}, {6768,6760,8329 ,8208,8208,8208 ,0,0,0}, - {6720,8329,6716 ,8208,8208,8208 ,0,0,0}, {6714,6716,8329 ,8208,8208,8208 ,0,0,0}, - {4876,8337,6232 ,1711,8209,4414 ,0,0,0}, {8338,6495,8339 ,8210,8211,8212 ,0,0,0}, - {6480,6233,8340 ,8213,8214,4410 ,0,0,0}, {6494,8341,6224 ,4402,8215,8216 ,0,0,0}, - {8342,8343,6493 ,8217,8218,8219 ,0,0,0}, {8344,6254,8345 ,8220,8221,8222 ,0,0,0}, - {6253,6479,8346 ,8223,8224,8225 ,0,0,0}, {6227,6226,8347 ,8226,8227,8228 ,0,0,0}, - {6249,8348,6226 ,8229,8230,8227 ,0,0,0}, {6230,8349,8350 ,8231,8232,8233 ,0,0,0}, - {6227,8351,6229 ,8226,8234,8235 ,0,0,0}, {8352,6246,8350 ,8236,8237,8233 ,0,0,0}, - {6230,8350,6246 ,8231,8233,8237 ,0,0,0}, {8352,8353,6234 ,8236,8238,8239 ,0,0,0}, - {6234,6246,8352 ,8239,8237,8236 ,0,0,0}, {6482,8353,8354 ,8240,8238,8241 ,0,0,0}, - {8353,6482,6234 ,8238,8240,8239 ,0,0,0}, {8355,6242,8354 ,8242,8243,8241 ,0,0,0}, - {6482,8354,6242 ,8240,8241,8243 ,0,0,0}, {8355,4895,4896 ,8242,1790,1790 ,0,0,0}, - {4896,6242,8355 ,1790,8243,8242 ,0,0,0}, {8347,6226,8348 ,8228,8227,8230 ,0,0,0}, - {8349,6229,8351 ,8232,8235,8234 ,0,0,0}, {6229,8349,6230 ,8235,8232,8231 ,0,0,0}, - {8347,8351,6227 ,8228,8234,8226 ,0,0,0}, {8344,8348,6249 ,8220,8230,8229 ,0,0,0}, - {6253,8346,8345 ,8223,8225,8222 ,0,0,0}, {6253,8345,6254 ,8223,8222,8221 ,0,0,0}, - {6249,6254,8344 ,8229,8221,8220 ,0,0,0}, {6479,8356,8346 ,8224,8244,8225 ,0,0,0}, - {8356,6479,6224 ,8244,8224,8216 ,0,0,0}, {8343,8341,6494 ,8218,8215,4402 ,0,0,0}, - {8341,8356,6224 ,8215,8244,8216 ,0,0,0}, {6493,8343,6494 ,8219,8218,4402 ,0,0,0}, - {6194,8338,8342 ,8245,8210,8217 ,0,0,0}, {6194,8342,6493 ,8245,8217,8219 ,0,0,0}, - {6495,6480,8339 ,8211,8213,8212 ,0,0,0}, {6194,6495,8338 ,8245,8211,8210 ,0,0,0}, - {6233,8337,8340 ,8214,8209,4410 ,0,0,0}, {8339,6480,8340 ,8212,8213,4410 ,0,0,0}, - {4876,6232,4874 ,1711,4414,1711 ,0,0,0}, {8337,6233,6232 ,8209,8214,4414 ,0,0,0}, - {8342,8347,8348 ,726,726,7626 ,0,0,0}, {8356,8345,8346 ,726,726,726 ,0,0,0}, - {8344,8356,8341 ,726,726,726 ,0,0,0}, {8343,8344,8341 ,726,726,726 ,0,0,0}, - {8343,8348,8344 ,726,7626,726 ,0,0,0}, {8356,8344,8345 ,726,726,726 ,0,0,0}, - {8343,8342,8348 ,726,726,7626 ,0,0,0}, {8338,8351,8347 ,726,726,726 ,0,0,0}, - {8342,8338,8347 ,726,726,726 ,0,0,0}, {8351,8339,8349 ,726,726,7626 ,0,0,0}, - {8339,8351,8338 ,726,726,726 ,0,0,0}, {8350,8349,8340 ,7628,7626,726 ,0,0,0}, - {8339,8340,8349 ,726,726,7626 ,0,0,0}, {8337,8352,8350 ,726,726,7628 ,0,0,0}, - {8350,8340,8337 ,7628,726,726 ,0,0,0}, {8352,4876,8353 ,726,726,726 ,0,0,0}, - {4876,8352,8337 ,726,726,726 ,0,0,0}, {8354,8353,4873 ,7625,726,726 ,0,0,0}, - {4876,4873,8353 ,726,726,726 ,0,0,0}, {8354,4873,4872 ,7625,726,726 ,0,0,0}, - {8355,8354,4872 ,726,7625,726 ,0,0,0}, {4872,4870,8355 ,726,726,726 ,0,0,0}, - {4864,4895,4870 ,726,726,726 ,0,0,0}, {8355,4870,4895 ,726,726,726 ,0,0,0}, - {4867,4861,4889 ,726,726,7625 ,0,0,0}, {4864,4869,4893 ,726,726,726 ,0,0,0}, - {4858,4883,4884 ,7626,726,726 ,0,0,0}, {4884,4887,4860 ,726,726,726 ,0,0,0}, - {4883,4857,4881 ,726,7625,7625 ,0,0,0}, {4857,4878,4881 ,7625,726,7625 ,0,0,0}, - {4855,4878,4857 ,726,726,7625 ,0,0,0}, {4855,4877,4878 ,726,726,726 ,0,0,0}, - {4860,4858,4884 ,726,7626,726 ,0,0,0}, {4857,4883,4858 ,7625,726,7626 ,0,0,0}, - {4887,4889,4861 ,726,7625,726 ,0,0,0}, {4860,4887,4861 ,726,726,726 ,0,0,0}, - {4867,4890,4869 ,726,726,726 ,0,0,0}, {4867,4889,4890 ,726,7625,726 ,0,0,0}, - {4864,4893,4895 ,726,726,726 ,0,0,0}, {4890,4893,4869 ,726,726,726 ,0,0,0}, - {4837,8357,6506 ,1711,8246,8247 ,0,0,0}, {6565,6579,8358 ,8248,8249,8250 ,0,0,0}, - {6578,6507,8359 ,8251,8252,8253 ,0,0,0}, {6418,8360,6417 ,8254,8255,8256 ,0,0,0}, - {8361,8362,6599 ,8257,8258,8259 ,0,0,0}, {8363,8364,6597 ,8260,8261,8262 ,0,0,0}, - {8363,6596,8365 ,8260,8263,8264 ,0,0,0}, {8366,8367,6499 ,8265,8266,8267 ,0,0,0}, - {6499,6500,8366 ,8267,8268,8265 ,0,0,0}, {6595,8367,8368 ,8269,8266,8270 ,0,0,0}, - {8367,6595,6499 ,8266,8269,8267 ,0,0,0}, {8369,6498,8368 ,8271,8272,8270 ,0,0,0}, - {6595,8368,6498 ,8269,8270,8272 ,0,0,0}, {8369,4851,4852 ,8271,1790,1790 ,0,0,0}, - {4852,6498,8369 ,1790,8272,8271 ,0,0,0}, {8360,6418,8362 ,8255,8254,8258 ,0,0,0}, - {8364,6500,6597 ,8261,8268,8262 ,0,0,0}, {8366,6500,8364 ,8265,8268,8261 ,0,0,0}, - {8358,6579,8370 ,8250,8249,8273 ,0,0,0}, {8365,6596,6417 ,8264,8263,8256 ,0,0,0}, - {8363,6597,6596 ,8260,8262,8263 ,0,0,0}, {8360,8365,6417 ,8255,8264,8256 ,0,0,0}, - {6599,8362,6418 ,8259,8258,8254 ,0,0,0}, {6565,8358,8361 ,8248,8250,8257 ,0,0,0}, - {8361,6599,6565 ,8257,8259,8248 ,0,0,0}, {6507,8357,8359 ,8252,8246,8253 ,0,0,0}, - {8370,6578,8359 ,8273,8251,8253 ,0,0,0}, {6579,6578,8370 ,8249,8251,8273 ,0,0,0}, - {4837,6506,4838 ,1711,8247,1711 ,0,0,0}, {8357,6507,6506 ,8246,8252,8247 ,0,0,0}, - {4851,8369,8368 ,726,7658,726 ,0,0,0}, {8370,4826,8358 ,726,726,726 ,0,0,0}, - {4849,8368,8367 ,7660,726,7660 ,0,0,0}, {8363,4845,8364 ,7660,726,7660 ,0,0,0}, - {4846,4849,8366 ,7660,7660,7583 ,0,0,0}, {4839,8360,8362 ,7660,7661,7661 ,0,0,0}, - {4843,8363,8365 ,726,7660,7658 ,0,0,0}, {4824,8358,4826 ,726,726,726 ,0,0,0}, - {8362,8361,4823 ,7661,726,726 ,0,0,0}, {8357,4832,4830 ,726,726,726 ,0,0,0}, - {8359,4827,8370 ,726,726,726 ,0,0,0}, {4837,4836,4832 ,726,726,726 ,0,0,0}, - {4834,4832,4836 ,726,726,726 ,0,0,0}, {4832,8357,4837 ,726,726,726 ,0,0,0}, - {8359,4830,4827 ,726,726,726 ,0,0,0}, {8359,8357,4830 ,726,726,726 ,0,0,0}, - {8361,8358,4824 ,726,726,726 ,0,0,0}, {4826,8370,4827 ,726,726,726 ,0,0,0}, - {4823,4839,8362 ,726,7660,7661 ,0,0,0}, {4824,4823,8361 ,726,726,726 ,0,0,0}, - {8365,8360,4840 ,7658,7661,7659 ,0,0,0}, {4840,8360,4839 ,7659,7661,7660 ,0,0,0}, - {4843,8365,4840 ,726,7658,7659 ,0,0,0}, {4846,8364,4845 ,7660,7660,726 ,0,0,0}, - {8363,4843,4845 ,7660,726,726 ,0,0,0}, {4849,8367,8366 ,7660,7660,7583 ,0,0,0}, - {4846,8366,8364 ,7660,7583,7660 ,0,0,0}, {4849,4851,8368 ,7660,726,726 ,0,0,0}, - {6604,4796,8371 ,8274,8275,8276 ,0,0,0}, {6605,6581,8372 ,8277,8278,8279 ,0,0,0}, - {8373,6581,6598 ,8280,8278,8281 ,0,0,0}, {8374,8375,6505 ,8282,8283,8284 ,0,0,0}, - {8376,6577,6576 ,8285,8286,8287 ,0,0,0}, {6586,6574,8377 ,8288,8289,8290 ,0,0,0}, - {6585,8378,8379 ,8291,8292,8293 ,0,0,0}, {6608,8380,6591 ,8294,8295,8296 ,0,0,0}, - {8381,8382,6587 ,1631,8297,1631 ,0,0,0}, {8383,8384,6589 ,8298,8299,8300 ,0,0,0}, - {8383,6609,8385 ,8298,8301,8302 ,0,0,0}, {8386,8387,6584 ,8303,8304,8305 ,0,0,0}, - {8386,6583,8384 ,8303,8306,8299 ,0,0,0}, {6522,8387,8388 ,8307,8304,8308 ,0,0,0}, - {8387,6522,6584 ,8304,8307,8305 ,0,0,0}, {8389,6563,8388 ,8309,8310,8308 ,0,0,0}, - {6522,8388,6563 ,8307,8308,8310 ,0,0,0}, {6504,8389,6557 ,8311,8309,8312 ,0,0,0}, - {6504,6563,8389 ,8311,8310,8309 ,0,0,0}, {6555,6557,8390 ,8313,8312,8314 ,0,0,0}, - {8389,8390,6557 ,8309,8314,8312 ,0,0,0}, {8391,4820,6555 ,8315,126,8313 ,0,0,0}, - {6555,8390,8391 ,8313,8314,8315 ,0,0,0}, {4818,4820,8391 ,126,126,8315 ,0,0,0}, - {6583,6589,8384 ,8306,8300,8299 ,0,0,0}, {8386,6584,6583 ,8303,8305,8306 ,0,0,0}, - {6609,6591,8385 ,8301,8296,8302 ,0,0,0}, {8383,6589,6609 ,8298,8300,8301 ,0,0,0}, - {8382,8380,6608 ,8297,8295,8294 ,0,0,0}, {8380,8385,6591 ,8295,8302,8296 ,0,0,0}, - {6586,8381,6587 ,8288,1631,1631 ,0,0,0}, {6587,8382,6608 ,1631,8297,8294 ,0,0,0}, - {6574,8379,8377 ,8289,8293,8290 ,0,0,0}, {6586,8377,8381 ,8288,8290,1631 ,0,0,0}, - {6585,6607,8378 ,8291,8316,8292 ,0,0,0}, {6574,6585,8379 ,8289,8291,8293 ,0,0,0}, - {6505,8375,6607 ,8284,8283,8316 ,0,0,0}, {8378,6607,8375 ,8292,8316,8283 ,0,0,0}, - {8376,8374,6577 ,8285,8282,8286 ,0,0,0}, {8374,6505,6577 ,8282,8284,8286 ,0,0,0}, - {6605,8392,6576 ,8277,8317,8287 ,0,0,0}, {8392,8376,6576 ,8317,8285,8287 ,0,0,0}, - {6581,8393,8372 ,8278,8318,8279 ,0,0,0}, {6605,8372,8392 ,8277,8279,8317 ,0,0,0}, - {8373,6598,8371 ,8280,8281,8276 ,0,0,0}, {8393,6581,8373 ,8318,8278,8280 ,0,0,0}, - {4796,6604,4795 ,8275,8274,4114 ,0,0,0}, {8371,6598,6604 ,8276,8281,8274 ,0,0,0}, - {8383,8394,8384 ,726,726,726 ,0,0,0}, {8395,4769,8391 ,726,726,726 ,0,0,0}, - {8396,8387,8397 ,726,726,726 ,0,0,0}, {4800,4754,4753 ,726,726,7661 ,0,0,0}, - {4809,4811,4763 ,726,726,726 ,0,0,0}, {8398,8390,8389 ,726,726,726 ,0,0,0}, - {4814,4817,4768 ,726,726,726 ,0,0,0}, {4818,4769,4817 ,726,726,726 ,0,0,0}, - {4766,4764,4815 ,7658,726,726 ,0,0,0}, {4814,4768,4766 ,726,726,7658 ,0,0,0}, - {8398,8395,8390 ,726,726,726 ,0,0,0}, {4811,4812,4764 ,726,726,726 ,0,0,0}, - {4809,4763,4760 ,726,726,726 ,0,0,0}, {4805,4758,4803 ,726,726,726 ,0,0,0}, - {4806,4760,4758 ,726,726,726 ,0,0,0}, {4754,4800,4803 ,726,726,726 ,0,0,0}, - {8396,8389,8388 ,726,726,726 ,0,0,0}, {8384,8399,8386 ,726,7661,726 ,0,0,0}, - {8386,8399,8397 ,726,7661,726 ,0,0,0}, {4733,4773,4772 ,7658,726,7658 ,0,0,0}, - {4799,4753,4733 ,726,7661,7658 ,0,0,0}, {8400,8394,8385 ,726,726,726 ,0,0,0}, - {4773,4737,4774 ,726,7658,726 ,0,0,0}, {4776,4738,4739 ,7661,7658,726 ,0,0,0}, - {8380,8382,8401 ,726,7661,726 ,0,0,0}, {8380,8401,8400 ,726,726,726 ,0,0,0}, - {8382,8381,8402 ,7661,7658,7658 ,0,0,0}, {4780,4779,4739 ,726,726,726 ,0,0,0}, - {4743,4782,4740 ,726,7583,726 ,0,0,0}, {8403,8404,8379 ,726,726,726 ,0,0,0}, - {8404,8402,8377 ,726,7658,726 ,0,0,0}, {4792,4746,4749 ,7664,726,7664 ,0,0,0}, - {8403,8379,8378 ,726,726,7661 ,0,0,0}, {8405,8378,8375 ,726,7661,7664 ,0,0,0}, - {4752,4796,4794 ,726,726,7664 ,0,0,0}, {8406,8371,4752 ,7664,726,726 ,0,0,0}, - {8405,8374,8407 ,726,7583,726 ,0,0,0}, {8373,8408,8393 ,7664,7664,726 ,0,0,0}, - {4774,4737,4738 ,726,7658,7658 ,0,0,0}, {8372,8393,8409 ,7664,726,7664 ,0,0,0}, - {8408,8409,8393 ,7664,7664,726 ,0,0,0}, {8373,8371,8406 ,7664,726,7664 ,0,0,0}, - {8373,8406,8408 ,7664,7664,7664 ,0,0,0}, {8410,8407,8376 ,7664,726,7583 ,0,0,0}, - {8410,8376,8392 ,7664,7583,7664 ,0,0,0}, {4796,4752,8371 ,726,726,726 ,0,0,0}, - {4745,4746,4788 ,726,726,726 ,0,0,0}, {4743,4745,4785 ,726,726,7664 ,0,0,0}, - {8410,8392,8409 ,7664,7664,7664 ,0,0,0}, {8392,8372,8409 ,7664,7664,7664 ,0,0,0}, - {8374,8376,8407 ,7583,7583,726 ,0,0,0}, {8375,8374,8405 ,7664,7583,726 ,0,0,0}, - {8403,8378,8405 ,726,7661,726 ,0,0,0}, {8377,8379,8404 ,726,726,726 ,0,0,0}, - {8381,8377,8402 ,7658,726,7658 ,0,0,0}, {8401,8382,8402 ,726,7661,7658 ,0,0,0}, - {8385,8380,8400 ,726,726,726 ,0,0,0}, {8383,8385,8394 ,726,726,726 ,0,0,0}, - {8399,8384,8394 ,7661,726,726 ,0,0,0}, {8387,8386,8397 ,726,726,726 ,0,0,0}, - {8388,8387,8396 ,726,726,726 ,0,0,0}, {8398,8389,8396 ,726,726,726 ,0,0,0}, - {8391,8390,8395 ,726,726,726 ,0,0,0}, {4818,8391,4769 ,726,726,726 ,0,0,0}, - {4768,4817,4769 ,726,726,726 ,0,0,0}, {4815,4814,4766 ,726,726,7658 ,0,0,0}, - {4812,4815,4764 ,726,726,726 ,0,0,0}, {4763,4811,4764 ,726,726,726 ,0,0,0}, - {4806,4809,4760 ,726,726,726 ,0,0,0}, {4805,4806,4758 ,726,726,726 ,0,0,0}, - {4754,4803,4758 ,726,726,726 ,0,0,0}, {4799,4800,4753 ,726,726,7661 ,0,0,0}, - {4772,4799,4733 ,7658,726,7658 ,0,0,0}, {4737,4773,4733 ,7658,726,7658 ,0,0,0}, - {4779,4776,4739 ,726,7661,726 ,0,0,0}, {4776,4774,4738 ,7661,726,7658 ,0,0,0}, - {4740,4780,4739 ,726,726,726 ,0,0,0}, {4743,4785,4782 ,726,7664,7583 ,0,0,0}, - {4740,4782,4780 ,726,7583,726 ,0,0,0}, {4745,4786,4785 ,726,7664,7664 ,0,0,0}, - {4788,4746,4792 ,726,726,7664 ,0,0,0}, {4786,4745,4788 ,7664,726,726 ,0,0,0}, - {4792,4749,4794 ,7664,7664,7664 ,0,0,0}, {4752,4794,4749 ,726,7664,7664 ,0,0,0}, - {8411,8412,4736 ,726,726,726 ,0,0,0}, {4755,4757,4765 ,726,726,726 ,0,0,0}, - {4734,4755,4770 ,726,726,726 ,0,0,0}, {4736,4735,8411 ,726,726,726 ,0,0,0}, - {4761,4762,4765 ,726,726,726 ,0,0,0}, {4756,4759,4757 ,726,726,726 ,0,0,0}, - {4761,4765,4759 ,726,726,726 ,0,0,0}, {4757,4759,4765 ,726,726,726 ,0,0,0}, - {4765,4767,4755 ,726,726,726 ,0,0,0}, {8411,4734,4770 ,726,726,726 ,0,0,0}, - {4770,4755,4767 ,726,726,726 ,0,0,0}, {4736,8412,8413 ,726,726,726 ,0,0,0}, - {8411,4735,4734 ,726,726,726 ,0,0,0}, {4741,8413,8414 ,726,726,726 ,0,0,0}, - {8413,4741,4736 ,726,726,726 ,0,0,0}, {8414,4744,4742 ,726,726,7658 ,0,0,0}, - {4741,8414,4742 ,726,726,7658 ,0,0,0}, {8415,4744,8414 ,726,726,726 ,0,0,0}, - {4744,8416,4747 ,726,726,7661 ,0,0,0}, {8416,4744,8415 ,726,726,726 ,0,0,0}, - {8416,8417,4747 ,726,726,7661 ,0,0,0}, {4748,8417,4750 ,726,726,7661 ,0,0,0}, - {4748,4747,8417 ,726,7661,726 ,0,0,0}, {4750,8418,8419 ,7661,726,726 ,0,0,0}, - {8417,8418,4750 ,726,726,7661 ,0,0,0}, {8420,4751,8419 ,726,7658,726 ,0,0,0}, - {4750,8419,4751 ,7661,726,7658 ,0,0,0}, {8421,8422,8423 ,726,726,7660 ,0,0,0}, - {8423,8424,8421 ,7660,726,726 ,0,0,0}, {8422,8425,8426 ,726,726,7658 ,0,0,0}, - {8422,8420,8423 ,726,726,7660 ,0,0,0}, {8422,8427,8420 ,726,7661,726 ,0,0,0}, - {8422,8421,8425 ,726,726,726 ,0,0,0}, {8420,8427,4751 ,726,7661,7658 ,0,0,0}, - {8427,4752,4751 ,8319,81,8320 ,0,0,0}, {8425,8410,8426 ,8321,8322,8323 ,0,0,0}, - {8422,8409,8408 ,8324,8325,8326 ,0,0,0}, {8423,8420,8403 ,8327,8328,8329 ,0,0,0}, - {8421,8424,8405 ,8330,8331,8332 ,0,0,0}, {8417,8401,8418 ,8333,8334,8335 ,0,0,0}, - {8402,8419,8418 ,8336,8337,8335 ,0,0,0}, {8415,8399,8416 ,7530,8338,8339 ,0,0,0}, - {8394,8417,8416 ,8340,8333,8339 ,0,0,0}, {8414,8396,8397 ,8341,8342,8343 ,0,0,0}, - {8397,8415,8414 ,8343,7530,8341 ,0,0,0}, {8396,8413,8398 ,8342,8344,8345 ,0,0,0}, - {8413,8396,8414 ,8344,8342,8341 ,0,0,0}, {8395,8398,8412 ,8346,8345,8347 ,0,0,0}, - {8413,8412,8398 ,8344,8347,8345 ,0,0,0}, {4770,8395,8411 ,96,8346,8348 ,0,0,0}, - {8395,8412,8411 ,8346,8347,8348 ,0,0,0}, {4769,8395,4770 ,96,8346,96 ,0,0,0}, - {8394,8416,8399 ,8340,8339,8338 ,0,0,0}, {8397,8399,8415 ,8343,8338,7530 ,0,0,0}, - {8400,8401,8417 ,8349,8334,8333 ,0,0,0}, {8394,8400,8417 ,8340,8349,8333 ,0,0,0}, - {8404,8419,8402 ,8350,8337,8336 ,0,0,0}, {8401,8402,8418 ,8334,8336,8335 ,0,0,0}, - {8403,8420,8404 ,8329,8328,8350 ,0,0,0}, {8419,8404,8420 ,8337,8350,8328 ,0,0,0}, - {8405,8424,8403 ,8332,8331,8329 ,0,0,0}, {8424,8423,8403 ,8331,8327,8329 ,0,0,0}, - {8407,8425,8421 ,7516,8321,8330 ,0,0,0}, {8407,8421,8405 ,7516,8330,8332 ,0,0,0}, - {8410,8409,8426 ,8322,8325,8323 ,0,0,0}, {8407,8410,8425 ,7516,8322,8321 ,0,0,0}, - {8422,8408,8427 ,8324,8326,8319 ,0,0,0}, {8426,8409,8422 ,8323,8325,8324 ,0,0,0}, - {4752,8427,8406 ,81,8319,8351 ,0,0,0}, {8427,8408,8406 ,8319,8326,8351 ,0,0,0} -// MotorHacker.prt - , {8428,8429,8430 ,4056,4057,4058 ,0,0,0}, {8431,8432,8430 ,4059,4060,4058 ,0,0,0}, - {8428,8430,8432 ,4056,4058,4060 ,0,0,0}, {8433,8431,8434 ,4061,4059,4062 ,0,0,0}, - {8433,8432,8431 ,4061,4060,4059 ,0,0,0}, {8435,8434,8436 ,4063,4062,4064 ,0,0,0}, - {8431,8436,8434 ,4059,4064,4062 ,0,0,0}, {8437,8438,8435 ,4065,4066,4063 ,0,0,0}, - {8435,8436,8437 ,4063,4064,4065 ,0,0,0}, {8438,8439,8440 ,4066,4067,4068 ,0,0,0}, - {8439,8438,8437 ,4067,4066,4065 ,0,0,0}, {8441,8440,8442 ,4069,4068,4070 ,0,0,0}, - {8439,8442,8440 ,4067,4070,4068 ,0,0,0}, {8443,8444,8441 ,4071,4072,4069 ,0,0,0}, - {8441,8442,8443 ,4069,4070,4071 ,0,0,0}, {8445,8446,8444 ,4073,81,4072 ,0,0,0}, - {8445,8444,8443 ,4073,4072,4071 ,0,0,0}, {8446,8447,8444 ,81,81,4072 ,0,0,0}, - {8448,8429,8428 ,4074,4057,4056 ,0,0,0}, {8448,8449,8450 ,4074,4075,4076 ,0,0,0}, - {8450,8429,8448 ,4076,4057,4074 ,0,0,0}, {8451,8452,8449 ,4077,4078,4075 ,0,0,0}, - {8449,8452,8450 ,4075,4078,4076 ,0,0,0}, {8453,8454,8451 ,4079,4080,4077 ,0,0,0}, - {8451,8449,8453 ,4077,4075,4079 ,0,0,0}, {8454,8455,8456 ,4080,4081,4082 ,0,0,0}, - {8455,8454,8453 ,4081,4080,4079 ,0,0,0}, {8457,8456,8458 ,4083,4082,4084 ,0,0,0}, - {8455,8458,8456 ,4081,4084,4082 ,0,0,0}, {8459,8460,8457 ,4085,4086,4083 ,0,0,0}, - {8457,8458,8459 ,4083,4084,4085 ,0,0,0}, {8460,8461,8462 ,4086,4087,4088 ,0,0,0}, - {8461,8460,8459 ,4087,4086,4085 ,0,0,0}, {8462,8463,8464 ,4088,4089,4090 ,0,0,0}, - {8461,8463,8462 ,4087,4089,4088 ,0,0,0}, {8462,8464,8465 ,4088,4090,4091 ,0,0,0}, - {8466,8467,8468 ,2394,2394,4092 ,0,0,0}, {8469,8470,8468 ,4093,4094,4092 ,0,0,0}, - {8466,8468,8470 ,2394,4092,4094 ,0,0,0}, {8469,8471,8472 ,4093,4095,4096 ,0,0,0}, - {8472,8470,8469 ,4096,4094,4093 ,0,0,0}, {8473,8471,8474 ,4097,4095,4098 ,0,0,0}, - {8471,8473,8472 ,4095,4097,4096 ,0,0,0}, {8475,8476,8474 ,4099,4100,4098 ,0,0,0}, - {8473,8474,8476 ,4097,4098,4100 ,0,0,0}, {8475,8477,8478 ,4099,4101,4102 ,0,0,0}, - {8478,8476,8475 ,4102,4100,4099 ,0,0,0}, {8479,8477,8480 ,4103,4101,4104 ,0,0,0}, - {8477,8479,8478 ,4101,4103,4102 ,0,0,0}, {8481,8482,8480 ,4105,4106,4104 ,0,0,0}, - {8479,8480,8482 ,4103,4104,4106 ,0,0,0}, {8481,8483,8484 ,4105,4107,4108 ,0,0,0}, - {8484,8482,8481 ,4108,4106,4105 ,0,0,0}, {8485,8486,8483 ,4109,4110,4107 ,0,0,0}, - {8483,8486,8484 ,4107,4110,4108 ,0,0,0}, {8487,8488,8485 ,4111,4112,4109 ,0,0,0}, - {8485,8483,8487 ,4109,4107,4111 ,0,0,0}, {8488,8489,8490 ,4112,4113,4114 ,0,0,0}, - {8489,8488,8487 ,4113,4112,4111 ,0,0,0}, {8489,8491,8490 ,4113,4114,4114 ,0,0,0}, - {8492,8467,8466 ,4115,2394,2394 ,0,0,0}, {8492,8493,8494 ,4115,4116,4117 ,0,0,0}, - {8494,8467,8492 ,4117,2394,4115 ,0,0,0}, {8495,8493,8496 ,4118,4116,4119 ,0,0,0}, - {8493,8495,8494 ,4116,4118,4117 ,0,0,0}, {8497,8498,8496 ,4120,4121,4119 ,0,0,0}, - {8495,8496,8498 ,4118,4119,4121 ,0,0,0}, {8497,8499,8500 ,4120,4122,4123 ,0,0,0}, - {8500,8498,8497 ,4123,4121,4120 ,0,0,0}, {8501,8499,8502 ,4124,4122,4125 ,0,0,0}, - {8499,8501,8500 ,4122,4124,4123 ,0,0,0}, {8503,8504,8502 ,4126,4127,4125 ,0,0,0}, - {8501,8502,8504 ,4124,4125,4127 ,0,0,0}, {8503,8505,8506 ,4126,4128,4129 ,0,0,0}, - {8506,8504,8503 ,4129,4127,4126 ,0,0,0}, {8507,8505,8508 ,4130,4128,4131 ,0,0,0}, - {8505,8507,8506 ,4128,4130,4129 ,0,0,0}, {8508,8509,8510 ,4131,4132,4133 ,0,0,0}, - {8507,8508,8510 ,4130,4131,4133 ,0,0,0}, {8509,8511,8512 ,4132,4134,4135 ,0,0,0}, - {8511,8509,8508 ,4134,4132,4131 ,0,0,0}, {8513,8512,8514 ,126,4135,4136 ,0,0,0}, - {8511,8514,8512 ,4134,4136,4135 ,0,0,0}, {8513,8514,8515 ,126,4136,126 ,0,0,0}, - {8516,8517,8518 ,4137,4138,4139 ,0,0,0}, {8516,8519,8520 ,4137,4140,4141 ,0,0,0}, - {8519,8521,8520 ,4140,4142,4141 ,0,0,0}, {8518,8519,8516 ,4139,4140,4137 ,0,0,0}, - {8522,8523,8524 ,4143,4144,4145 ,0,0,0}, {8521,8522,8524 ,4142,4143,4145 ,0,0,0}, - {8523,8525,8526 ,4144,4146,4147 ,0,0,0}, {8525,8523,8522 ,4146,4144,4143 ,0,0,0}, - {8526,8525,8527 ,4147,4146,4148 ,0,0,0}, {8528,8526,8527 ,4149,4147,4148 ,0,0,0}, - {8528,8529,8530 ,4149,4150,4151 ,0,0,0}, {8528,8527,8529 ,4149,4148,4150 ,0,0,0}, - {8524,8520,8521 ,4145,4141,4142 ,0,0,0}, {8531,8532,8533 ,4152,1711,1711 ,0,0,0}, - {8531,8533,8530 ,4152,1711,4151 ,0,0,0}, {8529,8531,8530 ,4150,4152,4151 ,0,0,0}, - {8518,8517,8534 ,4139,4138,4153 ,0,0,0}, {8535,8534,8536 ,4154,4153,4155 ,0,0,0}, - {8517,8536,8534 ,4138,4155,4153 ,0,0,0}, {8537,8538,8535 ,4156,4157,4154 ,0,0,0}, - {8535,8536,8537 ,4154,4155,4156 ,0,0,0}, {8538,8539,8540 ,4157,4158,4159 ,0,0,0}, - {8539,8538,8537 ,4158,4157,4156 ,0,0,0}, {8541,8540,8542 ,4160,4159,4161 ,0,0,0}, - {8539,8542,8540 ,4158,4161,4159 ,0,0,0}, {8543,8544,8541 ,4162,4163,4160 ,0,0,0}, - {8541,8542,8543 ,4160,4161,4162 ,0,0,0}, {8544,8545,8546 ,4163,4164,1790 ,0,0,0}, - {8545,8544,8543 ,4164,4163,4162 ,0,0,0}, {8545,8547,8546 ,4164,1790,1790 ,0,0,0}, - {8548,8549,8550 ,4165,4166,4167 ,0,0,0}, {8551,8552,8553 ,4168,4169,4170 ,0,0,0}, - {8552,8548,8550 ,4169,4165,4167 ,0,0,0}, {8554,8551,8553 ,4171,4168,4170 ,0,0,0}, - {8552,8551,8548 ,4169,4168,4165 ,0,0,0}, {8554,8553,8555 ,4171,4170,4172 ,0,0,0}, - {8555,8556,8557 ,4172,4173,4174 ,0,0,0}, {8558,8557,8556 ,4175,4174,4173 ,0,0,0}, - {8559,8560,8561 ,4176,4177,4178 ,0,0,0}, {8556,8562,8558 ,4173,4179,4175 ,0,0,0}, - {8561,8563,8564 ,4178,4180,4181 ,0,0,0}, {8563,8562,8564 ,4180,4179,4181 ,0,0,0}, - {8558,8562,8563 ,4175,4179,4180 ,0,0,0}, {8561,8564,8559 ,4178,4181,4176 ,0,0,0}, - {8560,8559,8565 ,4177,4176,4182 ,0,0,0}, {8560,8565,8566 ,4177,4182,4183 ,0,0,0}, - {8567,8566,8565 ,4184,4183,4182 ,0,0,0}, {8568,8569,8570 ,4185,1711,4186 ,0,0,0}, - {8570,8566,8567 ,4186,4183,4184 ,0,0,0}, {8568,8570,8567 ,4185,4186,4184 ,0,0,0}, - {8568,8571,8569 ,4185,1711,1711 ,0,0,0}, {8554,8555,8557 ,4171,4172,4174 ,0,0,0}, - {8550,8549,8572 ,4167,4166,4187 ,0,0,0}, {8573,8572,8574 ,4188,4187,4189 ,0,0,0}, - {8549,8574,8572 ,4166,4189,4187 ,0,0,0}, {8575,8576,8573 ,4190,4191,4188 ,0,0,0}, - {8573,8574,8575 ,4188,4189,4190 ,0,0,0}, {8576,8577,8578 ,4191,4192,4193 ,0,0,0}, - {8577,8576,8575 ,4192,4191,4190 ,0,0,0}, {8579,8578,8580 ,4194,4193,4195 ,0,0,0}, - {8577,8580,8578 ,4192,4195,4193 ,0,0,0}, {8581,8582,8579 ,4196,4197,4194 ,0,0,0}, - {8579,8580,8581 ,4194,4195,4196 ,0,0,0}, {8582,8583,8584 ,4197,4198,4199 ,0,0,0}, - {8583,8582,8581 ,4198,4197,4196 ,0,0,0}, {8585,8584,8586 ,4200,4199,4201 ,0,0,0}, - {8583,8586,8584 ,4198,4201,4199 ,0,0,0}, {8587,8588,8585 ,4202,4203,4200 ,0,0,0}, - {8585,8586,8587 ,4200,4201,4202 ,0,0,0}, {8588,8589,8590 ,4203,4204,1790 ,0,0,0}, - {8589,8588,8587 ,4204,4203,4202 ,0,0,0}, {8589,8591,8590 ,4204,1790,1790 ,0,0,0}, - {8592,8593,8594 ,4205,4206,4207 ,0,0,0}, {8592,8595,8596 ,4205,4208,4209 ,0,0,0}, - {8595,8597,8596 ,4208,4210,4209 ,0,0,0}, {8594,8595,8592 ,4207,4208,4205 ,0,0,0}, - {8598,8599,8600 ,4211,4212,4213 ,0,0,0}, {8597,8598,8600 ,4210,4211,4213 ,0,0,0}, - {8599,8601,8602 ,4212,4214,4215 ,0,0,0}, {8601,8599,8598 ,4214,4212,4211 ,0,0,0}, - {8602,8601,8603 ,4215,4214,4216 ,0,0,0}, {8604,8602,8603 ,4217,4215,4216 ,0,0,0}, - {8604,8605,8606 ,4217,4218,4219 ,0,0,0}, {8604,8603,8605 ,4217,4216,4218 ,0,0,0}, - {8600,8596,8597 ,4213,4209,4210 ,0,0,0}, {8607,8608,8609 ,4220,1359,1359 ,0,0,0}, - {8607,8609,8606 ,4220,1359,4219 ,0,0,0}, {8605,8607,8606 ,4218,4220,4219 ,0,0,0}, - {8594,8593,8610 ,4207,4206,4221 ,0,0,0}, {8611,8610,8612 ,4222,4221,4223 ,0,0,0}, - {8593,8612,8610 ,4206,4223,4221 ,0,0,0}, {8613,8614,8611 ,4224,4225,4222 ,0,0,0}, - {8611,8612,8613 ,4222,4223,4224 ,0,0,0}, {8614,8615,8616 ,4225,4226,4227 ,0,0,0}, - {8615,8614,8613 ,4226,4225,4224 ,0,0,0}, {8617,8616,8618 ,4228,4227,4229 ,0,0,0}, - {8615,8618,8616 ,4226,4229,4227 ,0,0,0}, {8619,8620,8617 ,4230,4231,4228 ,0,0,0}, - {8617,8618,8619 ,4228,4229,4230 ,0,0,0}, {8620,8621,8622 ,4231,4232,1435 ,0,0,0}, - {8621,8620,8619 ,4232,4231,4230 ,0,0,0}, {8621,8623,8622 ,4232,1435,1435 ,0,0,0}, - {8624,8625,8626 ,4233,4234,4235 ,0,0,0}, {8627,8628,8629 ,4236,4237,4238 ,0,0,0}, - {8628,8624,8626 ,4237,4233,4235 ,0,0,0}, {8630,8627,8629 ,4239,4236,4238 ,0,0,0}, - {8628,8627,8624 ,4237,4236,4233 ,0,0,0}, {8630,8629,8631 ,4239,4238,4240 ,0,0,0}, - {8631,8632,8633 ,4240,4241,4242 ,0,0,0}, {8634,8633,8632 ,4243,4242,4241 ,0,0,0}, - {8635,8636,8637 ,4244,4245,4246 ,0,0,0}, {8632,8638,8634 ,4241,4247,4243 ,0,0,0}, - {8637,8639,8640 ,4246,4248,4249 ,0,0,0}, {8639,8638,8640 ,4248,4247,4249 ,0,0,0}, - {8634,8638,8639 ,4243,4247,4248 ,0,0,0}, {8637,8640,8635 ,4246,4249,4244 ,0,0,0}, - {8636,8635,8641 ,4245,4244,4250 ,0,0,0}, {8636,8641,8642 ,4245,4250,4251 ,0,0,0}, - {8643,8642,8641 ,4252,4251,4250 ,0,0,0}, {8644,8645,8646 ,4253,1359,4254 ,0,0,0}, - {8646,8642,8643 ,4254,4251,4252 ,0,0,0}, {8644,8646,8643 ,4253,4254,4252 ,0,0,0}, - {8644,8647,8645 ,4253,1359,1359 ,0,0,0}, {8630,8631,8633 ,4239,4240,4242 ,0,0,0}, - {8626,8625,8648 ,4235,4234,4255 ,0,0,0}, {8649,8648,8650 ,4256,4255,4257 ,0,0,0}, - {8625,8650,8648 ,4234,4257,4255 ,0,0,0}, {8651,8652,8649 ,4258,4259,4256 ,0,0,0}, - {8649,8650,8651 ,4256,4257,4258 ,0,0,0}, {8652,8653,8654 ,4259,4260,4261 ,0,0,0}, - {8653,8652,8651 ,4260,4259,4258 ,0,0,0}, {8655,8654,8656 ,4262,4261,4263 ,0,0,0}, - {8653,8656,8654 ,4260,4263,4261 ,0,0,0}, {8657,8658,8655 ,4264,4265,4262 ,0,0,0}, - {8655,8656,8657 ,4262,4263,4264 ,0,0,0}, {8658,8659,8660 ,4265,4266,4267 ,0,0,0}, - {8659,8658,8657 ,4266,4265,4264 ,0,0,0}, {8661,8660,8662 ,4268,4267,4269 ,0,0,0}, - {8659,8662,8660 ,4266,4269,4267 ,0,0,0}, {8663,8664,8661 ,4270,4271,4268 ,0,0,0}, - {8661,8662,8663 ,4268,4269,4270 ,0,0,0}, {8664,8665,8666 ,4271,4272,1435 ,0,0,0}, - {8665,8664,8663 ,4272,4271,4270 ,0,0,0}, {8665,8667,8666 ,4272,1435,1435 ,0,0,0}, - {8668,8669,8670 ,4273,4274,4275 ,0,0,0}, {8668,8671,8672 ,4273,4276,4277 ,0,0,0}, - {8671,8673,8672 ,4276,4278,4277 ,0,0,0}, {8670,8671,8668 ,4275,4276,4273 ,0,0,0}, - {8674,8675,8676 ,4279,4280,4281 ,0,0,0}, {8673,8674,8676 ,4278,4279,4281 ,0,0,0}, - {8675,8677,8678 ,4280,4282,4283 ,0,0,0}, {8677,8675,8674 ,4282,4280,4279 ,0,0,0}, - {8678,8677,8679 ,4283,4282,4284 ,0,0,0}, {8680,8678,8679 ,4285,4283,4284 ,0,0,0}, - {8680,8681,8682 ,4285,4286,4287 ,0,0,0}, {8680,8679,8681 ,4285,4284,4286 ,0,0,0}, - {8676,8672,8673 ,4281,4277,4278 ,0,0,0}, {8683,8684,8685 ,4288,126,4289 ,0,0,0}, - {8683,8685,8682 ,4288,4289,4287 ,0,0,0}, {8681,8683,8682 ,4286,4288,4287 ,0,0,0}, - {8670,8669,8686 ,4275,4274,4290 ,0,0,0}, {8687,8686,8688 ,4291,4290,4292 ,0,0,0}, - {8669,8688,8686 ,4274,4292,4290 ,0,0,0}, {8689,8690,8687 ,4293,4294,4291 ,0,0,0}, - {8687,8688,8689 ,4291,4292,4293 ,0,0,0}, {8690,8691,8692 ,4294,4295,4296 ,0,0,0}, - {8691,8690,8689 ,4295,4294,4293 ,0,0,0}, {8693,8692,8694 ,4297,4296,4298 ,0,0,0}, - {8691,8694,8692 ,4295,4298,4296 ,0,0,0}, {8695,8696,8693 ,4299,4300,4297 ,0,0,0}, - {8693,8694,8695 ,4297,4298,4299 ,0,0,0}, {8696,8697,8698 ,4300,4301,4302 ,0,0,0}, - {8697,8696,8695 ,4301,4300,4299 ,0,0,0}, {8697,8699,8698 ,4301,4303,4302 ,0,0,0}, - {8700,8701,8702 ,4304,4305,4306 ,0,0,0}, {8703,8704,8705 ,4307,4308,4309 ,0,0,0}, - {8704,8700,8702 ,4308,4304,4306 ,0,0,0}, {8706,8703,8705 ,4310,4307,4309 ,0,0,0}, - {8704,8703,8700 ,4308,4307,4304 ,0,0,0}, {8706,8705,8707 ,4310,4309,4311 ,0,0,0}, - {8707,8708,8709 ,4311,4312,4313 ,0,0,0}, {8710,8709,8708 ,4314,4313,4312 ,0,0,0}, - {8711,8712,8713 ,4315,4316,4317 ,0,0,0}, {8708,8714,8710 ,4312,4318,4314 ,0,0,0}, - {8713,8715,8716 ,4317,4319,4320 ,0,0,0}, {8715,8714,8716 ,4319,4318,4320 ,0,0,0}, - {8710,8714,8715 ,4314,4318,4319 ,0,0,0}, {8713,8716,8711 ,4317,4320,4315 ,0,0,0}, - {8712,8711,8717 ,4316,4315,4321 ,0,0,0}, {8712,8717,8718 ,4316,4321,4322 ,0,0,0}, - {8719,8718,8717 ,4323,4322,4321 ,0,0,0}, {8720,8721,8722 ,4324,126,4325 ,0,0,0}, - {8722,8718,8719 ,4325,4322,4323 ,0,0,0}, {8720,8722,8719 ,4324,4325,4323 ,0,0,0}, - {8720,8723,8721 ,4324,4326,126 ,0,0,0}, {8706,8707,8709 ,4310,4311,4313 ,0,0,0}, - {8702,8701,8724 ,4306,4305,4327 ,0,0,0}, {8725,8724,8726 ,4328,4327,4329 ,0,0,0}, - {8701,8726,8724 ,4305,4329,4327 ,0,0,0}, {8727,8728,8725 ,4330,4331,4328 ,0,0,0}, - {8725,8726,8727 ,4328,4329,4330 ,0,0,0}, {8728,8729,8730 ,4331,4332,4333 ,0,0,0}, - {8729,8728,8727 ,4332,4331,4330 ,0,0,0}, {8731,8730,8732 ,4334,4333,4335 ,0,0,0}, - {8729,8732,8730 ,4332,4335,4333 ,0,0,0}, {8733,8734,8731 ,4336,4337,4334 ,0,0,0}, - {8731,8732,8733 ,4334,4335,4336 ,0,0,0}, {8734,8735,8736 ,4337,4338,4339 ,0,0,0}, - {8735,8734,8733 ,4338,4337,4336 ,0,0,0}, {8737,8736,8738 ,4340,4339,4341 ,0,0,0}, - {8735,8738,8736 ,4338,4341,4339 ,0,0,0}, {8739,8740,8737 ,4342,4343,4340 ,0,0,0}, - {8737,8738,8739 ,4340,4341,4342 ,0,0,0}, {8740,8741,8742 ,4343,4344,4345 ,0,0,0}, - {8741,8740,8739 ,4344,4343,4342 ,0,0,0}, {8741,8743,8742 ,4344,4346,4345 ,0,0,0}, - {8744,8745,8746 ,4347,4348,4349 ,0,0,0}, {8744,8747,8748 ,4347,4350,4351 ,0,0,0}, - {8747,8749,8748 ,4350,4352,4351 ,0,0,0}, {8746,8747,8744 ,4349,4350,4347 ,0,0,0}, - {8750,8751,8752 ,4353,4354,4355 ,0,0,0}, {8749,8750,8752 ,4352,4353,4355 ,0,0,0}, - {8751,8753,8754 ,4354,4356,4357 ,0,0,0}, {8753,8751,8750 ,4356,4354,4353 ,0,0,0}, - {8754,8753,8755 ,4357,4356,4358 ,0,0,0}, {8756,8754,8755 ,4359,4357,4358 ,0,0,0}, - {8756,8757,8758 ,4359,4360,4361 ,0,0,0}, {8756,8755,8757 ,4359,4358,4360 ,0,0,0}, - {8752,8748,8749 ,4355,4351,4352 ,0,0,0}, {8759,8760,8761 ,4362,1790,1790 ,0,0,0}, - {8759,8761,8758 ,4362,1790,4361 ,0,0,0}, {8757,8759,8758 ,4360,4362,4361 ,0,0,0}, - {8746,8745,8762 ,4349,4348,4363 ,0,0,0}, {8763,8762,8764 ,4364,4363,4365 ,0,0,0}, - {8745,8764,8762 ,4348,4365,4363 ,0,0,0}, {8765,8766,8763 ,4366,4367,4364 ,0,0,0}, - {8763,8764,8765 ,4364,4365,4366 ,0,0,0}, {8766,8767,8768 ,4367,4368,4369 ,0,0,0}, - {8767,8766,8765 ,4368,4367,4366 ,0,0,0}, {8769,8768,8770 ,4370,4369,4371 ,0,0,0}, - {8767,8770,8768 ,4368,4371,4369 ,0,0,0}, {8771,8772,8769 ,4372,4373,4370 ,0,0,0}, - {8769,8770,8771 ,4370,4371,4372 ,0,0,0}, {8772,8773,8774 ,4373,4374,1711 ,0,0,0}, - {8773,8772,8771 ,4374,4373,4372 ,0,0,0}, {8773,8775,8774 ,4374,1711,1711 ,0,0,0}, - {8776,8777,8778 ,4375,4376,4377 ,0,0,0}, {8779,8780,8781 ,4378,4379,4380 ,0,0,0}, - {8780,8776,8778 ,4379,4375,4377 ,0,0,0}, {8782,8779,8781 ,4381,4378,4380 ,0,0,0}, - {8780,8779,8776 ,4379,4378,4375 ,0,0,0}, {8782,8781,8783 ,4381,4380,4382 ,0,0,0}, - {8783,8784,8785 ,4382,4383,4384 ,0,0,0}, {8786,8785,8784 ,4385,4384,4383 ,0,0,0}, - {8787,8788,8789 ,4386,4387,4388 ,0,0,0}, {8784,8790,8786 ,4383,4389,4385 ,0,0,0}, - {8789,8791,8792 ,4388,4390,4391 ,0,0,0}, {8791,8790,8792 ,4390,4389,4391 ,0,0,0}, - {8786,8790,8791 ,4385,4389,4390 ,0,0,0}, {8789,8792,8787 ,4388,4391,4386 ,0,0,0}, - {8788,8787,8793 ,4387,4386,4392 ,0,0,0}, {8788,8793,8794 ,4387,4392,4393 ,0,0,0}, - {8795,8794,8793 ,4394,4393,4392 ,0,0,0}, {8796,8797,8798 ,4395,1790,4396 ,0,0,0}, - {8798,8794,8795 ,4396,4393,4394 ,0,0,0}, {8796,8798,8795 ,4395,4396,4394 ,0,0,0}, - {8796,8799,8797 ,4395,1790,1790 ,0,0,0}, {8782,8783,8785 ,4381,4382,4384 ,0,0,0}, - {8778,8777,8800 ,4377,4376,4397 ,0,0,0}, {8801,8800,8802 ,4398,4397,4399 ,0,0,0}, - {8777,8802,8800 ,4376,4399,4397 ,0,0,0}, {8803,8804,8801 ,4400,4401,4398 ,0,0,0}, - {8801,8802,8803 ,4398,4399,4400 ,0,0,0}, {8804,8805,8806 ,4401,4402,4403 ,0,0,0}, - {8805,8804,8803 ,4402,4401,4400 ,0,0,0}, {8807,8806,8808 ,4404,4403,4405 ,0,0,0}, - {8805,8808,8806 ,4402,4405,4403 ,0,0,0}, {8809,8810,8807 ,4406,4407,4404 ,0,0,0}, - {8807,8808,8809 ,4404,4405,4406 ,0,0,0}, {8810,8811,8812 ,4407,4408,4409 ,0,0,0}, - {8811,8810,8809 ,4408,4407,4406 ,0,0,0}, {8813,8812,8814 ,4410,4409,4411 ,0,0,0}, - {8811,8814,8812 ,4408,4411,4409 ,0,0,0}, {8815,8816,8813 ,4412,4413,4410 ,0,0,0}, - {8813,8814,8815 ,4410,4411,4412 ,0,0,0}, {8816,8817,8818 ,4413,4414,1711 ,0,0,0}, - {8817,8816,8815 ,4414,4413,4412 ,0,0,0}, {8817,8819,8818 ,4414,1711,1711 ,0,0,0}, - {8820,8821,8822 ,4415,4416,4417 ,0,0,0}, {8820,8823,8824 ,4415,4418,4419 ,0,0,0}, - {8823,8825,8824 ,4418,4420,4419 ,0,0,0}, {8822,8823,8820 ,4417,4418,4415 ,0,0,0}, - {8826,8827,8828 ,4421,4422,4423 ,0,0,0}, {8825,8826,8828 ,4420,4421,4423 ,0,0,0}, - {8827,8829,8830 ,4422,4424,4425 ,0,0,0}, {8829,8827,8826 ,4424,4422,4421 ,0,0,0}, - {8830,8829,8831 ,4425,4424,4426 ,0,0,0}, {8832,8830,8831 ,4427,4425,4426 ,0,0,0}, - {8832,8833,8834 ,4427,4428,4429 ,0,0,0}, {8832,8831,8833 ,4427,4426,4428 ,0,0,0}, - {8828,8824,8825 ,4423,4419,4420 ,0,0,0}, {8835,8836,8837 ,4430,1435,1435 ,0,0,0}, - {8835,8837,8834 ,4430,1435,4429 ,0,0,0}, {8833,8835,8834 ,4428,4430,4429 ,0,0,0}, - {8822,8821,8838 ,4417,4416,4431 ,0,0,0}, {8839,8838,8840 ,4432,4431,4433 ,0,0,0}, - {8821,8840,8838 ,4416,4433,4431 ,0,0,0}, {8841,8842,8839 ,4434,4435,4432 ,0,0,0}, - {8839,8840,8841 ,4432,4433,4434 ,0,0,0}, {8842,8843,8844 ,4435,4436,4437 ,0,0,0}, - {8843,8842,8841 ,4436,4435,4434 ,0,0,0}, {8845,8844,8846 ,4438,4437,4439 ,0,0,0}, - {8843,8846,8844 ,4436,4439,4437 ,0,0,0}, {8847,8848,8845 ,4440,4441,4438 ,0,0,0}, - {8845,8846,8847 ,4438,4439,4440 ,0,0,0}, {8848,8849,8850 ,4441,4442,1359 ,0,0,0}, - {8849,8848,8847 ,4442,4441,4440 ,0,0,0}, {8849,8851,8850 ,4442,1359,1359 ,0,0,0}, - {8852,8853,8854 ,4443,4444,4445 ,0,0,0}, {8855,8856,8857 ,4446,4447,4448 ,0,0,0}, - {8856,8852,8854 ,4447,4443,4445 ,0,0,0}, {8858,8855,8857 ,4449,4446,4448 ,0,0,0}, - {8856,8855,8852 ,4447,4446,4443 ,0,0,0}, {8858,8857,8859 ,4449,4448,4450 ,0,0,0}, - {8859,8860,8861 ,4450,4451,4452 ,0,0,0}, {8862,8861,8860 ,4453,4452,4451 ,0,0,0}, - {8863,8864,8865 ,4454,4455,4456 ,0,0,0}, {8860,8866,8862 ,4451,4457,4453 ,0,0,0}, - {8865,8867,8868 ,4456,4458,4459 ,0,0,0}, {8867,8866,8868 ,4458,4457,4459 ,0,0,0}, - {8862,8866,8867 ,4453,4457,4458 ,0,0,0}, {8865,8868,8863 ,4456,4459,4454 ,0,0,0}, - {8864,8863,8869 ,4455,4454,4460 ,0,0,0}, {8864,8869,8870 ,4455,4460,4461 ,0,0,0}, - {8871,8870,8869 ,4462,4461,4460 ,0,0,0}, {8872,8873,8874 ,4463,1435,4464 ,0,0,0}, - {8874,8870,8871 ,4464,4461,4462 ,0,0,0}, {8872,8874,8871 ,4463,4464,4462 ,0,0,0}, - {8872,8875,8873 ,4463,1435,1435 ,0,0,0}, {8858,8859,8861 ,4449,4450,4452 ,0,0,0}, - {8854,8853,8876 ,4445,4444,4465 ,0,0,0}, {8877,8876,8878 ,4466,4465,4467 ,0,0,0}, - {8853,8878,8876 ,4444,4467,4465 ,0,0,0}, {8879,8880,8877 ,4468,4469,4466 ,0,0,0}, - {8877,8878,8879 ,4466,4467,4468 ,0,0,0}, {8880,8881,8882 ,4469,4470,4471 ,0,0,0}, - {8881,8880,8879 ,4470,4469,4468 ,0,0,0}, {8883,8882,8884 ,4472,4471,4473 ,0,0,0}, - {8881,8884,8882 ,4470,4473,4471 ,0,0,0}, {8885,8886,8883 ,4474,4475,4472 ,0,0,0}, - {8883,8884,8885 ,4472,4473,4474 ,0,0,0}, {8886,8887,8888 ,4475,4476,4477 ,0,0,0}, - {8887,8886,8885 ,4476,4475,4474 ,0,0,0}, {8889,8888,8890 ,4478,4477,4479 ,0,0,0}, - {8887,8890,8888 ,4476,4479,4477 ,0,0,0}, {8891,8892,8889 ,4480,4481,4478 ,0,0,0}, - {8889,8890,8891 ,4478,4479,4480 ,0,0,0}, {8892,8893,8894 ,4481,4482,1359 ,0,0,0}, - {8893,8892,8891 ,4482,4481,4480 ,0,0,0}, {8893,8895,8894 ,4482,1359,1359 ,0,0,0}, - {8896,8897,8898 ,4483,4484,4485 ,0,0,0}, {8896,8899,8900 ,4483,4486,4487 ,0,0,0}, - {8899,8901,8900 ,4486,4488,4487 ,0,0,0}, {8898,8899,8896 ,4485,4486,4483 ,0,0,0}, - {8902,8903,8904 ,4489,4490,4491 ,0,0,0}, {8901,8902,8904 ,4488,4489,4491 ,0,0,0}, - {8903,8905,8906 ,4490,4492,4493 ,0,0,0}, {8905,8903,8902 ,4492,4490,4489 ,0,0,0}, - {8906,8905,8907 ,4493,4492,4494 ,0,0,0}, {8908,8906,8907 ,4495,4493,4494 ,0,0,0}, - {8908,8909,8910 ,4495,4496,4497 ,0,0,0}, {8908,8907,8909 ,4495,4494,4496 ,0,0,0}, - {8904,8900,8901 ,4491,4487,4488 ,0,0,0}, {8911,8912,8913 ,4498,4499,82 ,0,0,0}, - {8911,8913,8910 ,4498,82,4497 ,0,0,0}, {8909,8911,8910 ,4496,4498,4497 ,0,0,0}, - {8898,8897,8914 ,4485,4484,4500 ,0,0,0}, {8915,8914,8916 ,4501,4500,4502 ,0,0,0}, - {8897,8916,8914 ,4484,4502,4500 ,0,0,0}, {8917,8918,8915 ,4503,4504,4501 ,0,0,0}, - {8915,8916,8917 ,4501,4502,4503 ,0,0,0}, {8918,8919,8920 ,4504,4505,4506 ,0,0,0}, - {8919,8918,8917 ,4505,4504,4503 ,0,0,0}, {8921,8920,8922 ,4507,4506,4508 ,0,0,0}, - {8919,8922,8920 ,4505,4508,4506 ,0,0,0}, {8923,8924,8921 ,4509,4510,4507 ,0,0,0}, - {8921,8922,8923 ,4507,4508,4509 ,0,0,0}, {8924,8925,8926 ,4510,4511,4512 ,0,0,0}, - {8925,8924,8923 ,4511,4510,4509 ,0,0,0}, {8925,8927,8926 ,4511,4513,4512 ,0,0,0}, - {8928,8929,8930 ,4514,4515,4516 ,0,0,0}, {8931,8932,8933 ,4517,4518,4519 ,0,0,0}, - {8932,8928,8930 ,4518,4514,4516 ,0,0,0}, {8934,8931,8933 ,4520,4517,4519 ,0,0,0}, - {8932,8931,8928 ,4518,4517,4514 ,0,0,0}, {8934,8933,8935 ,4520,4519,4521 ,0,0,0}, - {8935,8936,8937 ,4521,4522,4523 ,0,0,0}, {8938,8937,8936 ,4524,4523,4522 ,0,0,0}, - {8939,8940,8941 ,4525,4526,4527 ,0,0,0}, {8936,8942,8938 ,4522,4528,4524 ,0,0,0}, - {8941,8943,8944 ,4527,4529,4530 ,0,0,0}, {8943,8942,8944 ,4529,4528,4530 ,0,0,0}, - {8938,8942,8943 ,4524,4528,4529 ,0,0,0}, {8941,8944,8939 ,4527,4530,4525 ,0,0,0}, - {8940,8939,8945 ,4526,4525,4531 ,0,0,0}, {8940,8945,8946 ,4526,4531,4532 ,0,0,0}, - {8947,8946,8945 ,4533,4532,4531 ,0,0,0}, {8948,8949,8950 ,4534,4535,4536 ,0,0,0}, - {8950,8946,8947 ,4536,4532,4533 ,0,0,0}, {8948,8950,8947 ,4534,4536,4533 ,0,0,0}, - {8948,8951,8949 ,4534,4537,4535 ,0,0,0}, {8934,8935,8937 ,4520,4521,4523 ,0,0,0}, - {8930,8929,8952 ,4516,4515,4538 ,0,0,0}, {8953,8952,8954 ,4539,4538,4540 ,0,0,0}, - {8929,8954,8952 ,4515,4540,4538 ,0,0,0}, {8955,8956,8953 ,4541,4542,4539 ,0,0,0}, - {8953,8954,8955 ,4539,4540,4541 ,0,0,0}, {8956,8957,8958 ,4542,4543,4544 ,0,0,0}, - {8957,8956,8955 ,4543,4542,4541 ,0,0,0}, {8959,8958,8960 ,4545,4544,4546 ,0,0,0}, - {8957,8960,8958 ,4543,4546,4544 ,0,0,0}, {8961,8962,8959 ,4547,4548,4545 ,0,0,0}, - {8959,8960,8961 ,4545,4546,4547 ,0,0,0}, {8962,8963,8964 ,4548,4549,4550 ,0,0,0}, - {8963,8962,8961 ,4549,4548,4547 ,0,0,0}, {8965,8964,8966 ,4551,4550,4552 ,0,0,0}, - {8963,8966,8964 ,4549,4552,4550 ,0,0,0}, {8967,8968,8965 ,4553,4554,4551 ,0,0,0}, - {8965,8966,8967 ,4551,4552,4553 ,0,0,0}, {8968,8969,8970 ,4554,4555,4556 ,0,0,0}, - {8969,8968,8967 ,4555,4554,4553 ,0,0,0}, {8969,8971,8970 ,4555,126,4556 ,0,0,0}, - {8972,8973,8974 ,4557,4558,4559 ,0,0,0}, {8975,8976,8974 ,4560,4561,4559 ,0,0,0}, - {8972,8974,8976 ,4557,4559,4561 ,0,0,0}, {8977,8975,8978 ,4562,4560,4563 ,0,0,0}, - {8977,8976,8975 ,4562,4561,4560 ,0,0,0}, {8979,8978,8980 ,4564,4563,4565 ,0,0,0}, - {8975,8980,8978 ,4560,4565,4563 ,0,0,0}, {8981,8982,8979 ,4081,4566,4564 ,0,0,0}, - {8979,8980,8981 ,4564,4565,4081 ,0,0,0}, {8982,8983,8984 ,4566,4567,4568 ,0,0,0}, - {8983,8982,8981 ,4567,4566,4081 ,0,0,0}, {8985,8984,8986 ,4569,4568,4570 ,0,0,0}, - {8983,8986,8984 ,4567,4570,4568 ,0,0,0}, {8987,8988,8985 ,4571,4572,4569 ,0,0,0}, - {8985,8986,8987 ,4569,4570,4571 ,0,0,0}, {8989,8990,8988 ,4573,763,4572 ,0,0,0}, - {8989,8988,8987 ,4573,4572,4571 ,0,0,0}, {8990,8991,8988 ,763,763,4572 ,0,0,0}, - {8992,8973,8972 ,4574,4558,4557 ,0,0,0}, {8992,8993,8994 ,4574,4575,4576 ,0,0,0}, - {8994,8973,8992 ,4576,4558,4574 ,0,0,0}, {8995,8996,8993 ,4577,4578,4575 ,0,0,0}, - {8993,8996,8994 ,4575,4578,4576 ,0,0,0}, {8997,8998,8995 ,4579,4580,4577 ,0,0,0}, - {8995,8993,8997 ,4577,4575,4579 ,0,0,0}, {8998,8999,9000 ,4580,4065,4581 ,0,0,0}, - {8999,8998,8997 ,4065,4580,4579 ,0,0,0}, {9001,9000,9002 ,4582,4581,4583 ,0,0,0}, - {8999,9002,9000 ,4065,4583,4581 ,0,0,0}, {9003,9004,9001 ,4584,4585,4582 ,0,0,0}, - {9001,9002,9003 ,4582,4583,4584 ,0,0,0}, {9004,9005,9006 ,4585,4586,4587 ,0,0,0}, - {9005,9004,9003 ,4586,4585,4584 ,0,0,0}, {9006,9007,9008 ,4587,4588,54 ,0,0,0}, - {9005,9007,9006 ,4586,4588,4587 ,0,0,0}, {9006,9008,9009 ,4587,54,4589 ,0,0,0}, - {9010,9011,9012 ,4590,4591,4557 ,0,0,0}, {9013,9011,9014 ,4592,4591,4593 ,0,0,0}, - {9011,9013,9012 ,4591,4592,4557 ,0,0,0}, {9015,9016,9014 ,4594,4595,4593 ,0,0,0}, - {9013,9014,9016 ,4592,4593,4595 ,0,0,0}, {9015,9017,9018 ,4594,4596,4597 ,0,0,0}, - {9018,9016,9015 ,4597,4595,4594 ,0,0,0}, {9019,9017,9020 ,4598,4596,4599 ,0,0,0}, - {9017,9019,9018 ,4596,4598,4597 ,0,0,0}, {9021,9022,9020 ,4600,4601,4599 ,0,0,0}, - {9019,9020,9022 ,4598,4599,4601 ,0,0,0}, {9021,9023,9024 ,4600,4602,4603 ,0,0,0}, - {9024,9022,9021 ,4603,4601,4600 ,0,0,0}, {9025,9023,9026 ,4604,4602,4605 ,0,0,0}, - {9023,9025,9024 ,4602,4604,4603 ,0,0,0}, {9027,9028,9026 ,4606,4607,4605 ,0,0,0}, - {9025,9026,9028 ,4604,4605,4607 ,0,0,0}, {9027,9029,9030 ,4606,4608,4609 ,0,0,0}, - {9030,9028,9027 ,4609,4607,4606 ,0,0,0}, {9031,9029,9032 ,4610,4608,4611 ,0,0,0}, - {9029,9031,9030 ,4608,4610,4609 ,0,0,0}, {9033,9034,9032 ,4612,4613,4611 ,0,0,0}, - {9031,9032,9034 ,4610,4611,4613 ,0,0,0}, {9033,9035,9036 ,4612,4614,4615 ,0,0,0}, - {9036,9034,9033 ,4615,4613,4612 ,0,0,0}, {9037,9035,9038 ,4616,4614,4617 ,0,0,0}, - {9035,9037,9036 ,4614,4616,4615 ,0,0,0}, {9039,9040,9038 ,4618,4619,4617 ,0,0,0}, - {9037,9038,9040 ,4616,4617,4619 ,0,0,0}, {9039,9041,9042 ,4618,4620,4621 ,0,0,0}, - {9042,9040,9039 ,4621,4619,4618 ,0,0,0}, {9041,9043,9042 ,4620,4620,4621 ,0,0,0}, - {9044,9010,9012 ,4622,4590,4557 ,0,0,0}, {9045,9046,9044 ,4623,4624,4622 ,0,0,0}, - {9010,9044,9046 ,4590,4622,4624 ,0,0,0}, {9045,9047,9048 ,4623,4625,4626 ,0,0,0}, - {9048,9046,9045 ,4626,4624,4623 ,0,0,0}, {9049,9047,9050 ,4627,4625,4628 ,0,0,0}, - {9047,9049,9048 ,4625,4627,4626 ,0,0,0}, {9051,9052,9050 ,4629,4630,4628 ,0,0,0}, - {9049,9050,9052 ,4627,4628,4630 ,0,0,0}, {9051,9053,9054 ,4629,4631,4632 ,0,0,0}, - {9054,9052,9051 ,4632,4630,4629 ,0,0,0}, {9055,9053,9056 ,4633,4631,4634 ,0,0,0}, - {9053,9055,9054 ,4631,4633,4632 ,0,0,0}, {9057,9058,9056 ,4635,4636,4634 ,0,0,0}, - {9055,9056,9058 ,4633,4634,4636 ,0,0,0}, {9057,9059,9060 ,4635,4637,4638 ,0,0,0}, - {9060,9058,9057 ,4638,4636,4635 ,0,0,0}, {9061,9059,9062 ,4639,4637,4640 ,0,0,0}, - {9059,9061,9060 ,4637,4639,4638 ,0,0,0}, {9063,9064,9062 ,4641,4642,4640 ,0,0,0}, - {9061,9062,9064 ,4639,4640,4642 ,0,0,0}, {9063,9065,9066 ,4641,4643,4644 ,0,0,0}, - {9066,9064,9063 ,4644,4642,4641 ,0,0,0}, {9067,9065,9068 ,4645,4643,4646 ,0,0,0}, - {9065,9067,9066 ,4643,4645,4644 ,0,0,0}, {9069,9070,9068 ,4647,4648,4646 ,0,0,0}, - {9067,9068,9070 ,4645,4646,4648 ,0,0,0}, {9069,9071,9072 ,4647,4649,4650 ,0,0,0}, - {9072,9070,9069 ,4650,4648,4647 ,0,0,0}, {9073,9071,9074 ,4651,4649,82 ,0,0,0}, - {9071,9073,9072 ,4649,4651,4650 ,0,0,0}, {9073,9074,9075 ,4651,82,4652 ,0,0,0}, - {9076,9077,9078 ,4653,4654,4655 ,0,0,0}, {9079,9080,9081 ,4656,4657,4658 ,0,0,0}, - {9078,9081,9080 ,4655,4658,4657 ,0,0,0}, {9082,9083,9084 ,4659,4660,4661 ,0,0,0}, - {9085,9086,9079 ,4662,4663,4656 ,0,0,0}, {9082,9086,9085 ,4659,4663,4662 ,0,0,0}, - {9085,9083,9082 ,4662,4660,4659 ,0,0,0}, {9086,9080,9079 ,4663,4657,4656 ,0,0,0}, - {9087,9088,9089 ,4664,4665,4666 ,0,0,0}, {9088,9090,9089 ,4665,4667,4666 ,0,0,0}, - {9091,9092,9093 ,4668,4669,4670 ,0,0,0}, {9091,9093,9090 ,4668,4670,4667 ,0,0,0}, - {9088,9091,9090 ,4665,4668,4667 ,0,0,0}, {9083,9087,9084 ,4660,4664,4661 ,0,0,0}, - {9087,9089,9084 ,4664,4666,4661 ,0,0,0}, {9094,9095,9096 ,4671,4672,4673 ,0,0,0}, - {9097,9098,9099 ,4674,4675,4676 ,0,0,0}, {9096,9095,9097 ,4673,4672,4674 ,0,0,0}, - {9100,9101,9102 ,4677,4678,4679 ,0,0,0}, {9096,9097,9099 ,4673,4674,4676 ,0,0,0}, - {9102,9101,9098 ,4679,4678,4675 ,0,0,0}, {9101,9099,9098 ,4678,4676,4675 ,0,0,0}, - {9092,9095,9094 ,4669,4672,4671 ,0,0,0}, {9103,9100,9102 ,4677,4677,4679 ,0,0,0}, - {9093,9092,9094 ,4670,4669,4671 ,0,0,0}, {9077,9081,9078 ,4654,4658,4655 ,0,0,0}, - {9104,9077,9076 ,4680,4654,4653 ,0,0,0}, {9104,9105,9106 ,4680,4681,4682 ,0,0,0}, - {9105,9104,9076 ,4681,4680,4653 ,0,0,0}, {9107,9106,9108 ,4683,4682,4684 ,0,0,0}, - {9105,9108,9106 ,4681,4684,4682 ,0,0,0}, {9109,9110,9107 ,4685,4686,4683 ,0,0,0}, - {9107,9108,9109 ,4683,4684,4685 ,0,0,0}, {9110,9111,9112 ,4686,4687,4688 ,0,0,0}, - {9111,9110,9109 ,4687,4686,4685 ,0,0,0}, {9113,9112,9114 ,4689,4688,4690 ,0,0,0}, - {9111,9114,9112 ,4687,4690,4688 ,0,0,0}, {9115,9116,9113 ,4691,4692,4689 ,0,0,0}, - {9113,9114,9115 ,4689,4690,4691 ,0,0,0}, {9116,9117,9118 ,4692,4693,4694 ,0,0,0}, - {9117,9116,9115 ,4693,4692,4691 ,0,0,0}, {9119,9118,9120 ,4695,4694,4696 ,0,0,0}, - {9117,9120,9118 ,4693,4696,4694 ,0,0,0}, {9121,9122,9119 ,4697,4698,4695 ,0,0,0}, - {9119,9120,9121 ,4695,4696,4697 ,0,0,0}, {9122,9123,9124 ,4698,4699,4700 ,0,0,0}, - {9123,9122,9121 ,4699,4698,4697 ,0,0,0}, {9123,9125,9124 ,4699,4701,4700 ,0,0,0}, - {9126,9127,9128 ,4702,4703,4704 ,0,0,0}, {9129,9130,9131 ,4705,4706,4707 ,0,0,0}, - {9127,9131,9130 ,4703,4707,4706 ,0,0,0}, {9132,9133,9134 ,4708,4709,4710 ,0,0,0}, - {9135,9129,9136 ,4711,4705,4712 ,0,0,0}, {9132,9135,9136 ,4708,4711,4712 ,0,0,0}, - {9135,9132,9134 ,4711,4708,4710 ,0,0,0}, {9136,9129,9131 ,4712,4705,4707 ,0,0,0}, - {9137,9138,9139 ,4713,4714,4715 ,0,0,0}, {9139,9138,9140 ,4715,4714,4716 ,0,0,0}, - {9141,9142,9143 ,4717,4718,4719 ,0,0,0}, {9141,9140,9142 ,4717,4716,4718 ,0,0,0}, - {9139,9140,9141 ,4715,4716,4717 ,0,0,0}, {9134,9133,9137 ,4710,4709,4713 ,0,0,0}, - {9137,9133,9138 ,4713,4709,4714 ,0,0,0}, {9144,9145,9146 ,4720,4721,4722 ,0,0,0}, - {9147,9148,9149 ,4723,4724,4725 ,0,0,0}, {9145,9147,9146 ,4721,4723,4722 ,0,0,0}, - {9150,9151,9152 ,4726,4727,4728 ,0,0,0}, {9145,9148,9147 ,4721,4724,4723 ,0,0,0}, - {9151,9149,9152 ,4727,4725,4728 ,0,0,0}, {9152,9149,9148 ,4728,4725,4724 ,0,0,0}, - {9143,9144,9146 ,4719,4720,4722 ,0,0,0}, {9153,9151,9150 ,4726,4727,4726 ,0,0,0}, - {9142,9144,9143 ,4718,4720,4719 ,0,0,0}, {9128,9127,9130 ,4704,4703,4706 ,0,0,0}, - {9154,9126,9128 ,4729,4702,4704 ,0,0,0}, {9154,9155,9156 ,4729,4730,4731 ,0,0,0}, - {9156,9126,9154 ,4731,4702,4729 ,0,0,0}, {9157,9158,9155 ,4732,4733,4730 ,0,0,0}, - {9156,9155,9158 ,4731,4730,4733 ,0,0,0}, {9159,9157,9160 ,4734,4732,4735 ,0,0,0}, - {9157,9159,9158 ,4732,4734,4733 ,0,0,0}, {9160,9161,9162 ,4735,4736,4737 ,0,0,0}, - {9162,9159,9160 ,4737,4734,4735 ,0,0,0}, {9163,9164,9161 ,4738,4739,4736 ,0,0,0}, - {9162,9161,9164 ,4737,4736,4739 ,0,0,0}, {9165,9163,9166 ,4740,4738,4741 ,0,0,0}, - {9163,9165,9164 ,4738,4740,4739 ,0,0,0}, {9166,9167,9168 ,4741,4742,4743 ,0,0,0}, - {9168,9165,9166 ,4743,4740,4741 ,0,0,0}, {9169,9170,9167 ,4744,4745,4742 ,0,0,0}, - {9168,9167,9170 ,4743,4742,4745 ,0,0,0}, {9171,9169,9172 ,4746,4744,4747 ,0,0,0}, - {9169,9171,9170 ,4744,4746,4745 ,0,0,0}, {9172,9173,9174 ,4747,4748,4749 ,0,0,0}, - {9174,9171,9172 ,4749,4746,4747 ,0,0,0}, {9174,9173,9175 ,4749,4748,4750 ,0,0,0}, - {9176,9177,9178 ,4751,4752,4753 ,0,0,0}, {9179,9180,9181 ,4754,4755,4756 ,0,0,0}, - {9177,9181,9180 ,4752,4756,4755 ,0,0,0}, {9182,9183,9184 ,4757,4758,4759 ,0,0,0}, - {9185,9179,9186 ,4760,4754,4761 ,0,0,0}, {9185,9186,9182 ,4760,4761,4757 ,0,0,0}, - {9182,9184,9185 ,4757,4759,4760 ,0,0,0}, {9179,9181,9186 ,4754,4756,4761 ,0,0,0}, - {9187,9188,9189 ,4762,4763,4764 ,0,0,0}, {9190,9188,9187 ,4765,4763,4762 ,0,0,0}, - {9191,9192,9193 ,4766,4767,4768 ,0,0,0}, {9191,9193,9190 ,4766,4768,4765 ,0,0,0}, - {9190,9193,9188 ,4765,4768,4763 ,0,0,0}, {9183,9189,9184 ,4758,4764,4759 ,0,0,0}, - {9187,9189,9183 ,4762,4764,4758 ,0,0,0}, {9194,9195,9196 ,4769,4770,4771 ,0,0,0}, - {9197,9198,9199 ,4772,4773,4774 ,0,0,0}, {9196,9195,9199 ,4771,4770,4774 ,0,0,0}, - {9200,9201,9202 ,4775,4776,4777 ,0,0,0}, {9195,9197,9199 ,4770,4772,4774 ,0,0,0}, - {9200,9198,9201 ,4775,4773,4776 ,0,0,0}, {9198,9197,9201 ,4773,4772,4776 ,0,0,0}, - {9194,9196,9192 ,4769,4771,4767 ,0,0,0}, {9203,9200,9202 ,4777,4775,4777 ,0,0,0}, - {9191,9194,9192 ,4766,4769,4767 ,0,0,0}, {9177,9180,9178 ,4752,4755,4753 ,0,0,0}, - {9176,9178,9204 ,4751,4753,4778 ,0,0,0}, {9204,9205,9206 ,4778,4779,4780 ,0,0,0}, - {9206,9176,9204 ,4780,4751,4778 ,0,0,0}, {9207,9205,9208 ,4781,4779,4782 ,0,0,0}, - {9205,9207,9206 ,4779,4781,4780 ,0,0,0}, {9209,9210,9208 ,4783,4784,4782 ,0,0,0}, - {9207,9208,9210 ,4781,4782,4784 ,0,0,0}, {9209,9211,9212 ,4783,4785,4786 ,0,0,0}, - {9212,9210,9209 ,4786,4784,4783 ,0,0,0}, {9213,9211,9214 ,4787,4785,4788 ,0,0,0}, - {9211,9213,9212 ,4785,4787,4786 ,0,0,0}, {9215,9216,9214 ,4789,4790,4788 ,0,0,0}, - {9213,9214,9216 ,4787,4788,4790 ,0,0,0}, {9215,9217,9218 ,4789,4791,4792 ,0,0,0}, - {9218,9216,9215 ,4792,4790,4789 ,0,0,0}, {9219,9217,9220 ,4793,4791,4794 ,0,0,0}, - {9217,9219,9218 ,4791,4793,4792 ,0,0,0}, {9221,9222,9220 ,4795,4796,4794 ,0,0,0}, - {9219,9220,9222 ,4793,4794,4796 ,0,0,0}, {9221,9223,9224 ,4795,4797,4798 ,0,0,0}, - {9224,9222,9221 ,4798,4796,4795 ,0,0,0}, {9223,9225,9224 ,4797,4799,4798 ,0,0,0}, - {9223,9226,9225 ,4797,324,4799 ,0,0,0}, {9227,9228,9229 ,82,4800,4801 ,0,0,0}, - {9229,9230,9231 ,4801,4802,4803 ,0,0,0}, {9230,9232,9231 ,4802,4804,4803 ,0,0,0}, - {9229,9231,9227 ,4801,4803,82 ,0,0,0}, {9233,9234,9235 ,4805,4806,4807 ,0,0,0}, - {9235,9234,9232 ,4807,4806,4804 ,0,0,0}, {9233,9236,9237 ,4805,4808,4809 ,0,0,0}, - {9237,9234,9233 ,4809,4806,4805 ,0,0,0}, {9237,9236,9238 ,4809,4808,4810 ,0,0,0}, - {9238,9236,9239 ,4810,4808,4811 ,0,0,0}, {9239,9240,9241 ,4811,4812,4813 ,0,0,0}, - {9238,9239,9241 ,4810,4811,4813 ,0,0,0}, {9232,9230,9235 ,4804,4802,4807 ,0,0,0}, - {9242,9243,9244 ,4814,4815,4816 ,0,0,0}, {9242,9244,9240 ,4814,4816,4812 ,0,0,0}, - {9240,9244,9241 ,4812,4816,4813 ,0,0,0}, {9227,9245,9228 ,82,4817,4800 ,0,0,0}, - {9246,9245,9247 ,4818,4817,4819 ,0,0,0}, {9245,9246,9228 ,4817,4818,4800 ,0,0,0}, - {9248,9249,9247 ,4820,4821,4819 ,0,0,0}, {9246,9247,9249 ,4818,4819,4821 ,0,0,0}, - {9248,9250,9251 ,4820,4822,4823 ,0,0,0}, {9251,9249,9248 ,4823,4821,4820 ,0,0,0}, - {9252,9250,9253 ,4824,4822,4825 ,0,0,0}, {9250,9252,9251 ,4822,4824,4823 ,0,0,0}, - {9254,9255,9253 ,4826,4827,4825 ,0,0,0}, {9252,9253,9255 ,4824,4825,4827 ,0,0,0}, - {9254,9256,9257 ,4826,4828,4829 ,0,0,0}, {9257,9255,9254 ,4829,4827,4826 ,0,0,0}, - {9258,9256,9259 ,4830,4828,4831 ,0,0,0}, {9256,9258,9257 ,4828,4830,4829 ,0,0,0}, - {9254,9253,9260 ,4832,4833,4834 ,0,0,0}, {9260,9256,9254 ,4834,4835,4832 ,0,0,0}, - {9260,9259,9256 ,4834,4836,4835 ,0,0,0}, {9260,9250,9248 ,4834,4837,4838 ,0,0,0}, - {9253,9250,9260 ,4833,4837,4834 ,0,0,0}, {9260,9247,9245 ,4834,4839,4840 ,0,0,0}, - {9248,9247,9260 ,4838,4839,4834 ,0,0,0}, {9245,9227,9260 ,4840,4841,4834 ,0,0,0}, - {9232,9260,9231 ,4842,4834,4843 ,0,0,0}, {9260,9227,9231 ,4834,4841,4843 ,0,0,0}, - {9237,9260,9234 ,4844,4834,4845 ,0,0,0}, {9260,9232,9234 ,4834,4842,4845 ,0,0,0}, - {9241,9260,9238 ,4846,4834,4847 ,0,0,0}, {9260,9237,9238 ,4834,4844,4847 ,0,0,0}, - {9243,9260,9244 ,4848,4834,4849 ,0,0,0}, {9260,9241,9244 ,4834,4846,4849 ,0,0,0}, - {9261,9262,9263 ,82,4850,4851 ,0,0,0}, {9263,9264,9265 ,4851,4852,4853 ,0,0,0}, - {9264,9266,9265 ,4852,4854,4853 ,0,0,0}, {9263,9265,9261 ,4851,4853,82 ,0,0,0}, - {9267,9268,9269 ,4855,4856,4857 ,0,0,0}, {9269,9268,9266 ,4857,4856,4854 ,0,0,0}, - {9267,9270,9271 ,4855,4858,4859 ,0,0,0}, {9271,9268,9267 ,4859,4856,4855 ,0,0,0}, - {9271,9270,9272 ,4859,4858,4860 ,0,0,0}, {9272,9270,9273 ,4860,4858,4861 ,0,0,0}, - {9273,9274,9275 ,4861,4862,4863 ,0,0,0}, {9272,9273,9275 ,4860,4861,4863 ,0,0,0}, - {9266,9264,9269 ,4854,4852,4857 ,0,0,0}, {9276,9277,9278 ,4864,4865,4866 ,0,0,0}, - {9276,9278,9274 ,4864,4866,4862 ,0,0,0}, {9274,9278,9275 ,4862,4866,4863 ,0,0,0}, - {9261,9279,9262 ,82,4867,4850 ,0,0,0}, {9280,9279,9281 ,4868,4867,4869 ,0,0,0}, - {9279,9280,9262 ,4867,4868,4850 ,0,0,0}, {9282,9283,9281 ,4870,4871,4869 ,0,0,0}, - {9280,9281,9283 ,4868,4869,4871 ,0,0,0}, {9282,9284,9285 ,4870,4872,4873 ,0,0,0}, - {9285,9283,9282 ,4873,4871,4870 ,0,0,0}, {9286,9284,9287 ,4874,4872,4875 ,0,0,0}, - {9284,9286,9285 ,4872,4874,4873 ,0,0,0}, {9288,9289,9287 ,4876,4877,4875 ,0,0,0}, - {9286,9287,9289 ,4874,4875,4877 ,0,0,0}, {9288,9290,9291 ,4876,4878,4829 ,0,0,0}, - {9291,9289,9288 ,4829,4877,4876 ,0,0,0}, {9292,9290,9293 ,4879,4878,4831 ,0,0,0}, - {9290,9292,9291 ,4878,4879,4829 ,0,0,0}, {9288,9287,9294 ,4832,4833,4880 ,0,0,0}, - {9294,9290,9288 ,4880,4835,4832 ,0,0,0}, {9294,9293,9290 ,4880,4881,4835 ,0,0,0}, - {9294,9284,9282 ,4880,4837,4838 ,0,0,0}, {9287,9284,9294 ,4833,4837,4880 ,0,0,0}, - {9294,9281,9279 ,4880,4839,4840 ,0,0,0}, {9282,9281,9294 ,4838,4839,4880 ,0,0,0}, - {9279,9261,9294 ,4840,4882,4880 ,0,0,0}, {9266,9294,9265 ,4842,4880,4843 ,0,0,0}, - {9294,9261,9265 ,4880,4882,4843 ,0,0,0}, {9271,9294,9268 ,4844,4880,4845 ,0,0,0}, - {9294,9266,9268 ,4880,4842,4845 ,0,0,0}, {9275,9294,9272 ,4846,4880,4847 ,0,0,0}, - {9294,9271,9272 ,4880,4844,4847 ,0,0,0}, {9277,9294,9278 ,4883,4880,4849 ,0,0,0}, - {9294,9275,9278 ,4880,4846,4849 ,0,0,0}, {9295,9296,9297 ,4884,4885,4886 ,0,0,0}, - {9297,9298,9299 ,4886,4887,4888 ,0,0,0}, {9298,9300,9299 ,4887,4889,4888 ,0,0,0}, - {9297,9299,9295 ,4886,4888,4884 ,0,0,0}, {9301,9302,9303 ,4890,4891,4857 ,0,0,0}, - {9303,9302,9300 ,4857,4891,4889 ,0,0,0}, {9301,9304,9305 ,4890,4892,4893 ,0,0,0}, - {9305,9302,9301 ,4893,4891,4890 ,0,0,0}, {9305,9304,9306 ,4893,4892,4894 ,0,0,0}, - {9306,9304,9307 ,4894,4892,4895 ,0,0,0}, {9307,9308,9309 ,4895,4896,4897 ,0,0,0}, - {9306,9307,9309 ,4894,4895,4897 ,0,0,0}, {9300,9298,9303 ,4889,4887,4857 ,0,0,0}, - {9310,9311,9312 ,4898,4899,4900 ,0,0,0}, {9310,9312,9308 ,4898,4900,4896 ,0,0,0}, - {9308,9312,9309 ,4896,4900,4897 ,0,0,0}, {9295,9313,9296 ,4884,4901,4885 ,0,0,0}, - {9314,9313,9315 ,4868,4901,4902 ,0,0,0}, {9313,9314,9296 ,4901,4868,4885 ,0,0,0}, - {9316,9317,9315 ,4820,4903,4902 ,0,0,0}, {9314,9315,9317 ,4868,4902,4903 ,0,0,0}, - {9316,9318,9319 ,4820,4904,4905 ,0,0,0}, {9319,9317,9316 ,4905,4903,4820 ,0,0,0}, - {9320,9318,9321 ,4906,4904,4907 ,0,0,0}, {9318,9320,9319 ,4904,4906,4905 ,0,0,0}, - {9322,9323,9321 ,4826,4877,4907 ,0,0,0}, {9320,9321,9323 ,4906,4907,4877 ,0,0,0}, - {9322,9324,9325 ,4826,4828,4908 ,0,0,0}, {9325,9323,9322 ,4908,4877,4826 ,0,0,0}, - {9326,9324,9327 ,4909,4828,4910 ,0,0,0}, {9324,9326,9325 ,4828,4909,4908 ,0,0,0}, - {9322,9321,9328 ,4832,4833,4880 ,0,0,0}, {9328,9324,9322 ,4880,4835,4832 ,0,0,0}, - {9328,9327,9324 ,4880,4911,4835 ,0,0,0}, {9328,9318,9316 ,4880,4837,4838 ,0,0,0}, - {9321,9318,9328 ,4833,4837,4880 ,0,0,0}, {9328,9315,9313 ,4880,4839,4840 ,0,0,0}, - {9316,9315,9328 ,4838,4839,4880 ,0,0,0}, {9313,9295,9328 ,4840,4912,4880 ,0,0,0}, - {9300,9328,9299 ,4842,4880,4843 ,0,0,0}, {9328,9295,9299 ,4880,4912,4843 ,0,0,0}, - {9305,9328,9302 ,4844,4880,4845 ,0,0,0}, {9328,9300,9302 ,4880,4842,4845 ,0,0,0}, - {9309,9328,9306 ,4846,4880,4847 ,0,0,0}, {9328,9305,9306 ,4880,4844,4847 ,0,0,0}, - {9311,9328,9312 ,4913,4880,4849 ,0,0,0}, {9328,9309,9312 ,4880,4846,4849 ,0,0,0}, - {9329,9330,9331 ,4914,4915,4916 ,0,0,0}, {9331,9332,9333 ,4916,4917,4918 ,0,0,0}, - {9332,9334,9333 ,4917,4919,4918 ,0,0,0}, {9331,9333,9329 ,4916,4918,4914 ,0,0,0}, - {9335,9336,9337 ,4920,4921,4922 ,0,0,0}, {9337,9336,9334 ,4922,4921,4919 ,0,0,0}, - {9335,9338,9339 ,4920,4923,4924 ,0,0,0}, {9339,9336,9335 ,4924,4921,4920 ,0,0,0}, - {9339,9338,9340 ,4924,4923,4925 ,0,0,0}, {9340,9338,9341 ,4925,4923,4926 ,0,0,0}, - {9341,9342,9343 ,4926,4927,4928 ,0,0,0}, {9340,9341,9343 ,4925,4926,4928 ,0,0,0}, - {9334,9332,9337 ,4919,4917,4922 ,0,0,0}, {9344,9345,9346 ,4929,4815,4930 ,0,0,0}, - {9344,9346,9342 ,4929,4930,4927 ,0,0,0}, {9342,9346,9343 ,4927,4930,4928 ,0,0,0}, - {9329,9347,9330 ,4914,4931,4915 ,0,0,0}, {9348,9347,9349 ,4932,4931,4933 ,0,0,0}, - {9347,9348,9330 ,4931,4932,4915 ,0,0,0}, {9350,9351,9349 ,4934,4821,4933 ,0,0,0}, - {9348,9349,9351 ,4932,4933,4821 ,0,0,0}, {9350,9352,9353 ,4934,4935,4936 ,0,0,0}, - {9353,9351,9350 ,4936,4821,4934 ,0,0,0}, {9354,9352,9355 ,4937,4935,4938 ,0,0,0}, - {9352,9354,9353 ,4935,4937,4936 ,0,0,0}, {9356,9357,9355 ,4826,4877,4938 ,0,0,0}, - {9354,9355,9357 ,4937,4938,4877 ,0,0,0}, {9356,9358,9359 ,4826,4939,4940 ,0,0,0}, - {9359,9357,9356 ,4940,4877,4826 ,0,0,0}, {9360,9358,9361 ,4941,4939,4942 ,0,0,0}, - {9358,9360,9359 ,4939,4941,4940 ,0,0,0}, {9356,9355,9362 ,4832,4833,4943 ,0,0,0}, - {9362,9358,9356 ,4943,4835,4832 ,0,0,0}, {9362,9361,9358 ,4943,4944,4835 ,0,0,0}, - {9362,9352,9350 ,4943,4837,4838 ,0,0,0}, {9355,9352,9362 ,4833,4837,4943 ,0,0,0}, - {9362,9349,9347 ,4943,4839,4840 ,0,0,0}, {9350,9349,9362 ,4838,4839,4943 ,0,0,0}, - {9347,9329,9362 ,4840,4945,4943 ,0,0,0}, {9334,9362,9333 ,4842,4943,4843 ,0,0,0}, - {9362,9329,9333 ,4943,4945,4843 ,0,0,0}, {9339,9362,9336 ,4844,4943,4845 ,0,0,0}, - {9362,9334,9336 ,4943,4842,4845 ,0,0,0}, {9343,9362,9340 ,4846,4943,4847 ,0,0,0}, - {9362,9339,9340 ,4943,4844,4847 ,0,0,0}, {9345,9362,9346 ,4946,4943,4849 ,0,0,0}, - {9362,9343,9346 ,4943,4846,4849 ,0,0,0}, {9363,9364,9365 ,4947,4948,4949 ,0,0,0}, - {9366,9367,9368 ,4950,4951,4952 ,0,0,0}, {9365,9368,9367 ,4949,4952,4951 ,0,0,0}, - {9369,9370,9371 ,4953,4954,4955 ,0,0,0}, {9372,9373,9366 ,4956,4957,4950 ,0,0,0}, - {9369,9373,9372 ,4953,4957,4956 ,0,0,0}, {9372,9370,9369 ,4956,4954,4953 ,0,0,0}, - {9373,9367,9366 ,4957,4951,4950 ,0,0,0}, {9374,9375,9376 ,4958,4959,4960 ,0,0,0}, - {9375,9377,9376 ,4959,4961,4960 ,0,0,0}, {9378,9379,9380 ,4962,4963,4964 ,0,0,0}, - {9378,9380,9377 ,4962,4964,4961 ,0,0,0}, {9375,9378,9377 ,4959,4962,4961 ,0,0,0}, - {9370,9374,9371 ,4954,4958,4955 ,0,0,0}, {9374,9376,9371 ,4958,4960,4955 ,0,0,0}, - {9381,9382,9383 ,4965,4966,4967 ,0,0,0}, {9384,9385,9386 ,4968,4969,4970 ,0,0,0}, - {9383,9382,9384 ,4967,4966,4968 ,0,0,0}, {9387,9388,9389 ,4726,4971,4972 ,0,0,0}, - {9383,9384,9386 ,4967,4968,4970 ,0,0,0}, {9389,9388,9385 ,4972,4971,4969 ,0,0,0}, - {9388,9386,9385 ,4971,4970,4969 ,0,0,0}, {9379,9382,9381 ,4963,4966,4965 ,0,0,0}, - {9390,9387,9389 ,4726,4726,4972 ,0,0,0}, {9380,9379,9381 ,4964,4963,4965 ,0,0,0}, - {9364,9368,9365 ,4948,4952,4949 ,0,0,0}, {9391,9364,9363 ,4973,4948,4947 ,0,0,0}, - {9391,9392,9393 ,4973,4974,4975 ,0,0,0}, {9392,9391,9363 ,4974,4973,4947 ,0,0,0}, - {9394,9393,9395 ,4976,4975,4977 ,0,0,0}, {9392,9395,9393 ,4974,4977,4975 ,0,0,0}, - {9396,9397,9394 ,4978,4979,4976 ,0,0,0}, {9394,9395,9396 ,4976,4977,4978 ,0,0,0}, - {9397,9398,9399 ,4979,4980,4981 ,0,0,0}, {9398,9397,9396 ,4980,4979,4978 ,0,0,0}, - {9400,9399,9401 ,4982,4981,4983 ,0,0,0}, {9398,9401,9399 ,4980,4983,4981 ,0,0,0}, - {9402,9403,9400 ,4984,4985,4982 ,0,0,0}, {9400,9401,9402 ,4982,4983,4984 ,0,0,0}, - {9403,9404,9405 ,4985,4986,4987 ,0,0,0}, {9404,9403,9402 ,4986,4985,4984 ,0,0,0}, - {9406,9405,9407 ,4988,4987,4989 ,0,0,0}, {9404,9407,9405 ,4986,4989,4987 ,0,0,0}, - {9408,9409,9406 ,4990,4991,4988 ,0,0,0}, {9406,9407,9408 ,4988,4989,4990 ,0,0,0}, - {9409,9410,9411 ,4991,4992,4748 ,0,0,0}, {9410,9409,9408 ,4992,4991,4990 ,0,0,0}, - {9410,9412,9411 ,4992,4750,4748 ,0,0,0}, {9413,9414,9415 ,4993,4994,4995 ,0,0,0}, - {9416,9417,9418 ,4996,4997,4998 ,0,0,0}, {9414,9419,9420 ,4994,4999,5000 ,0,0,0}, - {9419,9414,9413 ,4999,4994,4993 ,0,0,0}, {9419,9421,9420 ,4999,5001,5000 ,0,0,0}, - {9415,9422,9413 ,4995,5002,4993 ,0,0,0}, {9416,9422,9423 ,4996,5002,5003 ,0,0,0}, - {9415,9423,9422 ,4995,5003,5002 ,0,0,0}, {9424,9425,9426 ,5004,5005,5006 ,0,0,0}, - {9416,9423,9417 ,4996,5003,4997 ,0,0,0}, {9427,9428,9429 ,5007,5008,5009 ,0,0,0}, - {9430,9431,9432 ,5010,5011,5012 ,0,0,0}, {9433,9434,9435 ,5013,5014,5015 ,0,0,0}, - {9436,9437,9438 ,5016,5017,5018 ,0,0,0}, {9439,9440,9441 ,5019,5020,5021 ,0,0,0}, - {9442,9443,9434 ,5022,5023,5014 ,0,0,0}, {9444,9445,9446 ,5024,5025,5026 ,0,0,0}, - {9445,9440,9447 ,5025,5020,5027 ,0,0,0}, {9448,9449,9450 ,5028,5029,5030 ,0,0,0}, - {9451,9452,9444 ,5031,5032,5024 ,0,0,0}, {9453,9454,9455 ,5033,5034,5035 ,0,0,0}, - {9456,9450,9457 ,5036,5030,5037 ,0,0,0}, {9458,9459,9460 ,5038,5039,5040 ,0,0,0}, - {9461,9459,9462 ,5041,5039,5042 ,0,0,0}, {9463,9464,9465 ,5043,5044,5045 ,0,0,0}, - {9460,9466,9463 ,5040,5046,5043 ,0,0,0}, {9467,9468,9469 ,5047,5048,5049 ,0,0,0}, - {9467,9470,9471 ,5047,5050,5051 ,0,0,0}, {9472,9473,9474 ,5052,5053,5054 ,0,0,0}, - {9475,9476,9474 ,5055,5056,5054 ,0,0,0}, {9477,9478,9479 ,5057,5058,5059 ,0,0,0}, - {9478,9472,9480 ,5058,5052,5060 ,0,0,0}, {9481,9482,9483 ,5061,5062,5063 ,0,0,0}, - {9477,9484,9481 ,5057,5064,5061 ,0,0,0}, {9485,9486,9487 ,5065,5066,5067 ,0,0,0}, - {9485,9488,9489 ,5065,5068,5069 ,0,0,0}, {9490,9491,9492 ,5070,5071,5072 ,0,0,0}, - {9490,9493,9486 ,5070,5073,5066 ,0,0,0}, {9494,9491,9495 ,5074,5071,5075 ,0,0,0}, - {9491,9494,9492 ,5071,5074,5072 ,0,0,0}, {9496,9497,9495 ,5076,5077,5075 ,0,0,0}, - {9494,9495,9497 ,5074,5075,5077 ,0,0,0}, {9498,9499,9497 ,5078,5079,5077 ,0,0,0}, - {9497,9496,9498 ,5077,5076,5078 ,0,0,0}, {9499,9500,9501 ,5079,5080,5081 ,0,0,0}, - {9500,9499,9498 ,5080,5079,5078 ,0,0,0}, {9502,9501,9503 ,5082,5081,5083 ,0,0,0}, - {9500,9503,9501 ,5080,5083,5081 ,0,0,0}, {9504,9505,9502 ,5084,5085,5082 ,0,0,0}, - {9502,9503,9504 ,5082,5083,5084 ,0,0,0}, {9505,9506,9507 ,5085,5086,5087 ,0,0,0}, - {9506,9505,9504 ,5086,5085,5084 ,0,0,0}, {9508,9507,9509 ,5088,5087,5089 ,0,0,0}, - {9506,9509,9507 ,5086,5089,5087 ,0,0,0}, {9510,9508,9511 ,5090,5088,5091 ,0,0,0}, - {9508,9509,9511 ,5088,5089,5091 ,0,0,0}, {9510,9512,9513 ,5090,5092,5093 ,0,0,0}, - {9513,9508,9510 ,5093,5088,5090 ,0,0,0}, {9514,9512,9515 ,5094,5092,5095 ,0,0,0}, - {9512,9514,9513 ,5092,5094,5093 ,0,0,0}, {9516,9517,9515 ,126,5096,5095 ,0,0,0}, - {9514,9515,9517 ,5094,5095,5096 ,0,0,0}, {9518,9517,9516 ,126,5096,126 ,0,0,0}, - {9487,9486,9493 ,5067,5066,5073 ,0,0,0}, {9490,9492,9493 ,5070,5072,5073 ,0,0,0}, - {9483,9488,9481 ,5063,5068,5061 ,0,0,0}, {9485,9487,9488 ,5065,5067,5068 ,0,0,0}, - {9483,9489,9488 ,5063,5069,5068 ,0,0,0}, {9479,9484,9477 ,5059,5064,5057 ,0,0,0}, - {9481,9484,9482 ,5061,5064,5062 ,0,0,0}, {9473,9472,9478 ,5053,5052,5058 ,0,0,0}, - {9478,9480,9479 ,5058,5060,5059 ,0,0,0}, {9475,9468,9476 ,5055,5048,5056 ,0,0,0}, - {9473,9475,9474 ,5053,5055,5054 ,0,0,0}, {9467,9469,9470 ,5047,5049,5050 ,0,0,0}, - {9468,9475,9469 ,5048,5055,5049 ,0,0,0}, {9464,9471,9465 ,5044,5051,5045 ,0,0,0}, - {9471,9470,9465 ,5051,5050,5045 ,0,0,0}, {9460,9463,9458 ,5040,5043,5038 ,0,0,0}, - {9466,9464,9463 ,5046,5044,5043 ,0,0,0}, {9453,9461,9454 ,5033,5041,5034 ,0,0,0}, - {9462,9459,9458 ,5042,5039,5038 ,0,0,0}, {9454,9461,9462 ,5034,5041,5042 ,0,0,0}, - {9455,9456,9457 ,5035,5036,5037 ,0,0,0}, {9454,9456,9455 ,5034,5036,5035 ,0,0,0}, - {9450,9452,9448 ,5030,5032,5028 ,0,0,0}, {9457,9450,9449 ,5037,5030,5029 ,0,0,0}, - {9519,9451,9444 ,5097,5031,5024 ,0,0,0}, {9451,9448,9452 ,5031,5028,5032 ,0,0,0}, - {9520,9445,9447 ,5098,5025,5027 ,0,0,0}, {9444,9446,9519 ,5024,5026,5097 ,0,0,0}, - {9445,9520,9446 ,5025,5098,5026 ,0,0,0}, {9441,9442,9439 ,5021,5022,5019 ,0,0,0}, - {9447,9440,9439 ,5027,5020,5019 ,0,0,0}, {9435,9438,9433 ,5015,5018,5013 ,0,0,0}, - {9442,9441,9443 ,5022,5021,5023 ,0,0,0}, {9434,9443,9435 ,5014,5023,5015 ,0,0,0}, - {9427,9436,9438 ,5007,5016,5018 ,0,0,0}, {9437,9433,9438 ,5017,5013,5018 ,0,0,0}, - {9428,9432,9429 ,5008,5012,5009 ,0,0,0}, {9427,9429,9436 ,5007,5009,5016 ,0,0,0}, - {9430,9424,9431 ,5010,5004,5011 ,0,0,0}, {9428,9430,9432 ,5008,5010,5012 ,0,0,0}, - {9426,9425,9418 ,5006,5005,4998 ,0,0,0}, {9431,9424,9426 ,5011,5004,5006 ,0,0,0}, - {9416,9418,9425 ,4996,4998,5005 ,0,0,0}, {9521,9522,9523 ,5099,5100,5101 ,0,0,0}, - {9524,9525,9526 ,5102,5103,5104 ,0,0,0}, {9527,9525,9524 ,5105,5103,5102 ,0,0,0}, - {9528,9524,9526 ,5106,5102,5104 ,0,0,0}, {9529,9530,9531 ,5107,5108,5109 ,0,0,0}, - {9532,9533,9528 ,5110,5108,5106 ,0,0,0}, {9530,9534,9531 ,5108,5111,5109 ,0,0,0}, - {9530,9533,9534 ,5108,5108,5111 ,0,0,0}, {9534,9535,9536 ,5111,5112,5113 ,0,0,0}, - {9535,9537,9536 ,5112,5114,5113 ,0,0,0}, {9536,9537,9538 ,5113,5114,5115 ,0,0,0}, - {9537,9539,9538 ,5114,5116,5115 ,0,0,0}, {9540,9541,9539 ,5117,5118,5116 ,0,0,0}, - {9540,9542,9543 ,5117,5119,5120 ,0,0,0}, {9544,9543,9542 ,5121,5120,5119 ,0,0,0}, - {9544,9542,9545 ,5121,5119,5122 ,0,0,0}, {9545,9546,9544 ,5122,5123,5121 ,0,0,0}, - {9541,9538,9539 ,5118,5115,5116 ,0,0,0}, {9543,9541,9540 ,5120,5118,5117 ,0,0,0}, - {9546,9547,9548 ,5123,5124,5125 ,0,0,0}, {9547,9546,9545 ,5124,5123,5122 ,0,0,0}, - {9125,9548,9547 ,5126,5125,5124 ,0,0,0}, {9527,9524,9549 ,5105,5102,5127 ,0,0,0}, - {9550,9551,9552 ,5128,5129,5130 ,0,0,0}, {9550,9549,9551 ,5128,5127,5129 ,0,0,0}, - {9551,9553,9552 ,5129,5131,5130 ,0,0,0}, {9553,9551,9554 ,5131,5129,5132 ,0,0,0}, - {9555,9556,9557 ,5133,5134,5135 ,0,0,0}, {9555,9554,9556 ,5133,5132,5134 ,0,0,0}, - {9558,9557,9556 ,5136,5135,5134 ,0,0,0}, {9557,9558,9559 ,5135,5136,5137 ,0,0,0}, - {9560,9561,9562 ,5138,5139,5140 ,0,0,0}, {9563,9564,9558 ,5141,5142,5136 ,0,0,0}, - {9565,9566,9563 ,5143,5144,5141 ,0,0,0}, {9566,9565,9567 ,5144,5143,5145 ,0,0,0}, - {9568,9569,9565 ,5146,5147,5143 ,0,0,0}, {9522,9521,9570 ,5100,5099,5148 ,0,0,0}, - {9571,9572,9568 ,5149,5150,5146 ,0,0,0}, {9573,9574,9575 ,5151,5152,5153 ,0,0,0}, - {9576,9577,9578 ,5154,5155,5156 ,0,0,0}, {9579,9580,9581 ,5157,5158,5159 ,0,0,0}, - {9582,9583,9584 ,5160,5161,5162 ,0,0,0}, {9585,9586,9587 ,5163,5164,5165 ,0,0,0}, - {9588,9589,9590 ,5166,5167,5168 ,0,0,0}, {9588,9591,9592 ,5166,5169,5170 ,0,0,0}, - {9593,9594,9595 ,5171,5172,5173 ,0,0,0}, {9596,9597,9598 ,5174,5175,5176 ,0,0,0}, - {9599,9600,9601 ,5177,5178,5179 ,0,0,0}, {9602,9594,9593 ,5180,5172,5171 ,0,0,0}, - {9603,9604,9605 ,5179,5181,5182 ,0,0,0}, {9603,9601,9600 ,5179,5179,5178 ,0,0,0}, - {9606,9607,9608 ,5183,5184,5185 ,0,0,0}, {9609,9606,9605 ,5186,5183,5182 ,0,0,0}, - {9610,9611,9612 ,5187,5188,5189 ,0,0,0}, {9613,9610,9608 ,5190,5187,5185 ,0,0,0}, - {9614,9615,9616 ,5191,5192,5193 ,0,0,0}, {9615,9614,9612 ,5192,5191,5189 ,0,0,0}, - {9617,9618,9616 ,5194,5195,5193 ,0,0,0}, {9614,9616,9618 ,5191,5193,5195 ,0,0,0}, - {9617,9619,9620 ,5194,5196,5197 ,0,0,0}, {9620,9618,9617 ,5197,5195,5194 ,0,0,0}, - {9613,9611,9610 ,5190,5188,5187 ,0,0,0}, {9611,9615,9612 ,5188,5192,5189 ,0,0,0}, - {9607,9613,9608 ,5184,5190,5185 ,0,0,0}, {9609,9607,9606 ,5186,5184,5183 ,0,0,0}, - {9604,9609,9605 ,5181,5186,5182 ,0,0,0}, {9604,9603,9600 ,5181,5179,5178 ,0,0,0}, - {9600,9621,9604 ,5178,5198,5181 ,0,0,0}, {9593,9621,9602 ,5171,5198,5180 ,0,0,0}, - {9621,9600,9602 ,5198,5178,5180 ,0,0,0}, {9622,9623,9624 ,5199,5200,5201 ,0,0,0}, - {9595,9594,9596 ,5173,5172,5174 ,0,0,0}, {9622,9625,9626 ,5199,5202,5203 ,0,0,0}, - {9626,9623,9622 ,5203,5200,5199 ,0,0,0}, {9627,9625,9628 ,5204,5202,5205 ,0,0,0}, - {9625,9627,9626 ,5202,5204,5203 ,0,0,0}, {9629,9223,9628 ,5206,5207,5205 ,0,0,0}, - {9627,9628,9223 ,5204,5205,5207 ,0,0,0}, {9226,9223,9629 ,5197,5207,5206 ,0,0,0}, - {9624,9623,9630 ,5201,5200,5208 ,0,0,0}, {9631,9632,9633 ,5209,5210,5211 ,0,0,0}, - {9624,9630,9633 ,5201,5208,5211 ,0,0,0}, {9631,9634,9632 ,5209,5212,5210 ,0,0,0}, - {9633,9630,9631 ,5211,5208,5209 ,0,0,0}, {9597,9589,9598 ,5175,5167,5176 ,0,0,0}, - {9634,9635,9632 ,5212,5213,5210 ,0,0,0}, {9601,9635,9599 ,5179,5213,5177 ,0,0,0}, - {9634,9599,9635 ,5212,5177,5213 ,0,0,0}, {9596,9598,9595 ,5174,5176,5173 ,0,0,0}, - {9587,9576,9585 ,5165,5154,5163 ,0,0,0}, {9588,9590,9591 ,5166,5168,5169 ,0,0,0}, - {9589,9597,9590 ,5167,5175,5168 ,0,0,0}, {9591,9584,9592 ,5169,5162,5170 ,0,0,0}, - {9586,9583,9582 ,5164,5161,5160 ,0,0,0}, {9583,9592,9584 ,5161,5170,5162 ,0,0,0}, - {9587,9586,9582 ,5165,5164,5160 ,0,0,0}, {9573,9580,9579 ,5151,5158,5157 ,0,0,0}, - {9576,9578,9585 ,5154,5156,5163 ,0,0,0}, {9577,9581,9578 ,5155,5159,5156 ,0,0,0}, - {9575,9580,9573 ,5153,5158,5151 ,0,0,0}, {9577,9579,9581 ,5155,5157,5159 ,0,0,0}, - {9523,9575,9574 ,5101,5153,5152 ,0,0,0}, {9574,9175,9571 ,5152,5214,5149 ,0,0,0}, - {9529,9636,9530 ,5107,5215,5108 ,0,0,0}, {9535,9534,9533 ,5112,5111,5108 ,0,0,0}, - {9532,9637,9533 ,5110,5216,5108 ,0,0,0}, {9535,9533,9637 ,5112,5108,5216 ,0,0,0}, - {9638,9636,9639 ,5217,5215,5218 ,0,0,0}, {9526,9532,9528 ,5104,5110,5106 ,0,0,0}, - {9640,9638,9641 ,5219,5217,5220 ,0,0,0}, {9640,9642,9638 ,5219,5221,5217 ,0,0,0}, - {9643,9642,9644 ,5222,5221,5223 ,0,0,0}, {9550,9527,9549 ,5128,5105,5127 ,0,0,0}, - {9645,9643,9646 ,5224,5222,5225 ,0,0,0}, {9645,9647,9643 ,5224,5226,5222 ,0,0,0}, - {9648,9647,9649 ,5227,5226,5228 ,0,0,0}, {9555,9553,9554 ,5133,5131,5132 ,0,0,0}, - {9650,9651,9648 ,5229,5230,5227 ,0,0,0}, {9652,9651,9650 ,5231,5230,5229 ,0,0,0}, - {9653,9651,9654 ,5232,5230,5233 ,0,0,0}, {9564,9559,9558 ,5142,5137,5136 ,0,0,0}, - {9562,9653,9560 ,5140,5232,5138 ,0,0,0}, {9566,9564,9563 ,5144,5142,5141 ,0,0,0}, - {9655,9562,9656 ,5234,5140,5235 ,0,0,0}, {9569,9567,9565 ,5147,5145,5143 ,0,0,0}, - {9521,9655,9570 ,5099,5234,5148 ,0,0,0}, {9572,9569,9568 ,5150,5147,5146 ,0,0,0}, - {9572,9571,9175 ,5150,5149,5214 ,0,0,0}, {9574,9571,9523 ,5152,5149,5101 ,0,0,0}, - {9523,9571,9521 ,5101,5149,5099 ,0,0,0}, {9656,9570,9655 ,5235,5148,5234 ,0,0,0}, - {9561,9656,9562 ,5139,5235,5140 ,0,0,0}, {9654,9560,9653 ,5233,5138,5232 ,0,0,0}, - {9652,9654,9651 ,5231,5233,5230 ,0,0,0}, {9649,9650,9648 ,5228,5229,5227 ,0,0,0}, - {9645,9649,9647 ,5224,5228,5226 ,0,0,0}, {9644,9646,9643 ,5223,5225,5222 ,0,0,0}, - {9640,9644,9642 ,5219,5223,5221 ,0,0,0}, {9639,9641,9638 ,5218,5220,5217 ,0,0,0}, - {9529,9639,9636 ,5107,5218,5215 ,0,0,0}, {9657,9658,9659 ,5236,5237,5238 ,0,0,0}, - {9660,9661,9659 ,5239,5240,5238 ,0,0,0}, {9657,9659,9661 ,5236,5238,5240 ,0,0,0}, - {9660,9662,9663 ,5239,5241,5242 ,0,0,0}, {9663,9661,9660 ,5242,5240,5239 ,0,0,0}, - {9664,9662,9665 ,5243,5241,5244 ,0,0,0}, {9662,9664,9663 ,5241,5243,5242 ,0,0,0}, - {9666,9667,9665 ,5245,5246,5244 ,0,0,0}, {9664,9665,9667 ,5243,5244,5246 ,0,0,0}, - {9666,9668,9669 ,5245,5247,5248 ,0,0,0}, {9669,9667,9666 ,5248,5246,5245 ,0,0,0}, - {9670,9668,9671 ,5249,5247,5250 ,0,0,0}, {9668,9670,9669 ,5247,5249,5248 ,0,0,0}, - {9672,9673,9671 ,5251,5252,5250 ,0,0,0}, {9670,9671,9673 ,5249,5250,5252 ,0,0,0}, - {9672,9674,9675 ,5251,5253,5254 ,0,0,0}, {9675,9673,9672 ,5254,5252,5251 ,0,0,0}, - {9676,9674,9677 ,5255,5253,5256 ,0,0,0}, {9674,9676,9675 ,5253,5255,5254 ,0,0,0}, - {9678,9679,9677 ,5257,5258,5256 ,0,0,0}, {9676,9677,9679 ,5255,5256,5258 ,0,0,0}, - {9678,9680,9681 ,5257,5259,5260 ,0,0,0}, {9681,9679,9678 ,5260,5258,5257 ,0,0,0}, - {9682,9680,9683 ,5261,5259,5262 ,0,0,0}, {9680,9682,9681 ,5259,5261,5260 ,0,0,0}, - {9684,9685,9683 ,5263,5264,5262 ,0,0,0}, {9682,9683,9685 ,5261,5262,5264 ,0,0,0}, - {9684,9686,9687 ,5263,5265,5266 ,0,0,0}, {9687,9685,9684 ,5266,5264,5263 ,0,0,0}, - {9688,9686,9689 ,5267,5265,5268 ,0,0,0}, {9686,9688,9687 ,5265,5267,5266 ,0,0,0}, - {9690,9691,9689 ,5269,5270,5268 ,0,0,0}, {9688,9689,9691 ,5267,5268,5270 ,0,0,0}, - {9690,9692,9693 ,5269,5271,5272 ,0,0,0}, {9693,9691,9690 ,5272,5270,5269 ,0,0,0}, - {9694,9692,9695 ,5273,5271,5274 ,0,0,0}, {9692,9694,9693 ,5271,5273,5272 ,0,0,0}, - {9696,9697,9695 ,5275,5276,5274 ,0,0,0}, {9694,9695,9697 ,5273,5274,5276 ,0,0,0}, - {9696,9698,9699 ,5275,5277,5278 ,0,0,0}, {9699,9697,9696 ,5278,5276,5275 ,0,0,0}, - {9700,9698,9701 ,5279,5277,5280 ,0,0,0}, {9698,9700,9699 ,5277,5279,5278 ,0,0,0}, - {9702,9703,9701 ,5281,5282,5280 ,0,0,0}, {9700,9701,9703 ,5279,5280,5282 ,0,0,0}, - {9704,9702,9705 ,5283,5281,5284 ,0,0,0}, {9704,9703,9702 ,5283,5282,5281 ,0,0,0}, - {9706,9705,9707 ,5285,5284,5286 ,0,0,0}, {9702,9707,9705 ,5281,5286,5284 ,0,0,0}, - {9708,9706,9709 ,5287,5285,5288 ,0,0,0}, {9706,9707,9709 ,5285,5286,5288 ,0,0,0}, - {9708,9710,9711 ,5287,5289,5290 ,0,0,0}, {9711,9706,9708 ,5290,5285,5287 ,0,0,0}, - {9710,9712,9711 ,5289,5291,5290 ,0,0,0}, {9713,9658,9657 ,5292,5237,5236 ,0,0,0}, - {9713,9714,9715 ,5292,5293,5294 ,0,0,0}, {9715,9658,9713 ,5294,5237,5292 ,0,0,0}, - {9716,9714,9717 ,5295,5293,5296 ,0,0,0}, {9714,9716,9715 ,5293,5295,5294 ,0,0,0}, - {9718,9719,9717 ,5297,5298,5296 ,0,0,0}, {9716,9717,9719 ,5295,5296,5298 ,0,0,0}, - {9718,9720,9721 ,5297,5299,5300 ,0,0,0}, {9721,9719,9718 ,5300,5298,5297 ,0,0,0}, - {9722,9720,9723 ,5301,5299,5302 ,0,0,0}, {9720,9722,9721 ,5299,5301,5300 ,0,0,0}, - {9724,9725,9723 ,5303,5304,5302 ,0,0,0}, {9722,9723,9725 ,5301,5302,5304 ,0,0,0}, - {9724,9726,9727 ,5303,5305,5306 ,0,0,0}, {9727,9725,9724 ,5306,5304,5303 ,0,0,0}, - {9728,9726,9729 ,5307,5305,5308 ,0,0,0}, {9726,9728,9727 ,5305,5307,5306 ,0,0,0}, - {9730,9731,9729 ,5309,5310,5308 ,0,0,0}, {9728,9729,9731 ,5307,5308,5310 ,0,0,0}, - {9730,9732,9733 ,5309,5311,5312 ,0,0,0}, {9733,9731,9730 ,5312,5310,5309 ,0,0,0}, - {9734,9732,9735 ,5313,5311,5314 ,0,0,0}, {9732,9734,9733 ,5311,5313,5312 ,0,0,0}, - {9736,9737,9735 ,5315,5316,5314 ,0,0,0}, {9734,9735,9737 ,5313,5314,5316 ,0,0,0}, - {9736,9738,9739 ,5315,5317,5318 ,0,0,0}, {9739,9737,9736 ,5318,5316,5315 ,0,0,0}, - {9740,9738,9741 ,5319,5317,5320 ,0,0,0}, {9738,9740,9739 ,5317,5319,5318 ,0,0,0}, - {9742,9743,9741 ,5321,5322,5320 ,0,0,0}, {9740,9741,9743 ,5319,5320,5322 ,0,0,0}, - {9742,9744,9745 ,5321,5323,5324 ,0,0,0}, {9745,9743,9742 ,5324,5322,5321 ,0,0,0}, - {9746,9744,9747 ,5325,5323,5326 ,0,0,0}, {9744,9746,9745 ,5323,5325,5324 ,0,0,0}, - {9748,9749,9747 ,5327,5328,5326 ,0,0,0}, {9746,9747,9749 ,5325,5326,5328 ,0,0,0}, - {9748,9750,9751 ,5327,5329,5330 ,0,0,0}, {9751,9749,9748 ,5330,5328,5327 ,0,0,0}, - {9752,9750,9753 ,5331,5329,5332 ,0,0,0}, {9750,9752,9751 ,5329,5331,5330 ,0,0,0}, - {9754,9755,9753 ,5333,5334,5332 ,0,0,0}, {9752,9753,9755 ,5331,5332,5334 ,0,0,0}, - {9754,9756,9757 ,5333,5335,5336 ,0,0,0}, {9757,9755,9754 ,5336,5334,5333 ,0,0,0}, - {9758,9759,9756 ,5337,5338,5335 ,0,0,0}, {9756,9759,9757 ,5335,5338,5336 ,0,0,0}, - {9760,9761,9758 ,5339,5340,5337 ,0,0,0}, {9758,9756,9760 ,5337,5335,5339 ,0,0,0}, - {9762,9763,9761 ,5341,5342,5340 ,0,0,0}, {9762,9761,9760 ,5341,5340,5339 ,0,0,0}, - {9764,9763,9765 ,5343,5342,5344 ,0,0,0}, {9763,9764,9761 ,5342,5343,5340 ,0,0,0}, - {9764,9765,9766 ,5343,5344,5345 ,0,0,0}, {9767,9768,9769 ,5346,5347,5348 ,0,0,0}, - {9770,9771,9769 ,5349,5350,5348 ,0,0,0}, {9767,9769,9771 ,5346,5348,5350 ,0,0,0}, - {9770,9772,9773 ,5349,5351,5352 ,0,0,0}, {9773,9771,9770 ,5352,5350,5349 ,0,0,0}, - {9774,9772,9775 ,5353,5351,5354 ,0,0,0}, {9772,9774,9773 ,5351,5353,5352 ,0,0,0}, - {9776,9777,9775 ,5355,5356,5354 ,0,0,0}, {9774,9775,9777 ,5353,5354,5356 ,0,0,0}, - {9776,9778,9779 ,5355,5357,5358 ,0,0,0}, {9779,9777,9776 ,5358,5356,5355 ,0,0,0}, - {9780,9778,9781 ,5359,5357,5360 ,0,0,0}, {9778,9780,9779 ,5357,5359,5358 ,0,0,0}, - {9782,9783,9781 ,5361,5362,5360 ,0,0,0}, {9780,9781,9783 ,5359,5360,5362 ,0,0,0}, - {9782,9784,9785 ,5361,5363,5364 ,0,0,0}, {9785,9783,9782 ,5364,5362,5361 ,0,0,0}, - {9786,9784,9787 ,5365,5363,5366 ,0,0,0}, {9784,9786,9785 ,5363,5365,5364 ,0,0,0}, - {9788,9789,9787 ,5367,5368,5366 ,0,0,0}, {9786,9787,9789 ,5365,5366,5368 ,0,0,0}, - {9788,9790,9791 ,5367,5369,5370 ,0,0,0}, {9791,9789,9788 ,5370,5368,5367 ,0,0,0}, - {9792,9790,9793 ,5371,5369,5372 ,0,0,0}, {9790,9792,9791 ,5369,5371,5370 ,0,0,0}, - {9794,9795,9793 ,5373,5374,5372 ,0,0,0}, {9792,9793,9795 ,5371,5372,5374 ,0,0,0}, - {9794,9796,9797 ,5373,5375,5376 ,0,0,0}, {9797,9795,9794 ,5376,5374,5373 ,0,0,0}, - {9798,9796,9799 ,5377,5375,5378 ,0,0,0}, {9796,9798,9797 ,5375,5377,5376 ,0,0,0}, - {9800,9801,9799 ,5379,5380,5378 ,0,0,0}, {9798,9799,9801 ,5377,5378,5380 ,0,0,0}, - {9800,9802,9803 ,5379,5381,5382 ,0,0,0}, {9803,9801,9800 ,5382,5380,5379 ,0,0,0}, - {9804,9802,9805 ,5383,5381,5384 ,0,0,0}, {9802,9804,9803 ,5381,5383,5382 ,0,0,0}, - {9806,9807,9805 ,5385,5386,5384 ,0,0,0}, {9804,9805,9807 ,5383,5384,5386 ,0,0,0}, - {9806,9808,9809 ,5385,5387,5388 ,0,0,0}, {9809,9807,9806 ,5388,5386,5385 ,0,0,0}, - {9810,9808,9811 ,5389,5387,5390 ,0,0,0}, {9808,9810,9809 ,5387,5389,5388 ,0,0,0}, - {9812,9813,9811 ,5391,5392,5390 ,0,0,0}, {9810,9811,9813 ,5389,5390,5392 ,0,0,0}, - {9812,9814,9815 ,5391,5393,5394 ,0,0,0}, {9815,9813,9812 ,5394,5392,5391 ,0,0,0}, - {9816,9814,9817 ,5395,5393,5396 ,0,0,0}, {9814,9816,9815 ,5393,5395,5394 ,0,0,0}, - {9818,9819,9817 ,5397,5398,5396 ,0,0,0}, {9816,9817,9819 ,5395,5396,5398 ,0,0,0}, - {9818,9820,9821 ,5397,5399,5400 ,0,0,0}, {9821,9819,9818 ,5400,5398,5397 ,0,0,0}, - {9822,9820,9823 ,5401,5399,5402 ,0,0,0}, {9820,9822,9821 ,5399,5401,5400 ,0,0,0}, - {9824,9825,9823 ,5403,5404,5402 ,0,0,0}, {9822,9823,9825 ,5401,5402,5404 ,0,0,0}, - {9824,9826,9827 ,5403,5405,5406 ,0,0,0}, {9827,9825,9824 ,5406,5404,5403 ,0,0,0}, - {9826,9828,9827 ,5405,5407,5406 ,0,0,0}, {9829,9768,9767 ,5408,5347,5346 ,0,0,0}, - {9829,9830,9831 ,5408,5409,5410 ,0,0,0}, {9831,9768,9829 ,5410,5347,5408 ,0,0,0}, - {9832,9830,9833 ,5411,5409,5412 ,0,0,0}, {9830,9832,9831 ,5409,5411,5410 ,0,0,0}, - {9834,9835,9833 ,5413,5414,5412 ,0,0,0}, {9832,9833,9835 ,5411,5412,5414 ,0,0,0}, - {9834,9836,9837 ,5413,5415,5416 ,0,0,0}, {9837,9835,9834 ,5416,5414,5413 ,0,0,0}, - {9838,9836,9839 ,5417,5415,5418 ,0,0,0}, {9836,9838,9837 ,5415,5417,5416 ,0,0,0}, - {9840,9841,9839 ,5419,5420,5418 ,0,0,0}, {9838,9839,9841 ,5417,5418,5420 ,0,0,0}, - {9840,9842,9843 ,5419,5421,5422 ,0,0,0}, {9843,9841,9840 ,5422,5420,5419 ,0,0,0}, - {9844,9842,9845 ,5423,5421,5424 ,0,0,0}, {9842,9844,9843 ,5421,5423,5422 ,0,0,0}, - {9846,9847,9845 ,5425,5426,5424 ,0,0,0}, {9844,9845,9847 ,5423,5424,5426 ,0,0,0}, - {9846,9848,9849 ,5425,5427,5428 ,0,0,0}, {9849,9847,9846 ,5428,5426,5425 ,0,0,0}, - {9850,9848,9851 ,5429,5427,5430 ,0,0,0}, {9848,9850,9849 ,5427,5429,5428 ,0,0,0}, - {9852,9853,9851 ,5431,5432,5430 ,0,0,0}, {9850,9851,9853 ,5429,5430,5432 ,0,0,0}, - {9852,9854,9855 ,5431,5433,5434 ,0,0,0}, {9855,9853,9852 ,5434,5432,5431 ,0,0,0}, - {9856,9854,9857 ,5435,5433,5436 ,0,0,0}, {9854,9856,9855 ,5433,5435,5434 ,0,0,0}, - {9858,9859,9857 ,5437,5438,5436 ,0,0,0}, {9856,9857,9859 ,5435,5436,5438 ,0,0,0}, - {9858,9860,9861 ,5437,5439,5440 ,0,0,0}, {9861,9859,9858 ,5440,5438,5437 ,0,0,0}, - {9862,9860,9863 ,5441,5439,5442 ,0,0,0}, {9860,9862,9861 ,5439,5441,5440 ,0,0,0}, - {9864,9865,9863 ,5443,5444,5442 ,0,0,0}, {9862,9863,9865 ,5441,5442,5444 ,0,0,0}, - {9864,9866,9867 ,5443,5445,5446 ,0,0,0}, {9867,9865,9864 ,5446,5444,5443 ,0,0,0}, - {9868,9866,9869 ,5447,5445,5448 ,0,0,0}, {9866,9868,9867 ,5445,5447,5446 ,0,0,0}, - {9870,9871,9869 ,5449,5450,5448 ,0,0,0}, {9868,9869,9871 ,5447,5448,5450 ,0,0,0}, - {9870,9872,9873 ,5449,5451,5452 ,0,0,0}, {9873,9871,9870 ,5452,5450,5449 ,0,0,0}, - {9874,9872,9875 ,5453,5451,5454 ,0,0,0}, {9872,9874,9873 ,5451,5453,5452 ,0,0,0}, - {9876,9877,9875 ,5455,5456,5454 ,0,0,0}, {9874,9875,9877 ,5453,5454,5456 ,0,0,0}, - {9876,9878,9879 ,5455,5457,5458 ,0,0,0}, {9879,9877,9876 ,5458,5456,5455 ,0,0,0}, - {9880,9878,9881 ,5459,5457,5460 ,0,0,0}, {9878,9880,9879 ,5457,5459,5458 ,0,0,0}, - {9882,9883,9881 ,5461,5462,5460 ,0,0,0}, {9880,9881,9883 ,5459,5460,5462 ,0,0,0}, - {9882,9884,9885 ,5461,5463,5464 ,0,0,0}, {9885,9883,9882 ,5464,5462,5461 ,0,0,0}, - {9886,9884,9887 ,5465,5463,5466 ,0,0,0}, {9884,9886,9885 ,5463,5465,5464 ,0,0,0}, - {9886,9887,9888 ,5465,5466,5467 ,0,0,0}, {9889,8923,8922 ,5468,5469,5469 ,0,0,0}, - {9890,9891,9892 ,726,726,726 ,0,0,0}, {9893,8656,8653 ,726,5470,726 ,0,0,0}, - {9894,9895,9896 ,5471,726,726 ,0,0,0}, {9897,9898,9899 ,726,726,726 ,0,0,0}, - {9900,8878,9901 ,5468,5471,5469 ,0,0,0}, {9902,9903,9904 ,5470,726,726 ,0,0,0}, - {9905,9906,9907 ,5471,5469,5469 ,0,0,0}, {9908,9907,8851 ,5468,5469,5469 ,0,0,0}, - {9909,9910,8957 ,5469,5472,5468 ,0,0,0}, {9911,9912,9913 ,5469,5468,5471 ,0,0,0}, - {9914,9915,9916 ,5473,5474,726 ,0,0,0}, {9917,9918,9919 ,5475,5476,5471 ,0,0,0}, - {9920,9921,9922 ,5477,5478,5469 ,0,0,0}, {9915,9914,9923 ,5474,5473,5479 ,0,0,0}, - {9924,9925,9926 ,5471,5469,726 ,0,0,0}, {9927,9928,8916 ,5468,5469,5471 ,0,0,0}, - {9929,9930,9931 ,726,5480,5481 ,0,0,0}, {9922,9932,9933 ,5469,726,5468 ,0,0,0}, - {9934,9935,9936 ,5475,5475,5482 ,0,0,0}, {9937,8591,9934 ,5468,5483,5475 ,0,0,0}, - {9936,9938,9939 ,5482,5482,5482 ,0,0,0}, {9935,9938,9936 ,5475,5482,5482 ,0,0,0}, - {9939,9940,9936 ,5482,5475,5482 ,0,0,0}, {9931,9925,9941 ,5481,5469,5475 ,0,0,0}, - {9942,8971,9943 ,726,5471,5484 ,0,0,0}, {9915,9923,9933 ,5474,5479,5468 ,0,0,0}, - {9944,9945,9946 ,5475,5485,5468 ,0,0,0}, {9947,9948,9949 ,5486,5483,5468 ,0,0,0}, - {9932,9915,9933 ,726,5474,5468 ,0,0,0}, {8916,9928,8917 ,5471,5469,726 ,0,0,0}, - {8923,9889,8925 ,5469,5468,726 ,0,0,0}, {8929,8928,9950 ,5471,5471,726 ,0,0,0}, - {8957,8927,9909 ,5468,5468,5469 ,0,0,0}, {8955,8927,8957 ,5471,5468,5468 ,0,0,0}, - {8929,9951,8954 ,5471,5471,5469 ,0,0,0}, {9952,8961,8960 ,5468,5478,726 ,0,0,0}, - {8928,9953,9950 ,5471,726,726 ,0,0,0}, {8884,9954,9955 ,5471,5468,726 ,0,0,0}, - {9956,8971,8969 ,5475,5471,726 ,0,0,0}, {9957,9958,9959 ,5469,5482,5483 ,0,0,0}, - {9960,9958,9961 ,5468,5482,5475 ,0,0,0}, {9962,9963,9964 ,726,5468,5468 ,0,0,0}, - {9965,9913,9966 ,726,5471,5469 ,0,0,0}, {9967,9968,9969 ,5475,5475,726 ,0,0,0}, - {9963,9962,9970 ,5468,726,5483 ,0,0,0}, {9971,9972,9973 ,5480,5487,5475 ,0,0,0}, - {9970,9974,9957 ,5483,5478,5469 ,0,0,0}, {9975,9976,9977 ,5475,5479,5474 ,0,0,0}, - {9977,9943,9975 ,5474,5484,5475 ,0,0,0}, {9978,9979,9977 ,5473,726,5474 ,0,0,0}, - {9978,9977,9976 ,5473,5474,5479 ,0,0,0}, {9960,9959,9958 ,5468,5483,5482 ,0,0,0}, - {9972,9967,9980 ,5487,5475,726 ,0,0,0}, {9958,9957,9974 ,5482,5469,5478 ,0,0,0}, - {9981,9982,9942 ,5486,5478,726 ,0,0,0}, {9965,9966,9964 ,726,5469,5468 ,0,0,0}, - {8881,9954,8884 ,726,5468,5471 ,0,0,0}, {9975,9943,8971 ,5475,5484,5471 ,0,0,0}, - {9983,9984,9985 ,726,726,726 ,0,0,0}, {9986,9987,8887 ,5468,5469,726 ,0,0,0}, - {9956,8969,9988 ,5475,726,5482 ,0,0,0}, {9989,8893,9990 ,726,726,5470 ,0,0,0}, - {8966,9991,9992 ,5475,5485,5475 ,0,0,0}, {9993,9994,8811 ,5471,726,5471 ,0,0,0}, - {8715,9995,8710 ,726,5470,726 ,0,0,0}, {9996,9997,9998 ,5470,5471,5471 ,0,0,0}, - {9999,10000,10001 ,726,726,5470 ,0,0,0}, {10001,9902,9999 ,5470,5470,726 ,0,0,0}, - {9983,9904,9984 ,726,726,726 ,0,0,0}, {10002,10003,10004 ,726,726,5470 ,0,0,0}, - {9896,9996,9998 ,726,5470,5471 ,0,0,0}, {10000,10005,10006 ,726,726,726 ,0,0,0}, - {8895,10007,10008 ,726,5470,726 ,0,0,0}, {10009,10010,10011 ,5470,726,726 ,0,0,0}, - {9984,9904,9903 ,726,726,726 ,0,0,0}, {10007,10012,10013 ,5470,726,5468 ,0,0,0}, - {9984,10014,9985 ,726,726,726 ,0,0,0}, {10013,10015,10016 ,5468,5468,726 ,0,0,0}, - {10012,10015,10013 ,726,5468,5468 ,0,0,0}, {10016,10017,10013 ,726,5471,5468 ,0,0,0}, - {10018,10019,10020 ,726,726,5471 ,0,0,0}, {8895,10012,10007 ,726,726,5470 ,0,0,0}, - {10008,10021,10022 ,726,726,726 ,0,0,0}, {10023,10024,10025 ,726,5488,5489 ,0,0,0}, - {8853,10026,10027 ,5471,5470,726 ,0,0,0}, {8881,9907,9954 ,726,5469,5468 ,0,0,0}, - {10028,8808,8805 ,726,726,5471 ,0,0,0}, {10029,8732,8729 ,726,726,726 ,0,0,0}, - {10030,8665,10031 ,726,5470,726 ,0,0,0}, {10032,8808,10028 ,726,726,726 ,0,0,0}, - {10033,10034,10035 ,726,726,726 ,0,0,0}, {10036,10037,10038 ,5489,726,726 ,0,0,0}, - {8802,10039,8803 ,726,5471,726 ,0,0,0}, {10040,10034,10041 ,726,726,726 ,0,0,0}, - {10042,10043,10044 ,726,726,5489 ,0,0,0}, {10045,10046,10047 ,726,726,726 ,0,0,0}, - {10048,10034,10040 ,726,726,726 ,0,0,0}, {9890,9892,10047 ,726,726,726 ,0,0,0}, - {10049,10050,10051 ,726,726,5489 ,0,0,0}, {9891,10033,10035 ,726,726,726 ,0,0,0}, - {10052,10053,10054 ,726,726,726 ,0,0,0}, {10050,10055,10052 ,726,5488,726 ,0,0,0}, - {10048,10035,10034 ,726,726,726 ,0,0,0}, {9899,10036,8819 ,726,5489,726 ,0,0,0}, - {10056,10057,10058 ,5489,726,726 ,0,0,0}, {10056,10059,10057 ,5489,5488,726 ,0,0,0}, - {10060,10061,10062 ,726,5471,726 ,0,0,0}, {10057,10059,10063 ,726,5488,726 ,0,0,0}, - {10064,10057,10063 ,726,726,726 ,0,0,0}, {10065,8777,10066 ,726,726,726 ,0,0,0}, - {8735,10067,10068 ,726,726,726 ,0,0,0}, {8893,8891,9990 ,726,726,5470 ,0,0,0}, - {9899,8815,10069 ,726,726,726 ,0,0,0}, {10061,10070,10071 ,5471,5471,726 ,0,0,0}, - {10072,8633,10073 ,726,5470,726 ,0,0,0}, {10062,10074,10060 ,726,5471,726 ,0,0,0}, - {8743,10075,10076 ,5489,726,726 ,0,0,0}, {10077,10078,10079 ,726,726,726 ,0,0,0}, - {10080,10081,10079 ,726,5471,726 ,0,0,0}, {10044,10043,10082 ,5489,726,5488 ,0,0,0}, - {10029,10083,8732 ,726,726,726 ,0,0,0}, {10037,9899,10058 ,726,726,726 ,0,0,0}, - {10084,10029,10082 ,726,726,5488 ,0,0,0}, {8659,10085,10086 ,726,5471,726 ,0,0,0}, - {10087,10088,10078 ,726,5488,726 ,0,0,0}, {10079,10089,10090 ,726,5471,726 ,0,0,0}, - {10091,10092,10093 ,726,726,5488 ,0,0,0}, {10094,10095,10091 ,726,726,726 ,0,0,0}, - {10096,10095,10097 ,726,726,726 ,0,0,0}, {10098,8743,10076 ,726,5489,726 ,0,0,0}, - {10099,10079,10100 ,726,726,726 ,0,0,0}, {10076,10075,10101 ,726,726,726 ,0,0,0}, - {10078,10102,10087 ,726,726,726 ,0,0,0}, {10103,10101,10075 ,726,726,726 ,0,0,0}, - {10078,10088,10079 ,726,5488,726 ,0,0,0}, {10103,10104,10101 ,726,5488,726 ,0,0,0}, - {10105,10102,10078 ,726,726,726 ,0,0,0}, {10101,10104,10106 ,726,5488,726 ,0,0,0}, - {10079,10107,10089 ,726,726,5471 ,0,0,0}, {8938,10108,8937 ,5469,5468,5468 ,0,0,0}, - {8938,8943,10109 ,5469,726,726 ,0,0,0}, {10110,8650,10111 ,726,5471,5471 ,0,0,0}, - {10112,8557,10113 ,5470,5468,5468 ,0,0,0}, {8667,10114,10115 ,5470,726,726 ,0,0,0}, - {10116,10117,10118 ,5468,726,5469 ,0,0,0}, {10119,10120,10121 ,5471,5468,726 ,0,0,0}, - {10122,10116,10123 ,5468,5468,726 ,0,0,0}, {10124,10125,10126 ,726,5470,5469 ,0,0,0}, - {10127,10128,10129 ,726,5469,726 ,0,0,0}, {10130,10131,10132 ,5471,5469,726 ,0,0,0}, - {10133,8954,10134 ,726,5469,5470 ,0,0,0}, {10098,10135,10136 ,726,5489,726 ,0,0,0}, - {10079,10081,10137 ,726,5471,726 ,0,0,0}, {10138,8841,8840 ,5468,726,5469 ,0,0,0}, - {10139,10140,10029 ,5470,5471,726 ,0,0,0}, {9893,10141,8656 ,726,726,5470 ,0,0,0}, - {10142,8701,8700 ,5471,726,726 ,0,0,0}, {10143,8943,8941 ,726,726,5468 ,0,0,0}, - {10144,10145,10146 ,726,5470,5471 ,0,0,0}, {10147,10148,10149 ,5471,726,5470 ,0,0,0}, - {10150,10151,10152 ,726,5470,726 ,0,0,0}, {10114,10153,10115 ,726,726,726 ,0,0,0}, - {10153,10114,10154 ,726,726,726 ,0,0,0}, {10115,10145,8667 ,726,5470,5470 ,0,0,0}, - {10153,10154,10155 ,726,726,726 ,0,0,0}, {10127,10121,10120 ,726,726,5468 ,0,0,0}, - {10153,10155,10156 ,726,726,726 ,0,0,0}, {10157,10158,10159 ,5471,5471,5468 ,0,0,0}, - {10125,10132,10126 ,5470,726,5469 ,0,0,0}, {10160,10124,10161 ,726,726,726 ,0,0,0}, - {10162,10163,10131 ,5468,5469,5469 ,0,0,0}, {10131,10130,10162 ,5469,5471,5468 ,0,0,0}, - {10164,10165,10162 ,5471,726,5468 ,0,0,0}, {10162,10165,10163 ,5468,726,5469 ,0,0,0}, - {8961,10166,8963 ,5478,5487,5468 ,0,0,0}, {8895,8893,9989 ,726,726,726 ,0,0,0}, - {9988,8969,8967 ,5482,726,5468 ,0,0,0}, {9987,8890,8887 ,5469,726,726 ,0,0,0}, - {9908,9905,9907 ,5468,5471,5469 ,0,0,0}, {10167,9906,9905 ,5468,5469,5471 ,0,0,0}, - {9912,9911,10168 ,5468,5469,5469 ,0,0,0}, {9906,10167,10169 ,5469,5468,5470 ,0,0,0}, - {9911,9913,9965 ,5469,5471,726 ,0,0,0}, {10168,10169,10170 ,5469,5470,5469 ,0,0,0}, - {9964,9966,9962 ,5468,5469,726 ,0,0,0}, {9970,9957,9963 ,5483,5469,5468 ,0,0,0}, - {9968,9974,9969 ,5475,5478,726 ,0,0,0}, {9974,9970,9969 ,5478,5483,726 ,0,0,0}, - {9981,9971,9982 ,5486,5480,5478 ,0,0,0}, {9972,9968,9967 ,5487,5475,5475 ,0,0,0}, - {9971,9973,9982 ,5480,5475,5478 ,0,0,0}, {9973,9972,9980 ,5475,5487,726 ,0,0,0}, - {9943,9981,9942 ,5484,5486,726 ,0,0,0}, {9956,9975,8971 ,5475,5475,5471 ,0,0,0}, - {9988,8967,9992 ,5482,5468,5475 ,0,0,0}, {9992,8967,8966 ,5475,5468,5475 ,0,0,0}, - {8963,10166,9991 ,5468,5487,5485 ,0,0,0}, {9991,8966,8963 ,5485,5475,5468 ,0,0,0}, - {9952,10166,8961 ,5468,5487,5478 ,0,0,0}, {9910,9952,8960 ,5472,5468,726 ,0,0,0}, - {10134,8954,9951 ,5470,5469,5471 ,0,0,0}, {8957,9910,8960 ,5468,5472,726 ,0,0,0}, - {10171,10172,8937 ,5471,5470,5468 ,0,0,0}, {8934,10172,10173 ,726,5470,726 ,0,0,0}, - {9919,10174,9917 ,5471,5468,5475 ,0,0,0}, {9928,10175,8917 ,5469,5469,726 ,0,0,0}, - {10176,10177,9937 ,5472,5482,5468 ,0,0,0}, {8900,8569,8896 ,5468,5468,5468 ,0,0,0}, - {8577,8575,10116 ,5471,726,5468 ,0,0,0}, {8832,8479,8830 ,5471,726,5469 ,0,0,0}, - {8843,10178,8846 ,5471,726,726 ,0,0,0}, {10028,8805,9894 ,726,5471,5471 ,0,0,0}, - {8499,10179,10180 ,726,726,5470 ,0,0,0}, {10181,10182,8741 ,726,726,726 ,0,0,0}, - {10183,8861,10184 ,726,726,5471 ,0,0,0}, {8476,10185,8473 ,5471,5471,5471 ,0,0,0}, - {8488,10186,10187 ,726,5469,5469 ,0,0,0}, {8827,8940,8946 ,5471,5469,5469 ,0,0,0}, - {8934,8937,10172 ,726,5468,5470 ,0,0,0}, {8950,8828,8946 ,5468,726,5469 ,0,0,0}, - {8940,8484,8941 ,5469,5471,5468 ,0,0,0}, {10143,10109,8943 ,726,726,726 ,0,0,0}, - {10109,10108,8938 ,726,5468,5469 ,0,0,0}, {10108,10171,8937 ,5468,5471,5468 ,0,0,0}, - {8931,8934,10173 ,726,726,726 ,0,0,0}, {8927,8955,10133 ,5468,5471,726 ,0,0,0}, - {8931,9953,8928 ,726,726,5471 ,0,0,0}, {9953,8931,10173 ,726,726,726 ,0,0,0}, - {9950,9951,8929 ,726,5471,5471 ,0,0,0}, {8954,10133,8955 ,5469,726,5471 ,0,0,0}, - {8925,10188,8927 ,726,5468,5468 ,0,0,0}, {9918,9909,10189 ,5476,5469,5468 ,0,0,0}, - {10188,9909,8927 ,5468,5469,5468 ,0,0,0}, {8917,10175,8919 ,726,5469,5470 ,0,0,0}, - {8922,8919,10190 ,5469,5470,726 ,0,0,0}, {10175,10190,8919 ,5469,726,5470 ,0,0,0}, - {9921,9920,9945 ,5478,5477,5485 ,0,0,0}, {8897,8569,9927 ,726,5468,5468 ,0,0,0}, - {8897,9927,8916 ,726,5468,5471 ,0,0,0}, {10191,10192,8589 ,5470,5470,5468 ,0,0,0}, - {8591,9935,9934 ,5483,5475,5475 ,0,0,0}, {10193,8575,8574 ,5468,726,5468 ,0,0,0}, - {10194,8549,10195 ,5469,5468,5471 ,0,0,0}, {8663,10031,8665 ,726,726,5470 ,0,0,0}, - {10196,10197,8625 ,5471,5471,5471 ,0,0,0}, {10198,8713,10199 ,726,726,5471 ,0,0,0}, - {10200,10201,10202 ,5471,5470,5471 ,0,0,0}, {8709,8710,10203 ,726,726,726 ,0,0,0}, - {8653,10070,9893 ,726,5471,726 ,0,0,0}, {10083,10029,10204 ,726,726,726 ,0,0,0}, - {8949,10205,8821 ,726,5468,5469 ,0,0,0}, {8846,10206,8847 ,726,726,5468 ,0,0,0}, - {8815,9899,8817 ,726,726,726 ,0,0,0}, {9994,8814,8811 ,726,5471,5471 ,0,0,0}, - {8775,9895,9894 ,726,726,5471 ,0,0,0}, {9896,9895,9996 ,726,726,5470 ,0,0,0}, - {10005,10018,10006 ,726,726,726 ,0,0,0}, {10020,10207,9997 ,5471,726,5471 ,0,0,0}, - {9998,9997,10207 ,5471,5471,726 ,0,0,0}, {10019,10018,10005 ,726,726,726 ,0,0,0}, - {10019,10207,10020 ,726,726,5471 ,0,0,0}, {10006,10001,10000 ,726,5470,726 ,0,0,0}, - {9902,9904,9999 ,5470,726,726 ,0,0,0}, {10003,9903,10004 ,726,726,5470 ,0,0,0}, - {9903,9902,10004 ,726,5470,5470 ,0,0,0}, {10010,10022,10021 ,726,726,726 ,0,0,0}, - {10002,10011,10208 ,726,726,5471 ,0,0,0}, {10208,10003,10002 ,5471,726,726 ,0,0,0}, - {10010,10009,10022 ,726,5470,726 ,0,0,0}, {10011,10010,10208 ,726,726,5471 ,0,0,0}, - {10007,10021,10008 ,5470,726,726 ,0,0,0}, {9989,10012,8895 ,726,726,726 ,0,0,0}, - {8881,8879,9907 ,726,726,5469 ,0,0,0}, {9990,8891,10209 ,5470,726,5470 ,0,0,0}, - {8890,9987,10209 ,726,5469,5470 ,0,0,0}, {10209,8891,8890 ,5470,726,726 ,0,0,0}, - {9986,8885,9955 ,5468,726,726 ,0,0,0}, {8885,9986,8887 ,726,5468,726 ,0,0,0}, - {8884,9955,8885 ,5471,726,726 ,0,0,0}, {10027,8878,8853 ,726,5471,5471 ,0,0,0}, - {8853,8852,10026 ,5471,5471,5470 ,0,0,0}, {9901,8878,10027 ,5469,5471,726 ,0,0,0}, - {10210,10211,8855 ,5470,5470,726 ,0,0,0}, {10183,8858,8861 ,726,5470,726 ,0,0,0}, - {10211,8852,8855 ,5470,5471,726 ,0,0,0}, {8862,8867,10212 ,726,726,726 ,0,0,0}, - {8862,10213,8861 ,726,5470,726 ,0,0,0}, {10214,8867,8865 ,726,726,5470 ,0,0,0}, - {8754,8756,8493 ,726,726,726 ,0,0,0}, {8870,8751,8864 ,726,726,5471 ,0,0,0}, - {8767,10215,8770 ,726,726,5470 ,0,0,0}, {8841,10216,8843 ,726,5471,5471 ,0,0,0}, - {10217,8599,8602 ,5471,5470,726 ,0,0,0}, {10218,8472,10219 ,726,726,5470 ,0,0,0}, - {8789,8503,10220 ,5471,5470,5470 ,0,0,0}, {10221,10222,8785 ,726,5471,726 ,0,0,0}, - {8479,8832,8478 ,726,5471,726 ,0,0,0}, {8950,8949,8824 ,5468,726,5471 ,0,0,0}, - {8874,8752,8870 ,5470,5471,726 ,0,0,0}, {8765,8764,10223 ,726,726,726 ,0,0,0}, - {8492,8466,8864 ,5470,5471,5471 ,0,0,0}, {10214,10212,8867 ,726,726,726 ,0,0,0}, - {10212,10213,8862 ,726,5470,726 ,0,0,0}, {10213,10184,8861 ,5470,5471,726 ,0,0,0}, - {8858,10210,8855 ,5470,5470,726 ,0,0,0}, {10210,8858,10183 ,5470,5470,726 ,0,0,0}, - {9908,8851,8849 ,5468,5469,726 ,0,0,0}, {10211,10026,8852 ,5470,5470,5471 ,0,0,0}, - {8879,8851,9907 ,726,5469,5469 ,0,0,0}, {9900,8879,8878 ,5468,726,5471 ,0,0,0}, - {9900,8851,8879 ,5468,5469,726 ,0,0,0}, {8849,8847,10206 ,726,5468,726 ,0,0,0}, - {8849,10206,9908 ,726,726,5468 ,0,0,0}, {8846,10178,10206 ,726,726,726 ,0,0,0}, - {8843,10216,10178 ,5471,5471,726 ,0,0,0}, {8840,10205,10138 ,5469,5468,5468 ,0,0,0}, - {8841,10138,10216 ,726,5468,5471 ,0,0,0}, {8821,8820,8949 ,5469,5468,726 ,0,0,0}, - {8840,8821,10205 ,5469,5469,5468 ,0,0,0}, {8824,8828,8950 ,5471,726,5468 ,0,0,0}, - {8820,8824,8949 ,5468,5471,726 ,0,0,0}, {8828,8827,8946 ,726,5471,5469 ,0,0,0}, - {8479,8482,8830 ,726,726,5469 ,0,0,0}, {8478,8832,8834 ,726,5471,5470 ,0,0,0}, - {10185,10219,8473 ,5471,5470,5471 ,0,0,0}, {8476,8478,8834 ,5471,726,5470 ,0,0,0}, - {10218,10214,8470 ,726,726,5470 ,0,0,0}, {8873,10224,8745 ,5470,5470,726 ,0,0,0}, - {8770,10225,8771 ,5470,5470,5470 ,0,0,0}, {10182,8743,8741 ,726,5489,726 ,0,0,0}, - {10068,8738,8735 ,726,726,726 ,0,0,0}, {10226,10082,10029 ,5489,5488,726 ,0,0,0}, - {10082,10226,10044 ,5488,5489,5489 ,0,0,0}, {10045,10023,10046 ,726,726,726 ,0,0,0}, - {10025,10227,10042 ,5489,726,726 ,0,0,0}, {10043,10042,10227 ,726,726,726 ,0,0,0}, - {10024,10023,10045 ,5488,726,726 ,0,0,0}, {10024,10227,10025 ,5488,726,5489 ,0,0,0}, - {10046,9890,10047 ,726,726,726 ,0,0,0}, {9891,10035,9892 ,726,726,726 ,0,0,0}, - {10051,10033,10049 ,5489,726,726 ,0,0,0}, {10033,9891,10049 ,726,726,726 ,0,0,0}, - {10037,10054,10038 ,726,726,726 ,0,0,0}, {10052,10051,10050 ,726,5489,726 ,0,0,0}, - {10054,10053,10038 ,726,726,726 ,0,0,0}, {10053,10052,10055 ,726,726,5488 ,0,0,0}, - {10037,10036,9899 ,726,5489,726 ,0,0,0}, {10058,9899,10056 ,726,726,5489 ,0,0,0}, - {8805,8803,9894 ,5471,726,5471 ,0,0,0}, {9899,10069,9897 ,726,726,726 ,0,0,0}, - {8814,9994,10069 ,5471,726,726 ,0,0,0}, {10069,8815,8814 ,726,726,5471 ,0,0,0}, - {9993,8809,10032 ,5471,726,726 ,0,0,0}, {8809,9993,8811 ,726,5471,5471 ,0,0,0}, - {8808,10032,8809 ,726,726,726 ,0,0,0}, {10228,8777,10065 ,5471,726,726 ,0,0,0}, - {8777,8776,10066 ,726,726,726 ,0,0,0}, {8802,8777,10228 ,726,726,5471 ,0,0,0}, - {10229,10230,8779 ,726,726,726 ,0,0,0}, {10222,8782,8785 ,5471,726,726 ,0,0,0}, - {10230,8776,8779 ,726,726,726 ,0,0,0}, {8786,8791,10231 ,726,726,726 ,0,0,0}, - {8786,10232,8785 ,726,5471,726 ,0,0,0}, {10220,8791,8789 ,5470,726,5471 ,0,0,0}, - {8508,8675,8678 ,5471,5471,726 ,0,0,0}, {8794,8675,8788 ,726,5471,726 ,0,0,0}, - {10233,8503,8502 ,5471,5470,726 ,0,0,0}, {8767,8765,10234 ,726,726,726 ,0,0,0}, - {8508,8505,8788 ,5471,726,726 ,0,0,0}, {8689,10235,8691 ,726,5470,726 ,0,0,0}, - {8596,8722,8721 ,5470,726,726 ,0,0,0}, {8709,10236,8706 ,726,726,5471 ,0,0,0}, - {8756,8496,8493 ,726,726,726 ,0,0,0}, {8874,8873,8748 ,5470,5470,726 ,0,0,0}, - {8798,8676,8794 ,5471,726,726 ,0,0,0}, {10198,8715,8713 ,726,726,726 ,0,0,0}, - {8788,8505,8789 ,726,726,5471 ,0,0,0}, {10220,10231,8791 ,5470,726,726 ,0,0,0}, - {10231,10232,8786 ,726,5471,726 ,0,0,0}, {10232,10221,8785 ,5471,726,726 ,0,0,0}, - {8782,10229,8779 ,726,726,726 ,0,0,0}, {10229,8782,10222 ,726,726,5471 ,0,0,0}, - {10237,8775,8773 ,5470,726,726 ,0,0,0}, {10230,10066,8776 ,726,726,726 ,0,0,0}, - {8803,8775,9894 ,726,726,5471 ,0,0,0}, {8775,8803,10039 ,726,726,5471 ,0,0,0}, - {10228,10039,8802 ,5471,5471,726 ,0,0,0}, {8775,10237,9895 ,726,5470,726 ,0,0,0}, - {8773,8771,10225 ,726,5470,5470 ,0,0,0}, {8773,10225,10237 ,726,5470,5470 ,0,0,0}, - {8770,10215,10225 ,5470,726,5470 ,0,0,0}, {8767,10234,10215 ,726,726,726 ,0,0,0}, - {8764,10224,10223 ,726,5470,726 ,0,0,0}, {8765,10223,10234 ,726,726,726 ,0,0,0}, - {8745,8744,8873 ,726,5470,5470 ,0,0,0}, {8764,8745,10224 ,726,726,5470 ,0,0,0}, - {8748,8752,8874 ,726,5471,5470 ,0,0,0}, {8744,8748,8873 ,5470,726,5470 ,0,0,0}, - {8752,8751,8870 ,5471,726,726 ,0,0,0}, {8493,8492,8754 ,726,5470,726 ,0,0,0}, - {8496,8758,8497 ,726,726,5471 ,0,0,0}, {8499,8497,10179 ,726,5471,726 ,0,0,0}, - {8756,8758,8496 ,726,726,726 ,0,0,0}, {10220,8503,10233 ,5470,5470,5471 ,0,0,0}, - {8739,10181,8741 ,5488,726,726 ,0,0,0}, {8941,8486,10143 ,5468,5470,726 ,0,0,0}, - {8665,10030,8667 ,5470,726,5470 ,0,0,0}, {10086,8662,8659 ,726,726,726 ,0,0,0}, - {10070,10238,10071 ,5471,726,726 ,0,0,0}, {10061,10071,10062 ,5471,726,726 ,0,0,0}, - {10107,10239,10074 ,726,5471,5471 ,0,0,0}, {10060,10074,10239 ,726,5471,5471 ,0,0,0}, - {10079,10137,10107 ,726,726,726 ,0,0,0}, {10137,10239,10107 ,726,5471,726 ,0,0,0}, - {10090,10100,10079 ,726,726,726 ,0,0,0}, {10240,10080,10079 ,726,726,726 ,0,0,0}, - {10077,10079,10092 ,726,726,726 ,0,0,0}, {10093,10092,10079 ,5488,726,726 ,0,0,0}, - {10135,10096,10136 ,5489,726,726 ,0,0,0}, {10095,10092,10091 ,726,726,726 ,0,0,0}, - {10096,10097,10136 ,726,726,726 ,0,0,0}, {10097,10095,10094 ,726,726,726 ,0,0,0}, - {10076,10135,10098 ,726,5489,726 ,0,0,0}, {10182,10075,8743 ,726,726,5489 ,0,0,0}, - {8727,8726,10029 ,726,5471,726 ,0,0,0}, {8738,10241,8739 ,726,726,5488 ,0,0,0}, - {10181,8739,10241 ,726,5488,726 ,0,0,0}, {10067,8733,10083 ,726,726,726 ,0,0,0}, - {10068,10241,8738 ,726,726,726 ,0,0,0}, {8733,10067,8735 ,726,726,726 ,0,0,0}, - {8732,10083,8733 ,726,726,726 ,0,0,0}, {10139,10029,10242 ,5470,726,5471 ,0,0,0}, - {10242,8701,10142 ,5471,726,5471 ,0,0,0}, {10242,10029,8701 ,5471,726,726 ,0,0,0}, - {8703,10243,8700 ,5471,726,726 ,0,0,0}, {8709,10244,10236 ,726,726,726 ,0,0,0}, - {8703,10245,10243 ,5471,726,726 ,0,0,0}, {10246,8694,8691 ,5471,726,726 ,0,0,0}, - {8694,10247,8695 ,726,726,726 ,0,0,0}, {10248,8689,8688 ,726,726,5471 ,0,0,0}, - {8797,10249,8669 ,5471,5471,5471 ,0,0,0}, {8672,8798,8797 ,726,5471,5471 ,0,0,0}, - {8508,8788,8675 ,5471,726,5471 ,0,0,0}, {10250,10251,10252 ,5470,726,726 ,0,0,0}, - {10253,8515,8685 ,726,5470,5471 ,0,0,0}, {8721,10254,8593 ,726,726,726 ,0,0,0}, - {10255,8619,8618 ,5471,5470,5471 ,0,0,0}, {8618,8615,10256 ,5471,726,726 ,0,0,0}, - {8718,8599,8712 ,726,5470,726 ,0,0,0}, {8511,8678,8680 ,5471,726,726 ,0,0,0}, - {8722,8600,8718 ,726,5471,726 ,0,0,0}, {8612,10257,8613 ,726,726,5471 ,0,0,0}, - {8712,10258,8713 ,726,726,726 ,0,0,0}, {10198,9995,8715 ,726,5470,726 ,0,0,0}, - {9995,10203,8710 ,5470,726,726 ,0,0,0}, {10203,10244,8709 ,726,726,726 ,0,0,0}, - {8706,10245,8703 ,5471,726,5471 ,0,0,0}, {10245,8706,10236 ,726,5471,726 ,0,0,0}, - {10247,10259,8697 ,726,726,726 ,0,0,0}, {8697,10259,10029 ,726,726,726 ,0,0,0}, - {10243,10142,8700 ,726,5471,726 ,0,0,0}, {8729,8727,10029 ,726,726,726 ,0,0,0}, - {10029,8726,8701 ,726,5471,726 ,0,0,0}, {8699,10029,10140 ,5471,726,5471 ,0,0,0}, - {10259,10226,10029 ,726,5489,726 ,0,0,0}, {8697,8695,10247 ,726,726,726 ,0,0,0}, - {8694,10246,10247 ,726,5471,726 ,0,0,0}, {8691,10235,10246 ,726,5470,5471 ,0,0,0}, - {8688,10249,10248 ,5471,5471,726 ,0,0,0}, {8689,10248,10235 ,726,726,5470 ,0,0,0}, - {8669,8668,8797 ,5471,726,5471 ,0,0,0}, {8688,8669,10249 ,5471,5471,5471 ,0,0,0}, - {8672,8676,8798 ,726,726,5471 ,0,0,0}, {8668,8672,8797 ,726,726,5471 ,0,0,0}, - {8676,8675,8794 ,726,5471,726 ,0,0,0}, {8511,8508,8678 ,5471,5471,726 ,0,0,0}, - {8511,8680,8514 ,5471,726,726 ,0,0,0}, {8682,8515,8514 ,726,5470,726 ,0,0,0}, - {8682,8514,8680 ,726,726,726 ,0,0,0}, {8682,8685,8515 ,726,5471,5470 ,0,0,0}, - {10260,8558,8563 ,5468,5469,5470 ,0,0,0}, {10116,10128,10123 ,5468,5469,726 ,0,0,0}, - {8903,8566,8904 ,5468,5471,5469 ,0,0,0}, {8586,8583,10116 ,5469,5471,5468 ,0,0,0}, - {8547,10129,10128 ,5469,726,5469 ,0,0,0}, {10127,10129,10121 ,726,726,726 ,0,0,0}, - {10161,10158,10160 ,726,5471,726 ,0,0,0}, {10157,10261,10119 ,5471,5468,5471 ,0,0,0}, - {10120,10119,10261 ,5468,5471,5468 ,0,0,0}, {10159,10158,10161 ,5468,5471,726 ,0,0,0}, - {10159,10261,10157 ,5468,5468,5471 ,0,0,0}, {10160,10125,10124 ,726,5470,726 ,0,0,0}, - {10132,10131,10126 ,726,5469,5469 ,0,0,0}, {10151,10130,10152 ,5470,5471,726 ,0,0,0}, - {10130,10132,10152 ,5471,726,726 ,0,0,0}, {10148,10144,10146 ,726,726,5471 ,0,0,0}, - {10150,10149,10262 ,726,5470,726 ,0,0,0}, {10262,10151,10150 ,726,5470,726 ,0,0,0}, - {10148,10147,10144 ,726,5471,726 ,0,0,0}, {10149,10148,10262 ,5470,726,726 ,0,0,0}, - {10115,10146,10145 ,726,5471,5470 ,0,0,0}, {10030,10114,8667 ,726,726,5470 ,0,0,0}, - {8653,8651,10070 ,726,5470,5471 ,0,0,0}, {8662,10263,8663 ,726,726,726 ,0,0,0}, - {10031,8663,10263 ,726,726,726 ,0,0,0}, {10085,8657,10141 ,5471,5470,726 ,0,0,0}, - {10086,10263,8662 ,726,726,726 ,0,0,0}, {8657,10085,8659 ,5470,5471,726 ,0,0,0}, - {8656,10141,8657 ,5470,726,5470 ,0,0,0}, {10197,8650,8625 ,5471,5471,5471 ,0,0,0}, - {8625,8624,10196 ,5471,726,5471 ,0,0,0}, {10111,8650,10197 ,5471,5471,5471 ,0,0,0}, - {10264,10265,8627 ,5471,726,726 ,0,0,0}, {10072,8630,8633 ,726,5470,5470 ,0,0,0}, - {10265,8624,8627 ,726,726,726 ,0,0,0}, {8634,8639,10266 ,5470,726,726 ,0,0,0}, - {8634,10267,8633 ,5470,726,5470 ,0,0,0}, {10268,8639,8637 ,726,726,726 ,0,0,0}, - {8526,8528,10269 ,726,5471,5471 ,0,0,0}, {8613,10270,8615 ,5471,726,726 ,0,0,0}, - {10271,10272,10273 ,5471,726,726 ,0,0,0}, {8561,10271,10274 ,5471,5471,5471 ,0,0,0}, - {10143,8486,10275 ,726,5470,5469 ,0,0,0}, {8903,8906,10276 ,5468,5468,5470 ,0,0,0}, - {8542,10277,8543 ,726,726,5471 ,0,0,0}, {8561,10274,8563 ,5471,5471,5470 ,0,0,0}, - {8642,8523,8636 ,726,5470,5470 ,0,0,0}, {8604,10278,10279 ,5470,5471,726 ,0,0,0}, - {8646,8524,8642 ,726,5471,726 ,0,0,0}, {10280,10269,8528 ,5471,5471,5471 ,0,0,0}, - {10281,10282,8636 ,726,5471,5470 ,0,0,0}, {10268,10266,8639 ,726,726,726 ,0,0,0}, - {10266,10267,8634 ,726,726,5470 ,0,0,0}, {10267,10073,8633 ,726,726,5470 ,0,0,0}, - {8630,10264,8627 ,5470,5471,726 ,0,0,0}, {10264,8630,10072 ,5471,5470,726 ,0,0,0}, - {8621,10255,10238 ,5471,5471,726 ,0,0,0}, {10238,8623,8621 ,726,726,5471 ,0,0,0}, - {10265,10196,8624 ,726,5471,726 ,0,0,0}, {8651,8623,10070 ,5470,726,5471 ,0,0,0}, - {10110,8651,8650 ,726,5470,5471 ,0,0,0}, {10110,8623,8651 ,726,726,5470 ,0,0,0}, - {10070,8623,10238 ,5471,726,726 ,0,0,0}, {8621,8619,10255 ,5471,5470,5471 ,0,0,0}, - {8618,10256,10255 ,5471,726,5471 ,0,0,0}, {8615,10270,10256 ,726,726,726 ,0,0,0}, - {8612,10254,10257 ,726,726,726 ,0,0,0}, {8613,10257,10270 ,5471,726,726 ,0,0,0}, - {8593,8592,8721 ,726,5471,726 ,0,0,0}, {8612,8593,10254 ,726,726,726 ,0,0,0}, - {8596,8600,8722 ,5470,5471,726 ,0,0,0}, {8592,8596,8721 ,5471,5470,726 ,0,0,0}, - {8600,8599,8718 ,5471,5470,726 ,0,0,0}, {10279,10217,8602 ,726,5471,726 ,0,0,0}, - {8712,8599,10217 ,726,5470,5471 ,0,0,0}, {8609,10283,10284 ,726,726,726 ,0,0,0}, - {10278,8606,10284 ,5471,726,726 ,0,0,0}, {10285,10286,10287 ,5470,5470,5471 ,0,0,0}, - {8589,10192,8591 ,5468,5470,5483 ,0,0,0}, {8897,8896,8569 ,726,5468,5468 ,0,0,0}, - {8589,8587,10191 ,5468,5469,5470 ,0,0,0}, {8925,9889,10188 ,726,5468,5468 ,0,0,0}, - {8922,10190,9889 ,5469,726,5468 ,0,0,0}, {10188,10189,9909 ,5468,5468,5469 ,0,0,0}, - {9918,10189,9919 ,5476,5468,5471 ,0,0,0}, {9946,9949,9944 ,5468,5468,5475 ,0,0,0}, - {9948,10288,10174 ,5483,726,5468 ,0,0,0}, {9917,10174,10288 ,5475,5468,726 ,0,0,0}, - {9947,9949,9946 ,5486,5468,5468 ,0,0,0}, {9947,10288,9948 ,5486,726,5483 ,0,0,0}, - {9944,9921,9945 ,5475,5478,5485 ,0,0,0}, {9922,9933,9920 ,5469,5468,5477 ,0,0,0}, - {9926,9932,9924 ,726,726,5471 ,0,0,0}, {9932,9922,9924 ,726,5469,5471 ,0,0,0}, - {10176,9930,10177 ,5472,5480,5482 ,0,0,0}, {9931,9926,9925 ,5481,726,5469 ,0,0,0}, - {9930,9929,10177 ,5480,726,5482 ,0,0,0}, {9929,9931,9941 ,726,5481,5475 ,0,0,0}, - {9934,10176,9937 ,5475,5472,5468 ,0,0,0}, {10192,9935,8591 ,5470,5475,5483 ,0,0,0}, - {10116,8575,10193 ,5468,726,5468 ,0,0,0}, {8586,10118,8587 ,5469,5469,5469 ,0,0,0}, - {10191,8587,10118 ,5470,5469,5469 ,0,0,0}, {10289,10117,10116 ,5468,726,5468 ,0,0,0}, - {10118,8586,10116 ,5469,5469,5468 ,0,0,0}, {10116,8583,8581 ,5468,5471,5470 ,0,0,0}, - {10116,8580,8577 ,5468,5469,5471 ,0,0,0}, {10290,8549,10194 ,5469,5468,5469 ,0,0,0}, - {8549,8548,10195 ,5468,5471,5471 ,0,0,0}, {8574,8549,10290 ,5468,5468,5469 ,0,0,0}, - {10291,10292,8551 ,5470,5471,5468 ,0,0,0}, {10112,8554,8557 ,5470,726,5468 ,0,0,0}, - {10292,8548,8551 ,5471,5471,5468 ,0,0,0}, {8906,8908,10293 ,5468,5468,5468 ,0,0,0}, - {8520,8646,8645 ,5471,726,726 ,0,0,0}, {8558,10294,8557 ,5469,5469,5468 ,0,0,0}, - {10295,8537,8536 ,726,5471,726 ,0,0,0}, {10296,8542,8539 ,726,726,5470 ,0,0,0}, - {10297,8517,8645 ,726,5470,726 ,0,0,0}, {10298,8539,8537 ,726,5470,5471 ,0,0,0}, - {8903,8560,8566 ,5468,5469,5471 ,0,0,0}, {8906,10293,10276 ,5468,5468,5470 ,0,0,0}, - {8566,8570,8904 ,5471,726,5469 ,0,0,0}, {8569,8900,8570 ,5468,5468,726 ,0,0,0}, - {8904,8570,8900 ,5469,726,5468 ,0,0,0}, {8485,10187,10275 ,5469,5469,5469 ,0,0,0}, - {8910,8490,10299 ,5471,5470,726 ,0,0,0}, {8490,10186,8488 ,5470,5469,726 ,0,0,0}, - {8560,10300,8561 ,5469,5471,5471 ,0,0,0}, {10274,10260,8563 ,5471,5468,5470 ,0,0,0}, - {10260,10294,8558 ,5468,5469,5469 ,0,0,0}, {10294,10113,8557 ,5469,5468,5468 ,0,0,0}, - {8554,10291,8551 ,726,5470,5468 ,0,0,0}, {10291,8554,10112 ,5470,726,5470 ,0,0,0}, - {8545,10277,10301 ,726,726,5471 ,0,0,0}, {10301,8547,8545 ,5471,5469,726 ,0,0,0}, - {10292,10195,8548 ,5471,5471,5471 ,0,0,0}, {8547,10128,10116 ,5469,5469,5468 ,0,0,0}, - {10116,10193,8547 ,5468,5468,5469 ,0,0,0}, {10290,10193,8574 ,5469,5468,5468 ,0,0,0}, - {8547,10301,10129 ,5469,5471,726 ,0,0,0}, {8545,8543,10277 ,726,5471,726 ,0,0,0}, - {8542,10296,10277 ,726,726,726 ,0,0,0}, {8539,10298,10296 ,5470,726,726 ,0,0,0}, - {8536,10297,10295 ,726,726,726 ,0,0,0}, {8537,10295,10298 ,5471,726,726 ,0,0,0}, - {8517,8516,8645 ,5470,726,726 ,0,0,0}, {8536,8517,10297 ,726,5470,726 ,0,0,0}, - {8520,8524,8646 ,5471,5471,726 ,0,0,0}, {8516,8520,8645 ,726,5471,726 ,0,0,0}, - {8524,8523,8642 ,5471,5470,726 ,0,0,0}, {10269,10281,8526 ,5471,726,726 ,0,0,0}, - {10280,8530,10302 ,5471,726,726 ,0,0,0}, {10200,10302,10201 ,5471,726,5470 ,0,0,0}, - {8528,8530,10280 ,5471,726,5471 ,0,0,0}, {10274,10271,10273 ,5471,5471,726 ,0,0,0}, - {10268,8637,10303 ,726,726,5471 ,0,0,0}, {10214,8865,8470 ,726,5470,5470 ,0,0,0}, - {10268,10303,10285 ,726,5471,5470 ,0,0,0}, {8505,8503,8789 ,726,5470,5471 ,0,0,0}, - {8499,10180,8502 ,726,5470,726 ,0,0,0}, {10233,8502,10180 ,5471,726,5470 ,0,0,0}, - {8865,8864,8466 ,5470,5471,5471 ,0,0,0}, {8761,8497,8758 ,726,5471,726 ,0,0,0}, - {8761,10179,8497 ,726,726,5471 ,0,0,0}, {8492,8864,8751 ,5470,5471,726 ,0,0,0}, - {8751,8754,8492 ,726,726,5470 ,0,0,0}, {8865,8466,8470 ,5470,5471,5470 ,0,0,0}, - {10218,8470,8472 ,726,5470,726 ,0,0,0}, {8484,8940,8482 ,5471,5469,726 ,0,0,0}, - {10219,8472,8473 ,5470,726,5471 ,0,0,0}, {8837,8476,8834 ,726,5471,5470 ,0,0,0}, - {8837,10185,8476 ,726,5471,5471 ,0,0,0}, {8940,8827,8482 ,5469,5471,726 ,0,0,0}, - {8827,8830,8482 ,5471,5469,726 ,0,0,0}, {8484,8486,8941 ,5471,5470,5468 ,0,0,0}, - {10275,8486,8485 ,5469,5470,5469 ,0,0,0}, {10300,8560,10276 ,5471,5469,5470 ,0,0,0}, - {10187,8485,8488 ,5469,5469,726 ,0,0,0}, {8913,8490,8910 ,5469,5470,5471 ,0,0,0}, - {8913,10186,8490 ,5469,5469,5470 ,0,0,0}, {10276,8560,8903 ,5470,5469,5468 ,0,0,0}, - {10299,10293,8908 ,726,5468,5468 ,0,0,0}, {10299,8908,8910 ,726,5468,5471 ,0,0,0}, - {10300,10271,8561 ,5471,5471,5471 ,0,0,0}, {10200,10202,10272 ,5471,5471,726 ,0,0,0}, - {10273,10272,10202 ,726,726,5471 ,0,0,0}, {8637,8636,10282 ,726,5470,5471 ,0,0,0}, - {8533,10302,8530 ,726,726,726 ,0,0,0}, {8533,10201,10302 ,726,5470,726 ,0,0,0}, - {10281,8636,8523 ,726,5470,5470 ,0,0,0}, {8523,8526,10281 ,5470,726,726 ,0,0,0}, - {8637,10282,10303 ,726,5471,5471 ,0,0,0}, {10287,10286,10304 ,5471,5470,726 ,0,0,0}, - {10285,10303,10286 ,5470,5471,5470 ,0,0,0}, {10304,10284,10283 ,726,726,726 ,0,0,0}, - {10283,10287,10304 ,726,5471,726 ,0,0,0}, {10284,8606,8609 ,726,726,726 ,0,0,0}, - {10278,8604,8606 ,5471,5470,726 ,0,0,0}, {10279,8602,8604 ,726,726,5470 ,0,0,0}, - {8712,10217,10258 ,726,5471,726 ,0,0,0}, {10199,10305,10198 ,5471,5471,726 ,0,0,0}, - {8713,10258,10199 ,726,726,5471 ,0,0,0}, {10251,10305,10252 ,726,5471,726 ,0,0,0}, - {10199,10252,10305 ,5471,726,5471 ,0,0,0}, {10251,10250,10253 ,726,5470,726 ,0,0,0}, - {8515,10253,10250 ,5470,726,5470 ,0,0,0}, {10289,10116,10122 ,5468,5468,5468 ,0,0,0}, - {8581,8580,10116 ,5470,5469,5468 ,0,0,0}, {10079,10099,10093 ,726,726,5488 ,0,0,0}, - {10088,10240,10079 ,5488,726,726 ,0,0,0}, {10029,8699,8697 ,726,5471,726 ,0,0,0}, - {10204,10029,10084 ,726,726,726 ,0,0,0}, {10170,10169,10167 ,5469,5470,5468 ,0,0,0}, - {10170,9912,10168 ,5469,5468,5469 ,0,0,0}, {10056,9899,9898 ,5489,726,726 ,0,0,0}, - {8819,8817,9899 ,726,726,726 ,0,0,0}, {10306,10307,10308 ,5490,5491,5492 ,0,0,0}, - {10309,10310,10311 ,5493,5494,5495 ,0,0,0}, {10312,10310,10313 ,5496,5494,5497 ,0,0,0}, - {10314,10315,10316 ,5498,5499,5500 ,0,0,0}, {10317,10318,10319 ,5501,5502,5503 ,0,0,0}, - {10320,10321,10322 ,5504,5505,5506 ,0,0,0}, {10323,10324,10325 ,5507,5508,5509 ,0,0,0}, - {9936,9940,10320 ,5510,5511,5504 ,0,0,0}, {10326,10327,10328 ,5512,5513,5514 ,0,0,0}, - {10317,10322,10321 ,5501,5506,5505 ,0,0,0}, {10329,10330,10327 ,5515,5516,5513 ,0,0,0}, - {10331,10329,10327 ,5517,5515,5513 ,0,0,0}, {10331,10332,10329 ,5517,5518,5515 ,0,0,0}, - {10332,10331,10333 ,5518,5517,5519 ,0,0,0}, {10334,10330,10335 ,5520,5516,5521 ,0,0,0}, - {10336,10337,10338 ,5522,5523,5524 ,0,0,0}, {10327,10330,10334 ,5513,5516,5520 ,0,0,0}, - {10338,10337,10333 ,5524,5523,5519 ,0,0,0}, {10339,10336,10340 ,5525,5522,5526 ,0,0,0}, - {10341,10342,10343 ,5527,5528,5529 ,0,0,0}, {10341,10334,10335 ,5527,5520,5521 ,0,0,0}, - {10344,10345,10346 ,5530,5531,5532 ,0,0,0}, {10341,10335,10342 ,5527,5521,5528 ,0,0,0}, - {10342,10344,10343 ,5528,5530,5529 ,0,0,0}, {10347,10348,10346 ,5533,5534,5532 ,0,0,0}, - {10324,10349,10325 ,5508,5535,5509 ,0,0,0}, {10346,10345,10347 ,5532,5531,5533 ,0,0,0}, - {10350,10309,10351 ,5536,5493,5537 ,0,0,0}, {10345,10352,10347 ,5531,5538,5533 ,0,0,0}, - {10324,10328,10349 ,5508,5514,5535 ,0,0,0}, {10353,10328,10334 ,5539,5514,5520 ,0,0,0}, - {10354,10355,10356 ,5540,5541,5542 ,0,0,0}, {10357,10354,10358 ,5543,5540,5544 ,0,0,0}, - {9915,9932,10307 ,5545,5546,5491 ,0,0,0}, {10359,10360,10361 ,5547,5548,5549 ,0,0,0}, - {9915,10306,9916 ,5545,5490,726 ,0,0,0}, {10362,9916,10306 ,5550,726,5490 ,0,0,0}, - {10363,10348,10364 ,5551,5534,5552 ,0,0,0}, {10344,10346,10343 ,5530,5532,5529 ,0,0,0}, - {10346,10348,10363 ,5532,5534,5551 ,0,0,0}, {10364,10365,10363 ,5552,5553,5551 ,0,0,0}, - {10366,10343,10363 ,5554,5529,5551 ,0,0,0}, {10328,10353,10349 ,5514,5539,5535 ,0,0,0}, - {10366,10353,10341 ,5554,5539,5527 ,0,0,0}, {10331,10367,10333 ,5517,5555,5519 ,0,0,0}, - {10341,10353,10334 ,5527,5539,5520 ,0,0,0}, {10368,10369,10338 ,5556,5557,5524 ,0,0,0}, - {10327,10334,10328 ,5513,5520,5514 ,0,0,0}, {10367,10331,10326 ,5555,5517,5512 ,0,0,0}, - {10336,10338,10340 ,5522,5524,5526 ,0,0,0}, {10332,10333,10337 ,5518,5519,5523 ,0,0,0}, - {10333,10367,10368 ,5519,5555,5556 ,0,0,0}, {10370,10340,10338 ,5558,5526,5524 ,0,0,0}, - {10346,10363,10343 ,5532,5551,5529 ,0,0,0}, {10371,10365,10364 ,5559,5553,5552 ,0,0,0}, - {10371,10358,10365 ,5559,5544,5553 ,0,0,0}, {10343,10366,10341 ,5529,5554,5527 ,0,0,0}, - {10365,10372,10366 ,5553,5560,5554 ,0,0,0}, {10324,10313,10326 ,5508,5497,5512 ,0,0,0}, - {10372,10349,10353 ,5560,5535,5539 ,0,0,0}, {10309,10369,10368 ,5493,5557,5556 ,0,0,0}, - {10350,10369,10309 ,5536,5557,5493 ,0,0,0}, {10327,10326,10331 ,5513,5512,5517 ,0,0,0}, - {10328,10324,10326 ,5514,5508,5512 ,0,0,0}, {10333,10368,10338 ,5519,5556,5524 ,0,0,0}, - {10313,10310,10367 ,5497,5494,5555 ,0,0,0}, {10338,10369,10370 ,5524,5557,5558 ,0,0,0}, - {10368,10310,10309 ,5556,5494,5493 ,0,0,0}, {10373,10370,10369 ,5561,5558,5557 ,0,0,0}, - {10363,10365,10366 ,5551,5553,5554 ,0,0,0}, {10357,10358,10371 ,5543,5544,5559 ,0,0,0}, - {10374,10356,10375 ,5562,5542,5563 ,0,0,0}, {10366,10372,10353 ,5554,5560,5539 ,0,0,0}, - {10376,10372,10358 ,5564,5560,5544 ,0,0,0}, {10313,10324,10323 ,5497,5508,5507 ,0,0,0}, - {10376,10325,10349 ,5564,5509,5535 ,0,0,0}, {10377,10351,10311 ,5565,5537,5495 ,0,0,0}, - {10367,10310,10368 ,5555,5494,5556 ,0,0,0}, {10326,10313,10367 ,5512,5497,5555 ,0,0,0}, - {10313,10323,10312 ,5497,5507,5496 ,0,0,0}, {10350,10351,10378 ,5536,5537,5566 ,0,0,0}, - {10312,10311,10310 ,5496,5495,5494 ,0,0,0}, {10369,10350,10373 ,5557,5536,5561 ,0,0,0}, - {10309,10311,10351 ,5493,5495,5537 ,0,0,0}, {10379,10373,10350 ,5567,5561,5536 ,0,0,0}, - {10365,10358,10372 ,5553,5544,5560 ,0,0,0}, {10355,10354,10357 ,5541,5540,5543 ,0,0,0}, - {10325,10380,10323 ,5509,5568,5507 ,0,0,0}, {10372,10376,10349 ,5560,5564,5535 ,0,0,0}, - {10381,10376,10354 ,5569,5564,5540 ,0,0,0}, {10323,10382,10312 ,5507,5570,5496 ,0,0,0}, - {10381,10380,10325 ,5569,5568,5509 ,0,0,0}, {10312,10383,10311 ,5496,5571,5495 ,0,0,0}, - {10382,10323,10380 ,5570,5507,5568 ,0,0,0}, {10351,10314,10378 ,5537,5498,5566 ,0,0,0}, - {10383,10312,10382 ,5571,5496,5570 ,0,0,0}, {10384,10378,10316 ,5572,5566,5500 ,0,0,0}, - {10377,10311,10383 ,5565,5495,5571 ,0,0,0}, {10350,10378,10379 ,5536,5566,5567 ,0,0,0}, - {10351,10377,10314 ,5537,5565,5498 ,0,0,0}, {10384,10379,10378 ,5572,5567,5566 ,0,0,0}, - {10358,10354,10376 ,5544,5540,5564 ,0,0,0}, {10375,10356,10355 ,5563,5542,5541 ,0,0,0}, - {10380,10360,10382 ,5568,5548,5570 ,0,0,0}, {10376,10381,10325 ,5564,5569,5509 ,0,0,0}, - {10356,10385,10381 ,5542,5573,5569 ,0,0,0}, {10382,10359,10383 ,5570,5547,5571 ,0,0,0}, - {10385,10360,10380 ,5573,5548,5568 ,0,0,0}, {10383,10386,10377 ,5571,5574,5565 ,0,0,0}, - {10360,10359,10382 ,5548,5547,5570 ,0,0,0}, {10387,10314,10377 ,5575,5498,5565 ,0,0,0}, - {10386,10383,10359 ,5574,5571,5547 ,0,0,0}, {10388,10316,10319 ,5576,5500,5503 ,0,0,0}, - {10377,10386,10387 ,5565,5574,5575 ,0,0,0}, {10387,10315,10314 ,5575,5499,5498 ,0,0,0}, - {10384,10316,10388 ,5572,5500,5576 ,0,0,0}, {10378,10314,10316 ,5566,5498,5500 ,0,0,0}, - {10354,10356,10381 ,5540,5542,5569 ,0,0,0}, {10389,10374,10375 ,5577,5562,5563 ,0,0,0}, - {10390,10386,10359 ,5578,5574,5547 ,0,0,0}, {10381,10385,10380 ,5569,5573,5568 ,0,0,0}, - {10374,10308,10385 ,5562,5492,5573 ,0,0,0}, {10391,10387,10386 ,5579,5575,5574 ,0,0,0}, - {10308,10361,10360 ,5492,5549,5548 ,0,0,0}, {10392,10315,10387 ,5580,5499,5575 ,0,0,0}, - {10361,10390,10359 ,5549,5578,5547 ,0,0,0}, {10322,10317,10393 ,5506,5501,5581 ,0,0,0}, - {10390,10391,10386 ,5578,5579,5574 ,0,0,0}, {10319,10315,10394 ,5503,5499,5582 ,0,0,0}, - {10392,10387,10391 ,5580,5575,5579 ,0,0,0}, {10394,10315,10392 ,5582,5499,5580 ,0,0,0}, - {10388,10319,10318 ,5576,5503,5502 ,0,0,0}, {10316,10315,10319 ,5500,5499,5503 ,0,0,0}, - {10356,10374,10385 ,5542,5562,5573 ,0,0,0}, {10306,10389,10362 ,5490,5577,5550 ,0,0,0}, - {10307,10395,10361 ,5491,5583,5549 ,0,0,0}, {10385,10308,10360 ,5573,5492,5548 ,0,0,0}, - {10307,10361,10308 ,5491,5549,5492 ,0,0,0}, {10395,10396,10390 ,5583,5584,5578 ,0,0,0}, - {10395,10390,10361 ,5583,5578,5549 ,0,0,0}, {10396,10397,10391 ,5584,5585,5579 ,0,0,0}, - {10396,10391,10390 ,5584,5579,5578 ,0,0,0}, {10397,10398,10392 ,5585,5586,5580 ,0,0,0}, - {10397,10392,10391 ,5585,5580,5579 ,0,0,0}, {10398,10393,10394 ,5586,5581,5582 ,0,0,0}, - {10394,10392,10398 ,5582,5580,5586 ,0,0,0}, {10393,10317,10394 ,5581,5501,5582 ,0,0,0}, - {10318,10317,10321 ,5502,5501,5505 ,0,0,0}, {10319,10394,10317 ,5503,5582,5501 ,0,0,0}, - {10389,10306,10374 ,5577,5490,5562 ,0,0,0}, {10308,10374,10306 ,5492,5562,5490 ,0,0,0}, - {10395,9932,9926 ,5583,5546,5587 ,0,0,0}, {9915,10307,10306 ,5545,5491,5490 ,0,0,0}, - {10396,9926,9931 ,5584,5587,5588 ,0,0,0}, {9932,10395,10307 ,5546,5583,5491 ,0,0,0}, - {10397,9931,9930 ,5585,5588,5589 ,0,0,0}, {9926,10396,10395 ,5587,5584,5583 ,0,0,0}, - {10398,9930,10176 ,5586,5589,5590 ,0,0,0}, {9931,10397,10396 ,5588,5585,5584 ,0,0,0}, - {10393,10176,9934 ,5581,5590,5591 ,0,0,0}, {9930,10398,10397 ,5589,5586,5585 ,0,0,0}, - {10322,9934,9936 ,5506,5591,5510 ,0,0,0}, {10176,10393,10398 ,5590,5581,5586 ,0,0,0}, - {9936,10320,10322 ,5510,5504,5506 ,0,0,0}, {9934,10322,10393 ,5591,5506,5581 ,0,0,0}, - {10399,10400,10401 ,5592,5593,5594 ,0,0,0}, {10402,10403,10404 ,5595,5596,5597 ,0,0,0}, - {10400,10405,10401 ,5593,5598,5594 ,0,0,0}, {10406,10404,10403 ,5599,5597,5596 ,0,0,0}, - {10407,10408,10409 ,5600,5601,5602 ,0,0,0}, {10410,10411,10408 ,5603,5604,5601 ,0,0,0}, - {10412,10413,10414 ,5605,5606,5607 ,0,0,0}, {10415,10411,10410 ,5608,5604,5603 ,0,0,0}, - {10411,10409,10408 ,5604,5602,5601 ,0,0,0}, {10416,10408,10402 ,5609,5601,5595 ,0,0,0}, - {10417,10418,10419 ,5610,5611,5612 ,0,0,0}, {10420,10421,10422 ,5613,5614,5615 ,0,0,0}, - {10423,10418,10424 ,5616,5611,5617 ,0,0,0}, {10425,10426,10399 ,5618,5619,5592 ,0,0,0}, - {10413,10162,10130 ,5606,5620,5621 ,0,0,0}, {10427,10428,10429 ,5622,5623,5624 ,0,0,0}, - {10430,10164,10412 ,5625,5626,5605 ,0,0,0}, {10162,10412,10164 ,5620,5605,5626 ,0,0,0}, - {10431,10432,10433 ,5627,5628,5629 ,0,0,0}, {10405,10434,10401 ,5598,5630,5594 ,0,0,0}, - {10435,10436,10437 ,5631,5632,5633 ,0,0,0}, {10438,10439,10440 ,5634,5635,5636 ,0,0,0}, - {10429,10432,10441 ,5624,5628,5637 ,0,0,0}, {10442,10443,10444 ,5638,5639,5640 ,0,0,0}, - {10445,10399,10446 ,5641,5592,5642 ,0,0,0}, {10443,10438,10444 ,5639,5634,5640 ,0,0,0}, - {10425,10406,10403 ,5618,5599,5596 ,0,0,0}, {10153,10156,10442 ,5643,5644,5638 ,0,0,0}, - {10406,10425,10447 ,5599,5618,5645 ,0,0,0}, {10447,10425,10445 ,5645,5618,5641 ,0,0,0}, - {10448,10449,10445 ,5646,5647,5641 ,0,0,0}, {10425,10403,10426 ,5618,5596,5619 ,0,0,0}, - {10448,10450,10451 ,5646,5648,5649 ,0,0,0}, {10451,10449,10448 ,5649,5647,5646 ,0,0,0}, - {10452,10453,10454 ,5650,5651,5652 ,0,0,0}, {10453,10452,10450 ,5651,5650,5648 ,0,0,0}, - {10410,10408,10416 ,5603,5601,5609 ,0,0,0}, {10455,10407,10409 ,5653,5600,5602 ,0,0,0}, - {10455,10456,10407 ,5653,5654,5600 ,0,0,0}, {10416,10402,10404 ,5609,5595,5597 ,0,0,0}, - {10457,10402,10407 ,5655,5595,5600 ,0,0,0}, {10399,10426,10400 ,5592,5619,5593 ,0,0,0}, - {10457,10426,10403 ,5655,5619,5596 ,0,0,0}, {10448,10458,10450 ,5646,5656,5648 ,0,0,0}, - {10459,10453,10460 ,5657,5651,5658 ,0,0,0}, {10447,10445,10449 ,5645,5641,5647 ,0,0,0}, - {10445,10425,10399 ,5641,5618,5592 ,0,0,0}, {10451,10450,10452 ,5649,5648,5650 ,0,0,0}, - {10446,10458,10448 ,5642,5656,5646 ,0,0,0}, {10453,10461,10454 ,5651,5659,5652 ,0,0,0}, - {10450,10458,10460 ,5648,5656,5658 ,0,0,0}, {10462,10461,10453 ,5660,5659,5651 ,0,0,0}, - {10408,10407,10402 ,5601,5600,5595 ,0,0,0}, {10463,10456,10455 ,5661,5654,5653 ,0,0,0}, - {10463,10419,10456 ,5661,5612,5654 ,0,0,0}, {10402,10457,10403 ,5595,5655,5596 ,0,0,0}, - {10456,10464,10457 ,5654,5662,5655 ,0,0,0}, {10401,10433,10446 ,5594,5629,5642 ,0,0,0}, - {10464,10400,10426 ,5662,5593,5619 ,0,0,0}, {10429,10459,10460 ,5624,5657,5658 ,0,0,0}, - {10428,10459,10429 ,5623,5657,5624 ,0,0,0}, {10445,10446,10448 ,5641,5642,5646 ,0,0,0}, - {10399,10401,10446 ,5592,5594,5642 ,0,0,0}, {10450,10460,10453 ,5648,5658,5651 ,0,0,0}, - {10433,10432,10458 ,5629,5628,5656 ,0,0,0}, {10453,10459,10462 ,5651,5657,5660 ,0,0,0}, - {10460,10432,10429 ,5658,5628,5624 ,0,0,0}, {10465,10462,10459 ,5663,5660,5657 ,0,0,0}, - {10407,10456,10457 ,5600,5654,5655 ,0,0,0}, {10417,10419,10463 ,5610,5612,5661 ,0,0,0}, - {10466,10423,10467 ,5664,5616,5665 ,0,0,0}, {10457,10464,10426 ,5655,5662,5619 ,0,0,0}, - {10468,10464,10419 ,5666,5662,5612 ,0,0,0}, {10433,10401,10434 ,5629,5594,5630 ,0,0,0}, - {10468,10405,10400 ,5666,5598,5593 ,0,0,0}, {10469,10427,10441 ,5667,5622,5637 ,0,0,0}, - {10458,10432,10460 ,5656,5628,5658 ,0,0,0}, {10446,10433,10458 ,5642,5629,5656 ,0,0,0}, - {10433,10434,10431 ,5629,5630,5627 ,0,0,0}, {10428,10427,10470 ,5623,5622,5668 ,0,0,0}, - {10431,10441,10432 ,5627,5637,5628 ,0,0,0}, {10459,10428,10465 ,5657,5623,5663 ,0,0,0}, - {10429,10441,10427 ,5624,5637,5622 ,0,0,0}, {10471,10465,10428 ,5669,5663,5623 ,0,0,0}, - {10456,10419,10464 ,5654,5612,5662 ,0,0,0}, {10424,10418,10417 ,5617,5611,5610 ,0,0,0}, - {10405,10472,10434 ,5598,5670,5630 ,0,0,0}, {10464,10468,10400 ,5662,5666,5593 ,0,0,0}, - {10473,10468,10418 ,5671,5666,5611 ,0,0,0}, {10434,10474,10431 ,5630,5672,5627 ,0,0,0}, - {10473,10472,10405 ,5671,5670,5598 ,0,0,0}, {10431,10475,10441 ,5627,5673,5637 ,0,0,0}, - {10474,10434,10472 ,5672,5630,5670 ,0,0,0}, {10427,10436,10470 ,5622,5632,5668 ,0,0,0}, - {10475,10431,10474 ,5673,5627,5672 ,0,0,0}, {10476,10470,10435 ,5674,5668,5631 ,0,0,0}, - {10469,10441,10475 ,5667,5637,5673 ,0,0,0}, {10428,10470,10471 ,5623,5668,5669 ,0,0,0}, - {10427,10469,10436 ,5622,5667,5632 ,0,0,0}, {10476,10471,10470 ,5674,5669,5668 ,0,0,0}, - {10419,10418,10468 ,5612,5611,5666 ,0,0,0}, {10467,10423,10424 ,5665,5616,5617 ,0,0,0}, - {10472,10420,10474 ,5670,5613,5672 ,0,0,0}, {10468,10473,10405 ,5666,5671,5598 ,0,0,0}, - {10423,10477,10473 ,5616,5675,5671 ,0,0,0}, {10474,10422,10475 ,5672,5615,5673 ,0,0,0}, - {10477,10420,10472 ,5675,5613,5670 ,0,0,0}, {10475,10478,10469 ,5673,5676,5667 ,0,0,0}, - {10420,10422,10474 ,5613,5615,5672 ,0,0,0}, {10479,10436,10469 ,5677,5632,5667 ,0,0,0}, - {10478,10475,10422 ,5676,5673,5615 ,0,0,0}, {10480,10435,10440 ,5678,5631,5636 ,0,0,0}, - {10469,10478,10479 ,5667,5676,5677 ,0,0,0}, {10479,10437,10436 ,5677,5633,5632 ,0,0,0}, - {10476,10435,10480 ,5674,5631,5678 ,0,0,0}, {10470,10436,10435 ,5668,5632,5631 ,0,0,0}, - {10418,10423,10473 ,5611,5616,5671 ,0,0,0}, {10481,10466,10467 ,5679,5664,5665 ,0,0,0}, - {10482,10478,10422 ,5680,5676,5615 ,0,0,0}, {10473,10477,10472 ,5671,5675,5670 ,0,0,0}, - {10466,10414,10477 ,5664,5607,5675 ,0,0,0}, {10483,10479,10478 ,5681,5677,5676 ,0,0,0}, - {10414,10421,10420 ,5607,5614,5613 ,0,0,0}, {10484,10437,10479 ,5682,5633,5677 ,0,0,0}, - {10421,10482,10422 ,5614,5680,5615 ,0,0,0}, {10444,10438,10485 ,5640,5634,5683 ,0,0,0}, - {10482,10483,10478 ,5680,5681,5676 ,0,0,0}, {10440,10437,10486 ,5636,5633,5684 ,0,0,0}, - {10484,10479,10483 ,5682,5677,5681 ,0,0,0}, {10486,10437,10484 ,5684,5633,5682 ,0,0,0}, - {10480,10440,10439 ,5678,5636,5635 ,0,0,0}, {10435,10437,10440 ,5631,5633,5636 ,0,0,0}, - {10423,10466,10477 ,5616,5664,5675 ,0,0,0}, {10412,10481,10430 ,5605,5679,5625 ,0,0,0}, - {10413,10487,10421 ,5606,5685,5614 ,0,0,0}, {10477,10414,10420 ,5675,5607,5613 ,0,0,0}, - {10413,10421,10414 ,5606,5614,5607 ,0,0,0}, {10487,10488,10482 ,5685,5686,5680 ,0,0,0}, - {10487,10482,10421 ,5685,5680,5614 ,0,0,0}, {10488,10489,10483 ,5686,5687,5681 ,0,0,0}, - {10488,10483,10482 ,5686,5681,5680 ,0,0,0}, {10489,10490,10484 ,5687,5688,5682 ,0,0,0}, - {10489,10484,10483 ,5687,5682,5681 ,0,0,0}, {10490,10485,10486 ,5688,5683,5684 ,0,0,0}, - {10486,10484,10490 ,5684,5682,5688 ,0,0,0}, {10485,10438,10486 ,5683,5634,5684 ,0,0,0}, - {10439,10438,10443 ,5635,5634,5639 ,0,0,0}, {10440,10486,10438 ,5636,5684,5634 ,0,0,0}, - {10481,10412,10466 ,5679,5605,5664 ,0,0,0}, {10414,10466,10412 ,5607,5664,5605 ,0,0,0}, - {10487,10130,10151 ,5685,5621,5689 ,0,0,0}, {10162,10413,10412 ,5620,5606,5605 ,0,0,0}, - {10488,10151,10262 ,5686,5689,5690 ,0,0,0}, {10130,10487,10413 ,5621,5685,5606 ,0,0,0}, - {10489,10262,10148 ,5687,5690,5691 ,0,0,0}, {10151,10488,10487 ,5689,5686,5685 ,0,0,0}, - {10490,10148,10146 ,5688,5691,5692 ,0,0,0}, {10262,10489,10488 ,5690,5687,5686 ,0,0,0}, - {10485,10146,10115 ,5683,5692,5693 ,0,0,0}, {10148,10490,10489 ,5691,5688,5687 ,0,0,0}, - {10444,10115,10153 ,5640,5693,5643 ,0,0,0}, {10146,10485,10490 ,5692,5683,5688 ,0,0,0}, - {10153,10442,10444 ,5643,5638,5640 ,0,0,0}, {10115,10444,10485 ,5693,5640,5683 ,0,0,0}, - {10491,10492,10493 ,5694,5695,5696 ,0,0,0}, {10494,10495,10496 ,5697,5698,5699 ,0,0,0}, - {10493,10497,10498 ,5696,5700,5701 ,0,0,0}, {10497,10499,10498 ,5700,5702,5701 ,0,0,0}, - {10500,10501,10502 ,5703,5704,5705 ,0,0,0}, {10502,10503,10500 ,5705,5706,5703 ,0,0,0}, - {10504,10505,10506 ,5707,5708,5709 ,0,0,0}, {10507,10501,10508 ,5710,5704,5711 ,0,0,0}, - {10507,10502,10501 ,5710,5705,5704 ,0,0,0}, {10508,10509,10507 ,5711,5712,5710 ,0,0,0}, - {10510,10496,10511 ,5713,5699,5714 ,0,0,0}, {10512,10513,10514 ,5715,5716,5717 ,0,0,0}, - {10504,10078,10077 ,5707,5718,5719 ,0,0,0}, {10515,10516,10517 ,5720,5721,5722 ,0,0,0}, - {10518,10105,10506 ,5723,5724,5709 ,0,0,0}, {10519,10520,10513 ,5725,5726,5716 ,0,0,0}, - {10078,10506,10105 ,5718,5709,5724 ,0,0,0}, {10521,10522,10523 ,5727,5728,5729 ,0,0,0}, - {10524,10498,10499 ,5730,5701,5702 ,0,0,0}, {10525,10526,10527 ,5731,5732,5733 ,0,0,0}, - {10528,10529,10493 ,5734,5735,5696 ,0,0,0}, {10530,10531,10532 ,5736,5737,5738 ,0,0,0}, - {10523,10533,10534 ,5729,5739,5740 ,0,0,0}, {10535,10533,10536 ,5741,5739,5742 ,0,0,0}, - {10537,10538,10539 ,5743,5744,5745 ,0,0,0}, {10491,10495,10494 ,5694,5698,5697 ,0,0,0}, - {10538,10525,10539 ,5744,5731,5745 ,0,0,0}, {10529,10540,10491 ,5735,5746,5694 ,0,0,0}, - {10101,10106,10537 ,5747,5748,5743 ,0,0,0}, {10541,10542,10529 ,5749,5750,5735 ,0,0,0}, - {10540,10495,10491 ,5746,5698,5694 ,0,0,0}, {10541,10543,10544 ,5749,5751,5752 ,0,0,0}, - {10529,10542,10540 ,5735,5750,5746 ,0,0,0}, {10545,10546,10547 ,5753,5754,5755 ,0,0,0}, - {10542,10541,10544 ,5750,5749,5752 ,0,0,0}, {10548,10547,10549 ,5756,5755,5757 ,0,0,0}, - {10546,10545,10543 ,5754,5753,5751 ,0,0,0}, {10511,10501,10510 ,5714,5704,5713 ,0,0,0}, - {10501,10511,10508 ,5704,5714,5711 ,0,0,0}, {10503,10550,10500 ,5706,5758,5703 ,0,0,0}, - {10510,10494,10496 ,5713,5697,5699 ,0,0,0}, {10551,10510,10500 ,5759,5713,5703 ,0,0,0}, - {10493,10492,10497 ,5696,5695,5700 ,0,0,0}, {10551,10492,10494 ,5759,5695,5697 ,0,0,0}, - {10541,10552,10543 ,5749,5760,5751 ,0,0,0}, {10494,10492,10491 ,5697,5695,5694 ,0,0,0}, - {10553,10554,10546 ,5761,5762,5754 ,0,0,0}, {10529,10491,10493 ,5735,5694,5696 ,0,0,0}, - {10552,10541,10528 ,5760,5749,5734 ,0,0,0}, {10547,10546,10549 ,5755,5754,5757 ,0,0,0}, - {10544,10543,10545 ,5752,5751,5753 ,0,0,0}, {10543,10552,10553 ,5751,5760,5761 ,0,0,0}, - {10555,10549,10546 ,5763,5757,5754 ,0,0,0}, {10501,10500,10510 ,5704,5703,5713 ,0,0,0}, - {10556,10550,10503 ,5764,5758,5706 ,0,0,0}, {10556,10519,10550 ,5764,5725,5758 ,0,0,0}, - {10510,10551,10494 ,5713,5759,5697 ,0,0,0}, {10550,10557,10551 ,5758,5765,5759 ,0,0,0}, - {10498,10536,10528 ,5701,5742,5734 ,0,0,0}, {10557,10497,10492 ,5765,5700,5695 ,0,0,0}, - {10523,10554,10553 ,5729,5762,5761 ,0,0,0}, {10522,10554,10523 ,5728,5762,5729 ,0,0,0}, - {10529,10528,10541 ,5735,5734,5749 ,0,0,0}, {10493,10498,10528 ,5696,5701,5734 ,0,0,0}, - {10543,10553,10546 ,5751,5761,5754 ,0,0,0}, {10536,10533,10552 ,5742,5739,5760 ,0,0,0}, - {10546,10554,10555 ,5754,5762,5763 ,0,0,0}, {10553,10533,10523 ,5761,5739,5729 ,0,0,0}, - {10558,10555,10554 ,5766,5763,5762 ,0,0,0}, {10500,10550,10551 ,5703,5758,5759 ,0,0,0}, - {10520,10519,10556 ,5726,5725,5764 ,0,0,0}, {10559,10512,10560 ,5767,5715,5768 ,0,0,0}, - {10551,10557,10492 ,5759,5765,5695 ,0,0,0}, {10561,10557,10519 ,5769,5765,5725 ,0,0,0}, - {10536,10498,10524 ,5742,5701,5730 ,0,0,0}, {10561,10499,10497 ,5769,5702,5700 ,0,0,0}, - {10562,10521,10534 ,5770,5727,5740 ,0,0,0}, {10552,10533,10553 ,5760,5739,5761 ,0,0,0}, - {10528,10536,10552 ,5734,5742,5760 ,0,0,0}, {10536,10524,10535 ,5742,5730,5741 ,0,0,0}, - {10522,10521,10563 ,5728,5727,5771 ,0,0,0}, {10535,10534,10533 ,5741,5740,5739 ,0,0,0}, - {10554,10522,10558 ,5762,5728,5766 ,0,0,0}, {10523,10534,10521 ,5729,5740,5727 ,0,0,0}, - {10564,10558,10522 ,5772,5766,5728 ,0,0,0}, {10550,10519,10557 ,5758,5725,5765 ,0,0,0}, - {10514,10513,10520 ,5717,5716,5726 ,0,0,0}, {10499,10565,10524 ,5702,5773,5730 ,0,0,0}, - {10557,10561,10497 ,5765,5769,5700 ,0,0,0}, {10566,10561,10513 ,5774,5769,5716 ,0,0,0}, - {10524,10567,10535 ,5730,5775,5741 ,0,0,0}, {10566,10565,10499 ,5774,5773,5702 ,0,0,0}, - {10535,10568,10534 ,5741,5776,5740 ,0,0,0}, {10567,10524,10565 ,5775,5730,5773 ,0,0,0}, - {10521,10531,10563 ,5727,5737,5771 ,0,0,0}, {10568,10535,10567 ,5776,5741,5775 ,0,0,0}, - {10569,10563,10530 ,5777,5771,5736 ,0,0,0}, {10562,10534,10568 ,5770,5740,5776 ,0,0,0}, - {10522,10563,10564 ,5728,5771,5772 ,0,0,0}, {10521,10562,10531 ,5727,5770,5737 ,0,0,0}, - {10569,10564,10563 ,5777,5772,5771 ,0,0,0}, {10519,10513,10561 ,5725,5716,5769 ,0,0,0}, - {10560,10512,10514 ,5768,5715,5717 ,0,0,0}, {10565,10516,10567 ,5773,5721,5775 ,0,0,0}, - {10561,10566,10499 ,5769,5774,5702 ,0,0,0}, {10512,10570,10566 ,5715,5778,5774 ,0,0,0}, - {10567,10515,10568 ,5775,5720,5776 ,0,0,0}, {10570,10516,10565 ,5778,5721,5773 ,0,0,0}, - {10568,10571,10562 ,5776,5779,5770 ,0,0,0}, {10516,10515,10567 ,5721,5720,5775 ,0,0,0}, - {10572,10531,10562 ,5780,5737,5770 ,0,0,0}, {10571,10568,10515 ,5779,5776,5720 ,0,0,0}, - {10573,10530,10527 ,5781,5736,5733 ,0,0,0}, {10562,10571,10572 ,5770,5779,5780 ,0,0,0}, - {10572,10532,10531 ,5780,5738,5737 ,0,0,0}, {10569,10530,10573 ,5777,5736,5781 ,0,0,0}, - {10563,10531,10530 ,5771,5737,5736 ,0,0,0}, {10513,10512,10566 ,5716,5715,5774 ,0,0,0}, - {10574,10559,10560 ,5782,5767,5768 ,0,0,0}, {10575,10571,10515 ,5783,5779,5720 ,0,0,0}, - {10566,10570,10565 ,5774,5778,5773 ,0,0,0}, {10559,10505,10570 ,5767,5708,5778 ,0,0,0}, - {10576,10572,10571 ,5784,5780,5779 ,0,0,0}, {10505,10517,10516 ,5708,5722,5721 ,0,0,0}, - {10577,10532,10572 ,5785,5738,5780 ,0,0,0}, {10517,10575,10515 ,5722,5783,5720 ,0,0,0}, - {10539,10525,10578 ,5745,5731,5786 ,0,0,0}, {10575,10576,10571 ,5783,5784,5779 ,0,0,0}, - {10527,10532,10579 ,5733,5738,5787 ,0,0,0}, {10577,10572,10576 ,5785,5780,5784 ,0,0,0}, - {10579,10532,10577 ,5787,5738,5785 ,0,0,0}, {10573,10527,10526 ,5781,5733,5732 ,0,0,0}, - {10530,10532,10527 ,5736,5738,5733 ,0,0,0}, {10512,10559,10570 ,5715,5767,5778 ,0,0,0}, - {10506,10574,10518 ,5709,5782,5723 ,0,0,0}, {10504,10580,10517 ,5707,5788,5722 ,0,0,0}, - {10570,10505,10516 ,5778,5708,5721 ,0,0,0}, {10504,10517,10505 ,5707,5722,5708 ,0,0,0}, - {10580,10581,10575 ,5788,5789,5783 ,0,0,0}, {10580,10575,10517 ,5788,5783,5722 ,0,0,0}, - {10581,10582,10576 ,5789,5790,5784 ,0,0,0}, {10581,10576,10575 ,5789,5784,5783 ,0,0,0}, - {10582,10583,10577 ,5790,5791,5785 ,0,0,0}, {10582,10577,10576 ,5790,5785,5784 ,0,0,0}, - {10583,10578,10579 ,5791,5786,5787 ,0,0,0}, {10579,10577,10583 ,5787,5785,5791 ,0,0,0}, - {10578,10525,10579 ,5786,5731,5787 ,0,0,0}, {10526,10525,10538 ,5732,5731,5744 ,0,0,0}, - {10527,10579,10525 ,5733,5787,5731 ,0,0,0}, {10574,10506,10559 ,5782,5709,5767 ,0,0,0}, - {10505,10559,10506 ,5708,5767,5709 ,0,0,0}, {10580,10077,10092 ,5788,5719,5792 ,0,0,0}, - {10078,10504,10506 ,5718,5707,5709 ,0,0,0}, {10581,10092,10095 ,5789,5792,5793 ,0,0,0}, - {10077,10580,10504 ,5719,5788,5707 ,0,0,0}, {10582,10095,10096 ,5790,5793,5794 ,0,0,0}, - {10092,10581,10580 ,5792,5789,5788 ,0,0,0}, {10583,10096,10135 ,5791,5794,5795 ,0,0,0}, - {10095,10582,10581 ,5793,5790,5789 ,0,0,0}, {10578,10135,10076 ,5786,5795,5796 ,0,0,0}, - {10096,10583,10582 ,5794,5791,5790 ,0,0,0}, {10539,10076,10101 ,5745,5796,5747 ,0,0,0}, - {10135,10578,10583 ,5795,5786,5791 ,0,0,0}, {10101,10537,10539 ,5747,5743,5745 ,0,0,0}, - {10076,10539,10578 ,5796,5745,5786 ,0,0,0}, {10584,10585,10586 ,5797,5798,5799 ,0,0,0}, - {10587,9501,9502 ,5800,5801,5802 ,0,0,0}, {10586,10588,10589 ,5799,5803,5804 ,0,0,0}, - {10588,10590,10589 ,5803,5805,5804 ,0,0,0}, {10591,10592,10593 ,5806,5807,5808 ,0,0,0}, - {10593,10594,10591 ,5808,5809,5806 ,0,0,0}, {10595,10596,10597 ,5810,5811,5812 ,0,0,0}, - {10598,10592,9507 ,5813,5807,5814 ,0,0,0}, {10598,10593,10592 ,5813,5808,5807 ,0,0,0}, - {9507,9508,10598 ,5814,5815,5813 ,0,0,0}, {10599,9502,9505 ,5816,5802,5817 ,0,0,0}, - {10600,10601,10602 ,5818,5819,5820 ,0,0,0}, {10595,10034,10033 ,5810,5821,5822 ,0,0,0}, - {10603,10604,10605 ,5823,5824,5825 ,0,0,0}, {10606,10041,10597 ,5826,5827,5812 ,0,0,0}, - {10607,10608,10601 ,5828,5829,5819 ,0,0,0}, {10034,10597,10041 ,5821,5812,5827 ,0,0,0}, - {10609,10610,10611 ,5830,5831,5832 ,0,0,0}, {10612,10589,10590 ,5833,5804,5805 ,0,0,0}, - {10613,10614,10615 ,5834,5835,5836 ,0,0,0}, {10616,10617,10586 ,5837,5838,5799 ,0,0,0}, - {10618,10619,10620 ,5839,5840,5841 ,0,0,0}, {10611,10621,10622 ,5832,5842,5843 ,0,0,0}, - {10623,10621,10624 ,5844,5842,5845 ,0,0,0}, {10625,10626,10627 ,5846,5847,5848 ,0,0,0}, - {10584,9501,10587 ,5797,5801,5800 ,0,0,0}, {10626,10613,10627 ,5847,5834,5848 ,0,0,0}, - {10617,9499,10584 ,5838,5849,5797 ,0,0,0}, {10057,10064,10625 ,5850,5851,5846 ,0,0,0}, - {10628,9497,10617 ,5852,5853,5838 ,0,0,0}, {9499,9501,10584 ,5849,5801,5797 ,0,0,0}, - {10628,10629,9494 ,5852,5854,5855 ,0,0,0}, {10617,9497,9499 ,5838,5853,5849 ,0,0,0}, - {9492,10630,9493 ,5856,5857,5858 ,0,0,0}, {9497,10628,9494 ,5853,5852,5855 ,0,0,0}, - {9487,9493,10631 ,5067,5858,5859 ,0,0,0}, {10630,9492,10629 ,5857,5856,5854 ,0,0,0}, - {9505,10592,10599 ,5817,5807,5816 ,0,0,0}, {10592,9505,9507 ,5807,5817,5814 ,0,0,0}, - {10594,10632,10591 ,5809,5860,5806 ,0,0,0}, {10599,10587,9502 ,5816,5800,5802 ,0,0,0}, - {10633,10599,10591 ,5861,5816,5806 ,0,0,0}, {10586,10585,10588 ,5799,5798,5803 ,0,0,0}, - {10633,10585,10587 ,5861,5798,5800 ,0,0,0}, {10628,10634,10629 ,5852,5862,5854 ,0,0,0}, - {10587,10585,10584 ,5800,5798,5797 ,0,0,0}, {10635,10636,10630 ,5863,5864,5857 ,0,0,0}, - {10617,10584,10586 ,5838,5797,5799 ,0,0,0}, {10634,10628,10616 ,5862,5852,5837 ,0,0,0}, - {9493,10630,10631 ,5858,5857,5859 ,0,0,0}, {9494,10629,9492 ,5855,5854,5856 ,0,0,0}, - {10629,10634,10635 ,5854,5862,5863 ,0,0,0}, {10637,10631,10630 ,5865,5859,5857 ,0,0,0}, - {10592,10591,10599 ,5807,5806,5816 ,0,0,0}, {10638,10632,10594 ,5866,5860,5809 ,0,0,0}, - {10638,10607,10632 ,5866,5828,5860 ,0,0,0}, {10599,10633,10587 ,5816,5861,5800 ,0,0,0}, - {10632,10639,10633 ,5860,5867,5861 ,0,0,0}, {10589,10624,10616 ,5804,5845,5837 ,0,0,0}, - {10639,10588,10585 ,5867,5803,5798 ,0,0,0}, {10611,10636,10635 ,5832,5864,5863 ,0,0,0}, - {10610,10636,10611 ,5831,5864,5832 ,0,0,0}, {10617,10616,10628 ,5838,5837,5852 ,0,0,0}, - {10586,10589,10616 ,5799,5804,5837 ,0,0,0}, {10629,10635,10630 ,5854,5863,5857 ,0,0,0}, - {10624,10621,10634 ,5845,5842,5862 ,0,0,0}, {10630,10636,10637 ,5857,5864,5865 ,0,0,0}, - {10635,10621,10611 ,5863,5842,5832 ,0,0,0}, {10640,10637,10636 ,5868,5865,5864 ,0,0,0}, - {10591,10632,10633 ,5806,5860,5861 ,0,0,0}, {10608,10607,10638 ,5829,5828,5866 ,0,0,0}, - {10641,10600,10642 ,5869,5818,5870 ,0,0,0}, {10633,10639,10585 ,5861,5867,5798 ,0,0,0}, - {10643,10639,10607 ,5871,5867,5828 ,0,0,0}, {10624,10589,10612 ,5845,5804,5833 ,0,0,0}, - {10643,10590,10588 ,5871,5805,5803 ,0,0,0}, {10644,10609,10622 ,5872,5830,5843 ,0,0,0}, - {10634,10621,10635 ,5862,5842,5863 ,0,0,0}, {10616,10624,10634 ,5837,5845,5862 ,0,0,0}, - {10624,10612,10623 ,5845,5833,5844 ,0,0,0}, {10610,10609,10645 ,5831,5830,5873 ,0,0,0}, - {10623,10622,10621 ,5844,5843,5842 ,0,0,0}, {10636,10610,10640 ,5864,5831,5868 ,0,0,0}, - {10611,10622,10609 ,5832,5843,5830 ,0,0,0}, {10646,10640,10610 ,5874,5868,5831 ,0,0,0}, - {10632,10607,10639 ,5860,5828,5867 ,0,0,0}, {10602,10601,10608 ,5820,5819,5829 ,0,0,0}, - {10590,10647,10612 ,5805,5875,5833 ,0,0,0}, {10639,10643,10588 ,5867,5871,5803 ,0,0,0}, - {10648,10643,10601 ,5876,5871,5819 ,0,0,0}, {10612,10649,10623 ,5833,5877,5844 ,0,0,0}, - {10648,10647,10590 ,5876,5875,5805 ,0,0,0}, {10623,10650,10622 ,5844,5878,5843 ,0,0,0}, - {10649,10612,10647 ,5877,5833,5875 ,0,0,0}, {10609,10619,10645 ,5830,5840,5873 ,0,0,0}, - {10650,10623,10649 ,5878,5844,5877 ,0,0,0}, {10651,10645,10618 ,5879,5873,5839 ,0,0,0}, - {10644,10622,10650 ,5872,5843,5878 ,0,0,0}, {10610,10645,10646 ,5831,5873,5874 ,0,0,0}, - {10609,10644,10619 ,5830,5872,5840 ,0,0,0}, {10651,10646,10645 ,5879,5874,5873 ,0,0,0}, - {10607,10601,10643 ,5828,5819,5871 ,0,0,0}, {10642,10600,10602 ,5870,5818,5820 ,0,0,0}, - {10647,10604,10649 ,5875,5824,5877 ,0,0,0}, {10643,10648,10590 ,5871,5876,5805 ,0,0,0}, - {10600,10652,10648 ,5818,5880,5876 ,0,0,0}, {10649,10603,10650 ,5877,5823,5878 ,0,0,0}, - {10652,10604,10647 ,5880,5824,5875 ,0,0,0}, {10650,10653,10644 ,5878,5881,5872 ,0,0,0}, - {10604,10603,10649 ,5824,5823,5877 ,0,0,0}, {10654,10619,10644 ,5882,5840,5872 ,0,0,0}, - {10653,10650,10603 ,5881,5878,5823 ,0,0,0}, {10655,10618,10615 ,5883,5839,5836 ,0,0,0}, - {10644,10653,10654 ,5872,5881,5882 ,0,0,0}, {10654,10620,10619 ,5882,5841,5840 ,0,0,0}, - {10651,10618,10655 ,5879,5839,5883 ,0,0,0}, {10645,10619,10618 ,5873,5840,5839 ,0,0,0}, - {10601,10600,10648 ,5819,5818,5876 ,0,0,0}, {10656,10641,10642 ,5884,5869,5870 ,0,0,0}, - {10657,10653,10603 ,5885,5881,5823 ,0,0,0}, {10648,10652,10647 ,5876,5880,5875 ,0,0,0}, - {10641,10596,10652 ,5869,5811,5880 ,0,0,0}, {10658,10654,10653 ,5886,5882,5881 ,0,0,0}, - {10596,10605,10604 ,5811,5825,5824 ,0,0,0}, {10659,10620,10654 ,5887,5841,5882 ,0,0,0}, - {10605,10657,10603 ,5825,5885,5823 ,0,0,0}, {10627,10613,10660 ,5848,5834,5888 ,0,0,0}, - {10657,10658,10653 ,5885,5886,5881 ,0,0,0}, {10615,10620,10661 ,5836,5841,5889 ,0,0,0}, - {10659,10654,10658 ,5887,5882,5886 ,0,0,0}, {10661,10620,10659 ,5889,5841,5887 ,0,0,0}, - {10655,10615,10614 ,5883,5836,5835 ,0,0,0}, {10618,10620,10615 ,5839,5841,5836 ,0,0,0}, - {10600,10641,10652 ,5818,5869,5880 ,0,0,0}, {10597,10656,10606 ,5812,5884,5826 ,0,0,0}, - {10595,10662,10605 ,5810,5890,5825 ,0,0,0}, {10652,10596,10604 ,5880,5811,5824 ,0,0,0}, - {10595,10605,10596 ,5810,5825,5811 ,0,0,0}, {10662,10663,10657 ,5890,5891,5885 ,0,0,0}, - {10662,10657,10605 ,5890,5885,5825 ,0,0,0}, {10663,10664,10658 ,5891,5892,5886 ,0,0,0}, - {10663,10658,10657 ,5891,5886,5885 ,0,0,0}, {10664,10665,10659 ,5892,5893,5887 ,0,0,0}, - {10664,10659,10658 ,5892,5887,5886 ,0,0,0}, {10665,10660,10661 ,5893,5888,5889 ,0,0,0}, - {10661,10659,10665 ,5889,5887,5893 ,0,0,0}, {10660,10613,10661 ,5888,5834,5889 ,0,0,0}, - {10614,10613,10626 ,5835,5834,5847 ,0,0,0}, {10615,10661,10613 ,5836,5889,5834 ,0,0,0}, - {10656,10597,10641 ,5884,5812,5869 ,0,0,0}, {10596,10641,10597 ,5811,5869,5812 ,0,0,0}, - {10662,10033,10051 ,5890,5822,5894 ,0,0,0}, {10034,10595,10597 ,5821,5810,5812 ,0,0,0}, - {10663,10051,10052 ,5891,5894,5895 ,0,0,0}, {10033,10662,10595 ,5822,5890,5810 ,0,0,0}, - {10664,10052,10054 ,5892,5895,5896 ,0,0,0}, {10051,10663,10662 ,5894,5891,5890 ,0,0,0}, - {10665,10054,10037 ,5893,5896,5897 ,0,0,0}, {10052,10664,10663 ,5895,5892,5891 ,0,0,0}, - {10660,10037,10058 ,5888,5897,5898 ,0,0,0}, {10054,10665,10664 ,5896,5893,5892 ,0,0,0}, - {10627,10058,10057 ,5848,5898,5850 ,0,0,0}, {10037,10660,10665 ,5897,5888,5893 ,0,0,0}, - {10057,10625,10627 ,5850,5846,5848 ,0,0,0}, {10058,10627,10660 ,5898,5848,5888 ,0,0,0}, - {10666,10667,10668 ,5899,5900,5901 ,0,0,0}, {10669,10670,9470 ,5902,5903,5904 ,0,0,0}, - {10667,10671,10668 ,5900,5905,5901 ,0,0,0}, {9465,9470,10670 ,5906,5904,5903 ,0,0,0}, - {10672,10673,10674 ,5907,5908,5909 ,0,0,0}, {9475,10675,10673 ,5910,5911,5908 ,0,0,0}, - {10676,10677,10678 ,5912,5913,5914 ,0,0,0}, {9473,10675,9475 ,5915,5911,5910 ,0,0,0}, - {10675,10674,10673 ,5911,5909,5908 ,0,0,0}, {9469,10673,10669 ,5916,5908,5902 ,0,0,0}, - {10679,10680,10681 ,5917,5918,5919 ,0,0,0}, {10682,10683,10684 ,5920,5921,5922 ,0,0,0}, - {10685,10680,10686 ,5923,5918,5924 ,0,0,0}, {10687,10688,10666 ,5925,5926,5899 ,0,0,0}, - {10677,9984,9903 ,5913,5927,5928 ,0,0,0}, {10689,10690,10691 ,5929,5930,5931 ,0,0,0}, - {10692,10014,10676 ,5932,5933,5912 ,0,0,0}, {9984,10676,10014 ,5927,5912,5933 ,0,0,0}, - {10693,10694,10695 ,5934,5935,5936 ,0,0,0}, {10671,10696,10668 ,5905,5937,5901 ,0,0,0}, - {10697,10698,10699 ,5938,5939,5940 ,0,0,0}, {10700,10701,10702 ,5941,5942,5943 ,0,0,0}, - {10691,10694,10703 ,5931,5935,5944 ,0,0,0}, {10704,10705,10706 ,5945,5946,5947 ,0,0,0}, - {10707,10666,10708 ,5948,5899,5949 ,0,0,0}, {10705,10700,10706 ,5946,5941,5947 ,0,0,0}, - {10687,9465,10670 ,5925,5906,5903 ,0,0,0}, {10013,10017,10704 ,5950,5951,5945 ,0,0,0}, - {9465,10687,9463 ,5906,5925,5952 ,0,0,0}, {9463,10687,10707 ,5952,5925,5948 ,0,0,0}, - {10709,9458,10707 ,5953,5954,5948 ,0,0,0}, {10687,10670,10688 ,5925,5903,5926 ,0,0,0}, - {10709,10710,9462 ,5953,5955,5956 ,0,0,0}, {9462,9458,10709 ,5956,5954,5953 ,0,0,0}, - {9454,10711,9456 ,5957,5958,5959 ,0,0,0}, {10711,9454,10710 ,5958,5957,5955 ,0,0,0}, - {9475,10673,9469 ,5910,5908,5916 ,0,0,0}, {10712,10672,10674 ,5960,5907,5909 ,0,0,0}, - {10712,10713,10672 ,5960,5961,5907 ,0,0,0}, {9469,10669,9470 ,5916,5902,5904 ,0,0,0}, - {10714,10669,10672 ,5962,5902,5907 ,0,0,0}, {10666,10688,10667 ,5899,5926,5900 ,0,0,0}, - {10714,10688,10670 ,5962,5926,5903 ,0,0,0}, {10709,10715,10710 ,5953,5963,5955 ,0,0,0}, - {10716,10711,10717 ,5964,5958,5965 ,0,0,0}, {9463,10707,9458 ,5952,5948,5954 ,0,0,0}, - {10707,10687,10666 ,5948,5925,5899 ,0,0,0}, {9462,10710,9454 ,5956,5955,5957 ,0,0,0}, - {10708,10715,10709 ,5949,5963,5953 ,0,0,0}, {10711,10718,9456 ,5958,5966,5959 ,0,0,0}, - {10710,10715,10717 ,5955,5963,5965 ,0,0,0}, {10719,10718,10711 ,5967,5966,5958 ,0,0,0}, - {10673,10672,10669 ,5908,5907,5902 ,0,0,0}, {10720,10713,10712 ,5968,5961,5960 ,0,0,0}, - {10720,10681,10713 ,5968,5919,5961 ,0,0,0}, {10669,10714,10670 ,5902,5962,5903 ,0,0,0}, - {10713,10721,10714 ,5961,5969,5962 ,0,0,0}, {10668,10695,10708 ,5901,5936,5949 ,0,0,0}, - {10721,10667,10688 ,5969,5900,5926 ,0,0,0}, {10691,10716,10717 ,5931,5964,5965 ,0,0,0}, - {10690,10716,10691 ,5930,5964,5931 ,0,0,0}, {10707,10708,10709 ,5948,5949,5953 ,0,0,0}, - {10666,10668,10708 ,5899,5901,5949 ,0,0,0}, {10710,10717,10711 ,5955,5965,5958 ,0,0,0}, - {10695,10694,10715 ,5936,5935,5963 ,0,0,0}, {10711,10716,10719 ,5958,5964,5967 ,0,0,0}, - {10717,10694,10691 ,5965,5935,5931 ,0,0,0}, {10722,10719,10716 ,5970,5967,5964 ,0,0,0}, - {10672,10713,10714 ,5907,5961,5962 ,0,0,0}, {10679,10681,10720 ,5917,5919,5968 ,0,0,0}, - {10723,10685,10724 ,5971,5923,5972 ,0,0,0}, {10714,10721,10688 ,5962,5969,5926 ,0,0,0}, - {10725,10721,10681 ,5973,5969,5919 ,0,0,0}, {10695,10668,10696 ,5936,5901,5937 ,0,0,0}, - {10725,10671,10667 ,5973,5905,5900 ,0,0,0}, {10726,10689,10703 ,5974,5929,5944 ,0,0,0}, - {10715,10694,10717 ,5963,5935,5965 ,0,0,0}, {10708,10695,10715 ,5949,5936,5963 ,0,0,0}, - {10695,10696,10693 ,5936,5937,5934 ,0,0,0}, {10690,10689,10727 ,5930,5929,5975 ,0,0,0}, - {10693,10703,10694 ,5934,5944,5935 ,0,0,0}, {10716,10690,10722 ,5964,5930,5970 ,0,0,0}, - {10691,10703,10689 ,5931,5944,5929 ,0,0,0}, {10728,10722,10690 ,5976,5970,5930 ,0,0,0}, - {10713,10681,10721 ,5961,5919,5969 ,0,0,0}, {10686,10680,10679 ,5924,5918,5917 ,0,0,0}, - {10671,10729,10696 ,5905,5977,5937 ,0,0,0}, {10721,10725,10667 ,5969,5973,5900 ,0,0,0}, - {10730,10725,10680 ,5978,5973,5918 ,0,0,0}, {10696,10731,10693 ,5937,5979,5934 ,0,0,0}, - {10730,10729,10671 ,5978,5977,5905 ,0,0,0}, {10693,10732,10703 ,5934,5980,5944 ,0,0,0}, - {10731,10696,10729 ,5979,5937,5977 ,0,0,0}, {10689,10698,10727 ,5929,5939,5975 ,0,0,0}, - {10732,10693,10731 ,5980,5934,5979 ,0,0,0}, {10733,10727,10697 ,5981,5975,5938 ,0,0,0}, - {10726,10703,10732 ,5974,5944,5980 ,0,0,0}, {10690,10727,10728 ,5930,5975,5976 ,0,0,0}, - {10689,10726,10698 ,5929,5974,5939 ,0,0,0}, {10733,10728,10727 ,5981,5976,5975 ,0,0,0}, - {10681,10680,10725 ,5919,5918,5973 ,0,0,0}, {10724,10685,10686 ,5972,5923,5924 ,0,0,0}, - {10729,10682,10731 ,5977,5920,5979 ,0,0,0}, {10725,10730,10671 ,5973,5978,5905 ,0,0,0}, - {10685,10734,10730 ,5923,5982,5978 ,0,0,0}, {10731,10684,10732 ,5979,5922,5980 ,0,0,0}, - {10734,10682,10729 ,5982,5920,5977 ,0,0,0}, {10732,10735,10726 ,5980,5983,5974 ,0,0,0}, - {10682,10684,10731 ,5920,5922,5979 ,0,0,0}, {10736,10698,10726 ,5984,5939,5974 ,0,0,0}, - {10735,10732,10684 ,5983,5980,5922 ,0,0,0}, {10737,10697,10702 ,5985,5938,5943 ,0,0,0}, - {10726,10735,10736 ,5974,5983,5984 ,0,0,0}, {10736,10699,10698 ,5984,5940,5939 ,0,0,0}, - {10733,10697,10737 ,5981,5938,5985 ,0,0,0}, {10727,10698,10697 ,5975,5939,5938 ,0,0,0}, - {10680,10685,10730 ,5918,5923,5978 ,0,0,0}, {10738,10723,10724 ,5986,5971,5972 ,0,0,0}, - {10739,10735,10684 ,5987,5983,5922 ,0,0,0}, {10730,10734,10729 ,5978,5982,5977 ,0,0,0}, - {10723,10678,10734 ,5971,5914,5982 ,0,0,0}, {10740,10736,10735 ,5988,5984,5983 ,0,0,0}, - {10678,10683,10682 ,5914,5921,5920 ,0,0,0}, {10741,10699,10736 ,5989,5940,5984 ,0,0,0}, - {10683,10739,10684 ,5921,5987,5922 ,0,0,0}, {10706,10700,10742 ,5947,5941,5990 ,0,0,0}, - {10739,10740,10735 ,5987,5988,5983 ,0,0,0}, {10702,10699,10743 ,5943,5940,5991 ,0,0,0}, - {10741,10736,10740 ,5989,5984,5988 ,0,0,0}, {10743,10699,10741 ,5991,5940,5989 ,0,0,0}, - {10737,10702,10701 ,5985,5943,5942 ,0,0,0}, {10697,10699,10702 ,5938,5940,5943 ,0,0,0}, - {10685,10723,10734 ,5923,5971,5982 ,0,0,0}, {10676,10738,10692 ,5912,5986,5932 ,0,0,0}, - {10677,10744,10683 ,5913,5992,5921 ,0,0,0}, {10734,10678,10682 ,5982,5914,5920 ,0,0,0}, - {10677,10683,10678 ,5913,5921,5914 ,0,0,0}, {10744,10745,10739 ,5992,5993,5987 ,0,0,0}, - {10744,10739,10683 ,5992,5987,5921 ,0,0,0}, {10745,10746,10740 ,5993,5994,5988 ,0,0,0}, - {10745,10740,10739 ,5993,5988,5987 ,0,0,0}, {10746,10747,10741 ,5994,5995,5989 ,0,0,0}, - {10746,10741,10740 ,5994,5989,5988 ,0,0,0}, {10747,10742,10743 ,5995,5990,5991 ,0,0,0}, - {10743,10741,10747 ,5991,5989,5995 ,0,0,0}, {10742,10700,10743 ,5990,5941,5991 ,0,0,0}, - {10701,10700,10705 ,5942,5941,5946 ,0,0,0}, {10702,10743,10700 ,5943,5991,5941 ,0,0,0}, - {10738,10676,10723 ,5986,5912,5971 ,0,0,0}, {10678,10723,10676 ,5914,5971,5912 ,0,0,0}, - {10744,9903,10003 ,5992,5928,5996 ,0,0,0}, {9984,10677,10676 ,5927,5913,5912 ,0,0,0}, - {10745,10003,10208 ,5993,5996,5997 ,0,0,0}, {9903,10744,10677 ,5928,5992,5913 ,0,0,0}, - {10746,10208,10010 ,5994,5997,5998 ,0,0,0}, {10003,10745,10744 ,5996,5993,5992 ,0,0,0}, - {10747,10010,10021 ,5995,5998,5999 ,0,0,0}, {10208,10746,10745 ,5997,5994,5993 ,0,0,0}, - {10742,10021,10007 ,5990,5999,6000 ,0,0,0}, {10010,10747,10746 ,5998,5995,5994 ,0,0,0}, - {10706,10007,10013 ,5947,6000,5950 ,0,0,0}, {10021,10742,10747 ,5999,5990,5995 ,0,0,0}, - {10013,10704,10706 ,5950,5945,5947 ,0,0,0}, {10007,10706,10742 ,6000,5947,5990 ,0,0,0}, - {10748,10749,10750 ,6001,6002,6003 ,0,0,0}, {10751,9438,9435 ,6004,6005,6006 ,0,0,0}, - {10750,10752,10753 ,6003,6007,6008 ,0,0,0}, {10752,10754,10753 ,6007,6009,6008 ,0,0,0}, - {10755,10756,10757 ,6010,6011,6012 ,0,0,0}, {10757,10758,10755 ,6012,6013,6010 ,0,0,0}, - {10759,10760,10761 ,6014,6015,6016 ,0,0,0}, {10762,10756,9441 ,6017,6011,6018 ,0,0,0}, - {10762,10757,10756 ,6017,6012,6011 ,0,0,0}, {9441,9440,10762 ,6018,5020,6017 ,0,0,0}, - {10763,9435,9443 ,6019,6006,6020 ,0,0,0}, {10764,10765,10766 ,6021,6022,6023 ,0,0,0}, - {10759,9958,9974 ,6014,6024,6025 ,0,0,0}, {10767,10768,10769 ,6026,6027,6028 ,0,0,0}, - {10770,9961,10761 ,6029,6030,6016 ,0,0,0}, {10771,10772,10765 ,6031,6032,6022 ,0,0,0}, - {9958,10761,9961 ,6024,6016,6030 ,0,0,0}, {10773,10774,10775 ,6033,6034,6035 ,0,0,0}, - {10776,10753,10754 ,6036,6008,6009 ,0,0,0}, {10777,10778,10779 ,6037,6038,6039 ,0,0,0}, - {10780,10781,10750 ,6040,6041,6003 ,0,0,0}, {10782,10783,10784 ,6042,6043,6044 ,0,0,0}, - {10775,10785,10786 ,6035,6045,6046 ,0,0,0}, {10787,10785,10788 ,6047,6045,6048 ,0,0,0}, - {10789,10790,10791 ,6049,6050,6051 ,0,0,0}, {10748,9438,10751 ,6001,6005,6004 ,0,0,0}, - {10790,10777,10791 ,6050,6037,6051 ,0,0,0}, {10781,9427,10748 ,6041,6052,6001 ,0,0,0}, - {9977,9979,10789 ,6053,6054,6049 ,0,0,0}, {10792,9428,10781 ,6055,6056,6041 ,0,0,0}, - {9427,9438,10748 ,6052,6005,6001 ,0,0,0}, {10792,10793,9430 ,6055,6057,6058 ,0,0,0}, - {10781,9428,9427 ,6041,6056,6052 ,0,0,0}, {9424,10794,9425 ,6059,6060,6061 ,0,0,0}, - {9428,10792,9430 ,6056,6055,6058 ,0,0,0}, {9416,9425,10795 ,6062,6061,6063 ,0,0,0}, - {10794,9424,10793 ,6060,6059,6057 ,0,0,0}, {9443,10756,10763 ,6020,6011,6019 ,0,0,0}, - {10756,9443,9441 ,6011,6020,6018 ,0,0,0}, {10758,10796,10755 ,6013,6064,6010 ,0,0,0}, - {10763,10751,9435 ,6019,6004,6006 ,0,0,0}, {10797,10763,10755 ,6065,6019,6010 ,0,0,0}, - {10750,10749,10752 ,6003,6002,6007 ,0,0,0}, {10797,10749,10751 ,6065,6002,6004 ,0,0,0}, - {10792,10798,10793 ,6055,6066,6057 ,0,0,0}, {10751,10749,10748 ,6004,6002,6001 ,0,0,0}, - {10799,10800,10794 ,6067,6068,6060 ,0,0,0}, {10781,10748,10750 ,6041,6001,6003 ,0,0,0}, - {10798,10792,10780 ,6066,6055,6040 ,0,0,0}, {9425,10794,10795 ,6061,6060,6063 ,0,0,0}, - {9430,10793,9424 ,6058,6057,6059 ,0,0,0}, {10793,10798,10799 ,6057,6066,6067 ,0,0,0}, - {10801,10795,10794 ,6069,6063,6060 ,0,0,0}, {10756,10755,10763 ,6011,6010,6019 ,0,0,0}, - {10802,10796,10758 ,6070,6064,6013 ,0,0,0}, {10802,10771,10796 ,6070,6031,6064 ,0,0,0}, - {10763,10797,10751 ,6019,6065,6004 ,0,0,0}, {10796,10803,10797 ,6064,6071,6065 ,0,0,0}, - {10753,10788,10780 ,6008,6048,6040 ,0,0,0}, {10803,10752,10749 ,6071,6007,6002 ,0,0,0}, - {10775,10800,10799 ,6035,6068,6067 ,0,0,0}, {10774,10800,10775 ,6034,6068,6035 ,0,0,0}, - {10781,10780,10792 ,6041,6040,6055 ,0,0,0}, {10750,10753,10780 ,6003,6008,6040 ,0,0,0}, - {10793,10799,10794 ,6057,6067,6060 ,0,0,0}, {10788,10785,10798 ,6048,6045,6066 ,0,0,0}, - {10794,10800,10801 ,6060,6068,6069 ,0,0,0}, {10799,10785,10775 ,6067,6045,6035 ,0,0,0}, - {10804,10801,10800 ,6072,6069,6068 ,0,0,0}, {10755,10796,10797 ,6010,6064,6065 ,0,0,0}, - {10772,10771,10802 ,6032,6031,6070 ,0,0,0}, {10805,10764,10806 ,6073,6021,6074 ,0,0,0}, - {10797,10803,10749 ,6065,6071,6002 ,0,0,0}, {10807,10803,10771 ,6075,6071,6031 ,0,0,0}, - {10788,10753,10776 ,6048,6008,6036 ,0,0,0}, {10807,10754,10752 ,6075,6009,6007 ,0,0,0}, - {10808,10773,10786 ,6076,6033,6046 ,0,0,0}, {10798,10785,10799 ,6066,6045,6067 ,0,0,0}, - {10780,10788,10798 ,6040,6048,6066 ,0,0,0}, {10788,10776,10787 ,6048,6036,6047 ,0,0,0}, - {10774,10773,10809 ,6034,6033,6077 ,0,0,0}, {10787,10786,10785 ,6047,6046,6045 ,0,0,0}, - {10800,10774,10804 ,6068,6034,6072 ,0,0,0}, {10775,10786,10773 ,6035,6046,6033 ,0,0,0}, - {10810,10804,10774 ,6078,6072,6034 ,0,0,0}, {10796,10771,10803 ,6064,6031,6071 ,0,0,0}, - {10766,10765,10772 ,6023,6022,6032 ,0,0,0}, {10754,10811,10776 ,6009,6079,6036 ,0,0,0}, - {10803,10807,10752 ,6071,6075,6007 ,0,0,0}, {10812,10807,10765 ,6080,6075,6022 ,0,0,0}, - {10776,10813,10787 ,6036,6081,6047 ,0,0,0}, {10812,10811,10754 ,6080,6079,6009 ,0,0,0}, - {10787,10814,10786 ,6047,6082,6046 ,0,0,0}, {10813,10776,10811 ,6081,6036,6079 ,0,0,0}, - {10773,10783,10809 ,6033,6043,6077 ,0,0,0}, {10814,10787,10813 ,6082,6047,6081 ,0,0,0}, - {10815,10809,10782 ,6083,6077,6042 ,0,0,0}, {10808,10786,10814 ,6076,6046,6082 ,0,0,0}, - {10774,10809,10810 ,6034,6077,6078 ,0,0,0}, {10773,10808,10783 ,6033,6076,6043 ,0,0,0}, - {10815,10810,10809 ,6083,6078,6077 ,0,0,0}, {10771,10765,10807 ,6031,6022,6075 ,0,0,0}, - {10806,10764,10766 ,6074,6021,6023 ,0,0,0}, {10811,10768,10813 ,6079,6027,6081 ,0,0,0}, - {10807,10812,10754 ,6075,6080,6009 ,0,0,0}, {10764,10816,10812 ,6021,6084,6080 ,0,0,0}, - {10813,10767,10814 ,6081,6026,6082 ,0,0,0}, {10816,10768,10811 ,6084,6027,6079 ,0,0,0}, - {10814,10817,10808 ,6082,6085,6076 ,0,0,0}, {10768,10767,10813 ,6027,6026,6081 ,0,0,0}, - {10818,10783,10808 ,6086,6043,6076 ,0,0,0}, {10817,10814,10767 ,6085,6082,6026 ,0,0,0}, - {10819,10782,10779 ,6087,6042,6039 ,0,0,0}, {10808,10817,10818 ,6076,6085,6086 ,0,0,0}, - {10818,10784,10783 ,6086,6044,6043 ,0,0,0}, {10815,10782,10819 ,6083,6042,6087 ,0,0,0}, - {10809,10783,10782 ,6077,6043,6042 ,0,0,0}, {10765,10764,10812 ,6022,6021,6080 ,0,0,0}, - {10820,10805,10806 ,6088,6073,6074 ,0,0,0}, {10821,10817,10767 ,6089,6085,6026 ,0,0,0}, - {10812,10816,10811 ,6080,6084,6079 ,0,0,0}, {10805,10760,10816 ,6073,6015,6084 ,0,0,0}, - {10822,10818,10817 ,6090,6086,6085 ,0,0,0}, {10760,10769,10768 ,6015,6028,6027 ,0,0,0}, - {10823,10784,10818 ,6091,6044,6086 ,0,0,0}, {10769,10821,10767 ,6028,6089,6026 ,0,0,0}, - {10791,10777,10824 ,6051,6037,6092 ,0,0,0}, {10821,10822,10817 ,6089,6090,6085 ,0,0,0}, - {10779,10784,10825 ,6039,6044,6093 ,0,0,0}, {10823,10818,10822 ,6091,6086,6090 ,0,0,0}, - {10825,10784,10823 ,6093,6044,6091 ,0,0,0}, {10819,10779,10778 ,6087,6039,6038 ,0,0,0}, - {10782,10784,10779 ,6042,6044,6039 ,0,0,0}, {10764,10805,10816 ,6021,6073,6084 ,0,0,0}, - {10761,10820,10770 ,6016,6088,6029 ,0,0,0}, {10759,10826,10769 ,6014,6094,6028 ,0,0,0}, - {10816,10760,10768 ,6084,6015,6027 ,0,0,0}, {10759,10769,10760 ,6014,6028,6015 ,0,0,0}, - {10826,10827,10821 ,6094,6095,6089 ,0,0,0}, {10826,10821,10769 ,6094,6089,6028 ,0,0,0}, - {10827,10828,10822 ,6095,6096,6090 ,0,0,0}, {10827,10822,10821 ,6095,6090,6089 ,0,0,0}, - {10828,10829,10823 ,6096,6097,6091 ,0,0,0}, {10828,10823,10822 ,6096,6091,6090 ,0,0,0}, - {10829,10824,10825 ,6097,6092,6093 ,0,0,0}, {10825,10823,10829 ,6093,6091,6097 ,0,0,0}, - {10824,10777,10825 ,6092,6037,6093 ,0,0,0}, {10778,10777,10790 ,6038,6037,6050 ,0,0,0}, - {10779,10825,10777 ,6039,6093,6037 ,0,0,0}, {10820,10761,10805 ,6088,6016,6073 ,0,0,0}, - {10760,10805,10761 ,6015,6073,6016 ,0,0,0}, {10826,9974,9968 ,6094,6025,6098 ,0,0,0}, - {9958,10759,10761 ,6024,6014,6016 ,0,0,0}, {10827,9968,9972 ,6095,6098,6099 ,0,0,0}, - {9974,10826,10759 ,6025,6094,6014 ,0,0,0}, {10828,9972,9971 ,6096,6099,6100 ,0,0,0}, - {9968,10827,10826 ,6098,6095,6094 ,0,0,0}, {10829,9971,9981 ,6097,6100,6101 ,0,0,0}, - {9972,10828,10827 ,6099,6096,6095 ,0,0,0}, {10824,9981,9943 ,6092,6101,6102 ,0,0,0}, - {9971,10829,10828 ,6100,6097,6096 ,0,0,0}, {10791,9943,9977 ,6051,6102,6053 ,0,0,0}, - {9981,10824,10829 ,6101,6092,6097 ,0,0,0}, {9977,10789,10791 ,6053,6049,6051 ,0,0,0}, - {9943,10791,10824 ,6102,6051,6092 ,0,0,0}, {10830,10831,10832 ,730,6103,6103 ,0,0,0}, - {9060,9002,8999 ,6103,730,730 ,0,0,0}, {10833,10831,10834 ,6104,6103,6105 ,0,0,0}, - {10833,10835,10836 ,6104,6106,6103 ,0,0,0}, {10837,10832,10838 ,6107,6103,6108 ,0,0,0}, - {10835,10839,10840 ,6106,6109,6110 ,0,0,0}, {10841,10842,10838 ,6103,6111,6108 ,0,0,0}, - {10840,10843,10844 ,6110,6112,6110 ,0,0,0}, {10845,10841,10846 ,6111,6103,6103 ,0,0,0}, - {10844,10847,10848 ,6110,6113,6112 ,0,0,0}, {10848,10849,10850 ,6112,6109,6110 ,0,0,0}, - {10850,10851,10852 ,6110,6106,6114 ,0,0,0}, {10846,10853,10854 ,6103,730,6115 ,0,0,0}, - {10855,10852,10856 ,6105,6114,6104 ,0,0,0}, {10857,10858,10859 ,6111,730,6111 ,0,0,0}, - {10860,10852,10855 ,6111,6114,6105 ,0,0,0}, {10859,10861,10862 ,6111,6110,6114 ,0,0,0}, - {10863,10864,10865 ,730,6114,6108 ,0,0,0}, {9008,9073,9075 ,6110,6111,6110 ,0,0,0}, - {10866,10867,10868 ,6115,730,6111 ,0,0,0}, {9072,9007,9070 ,730,730,6114 ,0,0,0}, - {10869,10870,8991 ,6111,6110,6110 ,0,0,0}, {9003,9066,9005 ,730,6114,6103 ,0,0,0}, - {8988,9038,9035 ,730,730,6114 ,0,0,0}, {9002,9061,9064 ,730,730,6103 ,0,0,0}, - {9032,8984,9033 ,6114,730,730 ,0,0,0}, {9058,9060,8999 ,730,6103,730 ,0,0,0}, - {8982,9026,8979 ,6103,6103,730 ,0,0,0}, {9052,9054,8993 ,730,730,730 ,0,0,0}, - {9020,9017,8978 ,730,730,730 ,0,0,0}, {9046,8992,8972 ,730,730,730 ,0,0,0}, - {8976,9015,9014 ,730,730,730 ,0,0,0}, {8976,8977,9015 ,730,730,730 ,0,0,0}, - {8978,9017,8977 ,730,730,730 ,0,0,0}, {9046,8972,9010 ,730,730,730 ,0,0,0}, - {8972,8976,9011 ,730,730,730 ,0,0,0}, {9021,8979,9023 ,6103,730,730 ,0,0,0}, - {8978,8979,9021 ,730,730,6103 ,0,0,0}, {8992,9049,8993 ,730,730,730 ,0,0,0}, - {8992,9048,9049 ,730,730,730 ,0,0,0}, {8982,8984,9029 ,6103,730,6103 ,0,0,0}, - {8982,9029,9027 ,6103,6103,730 ,0,0,0}, {8999,8997,9055 ,730,730,6103 ,0,0,0}, - {9054,8997,8993 ,730,730,730 ,0,0,0}, {8988,9035,8985 ,730,6114,6103 ,0,0,0}, - {8984,8985,9033 ,730,6103,730 ,0,0,0}, {9002,9060,9061 ,730,6103,730 ,0,0,0}, - {9041,9039,8991 ,6110,6111,6110 ,0,0,0}, {8988,8991,9039 ,730,6110,6111 ,0,0,0}, - {9003,9064,9066 ,730,6103,6114 ,0,0,0}, {9002,9064,9003 ,730,6103,730 ,0,0,0}, - {10868,10871,10869 ,6111,6111,6111 ,0,0,0}, {10872,10869,10871 ,6114,6111,6111 ,0,0,0}, - {9066,9067,9005 ,6114,730,6103 ,0,0,0}, {9005,9070,9007 ,6103,6114,730 ,0,0,0}, - {9067,9070,9005 ,730,6114,6103 ,0,0,0}, {9072,9073,9007 ,730,6111,730 ,0,0,0}, - {10873,10865,10864 ,6107,6108,6114 ,0,0,0}, {9008,9007,9073 ,6110,730,6111 ,0,0,0}, - {9075,10861,9008 ,6110,6110,6110 ,0,0,0}, {10864,10860,10874 ,6114,6111,730 ,0,0,0}, - {10875,10876,10863 ,6111,6110,730 ,0,0,0}, {10876,10866,10868 ,6110,6115,6111 ,0,0,0}, - {10849,10851,10850 ,6109,6106,6110 ,0,0,0}, {9058,8999,9055 ,730,730,6103 ,0,0,0}, - {9055,8997,9054 ,6103,730,730 ,0,0,0}, {9052,8993,9049 ,730,730,730 ,0,0,0}, - {9048,8992,9046 ,730,730,730 ,0,0,0}, {9010,8972,9011 ,730,730,730 ,0,0,0}, - {9011,8976,9014 ,730,730,730 ,0,0,0}, {9015,8977,9017 ,730,730,730 ,0,0,0}, - {9020,8978,9021 ,730,730,6103 ,0,0,0}, {9023,8979,9026 ,730,730,6103 ,0,0,0}, - {9026,8982,9027 ,6103,6103,730 ,0,0,0}, {9029,8984,9032 ,6103,730,6114 ,0,0,0}, - {9033,8985,9035 ,730,6103,6114 ,0,0,0}, {9038,8988,9039 ,730,730,6111 ,0,0,0}, - {9041,8991,10870 ,6110,6110,6110 ,0,0,0}, {10870,10869,10872 ,6110,6111,6114 ,0,0,0}, - {10871,10868,10867 ,6111,6111,730 ,0,0,0}, {10866,10876,10875 ,6115,6110,6111 ,0,0,0}, - {10877,10863,10865 ,6111,730,6108 ,0,0,0}, {10863,10877,10875 ,730,6111,6111 ,0,0,0}, - {10873,10864,10874 ,6107,6114,730 ,0,0,0}, {10874,10860,10855 ,730,6111,6105 ,0,0,0}, - {10856,10852,10851 ,6104,6114,6106 ,0,0,0}, {10850,10844,10848 ,6110,6110,6112 ,0,0,0}, - {10847,10844,10843 ,6113,6110,6112 ,0,0,0}, {10843,10840,10839 ,6112,6110,6109 ,0,0,0}, - {10835,10840,10836 ,6106,6110,6103 ,0,0,0}, {10833,10836,10831 ,6104,6103,6103 ,0,0,0}, - {10830,10834,10831 ,730,6105,6103 ,0,0,0}, {10837,10830,10832 ,6107,730,6103 ,0,0,0}, - {10841,10838,10832 ,6103,6108,6103 ,0,0,0}, {10841,10845,10842 ,6103,6111,6111 ,0,0,0}, - {10846,10854,10845 ,6103,6115,6111 ,0,0,0}, {10846,10858,10853 ,6103,730,730 ,0,0,0}, - {10857,10859,10862 ,6111,6111,6114 ,0,0,0}, {10853,10858,10857 ,730,730,6111 ,0,0,0}, - {10861,10859,9008 ,6110,6111,6110 ,0,0,0}, {9044,9012,10878 ,6116,6117,6118 ,0,0,0}, - {9047,10879,10880 ,6119,6120,6121 ,0,0,0}, {10881,10882,9199 ,6122,6123,6124 ,0,0,0}, - {9289,9059,9286 ,6125,6126,6127 ,0,0,0}, {9215,9214,9626 ,6128,6129,6130 ,0,0,0}, - {9145,9148,9069 ,6131,6132,6122 ,0,0,0}, {10883,9150,10884 ,6133,6134,6135 ,0,0,0}, - {10885,10886,10887 ,6136,6137,6138 ,0,0,0}, {9016,9096,9099 ,6122,6120,6139 ,0,0,0}, - {10882,9184,9189 ,6123,6140,6141 ,0,0,0}, {10888,9267,9269 ,6139,6142,6143 ,0,0,0}, - {9539,10889,9540 ,6144,6145,6146 ,0,0,0}, {9597,10890,9590 ,6147,6148,6149 ,0,0,0}, - {9117,10891,9120 ,6150,6144,6150 ,0,0,0}, {10892,9175,9574 ,6151,6134,6152 ,0,0,0}, - {10893,9076,10894 ,6145,6153,6154 ,0,0,0}, {10892,9574,10895 ,6151,6152,6155 ,0,0,0}, - {10896,9574,9573 ,6156,6152,6157 ,0,0,0}, {10897,10898,10899 ,6158,6144,6159 ,0,0,0}, - {10900,10901,10902 ,6160,6161,6162 ,0,0,0}, {9573,10903,10896 ,6157,6163,6156 ,0,0,0}, - {10904,10905,9573 ,6158,6164,6157 ,0,0,0}, {9579,10906,10904 ,6155,6165,6158 ,0,0,0}, - {10907,9584,10908 ,6166,6167,6116 ,0,0,0}, {9579,10904,9573 ,6155,6158,6157 ,0,0,0}, - {9591,10908,9584 ,6168,6116,6167 ,0,0,0}, {10899,10887,10886 ,6159,6138,6137 ,0,0,0}, - {10909,10910,10911 ,6122,6169,6170 ,0,0,0}, {10912,9579,9577 ,6171,6155,6172 ,0,0,0}, - {9577,10913,10912 ,6172,6118,6171 ,0,0,0}, {10914,10915,9587 ,6173,6174,6175 ,0,0,0}, - {9577,9576,10913 ,6172,6176,6118 ,0,0,0}, {9576,10915,10916 ,6176,6174,6177 ,0,0,0}, - {10917,9240,9239 ,6120,6146,6154 ,0,0,0}, {9576,9587,10915 ,6176,6175,6174 ,0,0,0}, - {10914,9587,9582 ,6173,6175,6178 ,0,0,0}, {10894,9078,10918 ,6154,6120,6145 ,0,0,0}, - {10919,10920,10921 ,6177,6179,6180 ,0,0,0}, {10922,10914,9582 ,6181,6173,6178 ,0,0,0}, - {10920,10923,10909 ,6179,6182,6122 ,0,0,0}, {10897,10924,10898 ,6158,6183,6144 ,0,0,0}, - {10911,10910,10925 ,6170,6169,6184 ,0,0,0}, {9591,9590,10926 ,6168,6149,6185 ,0,0,0}, - {10927,9024,10928 ,6186,6187,6119 ,0,0,0}, {9120,10929,9121 ,6150,6144,6188 ,0,0,0}, - {10930,9542,10931 ,6145,6144,6150 ,0,0,0}, {10924,9307,10932 ,6183,6189,6190 ,0,0,0}, - {9537,10933,10934 ,6154,6120,6127 ,0,0,0}, {9274,9273,9637 ,6191,6142,6192 ,0,0,0}, - {10879,9047,9045 ,6120,6119,6122 ,0,0,0}, {9631,9205,9204 ,6193,6194,6195 ,0,0,0}, - {9276,9532,9526 ,6196,6186,6197 ,0,0,0}, {9152,9074,9071 ,6196,6134,6138 ,0,0,0}, - {10882,9303,9298 ,6123,6198,6199 ,0,0,0}, {9069,9148,9071 ,6122,6132,6138 ,0,0,0}, - {9144,9145,9068 ,6157,6131,6137 ,0,0,0}, {9144,9068,9065 ,6157,6137,6131 ,0,0,0}, - {9063,9142,9065 ,6200,6143,6131 ,0,0,0}, {9051,9262,9280 ,6117,6201,6202 ,0,0,0}, - {10885,10935,10936 ,6136,6200,6156 ,0,0,0}, {9136,10937,9131 ,6118,6203,6132 ,0,0,0}, - {10938,9138,9140 ,6133,6204,6133 ,0,0,0}, {9068,9145,9069 ,6137,6131,6122 ,0,0,0}, - {9148,9152,9071 ,6132,6196,6138 ,0,0,0}, {9138,10939,9133 ,6204,6153,6201 ,0,0,0}, - {10940,9131,10937 ,6201,6132,6203 ,0,0,0}, {9053,9051,9280 ,6187,6117,6202 ,0,0,0}, - {9065,9142,9144 ,6131,6143,6157 ,0,0,0}, {9127,9557,9559 ,6132,6144,6205 ,0,0,0}, - {9140,9292,10938 ,6133,6201,6133 ,0,0,0}, {9063,9292,9142 ,6200,6201,6143 ,0,0,0}, - {9564,9126,9559 ,6206,6116,6205 ,0,0,0}, {9158,9564,9566 ,6207,6206,6204 ,0,0,0}, - {10941,10942,9132 ,6132,6119,6207 ,0,0,0}, {9557,9127,9131 ,6144,6132,6132 ,0,0,0}, - {9126,9564,9156 ,6116,6206,6121 ,0,0,0}, {9126,9127,9559 ,6116,6132,6205 ,0,0,0}, - {9567,9162,9566 ,6208,6207,6204 ,0,0,0}, {9158,9156,9564 ,6207,6121,6206 ,0,0,0}, - {9159,9158,9566 ,6209,6207,6204 ,0,0,0}, {9567,9569,9165 ,6208,6142,6196 ,0,0,0}, - {9162,9159,9566 ,6207,6209,6204 ,0,0,0}, {9164,9162,9567 ,6133,6207,6208 ,0,0,0}, - {9567,9165,9164 ,6208,6196,6133 ,0,0,0}, {9569,9168,9165 ,6142,6134,6196 ,0,0,0}, - {9572,9170,9569 ,6148,6131,6142 ,0,0,0}, {9569,9170,9168 ,6142,6131,6134 ,0,0,0}, - {9572,9171,9170 ,6148,6205,6131 ,0,0,0}, {9171,9572,9174 ,6205,6148,6204 ,0,0,0}, - {9572,9175,9174 ,6148,6134,6204 ,0,0,0}, {10896,10895,9574 ,6156,6155,6152 ,0,0,0}, - {10912,10906,9579 ,6171,6165,6155 ,0,0,0}, {10905,10903,9573 ,6164,6163,6157 ,0,0,0}, - {10913,9576,10916 ,6118,6176,6177 ,0,0,0}, {10907,10943,9582 ,6166,6210,6178 ,0,0,0}, - {10944,9596,10945 ,6157,6190,6211 ,0,0,0}, {10922,10946,10947 ,6181,6212,6182 ,0,0,0}, - {9188,10882,9189 ,6174,6123,6141 ,0,0,0}, {10948,10949,10882 ,6213,6214,6123 ,0,0,0}, - {9634,9631,9178 ,6215,6193,6216 ,0,0,0}, {9317,9319,9179 ,6217,6218,6219 ,0,0,0}, - {9204,9178,9631 ,6195,6216,6193 ,0,0,0}, {9209,9208,9623 ,6220,6221,6222 ,0,0,0}, - {9205,9630,9208 ,6194,6223,6221 ,0,0,0}, {9626,9214,9211 ,6130,6129,6181 ,0,0,0}, - {9211,9623,9626 ,6181,6222,6130 ,0,0,0}, {9220,9627,9221 ,6224,6225,6226 ,0,0,0}, - {9217,9626,9627 ,6227,6130,6225 ,0,0,0}, {9297,10882,9298 ,6212,6123,6199 ,0,0,0}, - {9228,10950,9229 ,6203,6228,6201 ,0,0,0}, {9319,9180,9179 ,6218,6229,6219 ,0,0,0}, - {10951,10952,10953 ,6230,6231,6232 ,0,0,0}, {9319,9320,9599 ,6218,6200,6233 ,0,0,0}, - {9220,9217,9627 ,6224,6227,6225 ,0,0,0}, {9627,9223,9221 ,6225,6234,6226 ,0,0,0}, - {9217,9215,9626 ,6227,6128,6130 ,0,0,0}, {9297,9296,10882 ,6212,6235,6123 ,0,0,0}, - {9209,9623,9211 ,6220,6222,6181 ,0,0,0}, {9630,9623,9208 ,6223,6222,6221 ,0,0,0}, - {9631,9630,9205 ,6193,6223,6194 ,0,0,0}, {9180,9634,9178 ,6229,6215,6216 ,0,0,0}, - {9634,9180,9599 ,6215,6229,6233 ,0,0,0}, {10949,9304,10882 ,6214,6236,6123 ,0,0,0}, - {9307,9304,10932 ,6189,6236,6190 ,0,0,0}, {10882,10954,10955 ,6123,6170,6214 ,0,0,0}, - {9196,10882,9192 ,6237,6123,6167 ,0,0,0}, {10881,10954,10882 ,6122,6170,6123 ,0,0,0}, - {9198,10956,10957 ,6238,6180,6179 ,0,0,0}, {10958,9235,10959 ,6197,6165,6196 ,0,0,0}, - {10960,9040,10961 ,6131,6122,6132 ,0,0,0}, {9203,10962,10956 ,6239,6240,6180 ,0,0,0}, - {10963,10964,10902 ,6171,6152,6162 ,0,0,0}, {9031,10965,9030 ,6204,6208,6126 ,0,0,0}, - {10966,10925,10967 ,6241,6184,6136 ,0,0,0}, {10968,9246,9249 ,6179,6179,6202 ,0,0,0}, - {9258,10965,9257 ,6127,6208,6242 ,0,0,0}, {9383,10969,10970 ,6156,6200,6136 ,0,0,0}, - {9386,9388,10971 ,6137,6135,6133 ,0,0,0}, {10972,10973,10974 ,6207,6133,6208 ,0,0,0}, - {9344,9377,9380 ,6196,6158,6159 ,0,0,0}, {9367,9337,9332 ,6181,6243,6139 ,0,0,0}, - {9351,9353,10975 ,6244,6245,6246 ,0,0,0}, {9330,10976,10977 ,6247,6190,6136 ,0,0,0}, - {10978,10952,10979 ,6248,6231,6170 ,0,0,0}, {10980,10981,9359 ,6152,6249,6250 ,0,0,0}, - {10982,10952,10978 ,6251,6231,6248 ,0,0,0}, {10983,10984,10985 ,6252,6253,6254 ,0,0,0}, - {10984,10951,10985 ,6253,6230,6254 ,0,0,0}, {10986,10987,10988 ,6255,6256,6257 ,0,0,0}, - {10989,10990,10991 ,6258,6259,6260 ,0,0,0}, {10984,10983,10991 ,6253,6252,6260 ,0,0,0}, - {10991,10990,10984 ,6260,6259,6253 ,0,0,0}, {10990,10989,10992 ,6259,6258,6261 ,0,0,0}, - {10993,10988,10994 ,6262,6257,6263 ,0,0,0}, {10992,10994,10990 ,6261,6263,6259 ,0,0,0}, - {10988,10987,10994 ,6257,6256,6263 ,0,0,0}, {10995,10996,10987 ,6264,6265,6256 ,0,0,0}, - {10992,10993,10994 ,6261,6262,6263 ,0,0,0}, {10986,10995,10987 ,6255,6264,6256 ,0,0,0}, - {10985,10951,10953 ,6254,6230,6232 ,0,0,0}, {10997,10998,9360 ,6138,6134,6266 ,0,0,0}, - {10953,10952,10982 ,6232,6231,6251 ,0,0,0}, {10979,10998,10997 ,6170,6134,6138 ,0,0,0}, - {10999,9353,9354 ,6267,6245,6268 ,0,0,0}, {9331,10977,11000 ,6167,6136,6199 ,0,0,0}, - {9348,9351,10976 ,6235,6244,6190 ,0,0,0}, {11001,9402,11002 ,6197,6164,6191 ,0,0,0}, - {9396,9395,11003 ,6171,6118,6269 ,0,0,0}, {9341,9338,9371 ,6270,6270,6174 ,0,0,0}, - {11001,9404,9402 ,6197,6163,6164 ,0,0,0}, {9376,9341,9371 ,6127,6270,6174 ,0,0,0}, - {11004,10936,10935 ,6137,6156,6200 ,0,0,0}, {11005,11006,11007 ,6213,6271,6169 ,0,0,0}, - {9365,9367,11008 ,6173,6181,6272 ,0,0,0}, {9407,9404,11001 ,6156,6163,6197 ,0,0,0}, - {10997,11009,10979 ,6138,6273,6170 ,0,0,0}, {11010,9408,9407 ,6201,6155,6156 ,0,0,0}, - {11010,9412,9410 ,6201,6134,6151 ,0,0,0}, {11011,10965,11012 ,6214,6208,6133 ,0,0,0}, - {11011,9025,9028 ,6214,6208,6117 ,0,0,0}, {11013,11014,11015 ,6190,6214,6199 ,0,0,0}, - {9402,9401,11002 ,6164,6158,6191 ,0,0,0}, {9396,11003,11002 ,6171,6269,6191 ,0,0,0}, - {11016,11017,11018 ,6274,6118,6183 ,0,0,0}, {11019,11020,11021 ,6149,6275,6214 ,0,0,0}, - {11022,10978,11009 ,6243,6248,6273 ,0,0,0}, {11022,11009,11023 ,6243,6273,6276 ,0,0,0}, - {11021,10911,10925 ,6214,6170,6184 ,0,0,0}, {10909,10923,10910 ,6122,6182,6169 ,0,0,0}, - {10921,11024,10919 ,6180,6244,6177 ,0,0,0}, {10920,10919,10923 ,6179,6177,6182 ,0,0,0}, - {10897,11025,9308 ,6158,6127,6249 ,0,0,0}, {9203,11024,10962 ,6239,6244,6240 ,0,0,0}, - {10921,10962,11024 ,6180,6240,6244 ,0,0,0}, {9203,10956,9200 ,6239,6180,6277 ,0,0,0}, - {10897,9308,9307 ,6158,6249,6189 ,0,0,0}, {9199,9198,10957 ,6124,6238,6179 ,0,0,0}, - {9198,9200,10956 ,6238,6277,6180 ,0,0,0}, {9326,9594,9602 ,6278,6279,6280 ,0,0,0}, - {9594,10945,9596 ,6279,6211,6190 ,0,0,0}, {10881,9199,10957 ,6122,6124,6179 ,0,0,0}, - {11026,10882,10955 ,6275,6123,6214 ,0,0,0}, {9199,10882,9196 ,6124,6123,6237 ,0,0,0}, - {9600,9323,9602 ,6281,6282,6280 ,0,0,0}, {9310,11025,11027 ,6283,6127,6174 ,0,0,0}, - {9308,11025,9310 ,6249,6127,6283 ,0,0,0}, {10898,10887,10899 ,6144,6138,6159 ,0,0,0}, - {10885,10936,10886 ,6136,6156,6137 ,0,0,0}, {11004,10883,10884 ,6137,6133,6135 ,0,0,0}, - {10883,11004,10935 ,6133,6137,6200 ,0,0,0}, {10883,9074,9150 ,6133,6134,6134 ,0,0,0}, - {9557,10940,9555 ,6144,6201,6209 ,0,0,0}, {9150,9074,9152 ,6134,6134,6196 ,0,0,0}, - {9292,9063,9291 ,6201,6200,6158 ,0,0,0}, {9056,9053,9283 ,6208,6187,6284 ,0,0,0}, - {9289,9291,9062 ,6125,6158,6204 ,0,0,0}, {11028,9552,9553 ,6191,6165,6179 ,0,0,0}, - {9550,11029,9527 ,6142,6172,6197 ,0,0,0}, {9274,9532,9276 ,6191,6186,6196 ,0,0,0}, - {9637,9532,9274 ,6192,6186,6191 ,0,0,0}, {9637,9273,9535 ,6192,6142,6285 ,0,0,0}, - {11030,9270,9267 ,6192,6228,6142 ,0,0,0}, {9096,9016,9018 ,6120,6122,6119 ,0,0,0}, - {9019,9094,9018 ,6171,6202,6119 ,0,0,0}, {11031,9547,9545 ,6150,6144,6150 ,0,0,0}, - {10891,9117,9115 ,6144,6150,6187 ,0,0,0}, {9123,9121,10929 ,6150,6188,6144 ,0,0,0}, - {9115,11032,10891 ,6187,6144,6144 ,0,0,0}, {9089,10927,11033 ,6165,6186,6286 ,0,0,0}, - {11032,9111,11034 ,6144,6192,6144 ,0,0,0}, {9109,9108,11034 ,6145,6145,6144 ,0,0,0}, - {11035,11036,10965 ,6143,6133,6208 ,0,0,0}, {10917,11037,9240 ,6120,6176,6146 ,0,0,0}, - {10960,9037,9040 ,6131,6137,6122 ,0,0,0}, {9043,9388,9387 ,6134,6135,6134 ,0,0,0}, - {10959,9230,9229 ,6196,6139,6201 ,0,0,0}, {10958,9236,9233 ,6197,6286,6165 ,0,0,0}, - {10968,9249,11038 ,6179,6202,6139 ,0,0,0}, {9252,11038,9251 ,6203,6139,6228 ,0,0,0}, - {9386,10971,10969 ,6137,6133,6200 ,0,0,0}, {10969,9383,9386 ,6200,6156,6137 ,0,0,0}, - {11039,11040,11041 ,6209,6207,6166 ,0,0,0}, {11042,9381,10970 ,6138,6137,6136 ,0,0,0}, - {11037,9242,9240 ,6176,6191,6146 ,0,0,0}, {11043,11044,11045 ,6186,6228,6287 ,0,0,0}, - {9236,10958,10917 ,6286,6197,6120 ,0,0,0}, {9236,10917,9239 ,6286,6120,6154 ,0,0,0}, - {9235,10958,9233 ,6165,6197,6165 ,0,0,0}, {9230,10959,9235 ,6139,6196,6165 ,0,0,0}, - {10950,9228,9246 ,6228,6203,6179 ,0,0,0}, {10950,10959,9229 ,6228,6196,6201 ,0,0,0}, - {9034,10965,9031 ,6200,6208,6204 ,0,0,0}, {10968,10950,9246 ,6179,6228,6179 ,0,0,0}, - {11046,11038,9252 ,6133,6139,6203 ,0,0,0}, {9251,11038,9249 ,6228,6139,6202 ,0,0,0}, - {9034,9036,10965 ,6200,6131,6208 ,0,0,0}, {10965,11047,9257 ,6208,6207,6242 ,0,0,0}, - {9042,9387,11048 ,6138,6134,6196 ,0,0,0}, {10965,9036,9037 ,6208,6131,6137 ,0,0,0}, - {10965,9028,9030 ,6208,6117,6126 ,0,0,0}, {9025,11011,10928 ,6208,6214,6119 ,0,0,0}, - {10965,11011,9028 ,6208,6214,6117 ,0,0,0}, {10893,9105,9076 ,6145,6120,6153 ,0,0,0}, - {11049,11050,9080 ,6201,6121,6288 ,0,0,0}, {9024,9025,10928 ,6187,6208,6119 ,0,0,0}, - {11051,9082,9084 ,6139,6192,6131 ,0,0,0}, {10918,9080,11050 ,6145,6288,6121 ,0,0,0}, - {9115,9114,11032 ,6187,6145,6144 ,0,0,0}, {9114,9111,11032 ,6145,6192,6144 ,0,0,0}, - {9108,9105,10893 ,6145,6120,6145 ,0,0,0}, {11050,11052,10918 ,6121,6289,6145 ,0,0,0}, - {11043,11052,11053 ,6186,6289,6191 ,0,0,0}, {11050,11053,11052 ,6121,6191,6289 ,0,0,0}, - {11043,11045,11037 ,6186,6287,6176 ,0,0,0}, {11043,11053,11044 ,6186,6191,6228 ,0,0,0}, - {9242,11037,11045 ,6191,6176,6287 ,0,0,0}, {11054,9045,9044 ,6202,6122,6116 ,0,0,0}, - {11055,11056,9525 ,6165,6191,6187 ,0,0,0}, {11057,9553,9555 ,6126,6179,6209 ,0,0,0}, - {11058,10933,9535 ,6154,6120,6285 ,0,0,0}, {9262,9051,11059 ,6201,6117,6120 ,0,0,0}, - {11060,11061,9264 ,6197,6201,6207 ,0,0,0}, {10880,11059,9050 ,6121,6120,6171 ,0,0,0}, - {9013,9101,9100 ,6116,6120,6201 ,0,0,0}, {10880,9050,9047 ,6121,6171,6119 ,0,0,0}, - {9053,9280,9283 ,6187,6202,6284 ,0,0,0}, {9283,9285,9056 ,6284,6140,6208 ,0,0,0}, - {9057,9285,9286 ,6117,6140,6127 ,0,0,0}, {9057,9286,9059 ,6117,6127,6126 ,0,0,0}, - {9059,9289,9062 ,6126,6125,6204 ,0,0,0}, {9063,9062,9291 ,6200,6204,6158 ,0,0,0}, - {9140,9142,9292 ,6133,6143,6201 ,0,0,0}, {9136,9132,10942 ,6118,6207,6119 ,0,0,0}, - {9138,10938,10939 ,6204,6133,6153 ,0,0,0}, {10941,9132,9133 ,6132,6207,6201 ,0,0,0}, - {10941,9133,10939 ,6132,6201,6153 ,0,0,0}, {10937,9136,10942 ,6203,6118,6119 ,0,0,0}, - {9131,10940,9557 ,6132,6201,6144 ,0,0,0}, {11057,9555,10940 ,6126,6209,6201 ,0,0,0}, - {11062,9552,11028 ,6242,6165,6191 ,0,0,0}, {11028,9553,11057 ,6191,6179,6126 ,0,0,0}, - {9550,11062,11063 ,6142,6242,6197 ,0,0,0}, {11062,9550,9552 ,6242,6142,6165 ,0,0,0}, - {11029,11055,9527 ,6172,6165,6197 ,0,0,0}, {11063,11029,9550 ,6197,6172,6142 ,0,0,0}, - {9525,11056,9526 ,6187,6191,6197 ,0,0,0}, {9527,11055,9525 ,6197,6165,6187 ,0,0,0}, - {9276,9526,11064 ,6196,6197,6202 ,0,0,0}, {9526,11056,11064 ,6197,6191,6202 ,0,0,0}, - {10924,10897,9307 ,6183,6158,6189 ,0,0,0}, {11027,11065,11066 ,6174,6118,6273 ,0,0,0}, - {9301,10882,9304 ,6290,6123,6236 ,0,0,0}, {10949,10932,9304 ,6214,6190,6236 ,0,0,0}, - {9301,9303,10882 ,6290,6198,6123 ,0,0,0}, {9193,10882,9188 ,6152,6123,6174 ,0,0,0}, - {9314,9317,9185 ,6124,6217,6291 ,0,0,0}, {9296,9184,10882 ,6235,6140,6123 ,0,0,0}, - {9314,9185,9184 ,6124,6291,6140 ,0,0,0}, {9314,9184,9296 ,6124,6140,6235 ,0,0,0}, - {9317,9179,9185 ,6217,6219,6291 ,0,0,0}, {9319,9599,9180 ,6218,6233,6229 ,0,0,0}, - {9320,9323,9600 ,6200,6282,6281 ,0,0,0}, {9320,9600,9599 ,6200,6281,6233 ,0,0,0}, - {9325,9326,9602 ,6269,6278,6280 ,0,0,0}, {9323,9325,9602 ,6282,6269,6280 ,0,0,0}, - {9594,9326,11067 ,6279,6278,6292 ,0,0,0}, {11067,10945,9594 ,6292,6211,6279 ,0,0,0}, - {11068,9596,10944 ,6293,6190,6157 ,0,0,0}, {9597,11068,11069 ,6147,6293,6266 ,0,0,0}, - {11068,9597,9596 ,6293,6147,6190 ,0,0,0}, {10890,11070,9590 ,6148,6273,6149 ,0,0,0}, - {11069,10890,9597 ,6266,6148,6147 ,0,0,0}, {10926,11071,9591 ,6185,6294,6168 ,0,0,0}, - {11070,10926,9590 ,6273,6185,6149 ,0,0,0}, {9582,9584,10907 ,6178,6167,6166 ,0,0,0}, - {11071,10908,9591 ,6294,6116,6168 ,0,0,0}, {10943,10922,9582 ,6210,6181,6178 ,0,0,0}, - {10947,10946,11065 ,6182,6212,6118 ,0,0,0}, {10943,10946,10922 ,6210,6212,6181 ,0,0,0}, - {11027,11066,9310 ,6174,6273,6283 ,0,0,0}, {11065,10946,11066 ,6118,6212,6273 ,0,0,0}, - {9332,11000,11008 ,6139,6199,6272 ,0,0,0}, {9363,11072,9392 ,6174,6295,6177 ,0,0,0}, - {10963,11022,11023 ,6171,6243,6276 ,0,0,0}, {9398,9396,11002 ,6165,6171,6191 ,0,0,0}, - {11072,9363,11073 ,6295,6174,6162 ,0,0,0}, {11008,9367,9332 ,6272,6181,6139 ,0,0,0}, - {9331,11000,9332 ,6167,6199,6139 ,0,0,0}, {9330,10977,9331 ,6247,6136,6167 ,0,0,0}, - {9348,10976,9330 ,6235,6190,6247 ,0,0,0}, {10975,10976,9351 ,6246,6190,6244 ,0,0,0}, - {10999,10975,9353 ,6267,6246,6245 ,0,0,0}, {9354,9357,10981 ,6268,6185,6249 ,0,0,0}, - {10981,10999,9354 ,6249,6267,6268 ,0,0,0}, {9360,10980,9359 ,6266,6152,6250 ,0,0,0}, - {9359,10981,9357 ,6250,6249,6185 ,0,0,0}, {9360,10998,10980 ,6266,6134,6152 ,0,0,0}, - {10978,10979,11009 ,6248,6170,6273 ,0,0,0}, {10966,11074,10925 ,6241,6296,6184 ,0,0,0}, - {10963,11023,10964 ,6171,6276,6152 ,0,0,0}, {10966,10967,11075 ,6241,6136,6200 ,0,0,0}, - {11075,10901,10900 ,6200,6161,6160 ,0,0,0}, {10900,10902,10964 ,6160,6162,6152 ,0,0,0}, - {11075,10967,10901 ,6200,6136,6161 ,0,0,0}, {11074,11019,11021 ,6296,6149,6214 ,0,0,0}, - {11021,10925,11074 ,6214,6184,6296 ,0,0,0}, {11006,11020,11019 ,6271,6275,6149 ,0,0,0}, - {11007,11014,11005 ,6169,6214,6213 ,0,0,0}, {11006,11005,11020 ,6271,6213,6275 ,0,0,0}, - {11015,11016,11013 ,6199,6274,6190 ,0,0,0}, {11007,11015,11014 ,6169,6199,6214 ,0,0,0}, - {11018,11017,11076 ,6183,6118,6144 ,0,0,0}, {11013,11016,11018 ,6190,6274,6183 ,0,0,0}, - {9344,11076,11017 ,6196,6144,6118 ,0,0,0}, {9019,9022,9093 ,6171,6117,6139 ,0,0,0}, - {10929,9125,9123 ,6144,6150,6150 ,0,0,0}, {10929,9120,10891 ,6144,6150,6144 ,0,0,0}, - {9090,9093,9022 ,6197,6139,6117 ,0,0,0}, {9024,10927,9090 ,6187,6186,6197 ,0,0,0}, - {10893,11034,9108 ,6145,6144,6145 ,0,0,0}, {9111,9109,11034 ,6192,6145,6144 ,0,0,0}, - {9078,9080,10918 ,6120,6288,6145 ,0,0,0}, {9076,9078,10894 ,6153,6120,6154 ,0,0,0}, - {9084,9089,11033 ,6131,6165,6286 ,0,0,0}, {9086,11077,11049 ,6144,6242,6201 ,0,0,0}, - {11049,9080,9086 ,6201,6288,6144 ,0,0,0}, {11033,11051,9084 ,6286,6139,6131 ,0,0,0}, - {9082,11051,11077 ,6192,6139,6242 ,0,0,0}, {9082,11077,9086 ,6192,6242,6144 ,0,0,0}, - {9089,9090,10927 ,6165,6197,6186 ,0,0,0}, {9022,9024,9090 ,6117,6187,6197 ,0,0,0}, - {9019,9093,9094 ,6171,6139,6202 ,0,0,0}, {9018,9094,9096 ,6119,6202,6120 ,0,0,0}, - {9101,9013,9099 ,6120,6116,6139 ,0,0,0}, {9016,9099,9013 ,6122,6139,6116 ,0,0,0}, - {9013,9100,9012 ,6116,6201,6117 ,0,0,0}, {9045,11054,10879 ,6122,6202,6120 ,0,0,0}, - {9012,9100,10878 ,6117,6201,6118 ,0,0,0}, {11054,9044,10878 ,6202,6116,6118 ,0,0,0}, - {11059,9051,9050 ,6120,6117,6171 ,0,0,0}, {11060,9263,11059 ,6197,6197,6120 ,0,0,0}, - {9262,11059,9263 ,6201,6120,6197 ,0,0,0}, {9270,11078,9273 ,6228,6145,6142 ,0,0,0}, - {9269,9264,11061 ,6143,6207,6201 ,0,0,0}, {9264,9263,11060 ,6207,6197,6197 ,0,0,0}, - {11030,9267,10888 ,6192,6142,6139 ,0,0,0}, {10888,9269,11061 ,6139,6143,6201 ,0,0,0}, - {9270,11030,11078 ,6228,6192,6145 ,0,0,0}, {11058,9535,9273 ,6154,6285,6142 ,0,0,0}, - {11058,9273,11078 ,6154,6142,6145 ,0,0,0}, {10933,9537,9535 ,6120,6154,6285 ,0,0,0}, - {9539,10934,11079 ,6144,6127,6187 ,0,0,0}, {10934,9539,9537 ,6127,6144,6154 ,0,0,0}, - {11079,10889,9539 ,6187,6145,6144 ,0,0,0}, {9540,11080,10931 ,6146,6145,6150 ,0,0,0}, - {10889,11080,9540 ,6145,6145,6146 ,0,0,0}, {9540,10931,9542 ,6146,6150,6144 ,0,0,0}, - {9545,9542,11081 ,6150,6144,6146 ,0,0,0}, {10930,11081,9542 ,6145,6146,6144 ,0,0,0}, - {9545,11082,11031 ,6150,6144,6150 ,0,0,0}, {9545,11081,11082 ,6150,6146,6144 ,0,0,0}, - {11083,9547,11084 ,6150,6144,6150 ,0,0,0}, {9547,11031,11084 ,6144,6150,6150 ,0,0,0}, - {9125,9547,11083 ,6150,6144,6150 ,0,0,0}, {11085,11086,11087 ,6131,6203,6207 ,0,0,0}, - {11042,11076,9380 ,6138,6144,6159 ,0,0,0}, {11010,9407,11001 ,6201,6156,6197 ,0,0,0}, - {11010,9410,9408 ,6201,6151,6155 ,0,0,0}, {11076,9344,9380 ,6144,6196,6159 ,0,0,0}, - {9365,11073,9363 ,6173,6162,6174 ,0,0,0}, {9392,11072,9395 ,6177,6295,6118 ,0,0,0}, - {9401,9398,11002 ,6158,6165,6191 ,0,0,0}, {11072,11003,9395 ,6295,6269,6118 ,0,0,0}, - {11073,9365,11008 ,6162,6173,6272 ,0,0,0}, {9367,9373,9337 ,6181,6182,6243 ,0,0,0}, - {9376,9377,9342 ,6127,6158,6297 ,0,0,0}, {9369,9335,9373 ,6118,6155,6182 ,0,0,0}, - {9337,9373,9335 ,6243,6182,6155 ,0,0,0}, {9369,9371,9338 ,6118,6174,6270 ,0,0,0}, - {9338,9335,9369 ,6270,6155,6118 ,0,0,0}, {9341,9376,9342 ,6270,6127,6297 ,0,0,0}, - {9344,9342,9377 ,6196,6297,6158 ,0,0,0}, {11042,9380,9381 ,6138,6159,6137 ,0,0,0}, - {10970,9381,9383 ,6136,6137,6156 ,0,0,0}, {11088,11089,11090 ,6205,6132,6116 ,0,0,0}, - {11089,11046,11091 ,6132,6133,6132 ,0,0,0}, {9037,10960,10965 ,6137,6131,6208 ,0,0,0}, - {10971,9388,9043 ,6133,6135,6134 ,0,0,0}, {9042,11048,10961 ,6138,6196,6132 ,0,0,0}, - {9042,9043,9387 ,6138,6134,6134 ,0,0,0}, {10961,9040,9042 ,6132,6122,6138 ,0,0,0}, - {10965,10960,11092 ,6208,6131,6157 ,0,0,0}, {11092,11035,10965 ,6157,6143,6208 ,0,0,0}, - {11091,9255,11093 ,6132,6172,6118 ,0,0,0}, {11094,11095,10965 ,6204,6201,6208 ,0,0,0}, - {10965,11096,11097 ,6208,6172,6214 ,0,0,0}, {10965,11095,11047 ,6208,6201,6207 ,0,0,0}, - {11096,10965,9258 ,6172,6208,6127 ,0,0,0}, {9257,11047,9255 ,6242,6207,6172 ,0,0,0}, - {11093,9255,11047 ,6118,6172,6207 ,0,0,0}, {11091,11046,9252 ,6132,6133,6203 ,0,0,0}, - {9252,9255,11091 ,6203,6172,6132 ,0,0,0}, {11089,11088,11046 ,6132,6205,6133 ,0,0,0}, - {11039,11090,11098 ,6209,6116,6121 ,0,0,0}, {11090,11039,11088 ,6116,6209,6205 ,0,0,0}, - {11098,11040,11039 ,6121,6207,6209 ,0,0,0}, {11041,11099,10972 ,6166,6209,6207 ,0,0,0}, - {11040,11099,11041 ,6207,6209,6166 ,0,0,0}, {11041,10972,10974 ,6166,6207,6208 ,0,0,0}, - {11087,10974,11100 ,6207,6208,6196 ,0,0,0}, {10973,11100,10974 ,6133,6196,6208 ,0,0,0}, - {11087,11101,11085 ,6207,6134,6131 ,0,0,0}, {11087,11100,11101 ,6207,6196,6134 ,0,0,0}, - {11102,11086,11103 ,6204,6203,6205 ,0,0,0}, {11086,11085,11103 ,6203,6131,6205 ,0,0,0}, - {9412,11086,11102 ,6134,6203,6204 ,0,0,0}, {10882,9193,9192 ,6123,6152,6167 ,0,0,0}, - {10882,11026,10948 ,6123,6275,6213 ,0,0,0}, {9285,9057,9056 ,6140,6117,6208 ,0,0,0}, - {10965,11036,11094 ,6208,6133,6204 ,0,0,0}, {10965,11097,11012 ,6208,6214,6133 ,0,0,0}, - {11104,9788,9787 ,6298,6299,6299 ,0,0,0}, {9793,11105,9794 ,6298,6298,6300 ,0,0,0}, - {11106,11107,9485 ,6301,6302,6302 ,0,0,0}, {9787,9784,11108 ,6299,6300,6303 ,0,0,0}, - {9482,11109,11110 ,6304,6304,6305 ,0,0,0}, {9778,11111,9781 ,6301,6299,6306 ,0,0,0}, - {9480,11112,11113 ,6305,6307,6308 ,0,0,0}, {11114,9775,9772 ,6298,6298,6309 ,0,0,0}, - {11115,9468,11116 ,6310,6311,6312 ,0,0,0}, {11117,11118,9474 ,6308,6313,6314 ,0,0,0}, - {9464,9888,11119 ,6315,6316,6317 ,0,0,0}, {11119,11120,9471 ,6317,6318,6319 ,0,0,0}, - {9459,9883,9885 ,6320,6321,6322 ,0,0,0}, {9843,9426,9841 ,6299,6303,6323 ,0,0,0}, - {9847,9849,9429 ,6324,6298,6306 ,0,0,0}, {9449,9873,9874 ,6325,6326,6327 ,0,0,0}, - {9850,9853,9437 ,6298,6328,6324 ,0,0,0}, {9865,9867,9446 ,6301,6329,6330 ,0,0,0}, - {9865,9520,9862 ,6301,6324,6331 ,0,0,0}, {9439,9859,9861 ,6332,6328,6333 ,0,0,0}, - {9859,9442,9856 ,6328,6334,6335 ,0,0,0}, {9868,9519,9867 ,6336,6298,6329 ,0,0,0}, - {9862,9447,9861 ,6331,6337,6333 ,0,0,0}, {9448,9871,9873 ,6338,6339,6326 ,0,0,0}, - {9868,9871,9451 ,6336,6339,6324 ,0,0,0}, {9853,9855,9433 ,6328,6328,6299 ,0,0,0}, - {9855,9856,9434 ,6328,6335,6340 ,0,0,0}, {9455,9877,9879 ,6341,6342,6343 ,0,0,0}, - {9457,9874,9877 ,6344,6327,6342 ,0,0,0}, {9879,9880,9453 ,6343,6345,6346 ,0,0,0}, - {9849,9850,9436 ,6298,6298,6347 ,0,0,0}, {9844,9847,9432 ,6348,6324,6316 ,0,0,0}, - {9461,9880,9883 ,6349,6345,6321 ,0,0,0}, {9460,9885,9886 ,6350,6322,6351 ,0,0,0}, - {9431,9844,9432 ,6324,6348,6316 ,0,0,0}, {9417,9838,9418 ,6300,6352,6353 ,0,0,0}, - {9466,9886,9888 ,6354,6351,6316 ,0,0,0}, {9414,9832,9415 ,6355,6299,6298 ,0,0,0}, - {9837,9423,9835 ,6299,6356,6357 ,0,0,0}, {11117,9476,11115 ,6308,6358,6310 ,0,0,0}, - {11120,11116,9467 ,6318,6312,6359 ,0,0,0}, {9770,9769,11121 ,6316,6306,6360 ,0,0,0}, - {11121,9769,9420 ,6360,6306,6299 ,0,0,0}, {11121,11122,9770 ,6360,6298,6316 ,0,0,0}, - {11118,11112,9472 ,6313,6307,6304 ,0,0,0}, {9479,11113,11123 ,6336,6308,6311 ,0,0,0}, - {9426,9843,9431 ,6303,6299,6324 ,0,0,0}, {11123,11109,9484 ,6311,6304,6314 ,0,0,0}, - {9778,9776,11124 ,6301,6300,6340 ,0,0,0}, {11125,9776,9775 ,6301,6300,6298 ,0,0,0}, - {11126,11106,9489 ,6301,6301,6333 ,0,0,0}, {9483,11110,11126 ,6361,6305,6301 ,0,0,0}, - {11127,9784,9782 ,6300,6300,6357 ,0,0,0}, {9781,11128,9782 ,6306,6355,6357 ,0,0,0}, - {11129,11130,9490 ,6353,6311,6301 ,0,0,0}, {9486,11107,11129 ,6362,6302,6353 ,0,0,0}, - {9790,9788,11131 ,6300,6299,6300 ,0,0,0}, {9491,11130,11132 ,6300,6311,6363 ,0,0,0}, - {9495,11132,11133 ,6301,6363,6353 ,0,0,0}, {9496,11133,11134 ,6300,6353,6328 ,0,0,0}, - {9790,11135,9793 ,6300,6300,6298 ,0,0,0}, {11136,9498,11134 ,6303,6352,6328 ,0,0,0}, - {11136,11137,9500 ,6303,6352,6340 ,0,0,0}, {11138,9796,9794 ,6299,6316,6300 ,0,0,0}, - {11139,9503,11137 ,6300,6340,6352 ,0,0,0}, {11140,9799,9796 ,6298,6364,6316 ,0,0,0}, - {9504,11139,11141 ,6316,6300,6306 ,0,0,0}, {11142,9800,9799 ,6364,6298,6364 ,0,0,0}, - {11141,11143,9506 ,6306,6340,6340 ,0,0,0}, {11144,9802,9800 ,6300,6300,6298 ,0,0,0}, - {11145,9509,11143 ,6323,6340,6340 ,0,0,0}, {11146,9805,9802 ,6298,6300,6300 ,0,0,0}, - {9511,11145,11147 ,6300,6323,6340 ,0,0,0}, {11148,9806,9805 ,6364,6300,6300 ,0,0,0}, - {11147,11149,9510 ,6340,6303,6303 ,0,0,0}, {11150,9808,9806 ,6300,6365,6300 ,0,0,0}, - {11151,9512,11149 ,6300,6300,6303 ,0,0,0}, {11152,9811,9808 ,6366,6300,6365 ,0,0,0}, - {9515,11151,11153 ,6300,6300,6316 ,0,0,0}, {11154,9812,9811 ,6367,6367,6300 ,0,0,0}, - {11153,11155,9516 ,6316,6300,6300 ,0,0,0}, {11156,9814,9812 ,6300,6300,6367 ,0,0,0}, - {11157,9516,11158 ,6301,6300,6300 ,0,0,0}, {11159,9817,9814 ,6368,6300,6300 ,0,0,0}, - {11160,11157,11161 ,6300,6301,6300 ,0,0,0}, {11162,9818,9817 ,6369,6367,6300 ,0,0,0}, - {11163,11160,11164 ,6316,6300,6300 ,0,0,0}, {9818,11165,9820 ,6367,6367,6300 ,0,0,0}, - {9823,9820,11166 ,6364,6300,6370 ,0,0,0}, {11167,9826,9824 ,6300,6316,6300 ,0,0,0}, - {11168,11163,11169 ,6300,6316,6316 ,0,0,0}, {11170,11171,11172 ,6300,6371,6300 ,0,0,0}, - {11173,11174,11175 ,6306,6300,6303 ,0,0,0}, {11176,11177,11178 ,6369,6300,6367 ,0,0,0}, - {11179,11180,11181 ,6301,6301,6300 ,0,0,0}, {11182,11183,11184 ,6300,6369,6367 ,0,0,0}, - {11185,11186,11187 ,6316,6316,6300 ,0,0,0}, {11188,11189,11190 ,6364,6300,6300 ,0,0,0}, - {11191,11182,11192 ,6364,6300,6316 ,0,0,0}, {11193,11194,11195 ,6300,6364,6316 ,0,0,0}, - {11190,11196,11195 ,6300,6316,6316 ,0,0,0}, {11197,11198,11199 ,6364,6372,6364 ,0,0,0}, - {11198,11191,11200 ,6372,6364,6300 ,0,0,0}, {11185,11194,11201 ,6316,6364,6367 ,0,0,0}, - {11202,11188,11197 ,6370,6364,6364 ,0,0,0}, {11178,11203,11204 ,6367,6367,6316 ,0,0,0}, - {11205,11183,11204 ,6316,6369,6316 ,0,0,0}, {11206,11179,11207 ,6306,6301,6303 ,0,0,0}, - {11207,11187,11208 ,6303,6300,6340 ,0,0,0}, {11209,11210,11172 ,6371,6300,6300 ,0,0,0}, - {11211,11176,11210 ,6300,6369,6300 ,0,0,0}, {11212,11173,11213 ,6300,6306,6300 ,0,0,0}, - {11212,11213,11181 ,6300,6300,6300 ,0,0,0}, {11214,11215,9826 ,6300,6300,6316 ,0,0,0}, - {11170,11215,11216 ,6300,6300,6316 ,0,0,0}, {11168,11217,11218 ,6300,6303,6301 ,0,0,0}, - {11174,11218,11219 ,6300,6301,6301 ,0,0,0}, {9824,9823,11220 ,6300,6364,6369 ,0,0,0}, - {9769,9768,9420 ,6306,6298,6299 ,0,0,0}, {9420,9768,9831 ,6299,6298,6340 ,0,0,0}, - {11122,11114,9772 ,6298,6298,6309 ,0,0,0}, {11122,9772,9770 ,6298,6309,6316 ,0,0,0}, - {11114,11125,9775 ,6298,6301,6298 ,0,0,0}, {11125,11124,9776 ,6301,6340,6300 ,0,0,0}, - {11124,11111,9778 ,6340,6299,6301 ,0,0,0}, {11111,11128,9781 ,6299,6355,6306 ,0,0,0}, - {11128,11127,9782 ,6355,6300,6357 ,0,0,0}, {11127,11108,9784 ,6300,6303,6300 ,0,0,0}, - {11108,11104,9787 ,6303,6298,6299 ,0,0,0}, {11104,11131,9788 ,6298,6300,6299 ,0,0,0}, - {11131,11135,9790 ,6300,6300,6300 ,0,0,0}, {11135,11105,9793 ,6300,6298,6298 ,0,0,0}, - {11105,11138,9794 ,6298,6299,6300 ,0,0,0}, {11138,11140,9796 ,6299,6298,6316 ,0,0,0}, - {11140,11142,9799 ,6298,6364,6364 ,0,0,0}, {11142,11144,9800 ,6364,6300,6298 ,0,0,0}, - {11144,11146,9802 ,6300,6298,6300 ,0,0,0}, {11146,11148,9805 ,6298,6364,6300 ,0,0,0}, - {11148,11150,9806 ,6364,6300,6300 ,0,0,0}, {11150,11152,9808 ,6300,6366,6365 ,0,0,0}, - {11152,11154,9811 ,6366,6367,6300 ,0,0,0}, {11154,11156,9812 ,6367,6300,6367 ,0,0,0}, - {11156,11159,9814 ,6300,6368,6300 ,0,0,0}, {11159,11162,9817 ,6368,6369,6300 ,0,0,0}, - {11162,11165,9818 ,6369,6367,6367 ,0,0,0}, {11165,11166,9820 ,6367,6370,6300 ,0,0,0}, - {11166,11220,9823 ,6370,6369,6364 ,0,0,0}, {11220,11167,9824 ,6369,6300,6300 ,0,0,0}, - {11167,11214,9826 ,6300,6300,6316 ,0,0,0}, {11214,11216,11215 ,6300,6316,6300 ,0,0,0}, - {11216,11171,11170 ,6316,6371,6300 ,0,0,0}, {11171,11209,11172 ,6371,6371,6300 ,0,0,0}, - {11209,11211,11210 ,6371,6300,6300 ,0,0,0}, {11211,11177,11176 ,6300,6300,6369 ,0,0,0}, - {11177,11203,11178 ,6300,6367,6367 ,0,0,0}, {11203,11205,11204 ,6367,6316,6316 ,0,0,0}, - {11205,11184,11183 ,6316,6367,6369 ,0,0,0}, {11184,11192,11182 ,6367,6316,6300 ,0,0,0}, - {11192,11200,11191 ,6316,6300,6364 ,0,0,0}, {11200,11199,11198 ,6300,6364,6372 ,0,0,0}, - {11199,11202,11197 ,6364,6370,6364 ,0,0,0}, {11202,11189,11188 ,6370,6300,6364 ,0,0,0}, - {11189,11196,11190 ,6300,6316,6300 ,0,0,0}, {11196,11193,11195 ,6316,6300,6316 ,0,0,0}, - {11193,11201,11194 ,6300,6367,6364 ,0,0,0}, {11201,11186,11185 ,6367,6316,6316 ,0,0,0}, - {11186,11208,11187 ,6316,6340,6300 ,0,0,0}, {11208,11206,11207 ,6340,6306,6303 ,0,0,0}, - {11206,11180,11179 ,6306,6301,6301 ,0,0,0}, {11180,11212,11181 ,6301,6300,6300 ,0,0,0}, - {11173,11175,11213 ,6306,6303,6300 ,0,0,0}, {11174,11219,11175 ,6300,6301,6303 ,0,0,0}, - {11218,11217,11219 ,6301,6303,6301 ,0,0,0}, {11168,11169,11217 ,6300,6316,6303 ,0,0,0}, - {11163,11164,11169 ,6316,6300,6316 ,0,0,0}, {11160,11161,11164 ,6300,6300,6300 ,0,0,0}, - {11157,11158,11161 ,6301,6300,6300 ,0,0,0}, {9516,11155,11158 ,6300,6300,6300 ,0,0,0}, - {9516,9515,11153 ,6300,6300,6316 ,0,0,0}, {9515,9512,11151 ,6300,6300,6300 ,0,0,0}, - {9512,9510,11149 ,6300,6303,6303 ,0,0,0}, {9510,9511,11147 ,6303,6300,6340 ,0,0,0}, - {9511,9509,11145 ,6300,6340,6323 ,0,0,0}, {9509,9506,11143 ,6340,6340,6340 ,0,0,0}, - {9506,9504,11141 ,6340,6316,6306 ,0,0,0}, {9504,9503,11139 ,6316,6340,6300 ,0,0,0}, - {9503,9500,11137 ,6340,6340,6352 ,0,0,0}, {9500,9498,11136 ,6340,6352,6303 ,0,0,0}, - {9498,9496,11134 ,6352,6300,6328 ,0,0,0}, {9496,9495,11133 ,6300,6301,6353 ,0,0,0}, - {9495,9491,11132 ,6301,6300,6363 ,0,0,0}, {9491,9490,11130 ,6300,6301,6311 ,0,0,0}, - {9490,9486,11129 ,6301,6362,6353 ,0,0,0}, {9486,9485,11107 ,6362,6302,6302 ,0,0,0}, - {9485,9489,11106 ,6302,6333,6301 ,0,0,0}, {9489,9483,11126 ,6333,6361,6301 ,0,0,0}, - {9483,9482,11110 ,6361,6304,6305 ,0,0,0}, {9482,9484,11109 ,6304,6314,6304 ,0,0,0}, - {9484,9479,11123 ,6314,6336,6311 ,0,0,0}, {9479,9480,11113 ,6336,6305,6308 ,0,0,0}, - {9480,9472,11112 ,6305,6304,6307 ,0,0,0}, {9472,9474,11118 ,6304,6314,6313 ,0,0,0}, - {9474,9476,11117 ,6314,6358,6308 ,0,0,0}, {9476,9468,11115 ,6358,6311,6310 ,0,0,0}, - {9468,9467,11116 ,6311,6359,6312 ,0,0,0}, {9467,9471,11120 ,6359,6319,6318 ,0,0,0}, - {9471,9464,11119 ,6319,6315,6317 ,0,0,0}, {9464,9466,9888 ,6315,6354,6316 ,0,0,0}, - {9466,9460,9886 ,6354,6350,6351 ,0,0,0}, {9460,9459,9885 ,6350,6320,6322 ,0,0,0}, - {9459,9461,9883 ,6320,6349,6321 ,0,0,0}, {9461,9453,9880 ,6349,6346,6345 ,0,0,0}, - {9453,9455,9879 ,6346,6341,6343 ,0,0,0}, {9455,9457,9877 ,6341,6344,6342 ,0,0,0}, - {9457,9449,9874 ,6344,6325,6327 ,0,0,0}, {9449,9448,9873 ,6325,6338,6326 ,0,0,0}, - {9448,9451,9871 ,6338,6324,6339 ,0,0,0}, {9451,9519,9868 ,6324,6298,6336 ,0,0,0}, - {9519,9446,9867 ,6298,6330,6329 ,0,0,0}, {9446,9520,9865 ,6330,6324,6301 ,0,0,0}, - {9520,9447,9862 ,6324,6337,6331 ,0,0,0}, {9447,9439,9861 ,6337,6332,6333 ,0,0,0}, - {9439,9442,9859 ,6332,6334,6328 ,0,0,0}, {9442,9434,9856 ,6334,6340,6335 ,0,0,0}, - {9434,9433,9855 ,6340,6299,6328 ,0,0,0}, {9433,9437,9853 ,6299,6324,6328 ,0,0,0}, - {9437,9436,9850 ,6324,6347,6298 ,0,0,0}, {9436,9429,9849 ,6347,6306,6298 ,0,0,0}, - {9429,9432,9847 ,6306,6316,6324 ,0,0,0}, {9431,9843,9844 ,6324,6299,6348 ,0,0,0}, - {9418,9841,9426 ,6353,6323,6303 ,0,0,0}, {9417,9837,9838 ,6300,6299,6352 ,0,0,0}, - {9418,9838,9841 ,6353,6352,6323 ,0,0,0}, {9423,9415,9835 ,6356,6298,6357 ,0,0,0}, - {9417,9423,9837 ,6300,6356,6299 ,0,0,0}, {9832,9414,9831 ,6299,6355,6340 ,0,0,0}, - {9835,9415,9832 ,6357,6298,6299 ,0,0,0}, {9420,9831,9414 ,6299,6340,6355 ,0,0,0}, - {11215,9828,9826 ,6373,6374,6375 ,0,0,0}, {11221,11222,11210 ,6376,6377,6378 ,0,0,0}, - {11172,11223,11170 ,6379,6380,6381 ,0,0,0}, {11204,11183,11224 ,6382,6383,6384 ,0,0,0}, - {11176,11178,11225 ,6385,6386,6387 ,0,0,0}, {11226,11227,11198 ,6388,6389,6390 ,0,0,0}, - {11228,11229,11182 ,6391,6392,6393 ,0,0,0}, {11190,11195,11230 ,6394,6395,6396 ,0,0,0}, - {11197,11188,11231 ,6397,6398,6399 ,0,0,0}, {11232,11233,11187 ,6400,6401,6402 ,0,0,0}, - {11234,11235,11194 ,6403,6404,6405 ,0,0,0}, {11181,11213,11236 ,6406,6407,6408 ,0,0,0}, - {11207,11179,11237 ,6409,6410,6411 ,0,0,0}, {11238,11239,11217 ,6412,6413,6414 ,0,0,0}, - {11240,11241,11175 ,6415,6416,6417 ,0,0,0}, {11242,11161,11243 ,6418,6419,6420 ,0,0,0}, - {11169,11164,11244 ,6421,6422,6423 ,0,0,0}, {11153,11245,11246 ,6424,6425,6426 ,0,0,0}, - {11155,11247,11158 ,6427,6428,6429 ,0,0,0}, {11248,11249,11147 ,6430,6431,6432 ,0,0,0}, - {11250,11151,11149 ,6433,6434,6435 ,0,0,0}, {11251,11143,11141 ,6436,6437,6438 ,0,0,0}, - {11145,11143,11252 ,6439,6437,6440 ,0,0,0}, {11253,11137,11254 ,6441,6442,6443 ,0,0,0}, - {11139,11253,11255 ,6444,6441,6445 ,0,0,0}, {11134,11133,11256 ,6446,6447,6448 ,0,0,0}, - {11136,11257,11254 ,6449,6450,6443 ,0,0,0}, {11132,11130,11258 ,6451,6452,6453 ,0,0,0}, - {11132,11259,11133 ,6451,6454,6447 ,0,0,0}, {11129,11107,11260 ,6455,6456,6457 ,0,0,0}, - {11129,11261,11130 ,6455,6458,6452 ,0,0,0}, {11262,11107,11106 ,6459,6456,6460 ,0,0,0}, - {11107,11262,11260 ,6456,6459,6457 ,0,0,0}, {11126,11263,11106 ,6461,6462,6460 ,0,0,0}, - {11262,11106,11263 ,6459,6460,6462 ,0,0,0}, {11126,11110,11264 ,6461,6463,6464 ,0,0,0}, - {11264,11263,11126 ,6464,6462,6461 ,0,0,0}, {11265,11110,11109 ,6465,6463,6466 ,0,0,0}, - {11110,11265,11264 ,6463,6465,6464 ,0,0,0}, {11123,11266,11109 ,6467,6468,6466 ,0,0,0}, - {11265,11109,11266 ,6465,6466,6468 ,0,0,0}, {11123,11113,11267 ,6467,6469,6470 ,0,0,0}, - {11267,11266,11123 ,6470,6468,6467 ,0,0,0}, {11268,11113,11112 ,6471,6469,6472 ,0,0,0}, - {11113,11268,11267 ,6469,6471,6470 ,0,0,0}, {11118,11269,11112 ,6473,6474,6472 ,0,0,0}, - {11268,11112,11269 ,6471,6472,6474 ,0,0,0}, {11118,11117,11270 ,6473,6475,6476 ,0,0,0}, - {11270,11269,11118 ,6476,6474,6473 ,0,0,0}, {11271,11117,11115 ,6477,6475,6478 ,0,0,0}, - {11117,11271,11270 ,6475,6477,6476 ,0,0,0}, {11116,11272,11115 ,6479,6480,6478 ,0,0,0}, - {11271,11115,11272 ,6477,6478,6480 ,0,0,0}, {11116,11120,11273 ,6479,6481,6482 ,0,0,0}, - {11273,11272,11116 ,6482,6480,6479 ,0,0,0}, {11274,11120,11119 ,6483,6481,6484 ,0,0,0}, - {11120,11274,11273 ,6481,6483,6482 ,0,0,0}, {9888,11275,11119 ,6485,6486,6484 ,0,0,0}, - {11274,11119,11275 ,6483,6484,6486 ,0,0,0}, {9887,11275,9888 ,6487,6486,6485 ,0,0,0}, - {11261,11258,11130 ,6458,6453,6452 ,0,0,0}, {11129,11260,11261 ,6455,6457,6458 ,0,0,0}, - {11259,11256,11133 ,6454,6448,6447 ,0,0,0}, {11132,11258,11259 ,6451,6453,6454 ,0,0,0}, - {11136,11134,11257 ,6449,6446,6450 ,0,0,0}, {11134,11256,11257 ,6446,6448,6450 ,0,0,0}, - {11137,11253,11139 ,6442,6441,6444 ,0,0,0}, {11137,11136,11254 ,6442,6449,6443 ,0,0,0}, - {11251,11141,11255 ,6436,6438,6445 ,0,0,0}, {11141,11139,11255 ,6438,6444,6445 ,0,0,0}, - {11145,11252,11248 ,6439,6440,6430 ,0,0,0}, {11252,11143,11251 ,6440,6437,6436 ,0,0,0}, - {11249,11149,11147 ,6431,6435,6432 ,0,0,0}, {11248,11147,11145 ,6430,6432,6439 ,0,0,0}, - {11250,11245,11151 ,6433,6425,6434 ,0,0,0}, {11249,11250,11149 ,6431,6433,6435 ,0,0,0}, - {11153,11246,11155 ,6424,6426,6427 ,0,0,0}, {11151,11245,11153 ,6434,6425,6424 ,0,0,0}, - {11158,11247,11243 ,6429,6428,6420 ,0,0,0}, {11155,11246,11247 ,6427,6426,6428 ,0,0,0}, - {11164,11161,11242 ,6422,6419,6418 ,0,0,0}, {11161,11158,11243 ,6419,6429,6420 ,0,0,0}, - {11238,11169,11244 ,6412,6421,6423 ,0,0,0}, {11244,11164,11242 ,6423,6422,6418 ,0,0,0}, - {11239,11219,11217 ,6413,6488,6414 ,0,0,0}, {11238,11217,11169 ,6412,6414,6421 ,0,0,0}, - {11175,11219,11240 ,6417,6488,6415 ,0,0,0}, {11239,11240,11219 ,6413,6415,6488 ,0,0,0}, - {11213,11241,11236 ,6407,6416,6408 ,0,0,0}, {11175,11241,11213 ,6417,6416,6407 ,0,0,0}, - {11179,11181,11276 ,6410,6406,6489 ,0,0,0}, {11181,11236,11276 ,6406,6408,6489 ,0,0,0}, - {11232,11207,11237 ,6400,6409,6411 ,0,0,0}, {11237,11179,11276 ,6411,6410,6489 ,0,0,0}, - {11233,11185,11187 ,6401,6490,6402 ,0,0,0}, {11232,11187,11207 ,6400,6402,6409 ,0,0,0}, - {11194,11185,11234 ,6405,6490,6403 ,0,0,0}, {11233,11234,11185 ,6401,6403,6490 ,0,0,0}, - {11195,11235,11230 ,6395,6404,6396 ,0,0,0}, {11194,11235,11195 ,6405,6404,6395 ,0,0,0}, - {11188,11190,11277 ,6398,6394,6491 ,0,0,0}, {11190,11230,11277 ,6394,6396,6491 ,0,0,0}, - {11226,11197,11231 ,6388,6397,6399 ,0,0,0}, {11231,11188,11277 ,6399,6398,6491 ,0,0,0}, - {11227,11191,11198 ,6389,6492,6390 ,0,0,0}, {11226,11198,11197 ,6388,6390,6397 ,0,0,0}, - {11182,11191,11228 ,6393,6492,6391 ,0,0,0}, {11227,11228,11191 ,6389,6391,6492 ,0,0,0}, - {11183,11229,11224 ,6383,6392,6384 ,0,0,0}, {11182,11229,11183 ,6393,6392,6383 ,0,0,0}, - {11178,11204,11278 ,6386,6382,6493 ,0,0,0}, {11204,11224,11278 ,6382,6384,6493 ,0,0,0}, - {11221,11176,11225 ,6376,6385,6387 ,0,0,0}, {11225,11178,11278 ,6387,6386,6493 ,0,0,0}, - {11222,11172,11210 ,6377,6379,6378 ,0,0,0}, {11221,11210,11176 ,6376,6378,6385 ,0,0,0}, - {11223,11279,11170 ,6380,6494,6381 ,0,0,0}, {11222,11223,11172 ,6377,6380,6379 ,0,0,0}, - {9828,11215,11279 ,6374,6373,6494 ,0,0,0}, {11170,11279,11215 ,6381,6494,6373 ,0,0,0}, - {9839,9725,9840 ,6495,6495,6496 ,0,0,0}, {9846,9845,9731 ,6497,6496,6496 ,0,0,0}, - {11234,11233,11280 ,6498,6499,6500 ,0,0,0}, {9722,9839,9836 ,6501,6495,6501 ,0,0,0}, - {11231,11277,11281 ,6502,6503,6503 ,0,0,0}, {9833,9716,9719 ,6496,6504,6501 ,0,0,0}, - {11282,11224,11229 ,6498,6505,6506 ,0,0,0}, {9658,9767,9771 ,6507,6495,6495 ,0,0,0}, - {9668,9666,9780 ,6508,6509,6504 ,0,0,0}, {11283,11222,11221 ,6510,6511,6512 ,0,0,0}, - {9827,9710,9708 ,6513,6500,6514 ,0,0,0}, {9828,9710,9827 ,6515,6500,6513 ,0,0,0}, - {9822,9825,9709 ,6516,6517,6518 ,0,0,0}, {9789,9791,9674 ,6519,6520,6497 ,0,0,0}, - {9795,9797,9680 ,6521,6522,6523 ,0,0,0}, {9819,9702,9701 ,6524,6525,6526 ,0,0,0}, - {9798,9684,9683 ,6527,6500,6498 ,0,0,0}, {9815,9696,9813 ,6528,6522,6529 ,0,0,0}, - {9813,9695,9810 ,6529,6530,6531 ,0,0,0}, {9690,9807,9692 ,6532,6533,6502 ,0,0,0}, - {9804,9690,9689 ,6534,6532,6495 ,0,0,0}, {9816,9698,9815 ,6535,6502,6528 ,0,0,0}, - {9809,9810,9692 ,6533,6531,6502 ,0,0,0}, {9819,9701,9816 ,6524,6526,6535 ,0,0,0}, - {9698,9816,9701 ,6502,6535,6526 ,0,0,0}, {9801,9686,9684 ,6503,6514,6500 ,0,0,0}, - {9689,9686,9803 ,6495,6514,6530 ,0,0,0}, {9707,9702,9821 ,6536,6525,6537 ,0,0,0}, - {9702,9819,9821 ,6525,6524,6537 ,0,0,0}, {9707,9821,9822 ,6536,6537,6516 ,0,0,0}, - {9798,9683,9797 ,6527,6498,6522 ,0,0,0}, {9795,9678,9792 ,6521,6501,6509 ,0,0,0}, - {9822,9709,9707 ,6516,6518,6536 ,0,0,0}, {9709,9825,9708 ,6518,6517,6514 ,0,0,0}, - {9792,9677,9791 ,6509,6500,6520 ,0,0,0}, {9672,9786,9674 ,6508,6509,6497 ,0,0,0}, - {9827,9708,9825 ,6513,6514,6517 ,0,0,0}, {9668,9783,9671 ,6508,6508,6495 ,0,0,0}, - {9671,9785,9672 ,6495,6530,6508 ,0,0,0}, {11284,11223,11285 ,6538,6539,6540 ,0,0,0}, - {11279,9710,9828 ,6541,6500,6515 ,0,0,0}, {9779,9665,9777 ,6495,6496,6542 ,0,0,0}, - {9666,9665,9779 ,6509,6496,6495 ,0,0,0}, {9773,9774,9660 ,6542,6504,6507 ,0,0,0}, - {11278,11224,11286 ,6543,6505,6500 ,0,0,0}, {11287,11228,11288 ,6503,6533,6500 ,0,0,0}, - {9771,9773,9659 ,6495,6542,6495 ,0,0,0}, {11289,11288,11226 ,6508,6500,6538 ,0,0,0}, - {9716,9830,9715 ,6504,6542,6501 ,0,0,0}, {9658,9715,9829 ,6507,6501,6495 ,0,0,0}, - {11235,11290,11291 ,6527,6530,6498 ,0,0,0}, {11277,11230,11292 ,6503,6527,6499 ,0,0,0}, - {9722,9836,9721 ,6501,6501,6544 ,0,0,0}, {9834,9719,9721 ,6504,6501,6544 ,0,0,0}, - {11237,11293,11294 ,6508,6530,6544 ,0,0,0}, {11295,11232,11294 ,6498,6500,6544 ,0,0,0}, - {9727,9842,9840 ,6495,6495,6496 ,0,0,0}, {11276,11236,11293 ,6523,6504,6530 ,0,0,0}, - {11241,11296,11236 ,6500,6504,6504 ,0,0,0}, {11241,11240,11297 ,6500,6522,6500 ,0,0,0}, - {9845,9842,9728 ,6496,6495,6496 ,0,0,0}, {11298,11240,11239 ,6515,6522,6504 ,0,0,0}, - {11238,11299,11239 ,6508,6500,6504 ,0,0,0}, {9848,9731,9733 ,6495,6496,6508 ,0,0,0}, - {11299,11238,11300 ,6500,6508,6498 ,0,0,0}, {9851,9733,9734 ,6504,6508,6507 ,0,0,0}, - {11301,11300,11244 ,6515,6498,6545 ,0,0,0}, {9852,9734,9737 ,6507,6507,6495 ,0,0,0}, - {11302,11301,11242 ,6498,6515,6504 ,0,0,0}, {9854,9737,9739 ,6504,6495,6495 ,0,0,0}, - {11303,11302,11243 ,6504,6498,6504 ,0,0,0}, {9739,9740,9857 ,6495,6504,6504 ,0,0,0}, - {11304,11303,11247 ,6504,6504,6498 ,0,0,0}, {9858,9857,9740 ,6504,6504,6504 ,0,0,0}, - {11304,11246,11245 ,6504,6504,6504 ,0,0,0}, {9860,9858,9743 ,6546,6504,6504 ,0,0,0}, - {11305,11245,11250 ,6508,6504,6504 ,0,0,0}, {9863,9860,9745 ,6507,6546,6504 ,0,0,0}, - {11306,11250,11249 ,6508,6504,6508 ,0,0,0}, {9864,9863,9746 ,6547,6507,6548 ,0,0,0}, - {11307,11249,11248 ,6498,6508,6498 ,0,0,0}, {9866,9864,9749 ,6546,6547,6548 ,0,0,0}, - {11308,11248,11252 ,6504,6498,6498 ,0,0,0}, {9751,9869,9749 ,6549,6547,6548 ,0,0,0}, - {11252,11309,11308 ,6498,6504,6504 ,0,0,0}, {9870,9751,9752 ,6549,6549,6550 ,0,0,0}, - {11309,11251,11310 ,6504,6504,6498 ,0,0,0}, {9752,9755,9872 ,6550,6549,6504 ,0,0,0}, - {9875,9755,9757 ,6549,6549,6545 ,0,0,0}, {9878,9876,9759 ,6549,6504,6504 ,0,0,0}, - {11310,11255,11311 ,6498,6504,6504 ,0,0,0}, {9884,9882,9764 ,6551,6504,6515 ,0,0,0}, - {11256,11312,11257 ,6504,6508,6515 ,0,0,0}, {11313,11274,11314 ,6504,6545,6515 ,0,0,0}, - {11315,11258,11261 ,6508,6552,6504 ,0,0,0}, {11271,11316,11317 ,6553,6504,6554 ,0,0,0}, - {11318,11319,11262 ,6555,6504,6515 ,0,0,0}, {11266,11267,11320 ,6504,6504,6504 ,0,0,0}, - {11271,11317,11270 ,6553,6554,6504 ,0,0,0}, {11264,11321,11322 ,6504,6504,6515 ,0,0,0}, - {11320,11321,11265 ,6504,6504,6515 ,0,0,0}, {11269,11323,11268 ,6548,6504,6504 ,0,0,0}, - {11269,11270,11324 ,6548,6504,6549 ,0,0,0}, {11318,11263,11322 ,6555,6504,6515 ,0,0,0}, - {11325,11267,11268 ,6504,6504,6504 ,0,0,0}, {11326,11273,11313 ,6504,6548,6504 ,0,0,0}, - {11316,11272,11326 ,6504,6548,6504 ,0,0,0}, {11260,11327,11261 ,6504,6544,6504 ,0,0,0}, - {11260,11319,11327 ,6504,6504,6544 ,0,0,0}, {9887,9884,9766 ,6515,6551,6554 ,0,0,0}, - {9766,11314,11275 ,6554,6515,6545 ,0,0,0}, {11259,11328,11256 ,6515,6504,6504 ,0,0,0}, - {11329,11259,11258 ,6508,6515,6552 ,0,0,0}, {9881,9878,9758 ,6504,6549,6549 ,0,0,0}, - {9761,9882,9881 ,6545,6504,6504 ,0,0,0}, {11253,11330,11311 ,6508,6498,6504 ,0,0,0}, - {11312,11330,11254 ,6508,6498,6498 ,0,0,0}, {9876,9757,9759 ,6504,6545,6504 ,0,0,0}, - {9774,9777,9662 ,6504,6542,6504 ,0,0,0}, {11331,11225,11332 ,6556,6557,6558 ,0,0,0}, - {11280,11233,11295 ,6500,6499,6498 ,0,0,0}, {9696,9815,9698 ,6522,6528,6502 ,0,0,0}, - {9695,9813,9696 ,6530,6529,6522 ,0,0,0}, {9692,9810,9695 ,6502,6531,6530 ,0,0,0}, - {9692,9807,9809 ,6502,6533,6533 ,0,0,0}, {9690,9804,9807 ,6532,6534,6533 ,0,0,0}, - {9689,9803,9804 ,6495,6530,6534 ,0,0,0}, {9686,9801,9803 ,6514,6503,6530 ,0,0,0}, - {9684,9798,9801 ,6500,6527,6503 ,0,0,0}, {9680,9797,9683 ,6523,6522,6498 ,0,0,0}, - {9678,9795,9680 ,6501,6521,6523 ,0,0,0}, {9677,9792,9678 ,6500,6509,6501 ,0,0,0}, - {9674,9791,9677 ,6497,6520,6500 ,0,0,0}, {9674,9786,9789 ,6497,6509,6519 ,0,0,0}, - {9672,9785,9786 ,6508,6530,6509 ,0,0,0}, {9671,9783,9785 ,6495,6508,6530 ,0,0,0}, - {9668,9780,9783 ,6508,6504,6508 ,0,0,0}, {9666,9779,9780 ,6509,6495,6504 ,0,0,0}, - {9662,9777,9665 ,6504,6542,6496 ,0,0,0}, {9660,9774,9662 ,6507,6504,6504 ,0,0,0}, - {9659,9773,9660 ,6495,6542,6507 ,0,0,0}, {9658,9771,9659 ,6507,6495,6495 ,0,0,0}, - {9658,9829,9767 ,6507,6495,6495 ,0,0,0}, {9715,9830,9829 ,6501,6542,6495 ,0,0,0}, - {9716,9833,9830 ,6504,6496,6542 ,0,0,0}, {9719,9834,9833 ,6501,6504,6496 ,0,0,0}, - {9721,9836,9834 ,6544,6501,6504 ,0,0,0}, {9725,9839,9722 ,6495,6495,6501 ,0,0,0}, - {9727,9840,9725 ,6495,6496,6495 ,0,0,0}, {9728,9842,9727 ,6496,6495,6495 ,0,0,0}, - {9731,9845,9728 ,6496,6496,6496 ,0,0,0}, {9731,9848,9846 ,6496,6495,6497 ,0,0,0}, - {9733,9851,9848 ,6508,6504,6495 ,0,0,0}, {9734,9852,9851 ,6507,6507,6504 ,0,0,0}, - {9737,9854,9852 ,6495,6504,6507 ,0,0,0}, {9739,9857,9854 ,6495,6504,6504 ,0,0,0}, - {9743,9858,9740 ,6504,6504,6504 ,0,0,0}, {9745,9860,9743 ,6504,6546,6504 ,0,0,0}, - {9746,9863,9745 ,6548,6507,6504 ,0,0,0}, {9749,9864,9746 ,6548,6547,6548 ,0,0,0}, - {9749,9869,9866 ,6548,6547,6546 ,0,0,0}, {9751,9870,9869 ,6549,6549,6547 ,0,0,0}, - {9752,9872,9870 ,6550,6504,6549 ,0,0,0}, {9755,9875,9872 ,6549,6549,6504 ,0,0,0}, - {9757,9876,9875 ,6545,6504,6549 ,0,0,0}, {9758,9878,9759 ,6549,6549,6504 ,0,0,0}, - {9761,9881,9758 ,6545,6504,6549 ,0,0,0}, {9764,9882,9761 ,6515,6504,6545 ,0,0,0}, - {9766,9884,9764 ,6554,6551,6515 ,0,0,0}, {9766,11275,9887 ,6554,6545,6515 ,0,0,0}, - {11314,11274,11275 ,6515,6545,6545 ,0,0,0}, {11313,11273,11274 ,6504,6548,6545 ,0,0,0}, - {11326,11272,11273 ,6504,6548,6548 ,0,0,0}, {11316,11271,11272 ,6504,6553,6548 ,0,0,0}, - {11324,11270,11317 ,6549,6504,6554 ,0,0,0}, {11323,11269,11324 ,6504,6548,6549 ,0,0,0}, - {11325,11268,11323 ,6504,6504,6504 ,0,0,0}, {11320,11267,11325 ,6504,6504,6504 ,0,0,0}, - {11320,11265,11266 ,6504,6515,6504 ,0,0,0}, {11321,11264,11265 ,6504,6504,6515 ,0,0,0}, - {11322,11263,11264 ,6515,6504,6504 ,0,0,0}, {11318,11262,11263 ,6555,6515,6504 ,0,0,0}, - {11319,11260,11262 ,6504,6504,6515 ,0,0,0}, {11315,11261,11327 ,6508,6504,6544 ,0,0,0}, - {11329,11258,11315 ,6508,6552,6508 ,0,0,0}, {11328,11259,11329 ,6504,6515,6508 ,0,0,0}, - {11312,11256,11328 ,6508,6504,6504 ,0,0,0}, {11312,11254,11257 ,6508,6498,6515 ,0,0,0}, - {11330,11253,11254 ,6498,6508,6498 ,0,0,0}, {11311,11255,11253 ,6504,6504,6508 ,0,0,0}, - {11310,11251,11255 ,6498,6504,6504 ,0,0,0}, {11309,11252,11251 ,6504,6498,6504 ,0,0,0}, - {11307,11248,11308 ,6498,6498,6504 ,0,0,0}, {11306,11249,11307 ,6508,6508,6498 ,0,0,0}, - {11305,11250,11306 ,6508,6504,6508 ,0,0,0}, {11304,11245,11305 ,6504,6504,6508 ,0,0,0}, - {11304,11247,11246 ,6504,6498,6504 ,0,0,0}, {11303,11243,11247 ,6504,6504,6498 ,0,0,0}, - {11302,11242,11243 ,6498,6504,6504 ,0,0,0}, {11301,11244,11242 ,6515,6545,6504 ,0,0,0}, - {11300,11238,11244 ,6498,6508,6545 ,0,0,0}, {11298,11239,11299 ,6515,6504,6500 ,0,0,0}, - {11297,11240,11298 ,6500,6522,6515 ,0,0,0}, {11296,11241,11297 ,6504,6500,6500 ,0,0,0}, - {11293,11236,11296 ,6530,6504,6504 ,0,0,0}, {11293,11237,11276 ,6530,6508,6523 ,0,0,0}, - {11294,11232,11237 ,6544,6500,6508 ,0,0,0}, {11295,11233,11232 ,6498,6499,6500 ,0,0,0}, - {11290,11234,11280 ,6530,6498,6500 ,0,0,0}, {11291,11230,11235 ,6498,6527,6527 ,0,0,0}, - {11290,11235,11234 ,6530,6527,6498 ,0,0,0}, {11292,11281,11277 ,6499,6503,6503 ,0,0,0}, - {11291,11292,11230 ,6498,6499,6527 ,0,0,0}, {11281,11289,11231 ,6503,6508,6502 ,0,0,0}, - {11226,11288,11227 ,6538,6500,6559 ,0,0,0}, {11231,11289,11226 ,6502,6508,6538 ,0,0,0}, - {11229,11228,11287 ,6506,6533,6503 ,0,0,0}, {11228,11227,11288 ,6533,6559,6500 ,0,0,0}, - {11286,11224,11282 ,6500,6505,6498 ,0,0,0}, {11282,11229,11287 ,6498,6506,6503 ,0,0,0}, - {11332,11278,11286 ,6558,6543,6500 ,0,0,0}, {11331,11221,11225 ,6556,6512,6557 ,0,0,0}, - {11332,11225,11278 ,6558,6557,6543 ,0,0,0}, {11283,11285,11222 ,6510,6540,6511 ,0,0,0}, - {11331,11283,11221 ,6556,6510,6512 ,0,0,0}, {11223,11284,11279 ,6539,6538,6541 ,0,0,0}, - {11222,11285,11223 ,6511,6540,6539 ,0,0,0}, {9710,11279,11284 ,6500,6541,6538 ,0,0,0}, - {11284,9712,9710 ,6560,6561,6562 ,0,0,0}, {11331,11333,11283 ,6563,6564,6565 ,0,0,0}, - {11285,11334,11335 ,6566,6567,6568 ,0,0,0}, {11282,11287,11336 ,6569,6570,6571 ,0,0,0}, - {11332,11286,11337 ,6572,6573,6574 ,0,0,0}, {11338,11339,11281 ,6575,6576,6577 ,0,0,0}, - {11340,11341,11288 ,6578,6579,6580 ,0,0,0}, {11290,11280,11342 ,6581,6582,6583 ,0,0,0}, - {11292,11291,11343 ,6584,6585,6586 ,0,0,0}, {11344,11345,11293 ,6587,6588,6589 ,0,0,0}, - {11346,11295,11294 ,6590,6591,6592 ,0,0,0}, {11298,11299,11347 ,6593,6594,6595 ,0,0,0}, - {11297,11348,11349 ,6596,6597,6598 ,0,0,0}, {11350,11351,11302 ,6599,6600,6601 ,0,0,0}, - {11352,11353,11300 ,6602,6603,6604 ,0,0,0}, {11354,11305,11355 ,6605,6606,6607 ,0,0,0}, - {11303,11304,11356 ,6608,6609,6610 ,0,0,0}, {11307,11308,11357 ,6611,6612,6613 ,0,0,0}, - {11307,11358,11306 ,6611,6614,6615 ,0,0,0}, {11311,11359,11310 ,6616,6617,6618 ,0,0,0}, - {11360,11361,11309 ,6619,6620,6621 ,0,0,0}, {11312,11362,11330 ,6622,6623,6624 ,0,0,0}, - {11363,11311,11330 ,6625,6616,6624 ,0,0,0}, {11364,11365,11329 ,6626,6627,6628 ,0,0,0}, - {11366,11328,11365 ,6629,6630,6627 ,0,0,0}, {11367,11368,11327 ,6631,6632,6633 ,0,0,0}, - {11364,11315,11368 ,6626,6634,6632 ,0,0,0}, {11318,11369,11319 ,6635,6636,6637 ,0,0,0}, - {11367,11319,11369 ,6631,6637,6636 ,0,0,0}, {11318,11322,11370 ,6635,6638,6639 ,0,0,0}, - {11370,11369,11318 ,6639,6636,6635 ,0,0,0}, {11371,11322,11321 ,6640,6638,6641 ,0,0,0}, - {11322,11371,11370 ,6638,6640,6639 ,0,0,0}, {11320,11372,11321 ,6642,6643,6641 ,0,0,0}, - {11371,11321,11372 ,6640,6641,6643 ,0,0,0}, {11320,11325,11373 ,6642,6644,6645 ,0,0,0}, - {11373,11372,11320 ,6645,6643,6642 ,0,0,0}, {11374,11325,11323 ,6646,6644,6647 ,0,0,0}, - {11325,11374,11373 ,6644,6646,6645 ,0,0,0}, {11324,11375,11323 ,6648,6649,6647 ,0,0,0}, - {11374,11323,11375 ,6646,6647,6649 ,0,0,0}, {11324,11317,11376 ,6648,6650,6651 ,0,0,0}, - {11376,11375,11324 ,6651,6649,6648 ,0,0,0}, {11377,11317,11316 ,6652,6650,6653 ,0,0,0}, - {11317,11377,11376 ,6650,6652,6651 ,0,0,0}, {11316,11378,11379 ,6653,6654,6655 ,0,0,0}, - {11377,11316,11379 ,6652,6653,6655 ,0,0,0}, {11378,11326,11380 ,6654,6656,6657 ,0,0,0}, - {11326,11378,11316 ,6656,6654,6653 ,0,0,0}, {11380,11313,11314 ,6657,6658,6659 ,0,0,0}, - {11326,11313,11380 ,6656,6658,6657 ,0,0,0}, {9766,11381,11314 ,6660,6661,6659 ,0,0,0}, - {11380,11314,11381 ,6657,6659,6661 ,0,0,0}, {9765,11381,9766 ,6660,6661,6660 ,0,0,0}, - {11315,11327,11368 ,6634,6633,6632 ,0,0,0}, {11367,11327,11319 ,6631,6633,6637 ,0,0,0}, - {11328,11329,11365 ,6630,6628,6627 ,0,0,0}, {11364,11329,11315 ,6626,6628,6634 ,0,0,0}, - {11366,11362,11312 ,6629,6623,6622 ,0,0,0}, {11366,11312,11328 ,6629,6622,6630 ,0,0,0}, - {11359,11311,11363 ,6617,6616,6625 ,0,0,0}, {11362,11363,11330 ,6623,6625,6624 ,0,0,0}, - {11310,11360,11309 ,6618,6619,6621 ,0,0,0}, {11359,11360,11310 ,6617,6619,6618 ,0,0,0}, - {11308,11361,11357 ,6612,6620,6613 ,0,0,0}, {11309,11361,11308 ,6621,6620,6612 ,0,0,0}, - {11358,11355,11306 ,6614,6607,6615 ,0,0,0}, {11307,11357,11358 ,6611,6613,6614 ,0,0,0}, - {11304,11305,11354 ,6609,6606,6605 ,0,0,0}, {11305,11306,11355 ,6606,6615,6607 ,0,0,0}, - {11350,11303,11356 ,6599,6608,6610 ,0,0,0}, {11356,11304,11354 ,6610,6609,6605 ,0,0,0}, - {11351,11301,11302 ,6600,6662,6601 ,0,0,0}, {11350,11302,11303 ,6599,6601,6608 ,0,0,0}, - {11300,11301,11352 ,6604,6662,6602 ,0,0,0}, {11351,11352,11301 ,6600,6602,6662 ,0,0,0}, - {11299,11353,11347 ,6594,6603,6595 ,0,0,0}, {11300,11353,11299 ,6604,6603,6594 ,0,0,0}, - {11297,11298,11348 ,6596,6593,6597 ,0,0,0}, {11298,11347,11348 ,6593,6595,6597 ,0,0,0}, - {11344,11296,11349 ,6587,6663,6598 ,0,0,0}, {11296,11297,11349 ,6663,6596,6598 ,0,0,0}, - {11345,11294,11293 ,6588,6592,6589 ,0,0,0}, {11344,11293,11296 ,6587,6589,6663 ,0,0,0}, - {11346,11382,11295 ,6590,6664,6591 ,0,0,0}, {11345,11346,11294 ,6588,6590,6592 ,0,0,0}, - {11342,11280,11382 ,6583,6582,6664 ,0,0,0}, {11295,11382,11280 ,6591,6664,6582 ,0,0,0}, - {11291,11290,11383 ,6585,6581,6665 ,0,0,0}, {11290,11342,11383 ,6581,6583,6665 ,0,0,0}, - {11338,11292,11343 ,6575,6584,6586 ,0,0,0}, {11343,11291,11383 ,6586,6585,6665 ,0,0,0}, - {11339,11289,11281 ,6576,6666,6577 ,0,0,0}, {11338,11281,11292 ,6575,6577,6584 ,0,0,0}, - {11288,11289,11340 ,6580,6666,6578 ,0,0,0}, {11339,11340,11289 ,6576,6578,6666 ,0,0,0}, - {11287,11341,11336 ,6570,6579,6571 ,0,0,0}, {11288,11341,11287 ,6580,6579,6570 ,0,0,0}, - {11286,11282,11384 ,6573,6569,6667 ,0,0,0}, {11282,11336,11384 ,6569,6571,6667 ,0,0,0}, - {11333,11332,11337 ,6564,6572,6574 ,0,0,0}, {11337,11286,11384 ,6574,6573,6667 ,0,0,0}, - {11333,11334,11283 ,6564,6567,6565 ,0,0,0}, {11333,11331,11332 ,6564,6563,6572 ,0,0,0}, - {11335,11385,11285 ,6568,6668,6566 ,0,0,0}, {11283,11334,11285 ,6565,6567,6566 ,0,0,0}, - {9712,11284,11385 ,6561,6560,6668 ,0,0,0}, {11285,11385,11284 ,6566,6668,6560 ,0,0,0}, - {9676,9679,9583 ,6669,6670,6671 ,0,0,0}, {11338,11343,11386 ,6672,6671,6671 ,0,0,0}, - {9589,9685,9598 ,6673,6674,6671 ,0,0,0}, {9679,9681,9592 ,6670,6669,6675 ,0,0,0}, - {9691,9621,9593 ,6670,6676,6677 ,0,0,0}, {11387,11388,11356 ,6324,6298,6672 ,0,0,0}, - {11389,11348,11347 ,6671,6672,6671 ,0,0,0}, {11390,11391,11352 ,6672,6671,6671 ,0,0,0}, - {9704,9615,9611 ,6678,6671,6679 ,0,0,0}, {11349,11348,11392 ,6671,6672,6680 ,0,0,0}, - {9617,9711,9619 ,6679,6671,6671 ,0,0,0}, {11393,11394,11346 ,6672,6672,6672 ,0,0,0}, - {11395,11396,11333 ,6672,6681,6672 ,0,0,0}, {11385,11335,11397 ,6671,6681,6672 ,0,0,0}, - {11398,11340,11339 ,6672,6672,6681 ,0,0,0}, {11336,11399,11400 ,6672,6672,6672 ,0,0,0}, - {11401,11384,11400 ,6672,6671,6672 ,0,0,0}, {11338,11402,11339 ,6672,6671,6681 ,0,0,0}, - {11341,11398,11399 ,6672,6672,6672 ,0,0,0}, {11395,11337,11401 ,6672,6672,6672 ,0,0,0}, - {11403,11404,11383 ,6671,6672,6672 ,0,0,0}, {11335,11334,11405 ,6681,6671,6671 ,0,0,0}, - {11342,11406,11403 ,6671,6681,6671 ,0,0,0}, {9712,11385,9619 ,6671,6671,6671 ,0,0,0}, - {11382,11394,11406 ,6672,6672,6681 ,0,0,0}, {9615,9705,9616 ,6671,6682,6672 ,0,0,0}, - {9617,9616,9706 ,6679,6672,6298 ,0,0,0}, {11349,11407,11344 ,6671,6671,6672 ,0,0,0}, - {11407,11393,11345 ,6671,6672,6672 ,0,0,0}, {9699,9700,9607 ,6672,6681,6670 ,0,0,0}, - {9611,9613,9703 ,6679,6669,6669 ,0,0,0}, {11391,11408,11353 ,6671,6672,6671 ,0,0,0}, - {9697,9699,9609 ,6671,6672,6681 ,0,0,0}, {9604,9621,9693 ,6669,6676,6298 ,0,0,0}, - {9604,9694,9697 ,6669,6669,6671 ,0,0,0}, {11409,11350,11388 ,6672,6671,6298 ,0,0,0}, - {11409,11390,11351 ,6672,6672,6672 ,0,0,0}, {9687,9595,9598 ,6683,6669,6671 ,0,0,0}, - {9593,9595,9688 ,6677,6669,6684 ,0,0,0}, {11358,11410,11355 ,6671,6685,6686 ,0,0,0}, - {11387,11354,11355 ,6324,6687,6686 ,0,0,0}, {11358,11357,11411 ,6671,6688,6688 ,0,0,0}, - {9681,9682,9588 ,6669,6689,6684 ,0,0,0}, {11412,11413,11360 ,6672,6690,6671 ,0,0,0}, - {11413,11414,11361 ,6690,6686,6690 ,0,0,0}, {11415,11412,11359 ,6691,6672,6691 ,0,0,0}, - {9583,9586,9675 ,6671,6692,6672 ,0,0,0}, {9585,9673,9586 ,6693,6673,6692 ,0,0,0}, - {9578,9670,9585 ,6672,6689,6693 ,0,0,0}, {11363,11416,11415 ,6686,6690,6691 ,0,0,0}, - {9669,9578,9581 ,6694,6672,6695 ,0,0,0}, {11362,11417,11416 ,6690,6691,6690 ,0,0,0}, - {9581,9580,9667 ,6695,6696,6697 ,0,0,0}, {11417,11366,11365 ,6691,6672,6688 ,0,0,0}, - {9575,9663,9664 ,6698,6699,6700 ,0,0,0}, {11418,11419,11364 ,6672,6688,6688 ,0,0,0}, - {11368,11367,11420 ,6688,6691,6701 ,0,0,0}, {11421,11369,11370 ,6686,6672,6671 ,0,0,0}, - {9661,9663,9523 ,6676,6699,6702 ,0,0,0}, {11371,11422,11423 ,6672,6671,6671 ,0,0,0}, - {9661,9522,9657 ,6676,6687,6703 ,0,0,0}, {11424,11372,11373 ,6686,6704,6672 ,0,0,0}, - {9522,9570,9713 ,6687,6705,6676 ,0,0,0}, {11375,11425,11374 ,6686,6706,6672 ,0,0,0}, - {9656,9714,9570 ,6698,6699,6705 ,0,0,0}, {9718,9561,9560 ,6697,6707,6708 ,0,0,0}, - {9717,9656,9561 ,6709,6698,6707 ,0,0,0}, {11426,11378,11380 ,6690,6671,6701 ,0,0,0}, - {9560,9654,9720 ,6708,6672,6694 ,0,0,0}, {11381,9548,11427 ,6690,6690,6686 ,0,0,0}, - {9724,9723,9652 ,6673,6689,6710 ,0,0,0}, {9546,9548,9763 ,6711,6690,6690 ,0,0,0}, - {9726,9724,9650 ,6686,6673,6692 ,0,0,0}, {9760,9544,9762 ,6712,6713,6685 ,0,0,0}, - {9645,9646,9732 ,6714,6684,6669 ,0,0,0}, {9756,9541,9543 ,6715,6716,6717 ,0,0,0}, - {9641,9738,9640 ,6718,6719,6691 ,0,0,0}, {9744,9742,9529 ,6298,6670,6676 ,0,0,0}, - {9750,9534,9536 ,6686,6704,6720 ,0,0,0}, {9536,9538,9753 ,6720,6669,6715 ,0,0,0}, - {9744,9531,9747 ,6298,6718,6669 ,0,0,0}, {9531,9534,9748 ,6718,6704,6691 ,0,0,0}, - {11419,11365,11364 ,6688,6688,6688 ,0,0,0}, {9639,9742,9741 ,6676,6670,6684 ,0,0,0}, - {9756,9754,9541 ,6715,6669,6716 ,0,0,0}, {9543,9544,9760 ,6717,6713,6712 ,0,0,0}, - {9543,9760,9756 ,6717,6712,6715 ,0,0,0}, {9644,9735,9646 ,6673,6721,6684 ,0,0,0}, - {9644,9640,9736 ,6673,6691,6670 ,0,0,0}, {9546,9763,9762 ,6711,6690,6685 ,0,0,0}, - {9546,9762,9544 ,6711,6685,6713 ,0,0,0}, {9649,9729,9726 ,6691,6669,6686 ,0,0,0}, - {9730,9649,9645 ,6720,6691,6714 ,0,0,0}, {9765,9763,9548 ,6671,6690,6690 ,0,0,0}, - {11379,11428,11429 ,6686,6722,6688 ,0,0,0}, {11376,11377,11430 ,6691,6723,6706 ,0,0,0}, - {9754,9753,9538 ,6669,6715,6669 ,0,0,0}, {9754,9538,9541 ,6669,6669,6716 ,0,0,0}, - {9753,9750,9536 ,6715,6686,6720 ,0,0,0}, {9750,9748,9534 ,6686,6691,6704 ,0,0,0}, - {9748,9747,9531 ,6691,6669,6718 ,0,0,0}, {9744,9529,9531 ,6298,6676,6718 ,0,0,0}, - {9742,9639,9529 ,6670,6676,6676 ,0,0,0}, {9741,9738,9641 ,6684,6719,6718 ,0,0,0}, - {9741,9641,9639 ,6684,6718,6676 ,0,0,0}, {9738,9736,9640 ,6719,6670,6691 ,0,0,0}, - {9736,9735,9644 ,6670,6721,6673 ,0,0,0}, {9735,9732,9646 ,6721,6669,6684 ,0,0,0}, - {9732,9730,9645 ,6669,6720,6714 ,0,0,0}, {9730,9729,9649 ,6720,6669,6691 ,0,0,0}, - {9726,9650,9649 ,6686,6692,6691 ,0,0,0}, {9724,9652,9650 ,6673,6710,6692 ,0,0,0}, - {9723,9720,9654 ,6689,6694,6672 ,0,0,0}, {9723,9654,9652 ,6689,6672,6710 ,0,0,0}, - {9720,9718,9560 ,6694,6697,6708 ,0,0,0}, {9718,9717,9561 ,6697,6709,6707 ,0,0,0}, - {9717,9714,9656 ,6709,6699,6698 ,0,0,0}, {9714,9713,9570 ,6699,6676,6705 ,0,0,0}, - {9713,9657,9522 ,6676,6703,6687 ,0,0,0}, {9661,9523,9522 ,6676,6702,6687 ,0,0,0}, - {9663,9575,9523 ,6699,6698,6702 ,0,0,0}, {9664,9667,9580 ,6700,6697,6696 ,0,0,0}, - {9664,9580,9575 ,6700,6696,6698 ,0,0,0}, {9667,9669,9581 ,6697,6694,6695 ,0,0,0}, - {9669,9670,9578 ,6694,6689,6672 ,0,0,0}, {9670,9673,9585 ,6689,6673,6693 ,0,0,0}, - {9673,9675,9586 ,6673,6672,6692 ,0,0,0}, {9675,9676,9583 ,6672,6669,6671 ,0,0,0}, - {9679,9592,9583 ,6670,6675,6671 ,0,0,0}, {9681,9588,9592 ,6669,6684,6675 ,0,0,0}, - {9682,9685,9589 ,6689,6674,6673 ,0,0,0}, {9682,9589,9588 ,6689,6673,6684 ,0,0,0}, - {9685,9687,9598 ,6674,6683,6671 ,0,0,0}, {9687,9688,9595 ,6683,6684,6669 ,0,0,0}, - {9688,9691,9593 ,6684,6670,6677 ,0,0,0}, {9691,9693,9621 ,6670,6298,6676 ,0,0,0}, - {9693,9694,9604 ,6298,6669,6669 ,0,0,0}, {9697,9609,9604 ,6671,6681,6669 ,0,0,0}, - {9699,9607,9609 ,6672,6670,6681 ,0,0,0}, {9700,9703,9613 ,6681,6669,6669 ,0,0,0}, - {9700,9613,9607 ,6681,6669,6670 ,0,0,0}, {9703,9704,9611 ,6669,6678,6679 ,0,0,0}, - {9704,9705,9615 ,6678,6682,6671 ,0,0,0}, {9705,9706,9616 ,6682,6298,6672 ,0,0,0}, - {9706,9711,9617 ,6298,6671,6679 ,0,0,0}, {9711,9712,9619 ,6671,6671,6671 ,0,0,0}, - {11385,11397,9619 ,6671,6672,6671 ,0,0,0}, {11335,11405,11397 ,6681,6671,6672 ,0,0,0}, - {11334,11333,11396 ,6671,6672,6681 ,0,0,0}, {11334,11396,11405 ,6671,6681,6671 ,0,0,0}, - {11333,11337,11395 ,6672,6672,6672 ,0,0,0}, {11337,11384,11401 ,6672,6671,6672 ,0,0,0}, - {11384,11336,11400 ,6671,6672,6672 ,0,0,0}, {11336,11341,11399 ,6672,6672,6672 ,0,0,0}, - {11341,11340,11398 ,6672,6672,6672 ,0,0,0}, {11339,11402,11398 ,6681,6671,6672 ,0,0,0}, - {11338,11386,11402 ,6672,6671,6671 ,0,0,0}, {11343,11383,11404 ,6671,6672,6672 ,0,0,0}, - {11343,11404,11386 ,6671,6672,6671 ,0,0,0}, {11383,11342,11403 ,6672,6671,6671 ,0,0,0}, - {11342,11382,11406 ,6671,6672,6681 ,0,0,0}, {11382,11346,11394 ,6672,6672,6672 ,0,0,0}, - {11346,11345,11393 ,6672,6672,6672 ,0,0,0}, {11345,11344,11407 ,6672,6672,6671 ,0,0,0}, - {11349,11392,11407 ,6671,6680,6671 ,0,0,0}, {11348,11389,11392 ,6672,6671,6680 ,0,0,0}, - {11347,11353,11408 ,6671,6671,6672 ,0,0,0}, {11347,11408,11389 ,6671,6672,6671 ,0,0,0}, - {11353,11352,11391 ,6671,6671,6671 ,0,0,0}, {11352,11351,11390 ,6671,6672,6672 ,0,0,0}, - {11351,11350,11409 ,6672,6671,6672 ,0,0,0}, {11350,11356,11388 ,6671,6672,6298 ,0,0,0}, - {11356,11354,11387 ,6672,6687,6324 ,0,0,0}, {11355,11410,11387 ,6686,6685,6324 ,0,0,0}, - {11358,11411,11410 ,6671,6688,6685 ,0,0,0}, {11357,11361,11414 ,6688,6690,6686 ,0,0,0}, - {11357,11414,11411 ,6688,6686,6688 ,0,0,0}, {11361,11360,11413 ,6690,6671,6690 ,0,0,0}, - {11360,11359,11412 ,6671,6691,6672 ,0,0,0}, {11359,11363,11415 ,6691,6686,6691 ,0,0,0}, - {11363,11362,11416 ,6686,6690,6690 ,0,0,0}, {11362,11366,11417 ,6690,6672,6691 ,0,0,0}, - {11365,11419,11417 ,6688,6688,6691 ,0,0,0}, {11368,11418,11364 ,6688,6672,6688 ,0,0,0}, - {11367,11431,11420 ,6691,6691,6701 ,0,0,0}, {11368,11420,11418 ,6688,6701,6672 ,0,0,0}, - {11421,11431,11369 ,6686,6691,6672 ,0,0,0}, {11367,11369,11431 ,6691,6672,6691 ,0,0,0}, - {11421,11370,11423 ,6686,6671,6671 ,0,0,0}, {11422,11371,11372 ,6671,6672,6704 ,0,0,0}, - {11423,11370,11371 ,6671,6671,6672 ,0,0,0}, {11424,11373,11374 ,6686,6672,6672 ,0,0,0}, - {11424,11422,11372 ,6686,6671,6704 ,0,0,0}, {11432,11425,11375 ,6688,6706,6686 ,0,0,0}, - {11425,11424,11374 ,6706,6686,6672 ,0,0,0}, {11432,11376,11430 ,6688,6691,6706 ,0,0,0}, - {11376,11432,11375 ,6691,6688,6686 ,0,0,0}, {11377,11429,11430 ,6723,6688,6706 ,0,0,0}, - {11379,11378,11428 ,6686,6671,6722 ,0,0,0}, {11377,11379,11429 ,6723,6686,6688 ,0,0,0}, - {11426,11380,11427 ,6690,6701,6686 ,0,0,0}, {11428,11378,11426 ,6722,6671,6690 ,0,0,0}, - {9548,11381,9765 ,6690,6690,6671 ,0,0,0}, {11427,11380,11381 ,6686,6701,6690 ,0,0,0}, - {11427,9125,10929 ,6724,6725,6726 ,0,0,0}, {10891,11428,11426 ,6727,6728,6729 ,0,0,0}, - {11430,10893,11432 ,6730,6731,6732 ,0,0,0}, {11034,11429,11032 ,6733,6734,6735 ,0,0,0}, - {11433,11043,11434 ,6736,6737,6738 ,0,0,0}, {10918,11433,11435 ,6739,6736,6736 ,0,0,0}, - {10959,11436,11437 ,6740,6741,6742 ,0,0,0}, {10958,11438,10917 ,6743,6744,6745 ,0,0,0}, - {11041,11439,11440 ,6746,6747,6748 ,0,0,0}, {11088,11441,11046 ,6749,6750,6751 ,0,0,0}, - {11442,11443,11086 ,6752,6753,6754 ,0,0,0}, {11439,10974,11087 ,6747,6755,6756 ,0,0,0}, - {11409,11010,11001 ,6757,6758,6759 ,0,0,0}, {9412,11010,11442 ,6760,6758,6752 ,0,0,0}, - {11391,11003,11408 ,6761,6762,6763 ,0,0,0}, {11002,11391,11390 ,6764,6761,6765 ,0,0,0}, - {11073,11008,11392 ,6766,6767,6768 ,0,0,0}, {11073,11389,11072 ,6766,6769,6770 ,0,0,0}, - {11407,11000,11393 ,6771,6772,6773 ,0,0,0}, {11000,11407,11008 ,6772,6771,6767 ,0,0,0}, - {11394,11393,10977 ,6774,6773,6775 ,0,0,0}, {11000,10977,11393 ,6772,6775,6773 ,0,0,0}, - {10975,11406,10976 ,6776,6777,6778 ,0,0,0}, {11394,10977,10976 ,6774,6775,6778 ,0,0,0}, - {10981,11404,10999 ,6779,6780,6781 ,0,0,0}, {11403,10975,10999 ,6782,6776,6781 ,0,0,0}, - {10980,11402,11386 ,6783,6784,6785 ,0,0,0}, {11399,11398,11444 ,6786,6787,6788 ,0,0,0}, - {11444,10998,11445 ,6788,6789,6788 ,0,0,0}, {11398,11402,10998 ,6787,6784,6789 ,0,0,0}, - {11446,10979,10952 ,6790,6791,6792 ,0,0,0}, {10979,11446,11445 ,6791,6790,6788 ,0,0,0}, - {10951,11447,10952 ,6793,6794,6792 ,0,0,0}, {11446,10952,11447 ,6790,6792,6794 ,0,0,0}, - {10951,10984,11448 ,6793,6795,6796 ,0,0,0}, {11448,11447,10951 ,6796,6794,6793 ,0,0,0}, - {11449,10984,10990 ,6797,6795,6798 ,0,0,0}, {10984,11449,11448 ,6795,6797,6796 ,0,0,0}, - {10994,11450,10990 ,6799,6800,6798 ,0,0,0}, {11449,10990,11450 ,6797,6798,6800 ,0,0,0}, - {10994,10987,11451 ,6799,6801,6802 ,0,0,0}, {11451,11450,10994 ,6802,6800,6799 ,0,0,0}, - {11452,10987,10996 ,6803,6801,6804 ,0,0,0}, {10987,11452,11451 ,6801,6803,6802 ,0,0,0}, - {9226,9629,10996 ,6805,6806,6804 ,0,0,0}, {11452,10996,9629 ,6803,6804,6806 ,0,0,0}, - {11396,11453,11454 ,6807,6808,6809 ,0,0,0}, {11398,10998,11444 ,6787,6789,6788 ,0,0,0}, - {11445,10998,10979 ,6788,6789,6791 ,0,0,0}, {10980,10998,11402 ,6783,6789,6784 ,0,0,0}, - {10981,10980,11386 ,6779,6783,6785 ,0,0,0}, {11386,11404,10981 ,6785,6780,6779 ,0,0,0}, - {10999,11404,11403 ,6781,6780,6782 ,0,0,0}, {10975,11403,11406 ,6776,6782,6777 ,0,0,0}, - {11406,11394,10976 ,6777,6774,6778 ,0,0,0}, {11444,11455,11399 ,6788,6810,6786 ,0,0,0}, - {11453,11396,11395 ,6808,6807,6811 ,0,0,0}, {11455,11400,11399 ,6810,6812,6786 ,0,0,0}, - {11454,11456,11405 ,6809,6813,6814 ,0,0,0}, {11405,11396,11454 ,6814,6807,6809 ,0,0,0}, - {11405,11457,11397 ,6814,6815,6816 ,0,0,0}, {11457,11405,11456 ,6815,6814,6813 ,0,0,0}, - {9619,11397,9620 ,6817,6816,6818 ,0,0,0}, {11457,9620,11397 ,6815,6818,6816 ,0,0,0}, - {11395,11458,11453 ,6811,6819,6808 ,0,0,0}, {11008,11407,11392 ,6767,6771,6768 ,0,0,0}, - {11458,11395,11401 ,6819,6811,6820 ,0,0,0}, {11459,11458,11401 ,6821,6819,6820 ,0,0,0}, - {11400,11455,11459 ,6812,6810,6821 ,0,0,0}, {11400,11459,11401 ,6812,6821,6820 ,0,0,0}, - {11392,11389,11073 ,6768,6769,6766 ,0,0,0}, {11039,11440,11441 ,6822,6748,6750 ,0,0,0}, - {11072,11408,11003 ,6770,6763,6762 ,0,0,0}, {11408,11072,11389 ,6763,6770,6769 ,0,0,0}, - {11391,11002,11003 ,6761,6764,6762 ,0,0,0}, {11001,11002,11390 ,6759,6764,6765 ,0,0,0}, - {11388,11010,11409 ,6823,6758,6757 ,0,0,0}, {11390,11409,11001 ,6765,6757,6759 ,0,0,0}, - {9412,11442,11086 ,6760,6752,6754 ,0,0,0}, {11388,11442,11010 ,6823,6752,6758 ,0,0,0}, - {11439,11041,10974 ,6747,6746,6755 ,0,0,0}, {11443,11439,11087 ,6753,6747,6756 ,0,0,0}, - {11441,11088,11039 ,6750,6749,6822 ,0,0,0}, {11460,11038,11461 ,6824,6825,6826 ,0,0,0}, - {11441,11461,11046 ,6750,6826,6751 ,0,0,0}, {11460,11436,10968 ,6824,6741,6827 ,0,0,0}, - {11038,11460,10968 ,6825,6824,6827 ,0,0,0}, {11437,11438,10958 ,6742,6744,6743 ,0,0,0}, - {10968,11436,10950 ,6827,6741,6828 ,0,0,0}, {11431,11421,11462 ,6829,6830,6831 ,0,0,0}, - {11422,11424,11435 ,6832,6833,6736 ,0,0,0}, {11438,11434,11037 ,6744,6738,6834 ,0,0,0}, - {11426,10929,10891 ,6729,6726,6727 ,0,0,0}, {11430,11429,11034 ,6730,6734,6733 ,0,0,0}, - {10894,10918,11425 ,6835,6739,6836 ,0,0,0}, {11052,11433,10918 ,6837,6736,6739 ,0,0,0}, - {11432,10894,11425 ,6732,6835,6836 ,0,0,0}, {11034,10893,11430 ,6733,6731,6730 ,0,0,0}, - {11432,10893,10894 ,6732,6731,6835 ,0,0,0}, {11428,11032,11429 ,6728,6735,6734 ,0,0,0}, - {11032,11428,10891 ,6735,6728,6727 ,0,0,0}, {10929,11426,11427 ,6726,6729,6724 ,0,0,0}, - {9125,11427,9548 ,6725,6724,6838 ,0,0,0}, {11410,11463,11387 ,6839,6840,6841 ,0,0,0}, - {11388,11387,11463 ,6823,6841,6840 ,0,0,0}, {11463,11410,11464 ,6840,6839,6842 ,0,0,0}, - {11388,11463,11442 ,6823,6840,6752 ,0,0,0}, {11465,11464,11411 ,6843,6842,6844 ,0,0,0}, - {11087,11086,11443 ,6756,6754,6753 ,0,0,0}, {11413,11465,11414 ,6845,6843,6846 ,0,0,0}, - {11413,11466,11465 ,6845,6847,6843 ,0,0,0}, {11467,11466,11412 ,6848,6847,6849 ,0,0,0}, - {11039,11041,11440 ,6822,6746,6748 ,0,0,0}, {11416,11467,11415 ,6850,6848,6851 ,0,0,0}, - {11416,11468,11467 ,6850,6852,6848 ,0,0,0}, {11469,11468,11417 ,6853,6852,6854 ,0,0,0}, - {11038,11046,11461 ,6825,6751,6826 ,0,0,0}, {11419,11470,11469 ,6855,6856,6853 ,0,0,0}, - {11418,11470,11419 ,6857,6856,6855 ,0,0,0}, {11471,11470,11420 ,6858,6856,6859 ,0,0,0}, - {10959,10950,11436 ,6740,6828,6741 ,0,0,0}, {11462,11471,11431 ,6831,6858,6829 ,0,0,0}, - {10958,10959,11437 ,6743,6740,6742 ,0,0,0}, {11472,11462,11423 ,6860,6831,6861 ,0,0,0}, - {11037,10917,11438 ,6834,6745,6744 ,0,0,0}, {11435,11472,11422 ,6736,6860,6832 ,0,0,0}, - {11043,11037,11434 ,6737,6834,6738 ,0,0,0}, {11425,10918,11435 ,6836,6739,6736 ,0,0,0}, - {11043,11433,11052 ,6737,6736,6837 ,0,0,0}, {11425,11435,11424 ,6836,6736,6833 ,0,0,0}, - {11423,11422,11472 ,6861,6832,6860 ,0,0,0}, {11421,11423,11462 ,6830,6861,6831 ,0,0,0}, - {11420,11431,11471 ,6859,6829,6858 ,0,0,0}, {11418,11420,11470 ,6857,6859,6856 ,0,0,0}, - {11417,11419,11469 ,6854,6855,6853 ,0,0,0}, {11416,11417,11468 ,6850,6854,6852 ,0,0,0}, - {11412,11415,11467 ,6849,6851,6848 ,0,0,0}, {11413,11412,11466 ,6845,6849,6847 ,0,0,0}, - {11411,11414,11465 ,6844,6846,6843 ,0,0,0}, {11410,11411,11464 ,6839,6844,6842 ,0,0,0}, - {11473,9420,9421 ,6862,6863,6864 ,0,0,0}, {11125,11114,10352 ,6865,6866,6867 ,0,0,0}, - {11474,11122,11121 ,6868,6869,6870 ,0,0,0}, {11124,10345,11111 ,6871,6872,6873 ,0,0,0}, - {10330,11104,11108 ,6874,6875,6876 ,0,0,0}, {10342,11127,11128 ,6877,6878,6879 ,0,0,0}, - {11138,10337,10336 ,6880,6881,6882 ,0,0,0}, {11135,10329,10332 ,6883,6884,6885 ,0,0,0}, - {11475,11148,11146 ,6886,6887,6888 ,0,0,0}, {11476,11142,10339 ,6889,6890,5525 ,0,0,0}, - {11159,11156,10415 ,6891,6892,6893 ,0,0,0}, {11152,11477,11478 ,6894,6895,6896 ,0,0,0}, - {11166,10404,11220 ,6897,6898,6899 ,0,0,0}, {11162,10410,11165 ,6900,6901,6902 ,0,0,0}, - {10451,11171,10449 ,6903,6904,6905 ,0,0,0}, {11214,11167,10447 ,6906,6907,6908 ,0,0,0}, - {11203,11479,11205 ,6909,6910,6911 ,0,0,0}, {11211,10452,11177 ,6912,6913,6914 ,0,0,0}, - {11480,11192,11184 ,6915,6916,6917 ,0,0,0}, {11202,11481,11189 ,6918,6919,6920 ,0,0,0}, - {11482,11199,11200 ,6921,6922,6923 ,0,0,0}, {10508,10511,11193 ,6924,6925,6926 ,0,0,0}, - {10508,11196,10509 ,6924,6927,5712 ,0,0,0}, {10496,10495,11186 ,6928,6929,6930 ,0,0,0}, - {10496,11201,10511 ,6928,6931,6925 ,0,0,0}, {11206,11208,10495 ,6932,6933,6929 ,0,0,0}, - {10495,11208,11186 ,6929,6933,6930 ,0,0,0}, {11206,10495,10540 ,6932,6929,6934 ,0,0,0}, - {10540,10542,11180 ,6934,6935,6936 ,0,0,0}, {11180,11206,10540 ,6936,6932,6934 ,0,0,0}, - {11212,10542,10544 ,6937,6935,6938 ,0,0,0}, {10542,11212,11180 ,6935,6937,6936 ,0,0,0}, - {11212,10544,11173 ,6937,6938,6939 ,0,0,0}, {10545,11174,11173 ,6940,6941,6939 ,0,0,0}, - {11173,10544,10545 ,6939,6938,6940 ,0,0,0}, {11174,10547,11218 ,6941,6942,6943 ,0,0,0}, - {10547,11174,10545 ,6942,6941,6940 ,0,0,0}, {11168,11218,10548 ,6944,6943,6945 ,0,0,0}, - {10547,10548,11218 ,6942,6945,6943 ,0,0,0}, {10548,11483,11163 ,6945,6946,6947 ,0,0,0}, - {11163,11168,10548 ,6947,6944,6945 ,0,0,0}, {11160,11483,11484 ,6948,6946,6949 ,0,0,0}, - {11483,11160,11163 ,6946,6948,6947 ,0,0,0}, {11485,11157,11484 ,6950,6951,6949 ,0,0,0}, - {11160,11484,11157 ,6948,6949,6951 ,0,0,0}, {11485,9518,9516 ,6950,126,3135 ,0,0,0}, - {9516,11157,11485 ,3135,6951,6950 ,0,0,0}, {10511,11201,11193 ,6925,6931,6926 ,0,0,0}, - {10496,11186,11201 ,6928,6930,6931 ,0,0,0}, {11196,11189,10509 ,6927,6920,5712 ,0,0,0}, - {10508,11193,11196 ,6924,6926,6927 ,0,0,0}, {11481,11202,11199 ,6919,6918,6922 ,0,0,0}, - {11481,10509,11189 ,6919,5712,6920 ,0,0,0}, {11482,11200,11192 ,6921,6923,6916 ,0,0,0}, - {11482,11481,11199 ,6921,6919,6922 ,0,0,0}, {11479,11480,11184 ,6910,6915,6917 ,0,0,0}, - {11480,11482,11192 ,6915,6921,6916 ,0,0,0}, {10454,11479,11203 ,6952,6910,6909 ,0,0,0}, - {11205,11479,11184 ,6911,6910,6917 ,0,0,0}, {10454,11177,10452 ,6952,6914,6913 ,0,0,0}, - {11177,10454,11203 ,6914,6952,6909 ,0,0,0}, {11209,10451,10452 ,6953,6903,6913 ,0,0,0}, - {11209,10452,11211 ,6953,6913,6912 ,0,0,0}, {11171,11216,10449 ,6904,6954,6905 ,0,0,0}, - {11209,11171,10451 ,6953,6904,6903 ,0,0,0}, {11214,10447,11216 ,6906,6908,6954 ,0,0,0}, - {10449,11216,10447 ,6905,6954,6908 ,0,0,0}, {10406,11167,11220 ,6955,6907,6899 ,0,0,0}, - {10447,11167,10406 ,6908,6907,6955 ,0,0,0}, {10416,10404,11166 ,6956,6898,6897 ,0,0,0}, - {10404,10406,11220 ,6898,6955,6899 ,0,0,0}, {10416,11165,10410 ,6956,6902,6901 ,0,0,0}, - {11165,10416,11166 ,6902,6956,6897 ,0,0,0}, {11159,10415,10410 ,6891,6893,6901 ,0,0,0}, - {11159,10410,11162 ,6891,6901,6900 ,0,0,0}, {11156,11154,11478 ,6892,6957,6896 ,0,0,0}, - {11156,11478,10415 ,6892,6896,6893 ,0,0,0}, {11152,11150,11477 ,6894,6958,6895 ,0,0,0}, - {11154,11152,11478 ,6957,6894,6896 ,0,0,0}, {11148,11475,11150 ,6887,6886,6958 ,0,0,0}, - {11477,11150,11475 ,6895,6958,6886 ,0,0,0}, {11476,11146,11144 ,6889,6888,6959 ,0,0,0}, - {11475,11146,11476 ,6886,6888,6889 ,0,0,0}, {10339,11142,11140 ,5525,6890,6960 ,0,0,0}, - {11476,11144,11142 ,6889,6959,6890 ,0,0,0}, {11140,11138,10336 ,6960,6880,6882 ,0,0,0}, - {10336,10339,11140 ,6882,5525,6960 ,0,0,0}, {11105,10332,10337 ,6961,6885,6881 ,0,0,0}, - {11105,10337,11138 ,6961,6881,6880 ,0,0,0}, {11135,11131,10329 ,6883,6962,6884 ,0,0,0}, - {11105,11135,10332 ,6961,6883,6885 ,0,0,0}, {10330,10329,11104 ,6874,6884,6875 ,0,0,0}, - {11131,11104,10329 ,6962,6875,6884 ,0,0,0}, {10335,11108,11127 ,6963,6876,6878 ,0,0,0}, - {10330,11108,10335 ,6874,6876,6963 ,0,0,0}, {10344,10342,11128 ,6964,6877,6879 ,0,0,0}, - {10342,10335,11127 ,6877,6963,6878 ,0,0,0}, {10344,11111,10345 ,6964,6873,6872 ,0,0,0}, - {11111,10344,11128 ,6873,6964,6879 ,0,0,0}, {11124,11125,10352 ,6871,6865,6867 ,0,0,0}, - {11124,10352,10345 ,6871,6867,6872 ,0,0,0}, {11114,11122,11486 ,6866,6869,6965 ,0,0,0}, - {11114,11486,10352 ,6866,6965,6867 ,0,0,0}, {11474,11121,11473 ,6868,6870,6862 ,0,0,0}, - {11486,11122,11474 ,6965,6869,6868 ,0,0,0}, {9420,11473,11121 ,6863,6862,6870 ,0,0,0}, - {9390,11487,11048 ,6966,6967,6968 ,0,0,0}, {11488,11092,11489 ,6969,6970,6971 ,0,0,0}, - {10960,10961,11490 ,6972,6973,6974 ,0,0,0}, {11094,11491,11095 ,6975,6976,6977 ,0,0,0}, - {11492,11493,11036 ,6978,6979,6980 ,0,0,0}, {11494,11091,11495 ,6981,6982,6983 ,0,0,0}, - {11093,11047,11496 ,6984,6985,6986 ,0,0,0}, {11098,11497,11498 ,6987,6988,6989 ,0,0,0}, - {11089,11499,11090 ,6990,6991,6992 ,0,0,0}, {11099,11500,10972 ,6993,6994,6995 ,0,0,0}, - {11501,11099,11040 ,6996,6993,6997 ,0,0,0}, {10973,11502,11100 ,6998,6999,7000 ,0,0,0}, - {11503,10973,10972 ,7001,6998,6995 ,0,0,0}, {11101,11100,11504 ,7002,7000,7003 ,0,0,0}, - {11502,11504,11100 ,6999,7003,7000 ,0,0,0}, {11505,11085,11101 ,7004,7005,7002 ,0,0,0}, - {11101,11504,11505 ,7002,7003,7004 ,0,0,0}, {11085,11506,11103 ,7005,7006,7007 ,0,0,0}, - {11506,11085,11505 ,7006,7005,7004 ,0,0,0}, {11102,11103,11507 ,7008,7007,7009 ,0,0,0}, - {11506,11507,11103 ,7006,7009,7007 ,0,0,0}, {11508,9412,11102 ,7010,82,7008 ,0,0,0}, - {11102,11507,11508 ,7008,7009,7010 ,0,0,0}, {9411,9412,11508 ,7011,82,7010 ,0,0,0}, - {11040,11498,11501 ,6997,6989,6996 ,0,0,0}, {11500,11503,10972 ,6994,7001,6995 ,0,0,0}, - {11503,11502,10973 ,7001,6999,6998 ,0,0,0}, {11500,11099,11501 ,6994,6993,6996 ,0,0,0}, - {11497,11098,11090 ,6988,6987,6992 ,0,0,0}, {11498,11040,11098 ,6989,6997,6987 ,0,0,0}, - {11090,11499,11497 ,6992,6991,6988 ,0,0,0}, {11494,11499,11089 ,6981,6991,6990 ,0,0,0}, - {11509,11095,11491 ,7012,6977,6976 ,0,0,0}, {11093,11495,11091 ,6984,6983,6982 ,0,0,0}, - {11089,11091,11494 ,6990,6982,6981 ,0,0,0}, {11047,11095,11509 ,6985,6977,7012 ,0,0,0}, - {11047,11509,11496 ,6985,7012,6986 ,0,0,0}, {11495,11093,11496 ,6983,6984,6986 ,0,0,0}, - {11092,10960,11489 ,6970,6972,6971 ,0,0,0}, {11491,11094,11493 ,6976,6975,6979 ,0,0,0}, - {11492,11036,11035 ,6978,6980,7013 ,0,0,0}, {11036,11493,11094 ,6980,6979,6975 ,0,0,0}, - {11035,11092,11488 ,7013,6970,6969 ,0,0,0}, {11035,11488,11492 ,7013,6969,6978 ,0,0,0}, - {10961,11487,11490 ,6973,6967,6974 ,0,0,0}, {11489,10960,11490 ,6971,6972,6974 ,0,0,0}, - {9390,11048,9387 ,6966,6968,7014 ,0,0,0}, {11487,10961,11048 ,6967,6973,6968 ,0,0,0}, - {11509,9405,11496 ,730,730,730 ,0,0,0}, {11504,11502,11500 ,730,730,730 ,0,0,0}, - {11502,11503,11500 ,730,730,730 ,0,0,0}, {11500,11501,11505 ,730,730,730 ,0,0,0}, - {11505,11504,11500 ,730,730,730 ,0,0,0}, {11506,11501,11498 ,730,730,730 ,0,0,0}, - {11501,11506,11505 ,730,730,730 ,0,0,0}, {11497,11507,11498 ,730,730,730 ,0,0,0}, - {11506,11498,11507 ,730,730,730 ,0,0,0}, {11508,11497,9411 ,730,730,730 ,0,0,0}, - {11508,11507,11497 ,730,730,730 ,0,0,0}, {11499,11494,9409 ,730,730,730 ,0,0,0}, - {11497,11499,9411 ,730,730,730 ,0,0,0}, {11491,9400,9403 ,730,730,7015 ,0,0,0}, - {9406,9409,11495 ,730,730,730 ,0,0,0}, {11488,9394,9397 ,7016,7015,7017 ,0,0,0}, - {11493,9397,9399 ,730,7017,7017 ,0,0,0}, {9391,9393,11490 ,730,730,730 ,0,0,0}, - {9390,9366,9368 ,730,730,730 ,0,0,0}, {9364,9391,11487 ,7015,730,730 ,0,0,0}, - {9370,9384,9382 ,730,730,7017 ,0,0,0}, {9366,9385,9372 ,730,7017,7015 ,0,0,0}, - {9378,9374,9379 ,730,730,730 ,0,0,0}, {9374,9382,9379 ,730,7017,730 ,0,0,0}, - {9375,9374,9378 ,730,730,730 ,0,0,0}, {9370,9372,9384 ,730,7015,730 ,0,0,0}, - {9374,9370,9382 ,730,730,7017 ,0,0,0}, {9385,9366,9389 ,7017,730,730 ,0,0,0}, - {9384,9372,9385 ,730,7015,7017 ,0,0,0}, {9390,9389,9366 ,730,730,730 ,0,0,0}, - {11487,9368,9364 ,730,730,7015 ,0,0,0}, {11487,9390,9368 ,730,730,730 ,0,0,0}, - {9393,11489,11490 ,730,7016,730 ,0,0,0}, {11490,11487,9391 ,730,730,730 ,0,0,0}, - {11488,11489,9394 ,7016,7016,7015 ,0,0,0}, {9393,9394,11489 ,730,7015,7016 ,0,0,0}, - {9397,11493,11492 ,7017,730,730 ,0,0,0}, {9397,11492,11488 ,7017,730,7016 ,0,0,0}, - {9399,9400,11491 ,7017,730,730 ,0,0,0}, {11493,9399,11491 ,730,7017,730 ,0,0,0}, - {9403,9405,11509 ,7015,730,730 ,0,0,0}, {11491,9403,11509 ,730,7015,730 ,0,0,0}, - {11496,9406,11495 ,730,730,730 ,0,0,0}, {11496,9405,9406 ,730,730,730 ,0,0,0}, - {11499,9409,9411 ,730,730,730 ,0,0,0}, {11494,11495,9409 ,730,730,730 ,0,0,0}, - {11510,11511,9362 ,7018,7019,7020 ,0,0,0}, {9362,11512,11510 ,7020,7021,7018 ,0,0,0}, - {9362,9345,11512 ,7020,7022,7021 ,0,0,0}, {9362,11513,11514 ,7020,7023,7024 ,0,0,0}, - {11511,11513,9362 ,7019,7023,7020 ,0,0,0}, {9362,11515,11516 ,7020,7025,7026 ,0,0,0}, - {11514,11515,9362 ,7024,7025,7020 ,0,0,0}, {11516,11517,9362 ,7026,7027,7020 ,0,0,0}, - {11518,9362,11519 ,7028,7020,7029 ,0,0,0}, {9362,11517,11519 ,7020,7027,7029 ,0,0,0}, - {11520,9362,11521 ,7030,7020,7031 ,0,0,0}, {9362,11518,11521 ,7020,7028,7031 ,0,0,0}, - {11522,9362,11523 ,7032,7020,7033 ,0,0,0}, {9362,11520,11523 ,7020,7030,7033 ,0,0,0}, - {9361,9362,11522 ,7034,7020,7032 ,0,0,0}, {9344,11017,11512 ,7035,7036,7037 ,0,0,0}, - {11514,11513,11007 ,7038,7039,7040 ,0,0,0}, {11511,11510,11016 ,7041,7042,7043 ,0,0,0}, - {11516,11074,11517 ,7044,7045,7046 ,0,0,0}, {11006,11019,11515 ,7047,7048,7049 ,0,0,0}, - {11075,10900,11518 ,7050,7051,7052 ,0,0,0}, {11075,11519,10966 ,7050,7053,7054 ,0,0,0}, - {10964,11023,11520 ,7055,7056,7057 ,0,0,0}, {11520,11521,10964 ,7057,7058,7055 ,0,0,0}, - {11523,11023,11009 ,7059,7056,7060 ,0,0,0}, {11023,11523,11520 ,7056,7059,7057 ,0,0,0}, - {10997,11522,11009 ,7061,7062,7060 ,0,0,0}, {11523,11009,11522 ,7059,7060,7062 ,0,0,0}, - {10997,9360,9361 ,7061,7063,4910 ,0,0,0}, {9361,11522,10997 ,4910,7062,7061 ,0,0,0}, - {11074,11516,11019 ,7045,7044,7048 ,0,0,0}, {10900,11521,11518 ,7051,7058,7052 ,0,0,0}, - {10964,11521,10900 ,7055,7058,7051 ,0,0,0}, {11007,11513,11015 ,7040,7039,7064 ,0,0,0}, - {10966,11519,11517 ,7054,7053,7046 ,0,0,0}, {11075,11518,11519 ,7050,7052,7053 ,0,0,0}, - {11074,10966,11517 ,7045,7054,7046 ,0,0,0}, {11515,11019,11516 ,7049,7048,7044 ,0,0,0}, - {11514,11007,11006 ,7038,7040,7047 ,0,0,0}, {11006,11515,11514 ,7047,7049,7038 ,0,0,0}, - {11510,11017,11016 ,7042,7036,7043 ,0,0,0}, {11015,11511,11016 ,7064,7041,7043 ,0,0,0}, - {11513,11511,11015 ,7039,7041,7064 ,0,0,0}, {9344,11512,9345 ,7035,7037,4929 ,0,0,0}, - {11017,11510,11512 ,7036,7042,7037 ,0,0,0}, {11524,11525,9328 ,7018,7019,7065 ,0,0,0}, - {9328,11526,11524 ,7065,7021,7018 ,0,0,0}, {9328,9311,11526 ,7065,7066,7021 ,0,0,0}, - {9328,11527,11528 ,7065,7023,7024 ,0,0,0}, {11525,11527,9328 ,7019,7023,7065 ,0,0,0}, - {9328,11529,11530 ,7065,7025,7026 ,0,0,0}, {11528,11529,9328 ,7024,7025,7065 ,0,0,0}, - {11530,11531,9328 ,7026,7027,7065 ,0,0,0}, {11532,9328,11533 ,7028,7065,7029 ,0,0,0}, - {9328,11531,11533 ,7065,7027,7029 ,0,0,0}, {11534,9328,11535 ,7030,7065,7031 ,0,0,0}, - {9328,11532,11535 ,7065,7028,7031 ,0,0,0}, {11536,9328,11537 ,7032,7065,7033 ,0,0,0}, - {9328,11534,11537 ,7065,7030,7033 ,0,0,0}, {9327,9328,11536 ,7067,7065,7032 ,0,0,0}, - {9310,11066,11526 ,7068,7069,7070 ,0,0,0}, {11528,11527,10907 ,7071,7072,7073 ,0,0,0}, - {11525,11524,10946 ,7074,7075,7076 ,0,0,0}, {11530,10926,11531 ,7077,7078,7079 ,0,0,0}, - {10908,11071,11529 ,7047,7080,7081 ,0,0,0}, {10890,11069,11532 ,7082,7083,7084 ,0,0,0}, - {10890,11533,11070 ,7082,7085,7086 ,0,0,0}, {11068,10944,11534 ,7087,7088,7089 ,0,0,0}, - {11534,11535,11068 ,7089,7090,7087 ,0,0,0}, {11537,10944,10945 ,7091,7088,7092 ,0,0,0}, - {10944,11537,11534 ,7088,7091,7089 ,0,0,0}, {11067,11536,10945 ,7093,7094,7092 ,0,0,0}, - {11537,10945,11536 ,7091,7092,7094 ,0,0,0}, {11067,9326,9327 ,7093,4831,4942 ,0,0,0}, - {9327,11536,11067 ,4942,7094,7093 ,0,0,0}, {10926,11530,11071 ,7078,7077,7080 ,0,0,0}, - {11069,11535,11532 ,7083,7090,7084 ,0,0,0}, {11068,11535,11069 ,7087,7090,7083 ,0,0,0}, - {10907,11527,10943 ,7073,7072,7095 ,0,0,0}, {11070,11533,11531 ,7086,7085,7079 ,0,0,0}, - {10890,11532,11533 ,7082,7084,7085 ,0,0,0}, {10926,11070,11531 ,7078,7086,7079 ,0,0,0}, - {11529,11071,11530 ,7081,7080,7077 ,0,0,0}, {11528,10907,10908 ,7071,7073,7047 ,0,0,0}, - {10908,11529,11528 ,7047,7081,7071 ,0,0,0}, {11524,11066,10946 ,7075,7069,7076 ,0,0,0}, - {10943,11525,10946 ,7095,7074,7076 ,0,0,0}, {11527,11525,10943 ,7072,7074,7095 ,0,0,0}, - {9310,11526,9311 ,7068,7070,4899 ,0,0,0}, {11066,11524,11526 ,7069,7075,7070 ,0,0,0}, - {11538,11539,9294 ,7018,7019,7065 ,0,0,0}, {9294,11540,11538 ,7065,7021,7018 ,0,0,0}, - {9294,9277,11540 ,7065,7096,7021 ,0,0,0}, {9294,11541,11542 ,7065,7023,7024 ,0,0,0}, - {11539,11541,9294 ,7019,7023,7065 ,0,0,0}, {9294,11543,11544 ,7065,7025,7026 ,0,0,0}, - {11542,11543,9294 ,7024,7025,7065 ,0,0,0}, {11544,11545,9294 ,7026,7027,7065 ,0,0,0}, - {11546,9294,11547 ,7028,7065,7029 ,0,0,0}, {9294,11545,11547 ,7065,7027,7029 ,0,0,0}, - {11548,9294,11549 ,7030,7065,7031 ,0,0,0}, {9294,11546,11549 ,7065,7028,7031 ,0,0,0}, - {11550,9294,11551 ,7032,7065,7033 ,0,0,0}, {9294,11548,11551 ,7065,7030,7033 ,0,0,0}, - {9293,9294,11550 ,7097,7065,7032 ,0,0,0}, {9276,11064,11540 ,7098,7099,7100 ,0,0,0}, - {11542,11541,11029 ,7101,7102,7103 ,0,0,0}, {11539,11538,11056 ,7104,7105,7076 ,0,0,0}, - {11544,11028,11545 ,7106,7107,7108 ,0,0,0}, {11063,11062,11543 ,7109,7110,7111 ,0,0,0}, - {10940,10937,11546 ,7112,7113,7114 ,0,0,0}, {10940,11547,11057 ,7112,7115,7116 ,0,0,0}, - {10942,10941,11548 ,7117,7118,7119 ,0,0,0}, {11548,11549,10942 ,7119,7120,7117 ,0,0,0}, - {11551,10941,10939 ,7121,7118,7122 ,0,0,0}, {10941,11551,11548 ,7118,7121,7119 ,0,0,0}, - {10938,11550,10939 ,7123,7124,7122 ,0,0,0}, {11551,10939,11550 ,7121,7122,7124 ,0,0,0}, - {10938,9292,9293 ,7123,4831,4831 ,0,0,0}, {9293,11550,10938 ,4831,7124,7123 ,0,0,0}, - {11028,11544,11062 ,7107,7106,7110 ,0,0,0}, {10937,11549,11546 ,7113,7120,7114 ,0,0,0}, - {10942,11549,10937 ,7117,7120,7113 ,0,0,0}, {11029,11541,11055 ,7103,7102,7125 ,0,0,0}, - {11057,11547,11545 ,7116,7115,7108 ,0,0,0}, {10940,11546,11547 ,7112,7114,7115 ,0,0,0}, - {11028,11057,11545 ,7107,7116,7108 ,0,0,0}, {11543,11062,11544 ,7111,7110,7106 ,0,0,0}, - {11542,11029,11063 ,7101,7103,7109 ,0,0,0}, {11063,11543,11542 ,7109,7111,7101 ,0,0,0}, - {11538,11064,11056 ,7105,7099,7076 ,0,0,0}, {11055,11539,11056 ,7125,7104,7076 ,0,0,0}, - {11541,11539,11055 ,7102,7104,7125 ,0,0,0}, {9276,11540,9277 ,7098,7100,4865 ,0,0,0}, - {11064,11538,11540 ,7099,7105,7100 ,0,0,0}, {11552,11553,9260 ,7018,7019,7126 ,0,0,0}, - {9260,11554,11552 ,7126,7021,7018 ,0,0,0}, {9260,9243,11554 ,7126,7127,7021 ,0,0,0}, - {9260,11555,11556 ,7126,7023,7024 ,0,0,0}, {11553,11555,9260 ,7019,7023,7126 ,0,0,0}, - {9260,11557,11558 ,7126,7025,7026 ,0,0,0}, {11556,11557,9260 ,7024,7025,7126 ,0,0,0}, - {11558,11559,9260 ,7026,7027,7126 ,0,0,0}, {11560,9260,11561 ,7028,7126,7029 ,0,0,0}, - {9260,11559,11561 ,7126,7027,7029 ,0,0,0}, {11562,9260,11563 ,7030,7126,7031 ,0,0,0}, - {9260,11560,11563 ,7126,7028,7031 ,0,0,0}, {11564,9260,11565 ,7032,7126,7033 ,0,0,0}, - {9260,11562,11565 ,7126,7030,7033 ,0,0,0}, {9259,9260,11564 ,7128,7126,7032 ,0,0,0}, - {9242,11045,11554 ,7129,7099,7130 ,0,0,0}, {11556,11555,11050 ,7131,7132,7133 ,0,0,0}, - {11553,11552,11044 ,7041,7075,7134 ,0,0,0}, {11558,11051,11559 ,7135,7107,7136 ,0,0,0}, - {11049,11077,11557 ,7137,7138,7139 ,0,0,0}, {10927,10928,11560 ,7140,7141,7142 ,0,0,0}, - {10927,11561,11033 ,7140,7143,7144 ,0,0,0}, {11011,11012,11562 ,7145,7146,7147 ,0,0,0}, - {11562,11563,11011 ,7147,7148,7145 ,0,0,0}, {11565,11012,11097 ,7149,7146,7150 ,0,0,0}, - {11012,11565,11562 ,7146,7149,7147 ,0,0,0}, {11096,11564,11097 ,7151,7152,7150 ,0,0,0}, - {11565,11097,11564 ,7149,7150,7152 ,0,0,0}, {11096,9258,9259 ,7151,7153,4831 ,0,0,0}, - {9259,11564,11096 ,4831,7152,7151 ,0,0,0}, {11051,11558,11077 ,7107,7135,7138 ,0,0,0}, - {10928,11563,11560 ,7141,7148,7142 ,0,0,0}, {11011,11563,10928 ,7145,7148,7141 ,0,0,0}, - {11050,11555,11053 ,7133,7132,7154 ,0,0,0}, {11033,11561,11559 ,7144,7143,7136 ,0,0,0}, - {10927,11560,11561 ,7140,7142,7143 ,0,0,0}, {11051,11033,11559 ,7107,7144,7136 ,0,0,0}, - {11557,11077,11558 ,7139,7138,7135 ,0,0,0}, {11556,11050,11049 ,7131,7133,7137 ,0,0,0}, - {11049,11557,11556 ,7137,7139,7131 ,0,0,0}, {11552,11045,11044 ,7075,7099,7134 ,0,0,0}, - {11053,11553,11044 ,7154,7041,7134 ,0,0,0}, {11555,11553,11053 ,7132,7041,7154 ,0,0,0}, - {9242,11554,9243 ,7129,7130,4929 ,0,0,0}, {11045,11552,11554 ,7099,7075,7130 ,0,0,0}, - {9203,9202,11566 ,4777,21,7155 ,0,0,0}, {10910,10923,11567 ,7156,7157,7158 ,0,0,0}, - {10919,11568,11569 ,7159,7160,7161 ,0,0,0}, {11570,11571,10901 ,7162,7163,7164 ,0,0,0}, - {11572,10967,10925 ,7165,7166,7167 ,0,0,0}, {10978,11022,11573 ,7168,7169,7170 ,0,0,0}, - {10963,11574,11575 ,7171,7172,7173 ,0,0,0}, {10953,11576,10985 ,7174,7175,7176 ,0,0,0}, - {11577,11578,10982 ,7177,7178,7179 ,0,0,0}, {11579,11580,10991 ,7180,7181,7182 ,0,0,0}, - {11581,10983,10985 ,7183,7184,7176 ,0,0,0}, {11582,11583,10992 ,7185,7186,7187 ,0,0,0}, - {11582,10989,11580 ,7185,7188,7181 ,0,0,0}, {10993,11583,11584 ,7189,7186,7190 ,0,0,0}, - {11583,10993,10992 ,7186,7189,7187 ,0,0,0}, {11585,10988,11584 ,7191,7192,7190 ,0,0,0}, - {10993,11584,10988 ,7189,7190,7192 ,0,0,0}, {11585,11586,10986 ,7191,7193,7194 ,0,0,0}, - {10986,10988,11585 ,7194,7192,7191 ,0,0,0}, {10995,11586,11587 ,7195,7193,7196 ,0,0,0}, - {11586,10995,10986 ,7193,7195,7194 ,0,0,0}, {9225,10996,11587 ,7197,7198,7196 ,0,0,0}, - {10995,11587,10996 ,7195,7196,7198 ,0,0,0}, {9226,10996,9225 ,7199,7198,7197 ,0,0,0}, - {10953,11578,11576 ,7174,7178,7175 ,0,0,0}, {10989,10991,11580 ,7188,7182,7181 ,0,0,0}, - {11582,10992,10989 ,7185,7187,7188 ,0,0,0}, {10983,11581,11579 ,7184,7183,7180 ,0,0,0}, - {11579,10991,10983 ,7180,7182,7184 ,0,0,0}, {11581,10985,11576 ,7183,7176,7175 ,0,0,0}, - {11578,10953,10982 ,7178,7174,7179 ,0,0,0}, {10978,11573,11577 ,7168,7170,7177 ,0,0,0}, - {10978,11577,10982 ,7168,7177,7179 ,0,0,0}, {10967,11570,10901 ,7166,7162,7164 ,0,0,0}, - {11575,11022,10963 ,7173,7169,7171 ,0,0,0}, {11022,11575,11573 ,7169,7173,7170 ,0,0,0}, - {10902,10901,11571 ,7200,7164,7163 ,0,0,0}, {10963,10902,11574 ,7171,7200,7172 ,0,0,0}, - {11574,10902,11571 ,7172,7200,7163 ,0,0,0}, {11572,11570,10967 ,7165,7162,7166 ,0,0,0}, - {11588,11572,10925 ,7201,7165,7167 ,0,0,0}, {10910,11567,11588 ,7156,7158,7201 ,0,0,0}, - {10910,11588,10925 ,7156,7201,7167 ,0,0,0}, {11024,11566,11568 ,7202,7155,7160 ,0,0,0}, - {11569,10923,10919 ,7161,7157,7159 ,0,0,0}, {10923,11569,11567 ,7157,7161,7158 ,0,0,0}, - {11024,11568,10919 ,7202,7160,7159 ,0,0,0}, {11566,11024,9203 ,7155,7202,4777 ,0,0,0}, - {9191,11579,9194 ,730,7015,730 ,0,0,0}, {11569,11568,11574 ,730,730,730 ,0,0,0}, - {9201,9197,11578 ,730,730,730 ,0,0,0}, {9195,11581,11576 ,730,730,7015 ,0,0,0}, - {11575,11574,11568 ,730,730,730 ,0,0,0}, {9202,11577,11566 ,730,730,730 ,0,0,0}, - {11572,11588,11567 ,730,730,730 ,0,0,0}, {11567,11569,11571 ,730,730,730 ,0,0,0}, - {11567,11571,11570 ,730,730,730 ,0,0,0}, {11572,11567,11570 ,730,730,730 ,0,0,0}, - {11568,11566,11575 ,730,730,730 ,0,0,0}, {11571,11569,11574 ,730,730,730 ,0,0,0}, - {11566,11573,11575 ,730,730,730 ,0,0,0}, {11577,9202,11578 ,730,730,730 ,0,0,0}, - {11573,11566,11577 ,730,730,730 ,0,0,0}, {11578,9197,11576 ,730,730,7015 ,0,0,0}, - {11578,9202,9201 ,730,730,730 ,0,0,0}, {11581,9195,9194 ,730,730,730 ,0,0,0}, - {11576,9197,9195 ,7015,730,730 ,0,0,0}, {11580,11579,9191 ,730,7015,730 ,0,0,0}, - {11579,11581,9194 ,7015,730,730 ,0,0,0}, {11582,9191,9190 ,7015,730,730 ,0,0,0}, - {9191,11582,11580 ,730,7015,730 ,0,0,0}, {11582,9190,11583 ,7015,730,730 ,0,0,0}, - {9183,11583,9187 ,730,730,730 ,0,0,0}, {11583,9190,9187 ,730,730,730 ,0,0,0}, - {9183,9182,11584 ,730,730,7015 ,0,0,0}, {11584,11583,9183 ,7015,730,730 ,0,0,0}, - {11584,9182,11585 ,7015,730,7015 ,0,0,0}, {9186,11586,11585 ,730,730,7015 ,0,0,0}, - {11585,9182,9186 ,7015,730,730 ,0,0,0}, {11586,9181,11587 ,730,730,7015 ,0,0,0}, - {9181,11586,9186 ,730,730,730 ,0,0,0}, {9177,9225,9181 ,730,7015,730 ,0,0,0}, - {11587,9181,9225 ,7015,730,7015 ,0,0,0}, {9224,9206,9222 ,7015,7015,730 ,0,0,0}, - {9177,9176,9224 ,730,730,7015 ,0,0,0}, {9218,9213,9216 ,7015,7015,7015 ,0,0,0}, - {9210,9219,9207 ,7015,7015,730 ,0,0,0}, {9218,9210,9212 ,7015,7015,7015 ,0,0,0}, - {9213,9218,9212 ,7015,7015,7015 ,0,0,0}, {9222,9207,9219 ,730,730,7015 ,0,0,0}, - {9219,9210,9218 ,7015,7015,7015 ,0,0,0}, {9224,9176,9206 ,7015,730,7015 ,0,0,0}, - {9222,9206,9207 ,730,7015,730 ,0,0,0}, {9224,9225,9177 ,7015,7015,730 ,0,0,0}, - {9153,10884,11589 ,126,7203,7204 ,0,0,0}, {11590,11591,10886 ,7205,7206,7207 ,0,0,0}, - {10936,11592,11004 ,7208,7209,7210 ,0,0,0}, {11025,11027,11593 ,7211,7212,7213 ,0,0,0}, - {11594,10897,11595 ,7214,7215,7216 ,0,0,0}, {11596,11597,10922 ,7217,7218,7219 ,0,0,0}, - {10947,11598,11065 ,7220,7221,7222 ,0,0,0}, {10916,11599,11600 ,7223,7224,7225 ,0,0,0}, - {10914,10915,11601 ,7226,7227,7228 ,0,0,0}, {10912,10906,11602 ,7229,7230,7231 ,0,0,0}, - {11603,10913,10912 ,7232,7233,7229 ,0,0,0}, {10904,10905,11604 ,7234,7235,7236 ,0,0,0}, - {11605,10906,10904 ,7237,7230,7234 ,0,0,0}, {10903,11606,10905 ,7238,7239,7235 ,0,0,0}, - {11604,10905,11606 ,7236,7235,7239 ,0,0,0}, {11607,10903,10896 ,7240,7238,7241 ,0,0,0}, - {10903,11607,11606 ,7238,7240,7239 ,0,0,0}, {10896,10895,11608 ,7241,7242,7243 ,0,0,0}, - {11608,11607,10896 ,7243,7240,7241 ,0,0,0}, {10892,11609,10895 ,7244,7245,7242 ,0,0,0}, - {11608,10895,11609 ,7243,7242,7245 ,0,0,0}, {11610,10892,9175 ,7246,7244,82 ,0,0,0}, - {10892,11610,11609 ,7244,7246,7245 ,0,0,0}, {9173,11610,9175 ,7011,7246,82 ,0,0,0}, - {10913,11603,11599 ,7233,7232,7224 ,0,0,0}, {11602,10906,11605 ,7231,7230,7237 ,0,0,0}, - {11605,10904,11604 ,7237,7234,7236 ,0,0,0}, {11602,11603,10912 ,7231,7232,7229 ,0,0,0}, - {11600,10915,10916 ,7225,7227,7223 ,0,0,0}, {11599,10916,10913 ,7224,7223,7233 ,0,0,0}, - {10915,11600,11601 ,7227,7225,7228 ,0,0,0}, {11596,10914,11601 ,7217,7226,7228 ,0,0,0}, - {11611,11593,11027 ,7247,7213,7212 ,0,0,0}, {10947,10922,11597 ,7220,7219,7218 ,0,0,0}, - {10914,11596,10922 ,7226,7217,7219 ,0,0,0}, {11065,11611,11027 ,7222,7247,7212 ,0,0,0}, - {11065,11598,11611 ,7222,7221,7247 ,0,0,0}, {11597,11598,10947 ,7218,7221,7220 ,0,0,0}, - {10886,11591,10936 ,7207,7206,7208 ,0,0,0}, {11593,11595,11025 ,7213,7216,7211 ,0,0,0}, - {11594,10899,10897 ,7214,7248,7215 ,0,0,0}, {10897,11025,11595 ,7215,7211,7216 ,0,0,0}, - {10899,11590,10886 ,7248,7205,7207 ,0,0,0}, {10899,11594,11590 ,7248,7214,7205 ,0,0,0}, - {11004,11592,11589 ,7210,7209,7204 ,0,0,0}, {11591,11592,10936 ,7206,7209,7208 ,0,0,0}, - {9153,9150,10884 ,126,4726,7203 ,0,0,0}, {11589,10884,11004 ,7204,7203,7210 ,0,0,0}, - {11604,11602,11605 ,7249,7250,7251 ,0,0,0}, {9155,11591,9157 ,726,726,7252 ,0,0,0}, - {11607,11602,11606 ,7253,7250,7253 ,0,0,0}, {11602,11604,11606 ,7250,7249,7253 ,0,0,0}, - {11603,11607,11608 ,7254,7253,7249 ,0,0,0}, {11607,11603,11602 ,7253,7254,7250 ,0,0,0}, - {11608,11609,11599 ,7249,7249,7255 ,0,0,0}, {11599,11603,11608 ,7255,7254,7249 ,0,0,0}, - {11609,11600,11599 ,7249,7256,7255 ,0,0,0}, {11610,9173,11600 ,7257,7257,7256 ,0,0,0}, - {11610,11600,11609 ,7257,7256,7249 ,0,0,0}, {11601,9172,11596 ,7258,726,7259 ,0,0,0}, - {11600,9173,11601 ,7256,7257,7258 ,0,0,0}, {11611,11598,9167 ,7260,7254,7257 ,0,0,0}, - {9169,11597,9172 ,7252,7261,726 ,0,0,0}, {9160,11595,9161 ,726,7262,7252 ,0,0,0}, - {9166,9163,11593 ,726,7252,7263 ,0,0,0}, {11592,9155,9154 ,7253,726,726 ,0,0,0}, - {11590,9160,9157 ,726,726,7252 ,0,0,0}, {9153,9130,9129 ,726,726,726 ,0,0,0}, - {9128,11589,9154 ,7264,7253,726 ,0,0,0}, {9134,9146,9147 ,726,7257,726 ,0,0,0}, - {9129,9135,9149 ,726,7264,726 ,0,0,0}, {9141,9143,9137 ,7257,726,7257 ,0,0,0}, - {9143,9146,9137 ,726,7257,7257 ,0,0,0}, {9141,9137,9139 ,7257,7257,7257 ,0,0,0}, - {9147,9135,9134 ,726,7264,726 ,0,0,0}, {9146,9134,9137 ,7257,726,7257 ,0,0,0}, - {9151,9129,9149 ,726,726,726 ,0,0,0}, {9149,9135,9147 ,726,7264,726 ,0,0,0}, - {9130,9153,11589 ,726,726,7253 ,0,0,0}, {9129,9151,9153 ,726,726,726 ,0,0,0}, - {9154,11589,11592 ,726,7253,7253 ,0,0,0}, {9130,11589,9128 ,726,7253,7264 ,0,0,0}, - {9157,11591,11590 ,7252,726,726 ,0,0,0}, {11591,9155,11592 ,726,726,7253 ,0,0,0}, - {11595,9160,11594 ,7262,726,7262 ,0,0,0}, {11594,9160,11590 ,7262,726,726 ,0,0,0}, - {9163,9161,11593 ,7252,7252,7263 ,0,0,0}, {9161,11595,11593 ,7252,7262,7263 ,0,0,0}, - {11593,11611,9166 ,7263,7260,726 ,0,0,0}, {9169,9167,11598 ,7252,7257,7254 ,0,0,0}, - {9167,9166,11611 ,7257,726,7260 ,0,0,0}, {9172,11597,11596 ,726,7261,7259 ,0,0,0}, - {9169,11598,11597 ,7252,7254,7261 ,0,0,0}, {9172,11601,9173 ,726,7258,7257 ,0,0,0}, - {9103,11612,10878 ,4799,7265,7266 ,0,0,0}, {11613,10880,11614 ,7267,7268,7269 ,0,0,0}, - {10879,11054,11615 ,7270,7271,7272 ,0,0,0}, {11061,11616,10888 ,7273,7274,7275 ,0,0,0}, - {11617,11618,11060 ,7276,7277,7278 ,0,0,0}, {11619,11058,11620 ,7279,7280,7281 ,0,0,0}, - {11078,11030,11621 ,7282,7283,7284 ,0,0,0}, {11079,11622,11623 ,7285,7286,7287 ,0,0,0}, - {10933,11624,10934 ,7288,7289,7290 ,0,0,0}, {11080,11625,10931 ,7291,7292,7293 ,0,0,0}, - {11626,11080,10889 ,7294,7291,7295 ,0,0,0}, {10930,11627,11081 ,7296,7297,7298 ,0,0,0}, - {11628,10930,10931 ,7299,7296,7293 ,0,0,0}, {11082,11081,11629 ,7300,7298,7301 ,0,0,0}, - {11627,11629,11081 ,7297,7301,7298 ,0,0,0}, {11630,11031,11082 ,7302,7303,7300 ,0,0,0}, - {11082,11629,11630 ,7300,7301,7302 ,0,0,0}, {11031,11631,11084 ,7303,7304,7305 ,0,0,0}, - {11631,11031,11630 ,7304,7303,7302 ,0,0,0}, {11083,11084,11632 ,7306,7305,7307 ,0,0,0}, - {11631,11632,11084 ,7304,7307,7305 ,0,0,0}, {11633,9125,11083 ,7308,21,7306 ,0,0,0}, - {11083,11632,11633 ,7306,7307,7308 ,0,0,0}, {9124,9125,11633 ,7309,21,7308 ,0,0,0}, - {10889,11623,11626 ,7295,7287,7294 ,0,0,0}, {11625,11628,10931 ,7292,7299,7293 ,0,0,0}, - {11628,11627,10930 ,7299,7297,7296 ,0,0,0}, {11625,11080,11626 ,7292,7291,7294 ,0,0,0}, - {11622,11079,10934 ,7286,7285,7290 ,0,0,0}, {11623,10889,11079 ,7287,7295,7285 ,0,0,0}, - {10934,11624,11622 ,7290,7289,7286 ,0,0,0}, {11619,11624,10933 ,7279,7289,7288 ,0,0,0}, - {11634,10888,11616 ,7310,7275,7274 ,0,0,0}, {11078,11620,11058 ,7282,7281,7280 ,0,0,0}, - {10933,11058,11619 ,7288,7280,7279 ,0,0,0}, {11030,10888,11634 ,7283,7275,7310 ,0,0,0}, - {11030,11634,11621 ,7283,7310,7284 ,0,0,0}, {11620,11078,11621 ,7281,7282,7284 ,0,0,0}, - {10880,10879,11614 ,7268,7270,7269 ,0,0,0}, {11616,11061,11618 ,7274,7273,7277 ,0,0,0}, - {11617,11060,11059 ,7276,7278,7311 ,0,0,0}, {11060,11618,11061 ,7278,7277,7273 ,0,0,0}, - {11059,10880,11613 ,7311,7268,7267 ,0,0,0}, {11059,11613,11617 ,7311,7267,7276 ,0,0,0}, - {11054,11612,11615 ,7271,7265,7272 ,0,0,0}, {11614,10879,11615 ,7269,7270,7272 ,0,0,0}, - {9103,10878,9100 ,4799,7266,7199 ,0,0,0}, {11612,11054,10878 ,7265,7271,7266 ,0,0,0}, - {11625,9095,9092 ,730,7312,6103 ,0,0,0}, {9088,11629,9091 ,7313,730,730 ,0,0,0}, - {9098,11622,9102 ,7314,7015,7315 ,0,0,0}, {11626,11623,9097 ,730,730,7316 ,0,0,0}, - {11621,11615,11620 ,730,7317,7313 ,0,0,0}, {11624,11612,9103 ,730,7318,7319 ,0,0,0}, - {11613,11614,11634 ,7320,7316,7316 ,0,0,0}, {11616,11618,11613 ,7320,6103,7320 ,0,0,0}, - {11617,11613,11618 ,6111,7320,6103 ,0,0,0}, {11621,11634,11614 ,730,7316,7316 ,0,0,0}, - {11634,11616,11613 ,7316,7320,7320 ,0,0,0}, {11612,11620,11615 ,7318,7313,7317 ,0,0,0}, - {11615,11621,11614 ,7317,730,7316 ,0,0,0}, {11624,11619,11612 ,730,7316,7318 ,0,0,0}, - {11612,11619,11620 ,7318,7316,7313 ,0,0,0}, {9102,11622,9103 ,7315,7015,7319 ,0,0,0}, - {9103,11622,11624 ,7319,7015,730 ,0,0,0}, {9097,11623,9098 ,7316,730,7314 ,0,0,0}, - {9098,11623,11622 ,7314,730,7015 ,0,0,0}, {11626,9097,9095 ,730,7316,7312 ,0,0,0}, - {9092,11628,11625 ,6103,7017,730 ,0,0,0}, {9095,11625,11626 ,7312,730,730 ,0,0,0}, - {11628,9092,11627 ,7017,6103,7017 ,0,0,0}, {9091,11629,11627 ,730,730,7017 ,0,0,0}, - {11627,9092,9091 ,7017,6103,730 ,0,0,0}, {11629,9088,9087 ,730,7313,730 ,0,0,0}, - {9087,9083,11630 ,730,7316,730 ,0,0,0}, {11630,11629,9087 ,730,730,730 ,0,0,0}, - {11631,9083,9085 ,7016,7316,7313 ,0,0,0}, {9083,11631,11630 ,7316,7016,730 ,0,0,0}, - {9079,11632,9085 ,7015,730,7313 ,0,0,0}, {11631,9085,11632 ,7016,7313,730 ,0,0,0}, - {11633,9079,9124 ,730,7015,730 ,0,0,0}, {11633,11632,9079 ,730,730,7015 ,0,0,0}, - {9079,9081,9124 ,7015,7015,730 ,0,0,0}, {9122,9104,9119 ,730,730,730 ,0,0,0}, - {9081,9077,9122 ,7015,730,730 ,0,0,0}, {9116,9112,9113 ,730,730,7017 ,0,0,0}, - {9107,9118,9106 ,7015,7016,730 ,0,0,0}, {9116,9107,9110 ,730,7015,730 ,0,0,0}, - {9112,9116,9110 ,730,730,730 ,0,0,0}, {9119,9106,9118 ,730,730,7016 ,0,0,0}, - {9118,9107,9116 ,7016,7015,730 ,0,0,0}, {9122,9077,9104 ,730,730,730 ,0,0,0}, - {9119,9104,9106 ,730,730,730 ,0,0,0}, {9122,9124,9081 ,730,730,7015 ,0,0,0}, - {9635,11635,11636 ,7321,1711,7322 ,0,0,0}, {9625,9622,11637 ,7323,7324,7325 ,0,0,0}, - {11638,9624,9633 ,7326,7327,7328 ,0,0,0}, {11451,11639,11450 ,7329,7330,7331 ,0,0,0}, - {11640,11641,9629 ,7332,7333,7334 ,0,0,0}, {11448,11642,11447 ,7335,7336,7337 ,0,0,0}, - {11642,11449,11643 ,7336,7338,7339 ,0,0,0}, {11446,11447,11644 ,7340,7337,7341 ,0,0,0}, - {11642,11644,11447 ,7336,7341,7337 ,0,0,0}, {11645,11445,11446 ,1359,1359,7340 ,0,0,0}, - {11446,11644,11645 ,7340,7341,1359 ,0,0,0}, {11643,11449,11450 ,7339,7338,7331 ,0,0,0}, - {11642,11448,11449 ,7336,7335,7338 ,0,0,0}, {11639,11451,11452 ,7330,7329,7342 ,0,0,0}, - {11639,11643,11450 ,7330,7339,7331 ,0,0,0}, {11452,9629,11641 ,7342,7334,7333 ,0,0,0}, - {11641,11639,11452 ,7333,7330,7342 ,0,0,0}, {9628,11637,11640 ,7343,7325,7332 ,0,0,0}, - {9628,11640,9629 ,7343,7332,7334 ,0,0,0}, {9622,11646,11637 ,7324,7344,7325 ,0,0,0}, - {9628,9625,11637 ,7343,7323,7325 ,0,0,0}, {11638,11646,9624 ,7326,7344,7327 ,0,0,0}, - {9622,9624,11646 ,7324,7327,7344 ,0,0,0}, {11638,9632,11636 ,7326,7345,7322 ,0,0,0}, - {9633,9632,11638 ,7328,7345,7326 ,0,0,0}, {11635,9635,9601 ,1711,7321,1711 ,0,0,0}, - {11636,9632,9635 ,7322,7345,7321 ,0,0,0}, {11635,9603,11647 ,2197,7346,7346 ,0,0,0}, - {9603,11635,9601 ,7346,2197,2197 ,0,0,0}, {11648,11649,11455 ,1435,7347,7348 ,0,0,0}, - {11456,11454,11650 ,7349,7350,7351 ,0,0,0}, {11453,11458,11651 ,7352,7353,7354 ,0,0,0}, - {9614,11652,9612 ,7355,7356,7357 ,0,0,0}, {11653,11654,9620 ,7358,7359,7360 ,0,0,0}, - {9608,11655,9606 ,7361,7362,7363 ,0,0,0}, {9608,9610,11655 ,7361,7364,7362 ,0,0,0}, - {9605,9606,11656 ,7365,7363,7366 ,0,0,0}, {11655,11656,9606 ,7362,7366,7363 ,0,0,0}, - {11647,9603,9605 ,1790,1790,7365 ,0,0,0}, {9605,11656,11647 ,7365,7366,1790 ,0,0,0}, - {9612,11657,9610 ,7357,7367,7364 ,0,0,0}, {11655,9610,11657 ,7362,7364,7367 ,0,0,0}, - {11453,11658,11454 ,7352,7368,7350 ,0,0,0}, {9614,9618,11652 ,7355,7369,7356 ,0,0,0}, - {11652,11657,9612 ,7356,7367,7357 ,0,0,0}, {9618,9620,11654 ,7369,7360,7359 ,0,0,0}, - {11654,11652,9618 ,7359,7356,7369 ,0,0,0}, {11653,9620,11457 ,7358,7360,7370 ,0,0,0}, - {11650,11457,11456 ,7351,7370,7349 ,0,0,0}, {11457,11650,11653 ,7370,7351,7358 ,0,0,0}, - {11658,11650,11454 ,7368,7351,7350 ,0,0,0}, {11651,11459,11649 ,7354,7371,7347 ,0,0,0}, - {11459,11651,11458 ,7371,7354,7353 ,0,0,0}, {11658,11453,11651 ,7368,7352,7354 ,0,0,0}, - {11648,11455,11444 ,1435,7348,1435 ,0,0,0}, {11649,11459,11455 ,7347,7371,7348 ,0,0,0}, - {11444,11645,11648 ,1398,7372,1398 ,0,0,0}, {11645,11444,11445 ,7372,1398,7372 ,0,0,0}, - {11645,11649,11648 ,7373,730,730 ,0,0,0}, {11646,11655,11657 ,730,730,730 ,0,0,0}, - {11643,11650,11658 ,7374,7375,7375 ,0,0,0}, {11658,11651,11642 ,7375,730,7373 ,0,0,0}, - {11641,11654,11653 ,7375,7375,7375 ,0,0,0}, {11653,11650,11639 ,7375,7375,730 ,0,0,0}, - {11657,11652,11637 ,730,730,7376 ,0,0,0}, {11652,11654,11640 ,730,7375,7375 ,0,0,0}, - {11636,11656,11638 ,730,730,730 ,0,0,0}, {11655,11638,11656 ,730,730,730 ,0,0,0}, - {11636,11635,11647 ,730,730,730 ,0,0,0}, {11647,11656,11636 ,730,730,730 ,0,0,0}, - {11657,11637,11646 ,730,7376,730 ,0,0,0}, {11655,11646,11638 ,730,730,730 ,0,0,0}, - {11652,11640,11637 ,730,7375,7376 ,0,0,0}, {11654,11641,11640 ,7375,7375,7375 ,0,0,0}, - {11653,11639,11641 ,7375,730,7375 ,0,0,0}, {11650,11643,11639 ,7375,7374,730 ,0,0,0}, - {11658,11642,11643 ,7375,7373,7374 ,0,0,0}, {11651,11644,11642 ,730,730,7373 ,0,0,0}, - {11645,11644,11649 ,7373,730,730 ,0,0,0}, {11651,11649,11644 ,730,730,730 ,0,0,0}, - {11659,9533,11660 ,7377,1435,1435 ,0,0,0}, {11661,9549,11662 ,7378,7379,7379 ,0,0,0}, - {11663,9524,9528 ,7380,7380,7377 ,0,0,0}, {9556,11664,11665 ,7381,7381,7382 ,0,0,0}, - {9551,11666,9554 ,7378,7383,7383 ,0,0,0}, {9563,11667,9565 ,7384,7385,7385 ,0,0,0}, - {11668,9563,9558 ,7384,7384,7382 ,0,0,0}, {9568,9565,11669 ,7386,7385,7386 ,0,0,0}, - {11667,11669,9565 ,7385,7386,7385 ,0,0,0}, {11670,9571,9568 ,7387,7388,7386 ,0,0,0}, - {9568,11669,11670 ,7386,7386,7387 ,0,0,0}, {11665,11668,9558 ,7382,7384,7382 ,0,0,0}, - {11668,11667,9563 ,7384,7385,7384 ,0,0,0}, {9554,11664,9556 ,7383,7381,7381 ,0,0,0}, - {9556,11665,9558 ,7381,7382,7382 ,0,0,0}, {9551,11661,11666 ,7378,7378,7383 ,0,0,0}, - {9554,11666,11664 ,7383,7383,7381 ,0,0,0}, {9549,9524,11662 ,7379,7380,7379 ,0,0,0}, - {9551,9549,11661 ,7378,7379,7378 ,0,0,0}, {11663,9528,11659 ,7380,7377,7377 ,0,0,0}, - {11662,9524,11663 ,7379,7380,7380 ,0,0,0}, {9533,11659,9528 ,1435,7377,7377 ,0,0,0}, - {11660,9530,11671 ,1398,1398,1398 ,0,0,0}, {9530,11660,9533 ,1398,1398,1398 ,0,0,0}, - {11672,11673,9655 ,7389,7390,7390 ,0,0,0}, {11674,9651,11675 ,7391,7391,7392 ,0,0,0}, - {9653,9562,11676 ,7392,7393,7393 ,0,0,0}, {9643,11677,11678 ,7394,7395,7394 ,0,0,0}, - {9648,11679,9647 ,7396,7396,7395 ,0,0,0}, {9638,11680,11681 ,7397,7398,7397 ,0,0,0}, - {11680,9638,9642 ,7398,7397,7398 ,0,0,0}, {11682,9636,11681 ,7399,7399,7397 ,0,0,0}, - {9638,11681,9636 ,7397,7397,7399 ,0,0,0}, {11682,11671,9530 ,7399,1359,1359 ,0,0,0}, - {9530,9636,11682 ,1359,7399,7399 ,0,0,0}, {11675,9653,11676 ,7392,7392,7393 ,0,0,0}, - {9642,9643,11678 ,7398,7394,7394 ,0,0,0}, {11678,11680,9642 ,7394,7398,7398 ,0,0,0}, - {11677,9643,9647 ,7395,7394,7395 ,0,0,0}, {11674,11679,9648 ,7391,7396,7396 ,0,0,0}, - {9647,11679,11677 ,7395,7396,7395 ,0,0,0}, {9653,11675,9651 ,7392,7392,7391 ,0,0,0}, - {9648,9651,11674 ,7396,7391,7391 ,0,0,0}, {9655,11673,9562 ,7390,7390,7393 ,0,0,0}, - {9562,11673,11676 ,7393,7390,7393 ,0,0,0}, {11672,9655,9521 ,7389,7390,7400 ,0,0,0}, - {11670,11672,9521 ,7401,7402,7402 ,0,0,0}, {11670,9521,9571 ,7401,7402,7401 ,0,0,0}, - {11682,11663,11659 ,7403,7403,7404 ,0,0,0}, {11668,11676,11667 ,7375,7375,730 ,0,0,0}, - {11664,11674,11665 ,7375,730,730 ,0,0,0}, {11675,11668,11665 ,730,7375,730 ,0,0,0}, - {11661,11677,11666 ,7373,7375,7373 ,0,0,0}, {11679,11664,11666 ,730,7375,7373 ,0,0,0}, - {11662,11681,11680 ,7405,7406,730 ,0,0,0}, {11678,11661,11662 ,7373,7373,7405 ,0,0,0}, - {11682,11681,11663 ,7403,7406,7403 ,0,0,0}, {11659,11660,11671 ,7404,730,7407 ,0,0,0}, - {11671,11682,11659 ,7407,7403,7404 ,0,0,0}, {11681,11662,11663 ,7406,7405,7403 ,0,0,0}, - {11678,11662,11680 ,7373,7405,730 ,0,0,0}, {11677,11661,11678 ,7375,7373,7373 ,0,0,0}, - {11679,11666,11677 ,730,7373,7375 ,0,0,0}, {11674,11664,11679 ,730,7375,730 ,0,0,0}, - {11675,11665,11674 ,730,730,730 ,0,0,0}, {11676,11668,11675 ,7375,7375,730 ,0,0,0}, - {11673,11667,11676 ,730,730,7375 ,0,0,0}, {11669,11673,11672 ,7373,730,730 ,0,0,0}, - {11673,11669,11667 ,730,7373,730 ,0,0,0}, {11669,11672,11670 ,7373,730,7405 ,0,0,0}, - {11683,11442,11684 ,7408,7409,7410 ,0,0,0}, {11685,11440,11686 ,7411,7412,7412 ,0,0,0}, - {11687,11439,11443 ,7413,7413,7408 ,0,0,0}, {11460,11688,11689 ,7414,7414,7415 ,0,0,0}, - {11441,11690,11461 ,7411,7416,7416 ,0,0,0}, {11437,11691,11438 ,7417,7418,7418 ,0,0,0}, - {11692,11437,11436 ,7417,7417,7415 ,0,0,0}, {11434,11438,11693 ,7419,7418,7419 ,0,0,0}, - {11691,11693,11438 ,7418,7419,7418 ,0,0,0}, {11694,11433,11434 ,1790,1790,7419 ,0,0,0}, - {11434,11693,11694 ,7419,7419,1790 ,0,0,0}, {11689,11692,11436 ,7415,7417,7415 ,0,0,0}, - {11692,11691,11437 ,7417,7418,7417 ,0,0,0}, {11461,11688,11460 ,7416,7414,7414 ,0,0,0}, - {11460,11689,11436 ,7414,7415,7415 ,0,0,0}, {11441,11685,11690 ,7411,7411,7416 ,0,0,0}, - {11461,11690,11688 ,7416,7416,7414 ,0,0,0}, {11440,11439,11686 ,7412,7413,7412 ,0,0,0}, - {11441,11440,11685 ,7411,7412,7411 ,0,0,0}, {11687,11443,11683 ,7413,7408,7408 ,0,0,0}, - {11686,11439,11687 ,7412,7413,7413 ,0,0,0}, {11442,11683,11443 ,7409,7408,7408 ,0,0,0}, - {11463,11695,11684 ,7420,7420,7421 ,0,0,0}, {11463,11684,11442 ,7420,7421,7421 ,0,0,0}, - {11696,11697,11472 ,1711,7422,7422 ,0,0,0}, {11698,11470,11699 ,7423,7423,7424 ,0,0,0}, - {11471,11462,11700 ,7424,7425,7425 ,0,0,0}, {11467,11701,11702 ,7426,7427,7426 ,0,0,0}, - {11469,11703,11468 ,7428,7428,7427 ,0,0,0}, {11465,11704,11705 ,7429,7430,7429 ,0,0,0}, - {11704,11465,11466 ,7430,7429,7430 ,0,0,0}, {11706,11464,11705 ,7431,7431,7429 ,0,0,0}, - {11465,11705,11464 ,7429,7429,7431 ,0,0,0}, {11706,11695,11463 ,7431,7432,82 ,0,0,0}, - {11463,11464,11706 ,82,7431,7431 ,0,0,0}, {11699,11471,11700 ,7424,7424,7425 ,0,0,0}, - {11466,11467,11702 ,7430,7426,7426 ,0,0,0}, {11702,11704,11466 ,7426,7430,7430 ,0,0,0}, - {11701,11467,11468 ,7427,7426,7427 ,0,0,0}, {11698,11703,11469 ,7423,7428,7428 ,0,0,0}, - {11468,11703,11701 ,7427,7428,7427 ,0,0,0}, {11471,11699,11470 ,7424,7424,7423 ,0,0,0}, - {11469,11470,11698 ,7428,7423,7423 ,0,0,0}, {11472,11697,11462 ,7422,7422,7425 ,0,0,0}, - {11462,11697,11700 ,7425,7422,7425 ,0,0,0}, {11696,11472,11435 ,1711,7422,1711 ,0,0,0}, - {11435,11694,11696 ,2197,2197,2197 ,0,0,0}, {11694,11435,11433 ,2197,2197,2197 ,0,0,0}, - {11694,11697,11696 ,7433,730,730 ,0,0,0}, {11685,11686,11702 ,7375,7375,730 ,0,0,0}, - {11689,11699,11692 ,730,730,730 ,0,0,0}, {11699,11700,11691 ,730,7376,730 ,0,0,0}, - {11690,11703,11688 ,730,730,7376 ,0,0,0}, {11698,11689,11688 ,730,730,7376 ,0,0,0}, - {11701,11690,11685 ,7376,730,7375 ,0,0,0}, {11705,11687,11683 ,7375,7376,7376 ,0,0,0}, - {11686,11687,11704 ,7375,7376,7375 ,0,0,0}, {11684,11706,11683 ,7374,7376,7376 ,0,0,0}, - {11705,11683,11706 ,7375,7376,7376 ,0,0,0}, {11695,11706,11684 ,730,7376,7374 ,0,0,0}, - {11704,11687,11705 ,7375,7376,7375 ,0,0,0}, {11702,11686,11704 ,730,7375,7375 ,0,0,0}, - {11701,11685,11702 ,7376,7375,730 ,0,0,0}, {11703,11690,11701 ,730,730,7376 ,0,0,0}, - {11698,11688,11703 ,730,7376,730 ,0,0,0}, {11699,11689,11698 ,730,730,730 ,0,0,0}, - {11699,11691,11692 ,730,730,730 ,0,0,0}, {11700,11693,11691 ,7376,7433,730 ,0,0,0}, - {11694,11693,11697 ,7433,7433,730 ,0,0,0}, {11700,11697,11693 ,7376,730,7433 ,0,0,0}, - {10870,9043,9041 ,7434,4326,7435 ,0,0,0}, {11042,10970,10867 ,7436,7437,7438 ,0,0,0}, - {10871,10969,10872 ,7439,7440,7441 ,0,0,0}, {10877,10865,11013 ,7442,7443,7444 ,0,0,0}, - {10875,11018,11076 ,7445,7446,7447 ,0,0,0}, {11021,11020,10855 ,7448,7449,7450 ,0,0,0}, - {11005,10873,10874 ,7451,7452,7453 ,0,0,0}, {10849,10848,10920 ,7454,7455,7456 ,0,0,0}, - {10851,10909,10911 ,7457,7458,7459 ,0,0,0}, {10839,10956,10843 ,7460,7461,7462 ,0,0,0}, - {10962,10921,10847 ,7463,7464,7465 ,0,0,0}, {10954,10881,10833 ,7466,7467,7468 ,0,0,0}, - {10957,10835,10881 ,7469,7470,7467 ,0,0,0}, {11026,10830,10837 ,7471,7472,7473 ,0,0,0}, - {10834,10830,10955 ,7474,7472,7475 ,0,0,0}, {10949,10838,10842 ,7476,7477,7478 ,0,0,0}, - {10837,10838,10948 ,7473,7477,7479 ,0,0,0}, {10845,10932,10842 ,7480,7481,7478 ,0,0,0}, - {10949,10842,10932 ,7476,7478,7481 ,0,0,0}, {10845,10854,10924 ,7480,7482,7483 ,0,0,0}, - {10924,10932,10845 ,7483,7481,7480 ,0,0,0}, {10898,10854,10853 ,7484,7482,7485 ,0,0,0}, - {10854,10898,10924 ,7482,7484,7483 ,0,0,0}, {10857,10887,10853 ,7486,7487,7485 ,0,0,0}, - {10898,10853,10887 ,7484,7485,7487 ,0,0,0}, {10857,10862,10885 ,7486,7488,7489 ,0,0,0}, - {10885,10887,10857 ,7489,7487,7486 ,0,0,0}, {10935,10862,10861 ,7490,7488,7491 ,0,0,0}, - {10862,10935,10885 ,7488,7490,7489 ,0,0,0}, {9075,10883,10861 ,82,7492,7491 ,0,0,0}, - {10935,10861,10883 ,7490,7491,7492 ,0,0,0}, {9074,10883,9075 ,82,7492,82 ,0,0,0}, - {10948,11026,10837 ,7479,7471,7473 ,0,0,0}, {10948,10838,10949 ,7479,7477,7476 ,0,0,0}, - {10834,10955,10954 ,7474,7475,7466 ,0,0,0}, {10955,10830,11026 ,7475,7472,7471 ,0,0,0}, - {10881,10835,10833 ,7467,7470,7468 ,0,0,0}, {10954,10833,10834 ,7466,7468,7474 ,0,0,0}, - {10957,10956,10839 ,7469,7461,7460 ,0,0,0}, {10957,10839,10835 ,7469,7460,7470 ,0,0,0}, - {10843,10962,10847 ,7462,7463,7465 ,0,0,0}, {10956,10962,10843 ,7461,7463,7462 ,0,0,0}, - {10848,10921,10920 ,7455,7464,7456 ,0,0,0}, {10847,10921,10848 ,7465,7464,7455 ,0,0,0}, - {10851,10849,10909 ,7457,7454,7458 ,0,0,0}, {10849,10920,10909 ,7454,7456,7458 ,0,0,0}, - {11021,10856,10911 ,7448,7493,7459 ,0,0,0}, {10856,10851,10911 ,7493,7457,7459 ,0,0,0}, - {11020,10874,10855 ,7449,7453,7450 ,0,0,0}, {11021,10855,10856 ,7448,7450,7493 ,0,0,0}, - {11005,11014,10873 ,7451,7494,7452 ,0,0,0}, {11020,11005,10874 ,7449,7451,7453 ,0,0,0}, - {11013,10865,11014 ,7444,7443,7494 ,0,0,0}, {10873,11014,10865 ,7452,7494,7443 ,0,0,0}, - {10875,10877,11018 ,7445,7442,7446 ,0,0,0}, {10877,11013,11018 ,7442,7444,7446 ,0,0,0}, - {11042,10866,11076 ,7436,7495,7447 ,0,0,0}, {10866,10875,11076 ,7495,7445,7447 ,0,0,0}, - {10970,10871,10867 ,7437,7439,7438 ,0,0,0}, {11042,10867,10866 ,7436,7438,7495 ,0,0,0}, - {10969,10971,10872 ,7440,7496,7441 ,0,0,0}, {10970,10969,10871 ,7437,7440,7439 ,0,0,0}, - {9043,10870,10971 ,4326,7434,7496 ,0,0,0}, {10872,10971,10870 ,7441,7496,7434 ,0,0,0}, - {11707,8991,8990 ,7497,763,7498 ,0,0,0}, {11708,10863,11709 ,7499,7500,7501 ,0,0,0}, - {11710,10876,10868 ,7502,7503,7504 ,0,0,0}, {11711,11712,10852 ,7505,7506,7507 ,0,0,0}, - {11713,11714,10860 ,7508,7509,7510 ,0,0,0}, {11715,10840,11716 ,7511,7512,7513 ,0,0,0}, - {10844,11717,11716 ,7514,7515,7513 ,0,0,0}, {11718,10832,11719 ,7516,7517,7518 ,0,0,0}, - {10831,11715,11719 ,7519,7511,7518 ,0,0,0}, {11720,10846,10841 ,7520,7521,7522 ,0,0,0}, - {10841,11718,11720 ,7522,7516,7520 ,0,0,0}, {10846,11721,10858 ,7521,7523,7524 ,0,0,0}, - {11721,10846,11720 ,7523,7521,7520 ,0,0,0}, {10859,10858,11722 ,7525,7524,7526 ,0,0,0}, - {11721,11722,10858 ,7523,7526,7524 ,0,0,0}, {9009,10859,11723 ,761,7525,7527 ,0,0,0}, - {10859,11722,11723 ,7525,7526,7527 ,0,0,0}, {9008,10859,9009 ,761,7525,761 ,0,0,0}, - {10831,11719,10832 ,7519,7518,7517 ,0,0,0}, {10841,10832,11718 ,7522,7517,7516 ,0,0,0}, - {10836,10840,11715 ,7528,7512,7511 ,0,0,0}, {10831,10836,11715 ,7519,7528,7511 ,0,0,0}, - {10850,11717,10844 ,7529,7515,7514 ,0,0,0}, {10840,10844,11716 ,7512,7514,7513 ,0,0,0}, - {10852,11712,10850 ,7507,7506,7529 ,0,0,0}, {11717,10850,11712 ,7515,7529,7506 ,0,0,0}, - {10860,11714,10852 ,7510,7509,7507 ,0,0,0}, {11714,11711,10852 ,7509,7505,7507 ,0,0,0}, - {10864,11708,11713 ,7530,7499,7508 ,0,0,0}, {10864,11713,10860 ,7530,7508,7510 ,0,0,0}, - {10863,10876,11709 ,7500,7503,7501 ,0,0,0}, {10864,10863,11708 ,7530,7500,7499 ,0,0,0}, - {11710,10868,11707 ,7502,7504,7497 ,0,0,0}, {11709,10876,11710 ,7501,7503,7502 ,0,0,0}, - {8991,11707,10869 ,763,7497,7531 ,0,0,0}, {11707,10868,10869 ,7497,7504,7531 ,0,0,0}, - {11722,11721,11720 ,7015,7532,7017 ,0,0,0}, {8995,11709,11710 ,7016,7015,7015 ,0,0,0}, - {11715,11718,11719 ,7533,7534,7535 ,0,0,0}, {11720,11715,11722 ,7017,7533,7015 ,0,0,0}, - {11722,11715,11723 ,7015,7533,7016 ,0,0,0}, {11715,11720,11718 ,7533,7017,7534 ,0,0,0}, - {11716,11723,11715 ,7536,7016,7533 ,0,0,0}, {11723,11717,9009 ,7016,730,7015 ,0,0,0}, - {11717,11723,11716 ,730,7016,7536 ,0,0,0}, {11714,9004,11711 ,7535,730,7320 ,0,0,0}, - {11717,11712,9009 ,730,6104,7015 ,0,0,0}, {11708,8998,11713 ,730,730,7534 ,0,0,0}, - {9001,11714,11713 ,7537,7535,7534 ,0,0,0}, {11707,8990,8994 ,7016,7015,730 ,0,0,0}, - {11710,8996,8995 ,7015,730,7016 ,0,0,0}, {8987,8975,8989 ,730,730,730 ,0,0,0}, - {8989,8973,8990 ,730,7016,7015 ,0,0,0}, {8986,8983,8987 ,730,730,730 ,0,0,0}, - {8975,8981,8980 ,730,7016,7016 ,0,0,0}, {8983,8975,8987 ,730,730,730 ,0,0,0}, - {8975,8974,8989 ,730,730,730 ,0,0,0}, {8975,8983,8981 ,730,730,7016 ,0,0,0}, - {8973,8994,8990 ,7016,730,7015 ,0,0,0}, {8974,8973,8989 ,730,7016,730 ,0,0,0}, - {8996,11710,8994 ,730,7015,730 ,0,0,0}, {8994,11710,11707 ,730,7015,7016 ,0,0,0}, - {8995,8998,11709 ,7016,730,7015 ,0,0,0}, {11713,8998,9000 ,7534,730,7537 ,0,0,0}, - {11709,8998,11708 ,7015,730,730 ,0,0,0}, {11713,9000,9001 ,7534,7537,7537 ,0,0,0}, - {9004,11712,11711 ,730,6104,7320 ,0,0,0}, {11714,9001,9004 ,7535,7537,730 ,0,0,0}, - {9009,11712,9006 ,7015,6104,730 ,0,0,0}, {9004,9006,11712 ,730,730,6104 ,0,0,0}, - {9918,9917,11724 ,7538,7539,7540 ,0,0,0}, {11725,9909,9918 ,7541,7542,7538 ,0,0,0}, - {11725,11726,9909 ,7541,82,7542 ,0,0,0}, {11724,11725,9918 ,7540,7541,7538 ,0,0,0}, - {9917,10288,11727 ,7539,7543,7544 ,0,0,0}, {9947,9946,11728 ,7545,7546,7547 ,0,0,0}, - {11729,11727,10288 ,7548,7544,7543 ,0,0,0}, {10288,9947,11729 ,7543,7545,7548 ,0,0,0}, - {11728,11729,9947 ,7547,7548,7545 ,0,0,0}, {9917,11727,11724 ,7539,7544,7540 ,0,0,0}, - {11728,9946,11730 ,7547,7546,7549 ,0,0,0}, {9945,11731,11730 ,7550,7551,7549 ,0,0,0}, - {11730,9946,9945 ,7549,7546,7550 ,0,0,0}, {11731,9945,9920 ,7551,7550,7552 ,0,0,0}, - {9933,11732,9920 ,7553,7554,7552 ,0,0,0}, {9933,9923,11733 ,7553,7555,7556 ,0,0,0}, - {9933,11733,11732 ,7553,7556,7554 ,0,0,0}, {11734,9914,11735 ,7557,7558,7559 ,0,0,0}, - {11733,9923,11734 ,7556,7555,7557 ,0,0,0}, {11734,9923,9914 ,7557,7555,7558 ,0,0,0}, - {9914,9916,11735 ,7558,7559,7559 ,0,0,0}, {11731,9920,11732 ,7551,7552,7554 ,0,0,0}, - {9910,11726,11736 ,7560,82,7561 ,0,0,0}, {11726,9910,9909 ,82,7560,7542 ,0,0,0}, - {11737,9952,11736 ,7562,7563,7561 ,0,0,0}, {9910,11736,9952 ,7560,7561,7563 ,0,0,0}, - {11737,11738,10166 ,7562,7564,7565 ,0,0,0}, {10166,9952,11737 ,7565,7563,7562 ,0,0,0}, - {9991,11738,11739 ,7566,7564,7567 ,0,0,0}, {11738,9991,10166 ,7564,7566,7565 ,0,0,0}, - {11740,9992,11739 ,7568,7569,7567 ,0,0,0}, {9991,11739,9992 ,7566,7567,7569 ,0,0,0}, - {11740,11741,9988 ,7568,7570,7571 ,0,0,0}, {9988,9992,11740 ,7571,7569,7568 ,0,0,0}, - {9956,11741,11742 ,7572,7570,7573 ,0,0,0}, {11741,9956,9988 ,7570,7572,7571 ,0,0,0}, - {11743,9975,11742 ,7574,7575,7573 ,0,0,0}, {9956,11742,9975 ,7572,7573,7575 ,0,0,0}, - {11743,11744,9976 ,7574,7576,7577 ,0,0,0}, {9976,9975,11743 ,7577,7575,7574 ,0,0,0}, - {9978,11744,11745 ,7578,7576,7579 ,0,0,0}, {11744,9978,9976 ,7576,7578,7577 ,0,0,0}, - {9978,11745,9979 ,7578,7579,7580 ,0,0,0}, {9979,11745,11746 ,7580,7579,7580 ,0,0,0}, - {10804,10810,11746 ,7581,7581,7581 ,0,0,0}, {11746,9416,10795 ,7581,7581,7581 ,0,0,0}, - {10795,10801,11746 ,7581,7581,7581 ,0,0,0}, {10815,11746,10810 ,7581,7581,7581 ,0,0,0}, - {10801,10804,11746 ,7581,7581,7581 ,0,0,0}, {10819,10778,11746 ,7581,7581,7581 ,0,0,0}, - {10819,11746,10815 ,7581,7581,7581 ,0,0,0}, {10778,10790,11746 ,7581,7581,7581 ,0,0,0}, - {9979,11746,10789 ,7581,7581,7581 ,0,0,0}, {10790,10789,11746 ,7581,7581,7581 ,0,0,0}, - {11735,9916,10362 ,7582,7582,7582 ,0,0,0}, {10362,10389,11735 ,7582,7582,7582 ,0,0,0}, - {11735,10375,10355 ,7582,7582,7582 ,0,0,0}, {10389,10375,11735 ,7582,7582,7582 ,0,0,0}, - {11735,10357,10371 ,7582,7582,7582 ,0,0,0}, {10355,10357,11735 ,7582,7582,7582 ,0,0,0}, - {11735,10364,10348 ,7582,7582,7582 ,0,0,0}, {10371,10364,11735 ,7582,7582,7582 ,0,0,0}, - {10352,11735,10347 ,7582,7582,7582 ,0,0,0}, {10348,10347,11735 ,7582,7582,7582 ,0,0,0}, - {11743,9421,9419 ,726,726,726 ,0,0,0}, {11736,11726,9421 ,726,726,726 ,0,0,0}, - {11745,11744,9419 ,726,726,726 ,0,0,0}, {9419,11744,11743 ,726,726,726 ,0,0,0}, - {9419,9413,11746 ,726,726,726 ,0,0,0}, {11746,11745,9419 ,726,726,726 ,0,0,0}, - {9422,9416,11746 ,7583,7583,726 ,0,0,0}, {9422,11746,9413 ,7583,726,726 ,0,0,0}, - {11743,11742,9421 ,726,726,726 ,0,0,0}, {9421,11741,11740 ,726,726,726 ,0,0,0}, - {11742,11741,9421 ,726,726,726 ,0,0,0}, {9421,11739,11738 ,726,726,726 ,0,0,0}, - {11740,11739,9421 ,726,726,726 ,0,0,0}, {9421,11737,11736 ,726,726,726 ,0,0,0}, - {11738,11737,9421 ,726,726,726 ,0,0,0}, {11725,9421,11726 ,726,726,726 ,0,0,0}, - {11724,11727,9421 ,726,726,726 ,0,0,0}, {11724,9421,11725 ,726,726,726 ,0,0,0}, - {11729,11728,9421 ,726,726,726 ,0,0,0}, {11729,9421,11727 ,726,726,726 ,0,0,0}, - {11730,11731,9421 ,726,726,726 ,0,0,0}, {11730,9421,11728 ,726,726,726 ,0,0,0}, - {11732,11733,9421 ,726,726,726 ,0,0,0}, {11732,9421,11731 ,726,726,726 ,0,0,0}, - {9421,11733,11473 ,726,726,726 ,0,0,0}, {11735,11473,11734 ,726,726,726 ,0,0,0}, - {11473,11733,11734 ,726,726,726 ,0,0,0}, {11474,11473,11735 ,726,726,726 ,0,0,0}, - {10352,11486,11735 ,7583,726,726 ,0,0,0}, {11474,11735,11486 ,726,726,726 ,0,0,0}, - {8951,11747,10205 ,7584,7585,7586 ,0,0,0}, {11748,10178,11749 ,7587,7588,7589 ,0,0,0}, - {10216,10138,11750 ,7590,7591,7592 ,0,0,0}, {9905,11751,10167 ,7593,7594,7595 ,0,0,0}, - {11752,11753,9908 ,4334,7596,7597 ,0,0,0}, {11754,9913,11755 ,7598,7599,7600 ,0,0,0}, - {9912,10170,11756 ,7601,7602,7603 ,0,0,0}, {9970,9962,11757 ,7604,7605,7606 ,0,0,0}, - {9966,11758,9962 ,7607,7608,7605 ,0,0,0}, {9967,11759,11760 ,7609,7610,7611 ,0,0,0}, - {9970,11761,9969 ,7604,7612,7613 ,0,0,0}, {11762,9980,11760 ,7614,7615,7611 ,0,0,0}, - {9967,11760,9980 ,7609,7611,7615 ,0,0,0}, {11762,11763,9973 ,7614,7616,7617 ,0,0,0}, - {9973,9980,11762 ,7617,7615,7614 ,0,0,0}, {9982,11763,11764 ,7618,7616,7619 ,0,0,0}, - {11763,9982,9973 ,7616,7618,7617 ,0,0,0}, {11765,9942,11764 ,7620,7621,7619 ,0,0,0}, - {9982,11764,9942 ,7618,7619,7621 ,0,0,0}, {11765,8970,8971 ,7620,7622,4289 ,0,0,0}, - {8971,9942,11765 ,4289,7621,7620 ,0,0,0}, {11757,9962,11758 ,7606,7605,7608 ,0,0,0}, - {11759,9969,11761 ,7610,7613,7612 ,0,0,0}, {9969,11759,9967 ,7613,7610,7609 ,0,0,0}, - {11757,11761,9970 ,7606,7612,7604 ,0,0,0}, {11754,11758,9966 ,7598,7608,7607 ,0,0,0}, - {9912,11756,11755 ,7601,7603,7600 ,0,0,0}, {9912,11755,9913 ,7601,7600,7599 ,0,0,0}, - {9966,9913,11754 ,7607,7599,7598 ,0,0,0}, {10170,11766,11756 ,7602,7623,7603 ,0,0,0}, - {11766,10170,10167 ,7623,7602,7595 ,0,0,0}, {11753,11751,9905 ,7596,7594,7593 ,0,0,0}, - {11751,11766,10167 ,7594,7623,7595 ,0,0,0}, {9908,11753,9905 ,7597,7596,7593 ,0,0,0}, - {10206,11748,11752 ,7624,7587,4334 ,0,0,0}, {10206,11752,9908 ,7624,4334,7597 ,0,0,0}, - {10178,10216,11749 ,7588,7590,7589 ,0,0,0}, {10206,10178,11748 ,7624,7588,7587 ,0,0,0}, - {10138,11747,11750 ,7591,7585,7592 ,0,0,0}, {11749,10216,11750 ,7589,7590,7592 ,0,0,0}, - {8951,10205,8949 ,7584,7586,4535 ,0,0,0}, {11747,10138,10205 ,7585,7591,7586 ,0,0,0}, - {11753,8962,11751 ,726,7625,726 ,0,0,0}, {11762,11760,11763 ,726,726,726 ,0,0,0}, - {11765,11764,11763 ,726,726,726 ,0,0,0}, {11761,11757,11759 ,726,726,726 ,0,0,0}, - {11763,11760,11757 ,726,726,726 ,0,0,0}, {11763,11757,11758 ,726,726,726 ,0,0,0}, - {11759,11757,11760 ,726,726,726 ,0,0,0}, {11758,11754,11765 ,726,726,726 ,0,0,0}, - {11765,11763,11758 ,726,726,726 ,0,0,0}, {11754,11755,8968 ,726,726,7626 ,0,0,0}, - {11754,8970,11765 ,726,726,726 ,0,0,0}, {11766,8964,8965 ,726,726,726 ,0,0,0}, - {8965,8968,11756 ,726,7626,726 ,0,0,0}, {11749,8953,8956 ,726,7627,726 ,0,0,0}, - {8958,8959,11752 ,726,7625,726 ,0,0,0}, {11750,8952,8953 ,7626,7627,7627 ,0,0,0}, - {8948,8933,8932 ,7626,7625,726 ,0,0,0}, {8951,8932,11747 ,726,726,726 ,0,0,0}, - {8944,8935,8945 ,726,7627,7625 ,0,0,0}, {8935,8944,8942 ,7627,726,726 ,0,0,0}, - {8944,8945,8939 ,726,7625,7627 ,0,0,0}, {8945,8948,8947 ,7625,7626,7628 ,0,0,0}, - {8935,8933,8945 ,7627,7625,7625 ,0,0,0}, {8935,8942,8936 ,7627,726,726 ,0,0,0}, - {8951,8948,8932 ,726,7626,726 ,0,0,0}, {8948,8945,8933 ,7626,7625,7625 ,0,0,0}, - {8930,11747,8932 ,726,726,726 ,0,0,0}, {11750,11747,8952 ,7626,726,7627 ,0,0,0}, - {8930,8952,11747 ,726,7627,726 ,0,0,0}, {11749,8956,11748 ,726,726,726 ,0,0,0}, - {8953,11749,11750 ,7627,726,7626 ,0,0,0}, {8958,11752,11748 ,726,726,726 ,0,0,0}, - {11748,8956,8958 ,726,726,726 ,0,0,0}, {8959,8962,11753 ,7625,7625,726 ,0,0,0}, - {11752,8959,11753 ,726,7625,726 ,0,0,0}, {11751,8964,11766 ,726,726,726 ,0,0,0}, - {11751,8962,8964 ,726,7625,726 ,0,0,0}, {8968,11755,11756 ,7626,726,726 ,0,0,0}, - {11756,11766,8965 ,726,726,726 ,0,0,0}, {8968,8970,11754 ,7626,726,726 ,0,0,0}, - {8912,11767,10186 ,4303,7629,7630 ,0,0,0}, {10109,10143,11768 ,7631,7632,7633 ,0,0,0}, - {10275,10187,11769 ,7634,7635,7636 ,0,0,0}, {10171,11770,10172 ,7637,7638,7639 ,0,0,0}, - {11771,11772,10108 ,7640,7641,7642 ,0,0,0}, {11773,11774,9953 ,7643,7644,7645 ,0,0,0}, - {11773,10173,11775 ,7643,7646,7647 ,0,0,0}, {11776,11777,9951 ,7648,7649,7650 ,0,0,0}, - {9951,9950,11776 ,7650,7651,7648 ,0,0,0}, {10134,11777,11778 ,7652,7649,7653 ,0,0,0}, - {11777,10134,9951 ,7649,7652,7650 ,0,0,0}, {11779,10133,11778 ,7654,7655,7653 ,0,0,0}, - {10134,11778,10133 ,7652,7653,7655 ,0,0,0}, {11779,8926,8927 ,7654,126,7656 ,0,0,0}, - {8927,10133,11779 ,7656,7655,7654 ,0,0,0}, {11770,10171,11772 ,7638,7637,7641 ,0,0,0}, - {11774,9950,9953 ,7644,7651,7645 ,0,0,0}, {11776,9950,11774 ,7648,7651,7644 ,0,0,0}, - {11768,10143,11780 ,7633,7632,7657 ,0,0,0}, {11775,10173,10172 ,7647,7646,7639 ,0,0,0}, - {11773,9953,10173 ,7643,7645,7646 ,0,0,0}, {11770,11775,10172 ,7638,7647,7639 ,0,0,0}, - {10108,11772,10171 ,7642,7641,7637 ,0,0,0}, {10109,11768,11771 ,7631,7633,7640 ,0,0,0}, - {11771,10108,10109 ,7640,7642,7631 ,0,0,0}, {10187,11767,11769 ,7635,7629,7636 ,0,0,0}, - {11780,10275,11769 ,7657,7634,7636 ,0,0,0}, {10143,10275,11780 ,7632,7634,7657 ,0,0,0}, - {8912,10186,8913 ,4303,7630,82 ,0,0,0}, {11767,10187,10186 ,7629,7635,7630 ,0,0,0}, - {11774,11773,8909 ,726,7658,7659 ,0,0,0}, {11767,11772,11768 ,7660,7661,726 ,0,0,0}, - {11767,11770,11772 ,7660,7661,7661 ,0,0,0}, {8911,11775,8912 ,7659,726,726 ,0,0,0}, - {11771,11768,11772 ,7661,726,7661 ,0,0,0}, {11769,11767,11768 ,7659,7660,726 ,0,0,0}, - {11770,11767,8912 ,7661,7660,726 ,0,0,0}, {11780,11769,11768 ,726,7659,726 ,0,0,0}, - {11770,8912,11775 ,7661,726,726 ,0,0,0}, {8909,11773,8911 ,7659,7658,7659 ,0,0,0}, - {8911,11773,11775 ,7659,7658,726 ,0,0,0}, {8907,11776,11774 ,726,5488,726 ,0,0,0}, - {8909,8907,11774 ,7659,726,726 ,0,0,0}, {8905,11776,8907 ,726,5488,726 ,0,0,0}, - {8905,11777,11776 ,726,7662,5488 ,0,0,0}, {11778,11777,8902 ,5471,7662,7661 ,0,0,0}, - {8905,8902,11777 ,726,7661,7662 ,0,0,0}, {8901,11778,8902 ,726,5471,7661 ,0,0,0}, - {11779,8901,8899 ,7663,726,7661 ,0,0,0}, {8901,11779,11778 ,726,7663,5471 ,0,0,0}, - {8898,8926,8899 ,7658,726,7661 ,0,0,0}, {11779,8899,8926 ,7663,7661,726 ,0,0,0}, - {8918,8914,8915 ,7658,7664,726 ,0,0,0}, {8918,8924,8914 ,7658,7665,7664 ,0,0,0}, - {8921,8918,8920 ,7666,7658,7667 ,0,0,0}, {8921,8924,8918 ,7666,7665,7658 ,0,0,0}, - {8926,8898,8924 ,726,7658,7665 ,0,0,0}, {8914,8924,8898 ,7664,7665,7658 ,0,0,0}, - {11781,9452,11782 ,726,726,726 ,0,0,0}, {9452,11783,11782 ,726,726,726 ,0,0,0}, - {11784,11785,9452 ,726,726,726 ,0,0,0}, {9452,11781,11784 ,726,726,726 ,0,0,0}, - {11786,11787,9452 ,726,726,726 ,0,0,0}, {11786,9452,11785 ,726,726,726 ,0,0,0}, - {9444,11788,11789 ,7583,726,7661 ,0,0,0}, {9452,11790,11791 ,726,726,726 ,0,0,0}, - {9444,11792,11793 ,7583,7658,7661 ,0,0,0}, {11794,9444,11795 ,726,7583,726 ,0,0,0}, - {11796,11797,9444 ,726,726,7583 ,0,0,0}, {11798,11795,9444 ,726,726,7583 ,0,0,0}, - {9444,11794,11799 ,7583,726,5489 ,0,0,0}, {11796,9444,11800 ,726,7583,7583 ,0,0,0}, - {9444,11797,11798 ,7583,726,726 ,0,0,0}, {9444,11801,11792 ,7583,726,7658 ,0,0,0}, - {11793,11800,9444 ,7661,7583,7583 ,0,0,0}, {11791,11788,9444 ,726,726,7583 ,0,0,0}, - {11801,9444,11789 ,726,7583,7661 ,0,0,0}, {9452,11787,11790 ,726,726,726 ,0,0,0}, - {9452,11791,9444 ,726,726,7583 ,0,0,0}, {9445,11799,9440 ,726,5489,7668 ,0,0,0}, - {11799,9445,9444 ,5489,726,7583 ,0,0,0}, {11783,9452,11802 ,726,726,726 ,0,0,0}, - {11803,9452,9450 ,726,726,726 ,0,0,0}, {9452,11803,11802 ,726,726,726 ,0,0,0}, - {11803,9450,9456 ,726,726,726 ,0,0,0}, {9906,10169,11801 ,7669,7670,7671 ,0,0,0}, - {11789,9907,9906 ,7672,7673,7669 ,0,0,0}, {11789,11788,9907 ,7672,7673,7673 ,0,0,0}, - {11801,11789,9906 ,7671,7672,7669 ,0,0,0}, {10169,10168,11792 ,7670,7674,7675 ,0,0,0}, - {9911,9965,11800 ,7676,7677,7678 ,0,0,0}, {11793,11792,10168 ,7679,7675,7674 ,0,0,0}, - {10168,9911,11793 ,7674,7676,7679 ,0,0,0}, {11800,11793,9911 ,7678,7679,7676 ,0,0,0}, - {10169,11792,11801 ,7670,7675,7671 ,0,0,0}, {11800,9965,11796 ,7678,7677,7680 ,0,0,0}, - {9964,11797,11796 ,7681,7682,7680 ,0,0,0}, {11796,9965,9964 ,7680,7677,7681 ,0,0,0}, - {11797,9964,9963 ,7682,7681,7683 ,0,0,0}, {9957,11798,9963 ,7684,7685,7683 ,0,0,0}, - {9957,9959,11795 ,7684,7686,7687 ,0,0,0}, {9957,11795,11798 ,7684,7687,7685 ,0,0,0}, - {11794,9960,11799 ,7688,7689,7690 ,0,0,0}, {11795,9959,11794 ,7687,7686,7688 ,0,0,0}, - {11794,9959,9960 ,7688,7686,7689 ,0,0,0}, {9960,9961,11799 ,7689,7690,7690 ,0,0,0}, - {11797,9963,11798 ,7682,7683,7685 ,0,0,0}, {9954,11788,11791 ,7691,7673,7692 ,0,0,0}, - {11788,9954,9907 ,7673,7691,7673 ,0,0,0}, {11790,9955,11791 ,7693,7694,7692 ,0,0,0}, - {9954,11791,9955 ,7691,7692,7694 ,0,0,0}, {11790,11787,9986 ,7693,7695,7696 ,0,0,0}, - {9986,9955,11790 ,7696,7694,7693 ,0,0,0}, {9987,11787,11786 ,7697,7695,7698 ,0,0,0}, - {11787,9987,9986 ,7695,7697,7696 ,0,0,0}, {11785,10209,11786 ,7699,7700,7698 ,0,0,0}, - {9987,11786,10209 ,7697,7698,7700 ,0,0,0}, {11785,11784,9990 ,7699,7701,7702 ,0,0,0}, - {9990,10209,11785 ,7702,7700,7699 ,0,0,0}, {9989,11784,11781 ,7703,7701,7704 ,0,0,0}, - {11784,9989,9990 ,7701,7703,7702 ,0,0,0}, {11782,10012,11781 ,7705,7706,7704 ,0,0,0}, - {9989,11781,10012 ,7703,7704,7706 ,0,0,0}, {11782,11783,10015 ,7705,7707,7708 ,0,0,0}, - {10015,10012,11782 ,7708,7706,7705 ,0,0,0}, {10016,11783,11802 ,7709,7707,7710 ,0,0,0}, - {11783,10016,10015 ,7707,7709,7708 ,0,0,0}, {10016,11802,10017 ,7709,7710,7711 ,0,0,0}, - {10017,11802,11803 ,7711,7710,7711 ,0,0,0}, {10718,11803,9456 ,7712,7712,7712 ,0,0,0}, - {11803,10719,10722 ,7712,7712,7712 ,0,0,0}, {10718,10719,11803 ,7712,7712,7712 ,0,0,0}, - {11803,10728,10733 ,7712,7712,7712 ,0,0,0}, {10722,10728,11803 ,7712,7712,7712 ,0,0,0}, - {11803,10737,10701 ,7712,7712,7712 ,0,0,0}, {10733,10737,11803 ,7712,7712,7712 ,0,0,0}, - {11803,10705,10704 ,7712,7712,7712 ,0,0,0}, {10701,10705,11803 ,7712,7712,7712 ,0,0,0}, - {11803,10704,10017 ,7712,7712,7712 ,0,0,0}, {10770,11799,9961 ,7713,7713,7713 ,0,0,0}, - {10770,10820,11799 ,7713,7713,7713 ,0,0,0}, {11799,10820,10806 ,7713,7713,7713 ,0,0,0}, - {10766,10772,11799 ,7713,7713,7713 ,0,0,0}, {10766,11799,10806 ,7713,7713,7713 ,0,0,0}, - {10772,10802,11799 ,7713,7713,7713 ,0,0,0}, {11799,10758,10757 ,7713,7713,7713 ,0,0,0}, - {10802,10758,11799 ,7713,7713,7713 ,0,0,0}, {9440,11799,10762 ,7713,7713,7713 ,0,0,0}, - {10757,10762,11799 ,7713,7713,7713 ,0,0,0}, {8875,11804,10224 ,1435,7714,7715 ,0,0,0}, - {11805,10215,11806 ,7716,7717,7718 ,0,0,0}, {10234,10223,11807 ,7719,7720,7721 ,0,0,0}, - {9895,11808,9996 ,7722,7723,7724 ,0,0,0}, {11809,11810,10237 ,7725,7726,7727 ,0,0,0}, - {11811,10018,11812 ,7728,7729,7730 ,0,0,0}, {10020,9997,11813 ,7731,7732,7733 ,0,0,0}, - {9902,10001,11814 ,7734,7735,7736 ,0,0,0}, {10006,11815,10001 ,7737,7738,7735 ,0,0,0}, - {10002,11816,11817 ,7739,7740,7741 ,0,0,0}, {9902,11818,10004 ,7734,7742,7743 ,0,0,0}, - {11819,10011,11817 ,7744,7745,7741 ,0,0,0}, {10002,11817,10011 ,7739,7741,7745 ,0,0,0}, - {11819,11820,10009 ,7744,7746,7747 ,0,0,0}, {10009,10011,11819 ,7747,7745,7744 ,0,0,0}, - {10022,11820,11821 ,7748,7746,7749 ,0,0,0}, {11820,10022,10009 ,7746,7748,7747 ,0,0,0}, - {11822,10008,11821 ,7750,7751,7749 ,0,0,0}, {10022,11821,10008 ,7748,7749,7751 ,0,0,0}, - {11822,8894,8895 ,7750,1359,1359 ,0,0,0}, {8895,10008,11822 ,1359,7751,7750 ,0,0,0}, - {11814,10001,11815 ,7736,7735,7738 ,0,0,0}, {11816,10004,11818 ,7740,7743,7742 ,0,0,0}, - {10004,11816,10002 ,7743,7740,7739 ,0,0,0}, {11814,11818,9902 ,7736,7742,7734 ,0,0,0}, - {11811,11815,10006 ,7728,7738,7737 ,0,0,0}, {10020,11813,11812 ,7731,7733,7730 ,0,0,0}, - {10020,11812,10018 ,7731,7730,7729 ,0,0,0}, {10006,10018,11811 ,7737,7729,7728 ,0,0,0}, - {9997,11823,11813 ,7732,7752,7733 ,0,0,0}, {11823,9997,9996 ,7752,7732,7724 ,0,0,0}, - {11810,11808,9895 ,7726,7723,7722 ,0,0,0}, {11808,11823,9996 ,7723,7752,7724 ,0,0,0}, - {10237,11810,9895 ,7727,7726,7722 ,0,0,0}, {10225,11805,11809 ,7753,7716,7725 ,0,0,0}, - {10225,11809,10237 ,7753,7725,7727 ,0,0,0}, {10215,10234,11806 ,7717,7719,7718 ,0,0,0}, - {10225,10215,11805 ,7753,7717,7716 ,0,0,0}, {10223,11804,11807 ,7720,7714,7721 ,0,0,0}, - {11806,10234,11807 ,7718,7719,7721 ,0,0,0}, {8875,10224,8873 ,1435,7715,1435 ,0,0,0}, - {11804,10223,10224 ,7714,7720,7715 ,0,0,0}, {11822,11821,11820 ,726,7628,7628 ,0,0,0}, - {8877,11817,8876 ,7627,7628,726 ,0,0,0}, {8856,8854,11818 ,7754,7625,7626 ,0,0,0}, - {11817,11816,8876 ,7628,726,726 ,0,0,0}, {8859,11811,8860 ,7755,726,7756 ,0,0,0}, - {8856,11818,11814 ,7754,7626,7626 ,0,0,0}, {11813,11823,8868 ,726,7628,7757 ,0,0,0}, - {11813,8866,11812 ,726,7758,7626 ,0,0,0}, {8869,8863,11808 ,7759,7760,7628 ,0,0,0}, - {11805,11806,11807 ,7625,7754,726 ,0,0,0}, {8872,8869,11810 ,7628,7759,7627 ,0,0,0}, - {8875,8872,11804 ,7628,7628,7761 ,0,0,0}, {11804,11805,11807 ,7761,7625,726 ,0,0,0}, - {8872,11809,11805 ,7628,7628,7625 ,0,0,0}, {11804,8872,11805 ,7761,7628,7625 ,0,0,0}, - {8872,8871,8869 ,7628,7762,7759 ,0,0,0}, {8872,11810,11809 ,7628,7627,7628 ,0,0,0}, - {8868,11808,8863 ,7757,7628,7760 ,0,0,0}, {11808,11810,8869 ,7628,7627,7759 ,0,0,0}, - {8868,11823,11808 ,7757,7628,7628 ,0,0,0}, {11812,8866,8860 ,7626,7758,7756 ,0,0,0}, - {8868,8866,11813 ,7757,7758,726 ,0,0,0}, {11815,11811,8859 ,7628,726,7755 ,0,0,0}, - {11811,11812,8860 ,726,7626,7756 ,0,0,0}, {11815,8857,11814 ,7628,7628,7626 ,0,0,0}, - {8857,11815,8859 ,7628,7628,7755 ,0,0,0}, {11816,11818,8854 ,726,7626,7625 ,0,0,0}, - {8857,8856,11814 ,7628,7754,7626 ,0,0,0}, {8880,11817,8877 ,7625,7628,7627 ,0,0,0}, - {8854,8876,11816 ,7625,726,726 ,0,0,0}, {11820,11819,8880 ,7628,7628,7625 ,0,0,0}, - {8880,11819,11817 ,7625,7628,7628 ,0,0,0}, {8882,11822,11820 ,7628,726,7628 ,0,0,0}, - {11820,8880,8882 ,7628,7625,7628 ,0,0,0}, {8882,8883,11822 ,7628,7628,726 ,0,0,0}, - {8886,8889,8892 ,7628,7628,7628 ,0,0,0}, {8883,8886,11822 ,7628,7628,726 ,0,0,0}, - {8892,11822,8886 ,7628,726,7628 ,0,0,0}, {8886,8888,8889 ,7628,726,7628 ,0,0,0}, - {11822,8892,8894 ,726,7628,7628 ,0,0,0}, {8836,11824,10185 ,1435,7763,7764 ,0,0,0}, - {10212,10214,11825 ,7765,7766,7767 ,0,0,0}, {10218,10219,11826 ,7768,7769,7770 ,0,0,0}, - {10184,11827,10183 ,7771,7772,7773 ,0,0,0}, {11828,11829,10213 ,7774,4221,7775 ,0,0,0}, - {11830,11831,10211 ,7776,7777,7778 ,0,0,0}, {11830,10210,11832 ,7776,7779,7780 ,0,0,0}, - {11833,11834,10027 ,7781,7782,7783 ,0,0,0}, {10027,10026,11833 ,7783,7784,7781 ,0,0,0}, - {9901,11834,11835 ,7785,7782,7786 ,0,0,0}, {11834,9901,10027 ,7782,7785,7783 ,0,0,0}, - {11836,9900,11835 ,7787,7788,7786 ,0,0,0}, {9901,11835,9900 ,7785,7786,7788 ,0,0,0}, - {11836,8850,8851 ,7787,1359,1359 ,0,0,0}, {8851,9900,11836 ,1359,7788,7787 ,0,0,0}, - {11827,10184,11829 ,7772,7771,4221 ,0,0,0}, {11831,10026,10211 ,7777,7784,7778 ,0,0,0}, - {11833,10026,11831 ,7781,7784,7777 ,0,0,0}, {11825,10214,11837 ,7767,7766,4227 ,0,0,0}, - {11832,10210,10183 ,7780,7779,7773 ,0,0,0}, {11830,10211,10210 ,7776,7778,7779 ,0,0,0}, - {11827,11832,10183 ,7772,7780,7773 ,0,0,0}, {10213,11829,10184 ,7775,4221,7771 ,0,0,0}, - {10212,11825,11828 ,7765,7767,7774 ,0,0,0}, {11828,10213,10212 ,7774,7775,7765 ,0,0,0}, - {10219,11824,11826 ,7769,7763,7770 ,0,0,0}, {11837,10218,11826 ,4227,7768,7770 ,0,0,0}, - {10214,10218,11837 ,7766,7768,4227 ,0,0,0}, {8836,10185,8837 ,1435,7764,1435 ,0,0,0}, - {11824,10219,10185 ,7763,7769,7764 ,0,0,0}, {8835,8844,8836 ,726,5471,7661 ,0,0,0}, - {11827,11830,11832 ,726,726,726 ,0,0,0}, {11833,11831,11830 ,7658,726,726 ,0,0,0}, - {11830,11827,11833 ,726,726,7658 ,0,0,0}, {11833,11829,11834 ,7658,726,7658 ,0,0,0}, - {11829,11833,11827 ,726,7658,726 ,0,0,0}, {11835,11834,11828 ,7658,7658,726 ,0,0,0}, - {11829,11828,11834 ,726,726,7658 ,0,0,0}, {11825,11836,11835 ,7658,7661,7658 ,0,0,0}, - {11835,11828,11825 ,7658,726,7658 ,0,0,0}, {11836,11837,8850 ,7661,7661,7664 ,0,0,0}, - {11837,11836,11825 ,7661,7661,7658 ,0,0,0}, {11837,11826,8850 ,7661,726,7664 ,0,0,0}, - {11826,11824,8848 ,726,726,7662 ,0,0,0}, {8842,8835,8833 ,7789,726,7658 ,0,0,0}, - {8823,8822,8829 ,5488,7668,7661 ,0,0,0}, {8839,8831,8838 ,7790,7664,7791 ,0,0,0}, - {8823,8829,8825 ,5488,7661,7792 ,0,0,0}, {8826,8825,8829 ,5488,7792,7661 ,0,0,0}, - {8831,8829,8838 ,7664,7661,7791 ,0,0,0}, {8838,8829,8822 ,7791,7661,7668 ,0,0,0}, - {8831,8839,8833 ,7664,7790,7658 ,0,0,0}, {8844,8835,8842 ,5471,726,7789 ,0,0,0}, - {8842,8833,8839 ,7789,7658,7790 ,0,0,0}, {8836,8845,11824 ,7661,7583,726 ,0,0,0}, - {8836,8844,8845 ,7661,5471,7583 ,0,0,0}, {11826,8848,8850 ,726,7662,7664 ,0,0,0}, - {8845,8848,11824 ,7583,7662,726 ,0,0,0}, {11838,9481,11839 ,7583,726,726 ,0,0,0}, - {11840,9477,11841 ,7668,726,5470 ,0,0,0}, {11840,11842,9477 ,7668,726,726 ,0,0,0}, - {9477,11843,11841 ,726,726,5470 ,0,0,0}, {11842,11844,9477 ,726,5489,726 ,0,0,0}, - {9477,11845,11846 ,726,7793,7794 ,0,0,0}, {11844,11845,9477 ,5489,7793,726 ,0,0,0}, - {9481,11847,9477 ,726,5470,726 ,0,0,0}, {11847,11843,9477 ,5470,726,726 ,0,0,0}, - {11848,11847,9481 ,726,5470,726 ,0,0,0}, {11849,9477,11846 ,7795,726,7794 ,0,0,0}, - {9481,11850,11848 ,726,5488,726 ,0,0,0}, {11849,11851,9477 ,7795,726,726 ,0,0,0}, - {11852,9477,11853 ,5485,726,7796 ,0,0,0}, {9477,11851,11853 ,726,726,7796 ,0,0,0}, - {9481,11854,11850 ,726,7583,5488 ,0,0,0}, {11855,9477,11852 ,7583,726,5485 ,0,0,0}, - {9481,11856,11854 ,726,726,7583 ,0,0,0}, {9481,11857,11858 ,726,5488,7583 ,0,0,0}, - {9481,11858,11856 ,726,7583,726 ,0,0,0}, {9478,11855,9473 ,5489,7583,7797 ,0,0,0}, - {9481,11838,11857 ,726,7583,5488 ,0,0,0}, {11855,9478,9477 ,7583,5489,726 ,0,0,0}, - {11839,9481,11859 ,726,726,7583 ,0,0,0}, {11860,9481,9488 ,726,726,726 ,0,0,0}, - {9481,11860,11859 ,726,726,7583 ,0,0,0}, {11860,9488,9487 ,726,726,726 ,0,0,0}, - {9896,9998,11840 ,7798,7799,7800 ,0,0,0}, {11841,9894,9896 ,7801,7802,7798 ,0,0,0}, - {11841,11843,9894 ,7801,7802,7802 ,0,0,0}, {11840,11841,9896 ,7800,7801,7798 ,0,0,0}, - {9998,10207,11842 ,7799,7803,7804 ,0,0,0}, {10019,10005,11845 ,7805,7806,7807 ,0,0,0}, - {11844,11842,10207 ,7808,7804,7803 ,0,0,0}, {10207,10019,11844 ,7803,7805,7808 ,0,0,0}, - {11845,11844,10019 ,7807,7808,7805 ,0,0,0}, {9998,11842,11840 ,7799,7804,7800 ,0,0,0}, - {11845,10005,11846 ,7807,7806,7809 ,0,0,0}, {10000,11849,11846 ,7810,7811,7809 ,0,0,0}, - {11846,10005,10000 ,7809,7806,7810 ,0,0,0}, {11849,10000,9999 ,7811,7810,7812 ,0,0,0}, - {9904,11851,9999 ,7813,7814,7812 ,0,0,0}, {9904,9983,11853 ,7813,7815,7816 ,0,0,0}, - {9904,11853,11851 ,7813,7816,7814 ,0,0,0}, {11852,9985,11855 ,7817,7818,7819 ,0,0,0}, - {11853,9983,11852 ,7816,7815,7817 ,0,0,0}, {11852,9983,9985 ,7817,7815,7818 ,0,0,0}, - {9985,10014,11855 ,7818,7819,7819 ,0,0,0}, {11849,9999,11851 ,7811,7812,7814 ,0,0,0}, - {10028,11843,11847 ,7820,7802,7821 ,0,0,0}, {11843,10028,9894 ,7802,7820,7802 ,0,0,0}, - {11848,10032,11847 ,7822,7823,7821 ,0,0,0}, {10028,11847,10032 ,7820,7821,7823 ,0,0,0}, - {11848,11850,9993 ,7822,7824,7825 ,0,0,0}, {9993,10032,11848 ,7825,7823,7822 ,0,0,0}, - {9994,11850,11854 ,7826,7824,7827 ,0,0,0}, {11850,9994,9993 ,7824,7826,7825 ,0,0,0}, - {11856,10069,11854 ,7828,7829,7827 ,0,0,0}, {9994,11854,10069 ,7826,7827,7829 ,0,0,0}, - {11856,11858,9897 ,7828,7830,7831 ,0,0,0}, {9897,10069,11856 ,7831,7829,7828 ,0,0,0}, - {9898,11858,11857 ,7832,7830,7833 ,0,0,0}, {11858,9898,9897 ,7830,7832,7831 ,0,0,0}, - {11838,10056,11857 ,7834,7835,7833 ,0,0,0}, {9898,11857,10056 ,7832,7833,7835 ,0,0,0}, - {11838,11839,10059 ,7834,7836,7837 ,0,0,0}, {10059,10056,11838 ,7837,7835,7834 ,0,0,0}, - {10063,11839,11859 ,7838,7836,7839 ,0,0,0}, {11839,10063,10059 ,7836,7838,7837 ,0,0,0}, - {10063,11859,10064 ,7838,7839,7840 ,0,0,0}, {10064,11859,11860 ,7840,7839,7840 ,0,0,0}, - {10631,11860,9487 ,7841,7841,7841 ,0,0,0}, {11860,10637,10640 ,7841,7841,7841 ,0,0,0}, - {10631,10637,11860 ,7841,7841,7841 ,0,0,0}, {11860,10646,10651 ,7841,7841,7841 ,0,0,0}, - {10640,10646,11860 ,7841,7841,7841 ,0,0,0}, {11860,10655,10614 ,7841,7841,7841 ,0,0,0}, - {10651,10655,11860 ,7841,7841,7841 ,0,0,0}, {11860,10626,10625 ,7841,7841,7841 ,0,0,0}, - {10614,10626,11860 ,7841,7841,7841 ,0,0,0}, {11860,10625,10064 ,7841,7841,7841 ,0,0,0}, - {10692,11855,10014 ,7842,7842,7842 ,0,0,0}, {10692,10738,11855 ,7842,7842,7842 ,0,0,0}, - {11855,10738,10724 ,7842,7842,7842 ,0,0,0}, {10686,10679,11855 ,7842,7842,7842 ,0,0,0}, - {10686,11855,10724 ,7842,7842,7842 ,0,0,0}, {10679,10720,11855 ,7842,7842,7842 ,0,0,0}, - {11855,10712,10674 ,7842,7842,7842 ,0,0,0}, {10720,10712,11855 ,7842,7842,7842 ,0,0,0}, - {9473,11855,10675 ,7842,7842,7842 ,0,0,0}, {10674,10675,11855 ,7842,7842,7842 ,0,0,0}, - {8799,11861,10249 ,1790,7843,4204 ,0,0,0}, {11862,10246,11863 ,7844,4198,4199 ,0,0,0}, - {10235,10248,11864 ,7845,7846,7847 ,0,0,0}, {10226,11865,10044 ,7848,7849,7850 ,0,0,0}, - {11866,11867,10259 ,7851,7852,7853 ,0,0,0}, {11868,10023,11869 ,7854,7855,7856 ,0,0,0}, - {10025,10042,11870 ,7857,7858,7859 ,0,0,0}, {9891,9890,11871 ,7860,7861,7862 ,0,0,0}, - {10046,11872,9890 ,7863,7864,7861 ,0,0,0}, {10050,11873,11874 ,7865,7866,7867 ,0,0,0}, - {9891,11875,10049 ,7860,7868,7869 ,0,0,0}, {11876,10055,11874 ,7870,7871,7867 ,0,0,0}, - {10050,11874,10055 ,7865,7867,7871 ,0,0,0}, {11876,11877,10053 ,7870,7872,7873 ,0,0,0}, - {10053,10055,11876 ,7873,7871,7870 ,0,0,0}, {10038,11877,11878 ,7874,7872,7875 ,0,0,0}, - {11877,10038,10053 ,7872,7874,7873 ,0,0,0}, {11879,10036,11878 ,7876,7877,7875 ,0,0,0}, - {10038,11878,10036 ,7874,7875,7877 ,0,0,0}, {11879,8818,8819 ,7876,1711,1711 ,0,0,0}, - {8819,10036,11879 ,1711,7877,7876 ,0,0,0}, {11871,9890,11872 ,7862,7861,7864 ,0,0,0}, - {11873,10049,11875 ,7866,7869,7868 ,0,0,0}, {10049,11873,10050 ,7869,7866,7865 ,0,0,0}, - {11871,11875,9891 ,7862,7868,7860 ,0,0,0}, {11868,11872,10046 ,7854,7864,7863 ,0,0,0}, - {10025,11870,11869 ,7857,7859,7856 ,0,0,0}, {10025,11869,10023 ,7857,7856,7855 ,0,0,0}, - {10046,10023,11868 ,7863,7855,7854 ,0,0,0}, {10042,11880,11870 ,7858,7878,7859 ,0,0,0}, - {11880,10042,10044 ,7878,7858,7850 ,0,0,0}, {11867,11865,10226 ,7852,7849,7848 ,0,0,0}, - {11865,11880,10044 ,7849,7878,7850 ,0,0,0}, {10259,11867,10226 ,7853,7852,7848 ,0,0,0}, - {10247,11862,11866 ,7879,7844,7851 ,0,0,0}, {10247,11866,10259 ,7879,7851,7853 ,0,0,0}, - {10246,10235,11863 ,4198,7845,4199 ,0,0,0}, {10247,10246,11862 ,7879,4198,7844 ,0,0,0}, - {10248,11861,11864 ,7846,7843,7847 ,0,0,0}, {11863,10235,11864 ,4199,7845,7847 ,0,0,0}, - {8799,10249,8797 ,1790,4204,1790 ,0,0,0}, {11861,10248,10249 ,7843,7846,4204 ,0,0,0}, - {11871,11872,11866 ,726,7880,7881 ,0,0,0}, {11861,11876,11874 ,7882,7627,7625 ,0,0,0}, - {11867,11868,11865 ,7883,7758,726 ,0,0,0}, {11880,11865,11868 ,7884,726,7758 ,0,0,0}, - {11869,11870,11880 ,7880,7761,7884 ,0,0,0}, {11868,11867,11872 ,7758,7883,7880 ,0,0,0}, - {11869,11880,11868 ,7880,7884,7758 ,0,0,0}, {11871,11866,11862 ,726,7881,7885 ,0,0,0}, - {11872,11867,11866 ,7880,7883,7881 ,0,0,0}, {11862,11863,11875 ,7885,7886,7758 ,0,0,0}, - {11875,11871,11862 ,7758,726,7885 ,0,0,0}, {11873,11863,11864 ,726,7886,7887 ,0,0,0}, - {11863,11873,11875 ,7886,726,7758 ,0,0,0}, {11874,11873,11864 ,7625,726,7887 ,0,0,0}, - {8799,11876,11861 ,7758,7627,7882 ,0,0,0}, {11861,11874,11864 ,7882,7625,7887 ,0,0,0}, - {11877,8799,8796 ,7627,7758,7755 ,0,0,0}, {8799,11877,11876 ,7758,7627,7627 ,0,0,0}, - {8795,11878,8796 ,7625,726,7755 ,0,0,0}, {11877,8796,11878 ,7627,7755,726 ,0,0,0}, - {8795,8793,11879 ,7625,7761,726 ,0,0,0}, {11879,11878,8795 ,726,726,7625 ,0,0,0}, - {8818,8793,8787 ,7627,7761,7625 ,0,0,0}, {8793,8818,11879 ,7761,7627,726 ,0,0,0}, - {8784,8812,8790 ,726,7627,7625 ,0,0,0}, {8792,8816,8787 ,7880,726,7625 ,0,0,0}, - {8810,8783,8807 ,7625,726,726 ,0,0,0}, {8804,8780,8801 ,7627,7625,7625 ,0,0,0}, - {8806,8807,8781 ,726,726,7625 ,0,0,0}, {8801,8778,8800 ,7625,7625,726 ,0,0,0}, - {8780,8804,8806 ,7625,7627,726 ,0,0,0}, {8781,8780,8806 ,7625,7625,726 ,0,0,0}, - {8801,8780,8778 ,7625,7625,7625 ,0,0,0}, {8784,8783,8810 ,726,726,7625 ,0,0,0}, - {8781,8807,8783 ,7625,726,726 ,0,0,0}, {8813,8790,8812 ,726,7625,7627 ,0,0,0}, - {8812,8784,8810 ,7627,726,7625 ,0,0,0}, {8792,8813,8816 ,7880,726,726 ,0,0,0}, - {8813,8792,8790 ,726,7880,7625 ,0,0,0}, {8816,8818,8787 ,726,7627,7625 ,0,0,0}, - {8760,11881,10179 ,1790,7888,7889 ,0,0,0}, {10231,10220,11882 ,7890,7891,7892 ,0,0,0}, - {10233,10180,11883 ,7893,7894,7895 ,0,0,0}, {10221,11884,10222 ,7896,7897,4137 ,0,0,0}, - {11885,11886,10232 ,7898,7899,7900 ,0,0,0}, {11887,11888,10230 ,7901,7902,7903 ,0,0,0}, - {11887,10229,11889 ,7901,7904,7905 ,0,0,0}, {11890,11891,10065 ,7906,7907,7908 ,0,0,0}, - {10065,10066,11890 ,7908,7909,7906 ,0,0,0}, {10228,11891,11892 ,7910,7907,7911 ,0,0,0}, - {11891,10228,10065 ,7907,7910,7908 ,0,0,0}, {11893,10039,11892 ,7912,7913,7911 ,0,0,0}, - {10228,11892,10039 ,7910,7911,7913 ,0,0,0}, {11893,8774,8775 ,7912,1711,1711 ,0,0,0}, - {8775,10039,11893 ,1711,7913,7912 ,0,0,0}, {11884,10221,11886 ,7897,7896,7899 ,0,0,0}, - {11888,10066,10230 ,7902,7909,7903 ,0,0,0}, {11890,10066,11888 ,7906,7909,7902 ,0,0,0}, - {11882,10220,11894 ,7892,7891,7914 ,0,0,0}, {11889,10229,10222 ,7905,7904,4137 ,0,0,0}, - {11887,10230,10229 ,7901,7903,7904 ,0,0,0}, {11884,11889,10222 ,7897,7905,4137 ,0,0,0}, - {10232,11886,10221 ,7900,7899,7896 ,0,0,0}, {10231,11882,11885 ,7890,7892,7898 ,0,0,0}, - {11885,10232,10231 ,7898,7900,7890 ,0,0,0}, {10180,11881,11883 ,7894,7888,7895 ,0,0,0}, - {11894,10233,11883 ,7914,7893,7895 ,0,0,0}, {10220,10233,11894 ,7891,7893,7914 ,0,0,0}, - {8760,10179,8761 ,1790,7889,1790 ,0,0,0}, {11881,10180,10179 ,7888,7894,7889 ,0,0,0}, - {11887,8768,11888 ,726,7658,726 ,0,0,0}, {11892,11891,8772 ,726,726,7660 ,0,0,0}, - {8774,11893,11892 ,726,7660,726 ,0,0,0}, {11887,11889,8766 ,726,726,7658 ,0,0,0}, - {8769,8772,11890 ,7660,7660,7659 ,0,0,0}, {11886,11885,8746 ,7659,726,7661 ,0,0,0}, - {11886,8762,11884 ,7659,726,726 ,0,0,0}, {8749,8747,11882 ,7915,7916,726 ,0,0,0}, - {11881,8755,8753 ,7658,7917,5475 ,0,0,0}, {11883,8750,11894 ,7658,726,7659 ,0,0,0}, - {8760,8759,8755 ,7918,7918,7917 ,0,0,0}, {8757,8755,8759 ,7661,7917,7918 ,0,0,0}, - {11883,11881,8753 ,7658,7658,5475 ,0,0,0}, {11881,8760,8755 ,7658,7918,7917 ,0,0,0}, - {8750,11883,8753 ,726,7658,5475 ,0,0,0}, {11894,8750,8749 ,7659,726,7915 ,0,0,0}, - {11882,8747,11885 ,726,7916,726 ,0,0,0}, {11894,8749,11882 ,7659,7915,726 ,0,0,0}, - {11886,8746,8762 ,7659,7661,726 ,0,0,0}, {11885,8747,8746 ,726,7916,7661 ,0,0,0}, - {8763,11889,11884 ,7664,726,726 ,0,0,0}, {8762,8763,11884 ,726,7664,726 ,0,0,0}, - {8768,11887,8766 ,7658,726,7658 ,0,0,0}, {8766,11889,8763 ,7658,726,7664 ,0,0,0}, - {11888,8769,11890 ,726,7660,7659 ,0,0,0}, {11888,8768,8769 ,726,7658,7660 ,0,0,0}, - {11892,8772,8774 ,726,7660,726 ,0,0,0}, {11891,11890,8772 ,726,7659,7660 ,0,0,0}, - {9518,11895,11896 ,726,5469,7919 ,0,0,0}, {11897,9518,11898 ,7920,726,7921 ,0,0,0}, - {9518,11897,11895 ,726,7920,5469 ,0,0,0}, {9518,11899,11898 ,726,726,7921 ,0,0,0}, - {11900,9518,11896 ,7922,726,7919 ,0,0,0}, {11899,9518,11901 ,726,726,7920 ,0,0,0}, - {11900,11902,9518 ,7922,7923,726 ,0,0,0}, {9518,11903,11904 ,726,7924,7925 ,0,0,0}, - {11904,11905,9518 ,7925,7926,726 ,0,0,0}, {11902,11903,9518 ,7923,7924,726 ,0,0,0}, - {11906,11907,9518 ,5472,7927,726 ,0,0,0}, {11906,9518,11905 ,5472,726,7926 ,0,0,0}, - {11908,11909,9518 ,7928,7929,726 ,0,0,0}, {11908,9518,11907 ,7928,726,7927 ,0,0,0}, - {11910,11911,9518 ,726,5489,726 ,0,0,0}, {11910,9518,11909 ,726,726,7929 ,0,0,0}, - {9518,11912,9517 ,726,5488,7583 ,0,0,0}, {11912,9518,11911 ,5488,726,5489 ,0,0,0}, - {9517,11913,11914 ,7583,5470,5489 ,0,0,0}, {11912,11913,9517 ,5488,5470,7583 ,0,0,0}, - {9513,9514,11914 ,5489,5488,5489 ,0,0,0}, {9517,11914,9514 ,7583,5489,5488 ,0,0,0}, - {9508,9513,11914 ,5489,5489,5489 ,0,0,0}, {9518,11485,11901 ,726,5489,7920 ,0,0,0}, - {11485,11915,11916 ,5489,5470,5488 ,0,0,0}, {11901,11485,11916 ,7920,5489,5488 ,0,0,0}, - {11917,11485,11484 ,5489,5489,726 ,0,0,0}, {11485,11917,11915 ,5489,5489,5470 ,0,0,0}, - {10548,11917,11483 ,5489,5489,7583 ,0,0,0}, {11484,11483,11917 ,726,7583,5489 ,0,0,0}, - {10082,10043,11905 ,7930,7931,7932 ,0,0,0}, {11904,10084,10082 ,7933,7934,7930 ,0,0,0}, - {11904,11903,10084 ,7933,7935,7934 ,0,0,0}, {11905,11904,10082 ,7932,7933,7930 ,0,0,0}, - {10043,10227,11906 ,7931,7936,7937 ,0,0,0}, {10024,10045,11908 ,7938,7939,7940 ,0,0,0}, - {11907,11906,10227 ,7941,7937,7936 ,0,0,0}, {10227,10024,11907 ,7936,7938,7941 ,0,0,0}, - {11908,11907,10024 ,7940,7941,7938 ,0,0,0}, {10043,11906,11905 ,7931,7937,7932 ,0,0,0}, - {11908,10045,11909 ,7940,7939,7942 ,0,0,0}, {10047,11910,11909 ,7943,7944,7942 ,0,0,0}, - {11909,10045,10047 ,7942,7939,7943 ,0,0,0}, {11910,10047,9892 ,7944,7943,7945 ,0,0,0}, - {10035,11911,9892 ,7946,7947,7945 ,0,0,0}, {10035,10048,11912 ,7946,7948,7949 ,0,0,0}, - {10035,11912,11911 ,7946,7949,7947 ,0,0,0}, {11913,10040,11914 ,7950,7951,7952 ,0,0,0}, - {11912,10048,11913 ,7949,7948,7950 ,0,0,0}, {11913,10048,10040 ,7950,7948,7951 ,0,0,0}, - {10040,10041,11914 ,7951,7952,7952 ,0,0,0}, {11910,9892,11911 ,7944,7945,7947 ,0,0,0}, - {10204,11903,11902 ,7953,7935,7954 ,0,0,0}, {11903,10204,10084 ,7935,7953,7934 ,0,0,0}, - {11900,10083,11902 ,7955,7956,7954 ,0,0,0}, {10204,11902,10083 ,7953,7954,7956 ,0,0,0}, - {11900,11896,10067 ,7955,7957,7958 ,0,0,0}, {10067,10083,11900 ,7958,7956,7955 ,0,0,0}, - {10068,11896,11895 ,7959,7957,7960 ,0,0,0}, {11896,10068,10067 ,7957,7959,7958 ,0,0,0}, - {11897,10241,11895 ,7961,7962,7960 ,0,0,0}, {10068,11895,10241 ,7959,7960,7962 ,0,0,0}, - {11897,11898,10181 ,7961,7963,7964 ,0,0,0}, {10181,10241,11897 ,7964,7962,7961 ,0,0,0}, - {10182,11898,11899 ,7965,7963,7966 ,0,0,0}, {11898,10182,10181 ,7963,7965,7964 ,0,0,0}, - {11901,10075,11899 ,7967,7968,7966 ,0,0,0}, {10182,11899,10075 ,7965,7966,7968 ,0,0,0}, - {11901,11916,10103 ,7967,7969,7970 ,0,0,0}, {10103,10075,11901 ,7970,7968,7967 ,0,0,0}, - {10104,11916,11915 ,7971,7969,7972 ,0,0,0}, {11916,10104,10103 ,7969,7971,7970 ,0,0,0}, - {10104,11915,10106 ,7971,7972,7973 ,0,0,0}, {10106,11915,11917 ,7973,7972,7973 ,0,0,0}, - {10558,10564,11917 ,7974,7974,7974 ,0,0,0}, {11917,10548,10549 ,7974,7974,7974 ,0,0,0}, - {10549,10555,11917 ,7974,7974,7974 ,0,0,0}, {10569,11917,10564 ,7974,7974,7974 ,0,0,0}, - {10555,10558,11917 ,7974,7974,7974 ,0,0,0}, {10573,10526,11917 ,7974,7974,7974 ,0,0,0}, - {10573,11917,10569 ,7974,7974,7974 ,0,0,0}, {10526,10538,11917 ,7974,7974,7974 ,0,0,0}, - {10106,11917,10537 ,7974,7974,7974 ,0,0,0}, {10538,10537,11917 ,7974,7974,7974 ,0,0,0}, - {11914,10041,10606 ,7975,7975,7975 ,0,0,0}, {10606,10656,11914 ,7975,7975,7975 ,0,0,0}, - {11914,10642,10602 ,7975,7975,7975 ,0,0,0}, {10656,10642,11914 ,7975,7975,7975 ,0,0,0}, - {11914,10608,10638 ,7975,7975,7975 ,0,0,0}, {10602,10608,11914 ,7975,7975,7975 ,0,0,0}, - {11914,10594,10593 ,7975,7975,7975 ,0,0,0}, {10638,10594,11914 ,7975,7975,7975 ,0,0,0}, - {9508,11914,10598 ,7975,7975,7975 ,0,0,0}, {10593,10598,11914 ,7975,7975,7975 ,0,0,0}, - {8723,11918,10254 ,126,7976,7977 ,0,0,0}, {11919,10256,11920 ,7978,7979,7980 ,0,0,0}, - {10270,10257,11921 ,7981,7982,7983 ,0,0,0}, {10071,11922,10062 ,7984,7985,7986 ,0,0,0}, - {11923,11924,10238 ,7987,7988,7989 ,0,0,0}, {11925,10089,11926 ,7990,7991,7992 ,0,0,0}, - {10107,10074,11927 ,7993,7994,7995 ,0,0,0}, {10099,10100,11928 ,7996,7997,7998 ,0,0,0}, - {10090,11929,10100 ,7999,8000,7997 ,0,0,0}, {10091,11930,11931 ,8001,8002,8003 ,0,0,0}, - {10099,11932,10093 ,7996,8004,8005 ,0,0,0}, {11933,10094,11931 ,8006,8007,8003 ,0,0,0}, - {10091,11931,10094 ,8001,8003,8007 ,0,0,0}, {11933,11934,10097 ,8006,8008,8009 ,0,0,0}, - {10097,10094,11933 ,8009,8007,8006 ,0,0,0}, {10136,11934,11935 ,8010,8008,8011 ,0,0,0}, - {11934,10136,10097 ,8008,8010,8009 ,0,0,0}, {11936,10098,11935 ,8012,8013,8011 ,0,0,0}, - {10136,11935,10098 ,8010,8011,8013 ,0,0,0}, {11936,8742,8743 ,8012,8014,4346 ,0,0,0}, - {8743,10098,11936 ,4346,8013,8012 ,0,0,0}, {11928,10100,11929 ,7998,7997,8000 ,0,0,0}, - {11930,10093,11932 ,8002,8005,8004 ,0,0,0}, {10093,11930,10091 ,8005,8002,8001 ,0,0,0}, - {11928,11932,10099 ,7998,8004,7996 ,0,0,0}, {11925,11929,10090 ,7990,8000,7999 ,0,0,0}, - {10107,11927,11926 ,7993,7995,7992 ,0,0,0}, {10107,11926,10089 ,7993,7992,7991 ,0,0,0}, - {10090,10089,11925 ,7999,7991,7990 ,0,0,0}, {10074,11937,11927 ,7994,8015,7995 ,0,0,0}, - {11937,10074,10062 ,8015,7994,7986 ,0,0,0}, {11924,11922,10071 ,7988,7985,7984 ,0,0,0}, - {11922,11937,10062 ,7985,8015,7986 ,0,0,0}, {10238,11924,10071 ,7989,7988,7984 ,0,0,0}, - {10255,11919,11923 ,8016,7978,7987 ,0,0,0}, {10255,11923,10238 ,8016,7987,7989 ,0,0,0}, - {10256,10270,11920 ,7979,7981,7980 ,0,0,0}, {10255,10256,11919 ,8016,7979,7978 ,0,0,0}, - {10257,11918,11921 ,7982,7976,7983 ,0,0,0}, {11920,10270,11921 ,7980,7981,7983 ,0,0,0}, - {8723,10254,8721 ,126,7977,4289 ,0,0,0}, {11918,10257,10254 ,7976,7982,7977 ,0,0,0}, - {11936,11935,11934 ,7625,7880,7758 ,0,0,0}, {8728,11919,11920 ,7626,7880,726 ,0,0,0}, - {11934,11931,11928 ,7758,8017,8018 ,0,0,0}, {11934,11933,11931 ,7758,7758,8017 ,0,0,0}, - {11930,11928,11931 ,8017,8018,8017 ,0,0,0}, {11930,11932,11928 ,8017,7758,8018 ,0,0,0}, - {11929,11934,11928 ,8019,7758,8018 ,0,0,0}, {11929,11925,11936 ,8019,7884,7625 ,0,0,0}, - {11936,11934,11929 ,7625,7758,8019 ,0,0,0}, {11925,11926,8740 ,7884,8020,7625 ,0,0,0}, - {11925,8742,11936 ,7884,7625,7625 ,0,0,0}, {11937,8736,8737 ,8021,7625,726 ,0,0,0}, - {8737,8740,11927 ,726,7625,7257 ,0,0,0}, {8730,8731,11923 ,726,726,8017 ,0,0,0}, - {8734,11922,11924 ,7625,8022,7761 ,0,0,0}, {8725,11921,8724 ,7626,726,7626 ,0,0,0}, - {11920,8725,8728 ,726,7626,7626 ,0,0,0}, {8720,8705,8704 ,7625,726,726 ,0,0,0}, - {8723,8704,11918 ,7625,726,7625 ,0,0,0}, {8716,8707,8717 ,726,726,7625 ,0,0,0}, - {8707,8716,8714 ,726,726,726 ,0,0,0}, {8711,8716,8717 ,7625,726,7625 ,0,0,0}, - {8719,8717,8720 ,7625,7625,7625 ,0,0,0}, {8717,8707,8705 ,7625,726,726 ,0,0,0}, - {8708,8707,8714 ,726,726,726 ,0,0,0}, {8704,8723,8720 ,726,7625,7625 ,0,0,0}, - {8705,8720,8717 ,726,7625,7625 ,0,0,0}, {11918,8702,8724 ,7625,726,7626 ,0,0,0}, - {8702,11918,8704 ,726,7625,726 ,0,0,0}, {11921,8725,11920 ,726,7626,726 ,0,0,0}, - {11918,8724,11921 ,7625,7626,726 ,0,0,0}, {8728,8730,11919 ,7626,726,7880 ,0,0,0}, - {11923,8731,11924 ,8017,726,7761 ,0,0,0}, {11919,8730,11923 ,7880,726,8017 ,0,0,0}, - {11924,8731,8734 ,7761,726,7625 ,0,0,0}, {11922,8736,11937 ,8022,7625,8021 ,0,0,0}, - {11922,8734,8736 ,8022,7625,7625 ,0,0,0}, {8740,11926,11927 ,7625,8020,7257 ,0,0,0}, - {11927,11937,8737 ,7257,8021,726 ,0,0,0}, {8740,8742,11925 ,7625,7625,7884 ,0,0,0}, - {8684,11938,10253 ,8023,8024,8025 ,0,0,0}, {9995,10198,11939 ,8026,8027,8028 ,0,0,0}, - {10305,10251,11940 ,8029,8030,8031 ,0,0,0}, {10244,11941,10236 ,8032,8033,8034 ,0,0,0}, - {11942,11943,10203 ,8035,8036,8037 ,0,0,0}, {11944,11945,10243 ,8038,8039,8040 ,0,0,0}, - {11944,10245,11946 ,8038,8041,8042 ,0,0,0}, {11947,11948,10242 ,8043,8044,8045 ,0,0,0}, - {10242,10142,11947 ,8045,8046,8043 ,0,0,0}, {10139,11948,11949 ,8047,8044,8048 ,0,0,0}, - {11948,10139,10242 ,8044,8047,8045 ,0,0,0}, {11950,10140,11949 ,8049,8050,8048 ,0,0,0}, - {10139,11949,10140 ,8047,8048,8050 ,0,0,0}, {11950,8698,8699 ,8049,82,82 ,0,0,0}, - {8699,10140,11950 ,82,8050,8049 ,0,0,0}, {11941,10244,11943 ,8033,8032,8036 ,0,0,0}, - {11945,10142,10243 ,8039,8046,8040 ,0,0,0}, {11947,10142,11945 ,8043,8046,8039 ,0,0,0}, - {11939,10198,11951 ,8028,8027,8051 ,0,0,0}, {11946,10245,10236 ,8042,8041,8034 ,0,0,0}, - {11944,10243,10245 ,8038,8040,8041 ,0,0,0}, {11941,11946,10236 ,8033,8042,8034 ,0,0,0}, - {10203,11943,10244 ,8037,8036,8032 ,0,0,0}, {9995,11939,11942 ,8026,8028,8035 ,0,0,0}, - {11942,10203,9995 ,8035,8037,8026 ,0,0,0}, {10251,11938,11940 ,8030,8024,8031 ,0,0,0}, - {11951,10305,11940 ,8051,8029,8031 ,0,0,0}, {10198,10305,11951 ,8027,8029,8051 ,0,0,0}, - {8684,10253,8685 ,8023,8025,8052 ,0,0,0}, {11938,10251,10253 ,8024,8030,8025 ,0,0,0}, - {11944,8681,11945 ,726,726,726 ,0,0,0}, {11948,8677,8674 ,726,7661,726 ,0,0,0}, - {11941,11943,11938 ,726,7660,726 ,0,0,0}, {11946,8684,8683 ,726,726,726 ,0,0,0}, - {11940,11938,11939 ,7661,726,726 ,0,0,0}, {11939,11951,11940 ,726,7658,7661 ,0,0,0}, - {11939,11943,11942 ,726,7660,726 ,0,0,0}, {11938,8684,11941 ,726,726,726 ,0,0,0}, - {11943,11939,11938 ,7660,726,726 ,0,0,0}, {11946,8683,11944 ,726,726,726 ,0,0,0}, - {11941,8684,11946 ,726,726,726 ,0,0,0}, {11944,8683,8681 ,726,726,726 ,0,0,0}, - {11945,8679,11947 ,726,7658,726 ,0,0,0}, {11945,8681,8679 ,726,726,7658 ,0,0,0}, - {11948,11947,8677 ,726,726,7661 ,0,0,0}, {8679,8677,11947 ,7658,7661,726 ,0,0,0}, - {11948,8674,11949 ,726,726,726 ,0,0,0}, {8673,11950,11949 ,726,726,726 ,0,0,0}, - {11949,8674,8673 ,726,726,726 ,0,0,0}, {11950,8671,8698 ,726,726,726 ,0,0,0}, - {8671,11950,8673 ,726,726,726 ,0,0,0}, {8671,8670,8698 ,726,726,726 ,0,0,0}, - {8690,8686,8687 ,7659,726,726 ,0,0,0}, {8690,8696,8686 ,7659,726,726 ,0,0,0}, - {8693,8690,8692 ,726,7659,726 ,0,0,0}, {8693,8696,8690 ,726,726,7659 ,0,0,0}, - {8698,8670,8696 ,726,726,726 ,0,0,0}, {8686,8696,8670 ,726,726,726 ,0,0,0}, - {11952,11953,11480 ,726,8053,7583 ,0,0,0}, {11482,11954,11481 ,726,726,726 ,0,0,0}, - {11953,11955,11480 ,8053,7922,7583 ,0,0,0}, {11952,11480,11956 ,726,7583,5472 ,0,0,0}, - {11480,11957,11958 ,7583,7664,5488 ,0,0,0}, {11955,11957,11480 ,7922,7664,7583 ,0,0,0}, - {11959,11960,11480 ,7920,726,7583 ,0,0,0}, {11958,11961,11480 ,5488,5471,7583 ,0,0,0}, - {11962,11963,11482 ,7664,7583,726 ,0,0,0}, {11482,11964,11965 ,726,5488,7664 ,0,0,0}, - {11966,11482,11967 ,726,726,726 ,0,0,0}, {11968,11969,11482 ,7664,7664,726 ,0,0,0}, - {11970,11967,11482 ,726,726,726 ,0,0,0}, {11482,11966,11954 ,726,726,726 ,0,0,0}, - {11968,11482,11971 ,7664,726,7664 ,0,0,0}, {11482,11969,11970 ,726,7664,726 ,0,0,0}, - {11482,11963,11971 ,726,7583,7664 ,0,0,0}, {11482,11965,11972 ,726,7664,726 ,0,0,0}, - {11482,11972,11962 ,726,726,7664 ,0,0,0}, {11960,11482,11480 ,726,726,7583 ,0,0,0}, - {11960,11964,11482 ,726,5488,726 ,0,0,0}, {11480,11961,11959 ,7583,5471,7920 ,0,0,0}, - {10509,11481,11954 ,726,726,726 ,0,0,0}, {11956,11480,11973 ,5472,7583,7793 ,0,0,0}, - {11974,11480,11479 ,5471,7583,7664 ,0,0,0}, {11480,11974,11973 ,7583,5471,7793 ,0,0,0}, - {11974,11479,10454 ,5471,7664,7920 ,0,0,0}, {10061,10060,11972 ,8054,8055,8056 ,0,0,0}, - {11965,10070,10061 ,8057,8058,8054 ,0,0,0}, {11965,11964,10070 ,8057,8058,8058 ,0,0,0}, - {11972,11965,10061 ,8056,8057,8054 ,0,0,0}, {10060,10239,11962 ,8055,8059,8060 ,0,0,0}, - {10137,10081,11971 ,8061,8062,8063 ,0,0,0}, {11963,11962,10239 ,8064,8060,8059 ,0,0,0}, - {10239,10137,11963 ,8059,8061,8064 ,0,0,0}, {11971,11963,10137 ,8063,8064,8061 ,0,0,0}, - {10060,11962,11972 ,8055,8060,8056 ,0,0,0}, {11971,10081,11968 ,8063,8062,8065 ,0,0,0}, - {10080,11969,11968 ,8066,8067,8065 ,0,0,0}, {11968,10081,10080 ,8065,8062,8066 ,0,0,0}, - {11969,10080,10240 ,8067,8066,8068 ,0,0,0}, {10088,11970,10240 ,8069,8070,8068 ,0,0,0}, - {10088,10087,11967 ,8069,8071,8072 ,0,0,0}, {10088,11967,11970 ,8069,8072,8070 ,0,0,0}, - {11966,10102,11954 ,8073,8074,8075 ,0,0,0}, {11967,10087,11966 ,8072,8071,8073 ,0,0,0}, - {11966,10087,10102 ,8073,8071,8074 ,0,0,0}, {10102,10105,11954 ,8074,8075,8075 ,0,0,0}, - {11969,10240,11970 ,8067,8068,8070 ,0,0,0}, {9893,11964,11960 ,8076,8058,8077 ,0,0,0}, - {11964,9893,10070 ,8058,8076,8058 ,0,0,0}, {11959,10141,11960 ,8078,8079,8077 ,0,0,0}, - {9893,11960,10141 ,8076,8077,8079 ,0,0,0}, {11959,11961,10085 ,8078,8080,8081 ,0,0,0}, - {10085,10141,11959 ,8081,8079,8078 ,0,0,0}, {10086,11961,11958 ,8082,8080,8083 ,0,0,0}, - {11961,10086,10085 ,8080,8082,8081 ,0,0,0}, {11957,10263,11958 ,8084,8085,8083 ,0,0,0}, - {10086,11958,10263 ,8082,8083,8085 ,0,0,0}, {11957,11955,10031 ,8084,8086,8087 ,0,0,0}, - {10031,10263,11957 ,8087,8085,8084 ,0,0,0}, {10030,11955,11953 ,8088,8086,8089 ,0,0,0}, - {11955,10030,10031 ,8086,8088,8087 ,0,0,0}, {11952,10114,11953 ,8090,8091,8089 ,0,0,0}, - {10030,11953,10114 ,8088,8089,8091 ,0,0,0}, {11952,11956,10154 ,8090,8092,8093 ,0,0,0}, - {10154,10114,11952 ,8093,8091,8090 ,0,0,0}, {10155,11956,11973 ,8094,8092,8095 ,0,0,0}, - {11956,10155,10154 ,8092,8094,8093 ,0,0,0}, {10155,11973,10156 ,8094,8095,8096 ,0,0,0}, - {10156,11973,11974 ,8096,8095,8096 ,0,0,0}, {10461,11974,10454 ,8097,8098,8097 ,0,0,0}, - {11974,10462,10465 ,8098,8097,8098 ,0,0,0}, {10461,10462,11974 ,8097,8097,8098 ,0,0,0}, - {11974,10471,10476 ,8098,8098,8097 ,0,0,0}, {10465,10471,11974 ,8098,8098,8098 ,0,0,0}, - {11974,10480,10439 ,8098,8098,8097 ,0,0,0}, {10476,10480,11974 ,8097,8098,8098 ,0,0,0}, - {11974,10443,10442 ,8098,8097,8097 ,0,0,0}, {10439,10443,11974 ,8097,8097,8098 ,0,0,0}, - {11974,10442,10156 ,8098,8097,8098 ,0,0,0}, {10518,11954,10105 ,8099,8099,8099 ,0,0,0}, - {10518,10574,11954 ,8099,8099,8099 ,0,0,0}, {11954,10574,10560 ,8099,8099,8099 ,0,0,0}, - {10514,10520,11954 ,8099,8099,8099 ,0,0,0}, {10514,11954,10560 ,8099,8099,8099 ,0,0,0}, - {10520,10556,11954 ,8099,8099,8099 ,0,0,0}, {11954,10503,10502 ,8099,8099,8099 ,0,0,0}, - {10556,10503,11954 ,8099,8099,8099 ,0,0,0}, {10509,11954,10507 ,8099,8099,8099 ,0,0,0}, - {10502,10507,11954 ,8099,8099,8099 ,0,0,0}, {8647,11975,10297 ,1359,8100,4482 ,0,0,0}, - {11976,10296,11977 ,4475,8101,8102 ,0,0,0}, {10298,10295,11978 ,8103,8104,4478 ,0,0,0}, - {10129,11979,10121 ,8105,8106,8107 ,0,0,0}, {11980,11981,10301 ,4472,8108,8109 ,0,0,0}, - {11982,10158,11983 ,8110,8111,8112 ,0,0,0}, {10157,10119,11984 ,8113,8114,8115 ,0,0,0}, - {10132,10125,11985 ,8116,8117,8118 ,0,0,0}, {10160,11986,10125 ,8119,8120,8117 ,0,0,0}, - {10150,11987,11988 ,8121,8122,8123 ,0,0,0}, {10132,11989,10152 ,8116,8124,8125 ,0,0,0}, - {11990,10149,11988 ,8126,8127,8123 ,0,0,0}, {10150,11988,10149 ,8121,8123,8127 ,0,0,0}, - {11990,11991,10147 ,8126,8128,8129 ,0,0,0}, {10147,10149,11990 ,8129,8127,8126 ,0,0,0}, - {10144,11991,11992 ,8130,8128,8131 ,0,0,0}, {11991,10144,10147 ,8128,8130,8129 ,0,0,0}, - {11993,10145,11992 ,8132,8133,8131 ,0,0,0}, {10144,11992,10145 ,8130,8131,8133 ,0,0,0}, - {11993,8666,8667 ,8132,1435,1435 ,0,0,0}, {8667,10145,11993 ,1435,8133,8132 ,0,0,0}, - {11985,10125,11986 ,8118,8117,8120 ,0,0,0}, {11987,10152,11989 ,8122,8125,8124 ,0,0,0}, - {10152,11987,10150 ,8125,8122,8121 ,0,0,0}, {11985,11989,10132 ,8118,8124,8116 ,0,0,0}, - {11982,11986,10160 ,8110,8120,8119 ,0,0,0}, {10157,11984,11983 ,8113,8115,8112 ,0,0,0}, - {10157,11983,10158 ,8113,8112,8111 ,0,0,0}, {10160,10158,11982 ,8119,8111,8110 ,0,0,0}, - {10119,11994,11984 ,8114,8134,8115 ,0,0,0}, {11994,10119,10121 ,8134,8114,8107 ,0,0,0}, - {11981,11979,10129 ,8108,8106,8105 ,0,0,0}, {11979,11994,10121 ,8106,8134,8107 ,0,0,0}, - {10301,11981,10129 ,8109,8108,8105 ,0,0,0}, {10277,11976,11980 ,4474,4475,4472 ,0,0,0}, - {10277,11980,10301 ,4474,4472,8109 ,0,0,0}, {10296,10298,11977 ,8101,8103,8102 ,0,0,0}, - {10277,10296,11976 ,4474,8101,4475 ,0,0,0}, {10295,11975,11978 ,8104,8100,4478 ,0,0,0}, - {11977,10298,11978 ,8102,8103,4478 ,0,0,0}, {8647,10297,8645 ,1359,4482,1359 ,0,0,0}, - {11975,10295,10297 ,8100,8104,4482 ,0,0,0}, {8641,11979,11981 ,726,726,726 ,0,0,0}, - {11987,8648,11988 ,726,7626,7758 ,0,0,0}, {11993,11992,11991 ,7625,7625,726 ,0,0,0}, - {11989,11985,8628 ,8135,7628,7626 ,0,0,0}, {8628,8626,11989 ,7626,7626,8135 ,0,0,0}, - {8638,11983,11984 ,726,7627,726 ,0,0,0}, {8631,11982,8632 ,726,7628,726 ,0,0,0}, - {8635,11979,8641 ,726,726,726 ,0,0,0}, {11984,11994,8640 ,726,726,726 ,0,0,0}, - {11976,11977,11978 ,7628,7628,726 ,0,0,0}, {8644,8641,11981 ,726,726,726 ,0,0,0}, - {8647,8644,11975 ,726,726,726 ,0,0,0}, {11975,11976,11978 ,726,7628,726 ,0,0,0}, - {11975,8644,11976 ,726,726,7628 ,0,0,0}, {11981,11980,8644 ,726,726,726 ,0,0,0}, - {8644,11980,11976 ,726,726,7628 ,0,0,0}, {11979,8635,8640 ,726,726,726 ,0,0,0}, - {8644,8643,8641 ,726,726,726 ,0,0,0}, {8640,8638,11984 ,726,726,726 ,0,0,0}, - {8640,11994,11979 ,726,726,726 ,0,0,0}, {11982,11983,8632 ,7628,7627,726 ,0,0,0}, - {8632,11983,8638 ,726,7627,726 ,0,0,0}, {8629,11986,8631 ,726,726,726 ,0,0,0}, - {8631,11986,11982 ,726,726,7628 ,0,0,0}, {8629,8628,11985 ,726,7626,7628 ,0,0,0}, - {11985,11986,8629 ,7628,726,726 ,0,0,0}, {8626,8648,11987 ,7626,7626,726 ,0,0,0}, - {8626,11987,11989 ,7626,726,8135 ,0,0,0}, {8649,11988,8648 ,7626,7758,7626 ,0,0,0}, - {11990,11988,8652 ,8135,7758,7628 ,0,0,0}, {8649,8652,11988 ,7626,7628,7758 ,0,0,0}, - {8652,8654,11991 ,7628,726,726 ,0,0,0}, {11991,11990,8652 ,726,8135,7628 ,0,0,0}, - {11993,8654,8655 ,7625,726,7626 ,0,0,0}, {8654,11993,11991 ,726,7625,726 ,0,0,0}, - {8658,8661,8664 ,7626,726,7626 ,0,0,0}, {8655,8658,11993 ,7626,7626,7625 ,0,0,0}, - {8664,11993,8658 ,7626,7625,7626 ,0,0,0}, {8658,8660,8661 ,7626,7627,726 ,0,0,0}, - {11993,8664,8666 ,7625,7626,8135 ,0,0,0}, {8608,11995,10283 ,1359,8136,8137 ,0,0,0}, - {10266,10268,11996 ,8138,8139,8140 ,0,0,0}, {10285,10287,11997 ,8141,8142,8143 ,0,0,0}, - {10073,11998,10072 ,8144,8145,8146 ,0,0,0}, {11999,12000,10267 ,8147,8148,8149 ,0,0,0}, - {12001,12002,10265 ,8150,8151,8152 ,0,0,0}, {12001,10264,12003 ,8150,8153,8154 ,0,0,0}, - {12004,12005,10197 ,8155,8156,8157 ,0,0,0}, {10197,10196,12004 ,8157,8158,8155 ,0,0,0}, - {10111,12005,12006 ,8159,8156,8160 ,0,0,0}, {12005,10111,10197 ,8156,8159,8157 ,0,0,0}, - {12007,10110,12006 ,8161,8162,8160 ,0,0,0}, {10111,12006,10110 ,8159,8160,8162 ,0,0,0}, - {12007,8622,8623 ,8161,1435,1435 ,0,0,0}, {8623,10110,12007 ,1435,8162,8161 ,0,0,0}, - {11998,10073,12000 ,8145,8144,8148 ,0,0,0}, {12002,10196,10265 ,8151,8158,8152 ,0,0,0}, - {12004,10196,12002 ,8155,8158,8151 ,0,0,0}, {11996,10268,12008 ,8140,8139,8163 ,0,0,0}, - {12003,10264,10072 ,8154,8153,8146 ,0,0,0}, {12001,10265,10264 ,8150,8152,8153 ,0,0,0}, - {11998,12003,10072 ,8145,8154,8146 ,0,0,0}, {10267,12000,10073 ,8149,8148,8144 ,0,0,0}, - {10266,11996,11999 ,8138,8140,8147 ,0,0,0}, {11999,10267,10266 ,8147,8149,8138 ,0,0,0}, - {10287,11995,11997 ,8142,8136,8143 ,0,0,0}, {12008,10285,11997 ,8163,8141,8143 ,0,0,0}, - {10268,10285,12008 ,8139,8141,8163 ,0,0,0}, {8608,10283,8609 ,1359,8137,1359 ,0,0,0}, - {11995,10287,10283 ,8136,8142,8137 ,0,0,0}, {12005,12000,11999 ,726,7661,7661 ,0,0,0}, - {12001,12003,12004 ,7661,7658,726 ,0,0,0}, {12004,12002,12001 ,726,726,7661 ,0,0,0}, - {11998,12000,12004 ,7658,7661,726 ,0,0,0}, {11998,12004,12003 ,7658,726,7658 ,0,0,0}, - {11999,12006,12005 ,7661,726,726 ,0,0,0}, {12000,12005,12004 ,7661,726,726 ,0,0,0}, - {12006,11999,11996 ,726,7661,7658 ,0,0,0}, {11996,12008,12007 ,7658,7661,726 ,0,0,0}, - {12007,12006,11996 ,726,726,7658 ,0,0,0}, {8622,12008,11997 ,726,7661,7658 ,0,0,0}, - {12008,8622,12007 ,7661,726,726 ,0,0,0}, {8607,8616,8608 ,7658,726,726 ,0,0,0}, - {11995,8620,11997 ,7658,7660,7658 ,0,0,0}, {8614,8607,8605 ,726,7658,726 ,0,0,0}, - {8595,8594,8601 ,726,726,726 ,0,0,0}, {8611,8603,8610 ,726,726,726 ,0,0,0}, - {8601,8598,8597 ,726,726,726 ,0,0,0}, {8601,8594,8610 ,726,726,726 ,0,0,0}, - {8595,8601,8597 ,726,726,726 ,0,0,0}, {8605,8603,8611 ,726,726,726 ,0,0,0}, - {8603,8601,8610 ,726,726,726 ,0,0,0}, {8616,8607,8614 ,726,7658,726 ,0,0,0}, - {8614,8605,8611 ,726,726,726 ,0,0,0}, {8608,8617,11995 ,726,726,7658 ,0,0,0}, - {8608,8616,8617 ,726,726,726 ,0,0,0}, {11997,8620,8622 ,7658,7660,726 ,0,0,0}, - {8617,8620,11995 ,726,7660,7658 ,0,0,0}, {12009,12010,11477 ,726,726,7664 ,0,0,0}, - {12011,12009,11477 ,726,726,7664 ,0,0,0}, {12011,11477,12012 ,726,7664,726 ,0,0,0}, - {12013,11477,12010 ,726,7664,726 ,0,0,0}, {12014,12015,11477 ,726,726,7664 ,0,0,0}, - {12014,11477,12013 ,726,7664,726 ,0,0,0}, {12016,11477,11475 ,726,7664,726 ,0,0,0}, - {12012,11477,12016 ,726,7664,726 ,0,0,0}, {12017,11477,12015 ,726,7664,726 ,0,0,0}, - {11477,12017,12018 ,7664,726,726 ,0,0,0}, {12016,11475,12019 ,726,726,726 ,0,0,0}, - {12020,11477,12018 ,726,7664,726 ,0,0,0}, {12021,12019,11475 ,7583,726,726 ,0,0,0}, - {11475,12022,12021 ,726,7664,7583 ,0,0,0}, {11477,12020,12023 ,7664,726,726 ,0,0,0}, - {11477,12023,12024 ,7664,726,726 ,0,0,0}, {12025,12022,11475 ,726,7664,726 ,0,0,0}, - {12026,12027,11475 ,726,726,726 ,0,0,0}, {12027,12025,11475 ,726,726,726 ,0,0,0}, - {12028,11475,12029 ,726,726,726 ,0,0,0}, {12028,12026,11475 ,726,726,726 ,0,0,0}, - {11478,12024,10415 ,7664,726,726 ,0,0,0}, {12024,11478,11477 ,726,7664,7664 ,0,0,0}, - {12029,11475,12030 ,726,726,726 ,0,0,0}, {12031,11475,11476 ,726,726,7664 ,0,0,0}, - {11475,12031,12030 ,726,726,726 ,0,0,0}, {12031,11476,10339 ,726,7664,5488 ,0,0,0}, - {10127,10120,12009 ,8164,8165,8166 ,0,0,0}, {12011,10128,10127 ,8167,8168,8164 ,0,0,0}, - {12011,12012,10128 ,8167,8168,8168 ,0,0,0}, {12009,12011,10127 ,8166,8167,8164 ,0,0,0}, - {10120,10261,12010 ,8165,8169,8170 ,0,0,0}, {10159,10161,12014 ,8171,8172,8173 ,0,0,0}, - {12013,12010,10261 ,8174,8170,8169 ,0,0,0}, {10261,10159,12013 ,8169,8171,8174 ,0,0,0}, - {12014,12013,10159 ,8173,8174,8171 ,0,0,0}, {10120,12010,12009 ,8165,8170,8166 ,0,0,0}, - {12014,10161,12015 ,8173,8172,8175 ,0,0,0}, {10124,12017,12015 ,8176,8177,8175 ,0,0,0}, - {12015,10161,10124 ,8175,8172,8176 ,0,0,0}, {12017,10124,10126 ,8177,8176,8178 ,0,0,0}, - {10131,12018,10126 ,8179,8180,8178 ,0,0,0}, {10131,10163,12020 ,8179,8181,8182 ,0,0,0}, - {10131,12020,12018 ,8179,8182,8180 ,0,0,0}, {12023,10165,12024 ,8183,8184,8185 ,0,0,0}, - {12020,10163,12023 ,8182,8181,8183 ,0,0,0}, {12023,10163,10165 ,8183,8181,8184 ,0,0,0}, - {10165,10164,12024 ,8184,8185,8185 ,0,0,0}, {12017,10126,12018 ,8177,8178,8180 ,0,0,0}, - {10123,12012,12016 ,8186,8168,8187 ,0,0,0}, {12012,10123,10128 ,8168,8186,8168 ,0,0,0}, - {12019,10122,12016 ,8188,8189,8187 ,0,0,0}, {10123,12016,10122 ,8186,8187,8189 ,0,0,0}, - {12019,12021,10289 ,8188,8190,8191 ,0,0,0}, {10289,10122,12019 ,8191,8189,8188 ,0,0,0}, - {10117,12021,12022 ,8192,8190,8193 ,0,0,0}, {12021,10117,10289 ,8190,8192,8191 ,0,0,0}, - {12025,10118,12022 ,8194,8195,8193 ,0,0,0}, {10117,12022,10118 ,8192,8193,8195 ,0,0,0}, - {12025,12027,10191 ,8194,8196,8197 ,0,0,0}, {10191,10118,12025 ,8197,8195,8194 ,0,0,0}, - {10192,12027,12026 ,8198,8196,8199 ,0,0,0}, {12027,10192,10191 ,8196,8198,8197 ,0,0,0}, - {12028,9935,12026 ,8200,8201,8199 ,0,0,0}, {10192,12026,9935 ,8198,8199,8201 ,0,0,0}, - {12028,12029,9938 ,8200,8202,8203 ,0,0,0}, {9938,9935,12028 ,8203,8201,8200 ,0,0,0}, - {9939,12029,12030 ,8204,8202,8205 ,0,0,0}, {12029,9939,9938 ,8202,8204,8203 ,0,0,0}, - {9939,12030,9940 ,8204,8205,8206 ,0,0,0}, {9940,12030,12031 ,8206,8205,8206 ,0,0,0}, - {10340,12031,10339 ,8207,8207,8207 ,0,0,0}, {12031,10370,10373 ,8207,8207,8207 ,0,0,0}, - {10340,10370,12031 ,8207,8207,8207 ,0,0,0}, {12031,10379,10384 ,8207,8207,8207 ,0,0,0}, - {10373,10379,12031 ,8207,8207,8207 ,0,0,0}, {12031,10388,10318 ,8207,8207,8207 ,0,0,0}, - {10384,10388,12031 ,8207,8207,8207 ,0,0,0}, {12031,10321,10320 ,8207,8207,8207 ,0,0,0}, - {10318,10321,12031 ,8207,8207,8207 ,0,0,0}, {12031,10320,9940 ,8207,8207,8207 ,0,0,0}, - {10430,12024,10164 ,8208,8208,8208 ,0,0,0}, {10430,10481,12024 ,8208,8208,8208 ,0,0,0}, - {12024,10481,10467 ,8208,8208,8208 ,0,0,0}, {10424,10417,12024 ,8208,8208,8208 ,0,0,0}, - {10424,12024,10467 ,8208,8208,8208 ,0,0,0}, {10417,10463,12024 ,8208,8208,8208 ,0,0,0}, - {12024,10455,10409 ,8208,8208,8208 ,0,0,0}, {10463,10455,12024 ,8208,8208,8208 ,0,0,0}, - {10415,12024,10411 ,8208,8208,8208 ,0,0,0}, {10409,10411,12024 ,8208,8208,8208 ,0,0,0}, - {8571,12032,9927 ,1711,8209,4414 ,0,0,0}, {12033,10190,12034 ,8210,8211,8212 ,0,0,0}, - {10175,9928,12035 ,8213,8214,4410 ,0,0,0}, {10189,12036,9919 ,4402,8215,8216 ,0,0,0}, - {12037,12038,10188 ,8217,8218,8219 ,0,0,0}, {12039,9949,12040 ,8220,8221,8222 ,0,0,0}, - {9948,10174,12041 ,8223,8224,8225 ,0,0,0}, {9922,9921,12042 ,8226,8227,8228 ,0,0,0}, - {9944,12043,9921 ,8229,8230,8227 ,0,0,0}, {9925,12044,12045 ,8231,8232,8233 ,0,0,0}, - {9922,12046,9924 ,8226,8234,8235 ,0,0,0}, {12047,9941,12045 ,8236,8237,8233 ,0,0,0}, - {9925,12045,9941 ,8231,8233,8237 ,0,0,0}, {12047,12048,9929 ,8236,8238,8239 ,0,0,0}, - {9929,9941,12047 ,8239,8237,8236 ,0,0,0}, {10177,12048,12049 ,8240,8238,8241 ,0,0,0}, - {12048,10177,9929 ,8238,8240,8239 ,0,0,0}, {12050,9937,12049 ,8242,8243,8241 ,0,0,0}, - {10177,12049,9937 ,8240,8241,8243 ,0,0,0}, {12050,8590,8591 ,8242,1790,1790 ,0,0,0}, - {8591,9937,12050 ,1790,8243,8242 ,0,0,0}, {12042,9921,12043 ,8228,8227,8230 ,0,0,0}, - {12044,9924,12046 ,8232,8235,8234 ,0,0,0}, {9924,12044,9925 ,8235,8232,8231 ,0,0,0}, - {12042,12046,9922 ,8228,8234,8226 ,0,0,0}, {12039,12043,9944 ,8220,8230,8229 ,0,0,0}, - {9948,12041,12040 ,8223,8225,8222 ,0,0,0}, {9948,12040,9949 ,8223,8222,8221 ,0,0,0}, - {9944,9949,12039 ,8229,8221,8220 ,0,0,0}, {10174,12051,12041 ,8224,8244,8225 ,0,0,0}, - {12051,10174,9919 ,8244,8224,8216 ,0,0,0}, {12038,12036,10189 ,8218,8215,4402 ,0,0,0}, - {12036,12051,9919 ,8215,8244,8216 ,0,0,0}, {10188,12038,10189 ,8219,8218,4402 ,0,0,0}, - {9889,12033,12037 ,8245,8210,8217 ,0,0,0}, {9889,12037,10188 ,8245,8217,8219 ,0,0,0}, - {10190,10175,12034 ,8211,8213,8212 ,0,0,0}, {9889,10190,12033 ,8245,8211,8210 ,0,0,0}, - {9928,12032,12035 ,8214,8209,4410 ,0,0,0}, {12034,10175,12035 ,8212,8213,4410 ,0,0,0}, - {8571,9927,8569 ,1711,4414,1711 ,0,0,0}, {12032,9928,9927 ,8209,8214,4414 ,0,0,0}, - {12037,12042,12043 ,726,726,7626 ,0,0,0}, {12051,12040,12041 ,726,726,726 ,0,0,0}, - {12039,12051,12036 ,726,726,726 ,0,0,0}, {12038,12039,12036 ,726,726,726 ,0,0,0}, - {12038,12043,12039 ,726,7626,726 ,0,0,0}, {12051,12039,12040 ,726,726,726 ,0,0,0}, - {12038,12037,12043 ,726,726,7626 ,0,0,0}, {12033,12046,12042 ,726,726,726 ,0,0,0}, - {12037,12033,12042 ,726,726,726 ,0,0,0}, {12046,12034,12044 ,726,726,7626 ,0,0,0}, - {12034,12046,12033 ,726,726,726 ,0,0,0}, {12045,12044,12035 ,7628,7626,726 ,0,0,0}, - {12034,12035,12044 ,726,726,7626 ,0,0,0}, {12032,12047,12045 ,726,726,7628 ,0,0,0}, - {12045,12035,12032 ,7628,726,726 ,0,0,0}, {12047,8571,12048 ,726,726,726 ,0,0,0}, - {8571,12047,12032 ,726,726,726 ,0,0,0}, {12049,12048,8568 ,7625,726,726 ,0,0,0}, - {8571,8568,12048 ,726,726,726 ,0,0,0}, {12049,8568,8567 ,7625,726,726 ,0,0,0}, - {12050,12049,8567 ,726,7625,726 ,0,0,0}, {8567,8565,12050 ,726,726,726 ,0,0,0}, - {8559,8590,8565 ,726,726,726 ,0,0,0}, {12050,8565,8590 ,726,726,726 ,0,0,0}, - {8562,8556,8584 ,726,726,7625 ,0,0,0}, {8559,8564,8588 ,726,726,726 ,0,0,0}, - {8553,8578,8579 ,7626,726,726 ,0,0,0}, {8579,8582,8555 ,726,726,726 ,0,0,0}, - {8578,8552,8576 ,726,7625,7625 ,0,0,0}, {8552,8573,8576 ,7625,726,7625 ,0,0,0}, - {8550,8573,8552 ,726,726,7625 ,0,0,0}, {8550,8572,8573 ,726,726,726 ,0,0,0}, - {8555,8553,8579 ,726,7626,726 ,0,0,0}, {8552,8578,8553 ,7625,726,7626 ,0,0,0}, - {8582,8584,8556 ,726,7625,726 ,0,0,0}, {8555,8582,8556 ,726,726,726 ,0,0,0}, - {8562,8585,8564 ,726,726,726 ,0,0,0}, {8562,8584,8585 ,726,7625,726 ,0,0,0}, - {8559,8588,8590 ,726,726,726 ,0,0,0}, {8585,8588,8564 ,726,726,726 ,0,0,0}, - {8532,12052,10201 ,1711,8246,8247 ,0,0,0}, {10260,10274,12053 ,8248,8249,8250 ,0,0,0}, - {10273,10202,12054 ,8251,8252,8253 ,0,0,0}, {10113,12055,10112 ,8254,8255,8256 ,0,0,0}, - {12056,12057,10294 ,8257,8258,8259 ,0,0,0}, {12058,12059,10292 ,8260,8261,8262 ,0,0,0}, - {12058,10291,12060 ,8260,8263,8264 ,0,0,0}, {12061,12062,10194 ,8265,8266,8267 ,0,0,0}, - {10194,10195,12061 ,8267,8268,8265 ,0,0,0}, {10290,12062,12063 ,8269,8266,8270 ,0,0,0}, - {12062,10290,10194 ,8266,8269,8267 ,0,0,0}, {12064,10193,12063 ,8271,8272,8270 ,0,0,0}, - {10290,12063,10193 ,8269,8270,8272 ,0,0,0}, {12064,8546,8547 ,8271,1790,1790 ,0,0,0}, - {8547,10193,12064 ,1790,8272,8271 ,0,0,0}, {12055,10113,12057 ,8255,8254,8258 ,0,0,0}, - {12059,10195,10292 ,8261,8268,8262 ,0,0,0}, {12061,10195,12059 ,8265,8268,8261 ,0,0,0}, - {12053,10274,12065 ,8250,8249,8273 ,0,0,0}, {12060,10291,10112 ,8264,8263,8256 ,0,0,0}, - {12058,10292,10291 ,8260,8262,8263 ,0,0,0}, {12055,12060,10112 ,8255,8264,8256 ,0,0,0}, - {10294,12057,10113 ,8259,8258,8254 ,0,0,0}, {10260,12053,12056 ,8248,8250,8257 ,0,0,0}, - {12056,10294,10260 ,8257,8259,8248 ,0,0,0}, {10202,12052,12054 ,8252,8246,8253 ,0,0,0}, - {12065,10273,12054 ,8273,8251,8253 ,0,0,0}, {10274,10273,12065 ,8249,8251,8273 ,0,0,0}, - {8532,10201,8533 ,1711,8247,1711 ,0,0,0}, {12052,10202,10201 ,8246,8252,8247 ,0,0,0}, - {8546,12064,12063 ,726,7658,726 ,0,0,0}, {12065,8521,12053 ,726,726,726 ,0,0,0}, - {8544,12063,12062 ,7660,726,7660 ,0,0,0}, {12058,8540,12059 ,7660,726,7660 ,0,0,0}, - {8541,8544,12061 ,7660,7660,7583 ,0,0,0}, {8534,12055,12057 ,7660,7661,7661 ,0,0,0}, - {8538,12058,12060 ,726,7660,7658 ,0,0,0}, {8519,12053,8521 ,726,726,726 ,0,0,0}, - {12057,12056,8518 ,7661,726,726 ,0,0,0}, {12052,8527,8525 ,726,726,726 ,0,0,0}, - {12054,8522,12065 ,726,726,726 ,0,0,0}, {8532,8531,8527 ,726,726,726 ,0,0,0}, - {8529,8527,8531 ,726,726,726 ,0,0,0}, {8527,12052,8532 ,726,726,726 ,0,0,0}, - {12054,8525,8522 ,726,726,726 ,0,0,0}, {12054,12052,8525 ,726,726,726 ,0,0,0}, - {12056,12053,8519 ,726,726,726 ,0,0,0}, {8521,12065,8522 ,726,726,726 ,0,0,0}, - {8518,8534,12057 ,726,7660,7661 ,0,0,0}, {8519,8518,12056 ,726,726,726 ,0,0,0}, - {12060,12055,8535 ,7658,7661,7659 ,0,0,0}, {8535,12055,8534 ,7659,7661,7660 ,0,0,0}, - {8538,12060,8535 ,726,7658,7659 ,0,0,0}, {8541,12059,8540 ,7660,7660,726 ,0,0,0}, - {12058,8538,8540 ,7660,726,726 ,0,0,0}, {8544,12062,12061 ,7660,7660,7583 ,0,0,0}, - {8541,12061,12059 ,7660,7583,7660 ,0,0,0}, {8544,8546,12063 ,7660,726,726 ,0,0,0}, - {10299,8491,12066 ,8274,8275,8276 ,0,0,0}, {10300,10276,12067 ,8277,8278,8279 ,0,0,0}, - {12068,10276,10293 ,8280,8278,8281 ,0,0,0}, {12069,12070,10200 ,8282,8283,8284 ,0,0,0}, - {12071,10272,10271 ,8285,8286,8287 ,0,0,0}, {10281,10269,12072 ,8288,8289,8290 ,0,0,0}, - {10280,12073,12074 ,8291,8292,8293 ,0,0,0}, {10303,12075,10286 ,8294,8295,8296 ,0,0,0}, - {12076,12077,10282 ,1631,8297,1631 ,0,0,0}, {12078,12079,10284 ,8298,8299,8300 ,0,0,0}, - {12078,10304,12080 ,8298,8301,8302 ,0,0,0}, {12081,12082,10279 ,8303,8304,8305 ,0,0,0}, - {12081,10278,12079 ,8303,8306,8299 ,0,0,0}, {10217,12082,12083 ,8307,8304,8308 ,0,0,0}, - {12082,10217,10279 ,8304,8307,8305 ,0,0,0}, {12084,10258,12083 ,8309,8310,8308 ,0,0,0}, - {10217,12083,10258 ,8307,8308,8310 ,0,0,0}, {10199,12084,10252 ,8311,8309,8312 ,0,0,0}, - {10199,10258,12084 ,8311,8310,8309 ,0,0,0}, {10250,10252,12085 ,8313,8312,8314 ,0,0,0}, - {12084,12085,10252 ,8309,8314,8312 ,0,0,0}, {12086,8515,10250 ,8315,126,8313 ,0,0,0}, - {10250,12085,12086 ,8313,8314,8315 ,0,0,0}, {8513,8515,12086 ,126,126,8315 ,0,0,0}, - {10278,10284,12079 ,8306,8300,8299 ,0,0,0}, {12081,10279,10278 ,8303,8305,8306 ,0,0,0}, - {10304,10286,12080 ,8301,8296,8302 ,0,0,0}, {12078,10284,10304 ,8298,8300,8301 ,0,0,0}, - {12077,12075,10303 ,8297,8295,8294 ,0,0,0}, {12075,12080,10286 ,8295,8302,8296 ,0,0,0}, - {10281,12076,10282 ,8288,1631,1631 ,0,0,0}, {10282,12077,10303 ,1631,8297,8294 ,0,0,0}, - {10269,12074,12072 ,8289,8293,8290 ,0,0,0}, {10281,12072,12076 ,8288,8290,1631 ,0,0,0}, - {10280,10302,12073 ,8291,8316,8292 ,0,0,0}, {10269,10280,12074 ,8289,8291,8293 ,0,0,0}, - {10200,12070,10302 ,8284,8283,8316 ,0,0,0}, {12073,10302,12070 ,8292,8316,8283 ,0,0,0}, - {12071,12069,10272 ,8285,8282,8286 ,0,0,0}, {12069,10200,10272 ,8282,8284,8286 ,0,0,0}, - {10300,12087,10271 ,8277,8317,8287 ,0,0,0}, {12087,12071,10271 ,8317,8285,8287 ,0,0,0}, - {10276,12088,12067 ,8278,8318,8279 ,0,0,0}, {10300,12067,12087 ,8277,8279,8317 ,0,0,0}, - {12068,10293,12066 ,8280,8281,8276 ,0,0,0}, {12088,10276,12068 ,8318,8278,8280 ,0,0,0}, - {8491,10299,8490 ,8275,8274,4114 ,0,0,0}, {12066,10293,10299 ,8276,8281,8274 ,0,0,0}, - {12078,12089,12079 ,726,726,726 ,0,0,0}, {12090,8464,12086 ,726,726,726 ,0,0,0}, - {12091,12082,12092 ,726,726,726 ,0,0,0}, {8495,8449,8448 ,726,726,7661 ,0,0,0}, - {8504,8506,8458 ,726,726,726 ,0,0,0}, {12093,12085,12084 ,726,726,726 ,0,0,0}, - {8509,8512,8463 ,726,726,726 ,0,0,0}, {8513,8464,8512 ,726,726,726 ,0,0,0}, - {8461,8459,8510 ,7658,726,726 ,0,0,0}, {8509,8463,8461 ,726,726,7658 ,0,0,0}, - {12093,12090,12085 ,726,726,726 ,0,0,0}, {8506,8507,8459 ,726,726,726 ,0,0,0}, - {8504,8458,8455 ,726,726,726 ,0,0,0}, {8500,8453,8498 ,726,726,726 ,0,0,0}, - {8501,8455,8453 ,726,726,726 ,0,0,0}, {8449,8495,8498 ,726,726,726 ,0,0,0}, - {12091,12084,12083 ,726,726,726 ,0,0,0}, {12079,12094,12081 ,726,7661,726 ,0,0,0}, - {12081,12094,12092 ,726,7661,726 ,0,0,0}, {8428,8468,8467 ,7658,726,7658 ,0,0,0}, - {8494,8448,8428 ,726,7661,7658 ,0,0,0}, {12095,12089,12080 ,726,726,726 ,0,0,0}, - {8468,8432,8469 ,726,7658,726 ,0,0,0}, {8471,8433,8434 ,7661,7658,726 ,0,0,0}, - {12075,12077,12096 ,726,7661,726 ,0,0,0}, {12075,12096,12095 ,726,726,726 ,0,0,0}, - {12077,12076,12097 ,7661,7658,7658 ,0,0,0}, {8475,8474,8434 ,726,726,726 ,0,0,0}, - {8438,8477,8435 ,726,7583,726 ,0,0,0}, {12098,12099,12074 ,726,726,726 ,0,0,0}, - {12099,12097,12072 ,726,7658,726 ,0,0,0}, {8487,8441,8444 ,7664,726,7664 ,0,0,0}, - {12098,12074,12073 ,726,726,7661 ,0,0,0}, {12100,12073,12070 ,726,7661,7664 ,0,0,0}, - {8447,8491,8489 ,726,726,7664 ,0,0,0}, {12101,12066,8447 ,7664,726,726 ,0,0,0}, - {12100,12069,12102 ,726,7583,726 ,0,0,0}, {12068,12103,12088 ,7664,7664,726 ,0,0,0}, - {8469,8432,8433 ,726,7658,7658 ,0,0,0}, {12067,12088,12104 ,7664,726,7664 ,0,0,0}, - {12103,12104,12088 ,7664,7664,726 ,0,0,0}, {12068,12066,12101 ,7664,726,7664 ,0,0,0}, - {12068,12101,12103 ,7664,7664,7664 ,0,0,0}, {12105,12102,12071 ,7664,726,7583 ,0,0,0}, - {12105,12071,12087 ,7664,7583,7664 ,0,0,0}, {8491,8447,12066 ,726,726,726 ,0,0,0}, - {8440,8441,8483 ,726,726,726 ,0,0,0}, {8438,8440,8480 ,726,726,7664 ,0,0,0}, - {12105,12087,12104 ,7664,7664,7664 ,0,0,0}, {12087,12067,12104 ,7664,7664,7664 ,0,0,0}, - {12069,12071,12102 ,7583,7583,726 ,0,0,0}, {12070,12069,12100 ,7664,7583,726 ,0,0,0}, - {12098,12073,12100 ,726,7661,726 ,0,0,0}, {12072,12074,12099 ,726,726,726 ,0,0,0}, - {12076,12072,12097 ,7658,726,7658 ,0,0,0}, {12096,12077,12097 ,726,7661,7658 ,0,0,0}, - {12080,12075,12095 ,726,726,726 ,0,0,0}, {12078,12080,12089 ,726,726,726 ,0,0,0}, - {12094,12079,12089 ,7661,726,726 ,0,0,0}, {12082,12081,12092 ,726,726,726 ,0,0,0}, - {12083,12082,12091 ,726,726,726 ,0,0,0}, {12093,12084,12091 ,726,726,726 ,0,0,0}, - {12086,12085,12090 ,726,726,726 ,0,0,0}, {8513,12086,8464 ,726,726,726 ,0,0,0}, - {8463,8512,8464 ,726,726,726 ,0,0,0}, {8510,8509,8461 ,726,726,7658 ,0,0,0}, - {8507,8510,8459 ,726,726,726 ,0,0,0}, {8458,8506,8459 ,726,726,726 ,0,0,0}, - {8501,8504,8455 ,726,726,726 ,0,0,0}, {8500,8501,8453 ,726,726,726 ,0,0,0}, - {8449,8498,8453 ,726,726,726 ,0,0,0}, {8494,8495,8448 ,726,726,7661 ,0,0,0}, - {8467,8494,8428 ,7658,726,7658 ,0,0,0}, {8432,8468,8428 ,7658,726,7658 ,0,0,0}, - {8474,8471,8434 ,726,7661,726 ,0,0,0}, {8471,8469,8433 ,7661,726,7658 ,0,0,0}, - {8435,8475,8434 ,726,726,726 ,0,0,0}, {8438,8480,8477 ,726,7664,7583 ,0,0,0}, - {8435,8477,8475 ,726,7583,726 ,0,0,0}, {8440,8481,8480 ,726,7664,7664 ,0,0,0}, - {8483,8441,8487 ,726,726,7664 ,0,0,0}, {8481,8440,8483 ,7664,726,726 ,0,0,0}, - {8487,8444,8489 ,7664,7664,7664 ,0,0,0}, {8447,8489,8444 ,726,7664,7664 ,0,0,0}, - {12106,12107,8431 ,726,726,726 ,0,0,0}, {8450,8452,8460 ,726,726,726 ,0,0,0}, - {8429,8450,8465 ,726,726,726 ,0,0,0}, {8431,8430,12106 ,726,726,726 ,0,0,0}, - {8456,8457,8460 ,726,726,726 ,0,0,0}, {8451,8454,8452 ,726,726,726 ,0,0,0}, - {8456,8460,8454 ,726,726,726 ,0,0,0}, {8452,8454,8460 ,726,726,726 ,0,0,0}, - {8460,8462,8450 ,726,726,726 ,0,0,0}, {12106,8429,8465 ,726,726,726 ,0,0,0}, - {8465,8450,8462 ,726,726,726 ,0,0,0}, {8431,12107,12108 ,726,726,726 ,0,0,0}, - {12106,8430,8429 ,726,726,726 ,0,0,0}, {8436,12108,12109 ,726,726,726 ,0,0,0}, - {12108,8436,8431 ,726,726,726 ,0,0,0}, {12109,8439,8437 ,726,726,7658 ,0,0,0}, - {8436,12109,8437 ,726,726,7658 ,0,0,0}, {12110,8439,12109 ,726,726,726 ,0,0,0}, - {8439,12111,8442 ,726,726,7661 ,0,0,0}, {12111,8439,12110 ,726,726,726 ,0,0,0}, - {12111,12112,8442 ,726,726,7661 ,0,0,0}, {8443,12112,8445 ,726,726,7661 ,0,0,0}, - {8443,8442,12112 ,726,7661,726 ,0,0,0}, {8445,12113,12114 ,7661,726,726 ,0,0,0}, - {12112,12113,8445 ,726,726,7661 ,0,0,0}, {12115,8446,12114 ,726,7658,726 ,0,0,0}, - {8445,12114,8446 ,7661,726,7658 ,0,0,0}, {12116,12117,12118 ,726,726,7660 ,0,0,0}, - {12118,12119,12116 ,7660,726,726 ,0,0,0}, {12117,12120,12121 ,726,726,7658 ,0,0,0}, - {12117,12115,12118 ,726,726,7660 ,0,0,0}, {12117,12122,12115 ,726,7661,726 ,0,0,0}, - {12117,12116,12120 ,726,726,726 ,0,0,0}, {12115,12122,8446 ,726,7661,7658 ,0,0,0}, - {12122,8447,8446 ,8319,81,8320 ,0,0,0}, {12120,12105,12121 ,8321,8322,8323 ,0,0,0}, - {12117,12104,12103 ,8324,8325,8326 ,0,0,0}, {12118,12115,12098 ,8327,8328,8329 ,0,0,0}, - {12116,12119,12100 ,8330,8331,8332 ,0,0,0}, {12112,12096,12113 ,8333,8334,8335 ,0,0,0}, - {12097,12114,12113 ,8336,8337,8335 ,0,0,0}, {12110,12094,12111 ,7530,8338,8339 ,0,0,0}, - {12089,12112,12111 ,8340,8333,8339 ,0,0,0}, {12109,12091,12092 ,8341,8342,8343 ,0,0,0}, - {12092,12110,12109 ,8343,7530,8341 ,0,0,0}, {12091,12108,12093 ,8342,8344,8345 ,0,0,0}, - {12108,12091,12109 ,8344,8342,8341 ,0,0,0}, {12090,12093,12107 ,8346,8345,8347 ,0,0,0}, - {12108,12107,12093 ,8344,8347,8345 ,0,0,0}, {8465,12090,12106 ,96,8346,8348 ,0,0,0}, - {12090,12107,12106 ,8346,8347,8348 ,0,0,0}, {8464,12090,8465 ,96,8346,96 ,0,0,0}, - {12089,12111,12094 ,8340,8339,8338 ,0,0,0}, {12092,12094,12110 ,8343,8338,7530 ,0,0,0}, - {12095,12096,12112 ,8349,8334,8333 ,0,0,0}, {12089,12095,12112 ,8340,8349,8333 ,0,0,0}, - {12099,12114,12097 ,8350,8337,8336 ,0,0,0}, {12096,12097,12113 ,8334,8336,8335 ,0,0,0}, - {12098,12115,12099 ,8329,8328,8350 ,0,0,0}, {12114,12099,12115 ,8337,8350,8328 ,0,0,0}, - {12100,12119,12098 ,8332,8331,8329 ,0,0,0}, {12119,12118,12098 ,8331,8327,8329 ,0,0,0}, - {12102,12120,12116 ,7516,8321,8330 ,0,0,0}, {12102,12116,12100 ,7516,8330,8332 ,0,0,0}, - {12105,12104,12121 ,8322,8325,8323 ,0,0,0}, {12102,12105,12120 ,7516,8322,8321 ,0,0,0}, - {12117,12103,12122 ,8324,8326,8319 ,0,0,0}, {12121,12104,12117 ,8323,8325,8324 ,0,0,0}, - {8447,12122,12101 ,81,8319,8351 ,0,0,0}, {12122,12103,12101 ,8319,8326,8351 ,0,0,0} -// MotorHacker.prt - , {12123,12124,12125 ,4056,4057,4058 ,0,0,0}, {12126,12127,12125 ,4059,4060,4058 ,0,0,0}, - {12123,12125,12127 ,4056,4058,4060 ,0,0,0}, {12128,12126,12129 ,4061,4059,4062 ,0,0,0}, - {12128,12127,12126 ,4061,4060,4059 ,0,0,0}, {12130,12129,12131 ,4063,4062,4064 ,0,0,0}, - {12126,12131,12129 ,4059,4064,4062 ,0,0,0}, {12132,12133,12130 ,4065,4066,4063 ,0,0,0}, - {12130,12131,12132 ,4063,4064,4065 ,0,0,0}, {12133,12134,12135 ,4066,4067,4068 ,0,0,0}, - {12134,12133,12132 ,4067,4066,4065 ,0,0,0}, {12136,12135,12137 ,4069,4068,4070 ,0,0,0}, - {12134,12137,12135 ,4067,4070,4068 ,0,0,0}, {12138,12139,12136 ,4071,4072,4069 ,0,0,0}, - {12136,12137,12138 ,4069,4070,4071 ,0,0,0}, {12140,12141,12139 ,4073,81,4072 ,0,0,0}, - {12140,12139,12138 ,4073,4072,4071 ,0,0,0}, {12141,12142,12139 ,81,81,4072 ,0,0,0}, - {12143,12124,12123 ,4074,4057,4056 ,0,0,0}, {12143,12144,12145 ,4074,4075,4076 ,0,0,0}, - {12145,12124,12143 ,4076,4057,4074 ,0,0,0}, {12146,12147,12144 ,4077,4078,4075 ,0,0,0}, - {12144,12147,12145 ,4075,4078,4076 ,0,0,0}, {12148,12149,12146 ,4079,4080,4077 ,0,0,0}, - {12146,12144,12148 ,4077,4075,4079 ,0,0,0}, {12149,12150,12151 ,4080,4081,4082 ,0,0,0}, - {12150,12149,12148 ,4081,4080,4079 ,0,0,0}, {12152,12151,12153 ,4083,4082,4084 ,0,0,0}, - {12150,12153,12151 ,4081,4084,4082 ,0,0,0}, {12154,12155,12152 ,4085,4086,4083 ,0,0,0}, - {12152,12153,12154 ,4083,4084,4085 ,0,0,0}, {12155,12156,12157 ,4086,4087,4088 ,0,0,0}, - {12156,12155,12154 ,4087,4086,4085 ,0,0,0}, {12157,12158,12159 ,4088,4089,4090 ,0,0,0}, - {12156,12158,12157 ,4087,4089,4088 ,0,0,0}, {12157,12159,12160 ,4088,4090,4091 ,0,0,0}, - {12161,12162,12163 ,2394,2394,4092 ,0,0,0}, {12164,12165,12163 ,4093,4094,4092 ,0,0,0}, - {12161,12163,12165 ,2394,4092,4094 ,0,0,0}, {12164,12166,12167 ,4093,4095,4096 ,0,0,0}, - {12167,12165,12164 ,4096,4094,4093 ,0,0,0}, {12168,12166,12169 ,4097,4095,4098 ,0,0,0}, - {12166,12168,12167 ,4095,4097,4096 ,0,0,0}, {12170,12171,12169 ,4099,4100,4098 ,0,0,0}, - {12168,12169,12171 ,4097,4098,4100 ,0,0,0}, {12170,12172,12173 ,4099,4101,4102 ,0,0,0}, - {12173,12171,12170 ,4102,4100,4099 ,0,0,0}, {12174,12172,12175 ,4103,4101,4104 ,0,0,0}, - {12172,12174,12173 ,4101,4103,4102 ,0,0,0}, {12176,12177,12175 ,4105,4106,4104 ,0,0,0}, - {12174,12175,12177 ,4103,4104,4106 ,0,0,0}, {12176,12178,12179 ,4105,4107,4108 ,0,0,0}, - {12179,12177,12176 ,4108,4106,4105 ,0,0,0}, {12180,12181,12178 ,4109,4110,4107 ,0,0,0}, - {12178,12181,12179 ,4107,4110,4108 ,0,0,0}, {12182,12183,12180 ,4111,4112,4109 ,0,0,0}, - {12180,12178,12182 ,4109,4107,4111 ,0,0,0}, {12183,12184,12185 ,4112,4113,4114 ,0,0,0}, - {12184,12183,12182 ,4113,4112,4111 ,0,0,0}, {12184,12186,12185 ,4113,4114,4114 ,0,0,0}, - {12187,12162,12161 ,4115,2394,2394 ,0,0,0}, {12187,12188,12189 ,4115,4116,4117 ,0,0,0}, - {12189,12162,12187 ,4117,2394,4115 ,0,0,0}, {12190,12188,12191 ,4118,4116,4119 ,0,0,0}, - {12188,12190,12189 ,4116,4118,4117 ,0,0,0}, {12192,12193,12191 ,4120,4121,4119 ,0,0,0}, - {12190,12191,12193 ,4118,4119,4121 ,0,0,0}, {12192,12194,12195 ,4120,4122,4123 ,0,0,0}, - {12195,12193,12192 ,4123,4121,4120 ,0,0,0}, {12196,12194,12197 ,4124,4122,4125 ,0,0,0}, - {12194,12196,12195 ,4122,4124,4123 ,0,0,0}, {12198,12199,12197 ,4126,4127,4125 ,0,0,0}, - {12196,12197,12199 ,4124,4125,4127 ,0,0,0}, {12198,12200,12201 ,4126,4128,4129 ,0,0,0}, - {12201,12199,12198 ,4129,4127,4126 ,0,0,0}, {12202,12200,12203 ,4130,4128,4131 ,0,0,0}, - {12200,12202,12201 ,4128,4130,4129 ,0,0,0}, {12203,12204,12205 ,4131,4132,4133 ,0,0,0}, - {12202,12203,12205 ,4130,4131,4133 ,0,0,0}, {12204,12206,12207 ,4132,4134,4135 ,0,0,0}, - {12206,12204,12203 ,4134,4132,4131 ,0,0,0}, {12208,12207,12209 ,126,4135,4136 ,0,0,0}, - {12206,12209,12207 ,4134,4136,4135 ,0,0,0}, {12208,12209,12210 ,126,4136,126 ,0,0,0}, - {12211,12212,12213 ,4137,4138,4139 ,0,0,0}, {12211,12214,12215 ,4137,4140,4141 ,0,0,0}, - {12214,12216,12215 ,4140,4142,4141 ,0,0,0}, {12213,12214,12211 ,4139,4140,4137 ,0,0,0}, - {12217,12218,12219 ,4143,4144,4145 ,0,0,0}, {12216,12217,12219 ,4142,4143,4145 ,0,0,0}, - {12218,12220,12221 ,4144,4146,4147 ,0,0,0}, {12220,12218,12217 ,4146,4144,4143 ,0,0,0}, - {12221,12220,12222 ,4147,4146,4148 ,0,0,0}, {12223,12221,12222 ,4149,4147,4148 ,0,0,0}, - {12223,12224,12225 ,4149,4150,4151 ,0,0,0}, {12223,12222,12224 ,4149,4148,4150 ,0,0,0}, - {12219,12215,12216 ,4145,4141,4142 ,0,0,0}, {12226,12227,12228 ,4152,1711,1711 ,0,0,0}, - {12226,12228,12225 ,4152,1711,4151 ,0,0,0}, {12224,12226,12225 ,4150,4152,4151 ,0,0,0}, - {12213,12212,12229 ,4139,4138,4153 ,0,0,0}, {12230,12229,12231 ,4154,4153,4155 ,0,0,0}, - {12212,12231,12229 ,4138,4155,4153 ,0,0,0}, {12232,12233,12230 ,4156,4157,4154 ,0,0,0}, - {12230,12231,12232 ,4154,4155,4156 ,0,0,0}, {12233,12234,12235 ,4157,4158,4159 ,0,0,0}, - {12234,12233,12232 ,4158,4157,4156 ,0,0,0}, {12236,12235,12237 ,4160,4159,4161 ,0,0,0}, - {12234,12237,12235 ,4158,4161,4159 ,0,0,0}, {12238,12239,12236 ,4162,4163,4160 ,0,0,0}, - {12236,12237,12238 ,4160,4161,4162 ,0,0,0}, {12239,12240,12241 ,4163,4164,1790 ,0,0,0}, - {12240,12239,12238 ,4164,4163,4162 ,0,0,0}, {12240,12242,12241 ,4164,1790,1790 ,0,0,0}, - {12243,12244,12245 ,4165,4166,4167 ,0,0,0}, {12246,12247,12248 ,4168,4169,4170 ,0,0,0}, - {12247,12243,12245 ,4169,4165,4167 ,0,0,0}, {12249,12246,12248 ,4171,4168,4170 ,0,0,0}, - {12247,12246,12243 ,4169,4168,4165 ,0,0,0}, {12249,12248,12250 ,4171,4170,4172 ,0,0,0}, - {12250,12251,12252 ,4172,4173,4174 ,0,0,0}, {12253,12252,12251 ,4175,4174,4173 ,0,0,0}, - {12254,12255,12256 ,4176,4177,4178 ,0,0,0}, {12251,12257,12253 ,4173,4179,4175 ,0,0,0}, - {12256,12258,12259 ,4178,4180,4181 ,0,0,0}, {12258,12257,12259 ,4180,4179,4181 ,0,0,0}, - {12253,12257,12258 ,4175,4179,4180 ,0,0,0}, {12256,12259,12254 ,4178,4181,4176 ,0,0,0}, - {12255,12254,12260 ,4177,4176,4182 ,0,0,0}, {12255,12260,12261 ,4177,4182,4183 ,0,0,0}, - {12262,12261,12260 ,4184,4183,4182 ,0,0,0}, {12263,12264,12265 ,4185,1711,4186 ,0,0,0}, - {12265,12261,12262 ,4186,4183,4184 ,0,0,0}, {12263,12265,12262 ,4185,4186,4184 ,0,0,0}, - {12263,12266,12264 ,4185,1711,1711 ,0,0,0}, {12249,12250,12252 ,4171,4172,4174 ,0,0,0}, - {12245,12244,12267 ,4167,4166,4187 ,0,0,0}, {12268,12267,12269 ,4188,4187,4189 ,0,0,0}, - {12244,12269,12267 ,4166,4189,4187 ,0,0,0}, {12270,12271,12268 ,4190,4191,4188 ,0,0,0}, - {12268,12269,12270 ,4188,4189,4190 ,0,0,0}, {12271,12272,12273 ,4191,4192,4193 ,0,0,0}, - {12272,12271,12270 ,4192,4191,4190 ,0,0,0}, {12274,12273,12275 ,4194,4193,4195 ,0,0,0}, - {12272,12275,12273 ,4192,4195,4193 ,0,0,0}, {12276,12277,12274 ,4196,4197,4194 ,0,0,0}, - {12274,12275,12276 ,4194,4195,4196 ,0,0,0}, {12277,12278,12279 ,4197,4198,4199 ,0,0,0}, - {12278,12277,12276 ,4198,4197,4196 ,0,0,0}, {12280,12279,12281 ,4200,4199,4201 ,0,0,0}, - {12278,12281,12279 ,4198,4201,4199 ,0,0,0}, {12282,12283,12280 ,4202,4203,4200 ,0,0,0}, - {12280,12281,12282 ,4200,4201,4202 ,0,0,0}, {12283,12284,12285 ,4203,4204,1790 ,0,0,0}, - {12284,12283,12282 ,4204,4203,4202 ,0,0,0}, {12284,12286,12285 ,4204,1790,1790 ,0,0,0}, - {12287,12288,12289 ,4205,4206,4207 ,0,0,0}, {12287,12290,12291 ,4205,4208,4209 ,0,0,0}, - {12290,12292,12291 ,4208,4210,4209 ,0,0,0}, {12289,12290,12287 ,4207,4208,4205 ,0,0,0}, - {12293,12294,12295 ,4211,4212,4213 ,0,0,0}, {12292,12293,12295 ,4210,4211,4213 ,0,0,0}, - {12294,12296,12297 ,4212,4214,4215 ,0,0,0}, {12296,12294,12293 ,4214,4212,4211 ,0,0,0}, - {12297,12296,12298 ,4215,4214,4216 ,0,0,0}, {12299,12297,12298 ,4217,4215,4216 ,0,0,0}, - {12299,12300,12301 ,4217,4218,4219 ,0,0,0}, {12299,12298,12300 ,4217,4216,4218 ,0,0,0}, - {12295,12291,12292 ,4213,4209,4210 ,0,0,0}, {12302,12303,12304 ,4220,1359,1359 ,0,0,0}, - {12302,12304,12301 ,4220,1359,4219 ,0,0,0}, {12300,12302,12301 ,4218,4220,4219 ,0,0,0}, - {12289,12288,12305 ,4207,4206,4221 ,0,0,0}, {12306,12305,12307 ,4222,4221,4223 ,0,0,0}, - {12288,12307,12305 ,4206,4223,4221 ,0,0,0}, {12308,12309,12306 ,4224,4225,4222 ,0,0,0}, - {12306,12307,12308 ,4222,4223,4224 ,0,0,0}, {12309,12310,12311 ,4225,4226,4227 ,0,0,0}, - {12310,12309,12308 ,4226,4225,4224 ,0,0,0}, {12312,12311,12313 ,4228,4227,4229 ,0,0,0}, - {12310,12313,12311 ,4226,4229,4227 ,0,0,0}, {12314,12315,12312 ,4230,4231,4228 ,0,0,0}, - {12312,12313,12314 ,4228,4229,4230 ,0,0,0}, {12315,12316,12317 ,4231,4232,1435 ,0,0,0}, - {12316,12315,12314 ,4232,4231,4230 ,0,0,0}, {12316,12318,12317 ,4232,1435,1435 ,0,0,0}, - {12319,12320,12321 ,4233,4234,4235 ,0,0,0}, {12322,12323,12324 ,4236,4237,4238 ,0,0,0}, - {12323,12319,12321 ,4237,4233,4235 ,0,0,0}, {12325,12322,12324 ,4239,4236,4238 ,0,0,0}, - {12323,12322,12319 ,4237,4236,4233 ,0,0,0}, {12325,12324,12326 ,4239,4238,4240 ,0,0,0}, - {12326,12327,12328 ,4240,4241,4242 ,0,0,0}, {12329,12328,12327 ,4243,4242,4241 ,0,0,0}, - {12330,12331,12332 ,4244,4245,4246 ,0,0,0}, {12327,12333,12329 ,4241,4247,4243 ,0,0,0}, - {12332,12334,12335 ,4246,4248,4249 ,0,0,0}, {12334,12333,12335 ,4248,4247,4249 ,0,0,0}, - {12329,12333,12334 ,4243,4247,4248 ,0,0,0}, {12332,12335,12330 ,4246,4249,4244 ,0,0,0}, - {12331,12330,12336 ,4245,4244,4250 ,0,0,0}, {12331,12336,12337 ,4245,4250,4251 ,0,0,0}, - {12338,12337,12336 ,4252,4251,4250 ,0,0,0}, {12339,12340,12341 ,4253,1359,4254 ,0,0,0}, - {12341,12337,12338 ,4254,4251,4252 ,0,0,0}, {12339,12341,12338 ,4253,4254,4252 ,0,0,0}, - {12339,12342,12340 ,4253,1359,1359 ,0,0,0}, {12325,12326,12328 ,4239,4240,4242 ,0,0,0}, - {12321,12320,12343 ,4235,4234,4255 ,0,0,0}, {12344,12343,12345 ,4256,4255,4257 ,0,0,0}, - {12320,12345,12343 ,4234,4257,4255 ,0,0,0}, {12346,12347,12344 ,4258,4259,4256 ,0,0,0}, - {12344,12345,12346 ,4256,4257,4258 ,0,0,0}, {12347,12348,12349 ,4259,4260,4261 ,0,0,0}, - {12348,12347,12346 ,4260,4259,4258 ,0,0,0}, {12350,12349,12351 ,4262,4261,4263 ,0,0,0}, - {12348,12351,12349 ,4260,4263,4261 ,0,0,0}, {12352,12353,12350 ,4264,4265,4262 ,0,0,0}, - {12350,12351,12352 ,4262,4263,4264 ,0,0,0}, {12353,12354,12355 ,4265,4266,4267 ,0,0,0}, - {12354,12353,12352 ,4266,4265,4264 ,0,0,0}, {12356,12355,12357 ,4268,4267,4269 ,0,0,0}, - {12354,12357,12355 ,4266,4269,4267 ,0,0,0}, {12358,12359,12356 ,4270,4271,4268 ,0,0,0}, - {12356,12357,12358 ,4268,4269,4270 ,0,0,0}, {12359,12360,12361 ,4271,4272,1435 ,0,0,0}, - {12360,12359,12358 ,4272,4271,4270 ,0,0,0}, {12360,12362,12361 ,4272,1435,1435 ,0,0,0}, - {12363,12364,12365 ,4273,4274,4275 ,0,0,0}, {12363,12366,12367 ,4273,4276,4277 ,0,0,0}, - {12366,12368,12367 ,4276,4278,4277 ,0,0,0}, {12365,12366,12363 ,4275,4276,4273 ,0,0,0}, - {12369,12370,12371 ,4279,4280,4281 ,0,0,0}, {12368,12369,12371 ,4278,4279,4281 ,0,0,0}, - {12370,12372,12373 ,4280,4282,4283 ,0,0,0}, {12372,12370,12369 ,4282,4280,4279 ,0,0,0}, - {12373,12372,12374 ,4283,4282,4284 ,0,0,0}, {12375,12373,12374 ,4285,4283,4284 ,0,0,0}, - {12375,12376,12377 ,4285,4286,4287 ,0,0,0}, {12375,12374,12376 ,4285,4284,4286 ,0,0,0}, - {12371,12367,12368 ,4281,4277,4278 ,0,0,0}, {12378,12379,12380 ,4288,126,4289 ,0,0,0}, - {12378,12380,12377 ,4288,4289,4287 ,0,0,0}, {12376,12378,12377 ,4286,4288,4287 ,0,0,0}, - {12365,12364,12381 ,4275,4274,4290 ,0,0,0}, {12382,12381,12383 ,4291,4290,4292 ,0,0,0}, - {12364,12383,12381 ,4274,4292,4290 ,0,0,0}, {12384,12385,12382 ,4293,4294,4291 ,0,0,0}, - {12382,12383,12384 ,4291,4292,4293 ,0,0,0}, {12385,12386,12387 ,4294,4295,4296 ,0,0,0}, - {12386,12385,12384 ,4295,4294,4293 ,0,0,0}, {12388,12387,12389 ,4297,4296,4298 ,0,0,0}, - {12386,12389,12387 ,4295,4298,4296 ,0,0,0}, {12390,12391,12388 ,4299,4300,4297 ,0,0,0}, - {12388,12389,12390 ,4297,4298,4299 ,0,0,0}, {12391,12392,12393 ,4300,4301,4302 ,0,0,0}, - {12392,12391,12390 ,4301,4300,4299 ,0,0,0}, {12392,12394,12393 ,4301,4303,4302 ,0,0,0}, - {12395,12396,12397 ,4304,4305,4306 ,0,0,0}, {12398,12399,12400 ,4307,4308,4309 ,0,0,0}, - {12399,12395,12397 ,4308,4304,4306 ,0,0,0}, {12401,12398,12400 ,4310,4307,4309 ,0,0,0}, - {12399,12398,12395 ,4308,4307,4304 ,0,0,0}, {12401,12400,12402 ,4310,4309,4311 ,0,0,0}, - {12402,12403,12404 ,4311,4312,4313 ,0,0,0}, {12405,12404,12403 ,4314,4313,4312 ,0,0,0}, - {12406,12407,12408 ,4315,4316,4317 ,0,0,0}, {12403,12409,12405 ,4312,4318,4314 ,0,0,0}, - {12408,12410,12411 ,4317,4319,4320 ,0,0,0}, {12410,12409,12411 ,4319,4318,4320 ,0,0,0}, - {12405,12409,12410 ,4314,4318,4319 ,0,0,0}, {12408,12411,12406 ,4317,4320,4315 ,0,0,0}, - {12407,12406,12412 ,4316,4315,4321 ,0,0,0}, {12407,12412,12413 ,4316,4321,4322 ,0,0,0}, - {12414,12413,12412 ,4323,4322,4321 ,0,0,0}, {12415,12416,12417 ,4324,126,4325 ,0,0,0}, - {12417,12413,12414 ,4325,4322,4323 ,0,0,0}, {12415,12417,12414 ,4324,4325,4323 ,0,0,0}, - {12415,12418,12416 ,4324,4326,126 ,0,0,0}, {12401,12402,12404 ,4310,4311,4313 ,0,0,0}, - {12397,12396,12419 ,4306,4305,4327 ,0,0,0}, {12420,12419,12421 ,4328,4327,4329 ,0,0,0}, - {12396,12421,12419 ,4305,4329,4327 ,0,0,0}, {12422,12423,12420 ,4330,4331,4328 ,0,0,0}, - {12420,12421,12422 ,4328,4329,4330 ,0,0,0}, {12423,12424,12425 ,4331,4332,4333 ,0,0,0}, - {12424,12423,12422 ,4332,4331,4330 ,0,0,0}, {12426,12425,12427 ,4334,4333,4335 ,0,0,0}, - {12424,12427,12425 ,4332,4335,4333 ,0,0,0}, {12428,12429,12426 ,4336,4337,4334 ,0,0,0}, - {12426,12427,12428 ,4334,4335,4336 ,0,0,0}, {12429,12430,12431 ,4337,4338,4339 ,0,0,0}, - {12430,12429,12428 ,4338,4337,4336 ,0,0,0}, {12432,12431,12433 ,4340,4339,4341 ,0,0,0}, - {12430,12433,12431 ,4338,4341,4339 ,0,0,0}, {12434,12435,12432 ,4342,4343,4340 ,0,0,0}, - {12432,12433,12434 ,4340,4341,4342 ,0,0,0}, {12435,12436,12437 ,4343,4344,4345 ,0,0,0}, - {12436,12435,12434 ,4344,4343,4342 ,0,0,0}, {12436,12438,12437 ,4344,4346,4345 ,0,0,0}, - {12439,12440,12441 ,4347,4348,4349 ,0,0,0}, {12439,12442,12443 ,4347,4350,4351 ,0,0,0}, - {12442,12444,12443 ,4350,4352,4351 ,0,0,0}, {12441,12442,12439 ,4349,4350,4347 ,0,0,0}, - {12445,12446,12447 ,4353,4354,4355 ,0,0,0}, {12444,12445,12447 ,4352,4353,4355 ,0,0,0}, - {12446,12448,12449 ,4354,4356,4357 ,0,0,0}, {12448,12446,12445 ,4356,4354,4353 ,0,0,0}, - {12449,12448,12450 ,4357,4356,4358 ,0,0,0}, {12451,12449,12450 ,4359,4357,4358 ,0,0,0}, - {12451,12452,12453 ,4359,4360,4361 ,0,0,0}, {12451,12450,12452 ,4359,4358,4360 ,0,0,0}, - {12447,12443,12444 ,4355,4351,4352 ,0,0,0}, {12454,12455,12456 ,4362,1790,1790 ,0,0,0}, - {12454,12456,12453 ,4362,1790,4361 ,0,0,0}, {12452,12454,12453 ,4360,4362,4361 ,0,0,0}, - {12441,12440,12457 ,4349,4348,4363 ,0,0,0}, {12458,12457,12459 ,4364,4363,4365 ,0,0,0}, - {12440,12459,12457 ,4348,4365,4363 ,0,0,0}, {12460,12461,12458 ,4366,4367,4364 ,0,0,0}, - {12458,12459,12460 ,4364,4365,4366 ,0,0,0}, {12461,12462,12463 ,4367,4368,4369 ,0,0,0}, - {12462,12461,12460 ,4368,4367,4366 ,0,0,0}, {12464,12463,12465 ,4370,4369,4371 ,0,0,0}, - {12462,12465,12463 ,4368,4371,4369 ,0,0,0}, {12466,12467,12464 ,4372,4373,4370 ,0,0,0}, - {12464,12465,12466 ,4370,4371,4372 ,0,0,0}, {12467,12468,12469 ,4373,4374,1711 ,0,0,0}, - {12468,12467,12466 ,4374,4373,4372 ,0,0,0}, {12468,12470,12469 ,4374,1711,1711 ,0,0,0}, - {12471,12472,12473 ,4375,4376,4377 ,0,0,0}, {12474,12475,12476 ,4378,4379,4380 ,0,0,0}, - {12475,12471,12473 ,4379,4375,4377 ,0,0,0}, {12477,12474,12476 ,4381,4378,4380 ,0,0,0}, - {12475,12474,12471 ,4379,4378,4375 ,0,0,0}, {12477,12476,12478 ,4381,4380,4382 ,0,0,0}, - {12478,12479,12480 ,4382,4383,4384 ,0,0,0}, {12481,12480,12479 ,4385,4384,4383 ,0,0,0}, - {12482,12483,12484 ,4386,4387,4388 ,0,0,0}, {12479,12485,12481 ,4383,4389,4385 ,0,0,0}, - {12484,12486,12487 ,4388,4390,4391 ,0,0,0}, {12486,12485,12487 ,4390,4389,4391 ,0,0,0}, - {12481,12485,12486 ,4385,4389,4390 ,0,0,0}, {12484,12487,12482 ,4388,4391,4386 ,0,0,0}, - {12483,12482,12488 ,4387,4386,4392 ,0,0,0}, {12483,12488,12489 ,4387,4392,4393 ,0,0,0}, - {12490,12489,12488 ,4394,4393,4392 ,0,0,0}, {12491,12492,12493 ,4395,1790,4396 ,0,0,0}, - {12493,12489,12490 ,4396,4393,4394 ,0,0,0}, {12491,12493,12490 ,4395,4396,4394 ,0,0,0}, - {12491,12494,12492 ,4395,1790,1790 ,0,0,0}, {12477,12478,12480 ,4381,4382,4384 ,0,0,0}, - {12473,12472,12495 ,4377,4376,4397 ,0,0,0}, {12496,12495,12497 ,4398,4397,4399 ,0,0,0}, - {12472,12497,12495 ,4376,4399,4397 ,0,0,0}, {12498,12499,12496 ,4400,4401,4398 ,0,0,0}, - {12496,12497,12498 ,4398,4399,4400 ,0,0,0}, {12499,12500,12501 ,4401,4402,4403 ,0,0,0}, - {12500,12499,12498 ,4402,4401,4400 ,0,0,0}, {12502,12501,12503 ,4404,4403,4405 ,0,0,0}, - {12500,12503,12501 ,4402,4405,4403 ,0,0,0}, {12504,12505,12502 ,4406,4407,4404 ,0,0,0}, - {12502,12503,12504 ,4404,4405,4406 ,0,0,0}, {12505,12506,12507 ,4407,4408,4409 ,0,0,0}, - {12506,12505,12504 ,4408,4407,4406 ,0,0,0}, {12508,12507,12509 ,4410,4409,4411 ,0,0,0}, - {12506,12509,12507 ,4408,4411,4409 ,0,0,0}, {12510,12511,12508 ,4412,4413,4410 ,0,0,0}, - {12508,12509,12510 ,4410,4411,4412 ,0,0,0}, {12511,12512,12513 ,4413,4414,1711 ,0,0,0}, - {12512,12511,12510 ,4414,4413,4412 ,0,0,0}, {12512,12514,12513 ,4414,1711,1711 ,0,0,0}, - {12515,12516,12517 ,4415,4416,4417 ,0,0,0}, {12515,12518,12519 ,4415,4418,4419 ,0,0,0}, - {12518,12520,12519 ,4418,4420,4419 ,0,0,0}, {12517,12518,12515 ,4417,4418,4415 ,0,0,0}, - {12521,12522,12523 ,4421,4422,4423 ,0,0,0}, {12520,12521,12523 ,4420,4421,4423 ,0,0,0}, - {12522,12524,12525 ,4422,4424,4425 ,0,0,0}, {12524,12522,12521 ,4424,4422,4421 ,0,0,0}, - {12525,12524,12526 ,4425,4424,4426 ,0,0,0}, {12527,12525,12526 ,4427,4425,4426 ,0,0,0}, - {12527,12528,12529 ,4427,4428,4429 ,0,0,0}, {12527,12526,12528 ,4427,4426,4428 ,0,0,0}, - {12523,12519,12520 ,4423,4419,4420 ,0,0,0}, {12530,12531,12532 ,4430,1435,1435 ,0,0,0}, - {12530,12532,12529 ,4430,1435,4429 ,0,0,0}, {12528,12530,12529 ,4428,4430,4429 ,0,0,0}, - {12517,12516,12533 ,4417,4416,4431 ,0,0,0}, {12534,12533,12535 ,4432,4431,4433 ,0,0,0}, - {12516,12535,12533 ,4416,4433,4431 ,0,0,0}, {12536,12537,12534 ,4434,4435,4432 ,0,0,0}, - {12534,12535,12536 ,4432,4433,4434 ,0,0,0}, {12537,12538,12539 ,4435,4436,4437 ,0,0,0}, - {12538,12537,12536 ,4436,4435,4434 ,0,0,0}, {12540,12539,12541 ,4438,4437,4439 ,0,0,0}, - {12538,12541,12539 ,4436,4439,4437 ,0,0,0}, {12542,12543,12540 ,4440,4441,4438 ,0,0,0}, - {12540,12541,12542 ,4438,4439,4440 ,0,0,0}, {12543,12544,12545 ,4441,4442,1359 ,0,0,0}, - {12544,12543,12542 ,4442,4441,4440 ,0,0,0}, {12544,12546,12545 ,4442,1359,1359 ,0,0,0}, - {12547,12548,12549 ,4443,4444,4445 ,0,0,0}, {12550,12551,12552 ,4446,4447,4448 ,0,0,0}, - {12551,12547,12549 ,4447,4443,4445 ,0,0,0}, {12553,12550,12552 ,4449,4446,4448 ,0,0,0}, - {12551,12550,12547 ,4447,4446,4443 ,0,0,0}, {12553,12552,12554 ,4449,4448,4450 ,0,0,0}, - {12554,12555,12556 ,4450,4451,4452 ,0,0,0}, {12557,12556,12555 ,4453,4452,4451 ,0,0,0}, - {12558,12559,12560 ,4454,4455,4456 ,0,0,0}, {12555,12561,12557 ,4451,4457,4453 ,0,0,0}, - {12560,12562,12563 ,4456,4458,4459 ,0,0,0}, {12562,12561,12563 ,4458,4457,4459 ,0,0,0}, - {12557,12561,12562 ,4453,4457,4458 ,0,0,0}, {12560,12563,12558 ,4456,4459,4454 ,0,0,0}, - {12559,12558,12564 ,4455,4454,4460 ,0,0,0}, {12559,12564,12565 ,4455,4460,4461 ,0,0,0}, - {12566,12565,12564 ,4462,4461,4460 ,0,0,0}, {12567,12568,12569 ,4463,1435,4464 ,0,0,0}, - {12569,12565,12566 ,4464,4461,4462 ,0,0,0}, {12567,12569,12566 ,4463,4464,4462 ,0,0,0}, - {12567,12570,12568 ,4463,1435,1435 ,0,0,0}, {12553,12554,12556 ,4449,4450,4452 ,0,0,0}, - {12549,12548,12571 ,4445,4444,4465 ,0,0,0}, {12572,12571,12573 ,4466,4465,4467 ,0,0,0}, - {12548,12573,12571 ,4444,4467,4465 ,0,0,0}, {12574,12575,12572 ,4468,4469,4466 ,0,0,0}, - {12572,12573,12574 ,4466,4467,4468 ,0,0,0}, {12575,12576,12577 ,4469,4470,4471 ,0,0,0}, - {12576,12575,12574 ,4470,4469,4468 ,0,0,0}, {12578,12577,12579 ,4472,4471,4473 ,0,0,0}, - {12576,12579,12577 ,4470,4473,4471 ,0,0,0}, {12580,12581,12578 ,4474,4475,4472 ,0,0,0}, - {12578,12579,12580 ,4472,4473,4474 ,0,0,0}, {12581,12582,12583 ,4475,4476,4477 ,0,0,0}, - {12582,12581,12580 ,4476,4475,4474 ,0,0,0}, {12584,12583,12585 ,4478,4477,4479 ,0,0,0}, - {12582,12585,12583 ,4476,4479,4477 ,0,0,0}, {12586,12587,12584 ,4480,4481,4478 ,0,0,0}, - {12584,12585,12586 ,4478,4479,4480 ,0,0,0}, {12587,12588,12589 ,4481,4482,1359 ,0,0,0}, - {12588,12587,12586 ,4482,4481,4480 ,0,0,0}, {12588,12590,12589 ,4482,1359,1359 ,0,0,0}, - {12591,12592,12593 ,4483,4484,4485 ,0,0,0}, {12591,12594,12595 ,4483,4486,4487 ,0,0,0}, - {12594,12596,12595 ,4486,4488,4487 ,0,0,0}, {12593,12594,12591 ,4485,4486,4483 ,0,0,0}, - {12597,12598,12599 ,4489,4490,4491 ,0,0,0}, {12596,12597,12599 ,4488,4489,4491 ,0,0,0}, - {12598,12600,12601 ,4490,4492,4493 ,0,0,0}, {12600,12598,12597 ,4492,4490,4489 ,0,0,0}, - {12601,12600,12602 ,4493,4492,4494 ,0,0,0}, {12603,12601,12602 ,4495,4493,4494 ,0,0,0}, - {12603,12604,12605 ,4495,4496,4497 ,0,0,0}, {12603,12602,12604 ,4495,4494,4496 ,0,0,0}, - {12599,12595,12596 ,4491,4487,4488 ,0,0,0}, {12606,12607,12608 ,4498,4499,82 ,0,0,0}, - {12606,12608,12605 ,4498,82,4497 ,0,0,0}, {12604,12606,12605 ,4496,4498,4497 ,0,0,0}, - {12593,12592,12609 ,4485,4484,4500 ,0,0,0}, {12610,12609,12611 ,4501,4500,4502 ,0,0,0}, - {12592,12611,12609 ,4484,4502,4500 ,0,0,0}, {12612,12613,12610 ,4503,4504,4501 ,0,0,0}, - {12610,12611,12612 ,4501,4502,4503 ,0,0,0}, {12613,12614,12615 ,4504,4505,4506 ,0,0,0}, - {12614,12613,12612 ,4505,4504,4503 ,0,0,0}, {12616,12615,12617 ,4507,4506,4508 ,0,0,0}, - {12614,12617,12615 ,4505,4508,4506 ,0,0,0}, {12618,12619,12616 ,4509,4510,4507 ,0,0,0}, - {12616,12617,12618 ,4507,4508,4509 ,0,0,0}, {12619,12620,12621 ,4510,4511,4512 ,0,0,0}, - {12620,12619,12618 ,4511,4510,4509 ,0,0,0}, {12620,12622,12621 ,4511,4513,4512 ,0,0,0}, - {12623,12624,12625 ,4514,4515,4516 ,0,0,0}, {12626,12627,12628 ,4517,4518,4519 ,0,0,0}, - {12627,12623,12625 ,4518,4514,4516 ,0,0,0}, {12629,12626,12628 ,4520,4517,4519 ,0,0,0}, - {12627,12626,12623 ,4518,4517,4514 ,0,0,0}, {12629,12628,12630 ,4520,4519,4521 ,0,0,0}, - {12630,12631,12632 ,4521,4522,4523 ,0,0,0}, {12633,12632,12631 ,4524,4523,4522 ,0,0,0}, - {12634,12635,12636 ,4525,4526,4527 ,0,0,0}, {12631,12637,12633 ,4522,4528,4524 ,0,0,0}, - {12636,12638,12639 ,4527,4529,4530 ,0,0,0}, {12638,12637,12639 ,4529,4528,4530 ,0,0,0}, - {12633,12637,12638 ,4524,4528,4529 ,0,0,0}, {12636,12639,12634 ,4527,4530,4525 ,0,0,0}, - {12635,12634,12640 ,4526,4525,4531 ,0,0,0}, {12635,12640,12641 ,4526,4531,4532 ,0,0,0}, - {12642,12641,12640 ,4533,4532,4531 ,0,0,0}, {12643,12644,12645 ,4534,4535,4536 ,0,0,0}, - {12645,12641,12642 ,4536,4532,4533 ,0,0,0}, {12643,12645,12642 ,4534,4536,4533 ,0,0,0}, - {12643,12646,12644 ,4534,4537,4535 ,0,0,0}, {12629,12630,12632 ,4520,4521,4523 ,0,0,0}, - {12625,12624,12647 ,4516,4515,4538 ,0,0,0}, {12648,12647,12649 ,4539,4538,4540 ,0,0,0}, - {12624,12649,12647 ,4515,4540,4538 ,0,0,0}, {12650,12651,12648 ,4541,4542,4539 ,0,0,0}, - {12648,12649,12650 ,4539,4540,4541 ,0,0,0}, {12651,12652,12653 ,4542,4543,4544 ,0,0,0}, - {12652,12651,12650 ,4543,4542,4541 ,0,0,0}, {12654,12653,12655 ,4545,4544,4546 ,0,0,0}, - {12652,12655,12653 ,4543,4546,4544 ,0,0,0}, {12656,12657,12654 ,4547,4548,4545 ,0,0,0}, - {12654,12655,12656 ,4545,4546,4547 ,0,0,0}, {12657,12658,12659 ,4548,4549,4550 ,0,0,0}, - {12658,12657,12656 ,4549,4548,4547 ,0,0,0}, {12660,12659,12661 ,4551,4550,4552 ,0,0,0}, - {12658,12661,12659 ,4549,4552,4550 ,0,0,0}, {12662,12663,12660 ,4553,4554,4551 ,0,0,0}, - {12660,12661,12662 ,4551,4552,4553 ,0,0,0}, {12663,12664,12665 ,4554,4555,4556 ,0,0,0}, - {12664,12663,12662 ,4555,4554,4553 ,0,0,0}, {12664,12666,12665 ,4555,126,4556 ,0,0,0}, - {12667,12668,12669 ,4557,4558,4559 ,0,0,0}, {12670,12671,12669 ,4560,4561,4559 ,0,0,0}, - {12667,12669,12671 ,4557,4559,4561 ,0,0,0}, {12672,12670,12673 ,4562,4560,4563 ,0,0,0}, - {12672,12671,12670 ,4562,4561,4560 ,0,0,0}, {12674,12673,12675 ,4564,4563,4565 ,0,0,0}, - {12670,12675,12673 ,4560,4565,4563 ,0,0,0}, {12676,12677,12674 ,4081,4566,4564 ,0,0,0}, - {12674,12675,12676 ,4564,4565,4081 ,0,0,0}, {12677,12678,12679 ,4566,4567,4568 ,0,0,0}, - {12678,12677,12676 ,4567,4566,4081 ,0,0,0}, {12680,12679,12681 ,4569,4568,4570 ,0,0,0}, - {12678,12681,12679 ,4567,4570,4568 ,0,0,0}, {12682,12683,12680 ,4571,4572,4569 ,0,0,0}, - {12680,12681,12682 ,4569,4570,4571 ,0,0,0}, {12684,12685,12683 ,4573,763,4572 ,0,0,0}, - {12684,12683,12682 ,4573,4572,4571 ,0,0,0}, {12685,12686,12683 ,763,763,4572 ,0,0,0}, - {12687,12668,12667 ,4574,4558,4557 ,0,0,0}, {12687,12688,12689 ,4574,4575,4576 ,0,0,0}, - {12689,12668,12687 ,4576,4558,4574 ,0,0,0}, {12690,12691,12688 ,4577,4578,4575 ,0,0,0}, - {12688,12691,12689 ,4575,4578,4576 ,0,0,0}, {12692,12693,12690 ,4579,4580,4577 ,0,0,0}, - {12690,12688,12692 ,4577,4575,4579 ,0,0,0}, {12693,12694,12695 ,4580,4065,4581 ,0,0,0}, - {12694,12693,12692 ,4065,4580,4579 ,0,0,0}, {12696,12695,12697 ,4582,4581,4583 ,0,0,0}, - {12694,12697,12695 ,4065,4583,4581 ,0,0,0}, {12698,12699,12696 ,4584,4585,4582 ,0,0,0}, - {12696,12697,12698 ,4582,4583,4584 ,0,0,0}, {12699,12700,12701 ,4585,4586,4587 ,0,0,0}, - {12700,12699,12698 ,4586,4585,4584 ,0,0,0}, {12701,12702,12703 ,4587,4588,54 ,0,0,0}, - {12700,12702,12701 ,4586,4588,4587 ,0,0,0}, {12701,12703,12704 ,4587,54,4589 ,0,0,0}, - {12705,12706,12707 ,4590,4591,4557 ,0,0,0}, {12708,12706,12709 ,4592,4591,4593 ,0,0,0}, - {12706,12708,12707 ,4591,4592,4557 ,0,0,0}, {12710,12711,12709 ,4594,4595,4593 ,0,0,0}, - {12708,12709,12711 ,4592,4593,4595 ,0,0,0}, {12710,12712,12713 ,4594,4596,4597 ,0,0,0}, - {12713,12711,12710 ,4597,4595,4594 ,0,0,0}, {12714,12712,12715 ,4598,4596,4599 ,0,0,0}, - {12712,12714,12713 ,4596,4598,4597 ,0,0,0}, {12716,12717,12715 ,4600,4601,4599 ,0,0,0}, - {12714,12715,12717 ,4598,4599,4601 ,0,0,0}, {12716,12718,12719 ,4600,4602,4603 ,0,0,0}, - {12719,12717,12716 ,4603,4601,4600 ,0,0,0}, {12720,12718,12721 ,4604,4602,4605 ,0,0,0}, - {12718,12720,12719 ,4602,4604,4603 ,0,0,0}, {12722,12723,12721 ,4606,4607,4605 ,0,0,0}, - {12720,12721,12723 ,4604,4605,4607 ,0,0,0}, {12722,12724,12725 ,4606,4608,4609 ,0,0,0}, - {12725,12723,12722 ,4609,4607,4606 ,0,0,0}, {12726,12724,12727 ,4610,4608,4611 ,0,0,0}, - {12724,12726,12725 ,4608,4610,4609 ,0,0,0}, {12728,12729,12727 ,4612,4613,4611 ,0,0,0}, - {12726,12727,12729 ,4610,4611,4613 ,0,0,0}, {12728,12730,12731 ,4612,4614,4615 ,0,0,0}, - {12731,12729,12728 ,4615,4613,4612 ,0,0,0}, {12732,12730,12733 ,4616,4614,4617 ,0,0,0}, - {12730,12732,12731 ,4614,4616,4615 ,0,0,0}, {12734,12735,12733 ,4618,4619,4617 ,0,0,0}, - {12732,12733,12735 ,4616,4617,4619 ,0,0,0}, {12734,12736,12737 ,4618,4620,4621 ,0,0,0}, - {12737,12735,12734 ,4621,4619,4618 ,0,0,0}, {12736,12738,12737 ,4620,4620,4621 ,0,0,0}, - {12739,12705,12707 ,4622,4590,4557 ,0,0,0}, {12740,12741,12739 ,4623,4624,4622 ,0,0,0}, - {12705,12739,12741 ,4590,4622,4624 ,0,0,0}, {12740,12742,12743 ,4623,4625,4626 ,0,0,0}, - {12743,12741,12740 ,4626,4624,4623 ,0,0,0}, {12744,12742,12745 ,4627,4625,4628 ,0,0,0}, - {12742,12744,12743 ,4625,4627,4626 ,0,0,0}, {12746,12747,12745 ,4629,4630,4628 ,0,0,0}, - {12744,12745,12747 ,4627,4628,4630 ,0,0,0}, {12746,12748,12749 ,4629,4631,4632 ,0,0,0}, - {12749,12747,12746 ,4632,4630,4629 ,0,0,0}, {12750,12748,12751 ,4633,4631,4634 ,0,0,0}, - {12748,12750,12749 ,4631,4633,4632 ,0,0,0}, {12752,12753,12751 ,4635,4636,4634 ,0,0,0}, - {12750,12751,12753 ,4633,4634,4636 ,0,0,0}, {12752,12754,12755 ,4635,4637,4638 ,0,0,0}, - {12755,12753,12752 ,4638,4636,4635 ,0,0,0}, {12756,12754,12757 ,4639,4637,4640 ,0,0,0}, - {12754,12756,12755 ,4637,4639,4638 ,0,0,0}, {12758,12759,12757 ,4641,4642,4640 ,0,0,0}, - {12756,12757,12759 ,4639,4640,4642 ,0,0,0}, {12758,12760,12761 ,4641,4643,4644 ,0,0,0}, - {12761,12759,12758 ,4644,4642,4641 ,0,0,0}, {12762,12760,12763 ,4645,4643,4646 ,0,0,0}, - {12760,12762,12761 ,4643,4645,4644 ,0,0,0}, {12764,12765,12763 ,4647,4648,4646 ,0,0,0}, - {12762,12763,12765 ,4645,4646,4648 ,0,0,0}, {12764,12766,12767 ,4647,4649,4650 ,0,0,0}, - {12767,12765,12764 ,4650,4648,4647 ,0,0,0}, {12768,12766,12769 ,4651,4649,82 ,0,0,0}, - {12766,12768,12767 ,4649,4651,4650 ,0,0,0}, {12768,12769,12770 ,4651,82,4652 ,0,0,0}, - {12771,12772,12773 ,4653,4654,4655 ,0,0,0}, {12774,12775,12776 ,4656,4657,4658 ,0,0,0}, - {12773,12776,12775 ,4655,4658,4657 ,0,0,0}, {12777,12778,12779 ,4659,4660,4661 ,0,0,0}, - {12780,12781,12774 ,4662,4663,4656 ,0,0,0}, {12777,12781,12780 ,4659,4663,4662 ,0,0,0}, - {12780,12778,12777 ,4662,4660,4659 ,0,0,0}, {12781,12775,12774 ,4663,4657,4656 ,0,0,0}, - {12782,12783,12784 ,4664,4665,4666 ,0,0,0}, {12783,12785,12784 ,4665,4667,4666 ,0,0,0}, - {12786,12787,12788 ,4668,4669,4670 ,0,0,0}, {12786,12788,12785 ,4668,4670,4667 ,0,0,0}, - {12783,12786,12785 ,4665,4668,4667 ,0,0,0}, {12778,12782,12779 ,4660,4664,4661 ,0,0,0}, - {12782,12784,12779 ,4664,4666,4661 ,0,0,0}, {12789,12790,12791 ,4671,4672,4673 ,0,0,0}, - {12792,12793,12794 ,4674,4675,4676 ,0,0,0}, {12791,12790,12792 ,4673,4672,4674 ,0,0,0}, - {12795,12796,12797 ,4677,4678,4679 ,0,0,0}, {12791,12792,12794 ,4673,4674,4676 ,0,0,0}, - {12797,12796,12793 ,4679,4678,4675 ,0,0,0}, {12796,12794,12793 ,4678,4676,4675 ,0,0,0}, - {12787,12790,12789 ,4669,4672,4671 ,0,0,0}, {12798,12795,12797 ,4677,4677,4679 ,0,0,0}, - {12788,12787,12789 ,4670,4669,4671 ,0,0,0}, {12772,12776,12773 ,4654,4658,4655 ,0,0,0}, - {12799,12772,12771 ,4680,4654,4653 ,0,0,0}, {12799,12800,12801 ,4680,4681,4682 ,0,0,0}, - {12800,12799,12771 ,4681,4680,4653 ,0,0,0}, {12802,12801,12803 ,4683,4682,4684 ,0,0,0}, - {12800,12803,12801 ,4681,4684,4682 ,0,0,0}, {12804,12805,12802 ,4685,4686,4683 ,0,0,0}, - {12802,12803,12804 ,4683,4684,4685 ,0,0,0}, {12805,12806,12807 ,4686,4687,4688 ,0,0,0}, - {12806,12805,12804 ,4687,4686,4685 ,0,0,0}, {12808,12807,12809 ,4689,4688,4690 ,0,0,0}, - {12806,12809,12807 ,4687,4690,4688 ,0,0,0}, {12810,12811,12808 ,4691,4692,4689 ,0,0,0}, - {12808,12809,12810 ,4689,4690,4691 ,0,0,0}, {12811,12812,12813 ,4692,4693,4694 ,0,0,0}, - {12812,12811,12810 ,4693,4692,4691 ,0,0,0}, {12814,12813,12815 ,4695,4694,4696 ,0,0,0}, - {12812,12815,12813 ,4693,4696,4694 ,0,0,0}, {12816,12817,12814 ,4697,4698,4695 ,0,0,0}, - {12814,12815,12816 ,4695,4696,4697 ,0,0,0}, {12817,12818,12819 ,4698,4699,4700 ,0,0,0}, - {12818,12817,12816 ,4699,4698,4697 ,0,0,0}, {12818,12820,12819 ,4699,4701,4700 ,0,0,0}, - {12821,12822,12823 ,4702,4703,4704 ,0,0,0}, {12824,12825,12826 ,4705,4706,4707 ,0,0,0}, - {12822,12826,12825 ,4703,4707,4706 ,0,0,0}, {12827,12828,12829 ,4708,4709,4710 ,0,0,0}, - {12830,12824,12831 ,4711,4705,4712 ,0,0,0}, {12827,12830,12831 ,4708,4711,4712 ,0,0,0}, - {12830,12827,12829 ,4711,4708,4710 ,0,0,0}, {12831,12824,12826 ,4712,4705,4707 ,0,0,0}, - {12832,12833,12834 ,4713,4714,4715 ,0,0,0}, {12834,12833,12835 ,4715,4714,4716 ,0,0,0}, - {12836,12837,12838 ,4717,4718,4719 ,0,0,0}, {12836,12835,12837 ,4717,4716,4718 ,0,0,0}, - {12834,12835,12836 ,4715,4716,4717 ,0,0,0}, {12829,12828,12832 ,4710,4709,4713 ,0,0,0}, - {12832,12828,12833 ,4713,4709,4714 ,0,0,0}, {12839,12840,12841 ,4720,4721,4722 ,0,0,0}, - {12842,12843,12844 ,4723,4724,4725 ,0,0,0}, {12840,12842,12841 ,4721,4723,4722 ,0,0,0}, - {12845,12846,12847 ,4726,4727,4728 ,0,0,0}, {12840,12843,12842 ,4721,4724,4723 ,0,0,0}, - {12846,12844,12847 ,4727,4725,4728 ,0,0,0}, {12847,12844,12843 ,4728,4725,4724 ,0,0,0}, - {12838,12839,12841 ,4719,4720,4722 ,0,0,0}, {12848,12846,12845 ,4726,4727,4726 ,0,0,0}, - {12837,12839,12838 ,4718,4720,4719 ,0,0,0}, {12823,12822,12825 ,4704,4703,4706 ,0,0,0}, - {12849,12821,12823 ,4729,4702,4704 ,0,0,0}, {12849,12850,12851 ,4729,4730,4731 ,0,0,0}, - {12851,12821,12849 ,4731,4702,4729 ,0,0,0}, {12852,12853,12850 ,4732,4733,4730 ,0,0,0}, - {12851,12850,12853 ,4731,4730,4733 ,0,0,0}, {12854,12852,12855 ,4734,4732,4735 ,0,0,0}, - {12852,12854,12853 ,4732,4734,4733 ,0,0,0}, {12855,12856,12857 ,4735,4736,4737 ,0,0,0}, - {12857,12854,12855 ,4737,4734,4735 ,0,0,0}, {12858,12859,12856 ,4738,4739,4736 ,0,0,0}, - {12857,12856,12859 ,4737,4736,4739 ,0,0,0}, {12860,12858,12861 ,4740,4738,4741 ,0,0,0}, - {12858,12860,12859 ,4738,4740,4739 ,0,0,0}, {12861,12862,12863 ,4741,4742,4743 ,0,0,0}, - {12863,12860,12861 ,4743,4740,4741 ,0,0,0}, {12864,12865,12862 ,4744,4745,4742 ,0,0,0}, - {12863,12862,12865 ,4743,4742,4745 ,0,0,0}, {12866,12864,12867 ,4746,4744,4747 ,0,0,0}, - {12864,12866,12865 ,4744,4746,4745 ,0,0,0}, {12867,12868,12869 ,4747,4748,4749 ,0,0,0}, - {12869,12866,12867 ,4749,4746,4747 ,0,0,0}, {12869,12868,12870 ,4749,4748,4750 ,0,0,0}, - {12871,12872,12873 ,4751,4752,4753 ,0,0,0}, {12874,12875,12876 ,4754,4755,4756 ,0,0,0}, - {12872,12876,12875 ,4752,4756,4755 ,0,0,0}, {12877,12878,12879 ,4757,4758,4759 ,0,0,0}, - {12880,12874,12881 ,4760,4754,4761 ,0,0,0}, {12880,12881,12877 ,4760,4761,4757 ,0,0,0}, - {12877,12879,12880 ,4757,4759,4760 ,0,0,0}, {12874,12876,12881 ,4754,4756,4761 ,0,0,0}, - {12882,12883,12884 ,4762,4763,4764 ,0,0,0}, {12885,12883,12882 ,4765,4763,4762 ,0,0,0}, - {12886,12887,12888 ,4766,4767,4768 ,0,0,0}, {12886,12888,12885 ,4766,4768,4765 ,0,0,0}, - {12885,12888,12883 ,4765,4768,4763 ,0,0,0}, {12878,12884,12879 ,4758,4764,4759 ,0,0,0}, - {12882,12884,12878 ,4762,4764,4758 ,0,0,0}, {12889,12890,12891 ,4769,4770,4771 ,0,0,0}, - {12892,12893,12894 ,4772,4773,4774 ,0,0,0}, {12891,12890,12894 ,4771,4770,4774 ,0,0,0}, - {12895,12896,12897 ,4775,4776,4777 ,0,0,0}, {12890,12892,12894 ,4770,4772,4774 ,0,0,0}, - {12895,12893,12896 ,4775,4773,4776 ,0,0,0}, {12893,12892,12896 ,4773,4772,4776 ,0,0,0}, - {12889,12891,12887 ,4769,4771,4767 ,0,0,0}, {12898,12895,12897 ,4777,4775,4777 ,0,0,0}, - {12886,12889,12887 ,4766,4769,4767 ,0,0,0}, {12872,12875,12873 ,4752,4755,4753 ,0,0,0}, - {12871,12873,12899 ,4751,4753,4778 ,0,0,0}, {12899,12900,12901 ,4778,4779,4780 ,0,0,0}, - {12901,12871,12899 ,4780,4751,4778 ,0,0,0}, {12902,12900,12903 ,4781,4779,4782 ,0,0,0}, - {12900,12902,12901 ,4779,4781,4780 ,0,0,0}, {12904,12905,12903 ,4783,4784,4782 ,0,0,0}, - {12902,12903,12905 ,4781,4782,4784 ,0,0,0}, {12904,12906,12907 ,4783,4785,4786 ,0,0,0}, - {12907,12905,12904 ,4786,4784,4783 ,0,0,0}, {12908,12906,12909 ,4787,4785,4788 ,0,0,0}, - {12906,12908,12907 ,4785,4787,4786 ,0,0,0}, {12910,12911,12909 ,4789,4790,4788 ,0,0,0}, - {12908,12909,12911 ,4787,4788,4790 ,0,0,0}, {12910,12912,12913 ,4789,4791,4792 ,0,0,0}, - {12913,12911,12910 ,4792,4790,4789 ,0,0,0}, {12914,12912,12915 ,4793,4791,4794 ,0,0,0}, - {12912,12914,12913 ,4791,4793,4792 ,0,0,0}, {12916,12917,12915 ,4795,4796,4794 ,0,0,0}, - {12914,12915,12917 ,4793,4794,4796 ,0,0,0}, {12916,12918,12919 ,4795,4797,4798 ,0,0,0}, - {12919,12917,12916 ,4798,4796,4795 ,0,0,0}, {12918,12920,12919 ,4797,4799,4798 ,0,0,0}, - {12918,12921,12920 ,4797,324,4799 ,0,0,0}, {12922,12923,12924 ,82,4800,4801 ,0,0,0}, - {12924,12925,12926 ,4801,4802,4803 ,0,0,0}, {12925,12927,12926 ,4802,4804,4803 ,0,0,0}, - {12924,12926,12922 ,4801,4803,82 ,0,0,0}, {12928,12929,12930 ,4805,4806,4807 ,0,0,0}, - {12930,12929,12927 ,4807,4806,4804 ,0,0,0}, {12928,12931,12932 ,4805,4808,4809 ,0,0,0}, - {12932,12929,12928 ,4809,4806,4805 ,0,0,0}, {12932,12931,12933 ,4809,4808,4810 ,0,0,0}, - {12933,12931,12934 ,4810,4808,4811 ,0,0,0}, {12934,12935,12936 ,4811,4812,4813 ,0,0,0}, - {12933,12934,12936 ,4810,4811,4813 ,0,0,0}, {12927,12925,12930 ,4804,4802,4807 ,0,0,0}, - {12937,12938,12939 ,4814,4815,4816 ,0,0,0}, {12937,12939,12935 ,4814,4816,4812 ,0,0,0}, - {12935,12939,12936 ,4812,4816,4813 ,0,0,0}, {12922,12940,12923 ,82,4817,4800 ,0,0,0}, - {12941,12940,12942 ,4818,4817,4819 ,0,0,0}, {12940,12941,12923 ,4817,4818,4800 ,0,0,0}, - {12943,12944,12942 ,4820,4821,4819 ,0,0,0}, {12941,12942,12944 ,4818,4819,4821 ,0,0,0}, - {12943,12945,12946 ,4820,4822,4823 ,0,0,0}, {12946,12944,12943 ,4823,4821,4820 ,0,0,0}, - {12947,12945,12948 ,4824,4822,4825 ,0,0,0}, {12945,12947,12946 ,4822,4824,4823 ,0,0,0}, - {12949,12950,12948 ,4826,4827,4825 ,0,0,0}, {12947,12948,12950 ,4824,4825,4827 ,0,0,0}, - {12949,12951,12952 ,4826,4828,4829 ,0,0,0}, {12952,12950,12949 ,4829,4827,4826 ,0,0,0}, - {12953,12951,12954 ,4830,4828,4831 ,0,0,0}, {12951,12953,12952 ,4828,4830,4829 ,0,0,0}, - {12949,12948,12955 ,4832,4833,4834 ,0,0,0}, {12955,12951,12949 ,4834,4835,4832 ,0,0,0}, - {12955,12954,12951 ,4834,4836,4835 ,0,0,0}, {12955,12945,12943 ,4834,4837,4838 ,0,0,0}, - {12948,12945,12955 ,4833,4837,4834 ,0,0,0}, {12955,12942,12940 ,4834,4839,4840 ,0,0,0}, - {12943,12942,12955 ,4838,4839,4834 ,0,0,0}, {12940,12922,12955 ,4840,4841,4834 ,0,0,0}, - {12927,12955,12926 ,4842,4834,4843 ,0,0,0}, {12955,12922,12926 ,4834,4841,4843 ,0,0,0}, - {12932,12955,12929 ,4844,4834,4845 ,0,0,0}, {12955,12927,12929 ,4834,4842,4845 ,0,0,0}, - {12936,12955,12933 ,4846,4834,4847 ,0,0,0}, {12955,12932,12933 ,4834,4844,4847 ,0,0,0}, - {12938,12955,12939 ,4848,4834,4849 ,0,0,0}, {12955,12936,12939 ,4834,4846,4849 ,0,0,0}, - {12956,12957,12958 ,82,4850,4851 ,0,0,0}, {12958,12959,12960 ,4851,4852,4853 ,0,0,0}, - {12959,12961,12960 ,4852,4854,4853 ,0,0,0}, {12958,12960,12956 ,4851,4853,82 ,0,0,0}, - {12962,12963,12964 ,4855,4856,4857 ,0,0,0}, {12964,12963,12961 ,4857,4856,4854 ,0,0,0}, - {12962,12965,12966 ,4855,4858,4859 ,0,0,0}, {12966,12963,12962 ,4859,4856,4855 ,0,0,0}, - {12966,12965,12967 ,4859,4858,4860 ,0,0,0}, {12967,12965,12968 ,4860,4858,4861 ,0,0,0}, - {12968,12969,12970 ,4861,4862,4863 ,0,0,0}, {12967,12968,12970 ,4860,4861,4863 ,0,0,0}, - {12961,12959,12964 ,4854,4852,4857 ,0,0,0}, {12971,12972,12973 ,4864,4865,4866 ,0,0,0}, - {12971,12973,12969 ,4864,4866,4862 ,0,0,0}, {12969,12973,12970 ,4862,4866,4863 ,0,0,0}, - {12956,12974,12957 ,82,4867,4850 ,0,0,0}, {12975,12974,12976 ,4868,4867,4869 ,0,0,0}, - {12974,12975,12957 ,4867,4868,4850 ,0,0,0}, {12977,12978,12976 ,4870,4871,4869 ,0,0,0}, - {12975,12976,12978 ,4868,4869,4871 ,0,0,0}, {12977,12979,12980 ,4870,4872,4873 ,0,0,0}, - {12980,12978,12977 ,4873,4871,4870 ,0,0,0}, {12981,12979,12982 ,4874,4872,4875 ,0,0,0}, - {12979,12981,12980 ,4872,4874,4873 ,0,0,0}, {12983,12984,12982 ,4876,4877,4875 ,0,0,0}, - {12981,12982,12984 ,4874,4875,4877 ,0,0,0}, {12983,12985,12986 ,4876,4878,4829 ,0,0,0}, - {12986,12984,12983 ,4829,4877,4876 ,0,0,0}, {12987,12985,12988 ,4879,4878,4831 ,0,0,0}, - {12985,12987,12986 ,4878,4879,4829 ,0,0,0}, {12983,12982,12989 ,4832,4833,4880 ,0,0,0}, - {12989,12985,12983 ,4880,4835,4832 ,0,0,0}, {12989,12988,12985 ,4880,4881,4835 ,0,0,0}, - {12989,12979,12977 ,4880,4837,4838 ,0,0,0}, {12982,12979,12989 ,4833,4837,4880 ,0,0,0}, - {12989,12976,12974 ,4880,4839,4840 ,0,0,0}, {12977,12976,12989 ,4838,4839,4880 ,0,0,0}, - {12974,12956,12989 ,4840,4882,4880 ,0,0,0}, {12961,12989,12960 ,4842,4880,4843 ,0,0,0}, - {12989,12956,12960 ,4880,4882,4843 ,0,0,0}, {12966,12989,12963 ,4844,4880,4845 ,0,0,0}, - {12989,12961,12963 ,4880,4842,4845 ,0,0,0}, {12970,12989,12967 ,4846,4880,4847 ,0,0,0}, - {12989,12966,12967 ,4880,4844,4847 ,0,0,0}, {12972,12989,12973 ,4883,4880,4849 ,0,0,0}, - {12989,12970,12973 ,4880,4846,4849 ,0,0,0}, {12990,12991,12992 ,4884,4885,4886 ,0,0,0}, - {12992,12993,12994 ,4886,4887,4888 ,0,0,0}, {12993,12995,12994 ,4887,4889,4888 ,0,0,0}, - {12992,12994,12990 ,4886,4888,4884 ,0,0,0}, {12996,12997,12998 ,4890,4891,4857 ,0,0,0}, - {12998,12997,12995 ,4857,4891,4889 ,0,0,0}, {12996,12999,13000 ,4890,4892,4893 ,0,0,0}, - {13000,12997,12996 ,4893,4891,4890 ,0,0,0}, {13000,12999,13001 ,4893,4892,4894 ,0,0,0}, - {13001,12999,13002 ,4894,4892,4895 ,0,0,0}, {13002,13003,13004 ,4895,4896,4897 ,0,0,0}, - {13001,13002,13004 ,4894,4895,4897 ,0,0,0}, {12995,12993,12998 ,4889,4887,4857 ,0,0,0}, - {13005,13006,13007 ,4898,4899,4900 ,0,0,0}, {13005,13007,13003 ,4898,4900,4896 ,0,0,0}, - {13003,13007,13004 ,4896,4900,4897 ,0,0,0}, {12990,13008,12991 ,4884,4901,4885 ,0,0,0}, - {13009,13008,13010 ,4868,4901,4902 ,0,0,0}, {13008,13009,12991 ,4901,4868,4885 ,0,0,0}, - {13011,13012,13010 ,4820,4903,4902 ,0,0,0}, {13009,13010,13012 ,4868,4902,4903 ,0,0,0}, - {13011,13013,13014 ,4820,4904,4905 ,0,0,0}, {13014,13012,13011 ,4905,4903,4820 ,0,0,0}, - {13015,13013,13016 ,4906,4904,4907 ,0,0,0}, {13013,13015,13014 ,4904,4906,4905 ,0,0,0}, - {13017,13018,13016 ,4826,4877,4907 ,0,0,0}, {13015,13016,13018 ,4906,4907,4877 ,0,0,0}, - {13017,13019,13020 ,4826,4828,4908 ,0,0,0}, {13020,13018,13017 ,4908,4877,4826 ,0,0,0}, - {13021,13019,13022 ,4909,4828,4910 ,0,0,0}, {13019,13021,13020 ,4828,4909,4908 ,0,0,0}, - {13017,13016,13023 ,4832,4833,4880 ,0,0,0}, {13023,13019,13017 ,4880,4835,4832 ,0,0,0}, - {13023,13022,13019 ,4880,4911,4835 ,0,0,0}, {13023,13013,13011 ,4880,4837,4838 ,0,0,0}, - {13016,13013,13023 ,4833,4837,4880 ,0,0,0}, {13023,13010,13008 ,4880,4839,4840 ,0,0,0}, - {13011,13010,13023 ,4838,4839,4880 ,0,0,0}, {13008,12990,13023 ,4840,4912,4880 ,0,0,0}, - {12995,13023,12994 ,4842,4880,4843 ,0,0,0}, {13023,12990,12994 ,4880,4912,4843 ,0,0,0}, - {13000,13023,12997 ,4844,4880,4845 ,0,0,0}, {13023,12995,12997 ,4880,4842,4845 ,0,0,0}, - {13004,13023,13001 ,4846,4880,4847 ,0,0,0}, {13023,13000,13001 ,4880,4844,4847 ,0,0,0}, - {13006,13023,13007 ,4913,4880,4849 ,0,0,0}, {13023,13004,13007 ,4880,4846,4849 ,0,0,0}, - {13024,13025,13026 ,4914,4915,4916 ,0,0,0}, {13026,13027,13028 ,4916,4917,4918 ,0,0,0}, - {13027,13029,13028 ,4917,4919,4918 ,0,0,0}, {13026,13028,13024 ,4916,4918,4914 ,0,0,0}, - {13030,13031,13032 ,4920,4921,4922 ,0,0,0}, {13032,13031,13029 ,4922,4921,4919 ,0,0,0}, - {13030,13033,13034 ,4920,4923,4924 ,0,0,0}, {13034,13031,13030 ,4924,4921,4920 ,0,0,0}, - {13034,13033,13035 ,4924,4923,4925 ,0,0,0}, {13035,13033,13036 ,4925,4923,4926 ,0,0,0}, - {13036,13037,13038 ,4926,4927,4928 ,0,0,0}, {13035,13036,13038 ,4925,4926,4928 ,0,0,0}, - {13029,13027,13032 ,4919,4917,4922 ,0,0,0}, {13039,13040,13041 ,4929,4815,4930 ,0,0,0}, - {13039,13041,13037 ,4929,4930,4927 ,0,0,0}, {13037,13041,13038 ,4927,4930,4928 ,0,0,0}, - {13024,13042,13025 ,4914,4931,4915 ,0,0,0}, {13043,13042,13044 ,4932,4931,4933 ,0,0,0}, - {13042,13043,13025 ,4931,4932,4915 ,0,0,0}, {13045,13046,13044 ,4934,4821,4933 ,0,0,0}, - {13043,13044,13046 ,4932,4933,4821 ,0,0,0}, {13045,13047,13048 ,4934,4935,4936 ,0,0,0}, - {13048,13046,13045 ,4936,4821,4934 ,0,0,0}, {13049,13047,13050 ,4937,4935,4938 ,0,0,0}, - {13047,13049,13048 ,4935,4937,4936 ,0,0,0}, {13051,13052,13050 ,4826,4877,4938 ,0,0,0}, - {13049,13050,13052 ,4937,4938,4877 ,0,0,0}, {13051,13053,13054 ,4826,4939,4940 ,0,0,0}, - {13054,13052,13051 ,4940,4877,4826 ,0,0,0}, {13055,13053,13056 ,4941,4939,4942 ,0,0,0}, - {13053,13055,13054 ,4939,4941,4940 ,0,0,0}, {13051,13050,13057 ,4832,4833,4943 ,0,0,0}, - {13057,13053,13051 ,4943,4835,4832 ,0,0,0}, {13057,13056,13053 ,4943,4944,4835 ,0,0,0}, - {13057,13047,13045 ,4943,4837,4838 ,0,0,0}, {13050,13047,13057 ,4833,4837,4943 ,0,0,0}, - {13057,13044,13042 ,4943,4839,4840 ,0,0,0}, {13045,13044,13057 ,4838,4839,4943 ,0,0,0}, - {13042,13024,13057 ,4840,4945,4943 ,0,0,0}, {13029,13057,13028 ,4842,4943,4843 ,0,0,0}, - {13057,13024,13028 ,4943,4945,4843 ,0,0,0}, {13034,13057,13031 ,4844,4943,4845 ,0,0,0}, - {13057,13029,13031 ,4943,4842,4845 ,0,0,0}, {13038,13057,13035 ,4846,4943,4847 ,0,0,0}, - {13057,13034,13035 ,4943,4844,4847 ,0,0,0}, {13040,13057,13041 ,4946,4943,4849 ,0,0,0}, - {13057,13038,13041 ,4943,4846,4849 ,0,0,0}, {13058,13059,13060 ,4947,4948,4949 ,0,0,0}, - {13061,13062,13063 ,4950,4951,4952 ,0,0,0}, {13060,13063,13062 ,4949,4952,4951 ,0,0,0}, - {13064,13065,13066 ,4953,4954,4955 ,0,0,0}, {13067,13068,13061 ,4956,4957,4950 ,0,0,0}, - {13064,13068,13067 ,4953,4957,4956 ,0,0,0}, {13067,13065,13064 ,4956,4954,4953 ,0,0,0}, - {13068,13062,13061 ,4957,4951,4950 ,0,0,0}, {13069,13070,13071 ,4958,4959,4960 ,0,0,0}, - {13070,13072,13071 ,4959,4961,4960 ,0,0,0}, {13073,13074,13075 ,4962,4963,4964 ,0,0,0}, - {13073,13075,13072 ,4962,4964,4961 ,0,0,0}, {13070,13073,13072 ,4959,4962,4961 ,0,0,0}, - {13065,13069,13066 ,4954,4958,4955 ,0,0,0}, {13069,13071,13066 ,4958,4960,4955 ,0,0,0}, - {13076,13077,13078 ,4965,4966,4967 ,0,0,0}, {13079,13080,13081 ,4968,4969,4970 ,0,0,0}, - {13078,13077,13079 ,4967,4966,4968 ,0,0,0}, {13082,13083,13084 ,4726,4971,4972 ,0,0,0}, - {13078,13079,13081 ,4967,4968,4970 ,0,0,0}, {13084,13083,13080 ,4972,4971,4969 ,0,0,0}, - {13083,13081,13080 ,4971,4970,4969 ,0,0,0}, {13074,13077,13076 ,4963,4966,4965 ,0,0,0}, - {13085,13082,13084 ,4726,4726,4972 ,0,0,0}, {13075,13074,13076 ,4964,4963,4965 ,0,0,0}, - {13059,13063,13060 ,4948,4952,4949 ,0,0,0}, {13086,13059,13058 ,4973,4948,4947 ,0,0,0}, - {13086,13087,13088 ,4973,4974,4975 ,0,0,0}, {13087,13086,13058 ,4974,4973,4947 ,0,0,0}, - {13089,13088,13090 ,4976,4975,4977 ,0,0,0}, {13087,13090,13088 ,4974,4977,4975 ,0,0,0}, - {13091,13092,13089 ,4978,4979,4976 ,0,0,0}, {13089,13090,13091 ,4976,4977,4978 ,0,0,0}, - {13092,13093,13094 ,4979,4980,4981 ,0,0,0}, {13093,13092,13091 ,4980,4979,4978 ,0,0,0}, - {13095,13094,13096 ,4982,4981,4983 ,0,0,0}, {13093,13096,13094 ,4980,4983,4981 ,0,0,0}, - {13097,13098,13095 ,4984,4985,4982 ,0,0,0}, {13095,13096,13097 ,4982,4983,4984 ,0,0,0}, - {13098,13099,13100 ,4985,4986,4987 ,0,0,0}, {13099,13098,13097 ,4986,4985,4984 ,0,0,0}, - {13101,13100,13102 ,4988,4987,4989 ,0,0,0}, {13099,13102,13100 ,4986,4989,4987 ,0,0,0}, - {13103,13104,13101 ,4990,4991,4988 ,0,0,0}, {13101,13102,13103 ,4988,4989,4990 ,0,0,0}, - {13104,13105,13106 ,4991,4992,4748 ,0,0,0}, {13105,13104,13103 ,4992,4991,4990 ,0,0,0}, - {13105,13107,13106 ,4992,4750,4748 ,0,0,0}, {13108,13109,13110 ,4993,4994,4995 ,0,0,0}, - {13111,13112,13113 ,4996,4997,4998 ,0,0,0}, {13109,13114,13115 ,4994,4999,5000 ,0,0,0}, - {13114,13109,13108 ,4999,4994,4993 ,0,0,0}, {13114,13116,13115 ,4999,5001,5000 ,0,0,0}, - {13110,13117,13108 ,4995,5002,4993 ,0,0,0}, {13111,13117,13118 ,4996,5002,5003 ,0,0,0}, - {13110,13118,13117 ,4995,5003,5002 ,0,0,0}, {13119,13120,13121 ,5004,5005,5006 ,0,0,0}, - {13111,13118,13112 ,4996,5003,4997 ,0,0,0}, {13122,13123,13124 ,5007,5008,5009 ,0,0,0}, - {13125,13126,13127 ,5010,5011,5012 ,0,0,0}, {13128,13129,13130 ,5013,5014,5015 ,0,0,0}, - {13131,13132,13133 ,5016,5017,5018 ,0,0,0}, {13134,13135,13136 ,5019,5020,5021 ,0,0,0}, - {13137,13138,13129 ,5022,5023,5014 ,0,0,0}, {13139,13140,13141 ,5024,5025,5026 ,0,0,0}, - {13140,13135,13142 ,5025,5020,5027 ,0,0,0}, {13143,13144,13145 ,5028,5029,5030 ,0,0,0}, - {13146,13147,13139 ,5031,5032,5024 ,0,0,0}, {13148,13149,13150 ,5033,5034,5035 ,0,0,0}, - {13151,13145,13152 ,5036,5030,5037 ,0,0,0}, {13153,13154,13155 ,5038,5039,5040 ,0,0,0}, - {13156,13154,13157 ,5041,5039,5042 ,0,0,0}, {13158,13159,13160 ,5043,5044,5045 ,0,0,0}, - {13155,13161,13158 ,5040,5046,5043 ,0,0,0}, {13162,13163,13164 ,5047,5048,5049 ,0,0,0}, - {13162,13165,13166 ,5047,5050,5051 ,0,0,0}, {13167,13168,13169 ,5052,5053,5054 ,0,0,0}, - {13170,13171,13169 ,5055,5056,5054 ,0,0,0}, {13172,13173,13174 ,5057,5058,5059 ,0,0,0}, - {13173,13167,13175 ,5058,5052,5060 ,0,0,0}, {13176,13177,13178 ,5061,5062,5063 ,0,0,0}, - {13172,13179,13176 ,5057,5064,5061 ,0,0,0}, {13180,13181,13182 ,5065,5066,5067 ,0,0,0}, - {13180,13183,13184 ,5065,5068,5069 ,0,0,0}, {13185,13186,13187 ,5070,5071,5072 ,0,0,0}, - {13185,13188,13181 ,5070,5073,5066 ,0,0,0}, {13189,13186,13190 ,5074,5071,5075 ,0,0,0}, - {13186,13189,13187 ,5071,5074,5072 ,0,0,0}, {13191,13192,13190 ,5076,5077,5075 ,0,0,0}, - {13189,13190,13192 ,5074,5075,5077 ,0,0,0}, {13193,13194,13192 ,5078,5079,5077 ,0,0,0}, - {13192,13191,13193 ,5077,5076,5078 ,0,0,0}, {13194,13195,13196 ,5079,5080,5081 ,0,0,0}, - {13195,13194,13193 ,5080,5079,5078 ,0,0,0}, {13197,13196,13198 ,5082,5081,5083 ,0,0,0}, - {13195,13198,13196 ,5080,5083,5081 ,0,0,0}, {13199,13200,13197 ,5084,5085,5082 ,0,0,0}, - {13197,13198,13199 ,5082,5083,5084 ,0,0,0}, {13200,13201,13202 ,5085,5086,5087 ,0,0,0}, - {13201,13200,13199 ,5086,5085,5084 ,0,0,0}, {13203,13202,13204 ,5088,5087,5089 ,0,0,0}, - {13201,13204,13202 ,5086,5089,5087 ,0,0,0}, {13205,13203,13206 ,5090,5088,5091 ,0,0,0}, - {13203,13204,13206 ,5088,5089,5091 ,0,0,0}, {13205,13207,13208 ,5090,5092,5093 ,0,0,0}, - {13208,13203,13205 ,5093,5088,5090 ,0,0,0}, {13209,13207,13210 ,5094,5092,5095 ,0,0,0}, - {13207,13209,13208 ,5092,5094,5093 ,0,0,0}, {13211,13212,13210 ,126,5096,5095 ,0,0,0}, - {13209,13210,13212 ,5094,5095,5096 ,0,0,0}, {13213,13212,13211 ,126,5096,126 ,0,0,0}, - {13182,13181,13188 ,5067,5066,5073 ,0,0,0}, {13185,13187,13188 ,5070,5072,5073 ,0,0,0}, - {13178,13183,13176 ,5063,5068,5061 ,0,0,0}, {13180,13182,13183 ,5065,5067,5068 ,0,0,0}, - {13178,13184,13183 ,5063,5069,5068 ,0,0,0}, {13174,13179,13172 ,5059,5064,5057 ,0,0,0}, - {13176,13179,13177 ,5061,5064,5062 ,0,0,0}, {13168,13167,13173 ,5053,5052,5058 ,0,0,0}, - {13173,13175,13174 ,5058,5060,5059 ,0,0,0}, {13170,13163,13171 ,5055,5048,5056 ,0,0,0}, - {13168,13170,13169 ,5053,5055,5054 ,0,0,0}, {13162,13164,13165 ,5047,5049,5050 ,0,0,0}, - {13163,13170,13164 ,5048,5055,5049 ,0,0,0}, {13159,13166,13160 ,5044,5051,5045 ,0,0,0}, - {13166,13165,13160 ,5051,5050,5045 ,0,0,0}, {13155,13158,13153 ,5040,5043,5038 ,0,0,0}, - {13161,13159,13158 ,5046,5044,5043 ,0,0,0}, {13148,13156,13149 ,5033,5041,5034 ,0,0,0}, - {13157,13154,13153 ,5042,5039,5038 ,0,0,0}, {13149,13156,13157 ,5034,5041,5042 ,0,0,0}, - {13150,13151,13152 ,5035,5036,5037 ,0,0,0}, {13149,13151,13150 ,5034,5036,5035 ,0,0,0}, - {13145,13147,13143 ,5030,5032,5028 ,0,0,0}, {13152,13145,13144 ,5037,5030,5029 ,0,0,0}, - {13214,13146,13139 ,5097,5031,5024 ,0,0,0}, {13146,13143,13147 ,5031,5028,5032 ,0,0,0}, - {13215,13140,13142 ,5098,5025,5027 ,0,0,0}, {13139,13141,13214 ,5024,5026,5097 ,0,0,0}, - {13140,13215,13141 ,5025,5098,5026 ,0,0,0}, {13136,13137,13134 ,5021,5022,5019 ,0,0,0}, - {13142,13135,13134 ,5027,5020,5019 ,0,0,0}, {13130,13133,13128 ,5015,5018,5013 ,0,0,0}, - {13137,13136,13138 ,5022,5021,5023 ,0,0,0}, {13129,13138,13130 ,5014,5023,5015 ,0,0,0}, - {13122,13131,13133 ,5007,5016,5018 ,0,0,0}, {13132,13128,13133 ,5017,5013,5018 ,0,0,0}, - {13123,13127,13124 ,5008,5012,5009 ,0,0,0}, {13122,13124,13131 ,5007,5009,5016 ,0,0,0}, - {13125,13119,13126 ,5010,5004,5011 ,0,0,0}, {13123,13125,13127 ,5008,5010,5012 ,0,0,0}, - {13121,13120,13113 ,5006,5005,4998 ,0,0,0}, {13126,13119,13121 ,5011,5004,5006 ,0,0,0}, - {13111,13113,13120 ,4996,4998,5005 ,0,0,0}, {13216,13217,13218 ,5099,5100,5101 ,0,0,0}, - {13219,13220,13221 ,5102,5103,5104 ,0,0,0}, {13222,13220,13219 ,5105,5103,5102 ,0,0,0}, - {13223,13219,13221 ,5106,5102,5104 ,0,0,0}, {13224,13225,13226 ,5107,5108,5109 ,0,0,0}, - {13227,13228,13223 ,5110,5108,5106 ,0,0,0}, {13225,13229,13226 ,5108,5111,5109 ,0,0,0}, - {13225,13228,13229 ,5108,5108,5111 ,0,0,0}, {13229,13230,13231 ,5111,5112,5113 ,0,0,0}, - {13230,13232,13231 ,5112,5114,5113 ,0,0,0}, {13231,13232,13233 ,5113,5114,5115 ,0,0,0}, - {13232,13234,13233 ,5114,5116,5115 ,0,0,0}, {13235,13236,13234 ,5117,5118,5116 ,0,0,0}, - {13235,13237,13238 ,5117,5119,5120 ,0,0,0}, {13239,13238,13237 ,5121,5120,5119 ,0,0,0}, - {13239,13237,13240 ,5121,5119,5122 ,0,0,0}, {13240,13241,13239 ,5122,5123,5121 ,0,0,0}, - {13236,13233,13234 ,5118,5115,5116 ,0,0,0}, {13238,13236,13235 ,5120,5118,5117 ,0,0,0}, - {13241,13242,13243 ,5123,5124,5125 ,0,0,0}, {13242,13241,13240 ,5124,5123,5122 ,0,0,0}, - {12820,13243,13242 ,5126,5125,5124 ,0,0,0}, {13222,13219,13244 ,5105,5102,5127 ,0,0,0}, - {13245,13246,13247 ,5128,5129,5130 ,0,0,0}, {13245,13244,13246 ,5128,5127,5129 ,0,0,0}, - {13246,13248,13247 ,5129,5131,5130 ,0,0,0}, {13248,13246,13249 ,5131,5129,5132 ,0,0,0}, - {13250,13251,13252 ,5133,5134,5135 ,0,0,0}, {13250,13249,13251 ,5133,5132,5134 ,0,0,0}, - {13253,13252,13251 ,5136,5135,5134 ,0,0,0}, {13252,13253,13254 ,5135,5136,5137 ,0,0,0}, - {13255,13256,13257 ,5138,5139,5140 ,0,0,0}, {13258,13259,13253 ,5141,5142,5136 ,0,0,0}, - {13260,13261,13258 ,5143,5144,5141 ,0,0,0}, {13261,13260,13262 ,5144,5143,5145 ,0,0,0}, - {13263,13264,13260 ,5146,5147,5143 ,0,0,0}, {13217,13216,13265 ,5100,5099,5148 ,0,0,0}, - {13266,13267,13263 ,5149,5150,5146 ,0,0,0}, {13268,13269,13270 ,5151,5152,5153 ,0,0,0}, - {13271,13272,13273 ,5154,5155,5156 ,0,0,0}, {13274,13275,13276 ,5157,5158,5159 ,0,0,0}, - {13277,13278,13279 ,5160,5161,5162 ,0,0,0}, {13280,13281,13282 ,5163,5164,5165 ,0,0,0}, - {13283,13284,13285 ,5166,5167,5168 ,0,0,0}, {13283,13286,13287 ,5166,5169,5170 ,0,0,0}, - {13288,13289,13290 ,5171,5172,5173 ,0,0,0}, {13291,13292,13293 ,5174,5175,5176 ,0,0,0}, - {13294,13295,13296 ,5177,5178,5179 ,0,0,0}, {13297,13289,13288 ,5180,5172,5171 ,0,0,0}, - {13298,13299,13300 ,5179,5181,5182 ,0,0,0}, {13298,13296,13295 ,5179,5179,5178 ,0,0,0}, - {13301,13302,13303 ,5183,5184,5185 ,0,0,0}, {13304,13301,13300 ,5186,5183,5182 ,0,0,0}, - {13305,13306,13307 ,5187,5188,5189 ,0,0,0}, {13308,13305,13303 ,5190,5187,5185 ,0,0,0}, - {13309,13310,13311 ,5191,5192,5193 ,0,0,0}, {13310,13309,13307 ,5192,5191,5189 ,0,0,0}, - {13312,13313,13311 ,5194,5195,5193 ,0,0,0}, {13309,13311,13313 ,5191,5193,5195 ,0,0,0}, - {13312,13314,13315 ,5194,5196,5197 ,0,0,0}, {13315,13313,13312 ,5197,5195,5194 ,0,0,0}, - {13308,13306,13305 ,5190,5188,5187 ,0,0,0}, {13306,13310,13307 ,5188,5192,5189 ,0,0,0}, - {13302,13308,13303 ,5184,5190,5185 ,0,0,0}, {13304,13302,13301 ,5186,5184,5183 ,0,0,0}, - {13299,13304,13300 ,5181,5186,5182 ,0,0,0}, {13299,13298,13295 ,5181,5179,5178 ,0,0,0}, - {13295,13316,13299 ,5178,5198,5181 ,0,0,0}, {13288,13316,13297 ,5171,5198,5180 ,0,0,0}, - {13316,13295,13297 ,5198,5178,5180 ,0,0,0}, {13317,13318,13319 ,5199,5200,5201 ,0,0,0}, - {13290,13289,13291 ,5173,5172,5174 ,0,0,0}, {13317,13320,13321 ,5199,5202,5203 ,0,0,0}, - {13321,13318,13317 ,5203,5200,5199 ,0,0,0}, {13322,13320,13323 ,5204,5202,5205 ,0,0,0}, - {13320,13322,13321 ,5202,5204,5203 ,0,0,0}, {13324,12918,13323 ,5206,5207,5205 ,0,0,0}, - {13322,13323,12918 ,5204,5205,5207 ,0,0,0}, {12921,12918,13324 ,5197,5207,5206 ,0,0,0}, - {13319,13318,13325 ,5201,5200,5208 ,0,0,0}, {13326,13327,13328 ,5209,5210,5211 ,0,0,0}, - {13319,13325,13328 ,5201,5208,5211 ,0,0,0}, {13326,13329,13327 ,5209,5212,5210 ,0,0,0}, - {13328,13325,13326 ,5211,5208,5209 ,0,0,0}, {13292,13284,13293 ,5175,5167,5176 ,0,0,0}, - {13329,13330,13327 ,5212,5213,5210 ,0,0,0}, {13296,13330,13294 ,5179,5213,5177 ,0,0,0}, - {13329,13294,13330 ,5212,5177,5213 ,0,0,0}, {13291,13293,13290 ,5174,5176,5173 ,0,0,0}, - {13282,13271,13280 ,5165,5154,5163 ,0,0,0}, {13283,13285,13286 ,5166,5168,5169 ,0,0,0}, - {13284,13292,13285 ,5167,5175,5168 ,0,0,0}, {13286,13279,13287 ,5169,5162,5170 ,0,0,0}, - {13281,13278,13277 ,5164,5161,5160 ,0,0,0}, {13278,13287,13279 ,5161,5170,5162 ,0,0,0}, - {13282,13281,13277 ,5165,5164,5160 ,0,0,0}, {13268,13275,13274 ,5151,5158,5157 ,0,0,0}, - {13271,13273,13280 ,5154,5156,5163 ,0,0,0}, {13272,13276,13273 ,5155,5159,5156 ,0,0,0}, - {13270,13275,13268 ,5153,5158,5151 ,0,0,0}, {13272,13274,13276 ,5155,5157,5159 ,0,0,0}, - {13218,13270,13269 ,5101,5153,5152 ,0,0,0}, {13269,12870,13266 ,5152,5214,5149 ,0,0,0}, - {13224,13331,13225 ,5107,5215,5108 ,0,0,0}, {13230,13229,13228 ,5112,5111,5108 ,0,0,0}, - {13227,13332,13228 ,5110,5216,5108 ,0,0,0}, {13230,13228,13332 ,5112,5108,5216 ,0,0,0}, - {13333,13331,13334 ,5217,5215,5218 ,0,0,0}, {13221,13227,13223 ,5104,5110,5106 ,0,0,0}, - {13335,13333,13336 ,5219,5217,5220 ,0,0,0}, {13335,13337,13333 ,5219,5221,5217 ,0,0,0}, - {13338,13337,13339 ,5222,5221,5223 ,0,0,0}, {13245,13222,13244 ,5128,5105,5127 ,0,0,0}, - {13340,13338,13341 ,5224,5222,5225 ,0,0,0}, {13340,13342,13338 ,5224,5226,5222 ,0,0,0}, - {13343,13342,13344 ,5227,5226,5228 ,0,0,0}, {13250,13248,13249 ,5133,5131,5132 ,0,0,0}, - {13345,13346,13343 ,5229,5230,5227 ,0,0,0}, {13347,13346,13345 ,5231,5230,5229 ,0,0,0}, - {13348,13346,13349 ,5232,5230,5233 ,0,0,0}, {13259,13254,13253 ,5142,5137,5136 ,0,0,0}, - {13257,13348,13255 ,5140,5232,5138 ,0,0,0}, {13261,13259,13258 ,5144,5142,5141 ,0,0,0}, - {13350,13257,13351 ,5234,5140,5235 ,0,0,0}, {13264,13262,13260 ,5147,5145,5143 ,0,0,0}, - {13216,13350,13265 ,5099,5234,5148 ,0,0,0}, {13267,13264,13263 ,5150,5147,5146 ,0,0,0}, - {13267,13266,12870 ,5150,5149,5214 ,0,0,0}, {13269,13266,13218 ,5152,5149,5101 ,0,0,0}, - {13218,13266,13216 ,5101,5149,5099 ,0,0,0}, {13351,13265,13350 ,5235,5148,5234 ,0,0,0}, - {13256,13351,13257 ,5139,5235,5140 ,0,0,0}, {13349,13255,13348 ,5233,5138,5232 ,0,0,0}, - {13347,13349,13346 ,5231,5233,5230 ,0,0,0}, {13344,13345,13343 ,5228,5229,5227 ,0,0,0}, - {13340,13344,13342 ,5224,5228,5226 ,0,0,0}, {13339,13341,13338 ,5223,5225,5222 ,0,0,0}, - {13335,13339,13337 ,5219,5223,5221 ,0,0,0}, {13334,13336,13333 ,5218,5220,5217 ,0,0,0}, - {13224,13334,13331 ,5107,5218,5215 ,0,0,0}, {13352,13353,13354 ,5236,5237,5238 ,0,0,0}, - {13355,13356,13354 ,5239,5240,5238 ,0,0,0}, {13352,13354,13356 ,5236,5238,5240 ,0,0,0}, - {13355,13357,13358 ,5239,5241,5242 ,0,0,0}, {13358,13356,13355 ,5242,5240,5239 ,0,0,0}, - {13359,13357,13360 ,5243,5241,5244 ,0,0,0}, {13357,13359,13358 ,5241,5243,5242 ,0,0,0}, - {13361,13362,13360 ,5245,5246,5244 ,0,0,0}, {13359,13360,13362 ,5243,5244,5246 ,0,0,0}, - {13361,13363,13364 ,5245,5247,5248 ,0,0,0}, {13364,13362,13361 ,5248,5246,5245 ,0,0,0}, - {13365,13363,13366 ,5249,5247,5250 ,0,0,0}, {13363,13365,13364 ,5247,5249,5248 ,0,0,0}, - {13367,13368,13366 ,5251,5252,5250 ,0,0,0}, {13365,13366,13368 ,5249,5250,5252 ,0,0,0}, - {13367,13369,13370 ,5251,5253,5254 ,0,0,0}, {13370,13368,13367 ,5254,5252,5251 ,0,0,0}, - {13371,13369,13372 ,5255,5253,5256 ,0,0,0}, {13369,13371,13370 ,5253,5255,5254 ,0,0,0}, - {13373,13374,13372 ,5257,5258,5256 ,0,0,0}, {13371,13372,13374 ,5255,5256,5258 ,0,0,0}, - {13373,13375,13376 ,5257,5259,5260 ,0,0,0}, {13376,13374,13373 ,5260,5258,5257 ,0,0,0}, - {13377,13375,13378 ,5261,5259,5262 ,0,0,0}, {13375,13377,13376 ,5259,5261,5260 ,0,0,0}, - {13379,13380,13378 ,5263,5264,5262 ,0,0,0}, {13377,13378,13380 ,5261,5262,5264 ,0,0,0}, - {13379,13381,13382 ,5263,5265,5266 ,0,0,0}, {13382,13380,13379 ,5266,5264,5263 ,0,0,0}, - {13383,13381,13384 ,5267,5265,5268 ,0,0,0}, {13381,13383,13382 ,5265,5267,5266 ,0,0,0}, - {13385,13386,13384 ,5269,5270,5268 ,0,0,0}, {13383,13384,13386 ,5267,5268,5270 ,0,0,0}, - {13385,13387,13388 ,5269,5271,5272 ,0,0,0}, {13388,13386,13385 ,5272,5270,5269 ,0,0,0}, - {13389,13387,13390 ,5273,5271,5274 ,0,0,0}, {13387,13389,13388 ,5271,5273,5272 ,0,0,0}, - {13391,13392,13390 ,5275,5276,5274 ,0,0,0}, {13389,13390,13392 ,5273,5274,5276 ,0,0,0}, - {13391,13393,13394 ,5275,5277,5278 ,0,0,0}, {13394,13392,13391 ,5278,5276,5275 ,0,0,0}, - {13395,13393,13396 ,5279,5277,5280 ,0,0,0}, {13393,13395,13394 ,5277,5279,5278 ,0,0,0}, - {13397,13398,13396 ,5281,5282,5280 ,0,0,0}, {13395,13396,13398 ,5279,5280,5282 ,0,0,0}, - {13399,13397,13400 ,5283,5281,5284 ,0,0,0}, {13399,13398,13397 ,5283,5282,5281 ,0,0,0}, - {13401,13400,13402 ,5285,5284,5286 ,0,0,0}, {13397,13402,13400 ,5281,5286,5284 ,0,0,0}, - {13403,13401,13404 ,5287,5285,5288 ,0,0,0}, {13401,13402,13404 ,5285,5286,5288 ,0,0,0}, - {13403,13405,13406 ,5287,5289,5290 ,0,0,0}, {13406,13401,13403 ,5290,5285,5287 ,0,0,0}, - {13405,13407,13406 ,5289,5291,5290 ,0,0,0}, {13408,13353,13352 ,5292,5237,5236 ,0,0,0}, - {13408,13409,13410 ,5292,5293,5294 ,0,0,0}, {13410,13353,13408 ,5294,5237,5292 ,0,0,0}, - {13411,13409,13412 ,5295,5293,5296 ,0,0,0}, {13409,13411,13410 ,5293,5295,5294 ,0,0,0}, - {13413,13414,13412 ,5297,5298,5296 ,0,0,0}, {13411,13412,13414 ,5295,5296,5298 ,0,0,0}, - {13413,13415,13416 ,5297,5299,5300 ,0,0,0}, {13416,13414,13413 ,5300,5298,5297 ,0,0,0}, - {13417,13415,13418 ,5301,5299,5302 ,0,0,0}, {13415,13417,13416 ,5299,5301,5300 ,0,0,0}, - {13419,13420,13418 ,5303,5304,5302 ,0,0,0}, {13417,13418,13420 ,5301,5302,5304 ,0,0,0}, - {13419,13421,13422 ,5303,5305,5306 ,0,0,0}, {13422,13420,13419 ,5306,5304,5303 ,0,0,0}, - {13423,13421,13424 ,5307,5305,5308 ,0,0,0}, {13421,13423,13422 ,5305,5307,5306 ,0,0,0}, - {13425,13426,13424 ,5309,5310,5308 ,0,0,0}, {13423,13424,13426 ,5307,5308,5310 ,0,0,0}, - {13425,13427,13428 ,5309,5311,5312 ,0,0,0}, {13428,13426,13425 ,5312,5310,5309 ,0,0,0}, - {13429,13427,13430 ,5313,5311,5314 ,0,0,0}, {13427,13429,13428 ,5311,5313,5312 ,0,0,0}, - {13431,13432,13430 ,5315,5316,5314 ,0,0,0}, {13429,13430,13432 ,5313,5314,5316 ,0,0,0}, - {13431,13433,13434 ,5315,5317,5318 ,0,0,0}, {13434,13432,13431 ,5318,5316,5315 ,0,0,0}, - {13435,13433,13436 ,5319,5317,5320 ,0,0,0}, {13433,13435,13434 ,5317,5319,5318 ,0,0,0}, - {13437,13438,13436 ,5321,5322,5320 ,0,0,0}, {13435,13436,13438 ,5319,5320,5322 ,0,0,0}, - {13437,13439,13440 ,5321,5323,5324 ,0,0,0}, {13440,13438,13437 ,5324,5322,5321 ,0,0,0}, - {13441,13439,13442 ,5325,5323,5326 ,0,0,0}, {13439,13441,13440 ,5323,5325,5324 ,0,0,0}, - {13443,13444,13442 ,5327,5328,5326 ,0,0,0}, {13441,13442,13444 ,5325,5326,5328 ,0,0,0}, - {13443,13445,13446 ,5327,5329,5330 ,0,0,0}, {13446,13444,13443 ,5330,5328,5327 ,0,0,0}, - {13447,13445,13448 ,5331,5329,5332 ,0,0,0}, {13445,13447,13446 ,5329,5331,5330 ,0,0,0}, - {13449,13450,13448 ,5333,5334,5332 ,0,0,0}, {13447,13448,13450 ,5331,5332,5334 ,0,0,0}, - {13449,13451,13452 ,5333,5335,5336 ,0,0,0}, {13452,13450,13449 ,5336,5334,5333 ,0,0,0}, - {13453,13454,13451 ,5337,5338,5335 ,0,0,0}, {13451,13454,13452 ,5335,5338,5336 ,0,0,0}, - {13455,13456,13453 ,5339,5340,5337 ,0,0,0}, {13453,13451,13455 ,5337,5335,5339 ,0,0,0}, - {13457,13458,13456 ,5341,5342,5340 ,0,0,0}, {13457,13456,13455 ,5341,5340,5339 ,0,0,0}, - {13459,13458,13460 ,5343,5342,5344 ,0,0,0}, {13458,13459,13456 ,5342,5343,5340 ,0,0,0}, - {13459,13460,13461 ,5343,5344,5345 ,0,0,0}, {13462,13463,13464 ,5346,5347,5348 ,0,0,0}, - {13465,13466,13464 ,5349,5350,5348 ,0,0,0}, {13462,13464,13466 ,5346,5348,5350 ,0,0,0}, - {13465,13467,13468 ,5349,5351,5352 ,0,0,0}, {13468,13466,13465 ,5352,5350,5349 ,0,0,0}, - {13469,13467,13470 ,5353,5351,5354 ,0,0,0}, {13467,13469,13468 ,5351,5353,5352 ,0,0,0}, - {13471,13472,13470 ,5355,5356,5354 ,0,0,0}, {13469,13470,13472 ,5353,5354,5356 ,0,0,0}, - {13471,13473,13474 ,5355,5357,5358 ,0,0,0}, {13474,13472,13471 ,5358,5356,5355 ,0,0,0}, - {13475,13473,13476 ,5359,5357,5360 ,0,0,0}, {13473,13475,13474 ,5357,5359,5358 ,0,0,0}, - {13477,13478,13476 ,5361,5362,5360 ,0,0,0}, {13475,13476,13478 ,5359,5360,5362 ,0,0,0}, - {13477,13479,13480 ,5361,5363,5364 ,0,0,0}, {13480,13478,13477 ,5364,5362,5361 ,0,0,0}, - {13481,13479,13482 ,5365,5363,5366 ,0,0,0}, {13479,13481,13480 ,5363,5365,5364 ,0,0,0}, - {13483,13484,13482 ,5367,5368,5366 ,0,0,0}, {13481,13482,13484 ,5365,5366,5368 ,0,0,0}, - {13483,13485,13486 ,5367,5369,5370 ,0,0,0}, {13486,13484,13483 ,5370,5368,5367 ,0,0,0}, - {13487,13485,13488 ,5371,5369,5372 ,0,0,0}, {13485,13487,13486 ,5369,5371,5370 ,0,0,0}, - {13489,13490,13488 ,5373,5374,5372 ,0,0,0}, {13487,13488,13490 ,5371,5372,5374 ,0,0,0}, - {13489,13491,13492 ,5373,5375,5376 ,0,0,0}, {13492,13490,13489 ,5376,5374,5373 ,0,0,0}, - {13493,13491,13494 ,5377,5375,5378 ,0,0,0}, {13491,13493,13492 ,5375,5377,5376 ,0,0,0}, - {13495,13496,13494 ,5379,5380,5378 ,0,0,0}, {13493,13494,13496 ,5377,5378,5380 ,0,0,0}, - {13495,13497,13498 ,5379,5381,5382 ,0,0,0}, {13498,13496,13495 ,5382,5380,5379 ,0,0,0}, - {13499,13497,13500 ,5383,5381,5384 ,0,0,0}, {13497,13499,13498 ,5381,5383,5382 ,0,0,0}, - {13501,13502,13500 ,5385,5386,5384 ,0,0,0}, {13499,13500,13502 ,5383,5384,5386 ,0,0,0}, - {13501,13503,13504 ,5385,5387,5388 ,0,0,0}, {13504,13502,13501 ,5388,5386,5385 ,0,0,0}, - {13505,13503,13506 ,5389,5387,5390 ,0,0,0}, {13503,13505,13504 ,5387,5389,5388 ,0,0,0}, - {13507,13508,13506 ,5391,5392,5390 ,0,0,0}, {13505,13506,13508 ,5389,5390,5392 ,0,0,0}, - {13507,13509,13510 ,5391,5393,5394 ,0,0,0}, {13510,13508,13507 ,5394,5392,5391 ,0,0,0}, - {13511,13509,13512 ,5395,5393,5396 ,0,0,0}, {13509,13511,13510 ,5393,5395,5394 ,0,0,0}, - {13513,13514,13512 ,5397,5398,5396 ,0,0,0}, {13511,13512,13514 ,5395,5396,5398 ,0,0,0}, - {13513,13515,13516 ,5397,5399,5400 ,0,0,0}, {13516,13514,13513 ,5400,5398,5397 ,0,0,0}, - {13517,13515,13518 ,5401,5399,5402 ,0,0,0}, {13515,13517,13516 ,5399,5401,5400 ,0,0,0}, - {13519,13520,13518 ,5403,5404,5402 ,0,0,0}, {13517,13518,13520 ,5401,5402,5404 ,0,0,0}, - {13519,13521,13522 ,5403,5405,5406 ,0,0,0}, {13522,13520,13519 ,5406,5404,5403 ,0,0,0}, - {13521,13523,13522 ,5405,5407,5406 ,0,0,0}, {13524,13463,13462 ,5408,5347,5346 ,0,0,0}, - {13524,13525,13526 ,5408,5409,5410 ,0,0,0}, {13526,13463,13524 ,5410,5347,5408 ,0,0,0}, - {13527,13525,13528 ,5411,5409,5412 ,0,0,0}, {13525,13527,13526 ,5409,5411,5410 ,0,0,0}, - {13529,13530,13528 ,5413,5414,5412 ,0,0,0}, {13527,13528,13530 ,5411,5412,5414 ,0,0,0}, - {13529,13531,13532 ,5413,5415,5416 ,0,0,0}, {13532,13530,13529 ,5416,5414,5413 ,0,0,0}, - {13533,13531,13534 ,5417,5415,5418 ,0,0,0}, {13531,13533,13532 ,5415,5417,5416 ,0,0,0}, - {13535,13536,13534 ,5419,5420,5418 ,0,0,0}, {13533,13534,13536 ,5417,5418,5420 ,0,0,0}, - {13535,13537,13538 ,5419,5421,5422 ,0,0,0}, {13538,13536,13535 ,5422,5420,5419 ,0,0,0}, - {13539,13537,13540 ,5423,5421,5424 ,0,0,0}, {13537,13539,13538 ,5421,5423,5422 ,0,0,0}, - {13541,13542,13540 ,5425,5426,5424 ,0,0,0}, {13539,13540,13542 ,5423,5424,5426 ,0,0,0}, - {13541,13543,13544 ,5425,5427,5428 ,0,0,0}, {13544,13542,13541 ,5428,5426,5425 ,0,0,0}, - {13545,13543,13546 ,5429,5427,5430 ,0,0,0}, {13543,13545,13544 ,5427,5429,5428 ,0,0,0}, - {13547,13548,13546 ,5431,5432,5430 ,0,0,0}, {13545,13546,13548 ,5429,5430,5432 ,0,0,0}, - {13547,13549,13550 ,5431,5433,5434 ,0,0,0}, {13550,13548,13547 ,5434,5432,5431 ,0,0,0}, - {13551,13549,13552 ,5435,5433,5436 ,0,0,0}, {13549,13551,13550 ,5433,5435,5434 ,0,0,0}, - {13553,13554,13552 ,5437,5438,5436 ,0,0,0}, {13551,13552,13554 ,5435,5436,5438 ,0,0,0}, - {13553,13555,13556 ,5437,5439,5440 ,0,0,0}, {13556,13554,13553 ,5440,5438,5437 ,0,0,0}, - {13557,13555,13558 ,5441,5439,5442 ,0,0,0}, {13555,13557,13556 ,5439,5441,5440 ,0,0,0}, - {13559,13560,13558 ,5443,5444,5442 ,0,0,0}, {13557,13558,13560 ,5441,5442,5444 ,0,0,0}, - {13559,13561,13562 ,5443,5445,5446 ,0,0,0}, {13562,13560,13559 ,5446,5444,5443 ,0,0,0}, - {13563,13561,13564 ,5447,5445,5448 ,0,0,0}, {13561,13563,13562 ,5445,5447,5446 ,0,0,0}, - {13565,13566,13564 ,5449,5450,5448 ,0,0,0}, {13563,13564,13566 ,5447,5448,5450 ,0,0,0}, - {13565,13567,13568 ,5449,5451,5452 ,0,0,0}, {13568,13566,13565 ,5452,5450,5449 ,0,0,0}, - {13569,13567,13570 ,5453,5451,5454 ,0,0,0}, {13567,13569,13568 ,5451,5453,5452 ,0,0,0}, - {13571,13572,13570 ,5455,5456,5454 ,0,0,0}, {13569,13570,13572 ,5453,5454,5456 ,0,0,0}, - {13571,13573,13574 ,5455,5457,5458 ,0,0,0}, {13574,13572,13571 ,5458,5456,5455 ,0,0,0}, - {13575,13573,13576 ,5459,5457,5460 ,0,0,0}, {13573,13575,13574 ,5457,5459,5458 ,0,0,0}, - {13577,13578,13576 ,5461,5462,5460 ,0,0,0}, {13575,13576,13578 ,5459,5460,5462 ,0,0,0}, - {13577,13579,13580 ,5461,5463,5464 ,0,0,0}, {13580,13578,13577 ,5464,5462,5461 ,0,0,0}, - {13581,13579,13582 ,5465,5463,5466 ,0,0,0}, {13579,13581,13580 ,5463,5465,5464 ,0,0,0}, - {13581,13582,13583 ,5465,5466,5467 ,0,0,0}, {13584,12618,12617 ,5468,5469,5469 ,0,0,0}, - {13585,13586,13587 ,726,726,726 ,0,0,0}, {13588,12351,12348 ,726,5470,726 ,0,0,0}, - {13589,13590,13591 ,5471,726,726 ,0,0,0}, {13592,13593,13594 ,726,726,726 ,0,0,0}, - {13595,12573,13596 ,5468,5471,5469 ,0,0,0}, {13597,13598,13599 ,5470,726,726 ,0,0,0}, - {13600,13601,13602 ,5471,5469,5469 ,0,0,0}, {13603,13602,12546 ,5468,5469,5469 ,0,0,0}, - {13604,13605,12652 ,5469,5472,5468 ,0,0,0}, {13606,13607,13608 ,5469,5468,5471 ,0,0,0}, - {13609,13610,13611 ,5473,5474,726 ,0,0,0}, {13612,13613,13614 ,5475,5476,5471 ,0,0,0}, - {13615,13616,13617 ,5477,5478,5469 ,0,0,0}, {13610,13609,13618 ,5474,5473,5479 ,0,0,0}, - {13619,13620,13621 ,5471,5469,726 ,0,0,0}, {13622,13623,12611 ,5468,5469,5471 ,0,0,0}, - {13624,13625,13626 ,726,5480,5481 ,0,0,0}, {13617,13627,13628 ,5469,726,5468 ,0,0,0}, - {13629,13630,13631 ,5475,5475,5482 ,0,0,0}, {13632,12286,13629 ,5468,5483,5475 ,0,0,0}, - {13631,13633,13634 ,5482,5482,5482 ,0,0,0}, {13630,13633,13631 ,5475,5482,5482 ,0,0,0}, - {13634,13635,13631 ,5482,5475,5482 ,0,0,0}, {13626,13620,13636 ,5481,5469,5475 ,0,0,0}, - {13637,12666,13638 ,726,5471,5484 ,0,0,0}, {13610,13618,13628 ,5474,5479,5468 ,0,0,0}, - {13639,13640,13641 ,5475,5485,5468 ,0,0,0}, {13642,13643,13644 ,5486,5483,5468 ,0,0,0}, - {13627,13610,13628 ,726,5474,5468 ,0,0,0}, {12611,13623,12612 ,5471,5469,726 ,0,0,0}, - {12618,13584,12620 ,5469,5468,726 ,0,0,0}, {12624,12623,13645 ,5471,5471,726 ,0,0,0}, - {12652,12622,13604 ,5468,5468,5469 ,0,0,0}, {12650,12622,12652 ,5471,5468,5468 ,0,0,0}, - {12624,13646,12649 ,5471,5471,5469 ,0,0,0}, {13647,12656,12655 ,5468,5478,726 ,0,0,0}, - {12623,13648,13645 ,5471,726,726 ,0,0,0}, {12579,13649,13650 ,5471,5468,726 ,0,0,0}, - {13651,12666,12664 ,5475,5471,726 ,0,0,0}, {13652,13653,13654 ,5469,5482,5483 ,0,0,0}, - {13655,13653,13656 ,5468,5482,5475 ,0,0,0}, {13657,13658,13659 ,726,5468,5468 ,0,0,0}, - {13660,13608,13661 ,726,5471,5469 ,0,0,0}, {13662,13663,13664 ,5475,5475,726 ,0,0,0}, - {13658,13657,13665 ,5468,726,5483 ,0,0,0}, {13666,13667,13668 ,5480,5487,5475 ,0,0,0}, - {13665,13669,13652 ,5483,5478,5469 ,0,0,0}, {13670,13671,13672 ,5475,5479,5474 ,0,0,0}, - {13672,13638,13670 ,5474,5484,5475 ,0,0,0}, {13673,13674,13672 ,5473,726,5474 ,0,0,0}, - {13673,13672,13671 ,5473,5474,5479 ,0,0,0}, {13655,13654,13653 ,5468,5483,5482 ,0,0,0}, - {13667,13662,13675 ,5487,5475,726 ,0,0,0}, {13653,13652,13669 ,5482,5469,5478 ,0,0,0}, - {13676,13677,13637 ,5486,5478,726 ,0,0,0}, {13660,13661,13659 ,726,5469,5468 ,0,0,0}, - {12576,13649,12579 ,726,5468,5471 ,0,0,0}, {13670,13638,12666 ,5475,5484,5471 ,0,0,0}, - {13678,13679,13680 ,726,726,726 ,0,0,0}, {13681,13682,12582 ,5468,5469,726 ,0,0,0}, - {13651,12664,13683 ,5475,726,5482 ,0,0,0}, {13684,12588,13685 ,726,726,5470 ,0,0,0}, - {12661,13686,13687 ,5475,5485,5475 ,0,0,0}, {13688,13689,12506 ,5471,726,5471 ,0,0,0}, - {12410,13690,12405 ,726,5470,726 ,0,0,0}, {13691,13692,13693 ,5470,5471,5471 ,0,0,0}, - {13694,13695,13696 ,726,726,5470 ,0,0,0}, {13696,13597,13694 ,5470,5470,726 ,0,0,0}, - {13678,13599,13679 ,726,726,726 ,0,0,0}, {13697,13698,13699 ,726,726,5470 ,0,0,0}, - {13591,13691,13693 ,726,5470,5471 ,0,0,0}, {13695,13700,13701 ,726,726,726 ,0,0,0}, - {12590,13702,13703 ,726,5470,726 ,0,0,0}, {13704,13705,13706 ,5470,726,726 ,0,0,0}, - {13679,13599,13598 ,726,726,726 ,0,0,0}, {13702,13707,13708 ,5470,726,5468 ,0,0,0}, - {13679,13709,13680 ,726,726,726 ,0,0,0}, {13708,13710,13711 ,5468,5468,726 ,0,0,0}, - {13707,13710,13708 ,726,5468,5468 ,0,0,0}, {13711,13712,13708 ,726,5471,5468 ,0,0,0}, - {13713,13714,13715 ,726,726,5471 ,0,0,0}, {12590,13707,13702 ,726,726,5470 ,0,0,0}, - {13703,13716,13717 ,726,726,726 ,0,0,0}, {13718,13719,13720 ,726,5488,5489 ,0,0,0}, - {12548,13721,13722 ,5471,5470,726 ,0,0,0}, {12576,13602,13649 ,726,5469,5468 ,0,0,0}, - {13723,12503,12500 ,726,726,5471 ,0,0,0}, {13724,12427,12424 ,726,726,726 ,0,0,0}, - {13725,12360,13726 ,726,5470,726 ,0,0,0}, {13727,12503,13723 ,726,726,726 ,0,0,0}, - {13728,13729,13730 ,726,726,726 ,0,0,0}, {13731,13732,13733 ,5489,726,726 ,0,0,0}, - {12497,13734,12498 ,726,5471,726 ,0,0,0}, {13735,13729,13736 ,726,726,726 ,0,0,0}, - {13737,13738,13739 ,726,726,5489 ,0,0,0}, {13740,13741,13742 ,726,726,726 ,0,0,0}, - {13743,13729,13735 ,726,726,726 ,0,0,0}, {13585,13587,13742 ,726,726,726 ,0,0,0}, - {13744,13745,13746 ,726,726,5489 ,0,0,0}, {13586,13728,13730 ,726,726,726 ,0,0,0}, - {13747,13748,13749 ,726,726,726 ,0,0,0}, {13745,13750,13747 ,726,5488,726 ,0,0,0}, - {13743,13730,13729 ,726,726,726 ,0,0,0}, {13594,13731,12514 ,726,5489,726 ,0,0,0}, - {13751,13752,13753 ,5489,726,726 ,0,0,0}, {13751,13754,13752 ,5489,5488,726 ,0,0,0}, - {13755,13756,13757 ,726,5471,726 ,0,0,0}, {13752,13754,13758 ,726,5488,726 ,0,0,0}, - {13759,13752,13758 ,726,726,726 ,0,0,0}, {13760,12472,13761 ,726,726,726 ,0,0,0}, - {12430,13762,13763 ,726,726,726 ,0,0,0}, {12588,12586,13685 ,726,726,5470 ,0,0,0}, - {13594,12510,13764 ,726,726,726 ,0,0,0}, {13756,13765,13766 ,5471,5471,726 ,0,0,0}, - {13767,12328,13768 ,726,5470,726 ,0,0,0}, {13757,13769,13755 ,726,5471,726 ,0,0,0}, - {12438,13770,13771 ,5489,726,726 ,0,0,0}, {13772,13773,13774 ,726,726,726 ,0,0,0}, - {13775,13776,13774 ,726,5471,726 ,0,0,0}, {13739,13738,13777 ,5489,726,5488 ,0,0,0}, - {13724,13778,12427 ,726,726,726 ,0,0,0}, {13732,13594,13753 ,726,726,726 ,0,0,0}, - {13779,13724,13777 ,726,726,5488 ,0,0,0}, {12354,13780,13781 ,726,5471,726 ,0,0,0}, - {13782,13783,13773 ,726,5488,726 ,0,0,0}, {13774,13784,13785 ,726,5471,726 ,0,0,0}, - {13786,13787,13788 ,726,726,5488 ,0,0,0}, {13789,13790,13786 ,726,726,726 ,0,0,0}, - {13791,13790,13792 ,726,726,726 ,0,0,0}, {13793,12438,13771 ,726,5489,726 ,0,0,0}, - {13794,13774,13795 ,726,726,726 ,0,0,0}, {13771,13770,13796 ,726,726,726 ,0,0,0}, - {13773,13797,13782 ,726,726,726 ,0,0,0}, {13798,13796,13770 ,726,726,726 ,0,0,0}, - {13773,13783,13774 ,726,5488,726 ,0,0,0}, {13798,13799,13796 ,726,5488,726 ,0,0,0}, - {13800,13797,13773 ,726,726,726 ,0,0,0}, {13796,13799,13801 ,726,5488,726 ,0,0,0}, - {13774,13802,13784 ,726,726,5471 ,0,0,0}, {12633,13803,12632 ,5469,5468,5468 ,0,0,0}, - {12633,12638,13804 ,5469,726,726 ,0,0,0}, {13805,12345,13806 ,726,5471,5471 ,0,0,0}, - {13807,12252,13808 ,5470,5468,5468 ,0,0,0}, {12362,13809,13810 ,5470,726,726 ,0,0,0}, - {13811,13812,13813 ,5468,726,5469 ,0,0,0}, {13814,13815,13816 ,5471,5468,726 ,0,0,0}, - {13817,13811,13818 ,5468,5468,726 ,0,0,0}, {13819,13820,13821 ,726,5470,5469 ,0,0,0}, - {13822,13823,13824 ,726,5469,726 ,0,0,0}, {13825,13826,13827 ,5471,5469,726 ,0,0,0}, - {13828,12649,13829 ,726,5469,5470 ,0,0,0}, {13793,13830,13831 ,726,5489,726 ,0,0,0}, - {13774,13776,13832 ,726,5471,726 ,0,0,0}, {13833,12536,12535 ,5468,726,5469 ,0,0,0}, - {13834,13835,13724 ,5470,5471,726 ,0,0,0}, {13588,13836,12351 ,726,726,5470 ,0,0,0}, - {13837,12396,12395 ,5471,726,726 ,0,0,0}, {13838,12638,12636 ,726,726,5468 ,0,0,0}, - {13839,13840,13841 ,726,5470,5471 ,0,0,0}, {13842,13843,13844 ,5471,726,5470 ,0,0,0}, - {13845,13846,13847 ,726,5470,726 ,0,0,0}, {13809,13848,13810 ,726,726,726 ,0,0,0}, - {13848,13809,13849 ,726,726,726 ,0,0,0}, {13810,13840,12362 ,726,5470,5470 ,0,0,0}, - {13848,13849,13850 ,726,726,726 ,0,0,0}, {13822,13816,13815 ,726,726,5468 ,0,0,0}, - {13848,13850,13851 ,726,726,726 ,0,0,0}, {13852,13853,13854 ,5471,5471,5468 ,0,0,0}, - {13820,13827,13821 ,5470,726,5469 ,0,0,0}, {13855,13819,13856 ,726,726,726 ,0,0,0}, - {13857,13858,13826 ,5468,5469,5469 ,0,0,0}, {13826,13825,13857 ,5469,5471,5468 ,0,0,0}, - {13859,13860,13857 ,5471,726,5468 ,0,0,0}, {13857,13860,13858 ,5468,726,5469 ,0,0,0}, - {12656,13861,12658 ,5478,5487,5468 ,0,0,0}, {12590,12588,13684 ,726,726,726 ,0,0,0}, - {13683,12664,12662 ,5482,726,5468 ,0,0,0}, {13682,12585,12582 ,5469,726,726 ,0,0,0}, - {13603,13600,13602 ,5468,5471,5469 ,0,0,0}, {13862,13601,13600 ,5468,5469,5471 ,0,0,0}, - {13607,13606,13863 ,5468,5469,5469 ,0,0,0}, {13601,13862,13864 ,5469,5468,5470 ,0,0,0}, - {13606,13608,13660 ,5469,5471,726 ,0,0,0}, {13863,13864,13865 ,5469,5470,5469 ,0,0,0}, - {13659,13661,13657 ,5468,5469,726 ,0,0,0}, {13665,13652,13658 ,5483,5469,5468 ,0,0,0}, - {13663,13669,13664 ,5475,5478,726 ,0,0,0}, {13669,13665,13664 ,5478,5483,726 ,0,0,0}, - {13676,13666,13677 ,5486,5480,5478 ,0,0,0}, {13667,13663,13662 ,5487,5475,5475 ,0,0,0}, - {13666,13668,13677 ,5480,5475,5478 ,0,0,0}, {13668,13667,13675 ,5475,5487,726 ,0,0,0}, - {13638,13676,13637 ,5484,5486,726 ,0,0,0}, {13651,13670,12666 ,5475,5475,5471 ,0,0,0}, - {13683,12662,13687 ,5482,5468,5475 ,0,0,0}, {13687,12662,12661 ,5475,5468,5475 ,0,0,0}, - {12658,13861,13686 ,5468,5487,5485 ,0,0,0}, {13686,12661,12658 ,5485,5475,5468 ,0,0,0}, - {13647,13861,12656 ,5468,5487,5478 ,0,0,0}, {13605,13647,12655 ,5472,5468,726 ,0,0,0}, - {13829,12649,13646 ,5470,5469,5471 ,0,0,0}, {12652,13605,12655 ,5468,5472,726 ,0,0,0}, - {13866,13867,12632 ,5471,5470,5468 ,0,0,0}, {12629,13867,13868 ,726,5470,726 ,0,0,0}, - {13614,13869,13612 ,5471,5468,5475 ,0,0,0}, {13623,13870,12612 ,5469,5469,726 ,0,0,0}, - {13871,13872,13632 ,5472,5482,5468 ,0,0,0}, {12595,12264,12591 ,5468,5468,5468 ,0,0,0}, - {12272,12270,13811 ,5471,726,5468 ,0,0,0}, {12527,12174,12525 ,5471,726,5469 ,0,0,0}, - {12538,13873,12541 ,5471,726,726 ,0,0,0}, {13723,12500,13589 ,726,5471,5471 ,0,0,0}, - {12194,13874,13875 ,726,726,5470 ,0,0,0}, {13876,13877,12436 ,726,726,726 ,0,0,0}, - {13878,12556,13879 ,726,726,5471 ,0,0,0}, {12171,13880,12168 ,5471,5471,5471 ,0,0,0}, - {12183,13881,13882 ,726,5469,5469 ,0,0,0}, {12522,12635,12641 ,5471,5469,5469 ,0,0,0}, - {12629,12632,13867 ,726,5468,5470 ,0,0,0}, {12645,12523,12641 ,5468,726,5469 ,0,0,0}, - {12635,12179,12636 ,5469,5471,5468 ,0,0,0}, {13838,13804,12638 ,726,726,726 ,0,0,0}, - {13804,13803,12633 ,726,5468,5469 ,0,0,0}, {13803,13866,12632 ,5468,5471,5468 ,0,0,0}, - {12626,12629,13868 ,726,726,726 ,0,0,0}, {12622,12650,13828 ,5468,5471,726 ,0,0,0}, - {12626,13648,12623 ,726,726,5471 ,0,0,0}, {13648,12626,13868 ,726,726,726 ,0,0,0}, - {13645,13646,12624 ,726,5471,5471 ,0,0,0}, {12649,13828,12650 ,5469,726,5471 ,0,0,0}, - {12620,13883,12622 ,726,5468,5468 ,0,0,0}, {13613,13604,13884 ,5476,5469,5468 ,0,0,0}, - {13883,13604,12622 ,5468,5469,5468 ,0,0,0}, {12612,13870,12614 ,726,5469,5470 ,0,0,0}, - {12617,12614,13885 ,5469,5470,726 ,0,0,0}, {13870,13885,12614 ,5469,726,5470 ,0,0,0}, - {13616,13615,13640 ,5478,5477,5485 ,0,0,0}, {12592,12264,13622 ,726,5468,5468 ,0,0,0}, - {12592,13622,12611 ,726,5468,5471 ,0,0,0}, {13886,13887,12284 ,5470,5470,5468 ,0,0,0}, - {12286,13630,13629 ,5483,5475,5475 ,0,0,0}, {13888,12270,12269 ,5468,726,5468 ,0,0,0}, - {13889,12244,13890 ,5469,5468,5471 ,0,0,0}, {12358,13726,12360 ,726,726,5470 ,0,0,0}, - {13891,13892,12320 ,5471,5471,5471 ,0,0,0}, {13893,12408,13894 ,726,726,5471 ,0,0,0}, - {13895,13896,13897 ,5471,5470,5471 ,0,0,0}, {12404,12405,13898 ,726,726,726 ,0,0,0}, - {12348,13765,13588 ,726,5471,726 ,0,0,0}, {13778,13724,13899 ,726,726,726 ,0,0,0}, - {12644,13900,12516 ,726,5468,5469 ,0,0,0}, {12541,13901,12542 ,726,726,5468 ,0,0,0}, - {12510,13594,12512 ,726,726,726 ,0,0,0}, {13689,12509,12506 ,726,5471,5471 ,0,0,0}, - {12470,13590,13589 ,726,726,5471 ,0,0,0}, {13591,13590,13691 ,726,726,5470 ,0,0,0}, - {13700,13713,13701 ,726,726,726 ,0,0,0}, {13715,13902,13692 ,5471,726,5471 ,0,0,0}, - {13693,13692,13902 ,5471,5471,726 ,0,0,0}, {13714,13713,13700 ,726,726,726 ,0,0,0}, - {13714,13902,13715 ,726,726,5471 ,0,0,0}, {13701,13696,13695 ,726,5470,726 ,0,0,0}, - {13597,13599,13694 ,5470,726,726 ,0,0,0}, {13698,13598,13699 ,726,726,5470 ,0,0,0}, - {13598,13597,13699 ,726,5470,5470 ,0,0,0}, {13705,13717,13716 ,726,726,726 ,0,0,0}, - {13697,13706,13903 ,726,726,5471 ,0,0,0}, {13903,13698,13697 ,5471,726,726 ,0,0,0}, - {13705,13704,13717 ,726,5470,726 ,0,0,0}, {13706,13705,13903 ,726,726,5471 ,0,0,0}, - {13702,13716,13703 ,5470,726,726 ,0,0,0}, {13684,13707,12590 ,726,726,726 ,0,0,0}, - {12576,12574,13602 ,726,726,5469 ,0,0,0}, {13685,12586,13904 ,5470,726,5470 ,0,0,0}, - {12585,13682,13904 ,726,5469,5470 ,0,0,0}, {13904,12586,12585 ,5470,726,726 ,0,0,0}, - {13681,12580,13650 ,5468,726,726 ,0,0,0}, {12580,13681,12582 ,726,5468,726 ,0,0,0}, - {12579,13650,12580 ,5471,726,726 ,0,0,0}, {13722,12573,12548 ,726,5471,5471 ,0,0,0}, - {12548,12547,13721 ,5471,5471,5470 ,0,0,0}, {13596,12573,13722 ,5469,5471,726 ,0,0,0}, - {13905,13906,12550 ,5470,5470,726 ,0,0,0}, {13878,12553,12556 ,726,5470,726 ,0,0,0}, - {13906,12547,12550 ,5470,5471,726 ,0,0,0}, {12557,12562,13907 ,726,726,726 ,0,0,0}, - {12557,13908,12556 ,726,5470,726 ,0,0,0}, {13909,12562,12560 ,726,726,5470 ,0,0,0}, - {12449,12451,12188 ,726,726,726 ,0,0,0}, {12565,12446,12559 ,726,726,5471 ,0,0,0}, - {12462,13910,12465 ,726,726,5470 ,0,0,0}, {12536,13911,12538 ,726,5471,5471 ,0,0,0}, - {13912,12294,12297 ,5471,5470,726 ,0,0,0}, {13913,12167,13914 ,726,726,5470 ,0,0,0}, - {12484,12198,13915 ,5471,5470,5470 ,0,0,0}, {13916,13917,12480 ,726,5471,726 ,0,0,0}, - {12174,12527,12173 ,726,5471,726 ,0,0,0}, {12645,12644,12519 ,5468,726,5471 ,0,0,0}, - {12569,12447,12565 ,5470,5471,726 ,0,0,0}, {12460,12459,13918 ,726,726,726 ,0,0,0}, - {12187,12161,12559 ,5470,5471,5471 ,0,0,0}, {13909,13907,12562 ,726,726,726 ,0,0,0}, - {13907,13908,12557 ,726,5470,726 ,0,0,0}, {13908,13879,12556 ,5470,5471,726 ,0,0,0}, - {12553,13905,12550 ,5470,5470,726 ,0,0,0}, {13905,12553,13878 ,5470,5470,726 ,0,0,0}, - {13603,12546,12544 ,5468,5469,726 ,0,0,0}, {13906,13721,12547 ,5470,5470,5471 ,0,0,0}, - {12574,12546,13602 ,726,5469,5469 ,0,0,0}, {13595,12574,12573 ,5468,726,5471 ,0,0,0}, - {13595,12546,12574 ,5468,5469,726 ,0,0,0}, {12544,12542,13901 ,726,5468,726 ,0,0,0}, - {12544,13901,13603 ,726,726,5468 ,0,0,0}, {12541,13873,13901 ,726,726,726 ,0,0,0}, - {12538,13911,13873 ,5471,5471,726 ,0,0,0}, {12535,13900,13833 ,5469,5468,5468 ,0,0,0}, - {12536,13833,13911 ,726,5468,5471 ,0,0,0}, {12516,12515,12644 ,5469,5468,726 ,0,0,0}, - {12535,12516,13900 ,5469,5469,5468 ,0,0,0}, {12519,12523,12645 ,5471,726,5468 ,0,0,0}, - {12515,12519,12644 ,5468,5471,726 ,0,0,0}, {12523,12522,12641 ,726,5471,5469 ,0,0,0}, - {12174,12177,12525 ,726,726,5469 ,0,0,0}, {12173,12527,12529 ,726,5471,5470 ,0,0,0}, - {13880,13914,12168 ,5471,5470,5471 ,0,0,0}, {12171,12173,12529 ,5471,726,5470 ,0,0,0}, - {13913,13909,12165 ,726,726,5470 ,0,0,0}, {12568,13919,12440 ,5470,5470,726 ,0,0,0}, - {12465,13920,12466 ,5470,5470,5470 ,0,0,0}, {13877,12438,12436 ,726,5489,726 ,0,0,0}, - {13763,12433,12430 ,726,726,726 ,0,0,0}, {13921,13777,13724 ,5489,5488,726 ,0,0,0}, - {13777,13921,13739 ,5488,5489,5489 ,0,0,0}, {13740,13718,13741 ,726,726,726 ,0,0,0}, - {13720,13922,13737 ,5489,726,726 ,0,0,0}, {13738,13737,13922 ,726,726,726 ,0,0,0}, - {13719,13718,13740 ,5488,726,726 ,0,0,0}, {13719,13922,13720 ,5488,726,5489 ,0,0,0}, - {13741,13585,13742 ,726,726,726 ,0,0,0}, {13586,13730,13587 ,726,726,726 ,0,0,0}, - {13746,13728,13744 ,5489,726,726 ,0,0,0}, {13728,13586,13744 ,726,726,726 ,0,0,0}, - {13732,13749,13733 ,726,726,726 ,0,0,0}, {13747,13746,13745 ,726,5489,726 ,0,0,0}, - {13749,13748,13733 ,726,726,726 ,0,0,0}, {13748,13747,13750 ,726,726,5488 ,0,0,0}, - {13732,13731,13594 ,726,5489,726 ,0,0,0}, {13753,13594,13751 ,726,726,5489 ,0,0,0}, - {12500,12498,13589 ,5471,726,5471 ,0,0,0}, {13594,13764,13592 ,726,726,726 ,0,0,0}, - {12509,13689,13764 ,5471,726,726 ,0,0,0}, {13764,12510,12509 ,726,726,5471 ,0,0,0}, - {13688,12504,13727 ,5471,726,726 ,0,0,0}, {12504,13688,12506 ,726,5471,5471 ,0,0,0}, - {12503,13727,12504 ,726,726,726 ,0,0,0}, {13923,12472,13760 ,5471,726,726 ,0,0,0}, - {12472,12471,13761 ,726,726,726 ,0,0,0}, {12497,12472,13923 ,726,726,5471 ,0,0,0}, - {13924,13925,12474 ,726,726,726 ,0,0,0}, {13917,12477,12480 ,5471,726,726 ,0,0,0}, - {13925,12471,12474 ,726,726,726 ,0,0,0}, {12481,12486,13926 ,726,726,726 ,0,0,0}, - {12481,13927,12480 ,726,5471,726 ,0,0,0}, {13915,12486,12484 ,5470,726,5471 ,0,0,0}, - {12203,12370,12373 ,5471,5471,726 ,0,0,0}, {12489,12370,12483 ,726,5471,726 ,0,0,0}, - {13928,12198,12197 ,5471,5470,726 ,0,0,0}, {12462,12460,13929 ,726,726,726 ,0,0,0}, - {12203,12200,12483 ,5471,726,726 ,0,0,0}, {12384,13930,12386 ,726,5470,726 ,0,0,0}, - {12291,12417,12416 ,5470,726,726 ,0,0,0}, {12404,13931,12401 ,726,726,5471 ,0,0,0}, - {12451,12191,12188 ,726,726,726 ,0,0,0}, {12569,12568,12443 ,5470,5470,726 ,0,0,0}, - {12493,12371,12489 ,5471,726,726 ,0,0,0}, {13893,12410,12408 ,726,726,726 ,0,0,0}, - {12483,12200,12484 ,726,726,5471 ,0,0,0}, {13915,13926,12486 ,5470,726,726 ,0,0,0}, - {13926,13927,12481 ,726,5471,726 ,0,0,0}, {13927,13916,12480 ,5471,726,726 ,0,0,0}, - {12477,13924,12474 ,726,726,726 ,0,0,0}, {13924,12477,13917 ,726,726,5471 ,0,0,0}, - {13932,12470,12468 ,5470,726,726 ,0,0,0}, {13925,13761,12471 ,726,726,726 ,0,0,0}, - {12498,12470,13589 ,726,726,5471 ,0,0,0}, {12470,12498,13734 ,726,726,5471 ,0,0,0}, - {13923,13734,12497 ,5471,5471,726 ,0,0,0}, {12470,13932,13590 ,726,5470,726 ,0,0,0}, - {12468,12466,13920 ,726,5470,5470 ,0,0,0}, {12468,13920,13932 ,726,5470,5470 ,0,0,0}, - {12465,13910,13920 ,5470,726,5470 ,0,0,0}, {12462,13929,13910 ,726,726,726 ,0,0,0}, - {12459,13919,13918 ,726,5470,726 ,0,0,0}, {12460,13918,13929 ,726,726,726 ,0,0,0}, - {12440,12439,12568 ,726,5470,5470 ,0,0,0}, {12459,12440,13919 ,726,726,5470 ,0,0,0}, - {12443,12447,12569 ,726,5471,5470 ,0,0,0}, {12439,12443,12568 ,5470,726,5470 ,0,0,0}, - {12447,12446,12565 ,5471,726,726 ,0,0,0}, {12188,12187,12449 ,726,5470,726 ,0,0,0}, - {12191,12453,12192 ,726,726,5471 ,0,0,0}, {12194,12192,13874 ,726,5471,726 ,0,0,0}, - {12451,12453,12191 ,726,726,726 ,0,0,0}, {13915,12198,13928 ,5470,5470,5471 ,0,0,0}, - {12434,13876,12436 ,5488,726,726 ,0,0,0}, {12636,12181,13838 ,5468,5470,726 ,0,0,0}, - {12360,13725,12362 ,5470,726,5470 ,0,0,0}, {13781,12357,12354 ,726,726,726 ,0,0,0}, - {13765,13933,13766 ,5471,726,726 ,0,0,0}, {13756,13766,13757 ,5471,726,726 ,0,0,0}, - {13802,13934,13769 ,726,5471,5471 ,0,0,0}, {13755,13769,13934 ,726,5471,5471 ,0,0,0}, - {13774,13832,13802 ,726,726,726 ,0,0,0}, {13832,13934,13802 ,726,5471,726 ,0,0,0}, - {13785,13795,13774 ,726,726,726 ,0,0,0}, {13935,13775,13774 ,726,726,726 ,0,0,0}, - {13772,13774,13787 ,726,726,726 ,0,0,0}, {13788,13787,13774 ,5488,726,726 ,0,0,0}, - {13830,13791,13831 ,5489,726,726 ,0,0,0}, {13790,13787,13786 ,726,726,726 ,0,0,0}, - {13791,13792,13831 ,726,726,726 ,0,0,0}, {13792,13790,13789 ,726,726,726 ,0,0,0}, - {13771,13830,13793 ,726,5489,726 ,0,0,0}, {13877,13770,12438 ,726,726,5489 ,0,0,0}, - {12422,12421,13724 ,726,5471,726 ,0,0,0}, {12433,13936,12434 ,726,726,5488 ,0,0,0}, - {13876,12434,13936 ,726,5488,726 ,0,0,0}, {13762,12428,13778 ,726,726,726 ,0,0,0}, - {13763,13936,12433 ,726,726,726 ,0,0,0}, {12428,13762,12430 ,726,726,726 ,0,0,0}, - {12427,13778,12428 ,726,726,726 ,0,0,0}, {13834,13724,13937 ,5470,726,5471 ,0,0,0}, - {13937,12396,13837 ,5471,726,5471 ,0,0,0}, {13937,13724,12396 ,5471,726,726 ,0,0,0}, - {12398,13938,12395 ,5471,726,726 ,0,0,0}, {12404,13939,13931 ,726,726,726 ,0,0,0}, - {12398,13940,13938 ,5471,726,726 ,0,0,0}, {13941,12389,12386 ,5471,726,726 ,0,0,0}, - {12389,13942,12390 ,726,726,726 ,0,0,0}, {13943,12384,12383 ,726,726,5471 ,0,0,0}, - {12492,13944,12364 ,5471,5471,5471 ,0,0,0}, {12367,12493,12492 ,726,5471,5471 ,0,0,0}, - {12203,12483,12370 ,5471,726,5471 ,0,0,0}, {13945,13946,13947 ,5470,726,726 ,0,0,0}, - {13948,12210,12380 ,726,5470,5471 ,0,0,0}, {12416,13949,12288 ,726,726,726 ,0,0,0}, - {13950,12314,12313 ,5471,5470,5471 ,0,0,0}, {12313,12310,13951 ,5471,726,726 ,0,0,0}, - {12413,12294,12407 ,726,5470,726 ,0,0,0}, {12206,12373,12375 ,5471,726,726 ,0,0,0}, - {12417,12295,12413 ,726,5471,726 ,0,0,0}, {12307,13952,12308 ,726,726,5471 ,0,0,0}, - {12407,13953,12408 ,726,726,726 ,0,0,0}, {13893,13690,12410 ,726,5470,726 ,0,0,0}, - {13690,13898,12405 ,5470,726,726 ,0,0,0}, {13898,13939,12404 ,726,726,726 ,0,0,0}, - {12401,13940,12398 ,5471,726,5471 ,0,0,0}, {13940,12401,13931 ,726,5471,726 ,0,0,0}, - {13942,13954,12392 ,726,726,726 ,0,0,0}, {12392,13954,13724 ,726,726,726 ,0,0,0}, - {13938,13837,12395 ,726,5471,726 ,0,0,0}, {12424,12422,13724 ,726,726,726 ,0,0,0}, - {13724,12421,12396 ,726,5471,726 ,0,0,0}, {12394,13724,13835 ,5471,726,5471 ,0,0,0}, - {13954,13921,13724 ,726,5489,726 ,0,0,0}, {12392,12390,13942 ,726,726,726 ,0,0,0}, - {12389,13941,13942 ,726,5471,726 ,0,0,0}, {12386,13930,13941 ,726,5470,5471 ,0,0,0}, - {12383,13944,13943 ,5471,5471,726 ,0,0,0}, {12384,13943,13930 ,726,726,5470 ,0,0,0}, - {12364,12363,12492 ,5471,726,5471 ,0,0,0}, {12383,12364,13944 ,5471,5471,5471 ,0,0,0}, - {12367,12371,12493 ,726,726,5471 ,0,0,0}, {12363,12367,12492 ,726,726,5471 ,0,0,0}, - {12371,12370,12489 ,726,5471,726 ,0,0,0}, {12206,12203,12373 ,5471,5471,726 ,0,0,0}, - {12206,12375,12209 ,5471,726,726 ,0,0,0}, {12377,12210,12209 ,726,5470,726 ,0,0,0}, - {12377,12209,12375 ,726,726,726 ,0,0,0}, {12377,12380,12210 ,726,5471,5470 ,0,0,0}, - {13955,12253,12258 ,5468,5469,5470 ,0,0,0}, {13811,13823,13818 ,5468,5469,726 ,0,0,0}, - {12598,12261,12599 ,5468,5471,5469 ,0,0,0}, {12281,12278,13811 ,5469,5471,5468 ,0,0,0}, - {12242,13824,13823 ,5469,726,5469 ,0,0,0}, {13822,13824,13816 ,726,726,726 ,0,0,0}, - {13856,13853,13855 ,726,5471,726 ,0,0,0}, {13852,13956,13814 ,5471,5468,5471 ,0,0,0}, - {13815,13814,13956 ,5468,5471,5468 ,0,0,0}, {13854,13853,13856 ,5468,5471,726 ,0,0,0}, - {13854,13956,13852 ,5468,5468,5471 ,0,0,0}, {13855,13820,13819 ,726,5470,726 ,0,0,0}, - {13827,13826,13821 ,726,5469,5469 ,0,0,0}, {13846,13825,13847 ,5470,5471,726 ,0,0,0}, - {13825,13827,13847 ,5471,726,726 ,0,0,0}, {13843,13839,13841 ,726,726,5471 ,0,0,0}, - {13845,13844,13957 ,726,5470,726 ,0,0,0}, {13957,13846,13845 ,726,5470,726 ,0,0,0}, - {13843,13842,13839 ,726,5471,726 ,0,0,0}, {13844,13843,13957 ,5470,726,726 ,0,0,0}, - {13810,13841,13840 ,726,5471,5470 ,0,0,0}, {13725,13809,12362 ,726,726,5470 ,0,0,0}, - {12348,12346,13765 ,726,5470,5471 ,0,0,0}, {12357,13958,12358 ,726,726,726 ,0,0,0}, - {13726,12358,13958 ,726,726,726 ,0,0,0}, {13780,12352,13836 ,5471,5470,726 ,0,0,0}, - {13781,13958,12357 ,726,726,726 ,0,0,0}, {12352,13780,12354 ,5470,5471,726 ,0,0,0}, - {12351,13836,12352 ,5470,726,5470 ,0,0,0}, {13892,12345,12320 ,5471,5471,5471 ,0,0,0}, - {12320,12319,13891 ,5471,726,5471 ,0,0,0}, {13806,12345,13892 ,5471,5471,5471 ,0,0,0}, - {13959,13960,12322 ,5471,726,726 ,0,0,0}, {13767,12325,12328 ,726,5470,5470 ,0,0,0}, - {13960,12319,12322 ,726,726,726 ,0,0,0}, {12329,12334,13961 ,5470,726,726 ,0,0,0}, - {12329,13962,12328 ,5470,726,5470 ,0,0,0}, {13963,12334,12332 ,726,726,726 ,0,0,0}, - {12221,12223,13964 ,726,5471,5471 ,0,0,0}, {12308,13965,12310 ,5471,726,726 ,0,0,0}, - {13966,13967,13968 ,5471,726,726 ,0,0,0}, {12256,13966,13969 ,5471,5471,5471 ,0,0,0}, - {13838,12181,13970 ,726,5470,5469 ,0,0,0}, {12598,12601,13971 ,5468,5468,5470 ,0,0,0}, - {12237,13972,12238 ,726,726,5471 ,0,0,0}, {12256,13969,12258 ,5471,5471,5470 ,0,0,0}, - {12337,12218,12331 ,726,5470,5470 ,0,0,0}, {12299,13973,13974 ,5470,5471,726 ,0,0,0}, - {12341,12219,12337 ,726,5471,726 ,0,0,0}, {13975,13964,12223 ,5471,5471,5471 ,0,0,0}, - {13976,13977,12331 ,726,5471,5470 ,0,0,0}, {13963,13961,12334 ,726,726,726 ,0,0,0}, - {13961,13962,12329 ,726,726,5470 ,0,0,0}, {13962,13768,12328 ,726,726,5470 ,0,0,0}, - {12325,13959,12322 ,5470,5471,726 ,0,0,0}, {13959,12325,13767 ,5471,5470,726 ,0,0,0}, - {12316,13950,13933 ,5471,5471,726 ,0,0,0}, {13933,12318,12316 ,726,726,5471 ,0,0,0}, - {13960,13891,12319 ,726,5471,726 ,0,0,0}, {12346,12318,13765 ,5470,726,5471 ,0,0,0}, - {13805,12346,12345 ,726,5470,5471 ,0,0,0}, {13805,12318,12346 ,726,726,5470 ,0,0,0}, - {13765,12318,13933 ,5471,726,726 ,0,0,0}, {12316,12314,13950 ,5471,5470,5471 ,0,0,0}, - {12313,13951,13950 ,5471,726,5471 ,0,0,0}, {12310,13965,13951 ,726,726,726 ,0,0,0}, - {12307,13949,13952 ,726,726,726 ,0,0,0}, {12308,13952,13965 ,5471,726,726 ,0,0,0}, - {12288,12287,12416 ,726,5471,726 ,0,0,0}, {12307,12288,13949 ,726,726,726 ,0,0,0}, - {12291,12295,12417 ,5470,5471,726 ,0,0,0}, {12287,12291,12416 ,5471,5470,726 ,0,0,0}, - {12295,12294,12413 ,5471,5470,726 ,0,0,0}, {13974,13912,12297 ,726,5471,726 ,0,0,0}, - {12407,12294,13912 ,726,5470,5471 ,0,0,0}, {12304,13978,13979 ,726,726,726 ,0,0,0}, - {13973,12301,13979 ,5471,726,726 ,0,0,0}, {13980,13981,13982 ,5470,5470,5471 ,0,0,0}, - {12284,13887,12286 ,5468,5470,5483 ,0,0,0}, {12592,12591,12264 ,726,5468,5468 ,0,0,0}, - {12284,12282,13886 ,5468,5469,5470 ,0,0,0}, {12620,13584,13883 ,726,5468,5468 ,0,0,0}, - {12617,13885,13584 ,5469,726,5468 ,0,0,0}, {13883,13884,13604 ,5468,5468,5469 ,0,0,0}, - {13613,13884,13614 ,5476,5468,5471 ,0,0,0}, {13641,13644,13639 ,5468,5468,5475 ,0,0,0}, - {13643,13983,13869 ,5483,726,5468 ,0,0,0}, {13612,13869,13983 ,5475,5468,726 ,0,0,0}, - {13642,13644,13641 ,5486,5468,5468 ,0,0,0}, {13642,13983,13643 ,5486,726,5483 ,0,0,0}, - {13639,13616,13640 ,5475,5478,5485 ,0,0,0}, {13617,13628,13615 ,5469,5468,5477 ,0,0,0}, - {13621,13627,13619 ,726,726,5471 ,0,0,0}, {13627,13617,13619 ,726,5469,5471 ,0,0,0}, - {13871,13625,13872 ,5472,5480,5482 ,0,0,0}, {13626,13621,13620 ,5481,726,5469 ,0,0,0}, - {13625,13624,13872 ,5480,726,5482 ,0,0,0}, {13624,13626,13636 ,726,5481,5475 ,0,0,0}, - {13629,13871,13632 ,5475,5472,5468 ,0,0,0}, {13887,13630,12286 ,5470,5475,5483 ,0,0,0}, - {13811,12270,13888 ,5468,726,5468 ,0,0,0}, {12281,13813,12282 ,5469,5469,5469 ,0,0,0}, - {13886,12282,13813 ,5470,5469,5469 ,0,0,0}, {13984,13812,13811 ,5468,726,5468 ,0,0,0}, - {13813,12281,13811 ,5469,5469,5468 ,0,0,0}, {13811,12278,12276 ,5468,5471,5470 ,0,0,0}, - {13811,12275,12272 ,5468,5469,5471 ,0,0,0}, {13985,12244,13889 ,5469,5468,5469 ,0,0,0}, - {12244,12243,13890 ,5468,5471,5471 ,0,0,0}, {12269,12244,13985 ,5468,5468,5469 ,0,0,0}, - {13986,13987,12246 ,5470,5471,5468 ,0,0,0}, {13807,12249,12252 ,5470,726,5468 ,0,0,0}, - {13987,12243,12246 ,5471,5471,5468 ,0,0,0}, {12601,12603,13988 ,5468,5468,5468 ,0,0,0}, - {12215,12341,12340 ,5471,726,726 ,0,0,0}, {12253,13989,12252 ,5469,5469,5468 ,0,0,0}, - {13990,12232,12231 ,726,5471,726 ,0,0,0}, {13991,12237,12234 ,726,726,5470 ,0,0,0}, - {13992,12212,12340 ,726,5470,726 ,0,0,0}, {13993,12234,12232 ,726,5470,5471 ,0,0,0}, - {12598,12255,12261 ,5468,5469,5471 ,0,0,0}, {12601,13988,13971 ,5468,5468,5470 ,0,0,0}, - {12261,12265,12599 ,5471,726,5469 ,0,0,0}, {12264,12595,12265 ,5468,5468,726 ,0,0,0}, - {12599,12265,12595 ,5469,726,5468 ,0,0,0}, {12180,13882,13970 ,5469,5469,5469 ,0,0,0}, - {12605,12185,13994 ,5471,5470,726 ,0,0,0}, {12185,13881,12183 ,5470,5469,726 ,0,0,0}, - {12255,13995,12256 ,5469,5471,5471 ,0,0,0}, {13969,13955,12258 ,5471,5468,5470 ,0,0,0}, - {13955,13989,12253 ,5468,5469,5469 ,0,0,0}, {13989,13808,12252 ,5469,5468,5468 ,0,0,0}, - {12249,13986,12246 ,726,5470,5468 ,0,0,0}, {13986,12249,13807 ,5470,726,5470 ,0,0,0}, - {12240,13972,13996 ,726,726,5471 ,0,0,0}, {13996,12242,12240 ,5471,5469,726 ,0,0,0}, - {13987,13890,12243 ,5471,5471,5471 ,0,0,0}, {12242,13823,13811 ,5469,5469,5468 ,0,0,0}, - {13811,13888,12242 ,5468,5468,5469 ,0,0,0}, {13985,13888,12269 ,5469,5468,5468 ,0,0,0}, - {12242,13996,13824 ,5469,5471,726 ,0,0,0}, {12240,12238,13972 ,726,5471,726 ,0,0,0}, - {12237,13991,13972 ,726,726,726 ,0,0,0}, {12234,13993,13991 ,5470,726,726 ,0,0,0}, - {12231,13992,13990 ,726,726,726 ,0,0,0}, {12232,13990,13993 ,5471,726,726 ,0,0,0}, - {12212,12211,12340 ,5470,726,726 ,0,0,0}, {12231,12212,13992 ,726,5470,726 ,0,0,0}, - {12215,12219,12341 ,5471,5471,726 ,0,0,0}, {12211,12215,12340 ,726,5471,726 ,0,0,0}, - {12219,12218,12337 ,5471,5470,726 ,0,0,0}, {13964,13976,12221 ,5471,726,726 ,0,0,0}, - {13975,12225,13997 ,5471,726,726 ,0,0,0}, {13895,13997,13896 ,5471,726,5470 ,0,0,0}, - {12223,12225,13975 ,5471,726,5471 ,0,0,0}, {13969,13966,13968 ,5471,5471,726 ,0,0,0}, - {13963,12332,13998 ,726,726,5471 ,0,0,0}, {13909,12560,12165 ,726,5470,5470 ,0,0,0}, - {13963,13998,13980 ,726,5471,5470 ,0,0,0}, {12200,12198,12484 ,726,5470,5471 ,0,0,0}, - {12194,13875,12197 ,726,5470,726 ,0,0,0}, {13928,12197,13875 ,5471,726,5470 ,0,0,0}, - {12560,12559,12161 ,5470,5471,5471 ,0,0,0}, {12456,12192,12453 ,726,5471,726 ,0,0,0}, - {12456,13874,12192 ,726,726,5471 ,0,0,0}, {12187,12559,12446 ,5470,5471,726 ,0,0,0}, - {12446,12449,12187 ,726,726,5470 ,0,0,0}, {12560,12161,12165 ,5470,5471,5470 ,0,0,0}, - {13913,12165,12167 ,726,5470,726 ,0,0,0}, {12179,12635,12177 ,5471,5469,726 ,0,0,0}, - {13914,12167,12168 ,5470,726,5471 ,0,0,0}, {12532,12171,12529 ,726,5471,5470 ,0,0,0}, - {12532,13880,12171 ,726,5471,5471 ,0,0,0}, {12635,12522,12177 ,5469,5471,726 ,0,0,0}, - {12522,12525,12177 ,5471,5469,726 ,0,0,0}, {12179,12181,12636 ,5471,5470,5468 ,0,0,0}, - {13970,12181,12180 ,5469,5470,5469 ,0,0,0}, {13995,12255,13971 ,5471,5469,5470 ,0,0,0}, - {13882,12180,12183 ,5469,5469,726 ,0,0,0}, {12608,12185,12605 ,5469,5470,5471 ,0,0,0}, - {12608,13881,12185 ,5469,5469,5470 ,0,0,0}, {13971,12255,12598 ,5470,5469,5468 ,0,0,0}, - {13994,13988,12603 ,726,5468,5468 ,0,0,0}, {13994,12603,12605 ,726,5468,5471 ,0,0,0}, - {13995,13966,12256 ,5471,5471,5471 ,0,0,0}, {13895,13897,13967 ,5471,5471,726 ,0,0,0}, - {13968,13967,13897 ,726,726,5471 ,0,0,0}, {12332,12331,13977 ,726,5470,5471 ,0,0,0}, - {12228,13997,12225 ,726,726,726 ,0,0,0}, {12228,13896,13997 ,726,5470,726 ,0,0,0}, - {13976,12331,12218 ,726,5470,5470 ,0,0,0}, {12218,12221,13976 ,5470,726,726 ,0,0,0}, - {12332,13977,13998 ,726,5471,5471 ,0,0,0}, {13982,13981,13999 ,5471,5470,726 ,0,0,0}, - {13980,13998,13981 ,5470,5471,5470 ,0,0,0}, {13999,13979,13978 ,726,726,726 ,0,0,0}, - {13978,13982,13999 ,726,5471,726 ,0,0,0}, {13979,12301,12304 ,726,726,726 ,0,0,0}, - {13973,12299,12301 ,5471,5470,726 ,0,0,0}, {13974,12297,12299 ,726,726,5470 ,0,0,0}, - {12407,13912,13953 ,726,5471,726 ,0,0,0}, {13894,14000,13893 ,5471,5471,726 ,0,0,0}, - {12408,13953,13894 ,726,726,5471 ,0,0,0}, {13946,14000,13947 ,726,5471,726 ,0,0,0}, - {13894,13947,14000 ,5471,726,5471 ,0,0,0}, {13946,13945,13948 ,726,5470,726 ,0,0,0}, - {12210,13948,13945 ,5470,726,5470 ,0,0,0}, {13984,13811,13817 ,5468,5468,5468 ,0,0,0}, - {12276,12275,13811 ,5470,5469,5468 ,0,0,0}, {13774,13794,13788 ,726,726,5488 ,0,0,0}, - {13783,13935,13774 ,5488,726,726 ,0,0,0}, {13724,12394,12392 ,726,5471,726 ,0,0,0}, - {13899,13724,13779 ,726,726,726 ,0,0,0}, {13865,13864,13862 ,5469,5470,5468 ,0,0,0}, - {13865,13607,13863 ,5469,5468,5469 ,0,0,0}, {13751,13594,13593 ,5489,726,726 ,0,0,0}, - {12514,12512,13594 ,726,726,726 ,0,0,0}, {14001,14002,14003 ,5490,5491,5492 ,0,0,0}, - {14004,14005,14006 ,5493,5494,5495 ,0,0,0}, {14007,14005,14008 ,5496,5494,5497 ,0,0,0}, - {14009,14010,14011 ,5498,5499,5500 ,0,0,0}, {14012,14013,14014 ,5501,5502,5503 ,0,0,0}, - {14015,14016,14017 ,5504,5505,5506 ,0,0,0}, {14018,14019,14020 ,5507,5508,5509 ,0,0,0}, - {13631,13635,14015 ,5510,5511,5504 ,0,0,0}, {14021,14022,14023 ,5512,5513,5514 ,0,0,0}, - {14012,14017,14016 ,5501,5506,5505 ,0,0,0}, {14024,14025,14022 ,5515,5516,5513 ,0,0,0}, - {14026,14024,14022 ,5517,5515,5513 ,0,0,0}, {14026,14027,14024 ,5517,5518,5515 ,0,0,0}, - {14027,14026,14028 ,5518,5517,5519 ,0,0,0}, {14029,14025,14030 ,5520,5516,5521 ,0,0,0}, - {14031,14032,14033 ,5522,5523,5524 ,0,0,0}, {14022,14025,14029 ,5513,5516,5520 ,0,0,0}, - {14033,14032,14028 ,5524,5523,5519 ,0,0,0}, {14034,14031,14035 ,5525,5522,5526 ,0,0,0}, - {14036,14037,14038 ,5527,5528,5529 ,0,0,0}, {14036,14029,14030 ,5527,5520,5521 ,0,0,0}, - {14039,14040,14041 ,5530,5531,5532 ,0,0,0}, {14036,14030,14037 ,5527,5521,5528 ,0,0,0}, - {14037,14039,14038 ,5528,5530,5529 ,0,0,0}, {14042,14043,14041 ,5533,5534,5532 ,0,0,0}, - {14019,14044,14020 ,5508,5535,5509 ,0,0,0}, {14041,14040,14042 ,5532,5531,5533 ,0,0,0}, - {14045,14004,14046 ,5536,5493,5537 ,0,0,0}, {14040,14047,14042 ,5531,5538,5533 ,0,0,0}, - {14019,14023,14044 ,5508,5514,5535 ,0,0,0}, {14048,14023,14029 ,5539,5514,5520 ,0,0,0}, - {14049,14050,14051 ,5540,5541,5542 ,0,0,0}, {14052,14049,14053 ,5543,5540,5544 ,0,0,0}, - {13610,13627,14002 ,5545,5546,5491 ,0,0,0}, {14054,14055,14056 ,5547,5548,5549 ,0,0,0}, - {13610,14001,13611 ,5545,5490,726 ,0,0,0}, {14057,13611,14001 ,5550,726,5490 ,0,0,0}, - {14058,14043,14059 ,5551,5534,5552 ,0,0,0}, {14039,14041,14038 ,5530,5532,5529 ,0,0,0}, - {14041,14043,14058 ,5532,5534,5551 ,0,0,0}, {14059,14060,14058 ,5552,5553,5551 ,0,0,0}, - {14061,14038,14058 ,5554,5529,5551 ,0,0,0}, {14023,14048,14044 ,5514,5539,5535 ,0,0,0}, - {14061,14048,14036 ,5554,5539,5527 ,0,0,0}, {14026,14062,14028 ,5517,5555,5519 ,0,0,0}, - {14036,14048,14029 ,5527,5539,5520 ,0,0,0}, {14063,14064,14033 ,5556,5557,5524 ,0,0,0}, - {14022,14029,14023 ,5513,5520,5514 ,0,0,0}, {14062,14026,14021 ,5555,5517,5512 ,0,0,0}, - {14031,14033,14035 ,5522,5524,5526 ,0,0,0}, {14027,14028,14032 ,5518,5519,5523 ,0,0,0}, - {14028,14062,14063 ,5519,5555,5556 ,0,0,0}, {14065,14035,14033 ,5558,5526,5524 ,0,0,0}, - {14041,14058,14038 ,5532,5551,5529 ,0,0,0}, {14066,14060,14059 ,5559,5553,5552 ,0,0,0}, - {14066,14053,14060 ,5559,5544,5553 ,0,0,0}, {14038,14061,14036 ,5529,5554,5527 ,0,0,0}, - {14060,14067,14061 ,5553,5560,5554 ,0,0,0}, {14019,14008,14021 ,5508,5497,5512 ,0,0,0}, - {14067,14044,14048 ,5560,5535,5539 ,0,0,0}, {14004,14064,14063 ,5493,5557,5556 ,0,0,0}, - {14045,14064,14004 ,5536,5557,5493 ,0,0,0}, {14022,14021,14026 ,5513,5512,5517 ,0,0,0}, - {14023,14019,14021 ,5514,5508,5512 ,0,0,0}, {14028,14063,14033 ,5519,5556,5524 ,0,0,0}, - {14008,14005,14062 ,5497,5494,5555 ,0,0,0}, {14033,14064,14065 ,5524,5557,5558 ,0,0,0}, - {14063,14005,14004 ,5556,5494,5493 ,0,0,0}, {14068,14065,14064 ,5561,5558,5557 ,0,0,0}, - {14058,14060,14061 ,5551,5553,5554 ,0,0,0}, {14052,14053,14066 ,5543,5544,5559 ,0,0,0}, - {14069,14051,14070 ,5562,5542,5563 ,0,0,0}, {14061,14067,14048 ,5554,5560,5539 ,0,0,0}, - {14071,14067,14053 ,5564,5560,5544 ,0,0,0}, {14008,14019,14018 ,5497,5508,5507 ,0,0,0}, - {14071,14020,14044 ,5564,5509,5535 ,0,0,0}, {14072,14046,14006 ,5565,5537,5495 ,0,0,0}, - {14062,14005,14063 ,5555,5494,5556 ,0,0,0}, {14021,14008,14062 ,5512,5497,5555 ,0,0,0}, - {14008,14018,14007 ,5497,5507,5496 ,0,0,0}, {14045,14046,14073 ,5536,5537,5566 ,0,0,0}, - {14007,14006,14005 ,5496,5495,5494 ,0,0,0}, {14064,14045,14068 ,5557,5536,5561 ,0,0,0}, - {14004,14006,14046 ,5493,5495,5537 ,0,0,0}, {14074,14068,14045 ,5567,5561,5536 ,0,0,0}, - {14060,14053,14067 ,5553,5544,5560 ,0,0,0}, {14050,14049,14052 ,5541,5540,5543 ,0,0,0}, - {14020,14075,14018 ,5509,5568,5507 ,0,0,0}, {14067,14071,14044 ,5560,5564,5535 ,0,0,0}, - {14076,14071,14049 ,5569,5564,5540 ,0,0,0}, {14018,14077,14007 ,5507,5570,5496 ,0,0,0}, - {14076,14075,14020 ,5569,5568,5509 ,0,0,0}, {14007,14078,14006 ,5496,5571,5495 ,0,0,0}, - {14077,14018,14075 ,5570,5507,5568 ,0,0,0}, {14046,14009,14073 ,5537,5498,5566 ,0,0,0}, - {14078,14007,14077 ,5571,5496,5570 ,0,0,0}, {14079,14073,14011 ,5572,5566,5500 ,0,0,0}, - {14072,14006,14078 ,5565,5495,5571 ,0,0,0}, {14045,14073,14074 ,5536,5566,5567 ,0,0,0}, - {14046,14072,14009 ,5537,5565,5498 ,0,0,0}, {14079,14074,14073 ,5572,5567,5566 ,0,0,0}, - {14053,14049,14071 ,5544,5540,5564 ,0,0,0}, {14070,14051,14050 ,5563,5542,5541 ,0,0,0}, - {14075,14055,14077 ,5568,5548,5570 ,0,0,0}, {14071,14076,14020 ,5564,5569,5509 ,0,0,0}, - {14051,14080,14076 ,5542,5573,5569 ,0,0,0}, {14077,14054,14078 ,5570,5547,5571 ,0,0,0}, - {14080,14055,14075 ,5573,5548,5568 ,0,0,0}, {14078,14081,14072 ,5571,5574,5565 ,0,0,0}, - {14055,14054,14077 ,5548,5547,5570 ,0,0,0}, {14082,14009,14072 ,5575,5498,5565 ,0,0,0}, - {14081,14078,14054 ,5574,5571,5547 ,0,0,0}, {14083,14011,14014 ,5576,5500,5503 ,0,0,0}, - {14072,14081,14082 ,5565,5574,5575 ,0,0,0}, {14082,14010,14009 ,5575,5499,5498 ,0,0,0}, - {14079,14011,14083 ,5572,5500,5576 ,0,0,0}, {14073,14009,14011 ,5566,5498,5500 ,0,0,0}, - {14049,14051,14076 ,5540,5542,5569 ,0,0,0}, {14084,14069,14070 ,5577,5562,5563 ,0,0,0}, - {14085,14081,14054 ,5578,5574,5547 ,0,0,0}, {14076,14080,14075 ,5569,5573,5568 ,0,0,0}, - {14069,14003,14080 ,5562,5492,5573 ,0,0,0}, {14086,14082,14081 ,5579,5575,5574 ,0,0,0}, - {14003,14056,14055 ,5492,5549,5548 ,0,0,0}, {14087,14010,14082 ,5580,5499,5575 ,0,0,0}, - {14056,14085,14054 ,5549,5578,5547 ,0,0,0}, {14017,14012,14088 ,5506,5501,5581 ,0,0,0}, - {14085,14086,14081 ,5578,5579,5574 ,0,0,0}, {14014,14010,14089 ,5503,5499,5582 ,0,0,0}, - {14087,14082,14086 ,5580,5575,5579 ,0,0,0}, {14089,14010,14087 ,5582,5499,5580 ,0,0,0}, - {14083,14014,14013 ,5576,5503,5502 ,0,0,0}, {14011,14010,14014 ,5500,5499,5503 ,0,0,0}, - {14051,14069,14080 ,5542,5562,5573 ,0,0,0}, {14001,14084,14057 ,5490,5577,5550 ,0,0,0}, - {14002,14090,14056 ,5491,5583,5549 ,0,0,0}, {14080,14003,14055 ,5573,5492,5548 ,0,0,0}, - {14002,14056,14003 ,5491,5549,5492 ,0,0,0}, {14090,14091,14085 ,5583,5584,5578 ,0,0,0}, - {14090,14085,14056 ,5583,5578,5549 ,0,0,0}, {14091,14092,14086 ,5584,5585,5579 ,0,0,0}, - {14091,14086,14085 ,5584,5579,5578 ,0,0,0}, {14092,14093,14087 ,5585,5586,5580 ,0,0,0}, - {14092,14087,14086 ,5585,5580,5579 ,0,0,0}, {14093,14088,14089 ,5586,5581,5582 ,0,0,0}, - {14089,14087,14093 ,5582,5580,5586 ,0,0,0}, {14088,14012,14089 ,5581,5501,5582 ,0,0,0}, - {14013,14012,14016 ,5502,5501,5505 ,0,0,0}, {14014,14089,14012 ,5503,5582,5501 ,0,0,0}, - {14084,14001,14069 ,5577,5490,5562 ,0,0,0}, {14003,14069,14001 ,5492,5562,5490 ,0,0,0}, - {14090,13627,13621 ,5583,5546,5587 ,0,0,0}, {13610,14002,14001 ,5545,5491,5490 ,0,0,0}, - {14091,13621,13626 ,5584,5587,5588 ,0,0,0}, {13627,14090,14002 ,5546,5583,5491 ,0,0,0}, - {14092,13626,13625 ,5585,5588,5589 ,0,0,0}, {13621,14091,14090 ,5587,5584,5583 ,0,0,0}, - {14093,13625,13871 ,5586,5589,5590 ,0,0,0}, {13626,14092,14091 ,5588,5585,5584 ,0,0,0}, - {14088,13871,13629 ,5581,5590,5591 ,0,0,0}, {13625,14093,14092 ,5589,5586,5585 ,0,0,0}, - {14017,13629,13631 ,5506,5591,5510 ,0,0,0}, {13871,14088,14093 ,5590,5581,5586 ,0,0,0}, - {13631,14015,14017 ,5510,5504,5506 ,0,0,0}, {13629,14017,14088 ,5591,5506,5581 ,0,0,0}, - {14094,14095,14096 ,5592,5593,5594 ,0,0,0}, {14097,14098,14099 ,5595,5596,5597 ,0,0,0}, - {14095,14100,14096 ,5593,5598,5594 ,0,0,0}, {14101,14099,14098 ,5599,5597,5596 ,0,0,0}, - {14102,14103,14104 ,5600,5601,5602 ,0,0,0}, {14105,14106,14103 ,5603,5604,5601 ,0,0,0}, - {14107,14108,14109 ,5605,5606,5607 ,0,0,0}, {14110,14106,14105 ,5608,5604,5603 ,0,0,0}, - {14106,14104,14103 ,5604,5602,5601 ,0,0,0}, {14111,14103,14097 ,5609,5601,5595 ,0,0,0}, - {14112,14113,14114 ,5610,5611,5612 ,0,0,0}, {14115,14116,14117 ,5613,5614,5615 ,0,0,0}, - {14118,14113,14119 ,5616,5611,5617 ,0,0,0}, {14120,14121,14094 ,5618,5619,5592 ,0,0,0}, - {14108,13857,13825 ,5606,5620,5621 ,0,0,0}, {14122,14123,14124 ,5622,5623,5624 ,0,0,0}, - {14125,13859,14107 ,5625,5626,5605 ,0,0,0}, {13857,14107,13859 ,5620,5605,5626 ,0,0,0}, - {14126,14127,14128 ,5627,5628,5629 ,0,0,0}, {14100,14129,14096 ,5598,5630,5594 ,0,0,0}, - {14130,14131,14132 ,5631,5632,5633 ,0,0,0}, {14133,14134,14135 ,5634,5635,5636 ,0,0,0}, - {14124,14127,14136 ,5624,5628,5637 ,0,0,0}, {14137,14138,14139 ,5638,5639,5640 ,0,0,0}, - {14140,14094,14141 ,5641,5592,5642 ,0,0,0}, {14138,14133,14139 ,5639,5634,5640 ,0,0,0}, - {14120,14101,14098 ,5618,5599,5596 ,0,0,0}, {13848,13851,14137 ,5643,5644,5638 ,0,0,0}, - {14101,14120,14142 ,5599,5618,5645 ,0,0,0}, {14142,14120,14140 ,5645,5618,5641 ,0,0,0}, - {14143,14144,14140 ,5646,5647,5641 ,0,0,0}, {14120,14098,14121 ,5618,5596,5619 ,0,0,0}, - {14143,14145,14146 ,5646,5648,5649 ,0,0,0}, {14146,14144,14143 ,5649,5647,5646 ,0,0,0}, - {14147,14148,14149 ,5650,5651,5652 ,0,0,0}, {14148,14147,14145 ,5651,5650,5648 ,0,0,0}, - {14105,14103,14111 ,5603,5601,5609 ,0,0,0}, {14150,14102,14104 ,5653,5600,5602 ,0,0,0}, - {14150,14151,14102 ,5653,5654,5600 ,0,0,0}, {14111,14097,14099 ,5609,5595,5597 ,0,0,0}, - {14152,14097,14102 ,5655,5595,5600 ,0,0,0}, {14094,14121,14095 ,5592,5619,5593 ,0,0,0}, - {14152,14121,14098 ,5655,5619,5596 ,0,0,0}, {14143,14153,14145 ,5646,5656,5648 ,0,0,0}, - {14154,14148,14155 ,5657,5651,5658 ,0,0,0}, {14142,14140,14144 ,5645,5641,5647 ,0,0,0}, - {14140,14120,14094 ,5641,5618,5592 ,0,0,0}, {14146,14145,14147 ,5649,5648,5650 ,0,0,0}, - {14141,14153,14143 ,5642,5656,5646 ,0,0,0}, {14148,14156,14149 ,5651,5659,5652 ,0,0,0}, - {14145,14153,14155 ,5648,5656,5658 ,0,0,0}, {14157,14156,14148 ,5660,5659,5651 ,0,0,0}, - {14103,14102,14097 ,5601,5600,5595 ,0,0,0}, {14158,14151,14150 ,5661,5654,5653 ,0,0,0}, - {14158,14114,14151 ,5661,5612,5654 ,0,0,0}, {14097,14152,14098 ,5595,5655,5596 ,0,0,0}, - {14151,14159,14152 ,5654,5662,5655 ,0,0,0}, {14096,14128,14141 ,5594,5629,5642 ,0,0,0}, - {14159,14095,14121 ,5662,5593,5619 ,0,0,0}, {14124,14154,14155 ,5624,5657,5658 ,0,0,0}, - {14123,14154,14124 ,5623,5657,5624 ,0,0,0}, {14140,14141,14143 ,5641,5642,5646 ,0,0,0}, - {14094,14096,14141 ,5592,5594,5642 ,0,0,0}, {14145,14155,14148 ,5648,5658,5651 ,0,0,0}, - {14128,14127,14153 ,5629,5628,5656 ,0,0,0}, {14148,14154,14157 ,5651,5657,5660 ,0,0,0}, - {14155,14127,14124 ,5658,5628,5624 ,0,0,0}, {14160,14157,14154 ,5663,5660,5657 ,0,0,0}, - {14102,14151,14152 ,5600,5654,5655 ,0,0,0}, {14112,14114,14158 ,5610,5612,5661 ,0,0,0}, - {14161,14118,14162 ,5664,5616,5665 ,0,0,0}, {14152,14159,14121 ,5655,5662,5619 ,0,0,0}, - {14163,14159,14114 ,5666,5662,5612 ,0,0,0}, {14128,14096,14129 ,5629,5594,5630 ,0,0,0}, - {14163,14100,14095 ,5666,5598,5593 ,0,0,0}, {14164,14122,14136 ,5667,5622,5637 ,0,0,0}, - {14153,14127,14155 ,5656,5628,5658 ,0,0,0}, {14141,14128,14153 ,5642,5629,5656 ,0,0,0}, - {14128,14129,14126 ,5629,5630,5627 ,0,0,0}, {14123,14122,14165 ,5623,5622,5668 ,0,0,0}, - {14126,14136,14127 ,5627,5637,5628 ,0,0,0}, {14154,14123,14160 ,5657,5623,5663 ,0,0,0}, - {14124,14136,14122 ,5624,5637,5622 ,0,0,0}, {14166,14160,14123 ,5669,5663,5623 ,0,0,0}, - {14151,14114,14159 ,5654,5612,5662 ,0,0,0}, {14119,14113,14112 ,5617,5611,5610 ,0,0,0}, - {14100,14167,14129 ,5598,5670,5630 ,0,0,0}, {14159,14163,14095 ,5662,5666,5593 ,0,0,0}, - {14168,14163,14113 ,5671,5666,5611 ,0,0,0}, {14129,14169,14126 ,5630,5672,5627 ,0,0,0}, - {14168,14167,14100 ,5671,5670,5598 ,0,0,0}, {14126,14170,14136 ,5627,5673,5637 ,0,0,0}, - {14169,14129,14167 ,5672,5630,5670 ,0,0,0}, {14122,14131,14165 ,5622,5632,5668 ,0,0,0}, - {14170,14126,14169 ,5673,5627,5672 ,0,0,0}, {14171,14165,14130 ,5674,5668,5631 ,0,0,0}, - {14164,14136,14170 ,5667,5637,5673 ,0,0,0}, {14123,14165,14166 ,5623,5668,5669 ,0,0,0}, - {14122,14164,14131 ,5622,5667,5632 ,0,0,0}, {14171,14166,14165 ,5674,5669,5668 ,0,0,0}, - {14114,14113,14163 ,5612,5611,5666 ,0,0,0}, {14162,14118,14119 ,5665,5616,5617 ,0,0,0}, - {14167,14115,14169 ,5670,5613,5672 ,0,0,0}, {14163,14168,14100 ,5666,5671,5598 ,0,0,0}, - {14118,14172,14168 ,5616,5675,5671 ,0,0,0}, {14169,14117,14170 ,5672,5615,5673 ,0,0,0}, - {14172,14115,14167 ,5675,5613,5670 ,0,0,0}, {14170,14173,14164 ,5673,5676,5667 ,0,0,0}, - {14115,14117,14169 ,5613,5615,5672 ,0,0,0}, {14174,14131,14164 ,5677,5632,5667 ,0,0,0}, - {14173,14170,14117 ,5676,5673,5615 ,0,0,0}, {14175,14130,14135 ,5678,5631,5636 ,0,0,0}, - {14164,14173,14174 ,5667,5676,5677 ,0,0,0}, {14174,14132,14131 ,5677,5633,5632 ,0,0,0}, - {14171,14130,14175 ,5674,5631,5678 ,0,0,0}, {14165,14131,14130 ,5668,5632,5631 ,0,0,0}, - {14113,14118,14168 ,5611,5616,5671 ,0,0,0}, {14176,14161,14162 ,5679,5664,5665 ,0,0,0}, - {14177,14173,14117 ,5680,5676,5615 ,0,0,0}, {14168,14172,14167 ,5671,5675,5670 ,0,0,0}, - {14161,14109,14172 ,5664,5607,5675 ,0,0,0}, {14178,14174,14173 ,5681,5677,5676 ,0,0,0}, - {14109,14116,14115 ,5607,5614,5613 ,0,0,0}, {14179,14132,14174 ,5682,5633,5677 ,0,0,0}, - {14116,14177,14117 ,5614,5680,5615 ,0,0,0}, {14139,14133,14180 ,5640,5634,5683 ,0,0,0}, - {14177,14178,14173 ,5680,5681,5676 ,0,0,0}, {14135,14132,14181 ,5636,5633,5684 ,0,0,0}, - {14179,14174,14178 ,5682,5677,5681 ,0,0,0}, {14181,14132,14179 ,5684,5633,5682 ,0,0,0}, - {14175,14135,14134 ,5678,5636,5635 ,0,0,0}, {14130,14132,14135 ,5631,5633,5636 ,0,0,0}, - {14118,14161,14172 ,5616,5664,5675 ,0,0,0}, {14107,14176,14125 ,5605,5679,5625 ,0,0,0}, - {14108,14182,14116 ,5606,5685,5614 ,0,0,0}, {14172,14109,14115 ,5675,5607,5613 ,0,0,0}, - {14108,14116,14109 ,5606,5614,5607 ,0,0,0}, {14182,14183,14177 ,5685,5686,5680 ,0,0,0}, - {14182,14177,14116 ,5685,5680,5614 ,0,0,0}, {14183,14184,14178 ,5686,5687,5681 ,0,0,0}, - {14183,14178,14177 ,5686,5681,5680 ,0,0,0}, {14184,14185,14179 ,5687,5688,5682 ,0,0,0}, - {14184,14179,14178 ,5687,5682,5681 ,0,0,0}, {14185,14180,14181 ,5688,5683,5684 ,0,0,0}, - {14181,14179,14185 ,5684,5682,5688 ,0,0,0}, {14180,14133,14181 ,5683,5634,5684 ,0,0,0}, - {14134,14133,14138 ,5635,5634,5639 ,0,0,0}, {14135,14181,14133 ,5636,5684,5634 ,0,0,0}, - {14176,14107,14161 ,5679,5605,5664 ,0,0,0}, {14109,14161,14107 ,5607,5664,5605 ,0,0,0}, - {14182,13825,13846 ,5685,5621,5689 ,0,0,0}, {13857,14108,14107 ,5620,5606,5605 ,0,0,0}, - {14183,13846,13957 ,5686,5689,5690 ,0,0,0}, {13825,14182,14108 ,5621,5685,5606 ,0,0,0}, - {14184,13957,13843 ,5687,5690,5691 ,0,0,0}, {13846,14183,14182 ,5689,5686,5685 ,0,0,0}, - {14185,13843,13841 ,5688,5691,5692 ,0,0,0}, {13957,14184,14183 ,5690,5687,5686 ,0,0,0}, - {14180,13841,13810 ,5683,5692,5693 ,0,0,0}, {13843,14185,14184 ,5691,5688,5687 ,0,0,0}, - {14139,13810,13848 ,5640,5693,5643 ,0,0,0}, {13841,14180,14185 ,5692,5683,5688 ,0,0,0}, - {13848,14137,14139 ,5643,5638,5640 ,0,0,0}, {13810,14139,14180 ,5693,5640,5683 ,0,0,0}, - {14186,14187,14188 ,5694,5695,5696 ,0,0,0}, {14189,14190,14191 ,5697,5698,5699 ,0,0,0}, - {14188,14192,14193 ,5696,5700,5701 ,0,0,0}, {14192,14194,14193 ,5700,5702,5701 ,0,0,0}, - {14195,14196,14197 ,5703,5704,5705 ,0,0,0}, {14197,14198,14195 ,5705,5706,5703 ,0,0,0}, - {14199,14200,14201 ,5707,5708,5709 ,0,0,0}, {14202,14196,14203 ,5710,5704,5711 ,0,0,0}, - {14202,14197,14196 ,5710,5705,5704 ,0,0,0}, {14203,14204,14202 ,5711,5712,5710 ,0,0,0}, - {14205,14191,14206 ,5713,5699,5714 ,0,0,0}, {14207,14208,14209 ,5715,5716,5717 ,0,0,0}, - {14199,13773,13772 ,5707,5718,5719 ,0,0,0}, {14210,14211,14212 ,5720,5721,5722 ,0,0,0}, - {14213,13800,14201 ,5723,5724,5709 ,0,0,0}, {14214,14215,14208 ,5725,5726,5716 ,0,0,0}, - {13773,14201,13800 ,5718,5709,5724 ,0,0,0}, {14216,14217,14218 ,5727,5728,5729 ,0,0,0}, - {14219,14193,14194 ,5730,5701,5702 ,0,0,0}, {14220,14221,14222 ,5731,5732,5733 ,0,0,0}, - {14223,14224,14188 ,5734,5735,5696 ,0,0,0}, {14225,14226,14227 ,5736,5737,5738 ,0,0,0}, - {14218,14228,14229 ,5729,5739,5740 ,0,0,0}, {14230,14228,14231 ,5741,5739,5742 ,0,0,0}, - {14232,14233,14234 ,5743,5744,5745 ,0,0,0}, {14186,14190,14189 ,5694,5698,5697 ,0,0,0}, - {14233,14220,14234 ,5744,5731,5745 ,0,0,0}, {14224,14235,14186 ,5735,5746,5694 ,0,0,0}, - {13796,13801,14232 ,5747,5748,5743 ,0,0,0}, {14236,14237,14224 ,5749,5750,5735 ,0,0,0}, - {14235,14190,14186 ,5746,5698,5694 ,0,0,0}, {14236,14238,14239 ,5749,5751,5752 ,0,0,0}, - {14224,14237,14235 ,5735,5750,5746 ,0,0,0}, {14240,14241,14242 ,5753,5754,5755 ,0,0,0}, - {14237,14236,14239 ,5750,5749,5752 ,0,0,0}, {14243,14242,14244 ,5756,5755,5757 ,0,0,0}, - {14241,14240,14238 ,5754,5753,5751 ,0,0,0}, {14206,14196,14205 ,5714,5704,5713 ,0,0,0}, - {14196,14206,14203 ,5704,5714,5711 ,0,0,0}, {14198,14245,14195 ,5706,5758,5703 ,0,0,0}, - {14205,14189,14191 ,5713,5697,5699 ,0,0,0}, {14246,14205,14195 ,5759,5713,5703 ,0,0,0}, - {14188,14187,14192 ,5696,5695,5700 ,0,0,0}, {14246,14187,14189 ,5759,5695,5697 ,0,0,0}, - {14236,14247,14238 ,5749,5760,5751 ,0,0,0}, {14189,14187,14186 ,5697,5695,5694 ,0,0,0}, - {14248,14249,14241 ,5761,5762,5754 ,0,0,0}, {14224,14186,14188 ,5735,5694,5696 ,0,0,0}, - {14247,14236,14223 ,5760,5749,5734 ,0,0,0}, {14242,14241,14244 ,5755,5754,5757 ,0,0,0}, - {14239,14238,14240 ,5752,5751,5753 ,0,0,0}, {14238,14247,14248 ,5751,5760,5761 ,0,0,0}, - {14250,14244,14241 ,5763,5757,5754 ,0,0,0}, {14196,14195,14205 ,5704,5703,5713 ,0,0,0}, - {14251,14245,14198 ,5764,5758,5706 ,0,0,0}, {14251,14214,14245 ,5764,5725,5758 ,0,0,0}, - {14205,14246,14189 ,5713,5759,5697 ,0,0,0}, {14245,14252,14246 ,5758,5765,5759 ,0,0,0}, - {14193,14231,14223 ,5701,5742,5734 ,0,0,0}, {14252,14192,14187 ,5765,5700,5695 ,0,0,0}, - {14218,14249,14248 ,5729,5762,5761 ,0,0,0}, {14217,14249,14218 ,5728,5762,5729 ,0,0,0}, - {14224,14223,14236 ,5735,5734,5749 ,0,0,0}, {14188,14193,14223 ,5696,5701,5734 ,0,0,0}, - {14238,14248,14241 ,5751,5761,5754 ,0,0,0}, {14231,14228,14247 ,5742,5739,5760 ,0,0,0}, - {14241,14249,14250 ,5754,5762,5763 ,0,0,0}, {14248,14228,14218 ,5761,5739,5729 ,0,0,0}, - {14253,14250,14249 ,5766,5763,5762 ,0,0,0}, {14195,14245,14246 ,5703,5758,5759 ,0,0,0}, - {14215,14214,14251 ,5726,5725,5764 ,0,0,0}, {14254,14207,14255 ,5767,5715,5768 ,0,0,0}, - {14246,14252,14187 ,5759,5765,5695 ,0,0,0}, {14256,14252,14214 ,5769,5765,5725 ,0,0,0}, - {14231,14193,14219 ,5742,5701,5730 ,0,0,0}, {14256,14194,14192 ,5769,5702,5700 ,0,0,0}, - {14257,14216,14229 ,5770,5727,5740 ,0,0,0}, {14247,14228,14248 ,5760,5739,5761 ,0,0,0}, - {14223,14231,14247 ,5734,5742,5760 ,0,0,0}, {14231,14219,14230 ,5742,5730,5741 ,0,0,0}, - {14217,14216,14258 ,5728,5727,5771 ,0,0,0}, {14230,14229,14228 ,5741,5740,5739 ,0,0,0}, - {14249,14217,14253 ,5762,5728,5766 ,0,0,0}, {14218,14229,14216 ,5729,5740,5727 ,0,0,0}, - {14259,14253,14217 ,5772,5766,5728 ,0,0,0}, {14245,14214,14252 ,5758,5725,5765 ,0,0,0}, - {14209,14208,14215 ,5717,5716,5726 ,0,0,0}, {14194,14260,14219 ,5702,5773,5730 ,0,0,0}, - {14252,14256,14192 ,5765,5769,5700 ,0,0,0}, {14261,14256,14208 ,5774,5769,5716 ,0,0,0}, - {14219,14262,14230 ,5730,5775,5741 ,0,0,0}, {14261,14260,14194 ,5774,5773,5702 ,0,0,0}, - {14230,14263,14229 ,5741,5776,5740 ,0,0,0}, {14262,14219,14260 ,5775,5730,5773 ,0,0,0}, - {14216,14226,14258 ,5727,5737,5771 ,0,0,0}, {14263,14230,14262 ,5776,5741,5775 ,0,0,0}, - {14264,14258,14225 ,5777,5771,5736 ,0,0,0}, {14257,14229,14263 ,5770,5740,5776 ,0,0,0}, - {14217,14258,14259 ,5728,5771,5772 ,0,0,0}, {14216,14257,14226 ,5727,5770,5737 ,0,0,0}, - {14264,14259,14258 ,5777,5772,5771 ,0,0,0}, {14214,14208,14256 ,5725,5716,5769 ,0,0,0}, - {14255,14207,14209 ,5768,5715,5717 ,0,0,0}, {14260,14211,14262 ,5773,5721,5775 ,0,0,0}, - {14256,14261,14194 ,5769,5774,5702 ,0,0,0}, {14207,14265,14261 ,5715,5778,5774 ,0,0,0}, - {14262,14210,14263 ,5775,5720,5776 ,0,0,0}, {14265,14211,14260 ,5778,5721,5773 ,0,0,0}, - {14263,14266,14257 ,5776,5779,5770 ,0,0,0}, {14211,14210,14262 ,5721,5720,5775 ,0,0,0}, - {14267,14226,14257 ,5780,5737,5770 ,0,0,0}, {14266,14263,14210 ,5779,5776,5720 ,0,0,0}, - {14268,14225,14222 ,5781,5736,5733 ,0,0,0}, {14257,14266,14267 ,5770,5779,5780 ,0,0,0}, - {14267,14227,14226 ,5780,5738,5737 ,0,0,0}, {14264,14225,14268 ,5777,5736,5781 ,0,0,0}, - {14258,14226,14225 ,5771,5737,5736 ,0,0,0}, {14208,14207,14261 ,5716,5715,5774 ,0,0,0}, - {14269,14254,14255 ,5782,5767,5768 ,0,0,0}, {14270,14266,14210 ,5783,5779,5720 ,0,0,0}, - {14261,14265,14260 ,5774,5778,5773 ,0,0,0}, {14254,14200,14265 ,5767,5708,5778 ,0,0,0}, - {14271,14267,14266 ,5784,5780,5779 ,0,0,0}, {14200,14212,14211 ,5708,5722,5721 ,0,0,0}, - {14272,14227,14267 ,5785,5738,5780 ,0,0,0}, {14212,14270,14210 ,5722,5783,5720 ,0,0,0}, - {14234,14220,14273 ,5745,5731,5786 ,0,0,0}, {14270,14271,14266 ,5783,5784,5779 ,0,0,0}, - {14222,14227,14274 ,5733,5738,5787 ,0,0,0}, {14272,14267,14271 ,5785,5780,5784 ,0,0,0}, - {14274,14227,14272 ,5787,5738,5785 ,0,0,0}, {14268,14222,14221 ,5781,5733,5732 ,0,0,0}, - {14225,14227,14222 ,5736,5738,5733 ,0,0,0}, {14207,14254,14265 ,5715,5767,5778 ,0,0,0}, - {14201,14269,14213 ,5709,5782,5723 ,0,0,0}, {14199,14275,14212 ,5707,5788,5722 ,0,0,0}, - {14265,14200,14211 ,5778,5708,5721 ,0,0,0}, {14199,14212,14200 ,5707,5722,5708 ,0,0,0}, - {14275,14276,14270 ,5788,5789,5783 ,0,0,0}, {14275,14270,14212 ,5788,5783,5722 ,0,0,0}, - {14276,14277,14271 ,5789,5790,5784 ,0,0,0}, {14276,14271,14270 ,5789,5784,5783 ,0,0,0}, - {14277,14278,14272 ,5790,5791,5785 ,0,0,0}, {14277,14272,14271 ,5790,5785,5784 ,0,0,0}, - {14278,14273,14274 ,5791,5786,5787 ,0,0,0}, {14274,14272,14278 ,5787,5785,5791 ,0,0,0}, - {14273,14220,14274 ,5786,5731,5787 ,0,0,0}, {14221,14220,14233 ,5732,5731,5744 ,0,0,0}, - {14222,14274,14220 ,5733,5787,5731 ,0,0,0}, {14269,14201,14254 ,5782,5709,5767 ,0,0,0}, - {14200,14254,14201 ,5708,5767,5709 ,0,0,0}, {14275,13772,13787 ,5788,5719,5792 ,0,0,0}, - {13773,14199,14201 ,5718,5707,5709 ,0,0,0}, {14276,13787,13790 ,5789,5792,5793 ,0,0,0}, - {13772,14275,14199 ,5719,5788,5707 ,0,0,0}, {14277,13790,13791 ,5790,5793,5794 ,0,0,0}, - {13787,14276,14275 ,5792,5789,5788 ,0,0,0}, {14278,13791,13830 ,5791,5794,5795 ,0,0,0}, - {13790,14277,14276 ,5793,5790,5789 ,0,0,0}, {14273,13830,13771 ,5786,5795,5796 ,0,0,0}, - {13791,14278,14277 ,5794,5791,5790 ,0,0,0}, {14234,13771,13796 ,5745,5796,5747 ,0,0,0}, - {13830,14273,14278 ,5795,5786,5791 ,0,0,0}, {13796,14232,14234 ,5747,5743,5745 ,0,0,0}, - {13771,14234,14273 ,5796,5745,5786 ,0,0,0}, {14279,14280,14281 ,5797,5798,5799 ,0,0,0}, - {14282,13196,13197 ,5800,5801,5802 ,0,0,0}, {14281,14283,14284 ,5799,5803,5804 ,0,0,0}, - {14283,14285,14284 ,5803,5805,5804 ,0,0,0}, {14286,14287,14288 ,5806,5807,5808 ,0,0,0}, - {14288,14289,14286 ,5808,5809,5806 ,0,0,0}, {14290,14291,14292 ,5810,5811,5812 ,0,0,0}, - {14293,14287,13202 ,5813,5807,5814 ,0,0,0}, {14293,14288,14287 ,5813,5808,5807 ,0,0,0}, - {13202,13203,14293 ,5814,5815,5813 ,0,0,0}, {14294,13197,13200 ,5816,5802,5817 ,0,0,0}, - {14295,14296,14297 ,5818,5819,5820 ,0,0,0}, {14290,13729,13728 ,5810,5821,5822 ,0,0,0}, - {14298,14299,14300 ,5823,5824,5825 ,0,0,0}, {14301,13736,14292 ,5826,5827,5812 ,0,0,0}, - {14302,14303,14296 ,5828,5829,5819 ,0,0,0}, {13729,14292,13736 ,5821,5812,5827 ,0,0,0}, - {14304,14305,14306 ,5830,5831,5832 ,0,0,0}, {14307,14284,14285 ,5833,5804,5805 ,0,0,0}, - {14308,14309,14310 ,5834,5835,5836 ,0,0,0}, {14311,14312,14281 ,5837,5838,5799 ,0,0,0}, - {14313,14314,14315 ,5839,5840,5841 ,0,0,0}, {14306,14316,14317 ,5832,5842,5843 ,0,0,0}, - {14318,14316,14319 ,5844,5842,5845 ,0,0,0}, {14320,14321,14322 ,5846,5847,5848 ,0,0,0}, - {14279,13196,14282 ,5797,5801,5800 ,0,0,0}, {14321,14308,14322 ,5847,5834,5848 ,0,0,0}, - {14312,13194,14279 ,5838,5849,5797 ,0,0,0}, {13752,13759,14320 ,5850,5851,5846 ,0,0,0}, - {14323,13192,14312 ,5852,5853,5838 ,0,0,0}, {13194,13196,14279 ,5849,5801,5797 ,0,0,0}, - {14323,14324,13189 ,5852,5854,5855 ,0,0,0}, {14312,13192,13194 ,5838,5853,5849 ,0,0,0}, - {13187,14325,13188 ,5856,5857,5858 ,0,0,0}, {13192,14323,13189 ,5853,5852,5855 ,0,0,0}, - {13182,13188,14326 ,5067,5858,5859 ,0,0,0}, {14325,13187,14324 ,5857,5856,5854 ,0,0,0}, - {13200,14287,14294 ,5817,5807,5816 ,0,0,0}, {14287,13200,13202 ,5807,5817,5814 ,0,0,0}, - {14289,14327,14286 ,5809,5860,5806 ,0,0,0}, {14294,14282,13197 ,5816,5800,5802 ,0,0,0}, - {14328,14294,14286 ,5861,5816,5806 ,0,0,0}, {14281,14280,14283 ,5799,5798,5803 ,0,0,0}, - {14328,14280,14282 ,5861,5798,5800 ,0,0,0}, {14323,14329,14324 ,5852,5862,5854 ,0,0,0}, - {14282,14280,14279 ,5800,5798,5797 ,0,0,0}, {14330,14331,14325 ,5863,5864,5857 ,0,0,0}, - {14312,14279,14281 ,5838,5797,5799 ,0,0,0}, {14329,14323,14311 ,5862,5852,5837 ,0,0,0}, - {13188,14325,14326 ,5858,5857,5859 ,0,0,0}, {13189,14324,13187 ,5855,5854,5856 ,0,0,0}, - {14324,14329,14330 ,5854,5862,5863 ,0,0,0}, {14332,14326,14325 ,5865,5859,5857 ,0,0,0}, - {14287,14286,14294 ,5807,5806,5816 ,0,0,0}, {14333,14327,14289 ,5866,5860,5809 ,0,0,0}, - {14333,14302,14327 ,5866,5828,5860 ,0,0,0}, {14294,14328,14282 ,5816,5861,5800 ,0,0,0}, - {14327,14334,14328 ,5860,5867,5861 ,0,0,0}, {14284,14319,14311 ,5804,5845,5837 ,0,0,0}, - {14334,14283,14280 ,5867,5803,5798 ,0,0,0}, {14306,14331,14330 ,5832,5864,5863 ,0,0,0}, - {14305,14331,14306 ,5831,5864,5832 ,0,0,0}, {14312,14311,14323 ,5838,5837,5852 ,0,0,0}, - {14281,14284,14311 ,5799,5804,5837 ,0,0,0}, {14324,14330,14325 ,5854,5863,5857 ,0,0,0}, - {14319,14316,14329 ,5845,5842,5862 ,0,0,0}, {14325,14331,14332 ,5857,5864,5865 ,0,0,0}, - {14330,14316,14306 ,5863,5842,5832 ,0,0,0}, {14335,14332,14331 ,5868,5865,5864 ,0,0,0}, - {14286,14327,14328 ,5806,5860,5861 ,0,0,0}, {14303,14302,14333 ,5829,5828,5866 ,0,0,0}, - {14336,14295,14337 ,5869,5818,5870 ,0,0,0}, {14328,14334,14280 ,5861,5867,5798 ,0,0,0}, - {14338,14334,14302 ,5871,5867,5828 ,0,0,0}, {14319,14284,14307 ,5845,5804,5833 ,0,0,0}, - {14338,14285,14283 ,5871,5805,5803 ,0,0,0}, {14339,14304,14317 ,5872,5830,5843 ,0,0,0}, - {14329,14316,14330 ,5862,5842,5863 ,0,0,0}, {14311,14319,14329 ,5837,5845,5862 ,0,0,0}, - {14319,14307,14318 ,5845,5833,5844 ,0,0,0}, {14305,14304,14340 ,5831,5830,5873 ,0,0,0}, - {14318,14317,14316 ,5844,5843,5842 ,0,0,0}, {14331,14305,14335 ,5864,5831,5868 ,0,0,0}, - {14306,14317,14304 ,5832,5843,5830 ,0,0,0}, {14341,14335,14305 ,5874,5868,5831 ,0,0,0}, - {14327,14302,14334 ,5860,5828,5867 ,0,0,0}, {14297,14296,14303 ,5820,5819,5829 ,0,0,0}, - {14285,14342,14307 ,5805,5875,5833 ,0,0,0}, {14334,14338,14283 ,5867,5871,5803 ,0,0,0}, - {14343,14338,14296 ,5876,5871,5819 ,0,0,0}, {14307,14344,14318 ,5833,5877,5844 ,0,0,0}, - {14343,14342,14285 ,5876,5875,5805 ,0,0,0}, {14318,14345,14317 ,5844,5878,5843 ,0,0,0}, - {14344,14307,14342 ,5877,5833,5875 ,0,0,0}, {14304,14314,14340 ,5830,5840,5873 ,0,0,0}, - {14345,14318,14344 ,5878,5844,5877 ,0,0,0}, {14346,14340,14313 ,5879,5873,5839 ,0,0,0}, - {14339,14317,14345 ,5872,5843,5878 ,0,0,0}, {14305,14340,14341 ,5831,5873,5874 ,0,0,0}, - {14304,14339,14314 ,5830,5872,5840 ,0,0,0}, {14346,14341,14340 ,5879,5874,5873 ,0,0,0}, - {14302,14296,14338 ,5828,5819,5871 ,0,0,0}, {14337,14295,14297 ,5870,5818,5820 ,0,0,0}, - {14342,14299,14344 ,5875,5824,5877 ,0,0,0}, {14338,14343,14285 ,5871,5876,5805 ,0,0,0}, - {14295,14347,14343 ,5818,5880,5876 ,0,0,0}, {14344,14298,14345 ,5877,5823,5878 ,0,0,0}, - {14347,14299,14342 ,5880,5824,5875 ,0,0,0}, {14345,14348,14339 ,5878,5881,5872 ,0,0,0}, - {14299,14298,14344 ,5824,5823,5877 ,0,0,0}, {14349,14314,14339 ,5882,5840,5872 ,0,0,0}, - {14348,14345,14298 ,5881,5878,5823 ,0,0,0}, {14350,14313,14310 ,5883,5839,5836 ,0,0,0}, - {14339,14348,14349 ,5872,5881,5882 ,0,0,0}, {14349,14315,14314 ,5882,5841,5840 ,0,0,0}, - {14346,14313,14350 ,5879,5839,5883 ,0,0,0}, {14340,14314,14313 ,5873,5840,5839 ,0,0,0}, - {14296,14295,14343 ,5819,5818,5876 ,0,0,0}, {14351,14336,14337 ,5884,5869,5870 ,0,0,0}, - {14352,14348,14298 ,5885,5881,5823 ,0,0,0}, {14343,14347,14342 ,5876,5880,5875 ,0,0,0}, - {14336,14291,14347 ,5869,5811,5880 ,0,0,0}, {14353,14349,14348 ,5886,5882,5881 ,0,0,0}, - {14291,14300,14299 ,5811,5825,5824 ,0,0,0}, {14354,14315,14349 ,5887,5841,5882 ,0,0,0}, - {14300,14352,14298 ,5825,5885,5823 ,0,0,0}, {14322,14308,14355 ,5848,5834,5888 ,0,0,0}, - {14352,14353,14348 ,5885,5886,5881 ,0,0,0}, {14310,14315,14356 ,5836,5841,5889 ,0,0,0}, - {14354,14349,14353 ,5887,5882,5886 ,0,0,0}, {14356,14315,14354 ,5889,5841,5887 ,0,0,0}, - {14350,14310,14309 ,5883,5836,5835 ,0,0,0}, {14313,14315,14310 ,5839,5841,5836 ,0,0,0}, - {14295,14336,14347 ,5818,5869,5880 ,0,0,0}, {14292,14351,14301 ,5812,5884,5826 ,0,0,0}, - {14290,14357,14300 ,5810,5890,5825 ,0,0,0}, {14347,14291,14299 ,5880,5811,5824 ,0,0,0}, - {14290,14300,14291 ,5810,5825,5811 ,0,0,0}, {14357,14358,14352 ,5890,5891,5885 ,0,0,0}, - {14357,14352,14300 ,5890,5885,5825 ,0,0,0}, {14358,14359,14353 ,5891,5892,5886 ,0,0,0}, - {14358,14353,14352 ,5891,5886,5885 ,0,0,0}, {14359,14360,14354 ,5892,5893,5887 ,0,0,0}, - {14359,14354,14353 ,5892,5887,5886 ,0,0,0}, {14360,14355,14356 ,5893,5888,5889 ,0,0,0}, - {14356,14354,14360 ,5889,5887,5893 ,0,0,0}, {14355,14308,14356 ,5888,5834,5889 ,0,0,0}, - {14309,14308,14321 ,5835,5834,5847 ,0,0,0}, {14310,14356,14308 ,5836,5889,5834 ,0,0,0}, - {14351,14292,14336 ,5884,5812,5869 ,0,0,0}, {14291,14336,14292 ,5811,5869,5812 ,0,0,0}, - {14357,13728,13746 ,5890,5822,5894 ,0,0,0}, {13729,14290,14292 ,5821,5810,5812 ,0,0,0}, - {14358,13746,13747 ,5891,5894,5895 ,0,0,0}, {13728,14357,14290 ,5822,5890,5810 ,0,0,0}, - {14359,13747,13749 ,5892,5895,5896 ,0,0,0}, {13746,14358,14357 ,5894,5891,5890 ,0,0,0}, - {14360,13749,13732 ,5893,5896,5897 ,0,0,0}, {13747,14359,14358 ,5895,5892,5891 ,0,0,0}, - {14355,13732,13753 ,5888,5897,5898 ,0,0,0}, {13749,14360,14359 ,5896,5893,5892 ,0,0,0}, - {14322,13753,13752 ,5848,5898,5850 ,0,0,0}, {13732,14355,14360 ,5897,5888,5893 ,0,0,0}, - {13752,14320,14322 ,5850,5846,5848 ,0,0,0}, {13753,14322,14355 ,5898,5848,5888 ,0,0,0}, - {14361,14362,14363 ,5899,5900,5901 ,0,0,0}, {14364,14365,13165 ,5902,5903,5904 ,0,0,0}, - {14362,14366,14363 ,5900,5905,5901 ,0,0,0}, {13160,13165,14365 ,5906,5904,5903 ,0,0,0}, - {14367,14368,14369 ,5907,5908,5909 ,0,0,0}, {13170,14370,14368 ,5910,5911,5908 ,0,0,0}, - {14371,14372,14373 ,5912,5913,5914 ,0,0,0}, {13168,14370,13170 ,5915,5911,5910 ,0,0,0}, - {14370,14369,14368 ,5911,5909,5908 ,0,0,0}, {13164,14368,14364 ,5916,5908,5902 ,0,0,0}, - {14374,14375,14376 ,5917,5918,5919 ,0,0,0}, {14377,14378,14379 ,5920,5921,5922 ,0,0,0}, - {14380,14375,14381 ,5923,5918,5924 ,0,0,0}, {14382,14383,14361 ,5925,5926,5899 ,0,0,0}, - {14372,13679,13598 ,5913,5927,5928 ,0,0,0}, {14384,14385,14386 ,5929,5930,5931 ,0,0,0}, - {14387,13709,14371 ,5932,5933,5912 ,0,0,0}, {13679,14371,13709 ,5927,5912,5933 ,0,0,0}, - {14388,14389,14390 ,5934,5935,5936 ,0,0,0}, {14366,14391,14363 ,5905,5937,5901 ,0,0,0}, - {14392,14393,14394 ,5938,5939,5940 ,0,0,0}, {14395,14396,14397 ,5941,5942,5943 ,0,0,0}, - {14386,14389,14398 ,5931,5935,5944 ,0,0,0}, {14399,14400,14401 ,5945,5946,5947 ,0,0,0}, - {14402,14361,14403 ,5948,5899,5949 ,0,0,0}, {14400,14395,14401 ,5946,5941,5947 ,0,0,0}, - {14382,13160,14365 ,5925,5906,5903 ,0,0,0}, {13708,13712,14399 ,5950,5951,5945 ,0,0,0}, - {13160,14382,13158 ,5906,5925,5952 ,0,0,0}, {13158,14382,14402 ,5952,5925,5948 ,0,0,0}, - {14404,13153,14402 ,5953,5954,5948 ,0,0,0}, {14382,14365,14383 ,5925,5903,5926 ,0,0,0}, - {14404,14405,13157 ,5953,5955,5956 ,0,0,0}, {13157,13153,14404 ,5956,5954,5953 ,0,0,0}, - {13149,14406,13151 ,5957,5958,5959 ,0,0,0}, {14406,13149,14405 ,5958,5957,5955 ,0,0,0}, - {13170,14368,13164 ,5910,5908,5916 ,0,0,0}, {14407,14367,14369 ,5960,5907,5909 ,0,0,0}, - {14407,14408,14367 ,5960,5961,5907 ,0,0,0}, {13164,14364,13165 ,5916,5902,5904 ,0,0,0}, - {14409,14364,14367 ,5962,5902,5907 ,0,0,0}, {14361,14383,14362 ,5899,5926,5900 ,0,0,0}, - {14409,14383,14365 ,5962,5926,5903 ,0,0,0}, {14404,14410,14405 ,5953,5963,5955 ,0,0,0}, - {14411,14406,14412 ,5964,5958,5965 ,0,0,0}, {13158,14402,13153 ,5952,5948,5954 ,0,0,0}, - {14402,14382,14361 ,5948,5925,5899 ,0,0,0}, {13157,14405,13149 ,5956,5955,5957 ,0,0,0}, - {14403,14410,14404 ,5949,5963,5953 ,0,0,0}, {14406,14413,13151 ,5958,5966,5959 ,0,0,0}, - {14405,14410,14412 ,5955,5963,5965 ,0,0,0}, {14414,14413,14406 ,5967,5966,5958 ,0,0,0}, - {14368,14367,14364 ,5908,5907,5902 ,0,0,0}, {14415,14408,14407 ,5968,5961,5960 ,0,0,0}, - {14415,14376,14408 ,5968,5919,5961 ,0,0,0}, {14364,14409,14365 ,5902,5962,5903 ,0,0,0}, - {14408,14416,14409 ,5961,5969,5962 ,0,0,0}, {14363,14390,14403 ,5901,5936,5949 ,0,0,0}, - {14416,14362,14383 ,5969,5900,5926 ,0,0,0}, {14386,14411,14412 ,5931,5964,5965 ,0,0,0}, - {14385,14411,14386 ,5930,5964,5931 ,0,0,0}, {14402,14403,14404 ,5948,5949,5953 ,0,0,0}, - {14361,14363,14403 ,5899,5901,5949 ,0,0,0}, {14405,14412,14406 ,5955,5965,5958 ,0,0,0}, - {14390,14389,14410 ,5936,5935,5963 ,0,0,0}, {14406,14411,14414 ,5958,5964,5967 ,0,0,0}, - {14412,14389,14386 ,5965,5935,5931 ,0,0,0}, {14417,14414,14411 ,5970,5967,5964 ,0,0,0}, - {14367,14408,14409 ,5907,5961,5962 ,0,0,0}, {14374,14376,14415 ,5917,5919,5968 ,0,0,0}, - {14418,14380,14419 ,5971,5923,5972 ,0,0,0}, {14409,14416,14383 ,5962,5969,5926 ,0,0,0}, - {14420,14416,14376 ,5973,5969,5919 ,0,0,0}, {14390,14363,14391 ,5936,5901,5937 ,0,0,0}, - {14420,14366,14362 ,5973,5905,5900 ,0,0,0}, {14421,14384,14398 ,5974,5929,5944 ,0,0,0}, - {14410,14389,14412 ,5963,5935,5965 ,0,0,0}, {14403,14390,14410 ,5949,5936,5963 ,0,0,0}, - {14390,14391,14388 ,5936,5937,5934 ,0,0,0}, {14385,14384,14422 ,5930,5929,5975 ,0,0,0}, - {14388,14398,14389 ,5934,5944,5935 ,0,0,0}, {14411,14385,14417 ,5964,5930,5970 ,0,0,0}, - {14386,14398,14384 ,5931,5944,5929 ,0,0,0}, {14423,14417,14385 ,5976,5970,5930 ,0,0,0}, - {14408,14376,14416 ,5961,5919,5969 ,0,0,0}, {14381,14375,14374 ,5924,5918,5917 ,0,0,0}, - {14366,14424,14391 ,5905,5977,5937 ,0,0,0}, {14416,14420,14362 ,5969,5973,5900 ,0,0,0}, - {14425,14420,14375 ,5978,5973,5918 ,0,0,0}, {14391,14426,14388 ,5937,5979,5934 ,0,0,0}, - {14425,14424,14366 ,5978,5977,5905 ,0,0,0}, {14388,14427,14398 ,5934,5980,5944 ,0,0,0}, - {14426,14391,14424 ,5979,5937,5977 ,0,0,0}, {14384,14393,14422 ,5929,5939,5975 ,0,0,0}, - {14427,14388,14426 ,5980,5934,5979 ,0,0,0}, {14428,14422,14392 ,5981,5975,5938 ,0,0,0}, - {14421,14398,14427 ,5974,5944,5980 ,0,0,0}, {14385,14422,14423 ,5930,5975,5976 ,0,0,0}, - {14384,14421,14393 ,5929,5974,5939 ,0,0,0}, {14428,14423,14422 ,5981,5976,5975 ,0,0,0}, - {14376,14375,14420 ,5919,5918,5973 ,0,0,0}, {14419,14380,14381 ,5972,5923,5924 ,0,0,0}, - {14424,14377,14426 ,5977,5920,5979 ,0,0,0}, {14420,14425,14366 ,5973,5978,5905 ,0,0,0}, - {14380,14429,14425 ,5923,5982,5978 ,0,0,0}, {14426,14379,14427 ,5979,5922,5980 ,0,0,0}, - {14429,14377,14424 ,5982,5920,5977 ,0,0,0}, {14427,14430,14421 ,5980,5983,5974 ,0,0,0}, - {14377,14379,14426 ,5920,5922,5979 ,0,0,0}, {14431,14393,14421 ,5984,5939,5974 ,0,0,0}, - {14430,14427,14379 ,5983,5980,5922 ,0,0,0}, {14432,14392,14397 ,5985,5938,5943 ,0,0,0}, - {14421,14430,14431 ,5974,5983,5984 ,0,0,0}, {14431,14394,14393 ,5984,5940,5939 ,0,0,0}, - {14428,14392,14432 ,5981,5938,5985 ,0,0,0}, {14422,14393,14392 ,5975,5939,5938 ,0,0,0}, - {14375,14380,14425 ,5918,5923,5978 ,0,0,0}, {14433,14418,14419 ,5986,5971,5972 ,0,0,0}, - {14434,14430,14379 ,5987,5983,5922 ,0,0,0}, {14425,14429,14424 ,5978,5982,5977 ,0,0,0}, - {14418,14373,14429 ,5971,5914,5982 ,0,0,0}, {14435,14431,14430 ,5988,5984,5983 ,0,0,0}, - {14373,14378,14377 ,5914,5921,5920 ,0,0,0}, {14436,14394,14431 ,5989,5940,5984 ,0,0,0}, - {14378,14434,14379 ,5921,5987,5922 ,0,0,0}, {14401,14395,14437 ,5947,5941,5990 ,0,0,0}, - {14434,14435,14430 ,5987,5988,5983 ,0,0,0}, {14397,14394,14438 ,5943,5940,5991 ,0,0,0}, - {14436,14431,14435 ,5989,5984,5988 ,0,0,0}, {14438,14394,14436 ,5991,5940,5989 ,0,0,0}, - {14432,14397,14396 ,5985,5943,5942 ,0,0,0}, {14392,14394,14397 ,5938,5940,5943 ,0,0,0}, - {14380,14418,14429 ,5923,5971,5982 ,0,0,0}, {14371,14433,14387 ,5912,5986,5932 ,0,0,0}, - {14372,14439,14378 ,5913,5992,5921 ,0,0,0}, {14429,14373,14377 ,5982,5914,5920 ,0,0,0}, - {14372,14378,14373 ,5913,5921,5914 ,0,0,0}, {14439,14440,14434 ,5992,5993,5987 ,0,0,0}, - {14439,14434,14378 ,5992,5987,5921 ,0,0,0}, {14440,14441,14435 ,5993,5994,5988 ,0,0,0}, - {14440,14435,14434 ,5993,5988,5987 ,0,0,0}, {14441,14442,14436 ,5994,5995,5989 ,0,0,0}, - {14441,14436,14435 ,5994,5989,5988 ,0,0,0}, {14442,14437,14438 ,5995,5990,5991 ,0,0,0}, - {14438,14436,14442 ,5991,5989,5995 ,0,0,0}, {14437,14395,14438 ,5990,5941,5991 ,0,0,0}, - {14396,14395,14400 ,5942,5941,5946 ,0,0,0}, {14397,14438,14395 ,5943,5991,5941 ,0,0,0}, - {14433,14371,14418 ,5986,5912,5971 ,0,0,0}, {14373,14418,14371 ,5914,5971,5912 ,0,0,0}, - {14439,13598,13698 ,5992,5928,5996 ,0,0,0}, {13679,14372,14371 ,5927,5913,5912 ,0,0,0}, - {14440,13698,13903 ,5993,5996,5997 ,0,0,0}, {13598,14439,14372 ,5928,5992,5913 ,0,0,0}, - {14441,13903,13705 ,5994,5997,5998 ,0,0,0}, {13698,14440,14439 ,5996,5993,5992 ,0,0,0}, - {14442,13705,13716 ,5995,5998,5999 ,0,0,0}, {13903,14441,14440 ,5997,5994,5993 ,0,0,0}, - {14437,13716,13702 ,5990,5999,6000 ,0,0,0}, {13705,14442,14441 ,5998,5995,5994 ,0,0,0}, - {14401,13702,13708 ,5947,6000,5950 ,0,0,0}, {13716,14437,14442 ,5999,5990,5995 ,0,0,0}, - {13708,14399,14401 ,5950,5945,5947 ,0,0,0}, {13702,14401,14437 ,6000,5947,5990 ,0,0,0}, - {14443,14444,14445 ,6001,6002,6003 ,0,0,0}, {14446,13133,13130 ,6004,6005,6006 ,0,0,0}, - {14445,14447,14448 ,6003,6007,6008 ,0,0,0}, {14447,14449,14448 ,6007,6009,6008 ,0,0,0}, - {14450,14451,14452 ,6010,6011,6012 ,0,0,0}, {14452,14453,14450 ,6012,6013,6010 ,0,0,0}, - {14454,14455,14456 ,6014,6015,6016 ,0,0,0}, {14457,14451,13136 ,6017,6011,6018 ,0,0,0}, - {14457,14452,14451 ,6017,6012,6011 ,0,0,0}, {13136,13135,14457 ,6018,5020,6017 ,0,0,0}, - {14458,13130,13138 ,6019,6006,6020 ,0,0,0}, {14459,14460,14461 ,6021,6022,6023 ,0,0,0}, - {14454,13653,13669 ,6014,6024,6025 ,0,0,0}, {14462,14463,14464 ,6026,6027,6028 ,0,0,0}, - {14465,13656,14456 ,6029,6030,6016 ,0,0,0}, {14466,14467,14460 ,6031,6032,6022 ,0,0,0}, - {13653,14456,13656 ,6024,6016,6030 ,0,0,0}, {14468,14469,14470 ,6033,6034,6035 ,0,0,0}, - {14471,14448,14449 ,6036,6008,6009 ,0,0,0}, {14472,14473,14474 ,6037,6038,6039 ,0,0,0}, - {14475,14476,14445 ,6040,6041,6003 ,0,0,0}, {14477,14478,14479 ,6042,6043,6044 ,0,0,0}, - {14470,14480,14481 ,6035,6045,6046 ,0,0,0}, {14482,14480,14483 ,6047,6045,6048 ,0,0,0}, - {14484,14485,14486 ,6049,6050,6051 ,0,0,0}, {14443,13133,14446 ,6001,6005,6004 ,0,0,0}, - {14485,14472,14486 ,6050,6037,6051 ,0,0,0}, {14476,13122,14443 ,6041,6052,6001 ,0,0,0}, - {13672,13674,14484 ,6053,6054,6049 ,0,0,0}, {14487,13123,14476 ,6055,6056,6041 ,0,0,0}, - {13122,13133,14443 ,6052,6005,6001 ,0,0,0}, {14487,14488,13125 ,6055,6057,6058 ,0,0,0}, - {14476,13123,13122 ,6041,6056,6052 ,0,0,0}, {13119,14489,13120 ,6059,6060,6061 ,0,0,0}, - {13123,14487,13125 ,6056,6055,6058 ,0,0,0}, {13111,13120,14490 ,6062,6061,6063 ,0,0,0}, - {14489,13119,14488 ,6060,6059,6057 ,0,0,0}, {13138,14451,14458 ,6020,6011,6019 ,0,0,0}, - {14451,13138,13136 ,6011,6020,6018 ,0,0,0}, {14453,14491,14450 ,6013,6064,6010 ,0,0,0}, - {14458,14446,13130 ,6019,6004,6006 ,0,0,0}, {14492,14458,14450 ,6065,6019,6010 ,0,0,0}, - {14445,14444,14447 ,6003,6002,6007 ,0,0,0}, {14492,14444,14446 ,6065,6002,6004 ,0,0,0}, - {14487,14493,14488 ,6055,6066,6057 ,0,0,0}, {14446,14444,14443 ,6004,6002,6001 ,0,0,0}, - {14494,14495,14489 ,6067,6068,6060 ,0,0,0}, {14476,14443,14445 ,6041,6001,6003 ,0,0,0}, - {14493,14487,14475 ,6066,6055,6040 ,0,0,0}, {13120,14489,14490 ,6061,6060,6063 ,0,0,0}, - {13125,14488,13119 ,6058,6057,6059 ,0,0,0}, {14488,14493,14494 ,6057,6066,6067 ,0,0,0}, - {14496,14490,14489 ,6069,6063,6060 ,0,0,0}, {14451,14450,14458 ,6011,6010,6019 ,0,0,0}, - {14497,14491,14453 ,6070,6064,6013 ,0,0,0}, {14497,14466,14491 ,6070,6031,6064 ,0,0,0}, - {14458,14492,14446 ,6019,6065,6004 ,0,0,0}, {14491,14498,14492 ,6064,6071,6065 ,0,0,0}, - {14448,14483,14475 ,6008,6048,6040 ,0,0,0}, {14498,14447,14444 ,6071,6007,6002 ,0,0,0}, - {14470,14495,14494 ,6035,6068,6067 ,0,0,0}, {14469,14495,14470 ,6034,6068,6035 ,0,0,0}, - {14476,14475,14487 ,6041,6040,6055 ,0,0,0}, {14445,14448,14475 ,6003,6008,6040 ,0,0,0}, - {14488,14494,14489 ,6057,6067,6060 ,0,0,0}, {14483,14480,14493 ,6048,6045,6066 ,0,0,0}, - {14489,14495,14496 ,6060,6068,6069 ,0,0,0}, {14494,14480,14470 ,6067,6045,6035 ,0,0,0}, - {14499,14496,14495 ,6072,6069,6068 ,0,0,0}, {14450,14491,14492 ,6010,6064,6065 ,0,0,0}, - {14467,14466,14497 ,6032,6031,6070 ,0,0,0}, {14500,14459,14501 ,6073,6021,6074 ,0,0,0}, - {14492,14498,14444 ,6065,6071,6002 ,0,0,0}, {14502,14498,14466 ,6075,6071,6031 ,0,0,0}, - {14483,14448,14471 ,6048,6008,6036 ,0,0,0}, {14502,14449,14447 ,6075,6009,6007 ,0,0,0}, - {14503,14468,14481 ,6076,6033,6046 ,0,0,0}, {14493,14480,14494 ,6066,6045,6067 ,0,0,0}, - {14475,14483,14493 ,6040,6048,6066 ,0,0,0}, {14483,14471,14482 ,6048,6036,6047 ,0,0,0}, - {14469,14468,14504 ,6034,6033,6077 ,0,0,0}, {14482,14481,14480 ,6047,6046,6045 ,0,0,0}, - {14495,14469,14499 ,6068,6034,6072 ,0,0,0}, {14470,14481,14468 ,6035,6046,6033 ,0,0,0}, - {14505,14499,14469 ,6078,6072,6034 ,0,0,0}, {14491,14466,14498 ,6064,6031,6071 ,0,0,0}, - {14461,14460,14467 ,6023,6022,6032 ,0,0,0}, {14449,14506,14471 ,6009,6079,6036 ,0,0,0}, - {14498,14502,14447 ,6071,6075,6007 ,0,0,0}, {14507,14502,14460 ,6080,6075,6022 ,0,0,0}, - {14471,14508,14482 ,6036,6081,6047 ,0,0,0}, {14507,14506,14449 ,6080,6079,6009 ,0,0,0}, - {14482,14509,14481 ,6047,6082,6046 ,0,0,0}, {14508,14471,14506 ,6081,6036,6079 ,0,0,0}, - {14468,14478,14504 ,6033,6043,6077 ,0,0,0}, {14509,14482,14508 ,6082,6047,6081 ,0,0,0}, - {14510,14504,14477 ,6083,6077,6042 ,0,0,0}, {14503,14481,14509 ,6076,6046,6082 ,0,0,0}, - {14469,14504,14505 ,6034,6077,6078 ,0,0,0}, {14468,14503,14478 ,6033,6076,6043 ,0,0,0}, - {14510,14505,14504 ,6083,6078,6077 ,0,0,0}, {14466,14460,14502 ,6031,6022,6075 ,0,0,0}, - {14501,14459,14461 ,6074,6021,6023 ,0,0,0}, {14506,14463,14508 ,6079,6027,6081 ,0,0,0}, - {14502,14507,14449 ,6075,6080,6009 ,0,0,0}, {14459,14511,14507 ,6021,6084,6080 ,0,0,0}, - {14508,14462,14509 ,6081,6026,6082 ,0,0,0}, {14511,14463,14506 ,6084,6027,6079 ,0,0,0}, - {14509,14512,14503 ,6082,6085,6076 ,0,0,0}, {14463,14462,14508 ,6027,6026,6081 ,0,0,0}, - {14513,14478,14503 ,6086,6043,6076 ,0,0,0}, {14512,14509,14462 ,6085,6082,6026 ,0,0,0}, - {14514,14477,14474 ,6087,6042,6039 ,0,0,0}, {14503,14512,14513 ,6076,6085,6086 ,0,0,0}, - {14513,14479,14478 ,6086,6044,6043 ,0,0,0}, {14510,14477,14514 ,6083,6042,6087 ,0,0,0}, - {14504,14478,14477 ,6077,6043,6042 ,0,0,0}, {14460,14459,14507 ,6022,6021,6080 ,0,0,0}, - {14515,14500,14501 ,6088,6073,6074 ,0,0,0}, {14516,14512,14462 ,6089,6085,6026 ,0,0,0}, - {14507,14511,14506 ,6080,6084,6079 ,0,0,0}, {14500,14455,14511 ,6073,6015,6084 ,0,0,0}, - {14517,14513,14512 ,6090,6086,6085 ,0,0,0}, {14455,14464,14463 ,6015,6028,6027 ,0,0,0}, - {14518,14479,14513 ,6091,6044,6086 ,0,0,0}, {14464,14516,14462 ,6028,6089,6026 ,0,0,0}, - {14486,14472,14519 ,6051,6037,6092 ,0,0,0}, {14516,14517,14512 ,6089,6090,6085 ,0,0,0}, - {14474,14479,14520 ,6039,6044,6093 ,0,0,0}, {14518,14513,14517 ,6091,6086,6090 ,0,0,0}, - {14520,14479,14518 ,6093,6044,6091 ,0,0,0}, {14514,14474,14473 ,6087,6039,6038 ,0,0,0}, - {14477,14479,14474 ,6042,6044,6039 ,0,0,0}, {14459,14500,14511 ,6021,6073,6084 ,0,0,0}, - {14456,14515,14465 ,6016,6088,6029 ,0,0,0}, {14454,14521,14464 ,6014,6094,6028 ,0,0,0}, - {14511,14455,14463 ,6084,6015,6027 ,0,0,0}, {14454,14464,14455 ,6014,6028,6015 ,0,0,0}, - {14521,14522,14516 ,6094,6095,6089 ,0,0,0}, {14521,14516,14464 ,6094,6089,6028 ,0,0,0}, - {14522,14523,14517 ,6095,6096,6090 ,0,0,0}, {14522,14517,14516 ,6095,6090,6089 ,0,0,0}, - {14523,14524,14518 ,6096,6097,6091 ,0,0,0}, {14523,14518,14517 ,6096,6091,6090 ,0,0,0}, - {14524,14519,14520 ,6097,6092,6093 ,0,0,0}, {14520,14518,14524 ,6093,6091,6097 ,0,0,0}, - {14519,14472,14520 ,6092,6037,6093 ,0,0,0}, {14473,14472,14485 ,6038,6037,6050 ,0,0,0}, - {14474,14520,14472 ,6039,6093,6037 ,0,0,0}, {14515,14456,14500 ,6088,6016,6073 ,0,0,0}, - {14455,14500,14456 ,6015,6073,6016 ,0,0,0}, {14521,13669,13663 ,6094,6025,6098 ,0,0,0}, - {13653,14454,14456 ,6024,6014,6016 ,0,0,0}, {14522,13663,13667 ,6095,6098,6099 ,0,0,0}, - {13669,14521,14454 ,6025,6094,6014 ,0,0,0}, {14523,13667,13666 ,6096,6099,6100 ,0,0,0}, - {13663,14522,14521 ,6098,6095,6094 ,0,0,0}, {14524,13666,13676 ,6097,6100,6101 ,0,0,0}, - {13667,14523,14522 ,6099,6096,6095 ,0,0,0}, {14519,13676,13638 ,6092,6101,6102 ,0,0,0}, - {13666,14524,14523 ,6100,6097,6096 ,0,0,0}, {14486,13638,13672 ,6051,6102,6053 ,0,0,0}, - {13676,14519,14524 ,6101,6092,6097 ,0,0,0}, {13672,14484,14486 ,6053,6049,6051 ,0,0,0}, - {13638,14486,14519 ,6102,6051,6092 ,0,0,0}, {14525,14526,14527 ,730,6103,6103 ,0,0,0}, - {12755,12697,12694 ,6103,730,730 ,0,0,0}, {14528,14526,14529 ,6104,6103,6105 ,0,0,0}, - {14528,14530,14531 ,6104,6106,6103 ,0,0,0}, {14532,14527,14533 ,6107,6103,6108 ,0,0,0}, - {14530,14534,14535 ,6106,6109,6110 ,0,0,0}, {14536,14537,14533 ,6103,6111,6108 ,0,0,0}, - {14535,14538,14539 ,6110,6112,6110 ,0,0,0}, {14540,14536,14541 ,6111,6103,6103 ,0,0,0}, - {14539,14542,14543 ,6110,6113,6112 ,0,0,0}, {14543,14544,14545 ,6112,6109,6110 ,0,0,0}, - {14545,14546,14547 ,6110,6106,6114 ,0,0,0}, {14541,14548,14549 ,6103,730,6115 ,0,0,0}, - {14550,14547,14551 ,6105,6114,6104 ,0,0,0}, {14552,14553,14554 ,6111,730,6111 ,0,0,0}, - {14555,14547,14550 ,6111,6114,6105 ,0,0,0}, {14554,14556,14557 ,6111,6110,6114 ,0,0,0}, - {14558,14559,14560 ,730,6114,6108 ,0,0,0}, {12703,12768,12770 ,6110,6111,6110 ,0,0,0}, - {14561,14562,14563 ,6115,730,6111 ,0,0,0}, {12767,12702,12765 ,730,730,6114 ,0,0,0}, - {14564,14565,12686 ,6111,6110,6110 ,0,0,0}, {12698,12761,12700 ,730,6114,6103 ,0,0,0}, - {12683,12733,12730 ,730,730,6114 ,0,0,0}, {12697,12756,12759 ,730,730,6103 ,0,0,0}, - {12727,12679,12728 ,6114,730,730 ,0,0,0}, {12753,12755,12694 ,730,6103,730 ,0,0,0}, - {12677,12721,12674 ,6103,6103,730 ,0,0,0}, {12747,12749,12688 ,730,730,730 ,0,0,0}, - {12715,12712,12673 ,730,730,730 ,0,0,0}, {12741,12687,12667 ,730,730,730 ,0,0,0}, - {12671,12710,12709 ,730,730,730 ,0,0,0}, {12671,12672,12710 ,730,730,730 ,0,0,0}, - {12673,12712,12672 ,730,730,730 ,0,0,0}, {12741,12667,12705 ,730,730,730 ,0,0,0}, - {12667,12671,12706 ,730,730,730 ,0,0,0}, {12716,12674,12718 ,6103,730,730 ,0,0,0}, - {12673,12674,12716 ,730,730,6103 ,0,0,0}, {12687,12744,12688 ,730,730,730 ,0,0,0}, - {12687,12743,12744 ,730,730,730 ,0,0,0}, {12677,12679,12724 ,6103,730,6103 ,0,0,0}, - {12677,12724,12722 ,6103,6103,730 ,0,0,0}, {12694,12692,12750 ,730,730,6103 ,0,0,0}, - {12749,12692,12688 ,730,730,730 ,0,0,0}, {12683,12730,12680 ,730,6114,6103 ,0,0,0}, - {12679,12680,12728 ,730,6103,730 ,0,0,0}, {12697,12755,12756 ,730,6103,730 ,0,0,0}, - {12736,12734,12686 ,6110,6111,6110 ,0,0,0}, {12683,12686,12734 ,730,6110,6111 ,0,0,0}, - {12698,12759,12761 ,730,6103,6114 ,0,0,0}, {12697,12759,12698 ,730,6103,730 ,0,0,0}, - {14563,14566,14564 ,6111,6111,6111 ,0,0,0}, {14567,14564,14566 ,6114,6111,6111 ,0,0,0}, - {12761,12762,12700 ,6114,730,6103 ,0,0,0}, {12700,12765,12702 ,6103,6114,730 ,0,0,0}, - {12762,12765,12700 ,730,6114,6103 ,0,0,0}, {12767,12768,12702 ,730,6111,730 ,0,0,0}, - {14568,14560,14559 ,6107,6108,6114 ,0,0,0}, {12703,12702,12768 ,6110,730,6111 ,0,0,0}, - {12770,14556,12703 ,6110,6110,6110 ,0,0,0}, {14559,14555,14569 ,6114,6111,730 ,0,0,0}, - {14570,14571,14558 ,6111,6110,730 ,0,0,0}, {14571,14561,14563 ,6110,6115,6111 ,0,0,0}, - {14544,14546,14545 ,6109,6106,6110 ,0,0,0}, {12753,12694,12750 ,730,730,6103 ,0,0,0}, - {12750,12692,12749 ,6103,730,730 ,0,0,0}, {12747,12688,12744 ,730,730,730 ,0,0,0}, - {12743,12687,12741 ,730,730,730 ,0,0,0}, {12705,12667,12706 ,730,730,730 ,0,0,0}, - {12706,12671,12709 ,730,730,730 ,0,0,0}, {12710,12672,12712 ,730,730,730 ,0,0,0}, - {12715,12673,12716 ,730,730,6103 ,0,0,0}, {12718,12674,12721 ,730,730,6103 ,0,0,0}, - {12721,12677,12722 ,6103,6103,730 ,0,0,0}, {12724,12679,12727 ,6103,730,6114 ,0,0,0}, - {12728,12680,12730 ,730,6103,6114 ,0,0,0}, {12733,12683,12734 ,730,730,6111 ,0,0,0}, - {12736,12686,14565 ,6110,6110,6110 ,0,0,0}, {14565,14564,14567 ,6110,6111,6114 ,0,0,0}, - {14566,14563,14562 ,6111,6111,730 ,0,0,0}, {14561,14571,14570 ,6115,6110,6111 ,0,0,0}, - {14572,14558,14560 ,6111,730,6108 ,0,0,0}, {14558,14572,14570 ,730,6111,6111 ,0,0,0}, - {14568,14559,14569 ,6107,6114,730 ,0,0,0}, {14569,14555,14550 ,730,6111,6105 ,0,0,0}, - {14551,14547,14546 ,6104,6114,6106 ,0,0,0}, {14545,14539,14543 ,6110,6110,6112 ,0,0,0}, - {14542,14539,14538 ,6113,6110,6112 ,0,0,0}, {14538,14535,14534 ,6112,6110,6109 ,0,0,0}, - {14530,14535,14531 ,6106,6110,6103 ,0,0,0}, {14528,14531,14526 ,6104,6103,6103 ,0,0,0}, - {14525,14529,14526 ,730,6105,6103 ,0,0,0}, {14532,14525,14527 ,6107,730,6103 ,0,0,0}, - {14536,14533,14527 ,6103,6108,6103 ,0,0,0}, {14536,14540,14537 ,6103,6111,6111 ,0,0,0}, - {14541,14549,14540 ,6103,6115,6111 ,0,0,0}, {14541,14553,14548 ,6103,730,730 ,0,0,0}, - {14552,14554,14557 ,6111,6111,6114 ,0,0,0}, {14548,14553,14552 ,730,730,6111 ,0,0,0}, - {14556,14554,12703 ,6110,6111,6110 ,0,0,0}, {12739,12707,14573 ,6116,6117,6118 ,0,0,0}, - {12742,14574,14575 ,6119,6120,6121 ,0,0,0}, {14576,14577,12894 ,6122,6123,6124 ,0,0,0}, - {12984,12754,12981 ,6125,6126,6127 ,0,0,0}, {12910,12909,13321 ,6128,6129,6130 ,0,0,0}, - {12840,12843,12764 ,6131,6132,6122 ,0,0,0}, {14578,12845,14579 ,6133,6134,6135 ,0,0,0}, - {14580,14581,14582 ,6136,6137,6138 ,0,0,0}, {12711,12791,12794 ,6122,6120,6139 ,0,0,0}, - {14577,12879,12884 ,6123,6140,6141 ,0,0,0}, {14583,12962,12964 ,6139,6142,6143 ,0,0,0}, - {13234,14584,13235 ,6144,6145,6146 ,0,0,0}, {13292,14585,13285 ,6147,6148,6149 ,0,0,0}, - {12812,14586,12815 ,6150,6144,6150 ,0,0,0}, {14587,12870,13269 ,6151,6134,6152 ,0,0,0}, - {14588,12771,14589 ,6145,6153,6154 ,0,0,0}, {14587,13269,14590 ,6151,6152,6155 ,0,0,0}, - {14591,13269,13268 ,6156,6152,6157 ,0,0,0}, {14592,14593,14594 ,6158,6144,6159 ,0,0,0}, - {14595,14596,14597 ,6160,6161,6162 ,0,0,0}, {13268,14598,14591 ,6157,6163,6156 ,0,0,0}, - {14599,14600,13268 ,6158,6164,6157 ,0,0,0}, {13274,14601,14599 ,6155,6165,6158 ,0,0,0}, - {14602,13279,14603 ,6166,6167,6116 ,0,0,0}, {13274,14599,13268 ,6155,6158,6157 ,0,0,0}, - {13286,14603,13279 ,6168,6116,6167 ,0,0,0}, {14594,14582,14581 ,6159,6138,6137 ,0,0,0}, - {14604,14605,14606 ,6122,6169,6170 ,0,0,0}, {14607,13274,13272 ,6171,6155,6172 ,0,0,0}, - {13272,14608,14607 ,6172,6118,6171 ,0,0,0}, {14609,14610,13282 ,6173,6174,6175 ,0,0,0}, - {13272,13271,14608 ,6172,6176,6118 ,0,0,0}, {13271,14610,14611 ,6176,6174,6177 ,0,0,0}, - {14612,12935,12934 ,6120,6146,6154 ,0,0,0}, {13271,13282,14610 ,6176,6175,6174 ,0,0,0}, - {14609,13282,13277 ,6173,6175,6178 ,0,0,0}, {14589,12773,14613 ,6154,6120,6145 ,0,0,0}, - {14614,14615,14616 ,6177,6179,6180 ,0,0,0}, {14617,14609,13277 ,6181,6173,6178 ,0,0,0}, - {14615,14618,14604 ,6179,6182,6122 ,0,0,0}, {14592,14619,14593 ,6158,6183,6144 ,0,0,0}, - {14606,14605,14620 ,6170,6169,6184 ,0,0,0}, {13286,13285,14621 ,6168,6149,6185 ,0,0,0}, - {14622,12719,14623 ,6186,6187,6119 ,0,0,0}, {12815,14624,12816 ,6150,6144,6188 ,0,0,0}, - {14625,13237,14626 ,6145,6144,6150 ,0,0,0}, {14619,13002,14627 ,6183,6189,6190 ,0,0,0}, - {13232,14628,14629 ,6154,6120,6127 ,0,0,0}, {12969,12968,13332 ,6191,6142,6192 ,0,0,0}, - {14574,12742,12740 ,6120,6119,6122 ,0,0,0}, {13326,12900,12899 ,6193,6194,6195 ,0,0,0}, - {12971,13227,13221 ,6196,6186,6197 ,0,0,0}, {12847,12769,12766 ,6196,6134,6138 ,0,0,0}, - {14577,12998,12993 ,6123,6198,6199 ,0,0,0}, {12764,12843,12766 ,6122,6132,6138 ,0,0,0}, - {12839,12840,12763 ,6157,6131,6137 ,0,0,0}, {12839,12763,12760 ,6157,6137,6131 ,0,0,0}, - {12758,12837,12760 ,6200,6143,6131 ,0,0,0}, {12746,12957,12975 ,6117,6201,6202 ,0,0,0}, - {14580,14630,14631 ,6136,6200,6156 ,0,0,0}, {12831,14632,12826 ,6118,6203,6132 ,0,0,0}, - {14633,12833,12835 ,6133,6204,6133 ,0,0,0}, {12763,12840,12764 ,6137,6131,6122 ,0,0,0}, - {12843,12847,12766 ,6132,6196,6138 ,0,0,0}, {12833,14634,12828 ,6204,6153,6201 ,0,0,0}, - {14635,12826,14632 ,6201,6132,6203 ,0,0,0}, {12748,12746,12975 ,6187,6117,6202 ,0,0,0}, - {12760,12837,12839 ,6131,6143,6157 ,0,0,0}, {12822,13252,13254 ,6132,6144,6205 ,0,0,0}, - {12835,12987,14633 ,6133,6201,6133 ,0,0,0}, {12758,12987,12837 ,6200,6201,6143 ,0,0,0}, - {13259,12821,13254 ,6206,6116,6205 ,0,0,0}, {12853,13259,13261 ,6207,6206,6204 ,0,0,0}, - {14636,14637,12827 ,6132,6119,6207 ,0,0,0}, {13252,12822,12826 ,6144,6132,6132 ,0,0,0}, - {12821,13259,12851 ,6116,6206,6121 ,0,0,0}, {12821,12822,13254 ,6116,6132,6205 ,0,0,0}, - {13262,12857,13261 ,6208,6207,6204 ,0,0,0}, {12853,12851,13259 ,6207,6121,6206 ,0,0,0}, - {12854,12853,13261 ,6209,6207,6204 ,0,0,0}, {13262,13264,12860 ,6208,6142,6196 ,0,0,0}, - {12857,12854,13261 ,6207,6209,6204 ,0,0,0}, {12859,12857,13262 ,6133,6207,6208 ,0,0,0}, - {13262,12860,12859 ,6208,6196,6133 ,0,0,0}, {13264,12863,12860 ,6142,6134,6196 ,0,0,0}, - {13267,12865,13264 ,6148,6131,6142 ,0,0,0}, {13264,12865,12863 ,6142,6131,6134 ,0,0,0}, - {13267,12866,12865 ,6148,6205,6131 ,0,0,0}, {12866,13267,12869 ,6205,6148,6204 ,0,0,0}, - {13267,12870,12869 ,6148,6134,6204 ,0,0,0}, {14591,14590,13269 ,6156,6155,6152 ,0,0,0}, - {14607,14601,13274 ,6171,6165,6155 ,0,0,0}, {14600,14598,13268 ,6164,6163,6157 ,0,0,0}, - {14608,13271,14611 ,6118,6176,6177 ,0,0,0}, {14602,14638,13277 ,6166,6210,6178 ,0,0,0}, - {14639,13291,14640 ,6157,6190,6211 ,0,0,0}, {14617,14641,14642 ,6181,6212,6182 ,0,0,0}, - {12883,14577,12884 ,6174,6123,6141 ,0,0,0}, {14643,14644,14577 ,6213,6214,6123 ,0,0,0}, - {13329,13326,12873 ,6215,6193,6216 ,0,0,0}, {13012,13014,12874 ,6217,6218,6219 ,0,0,0}, - {12899,12873,13326 ,6195,6216,6193 ,0,0,0}, {12904,12903,13318 ,6220,6221,6222 ,0,0,0}, - {12900,13325,12903 ,6194,6223,6221 ,0,0,0}, {13321,12909,12906 ,6130,6129,6181 ,0,0,0}, - {12906,13318,13321 ,6181,6222,6130 ,0,0,0}, {12915,13322,12916 ,6224,6225,6226 ,0,0,0}, - {12912,13321,13322 ,6227,6130,6225 ,0,0,0}, {12992,14577,12993 ,6212,6123,6199 ,0,0,0}, - {12923,14645,12924 ,6203,6228,6201 ,0,0,0}, {13014,12875,12874 ,6218,6229,6219 ,0,0,0}, - {14646,14647,14648 ,6230,6231,6232 ,0,0,0}, {13014,13015,13294 ,6218,6200,6233 ,0,0,0}, - {12915,12912,13322 ,6224,6227,6225 ,0,0,0}, {13322,12918,12916 ,6225,6234,6226 ,0,0,0}, - {12912,12910,13321 ,6227,6128,6130 ,0,0,0}, {12992,12991,14577 ,6212,6235,6123 ,0,0,0}, - {12904,13318,12906 ,6220,6222,6181 ,0,0,0}, {13325,13318,12903 ,6223,6222,6221 ,0,0,0}, - {13326,13325,12900 ,6193,6223,6194 ,0,0,0}, {12875,13329,12873 ,6229,6215,6216 ,0,0,0}, - {13329,12875,13294 ,6215,6229,6233 ,0,0,0}, {14644,12999,14577 ,6214,6236,6123 ,0,0,0}, - {13002,12999,14627 ,6189,6236,6190 ,0,0,0}, {14577,14649,14650 ,6123,6170,6214 ,0,0,0}, - {12891,14577,12887 ,6237,6123,6167 ,0,0,0}, {14576,14649,14577 ,6122,6170,6123 ,0,0,0}, - {12893,14651,14652 ,6238,6180,6179 ,0,0,0}, {14653,12930,14654 ,6197,6165,6196 ,0,0,0}, - {14655,12735,14656 ,6131,6122,6132 ,0,0,0}, {12898,14657,14651 ,6239,6240,6180 ,0,0,0}, - {14658,14659,14597 ,6171,6152,6162 ,0,0,0}, {12726,14660,12725 ,6204,6208,6126 ,0,0,0}, - {14661,14620,14662 ,6241,6184,6136 ,0,0,0}, {14663,12941,12944 ,6179,6179,6202 ,0,0,0}, - {12953,14660,12952 ,6127,6208,6242 ,0,0,0}, {13078,14664,14665 ,6156,6200,6136 ,0,0,0}, - {13081,13083,14666 ,6137,6135,6133 ,0,0,0}, {14667,14668,14669 ,6207,6133,6208 ,0,0,0}, - {13039,13072,13075 ,6196,6158,6159 ,0,0,0}, {13062,13032,13027 ,6181,6243,6139 ,0,0,0}, - {13046,13048,14670 ,6244,6245,6246 ,0,0,0}, {13025,14671,14672 ,6247,6190,6136 ,0,0,0}, - {14673,14647,14674 ,6248,6231,6170 ,0,0,0}, {14675,14676,13054 ,6152,6249,6250 ,0,0,0}, - {14677,14647,14673 ,6251,6231,6248 ,0,0,0}, {14678,14679,14680 ,6252,6253,6254 ,0,0,0}, - {14679,14646,14680 ,6253,6230,6254 ,0,0,0}, {14681,14682,14683 ,6255,6256,6257 ,0,0,0}, - {14684,14685,14686 ,6258,6259,6260 ,0,0,0}, {14679,14678,14686 ,6253,6252,6260 ,0,0,0}, - {14686,14685,14679 ,6260,6259,6253 ,0,0,0}, {14685,14684,14687 ,6259,6258,6261 ,0,0,0}, - {14688,14683,14689 ,6262,6257,6263 ,0,0,0}, {14687,14689,14685 ,6261,6263,6259 ,0,0,0}, - {14683,14682,14689 ,6257,6256,6263 ,0,0,0}, {14690,14691,14682 ,6264,6265,6256 ,0,0,0}, - {14687,14688,14689 ,6261,6262,6263 ,0,0,0}, {14681,14690,14682 ,6255,6264,6256 ,0,0,0}, - {14680,14646,14648 ,6254,6230,6232 ,0,0,0}, {14692,14693,13055 ,6138,6134,6266 ,0,0,0}, - {14648,14647,14677 ,6232,6231,6251 ,0,0,0}, {14674,14693,14692 ,6170,6134,6138 ,0,0,0}, - {14694,13048,13049 ,6267,6245,6268 ,0,0,0}, {13026,14672,14695 ,6167,6136,6199 ,0,0,0}, - {13043,13046,14671 ,6235,6244,6190 ,0,0,0}, {14696,13097,14697 ,6197,6164,6191 ,0,0,0}, - {13091,13090,14698 ,6171,6118,6269 ,0,0,0}, {13036,13033,13066 ,6270,6270,6174 ,0,0,0}, - {14696,13099,13097 ,6197,6163,6164 ,0,0,0}, {13071,13036,13066 ,6127,6270,6174 ,0,0,0}, - {14699,14631,14630 ,6137,6156,6200 ,0,0,0}, {14700,14701,14702 ,6213,6271,6169 ,0,0,0}, - {13060,13062,14703 ,6173,6181,6272 ,0,0,0}, {13102,13099,14696 ,6156,6163,6197 ,0,0,0}, - {14692,14704,14674 ,6138,6273,6170 ,0,0,0}, {14705,13103,13102 ,6201,6155,6156 ,0,0,0}, - {14705,13107,13105 ,6201,6134,6151 ,0,0,0}, {14706,14660,14707 ,6214,6208,6133 ,0,0,0}, - {14706,12720,12723 ,6214,6208,6117 ,0,0,0}, {14708,14709,14710 ,6190,6214,6199 ,0,0,0}, - {13097,13096,14697 ,6164,6158,6191 ,0,0,0}, {13091,14698,14697 ,6171,6269,6191 ,0,0,0}, - {14711,14712,14713 ,6274,6118,6183 ,0,0,0}, {14714,14715,14716 ,6149,6275,6214 ,0,0,0}, - {14717,14673,14704 ,6243,6248,6273 ,0,0,0}, {14717,14704,14718 ,6243,6273,6276 ,0,0,0}, - {14716,14606,14620 ,6214,6170,6184 ,0,0,0}, {14604,14618,14605 ,6122,6182,6169 ,0,0,0}, - {14616,14719,14614 ,6180,6244,6177 ,0,0,0}, {14615,14614,14618 ,6179,6177,6182 ,0,0,0}, - {14592,14720,13003 ,6158,6127,6249 ,0,0,0}, {12898,14719,14657 ,6239,6244,6240 ,0,0,0}, - {14616,14657,14719 ,6180,6240,6244 ,0,0,0}, {12898,14651,12895 ,6239,6180,6277 ,0,0,0}, - {14592,13003,13002 ,6158,6249,6189 ,0,0,0}, {12894,12893,14652 ,6124,6238,6179 ,0,0,0}, - {12893,12895,14651 ,6238,6277,6180 ,0,0,0}, {13021,13289,13297 ,6278,6279,6280 ,0,0,0}, - {13289,14640,13291 ,6279,6211,6190 ,0,0,0}, {14576,12894,14652 ,6122,6124,6179 ,0,0,0}, - {14721,14577,14650 ,6275,6123,6214 ,0,0,0}, {12894,14577,12891 ,6124,6123,6237 ,0,0,0}, - {13295,13018,13297 ,6281,6282,6280 ,0,0,0}, {13005,14720,14722 ,6283,6127,6174 ,0,0,0}, - {13003,14720,13005 ,6249,6127,6283 ,0,0,0}, {14593,14582,14594 ,6144,6138,6159 ,0,0,0}, - {14580,14631,14581 ,6136,6156,6137 ,0,0,0}, {14699,14578,14579 ,6137,6133,6135 ,0,0,0}, - {14578,14699,14630 ,6133,6137,6200 ,0,0,0}, {14578,12769,12845 ,6133,6134,6134 ,0,0,0}, - {13252,14635,13250 ,6144,6201,6209 ,0,0,0}, {12845,12769,12847 ,6134,6134,6196 ,0,0,0}, - {12987,12758,12986 ,6201,6200,6158 ,0,0,0}, {12751,12748,12978 ,6208,6187,6284 ,0,0,0}, - {12984,12986,12757 ,6125,6158,6204 ,0,0,0}, {14723,13247,13248 ,6191,6165,6179 ,0,0,0}, - {13245,14724,13222 ,6142,6172,6197 ,0,0,0}, {12969,13227,12971 ,6191,6186,6196 ,0,0,0}, - {13332,13227,12969 ,6192,6186,6191 ,0,0,0}, {13332,12968,13230 ,6192,6142,6285 ,0,0,0}, - {14725,12965,12962 ,6192,6228,6142 ,0,0,0}, {12791,12711,12713 ,6120,6122,6119 ,0,0,0}, - {12714,12789,12713 ,6171,6202,6119 ,0,0,0}, {14726,13242,13240 ,6150,6144,6150 ,0,0,0}, - {14586,12812,12810 ,6144,6150,6187 ,0,0,0}, {12818,12816,14624 ,6150,6188,6144 ,0,0,0}, - {12810,14727,14586 ,6187,6144,6144 ,0,0,0}, {12784,14622,14728 ,6165,6186,6286 ,0,0,0}, - {14727,12806,14729 ,6144,6192,6144 ,0,0,0}, {12804,12803,14729 ,6145,6145,6144 ,0,0,0}, - {14730,14731,14660 ,6143,6133,6208 ,0,0,0}, {14612,14732,12935 ,6120,6176,6146 ,0,0,0}, - {14655,12732,12735 ,6131,6137,6122 ,0,0,0}, {12738,13083,13082 ,6134,6135,6134 ,0,0,0}, - {14654,12925,12924 ,6196,6139,6201 ,0,0,0}, {14653,12931,12928 ,6197,6286,6165 ,0,0,0}, - {14663,12944,14733 ,6179,6202,6139 ,0,0,0}, {12947,14733,12946 ,6203,6139,6228 ,0,0,0}, - {13081,14666,14664 ,6137,6133,6200 ,0,0,0}, {14664,13078,13081 ,6200,6156,6137 ,0,0,0}, - {14734,14735,14736 ,6209,6207,6166 ,0,0,0}, {14737,13076,14665 ,6138,6137,6136 ,0,0,0}, - {14732,12937,12935 ,6176,6191,6146 ,0,0,0}, {14738,14739,14740 ,6186,6228,6287 ,0,0,0}, - {12931,14653,14612 ,6286,6197,6120 ,0,0,0}, {12931,14612,12934 ,6286,6120,6154 ,0,0,0}, - {12930,14653,12928 ,6165,6197,6165 ,0,0,0}, {12925,14654,12930 ,6139,6196,6165 ,0,0,0}, - {14645,12923,12941 ,6228,6203,6179 ,0,0,0}, {14645,14654,12924 ,6228,6196,6201 ,0,0,0}, - {12729,14660,12726 ,6200,6208,6204 ,0,0,0}, {14663,14645,12941 ,6179,6228,6179 ,0,0,0}, - {14741,14733,12947 ,6133,6139,6203 ,0,0,0}, {12946,14733,12944 ,6228,6139,6202 ,0,0,0}, - {12729,12731,14660 ,6200,6131,6208 ,0,0,0}, {14660,14742,12952 ,6208,6207,6242 ,0,0,0}, - {12737,13082,14743 ,6138,6134,6196 ,0,0,0}, {14660,12731,12732 ,6208,6131,6137 ,0,0,0}, - {14660,12723,12725 ,6208,6117,6126 ,0,0,0}, {12720,14706,14623 ,6208,6214,6119 ,0,0,0}, - {14660,14706,12723 ,6208,6214,6117 ,0,0,0}, {14588,12800,12771 ,6145,6120,6153 ,0,0,0}, - {14744,14745,12775 ,6201,6121,6288 ,0,0,0}, {12719,12720,14623 ,6187,6208,6119 ,0,0,0}, - {14746,12777,12779 ,6139,6192,6131 ,0,0,0}, {14613,12775,14745 ,6145,6288,6121 ,0,0,0}, - {12810,12809,14727 ,6187,6145,6144 ,0,0,0}, {12809,12806,14727 ,6145,6192,6144 ,0,0,0}, - {12803,12800,14588 ,6145,6120,6145 ,0,0,0}, {14745,14747,14613 ,6121,6289,6145 ,0,0,0}, - {14738,14747,14748 ,6186,6289,6191 ,0,0,0}, {14745,14748,14747 ,6121,6191,6289 ,0,0,0}, - {14738,14740,14732 ,6186,6287,6176 ,0,0,0}, {14738,14748,14739 ,6186,6191,6228 ,0,0,0}, - {12937,14732,14740 ,6191,6176,6287 ,0,0,0}, {14749,12740,12739 ,6202,6122,6116 ,0,0,0}, - {14750,14751,13220 ,6165,6191,6187 ,0,0,0}, {14752,13248,13250 ,6126,6179,6209 ,0,0,0}, - {14753,14628,13230 ,6154,6120,6285 ,0,0,0}, {12957,12746,14754 ,6201,6117,6120 ,0,0,0}, - {14755,14756,12959 ,6197,6201,6207 ,0,0,0}, {14575,14754,12745 ,6121,6120,6171 ,0,0,0}, - {12708,12796,12795 ,6116,6120,6201 ,0,0,0}, {14575,12745,12742 ,6121,6171,6119 ,0,0,0}, - {12748,12975,12978 ,6187,6202,6284 ,0,0,0}, {12978,12980,12751 ,6284,6140,6208 ,0,0,0}, - {12752,12980,12981 ,6117,6140,6127 ,0,0,0}, {12752,12981,12754 ,6117,6127,6126 ,0,0,0}, - {12754,12984,12757 ,6126,6125,6204 ,0,0,0}, {12758,12757,12986 ,6200,6204,6158 ,0,0,0}, - {12835,12837,12987 ,6133,6143,6201 ,0,0,0}, {12831,12827,14637 ,6118,6207,6119 ,0,0,0}, - {12833,14633,14634 ,6204,6133,6153 ,0,0,0}, {14636,12827,12828 ,6132,6207,6201 ,0,0,0}, - {14636,12828,14634 ,6132,6201,6153 ,0,0,0}, {14632,12831,14637 ,6203,6118,6119 ,0,0,0}, - {12826,14635,13252 ,6132,6201,6144 ,0,0,0}, {14752,13250,14635 ,6126,6209,6201 ,0,0,0}, - {14757,13247,14723 ,6242,6165,6191 ,0,0,0}, {14723,13248,14752 ,6191,6179,6126 ,0,0,0}, - {13245,14757,14758 ,6142,6242,6197 ,0,0,0}, {14757,13245,13247 ,6242,6142,6165 ,0,0,0}, - {14724,14750,13222 ,6172,6165,6197 ,0,0,0}, {14758,14724,13245 ,6197,6172,6142 ,0,0,0}, - {13220,14751,13221 ,6187,6191,6197 ,0,0,0}, {13222,14750,13220 ,6197,6165,6187 ,0,0,0}, - {12971,13221,14759 ,6196,6197,6202 ,0,0,0}, {13221,14751,14759 ,6197,6191,6202 ,0,0,0}, - {14619,14592,13002 ,6183,6158,6189 ,0,0,0}, {14722,14760,14761 ,6174,6118,6273 ,0,0,0}, - {12996,14577,12999 ,6290,6123,6236 ,0,0,0}, {14644,14627,12999 ,6214,6190,6236 ,0,0,0}, - {12996,12998,14577 ,6290,6198,6123 ,0,0,0}, {12888,14577,12883 ,6152,6123,6174 ,0,0,0}, - {13009,13012,12880 ,6124,6217,6291 ,0,0,0}, {12991,12879,14577 ,6235,6140,6123 ,0,0,0}, - {13009,12880,12879 ,6124,6291,6140 ,0,0,0}, {13009,12879,12991 ,6124,6140,6235 ,0,0,0}, - {13012,12874,12880 ,6217,6219,6291 ,0,0,0}, {13014,13294,12875 ,6218,6233,6229 ,0,0,0}, - {13015,13018,13295 ,6200,6282,6281 ,0,0,0}, {13015,13295,13294 ,6200,6281,6233 ,0,0,0}, - {13020,13021,13297 ,6269,6278,6280 ,0,0,0}, {13018,13020,13297 ,6282,6269,6280 ,0,0,0}, - {13289,13021,14762 ,6279,6278,6292 ,0,0,0}, {14762,14640,13289 ,6292,6211,6279 ,0,0,0}, - {14763,13291,14639 ,6293,6190,6157 ,0,0,0}, {13292,14763,14764 ,6147,6293,6266 ,0,0,0}, - {14763,13292,13291 ,6293,6147,6190 ,0,0,0}, {14585,14765,13285 ,6148,6273,6149 ,0,0,0}, - {14764,14585,13292 ,6266,6148,6147 ,0,0,0}, {14621,14766,13286 ,6185,6294,6168 ,0,0,0}, - {14765,14621,13285 ,6273,6185,6149 ,0,0,0}, {13277,13279,14602 ,6178,6167,6166 ,0,0,0}, - {14766,14603,13286 ,6294,6116,6168 ,0,0,0}, {14638,14617,13277 ,6210,6181,6178 ,0,0,0}, - {14642,14641,14760 ,6182,6212,6118 ,0,0,0}, {14638,14641,14617 ,6210,6212,6181 ,0,0,0}, - {14722,14761,13005 ,6174,6273,6283 ,0,0,0}, {14760,14641,14761 ,6118,6212,6273 ,0,0,0}, - {13027,14695,14703 ,6139,6199,6272 ,0,0,0}, {13058,14767,13087 ,6174,6295,6177 ,0,0,0}, - {14658,14717,14718 ,6171,6243,6276 ,0,0,0}, {13093,13091,14697 ,6165,6171,6191 ,0,0,0}, - {14767,13058,14768 ,6295,6174,6162 ,0,0,0}, {14703,13062,13027 ,6272,6181,6139 ,0,0,0}, - {13026,14695,13027 ,6167,6199,6139 ,0,0,0}, {13025,14672,13026 ,6247,6136,6167 ,0,0,0}, - {13043,14671,13025 ,6235,6190,6247 ,0,0,0}, {14670,14671,13046 ,6246,6190,6244 ,0,0,0}, - {14694,14670,13048 ,6267,6246,6245 ,0,0,0}, {13049,13052,14676 ,6268,6185,6249 ,0,0,0}, - {14676,14694,13049 ,6249,6267,6268 ,0,0,0}, {13055,14675,13054 ,6266,6152,6250 ,0,0,0}, - {13054,14676,13052 ,6250,6249,6185 ,0,0,0}, {13055,14693,14675 ,6266,6134,6152 ,0,0,0}, - {14673,14674,14704 ,6248,6170,6273 ,0,0,0}, {14661,14769,14620 ,6241,6296,6184 ,0,0,0}, - {14658,14718,14659 ,6171,6276,6152 ,0,0,0}, {14661,14662,14770 ,6241,6136,6200 ,0,0,0}, - {14770,14596,14595 ,6200,6161,6160 ,0,0,0}, {14595,14597,14659 ,6160,6162,6152 ,0,0,0}, - {14770,14662,14596 ,6200,6136,6161 ,0,0,0}, {14769,14714,14716 ,6296,6149,6214 ,0,0,0}, - {14716,14620,14769 ,6214,6184,6296 ,0,0,0}, {14701,14715,14714 ,6271,6275,6149 ,0,0,0}, - {14702,14709,14700 ,6169,6214,6213 ,0,0,0}, {14701,14700,14715 ,6271,6213,6275 ,0,0,0}, - {14710,14711,14708 ,6199,6274,6190 ,0,0,0}, {14702,14710,14709 ,6169,6199,6214 ,0,0,0}, - {14713,14712,14771 ,6183,6118,6144 ,0,0,0}, {14708,14711,14713 ,6190,6274,6183 ,0,0,0}, - {13039,14771,14712 ,6196,6144,6118 ,0,0,0}, {12714,12717,12788 ,6171,6117,6139 ,0,0,0}, - {14624,12820,12818 ,6144,6150,6150 ,0,0,0}, {14624,12815,14586 ,6144,6150,6144 ,0,0,0}, - {12785,12788,12717 ,6197,6139,6117 ,0,0,0}, {12719,14622,12785 ,6187,6186,6197 ,0,0,0}, - {14588,14729,12803 ,6145,6144,6145 ,0,0,0}, {12806,12804,14729 ,6192,6145,6144 ,0,0,0}, - {12773,12775,14613 ,6120,6288,6145 ,0,0,0}, {12771,12773,14589 ,6153,6120,6154 ,0,0,0}, - {12779,12784,14728 ,6131,6165,6286 ,0,0,0}, {12781,14772,14744 ,6144,6242,6201 ,0,0,0}, - {14744,12775,12781 ,6201,6288,6144 ,0,0,0}, {14728,14746,12779 ,6286,6139,6131 ,0,0,0}, - {12777,14746,14772 ,6192,6139,6242 ,0,0,0}, {12777,14772,12781 ,6192,6242,6144 ,0,0,0}, - {12784,12785,14622 ,6165,6197,6186 ,0,0,0}, {12717,12719,12785 ,6117,6187,6197 ,0,0,0}, - {12714,12788,12789 ,6171,6139,6202 ,0,0,0}, {12713,12789,12791 ,6119,6202,6120 ,0,0,0}, - {12796,12708,12794 ,6120,6116,6139 ,0,0,0}, {12711,12794,12708 ,6122,6139,6116 ,0,0,0}, - {12708,12795,12707 ,6116,6201,6117 ,0,0,0}, {12740,14749,14574 ,6122,6202,6120 ,0,0,0}, - {12707,12795,14573 ,6117,6201,6118 ,0,0,0}, {14749,12739,14573 ,6202,6116,6118 ,0,0,0}, - {14754,12746,12745 ,6120,6117,6171 ,0,0,0}, {14755,12958,14754 ,6197,6197,6120 ,0,0,0}, - {12957,14754,12958 ,6201,6120,6197 ,0,0,0}, {12965,14773,12968 ,6228,6145,6142 ,0,0,0}, - {12964,12959,14756 ,6143,6207,6201 ,0,0,0}, {12959,12958,14755 ,6207,6197,6197 ,0,0,0}, - {14725,12962,14583 ,6192,6142,6139 ,0,0,0}, {14583,12964,14756 ,6139,6143,6201 ,0,0,0}, - {12965,14725,14773 ,6228,6192,6145 ,0,0,0}, {14753,13230,12968 ,6154,6285,6142 ,0,0,0}, - {14753,12968,14773 ,6154,6142,6145 ,0,0,0}, {14628,13232,13230 ,6120,6154,6285 ,0,0,0}, - {13234,14629,14774 ,6144,6127,6187 ,0,0,0}, {14629,13234,13232 ,6127,6144,6154 ,0,0,0}, - {14774,14584,13234 ,6187,6145,6144 ,0,0,0}, {13235,14775,14626 ,6146,6145,6150 ,0,0,0}, - {14584,14775,13235 ,6145,6145,6146 ,0,0,0}, {13235,14626,13237 ,6146,6150,6144 ,0,0,0}, - {13240,13237,14776 ,6150,6144,6146 ,0,0,0}, {14625,14776,13237 ,6145,6146,6144 ,0,0,0}, - {13240,14777,14726 ,6150,6144,6150 ,0,0,0}, {13240,14776,14777 ,6150,6146,6144 ,0,0,0}, - {14778,13242,14779 ,6150,6144,6150 ,0,0,0}, {13242,14726,14779 ,6144,6150,6150 ,0,0,0}, - {12820,13242,14778 ,6150,6144,6150 ,0,0,0}, {14780,14781,14782 ,6131,6203,6207 ,0,0,0}, - {14737,14771,13075 ,6138,6144,6159 ,0,0,0}, {14705,13102,14696 ,6201,6156,6197 ,0,0,0}, - {14705,13105,13103 ,6201,6151,6155 ,0,0,0}, {14771,13039,13075 ,6144,6196,6159 ,0,0,0}, - {13060,14768,13058 ,6173,6162,6174 ,0,0,0}, {13087,14767,13090 ,6177,6295,6118 ,0,0,0}, - {13096,13093,14697 ,6158,6165,6191 ,0,0,0}, {14767,14698,13090 ,6295,6269,6118 ,0,0,0}, - {14768,13060,14703 ,6162,6173,6272 ,0,0,0}, {13062,13068,13032 ,6181,6182,6243 ,0,0,0}, - {13071,13072,13037 ,6127,6158,6297 ,0,0,0}, {13064,13030,13068 ,6118,6155,6182 ,0,0,0}, - {13032,13068,13030 ,6243,6182,6155 ,0,0,0}, {13064,13066,13033 ,6118,6174,6270 ,0,0,0}, - {13033,13030,13064 ,6270,6155,6118 ,0,0,0}, {13036,13071,13037 ,6270,6127,6297 ,0,0,0}, - {13039,13037,13072 ,6196,6297,6158 ,0,0,0}, {14737,13075,13076 ,6138,6159,6137 ,0,0,0}, - {14665,13076,13078 ,6136,6137,6156 ,0,0,0}, {14783,14784,14785 ,6205,6132,6116 ,0,0,0}, - {14784,14741,14786 ,6132,6133,6132 ,0,0,0}, {12732,14655,14660 ,6137,6131,6208 ,0,0,0}, - {14666,13083,12738 ,6133,6135,6134 ,0,0,0}, {12737,14743,14656 ,6138,6196,6132 ,0,0,0}, - {12737,12738,13082 ,6138,6134,6134 ,0,0,0}, {14656,12735,12737 ,6132,6122,6138 ,0,0,0}, - {14660,14655,14787 ,6208,6131,6157 ,0,0,0}, {14787,14730,14660 ,6157,6143,6208 ,0,0,0}, - {14786,12950,14788 ,6132,6172,6118 ,0,0,0}, {14789,14790,14660 ,6204,6201,6208 ,0,0,0}, - {14660,14791,14792 ,6208,6172,6214 ,0,0,0}, {14660,14790,14742 ,6208,6201,6207 ,0,0,0}, - {14791,14660,12953 ,6172,6208,6127 ,0,0,0}, {12952,14742,12950 ,6242,6207,6172 ,0,0,0}, - {14788,12950,14742 ,6118,6172,6207 ,0,0,0}, {14786,14741,12947 ,6132,6133,6203 ,0,0,0}, - {12947,12950,14786 ,6203,6172,6132 ,0,0,0}, {14784,14783,14741 ,6132,6205,6133 ,0,0,0}, - {14734,14785,14793 ,6209,6116,6121 ,0,0,0}, {14785,14734,14783 ,6116,6209,6205 ,0,0,0}, - {14793,14735,14734 ,6121,6207,6209 ,0,0,0}, {14736,14794,14667 ,6166,6209,6207 ,0,0,0}, - {14735,14794,14736 ,6207,6209,6166 ,0,0,0}, {14736,14667,14669 ,6166,6207,6208 ,0,0,0}, - {14782,14669,14795 ,6207,6208,6196 ,0,0,0}, {14668,14795,14669 ,6133,6196,6208 ,0,0,0}, - {14782,14796,14780 ,6207,6134,6131 ,0,0,0}, {14782,14795,14796 ,6207,6196,6134 ,0,0,0}, - {14797,14781,14798 ,6204,6203,6205 ,0,0,0}, {14781,14780,14798 ,6203,6131,6205 ,0,0,0}, - {13107,14781,14797 ,6134,6203,6204 ,0,0,0}, {14577,12888,12887 ,6123,6152,6167 ,0,0,0}, - {14577,14721,14643 ,6123,6275,6213 ,0,0,0}, {12980,12752,12751 ,6140,6117,6208 ,0,0,0}, - {14660,14731,14789 ,6208,6133,6204 ,0,0,0}, {14660,14792,14707 ,6208,6214,6133 ,0,0,0}, - {14799,13483,13482 ,6298,6299,6299 ,0,0,0}, {13488,14800,13489 ,6298,6298,6300 ,0,0,0}, - {14801,14802,13180 ,6301,6302,6302 ,0,0,0}, {13482,13479,14803 ,6299,6300,6303 ,0,0,0}, - {13177,14804,14805 ,6304,6304,6305 ,0,0,0}, {13473,14806,13476 ,6301,6299,6306 ,0,0,0}, - {13175,14807,14808 ,6305,6307,6308 ,0,0,0}, {14809,13470,13467 ,6298,6298,6309 ,0,0,0}, - {14810,13163,14811 ,6310,6311,6312 ,0,0,0}, {14812,14813,13169 ,6308,6313,6314 ,0,0,0}, - {13159,13583,14814 ,6315,6316,6317 ,0,0,0}, {14814,14815,13166 ,6317,6318,6319 ,0,0,0}, - {13154,13578,13580 ,6320,6321,6322 ,0,0,0}, {13538,13121,13536 ,6299,6303,6323 ,0,0,0}, - {13542,13544,13124 ,6324,6298,6306 ,0,0,0}, {13144,13568,13569 ,6325,6326,6327 ,0,0,0}, - {13545,13548,13132 ,6298,6328,6324 ,0,0,0}, {13560,13562,13141 ,6301,6329,6330 ,0,0,0}, - {13560,13215,13557 ,6301,6324,6331 ,0,0,0}, {13134,13554,13556 ,6332,6328,6333 ,0,0,0}, - {13554,13137,13551 ,6328,6334,6335 ,0,0,0}, {13563,13214,13562 ,6336,6298,6329 ,0,0,0}, - {13557,13142,13556 ,6331,6337,6333 ,0,0,0}, {13143,13566,13568 ,6338,6339,6326 ,0,0,0}, - {13563,13566,13146 ,6336,6339,6324 ,0,0,0}, {13548,13550,13128 ,6328,6328,6299 ,0,0,0}, - {13550,13551,13129 ,6328,6335,6340 ,0,0,0}, {13150,13572,13574 ,6341,6342,6343 ,0,0,0}, - {13152,13569,13572 ,6344,6327,6342 ,0,0,0}, {13574,13575,13148 ,6343,6345,6346 ,0,0,0}, - {13544,13545,13131 ,6298,6298,6347 ,0,0,0}, {13539,13542,13127 ,6348,6324,6316 ,0,0,0}, - {13156,13575,13578 ,6349,6345,6321 ,0,0,0}, {13155,13580,13581 ,6350,6322,6351 ,0,0,0}, - {13126,13539,13127 ,6324,6348,6316 ,0,0,0}, {13112,13533,13113 ,6300,6352,6353 ,0,0,0}, - {13161,13581,13583 ,6354,6351,6316 ,0,0,0}, {13109,13527,13110 ,6355,6299,6298 ,0,0,0}, - {13532,13118,13530 ,6299,6356,6357 ,0,0,0}, {14812,13171,14810 ,6308,6358,6310 ,0,0,0}, - {14815,14811,13162 ,6318,6312,6359 ,0,0,0}, {13465,13464,14816 ,6316,6306,6360 ,0,0,0}, - {14816,13464,13115 ,6360,6306,6299 ,0,0,0}, {14816,14817,13465 ,6360,6298,6316 ,0,0,0}, - {14813,14807,13167 ,6313,6307,6304 ,0,0,0}, {13174,14808,14818 ,6336,6308,6311 ,0,0,0}, - {13121,13538,13126 ,6303,6299,6324 ,0,0,0}, {14818,14804,13179 ,6311,6304,6314 ,0,0,0}, - {13473,13471,14819 ,6301,6300,6340 ,0,0,0}, {14820,13471,13470 ,6301,6300,6298 ,0,0,0}, - {14821,14801,13184 ,6301,6301,6333 ,0,0,0}, {13178,14805,14821 ,6361,6305,6301 ,0,0,0}, - {14822,13479,13477 ,6300,6300,6357 ,0,0,0}, {13476,14823,13477 ,6306,6355,6357 ,0,0,0}, - {14824,14825,13185 ,6353,6311,6301 ,0,0,0}, {13181,14802,14824 ,6362,6302,6353 ,0,0,0}, - {13485,13483,14826 ,6300,6299,6300 ,0,0,0}, {13186,14825,14827 ,6300,6311,6363 ,0,0,0}, - {13190,14827,14828 ,6301,6363,6353 ,0,0,0}, {13191,14828,14829 ,6300,6353,6328 ,0,0,0}, - {13485,14830,13488 ,6300,6300,6298 ,0,0,0}, {14831,13193,14829 ,6303,6352,6328 ,0,0,0}, - {14831,14832,13195 ,6303,6352,6340 ,0,0,0}, {14833,13491,13489 ,6299,6316,6300 ,0,0,0}, - {14834,13198,14832 ,6300,6340,6352 ,0,0,0}, {14835,13494,13491 ,6298,6364,6316 ,0,0,0}, - {13199,14834,14836 ,6316,6300,6306 ,0,0,0}, {14837,13495,13494 ,6364,6298,6364 ,0,0,0}, - {14836,14838,13201 ,6306,6340,6340 ,0,0,0}, {14839,13497,13495 ,6300,6300,6298 ,0,0,0}, - {14840,13204,14838 ,6323,6340,6340 ,0,0,0}, {14841,13500,13497 ,6298,6300,6300 ,0,0,0}, - {13206,14840,14842 ,6300,6323,6340 ,0,0,0}, {14843,13501,13500 ,6364,6300,6300 ,0,0,0}, - {14842,14844,13205 ,6340,6303,6303 ,0,0,0}, {14845,13503,13501 ,6300,6365,6300 ,0,0,0}, - {14846,13207,14844 ,6300,6300,6303 ,0,0,0}, {14847,13506,13503 ,6366,6300,6365 ,0,0,0}, - {13210,14846,14848 ,6300,6300,6316 ,0,0,0}, {14849,13507,13506 ,6367,6367,6300 ,0,0,0}, - {14848,14850,13211 ,6316,6300,6300 ,0,0,0}, {14851,13509,13507 ,6300,6300,6367 ,0,0,0}, - {14852,13211,14853 ,6301,6300,6300 ,0,0,0}, {14854,13512,13509 ,6368,6300,6300 ,0,0,0}, - {14855,14852,14856 ,6300,6301,6300 ,0,0,0}, {14857,13513,13512 ,6369,6367,6300 ,0,0,0}, - {14858,14855,14859 ,6316,6300,6300 ,0,0,0}, {13513,14860,13515 ,6367,6367,6300 ,0,0,0}, - {13518,13515,14861 ,6364,6300,6370 ,0,0,0}, {14862,13521,13519 ,6300,6316,6300 ,0,0,0}, - {14863,14858,14864 ,6300,6316,6316 ,0,0,0}, {14865,14866,14867 ,6300,6371,6300 ,0,0,0}, - {14868,14869,14870 ,6306,6300,6303 ,0,0,0}, {14871,14872,14873 ,6369,6300,6367 ,0,0,0}, - {14874,14875,14876 ,6301,6301,6300 ,0,0,0}, {14877,14878,14879 ,6300,6369,6367 ,0,0,0}, - {14880,14881,14882 ,6316,6316,6300 ,0,0,0}, {14883,14884,14885 ,6364,6300,6300 ,0,0,0}, - {14886,14877,14887 ,6364,6300,6316 ,0,0,0}, {14888,14889,14890 ,6300,6364,6316 ,0,0,0}, - {14885,14891,14890 ,6300,6316,6316 ,0,0,0}, {14892,14893,14894 ,6364,6372,6364 ,0,0,0}, - {14893,14886,14895 ,6372,6364,6300 ,0,0,0}, {14880,14889,14896 ,6316,6364,6367 ,0,0,0}, - {14897,14883,14892 ,6370,6364,6364 ,0,0,0}, {14873,14898,14899 ,6367,6367,6316 ,0,0,0}, - {14900,14878,14899 ,6316,6369,6316 ,0,0,0}, {14901,14874,14902 ,6306,6301,6303 ,0,0,0}, - {14902,14882,14903 ,6303,6300,6340 ,0,0,0}, {14904,14905,14867 ,6371,6300,6300 ,0,0,0}, - {14906,14871,14905 ,6300,6369,6300 ,0,0,0}, {14907,14868,14908 ,6300,6306,6300 ,0,0,0}, - {14907,14908,14876 ,6300,6300,6300 ,0,0,0}, {14909,14910,13521 ,6300,6300,6316 ,0,0,0}, - {14865,14910,14911 ,6300,6300,6316 ,0,0,0}, {14863,14912,14913 ,6300,6303,6301 ,0,0,0}, - {14869,14913,14914 ,6300,6301,6301 ,0,0,0}, {13519,13518,14915 ,6300,6364,6369 ,0,0,0}, - {13464,13463,13115 ,6306,6298,6299 ,0,0,0}, {13115,13463,13526 ,6299,6298,6340 ,0,0,0}, - {14817,14809,13467 ,6298,6298,6309 ,0,0,0}, {14817,13467,13465 ,6298,6309,6316 ,0,0,0}, - {14809,14820,13470 ,6298,6301,6298 ,0,0,0}, {14820,14819,13471 ,6301,6340,6300 ,0,0,0}, - {14819,14806,13473 ,6340,6299,6301 ,0,0,0}, {14806,14823,13476 ,6299,6355,6306 ,0,0,0}, - {14823,14822,13477 ,6355,6300,6357 ,0,0,0}, {14822,14803,13479 ,6300,6303,6300 ,0,0,0}, - {14803,14799,13482 ,6303,6298,6299 ,0,0,0}, {14799,14826,13483 ,6298,6300,6299 ,0,0,0}, - {14826,14830,13485 ,6300,6300,6300 ,0,0,0}, {14830,14800,13488 ,6300,6298,6298 ,0,0,0}, - {14800,14833,13489 ,6298,6299,6300 ,0,0,0}, {14833,14835,13491 ,6299,6298,6316 ,0,0,0}, - {14835,14837,13494 ,6298,6364,6364 ,0,0,0}, {14837,14839,13495 ,6364,6300,6298 ,0,0,0}, - {14839,14841,13497 ,6300,6298,6300 ,0,0,0}, {14841,14843,13500 ,6298,6364,6300 ,0,0,0}, - {14843,14845,13501 ,6364,6300,6300 ,0,0,0}, {14845,14847,13503 ,6300,6366,6365 ,0,0,0}, - {14847,14849,13506 ,6366,6367,6300 ,0,0,0}, {14849,14851,13507 ,6367,6300,6367 ,0,0,0}, - {14851,14854,13509 ,6300,6368,6300 ,0,0,0}, {14854,14857,13512 ,6368,6369,6300 ,0,0,0}, - {14857,14860,13513 ,6369,6367,6367 ,0,0,0}, {14860,14861,13515 ,6367,6370,6300 ,0,0,0}, - {14861,14915,13518 ,6370,6369,6364 ,0,0,0}, {14915,14862,13519 ,6369,6300,6300 ,0,0,0}, - {14862,14909,13521 ,6300,6300,6316 ,0,0,0}, {14909,14911,14910 ,6300,6316,6300 ,0,0,0}, - {14911,14866,14865 ,6316,6371,6300 ,0,0,0}, {14866,14904,14867 ,6371,6371,6300 ,0,0,0}, - {14904,14906,14905 ,6371,6300,6300 ,0,0,0}, {14906,14872,14871 ,6300,6300,6369 ,0,0,0}, - {14872,14898,14873 ,6300,6367,6367 ,0,0,0}, {14898,14900,14899 ,6367,6316,6316 ,0,0,0}, - {14900,14879,14878 ,6316,6367,6369 ,0,0,0}, {14879,14887,14877 ,6367,6316,6300 ,0,0,0}, - {14887,14895,14886 ,6316,6300,6364 ,0,0,0}, {14895,14894,14893 ,6300,6364,6372 ,0,0,0}, - {14894,14897,14892 ,6364,6370,6364 ,0,0,0}, {14897,14884,14883 ,6370,6300,6364 ,0,0,0}, - {14884,14891,14885 ,6300,6316,6300 ,0,0,0}, {14891,14888,14890 ,6316,6300,6316 ,0,0,0}, - {14888,14896,14889 ,6300,6367,6364 ,0,0,0}, {14896,14881,14880 ,6367,6316,6316 ,0,0,0}, - {14881,14903,14882 ,6316,6340,6300 ,0,0,0}, {14903,14901,14902 ,6340,6306,6303 ,0,0,0}, - {14901,14875,14874 ,6306,6301,6301 ,0,0,0}, {14875,14907,14876 ,6301,6300,6300 ,0,0,0}, - {14868,14870,14908 ,6306,6303,6300 ,0,0,0}, {14869,14914,14870 ,6300,6301,6303 ,0,0,0}, - {14913,14912,14914 ,6301,6303,6301 ,0,0,0}, {14863,14864,14912 ,6300,6316,6303 ,0,0,0}, - {14858,14859,14864 ,6316,6300,6316 ,0,0,0}, {14855,14856,14859 ,6300,6300,6300 ,0,0,0}, - {14852,14853,14856 ,6301,6300,6300 ,0,0,0}, {13211,14850,14853 ,6300,6300,6300 ,0,0,0}, - {13211,13210,14848 ,6300,6300,6316 ,0,0,0}, {13210,13207,14846 ,6300,6300,6300 ,0,0,0}, - {13207,13205,14844 ,6300,6303,6303 ,0,0,0}, {13205,13206,14842 ,6303,6300,6340 ,0,0,0}, - {13206,13204,14840 ,6300,6340,6323 ,0,0,0}, {13204,13201,14838 ,6340,6340,6340 ,0,0,0}, - {13201,13199,14836 ,6340,6316,6306 ,0,0,0}, {13199,13198,14834 ,6316,6340,6300 ,0,0,0}, - {13198,13195,14832 ,6340,6340,6352 ,0,0,0}, {13195,13193,14831 ,6340,6352,6303 ,0,0,0}, - {13193,13191,14829 ,6352,6300,6328 ,0,0,0}, {13191,13190,14828 ,6300,6301,6353 ,0,0,0}, - {13190,13186,14827 ,6301,6300,6363 ,0,0,0}, {13186,13185,14825 ,6300,6301,6311 ,0,0,0}, - {13185,13181,14824 ,6301,6362,6353 ,0,0,0}, {13181,13180,14802 ,6362,6302,6302 ,0,0,0}, - {13180,13184,14801 ,6302,6333,6301 ,0,0,0}, {13184,13178,14821 ,6333,6361,6301 ,0,0,0}, - {13178,13177,14805 ,6361,6304,6305 ,0,0,0}, {13177,13179,14804 ,6304,6314,6304 ,0,0,0}, - {13179,13174,14818 ,6314,6336,6311 ,0,0,0}, {13174,13175,14808 ,6336,6305,6308 ,0,0,0}, - {13175,13167,14807 ,6305,6304,6307 ,0,0,0}, {13167,13169,14813 ,6304,6314,6313 ,0,0,0}, - {13169,13171,14812 ,6314,6358,6308 ,0,0,0}, {13171,13163,14810 ,6358,6311,6310 ,0,0,0}, - {13163,13162,14811 ,6311,6359,6312 ,0,0,0}, {13162,13166,14815 ,6359,6319,6318 ,0,0,0}, - {13166,13159,14814 ,6319,6315,6317 ,0,0,0}, {13159,13161,13583 ,6315,6354,6316 ,0,0,0}, - {13161,13155,13581 ,6354,6350,6351 ,0,0,0}, {13155,13154,13580 ,6350,6320,6322 ,0,0,0}, - {13154,13156,13578 ,6320,6349,6321 ,0,0,0}, {13156,13148,13575 ,6349,6346,6345 ,0,0,0}, - {13148,13150,13574 ,6346,6341,6343 ,0,0,0}, {13150,13152,13572 ,6341,6344,6342 ,0,0,0}, - {13152,13144,13569 ,6344,6325,6327 ,0,0,0}, {13144,13143,13568 ,6325,6338,6326 ,0,0,0}, - {13143,13146,13566 ,6338,6324,6339 ,0,0,0}, {13146,13214,13563 ,6324,6298,6336 ,0,0,0}, - {13214,13141,13562 ,6298,6330,6329 ,0,0,0}, {13141,13215,13560 ,6330,6324,6301 ,0,0,0}, - {13215,13142,13557 ,6324,6337,6331 ,0,0,0}, {13142,13134,13556 ,6337,6332,6333 ,0,0,0}, - {13134,13137,13554 ,6332,6334,6328 ,0,0,0}, {13137,13129,13551 ,6334,6340,6335 ,0,0,0}, - {13129,13128,13550 ,6340,6299,6328 ,0,0,0}, {13128,13132,13548 ,6299,6324,6328 ,0,0,0}, - {13132,13131,13545 ,6324,6347,6298 ,0,0,0}, {13131,13124,13544 ,6347,6306,6298 ,0,0,0}, - {13124,13127,13542 ,6306,6316,6324 ,0,0,0}, {13126,13538,13539 ,6324,6299,6348 ,0,0,0}, - {13113,13536,13121 ,6353,6323,6303 ,0,0,0}, {13112,13532,13533 ,6300,6299,6352 ,0,0,0}, - {13113,13533,13536 ,6353,6352,6323 ,0,0,0}, {13118,13110,13530 ,6356,6298,6357 ,0,0,0}, - {13112,13118,13532 ,6300,6356,6299 ,0,0,0}, {13527,13109,13526 ,6299,6355,6340 ,0,0,0}, - {13530,13110,13527 ,6357,6298,6299 ,0,0,0}, {13115,13526,13109 ,6299,6340,6355 ,0,0,0}, - {14910,13523,13521 ,6373,6374,6375 ,0,0,0}, {14916,14917,14905 ,6376,6377,6378 ,0,0,0}, - {14867,14918,14865 ,6379,6380,6381 ,0,0,0}, {14899,14878,14919 ,6382,6383,6384 ,0,0,0}, - {14871,14873,14920 ,6385,6386,6387 ,0,0,0}, {14921,14922,14893 ,6388,6389,6390 ,0,0,0}, - {14923,14924,14877 ,6391,6392,6393 ,0,0,0}, {14885,14890,14925 ,6394,6395,6396 ,0,0,0}, - {14892,14883,14926 ,6397,6398,6399 ,0,0,0}, {14927,14928,14882 ,6400,6401,6402 ,0,0,0}, - {14929,14930,14889 ,6403,6404,6405 ,0,0,0}, {14876,14908,14931 ,6406,6407,6408 ,0,0,0}, - {14902,14874,14932 ,6409,6410,6411 ,0,0,0}, {14933,14934,14912 ,6412,6413,6414 ,0,0,0}, - {14935,14936,14870 ,6415,6416,6417 ,0,0,0}, {14937,14856,14938 ,6418,6419,6420 ,0,0,0}, - {14864,14859,14939 ,6421,6422,6423 ,0,0,0}, {14848,14940,14941 ,6424,6425,6426 ,0,0,0}, - {14850,14942,14853 ,6427,6428,6429 ,0,0,0}, {14943,14944,14842 ,6430,6431,6432 ,0,0,0}, - {14945,14846,14844 ,6433,6434,6435 ,0,0,0}, {14946,14838,14836 ,6436,6437,6438 ,0,0,0}, - {14840,14838,14947 ,6439,6437,6440 ,0,0,0}, {14948,14832,14949 ,6441,6442,6443 ,0,0,0}, - {14834,14948,14950 ,6444,6441,6445 ,0,0,0}, {14829,14828,14951 ,6446,6447,6448 ,0,0,0}, - {14831,14952,14949 ,6449,6450,6443 ,0,0,0}, {14827,14825,14953 ,6451,6452,6453 ,0,0,0}, - {14827,14954,14828 ,6451,6454,6447 ,0,0,0}, {14824,14802,14955 ,6455,6456,6457 ,0,0,0}, - {14824,14956,14825 ,6455,6458,6452 ,0,0,0}, {14957,14802,14801 ,6459,6456,6460 ,0,0,0}, - {14802,14957,14955 ,6456,6459,6457 ,0,0,0}, {14821,14958,14801 ,6461,6462,6460 ,0,0,0}, - {14957,14801,14958 ,6459,6460,6462 ,0,0,0}, {14821,14805,14959 ,6461,6463,6464 ,0,0,0}, - {14959,14958,14821 ,6464,6462,6461 ,0,0,0}, {14960,14805,14804 ,6465,6463,6466 ,0,0,0}, - {14805,14960,14959 ,6463,6465,6464 ,0,0,0}, {14818,14961,14804 ,6467,6468,6466 ,0,0,0}, - {14960,14804,14961 ,6465,6466,6468 ,0,0,0}, {14818,14808,14962 ,6467,6469,6470 ,0,0,0}, - {14962,14961,14818 ,6470,6468,6467 ,0,0,0}, {14963,14808,14807 ,6471,6469,6472 ,0,0,0}, - {14808,14963,14962 ,6469,6471,6470 ,0,0,0}, {14813,14964,14807 ,6473,6474,6472 ,0,0,0}, - {14963,14807,14964 ,6471,6472,6474 ,0,0,0}, {14813,14812,14965 ,6473,6475,6476 ,0,0,0}, - {14965,14964,14813 ,6476,6474,6473 ,0,0,0}, {14966,14812,14810 ,6477,6475,6478 ,0,0,0}, - {14812,14966,14965 ,6475,6477,6476 ,0,0,0}, {14811,14967,14810 ,6479,6480,6478 ,0,0,0}, - {14966,14810,14967 ,6477,6478,6480 ,0,0,0}, {14811,14815,14968 ,6479,6481,6482 ,0,0,0}, - {14968,14967,14811 ,6482,6480,6479 ,0,0,0}, {14969,14815,14814 ,6483,6481,6484 ,0,0,0}, - {14815,14969,14968 ,6481,6483,6482 ,0,0,0}, {13583,14970,14814 ,6485,6486,6484 ,0,0,0}, - {14969,14814,14970 ,6483,6484,6486 ,0,0,0}, {13582,14970,13583 ,6487,6486,6485 ,0,0,0}, - {14956,14953,14825 ,6458,6453,6452 ,0,0,0}, {14824,14955,14956 ,6455,6457,6458 ,0,0,0}, - {14954,14951,14828 ,6454,6448,6447 ,0,0,0}, {14827,14953,14954 ,6451,6453,6454 ,0,0,0}, - {14831,14829,14952 ,6449,6446,6450 ,0,0,0}, {14829,14951,14952 ,6446,6448,6450 ,0,0,0}, - {14832,14948,14834 ,6442,6441,6444 ,0,0,0}, {14832,14831,14949 ,6442,6449,6443 ,0,0,0}, - {14946,14836,14950 ,6436,6438,6445 ,0,0,0}, {14836,14834,14950 ,6438,6444,6445 ,0,0,0}, - {14840,14947,14943 ,6439,6440,6430 ,0,0,0}, {14947,14838,14946 ,6440,6437,6436 ,0,0,0}, - {14944,14844,14842 ,6431,6435,6432 ,0,0,0}, {14943,14842,14840 ,6430,6432,6439 ,0,0,0}, - {14945,14940,14846 ,6433,6425,6434 ,0,0,0}, {14944,14945,14844 ,6431,6433,6435 ,0,0,0}, - {14848,14941,14850 ,6424,6426,6427 ,0,0,0}, {14846,14940,14848 ,6434,6425,6424 ,0,0,0}, - {14853,14942,14938 ,6429,6428,6420 ,0,0,0}, {14850,14941,14942 ,6427,6426,6428 ,0,0,0}, - {14859,14856,14937 ,6422,6419,6418 ,0,0,0}, {14856,14853,14938 ,6419,6429,6420 ,0,0,0}, - {14933,14864,14939 ,6412,6421,6423 ,0,0,0}, {14939,14859,14937 ,6423,6422,6418 ,0,0,0}, - {14934,14914,14912 ,6413,6488,6414 ,0,0,0}, {14933,14912,14864 ,6412,6414,6421 ,0,0,0}, - {14870,14914,14935 ,6417,6488,6415 ,0,0,0}, {14934,14935,14914 ,6413,6415,6488 ,0,0,0}, - {14908,14936,14931 ,6407,6416,6408 ,0,0,0}, {14870,14936,14908 ,6417,6416,6407 ,0,0,0}, - {14874,14876,14971 ,6410,6406,6489 ,0,0,0}, {14876,14931,14971 ,6406,6408,6489 ,0,0,0}, - {14927,14902,14932 ,6400,6409,6411 ,0,0,0}, {14932,14874,14971 ,6411,6410,6489 ,0,0,0}, - {14928,14880,14882 ,6401,6490,6402 ,0,0,0}, {14927,14882,14902 ,6400,6402,6409 ,0,0,0}, - {14889,14880,14929 ,6405,6490,6403 ,0,0,0}, {14928,14929,14880 ,6401,6403,6490 ,0,0,0}, - {14890,14930,14925 ,6395,6404,6396 ,0,0,0}, {14889,14930,14890 ,6405,6404,6395 ,0,0,0}, - {14883,14885,14972 ,6398,6394,6491 ,0,0,0}, {14885,14925,14972 ,6394,6396,6491 ,0,0,0}, - {14921,14892,14926 ,6388,6397,6399 ,0,0,0}, {14926,14883,14972 ,6399,6398,6491 ,0,0,0}, - {14922,14886,14893 ,6389,6492,6390 ,0,0,0}, {14921,14893,14892 ,6388,6390,6397 ,0,0,0}, - {14877,14886,14923 ,6393,6492,6391 ,0,0,0}, {14922,14923,14886 ,6389,6391,6492 ,0,0,0}, - {14878,14924,14919 ,6383,6392,6384 ,0,0,0}, {14877,14924,14878 ,6393,6392,6383 ,0,0,0}, - {14873,14899,14973 ,6386,6382,6493 ,0,0,0}, {14899,14919,14973 ,6382,6384,6493 ,0,0,0}, - {14916,14871,14920 ,6376,6385,6387 ,0,0,0}, {14920,14873,14973 ,6387,6386,6493 ,0,0,0}, - {14917,14867,14905 ,6377,6379,6378 ,0,0,0}, {14916,14905,14871 ,6376,6378,6385 ,0,0,0}, - {14918,14974,14865 ,6380,6494,6381 ,0,0,0}, {14917,14918,14867 ,6377,6380,6379 ,0,0,0}, - {13523,14910,14974 ,6374,6373,6494 ,0,0,0}, {14865,14974,14910 ,6381,6494,6373 ,0,0,0}, - {13534,13420,13535 ,6495,6495,6496 ,0,0,0}, {13541,13540,13426 ,6497,6496,6496 ,0,0,0}, - {14929,14928,14975 ,6498,6499,6500 ,0,0,0}, {13417,13534,13531 ,6501,6495,6501 ,0,0,0}, - {14926,14972,14976 ,6502,6503,6503 ,0,0,0}, {13528,13411,13414 ,6496,6504,6501 ,0,0,0}, - {14977,14919,14924 ,6498,6505,6506 ,0,0,0}, {13353,13462,13466 ,6507,6495,6495 ,0,0,0}, - {13363,13361,13475 ,6508,6509,6504 ,0,0,0}, {14978,14917,14916 ,6510,6511,6512 ,0,0,0}, - {13522,13405,13403 ,6513,6500,6514 ,0,0,0}, {13523,13405,13522 ,6515,6500,6513 ,0,0,0}, - {13517,13520,13404 ,6516,6517,6518 ,0,0,0}, {13484,13486,13369 ,6519,6520,6497 ,0,0,0}, - {13490,13492,13375 ,6521,6522,6523 ,0,0,0}, {13514,13397,13396 ,6524,6525,6526 ,0,0,0}, - {13493,13379,13378 ,6527,6500,6498 ,0,0,0}, {13510,13391,13508 ,6528,6522,6529 ,0,0,0}, - {13508,13390,13505 ,6529,6530,6531 ,0,0,0}, {13385,13502,13387 ,6532,6533,6502 ,0,0,0}, - {13499,13385,13384 ,6534,6532,6495 ,0,0,0}, {13511,13393,13510 ,6535,6502,6528 ,0,0,0}, - {13504,13505,13387 ,6533,6531,6502 ,0,0,0}, {13514,13396,13511 ,6524,6526,6535 ,0,0,0}, - {13393,13511,13396 ,6502,6535,6526 ,0,0,0}, {13496,13381,13379 ,6503,6514,6500 ,0,0,0}, - {13384,13381,13498 ,6495,6514,6530 ,0,0,0}, {13402,13397,13516 ,6536,6525,6537 ,0,0,0}, - {13397,13514,13516 ,6525,6524,6537 ,0,0,0}, {13402,13516,13517 ,6536,6537,6516 ,0,0,0}, - {13493,13378,13492 ,6527,6498,6522 ,0,0,0}, {13490,13373,13487 ,6521,6501,6509 ,0,0,0}, - {13517,13404,13402 ,6516,6518,6536 ,0,0,0}, {13404,13520,13403 ,6518,6517,6514 ,0,0,0}, - {13487,13372,13486 ,6509,6500,6520 ,0,0,0}, {13367,13481,13369 ,6508,6509,6497 ,0,0,0}, - {13522,13403,13520 ,6513,6514,6517 ,0,0,0}, {13363,13478,13366 ,6508,6508,6495 ,0,0,0}, - {13366,13480,13367 ,6495,6530,6508 ,0,0,0}, {14979,14918,14980 ,6538,6539,6540 ,0,0,0}, - {14974,13405,13523 ,6541,6500,6515 ,0,0,0}, {13474,13360,13472 ,6495,6496,6542 ,0,0,0}, - {13361,13360,13474 ,6509,6496,6495 ,0,0,0}, {13468,13469,13355 ,6542,6504,6507 ,0,0,0}, - {14973,14919,14981 ,6543,6505,6500 ,0,0,0}, {14982,14923,14983 ,6503,6533,6500 ,0,0,0}, - {13466,13468,13354 ,6495,6542,6495 ,0,0,0}, {14984,14983,14921 ,6508,6500,6538 ,0,0,0}, - {13411,13525,13410 ,6504,6542,6501 ,0,0,0}, {13353,13410,13524 ,6507,6501,6495 ,0,0,0}, - {14930,14985,14986 ,6527,6530,6498 ,0,0,0}, {14972,14925,14987 ,6503,6527,6499 ,0,0,0}, - {13417,13531,13416 ,6501,6501,6544 ,0,0,0}, {13529,13414,13416 ,6504,6501,6544 ,0,0,0}, - {14932,14988,14989 ,6508,6530,6544 ,0,0,0}, {14990,14927,14989 ,6498,6500,6544 ,0,0,0}, - {13422,13537,13535 ,6495,6495,6496 ,0,0,0}, {14971,14931,14988 ,6523,6504,6530 ,0,0,0}, - {14936,14991,14931 ,6500,6504,6504 ,0,0,0}, {14936,14935,14992 ,6500,6522,6500 ,0,0,0}, - {13540,13537,13423 ,6496,6495,6496 ,0,0,0}, {14993,14935,14934 ,6515,6522,6504 ,0,0,0}, - {14933,14994,14934 ,6508,6500,6504 ,0,0,0}, {13543,13426,13428 ,6495,6496,6508 ,0,0,0}, - {14994,14933,14995 ,6500,6508,6498 ,0,0,0}, {13546,13428,13429 ,6504,6508,6507 ,0,0,0}, - {14996,14995,14939 ,6515,6498,6545 ,0,0,0}, {13547,13429,13432 ,6507,6507,6495 ,0,0,0}, - {14997,14996,14937 ,6498,6515,6504 ,0,0,0}, {13549,13432,13434 ,6504,6495,6495 ,0,0,0}, - {14998,14997,14938 ,6504,6498,6504 ,0,0,0}, {13434,13435,13552 ,6495,6504,6504 ,0,0,0}, - {14999,14998,14942 ,6504,6504,6498 ,0,0,0}, {13553,13552,13435 ,6504,6504,6504 ,0,0,0}, - {14999,14941,14940 ,6504,6504,6504 ,0,0,0}, {13555,13553,13438 ,6546,6504,6504 ,0,0,0}, - {15000,14940,14945 ,6508,6504,6504 ,0,0,0}, {13558,13555,13440 ,6507,6546,6504 ,0,0,0}, - {15001,14945,14944 ,6508,6504,6508 ,0,0,0}, {13559,13558,13441 ,6547,6507,6548 ,0,0,0}, - {15002,14944,14943 ,6498,6508,6498 ,0,0,0}, {13561,13559,13444 ,6546,6547,6548 ,0,0,0}, - {15003,14943,14947 ,6504,6498,6498 ,0,0,0}, {13446,13564,13444 ,6549,6547,6548 ,0,0,0}, - {14947,15004,15003 ,6498,6504,6504 ,0,0,0}, {13565,13446,13447 ,6549,6549,6550 ,0,0,0}, - {15004,14946,15005 ,6504,6504,6498 ,0,0,0}, {13447,13450,13567 ,6550,6549,6504 ,0,0,0}, - {13570,13450,13452 ,6549,6549,6545 ,0,0,0}, {13573,13571,13454 ,6549,6504,6504 ,0,0,0}, - {15005,14950,15006 ,6498,6504,6504 ,0,0,0}, {13579,13577,13459 ,6551,6504,6515 ,0,0,0}, - {14951,15007,14952 ,6504,6508,6515 ,0,0,0}, {15008,14969,15009 ,6504,6545,6515 ,0,0,0}, - {15010,14953,14956 ,6508,6552,6504 ,0,0,0}, {14966,15011,15012 ,6553,6504,6554 ,0,0,0}, - {15013,15014,14957 ,6555,6504,6515 ,0,0,0}, {14961,14962,15015 ,6504,6504,6504 ,0,0,0}, - {14966,15012,14965 ,6553,6554,6504 ,0,0,0}, {14959,15016,15017 ,6504,6504,6515 ,0,0,0}, - {15015,15016,14960 ,6504,6504,6515 ,0,0,0}, {14964,15018,14963 ,6548,6504,6504 ,0,0,0}, - {14964,14965,15019 ,6548,6504,6549 ,0,0,0}, {15013,14958,15017 ,6555,6504,6515 ,0,0,0}, - {15020,14962,14963 ,6504,6504,6504 ,0,0,0}, {15021,14968,15008 ,6504,6548,6504 ,0,0,0}, - {15011,14967,15021 ,6504,6548,6504 ,0,0,0}, {14955,15022,14956 ,6504,6544,6504 ,0,0,0}, - {14955,15014,15022 ,6504,6504,6544 ,0,0,0}, {13582,13579,13461 ,6515,6551,6554 ,0,0,0}, - {13461,15009,14970 ,6554,6515,6545 ,0,0,0}, {14954,15023,14951 ,6515,6504,6504 ,0,0,0}, - {15024,14954,14953 ,6508,6515,6552 ,0,0,0}, {13576,13573,13453 ,6504,6549,6549 ,0,0,0}, - {13456,13577,13576 ,6545,6504,6504 ,0,0,0}, {14948,15025,15006 ,6508,6498,6504 ,0,0,0}, - {15007,15025,14949 ,6508,6498,6498 ,0,0,0}, {13571,13452,13454 ,6504,6545,6504 ,0,0,0}, - {13469,13472,13357 ,6504,6542,6504 ,0,0,0}, {15026,14920,15027 ,6556,6557,6558 ,0,0,0}, - {14975,14928,14990 ,6500,6499,6498 ,0,0,0}, {13391,13510,13393 ,6522,6528,6502 ,0,0,0}, - {13390,13508,13391 ,6530,6529,6522 ,0,0,0}, {13387,13505,13390 ,6502,6531,6530 ,0,0,0}, - {13387,13502,13504 ,6502,6533,6533 ,0,0,0}, {13385,13499,13502 ,6532,6534,6533 ,0,0,0}, - {13384,13498,13499 ,6495,6530,6534 ,0,0,0}, {13381,13496,13498 ,6514,6503,6530 ,0,0,0}, - {13379,13493,13496 ,6500,6527,6503 ,0,0,0}, {13375,13492,13378 ,6523,6522,6498 ,0,0,0}, - {13373,13490,13375 ,6501,6521,6523 ,0,0,0}, {13372,13487,13373 ,6500,6509,6501 ,0,0,0}, - {13369,13486,13372 ,6497,6520,6500 ,0,0,0}, {13369,13481,13484 ,6497,6509,6519 ,0,0,0}, - {13367,13480,13481 ,6508,6530,6509 ,0,0,0}, {13366,13478,13480 ,6495,6508,6530 ,0,0,0}, - {13363,13475,13478 ,6508,6504,6508 ,0,0,0}, {13361,13474,13475 ,6509,6495,6504 ,0,0,0}, - {13357,13472,13360 ,6504,6542,6496 ,0,0,0}, {13355,13469,13357 ,6507,6504,6504 ,0,0,0}, - {13354,13468,13355 ,6495,6542,6507 ,0,0,0}, {13353,13466,13354 ,6507,6495,6495 ,0,0,0}, - {13353,13524,13462 ,6507,6495,6495 ,0,0,0}, {13410,13525,13524 ,6501,6542,6495 ,0,0,0}, - {13411,13528,13525 ,6504,6496,6542 ,0,0,0}, {13414,13529,13528 ,6501,6504,6496 ,0,0,0}, - {13416,13531,13529 ,6544,6501,6504 ,0,0,0}, {13420,13534,13417 ,6495,6495,6501 ,0,0,0}, - {13422,13535,13420 ,6495,6496,6495 ,0,0,0}, {13423,13537,13422 ,6496,6495,6495 ,0,0,0}, - {13426,13540,13423 ,6496,6496,6496 ,0,0,0}, {13426,13543,13541 ,6496,6495,6497 ,0,0,0}, - {13428,13546,13543 ,6508,6504,6495 ,0,0,0}, {13429,13547,13546 ,6507,6507,6504 ,0,0,0}, - {13432,13549,13547 ,6495,6504,6507 ,0,0,0}, {13434,13552,13549 ,6495,6504,6504 ,0,0,0}, - {13438,13553,13435 ,6504,6504,6504 ,0,0,0}, {13440,13555,13438 ,6504,6546,6504 ,0,0,0}, - {13441,13558,13440 ,6548,6507,6504 ,0,0,0}, {13444,13559,13441 ,6548,6547,6548 ,0,0,0}, - {13444,13564,13561 ,6548,6547,6546 ,0,0,0}, {13446,13565,13564 ,6549,6549,6547 ,0,0,0}, - {13447,13567,13565 ,6550,6504,6549 ,0,0,0}, {13450,13570,13567 ,6549,6549,6504 ,0,0,0}, - {13452,13571,13570 ,6545,6504,6549 ,0,0,0}, {13453,13573,13454 ,6549,6549,6504 ,0,0,0}, - {13456,13576,13453 ,6545,6504,6549 ,0,0,0}, {13459,13577,13456 ,6515,6504,6545 ,0,0,0}, - {13461,13579,13459 ,6554,6551,6515 ,0,0,0}, {13461,14970,13582 ,6554,6545,6515 ,0,0,0}, - {15009,14969,14970 ,6515,6545,6545 ,0,0,0}, {15008,14968,14969 ,6504,6548,6545 ,0,0,0}, - {15021,14967,14968 ,6504,6548,6548 ,0,0,0}, {15011,14966,14967 ,6504,6553,6548 ,0,0,0}, - {15019,14965,15012 ,6549,6504,6554 ,0,0,0}, {15018,14964,15019 ,6504,6548,6549 ,0,0,0}, - {15020,14963,15018 ,6504,6504,6504 ,0,0,0}, {15015,14962,15020 ,6504,6504,6504 ,0,0,0}, - {15015,14960,14961 ,6504,6515,6504 ,0,0,0}, {15016,14959,14960 ,6504,6504,6515 ,0,0,0}, - {15017,14958,14959 ,6515,6504,6504 ,0,0,0}, {15013,14957,14958 ,6555,6515,6504 ,0,0,0}, - {15014,14955,14957 ,6504,6504,6515 ,0,0,0}, {15010,14956,15022 ,6508,6504,6544 ,0,0,0}, - {15024,14953,15010 ,6508,6552,6508 ,0,0,0}, {15023,14954,15024 ,6504,6515,6508 ,0,0,0}, - {15007,14951,15023 ,6508,6504,6504 ,0,0,0}, {15007,14949,14952 ,6508,6498,6515 ,0,0,0}, - {15025,14948,14949 ,6498,6508,6498 ,0,0,0}, {15006,14950,14948 ,6504,6504,6508 ,0,0,0}, - {15005,14946,14950 ,6498,6504,6504 ,0,0,0}, {15004,14947,14946 ,6504,6498,6504 ,0,0,0}, - {15002,14943,15003 ,6498,6498,6504 ,0,0,0}, {15001,14944,15002 ,6508,6508,6498 ,0,0,0}, - {15000,14945,15001 ,6508,6504,6508 ,0,0,0}, {14999,14940,15000 ,6504,6504,6508 ,0,0,0}, - {14999,14942,14941 ,6504,6498,6504 ,0,0,0}, {14998,14938,14942 ,6504,6504,6498 ,0,0,0}, - {14997,14937,14938 ,6498,6504,6504 ,0,0,0}, {14996,14939,14937 ,6515,6545,6504 ,0,0,0}, - {14995,14933,14939 ,6498,6508,6545 ,0,0,0}, {14993,14934,14994 ,6515,6504,6500 ,0,0,0}, - {14992,14935,14993 ,6500,6522,6515 ,0,0,0}, {14991,14936,14992 ,6504,6500,6500 ,0,0,0}, - {14988,14931,14991 ,6530,6504,6504 ,0,0,0}, {14988,14932,14971 ,6530,6508,6523 ,0,0,0}, - {14989,14927,14932 ,6544,6500,6508 ,0,0,0}, {14990,14928,14927 ,6498,6499,6500 ,0,0,0}, - {14985,14929,14975 ,6530,6498,6500 ,0,0,0}, {14986,14925,14930 ,6498,6527,6527 ,0,0,0}, - {14985,14930,14929 ,6530,6527,6498 ,0,0,0}, {14987,14976,14972 ,6499,6503,6503 ,0,0,0}, - {14986,14987,14925 ,6498,6499,6527 ,0,0,0}, {14976,14984,14926 ,6503,6508,6502 ,0,0,0}, - {14921,14983,14922 ,6538,6500,6559 ,0,0,0}, {14926,14984,14921 ,6502,6508,6538 ,0,0,0}, - {14924,14923,14982 ,6506,6533,6503 ,0,0,0}, {14923,14922,14983 ,6533,6559,6500 ,0,0,0}, - {14981,14919,14977 ,6500,6505,6498 ,0,0,0}, {14977,14924,14982 ,6498,6506,6503 ,0,0,0}, - {15027,14973,14981 ,6558,6543,6500 ,0,0,0}, {15026,14916,14920 ,6556,6512,6557 ,0,0,0}, - {15027,14920,14973 ,6558,6557,6543 ,0,0,0}, {14978,14980,14917 ,6510,6540,6511 ,0,0,0}, - {15026,14978,14916 ,6556,6510,6512 ,0,0,0}, {14918,14979,14974 ,6539,6538,6541 ,0,0,0}, - {14917,14980,14918 ,6511,6540,6539 ,0,0,0}, {13405,14974,14979 ,6500,6541,6538 ,0,0,0}, - {14979,13407,13405 ,6560,6561,6562 ,0,0,0}, {15026,15028,14978 ,6563,6564,6565 ,0,0,0}, - {14980,15029,15030 ,6566,6567,6568 ,0,0,0}, {14977,14982,15031 ,6569,6570,6571 ,0,0,0}, - {15027,14981,15032 ,6572,6573,6574 ,0,0,0}, {15033,15034,14976 ,6575,6576,6577 ,0,0,0}, - {15035,15036,14983 ,6578,6579,6580 ,0,0,0}, {14985,14975,15037 ,6581,6582,6583 ,0,0,0}, - {14987,14986,15038 ,6584,6585,6586 ,0,0,0}, {15039,15040,14988 ,6587,6588,6589 ,0,0,0}, - {15041,14990,14989 ,6590,6591,6592 ,0,0,0}, {14993,14994,15042 ,6593,6594,6595 ,0,0,0}, - {14992,15043,15044 ,6596,6597,6598 ,0,0,0}, {15045,15046,14997 ,6599,6600,6601 ,0,0,0}, - {15047,15048,14995 ,6602,6603,6604 ,0,0,0}, {15049,15000,15050 ,6605,6606,6607 ,0,0,0}, - {14998,14999,15051 ,6608,6609,6610 ,0,0,0}, {15002,15003,15052 ,6611,6612,6613 ,0,0,0}, - {15002,15053,15001 ,6611,6614,6615 ,0,0,0}, {15006,15054,15005 ,6616,6617,6618 ,0,0,0}, - {15055,15056,15004 ,6619,6620,6621 ,0,0,0}, {15007,15057,15025 ,6622,6623,6624 ,0,0,0}, - {15058,15006,15025 ,6625,6616,6624 ,0,0,0}, {15059,15060,15024 ,6626,6627,6628 ,0,0,0}, - {15061,15023,15060 ,6629,6630,6627 ,0,0,0}, {15062,15063,15022 ,6631,6632,6633 ,0,0,0}, - {15059,15010,15063 ,6626,6634,6632 ,0,0,0}, {15013,15064,15014 ,6635,6636,6637 ,0,0,0}, - {15062,15014,15064 ,6631,6637,6636 ,0,0,0}, {15013,15017,15065 ,6635,6638,6639 ,0,0,0}, - {15065,15064,15013 ,6639,6636,6635 ,0,0,0}, {15066,15017,15016 ,6640,6638,6641 ,0,0,0}, - {15017,15066,15065 ,6638,6640,6639 ,0,0,0}, {15015,15067,15016 ,6642,6643,6641 ,0,0,0}, - {15066,15016,15067 ,6640,6641,6643 ,0,0,0}, {15015,15020,15068 ,6642,6644,6645 ,0,0,0}, - {15068,15067,15015 ,6645,6643,6642 ,0,0,0}, {15069,15020,15018 ,6646,6644,6647 ,0,0,0}, - {15020,15069,15068 ,6644,6646,6645 ,0,0,0}, {15019,15070,15018 ,6648,6649,6647 ,0,0,0}, - {15069,15018,15070 ,6646,6647,6649 ,0,0,0}, {15019,15012,15071 ,6648,6650,6651 ,0,0,0}, - {15071,15070,15019 ,6651,6649,6648 ,0,0,0}, {15072,15012,15011 ,6652,6650,6653 ,0,0,0}, - {15012,15072,15071 ,6650,6652,6651 ,0,0,0}, {15011,15073,15074 ,6653,6654,6655 ,0,0,0}, - {15072,15011,15074 ,6652,6653,6655 ,0,0,0}, {15073,15021,15075 ,6654,6656,6657 ,0,0,0}, - {15021,15073,15011 ,6656,6654,6653 ,0,0,0}, {15075,15008,15009 ,6657,6658,6659 ,0,0,0}, - {15021,15008,15075 ,6656,6658,6657 ,0,0,0}, {13461,15076,15009 ,6660,6661,6659 ,0,0,0}, - {15075,15009,15076 ,6657,6659,6661 ,0,0,0}, {13460,15076,13461 ,6660,6661,6660 ,0,0,0}, - {15010,15022,15063 ,6634,6633,6632 ,0,0,0}, {15062,15022,15014 ,6631,6633,6637 ,0,0,0}, - {15023,15024,15060 ,6630,6628,6627 ,0,0,0}, {15059,15024,15010 ,6626,6628,6634 ,0,0,0}, - {15061,15057,15007 ,6629,6623,6622 ,0,0,0}, {15061,15007,15023 ,6629,6622,6630 ,0,0,0}, - {15054,15006,15058 ,6617,6616,6625 ,0,0,0}, {15057,15058,15025 ,6623,6625,6624 ,0,0,0}, - {15005,15055,15004 ,6618,6619,6621 ,0,0,0}, {15054,15055,15005 ,6617,6619,6618 ,0,0,0}, - {15003,15056,15052 ,6612,6620,6613 ,0,0,0}, {15004,15056,15003 ,6621,6620,6612 ,0,0,0}, - {15053,15050,15001 ,6614,6607,6615 ,0,0,0}, {15002,15052,15053 ,6611,6613,6614 ,0,0,0}, - {14999,15000,15049 ,6609,6606,6605 ,0,0,0}, {15000,15001,15050 ,6606,6615,6607 ,0,0,0}, - {15045,14998,15051 ,6599,6608,6610 ,0,0,0}, {15051,14999,15049 ,6610,6609,6605 ,0,0,0}, - {15046,14996,14997 ,6600,6662,6601 ,0,0,0}, {15045,14997,14998 ,6599,6601,6608 ,0,0,0}, - {14995,14996,15047 ,6604,6662,6602 ,0,0,0}, {15046,15047,14996 ,6600,6602,6662 ,0,0,0}, - {14994,15048,15042 ,6594,6603,6595 ,0,0,0}, {14995,15048,14994 ,6604,6603,6594 ,0,0,0}, - {14992,14993,15043 ,6596,6593,6597 ,0,0,0}, {14993,15042,15043 ,6593,6595,6597 ,0,0,0}, - {15039,14991,15044 ,6587,6663,6598 ,0,0,0}, {14991,14992,15044 ,6663,6596,6598 ,0,0,0}, - {15040,14989,14988 ,6588,6592,6589 ,0,0,0}, {15039,14988,14991 ,6587,6589,6663 ,0,0,0}, - {15041,15077,14990 ,6590,6664,6591 ,0,0,0}, {15040,15041,14989 ,6588,6590,6592 ,0,0,0}, - {15037,14975,15077 ,6583,6582,6664 ,0,0,0}, {14990,15077,14975 ,6591,6664,6582 ,0,0,0}, - {14986,14985,15078 ,6585,6581,6665 ,0,0,0}, {14985,15037,15078 ,6581,6583,6665 ,0,0,0}, - {15033,14987,15038 ,6575,6584,6586 ,0,0,0}, {15038,14986,15078 ,6586,6585,6665 ,0,0,0}, - {15034,14984,14976 ,6576,6666,6577 ,0,0,0}, {15033,14976,14987 ,6575,6577,6584 ,0,0,0}, - {14983,14984,15035 ,6580,6666,6578 ,0,0,0}, {15034,15035,14984 ,6576,6578,6666 ,0,0,0}, - {14982,15036,15031 ,6570,6579,6571 ,0,0,0}, {14983,15036,14982 ,6580,6579,6570 ,0,0,0}, - {14981,14977,15079 ,6573,6569,6667 ,0,0,0}, {14977,15031,15079 ,6569,6571,6667 ,0,0,0}, - {15028,15027,15032 ,6564,6572,6574 ,0,0,0}, {15032,14981,15079 ,6574,6573,6667 ,0,0,0}, - {15028,15029,14978 ,6564,6567,6565 ,0,0,0}, {15028,15026,15027 ,6564,6563,6572 ,0,0,0}, - {15030,15080,14980 ,6568,6668,6566 ,0,0,0}, {14978,15029,14980 ,6565,6567,6566 ,0,0,0}, - {13407,14979,15080 ,6561,6560,6668 ,0,0,0}, {14980,15080,14979 ,6566,6668,6560 ,0,0,0}, - {13371,13374,13278 ,6669,6670,6671 ,0,0,0}, {15033,15038,15081 ,6672,6671,6671 ,0,0,0}, - {13284,13380,13293 ,6673,6674,6671 ,0,0,0}, {13374,13376,13287 ,6670,6669,6675 ,0,0,0}, - {13386,13316,13288 ,6670,6676,6677 ,0,0,0}, {15082,15083,15051 ,6324,6298,6672 ,0,0,0}, - {15084,15043,15042 ,6671,6672,6671 ,0,0,0}, {15085,15086,15047 ,6672,6671,6671 ,0,0,0}, - {13399,13310,13306 ,6678,6671,6679 ,0,0,0}, {15044,15043,15087 ,6671,6672,6680 ,0,0,0}, - {13312,13406,13314 ,6679,6671,6671 ,0,0,0}, {15088,15089,15041 ,6672,6672,6672 ,0,0,0}, - {15090,15091,15028 ,6672,6681,6672 ,0,0,0}, {15080,15030,15092 ,6671,6681,6672 ,0,0,0}, - {15093,15035,15034 ,6672,6672,6681 ,0,0,0}, {15031,15094,15095 ,6672,6672,6672 ,0,0,0}, - {15096,15079,15095 ,6672,6671,6672 ,0,0,0}, {15033,15097,15034 ,6672,6671,6681 ,0,0,0}, - {15036,15093,15094 ,6672,6672,6672 ,0,0,0}, {15090,15032,15096 ,6672,6672,6672 ,0,0,0}, - {15098,15099,15078 ,6671,6672,6672 ,0,0,0}, {15030,15029,15100 ,6681,6671,6671 ,0,0,0}, - {15037,15101,15098 ,6671,6681,6671 ,0,0,0}, {13407,15080,13314 ,6671,6671,6671 ,0,0,0}, - {15077,15089,15101 ,6672,6672,6681 ,0,0,0}, {13310,13400,13311 ,6671,6682,6672 ,0,0,0}, - {13312,13311,13401 ,6679,6672,6298 ,0,0,0}, {15044,15102,15039 ,6671,6671,6672 ,0,0,0}, - {15102,15088,15040 ,6671,6672,6672 ,0,0,0}, {13394,13395,13302 ,6672,6681,6670 ,0,0,0}, - {13306,13308,13398 ,6679,6669,6669 ,0,0,0}, {15086,15103,15048 ,6671,6672,6671 ,0,0,0}, - {13392,13394,13304 ,6671,6672,6681 ,0,0,0}, {13299,13316,13388 ,6669,6676,6298 ,0,0,0}, - {13299,13389,13392 ,6669,6669,6671 ,0,0,0}, {15104,15045,15083 ,6672,6671,6298 ,0,0,0}, - {15104,15085,15046 ,6672,6672,6672 ,0,0,0}, {13382,13290,13293 ,6683,6669,6671 ,0,0,0}, - {13288,13290,13383 ,6677,6669,6684 ,0,0,0}, {15053,15105,15050 ,6671,6685,6686 ,0,0,0}, - {15082,15049,15050 ,6324,6687,6686 ,0,0,0}, {15053,15052,15106 ,6671,6688,6688 ,0,0,0}, - {13376,13377,13283 ,6669,6689,6684 ,0,0,0}, {15107,15108,15055 ,6672,6690,6671 ,0,0,0}, - {15108,15109,15056 ,6690,6686,6690 ,0,0,0}, {15110,15107,15054 ,6691,6672,6691 ,0,0,0}, - {13278,13281,13370 ,6671,6692,6672 ,0,0,0}, {13280,13368,13281 ,6693,6673,6692 ,0,0,0}, - {13273,13365,13280 ,6672,6689,6693 ,0,0,0}, {15058,15111,15110 ,6686,6690,6691 ,0,0,0}, - {13364,13273,13276 ,6694,6672,6695 ,0,0,0}, {15057,15112,15111 ,6690,6691,6690 ,0,0,0}, - {13276,13275,13362 ,6695,6696,6697 ,0,0,0}, {15112,15061,15060 ,6691,6672,6688 ,0,0,0}, - {13270,13358,13359 ,6698,6699,6700 ,0,0,0}, {15113,15114,15059 ,6672,6688,6688 ,0,0,0}, - {15063,15062,15115 ,6688,6691,6701 ,0,0,0}, {15116,15064,15065 ,6686,6672,6671 ,0,0,0}, - {13356,13358,13218 ,6676,6699,6702 ,0,0,0}, {15066,15117,15118 ,6672,6671,6671 ,0,0,0}, - {13356,13217,13352 ,6676,6687,6703 ,0,0,0}, {15119,15067,15068 ,6686,6704,6672 ,0,0,0}, - {13217,13265,13408 ,6687,6705,6676 ,0,0,0}, {15070,15120,15069 ,6686,6706,6672 ,0,0,0}, - {13351,13409,13265 ,6698,6699,6705 ,0,0,0}, {13413,13256,13255 ,6697,6707,6708 ,0,0,0}, - {13412,13351,13256 ,6709,6698,6707 ,0,0,0}, {15121,15073,15075 ,6690,6671,6701 ,0,0,0}, - {13255,13349,13415 ,6708,6672,6694 ,0,0,0}, {15076,13243,15122 ,6690,6690,6686 ,0,0,0}, - {13419,13418,13347 ,6673,6689,6710 ,0,0,0}, {13241,13243,13458 ,6711,6690,6690 ,0,0,0}, - {13421,13419,13345 ,6686,6673,6692 ,0,0,0}, {13455,13239,13457 ,6712,6713,6685 ,0,0,0}, - {13340,13341,13427 ,6714,6684,6669 ,0,0,0}, {13451,13236,13238 ,6715,6716,6717 ,0,0,0}, - {13336,13433,13335 ,6718,6719,6691 ,0,0,0}, {13439,13437,13224 ,6298,6670,6676 ,0,0,0}, - {13445,13229,13231 ,6686,6704,6720 ,0,0,0}, {13231,13233,13448 ,6720,6669,6715 ,0,0,0}, - {13439,13226,13442 ,6298,6718,6669 ,0,0,0}, {13226,13229,13443 ,6718,6704,6691 ,0,0,0}, - {15114,15060,15059 ,6688,6688,6688 ,0,0,0}, {13334,13437,13436 ,6676,6670,6684 ,0,0,0}, - {13451,13449,13236 ,6715,6669,6716 ,0,0,0}, {13238,13239,13455 ,6717,6713,6712 ,0,0,0}, - {13238,13455,13451 ,6717,6712,6715 ,0,0,0}, {13339,13430,13341 ,6673,6721,6684 ,0,0,0}, - {13339,13335,13431 ,6673,6691,6670 ,0,0,0}, {13241,13458,13457 ,6711,6690,6685 ,0,0,0}, - {13241,13457,13239 ,6711,6685,6713 ,0,0,0}, {13344,13424,13421 ,6691,6669,6686 ,0,0,0}, - {13425,13344,13340 ,6720,6691,6714 ,0,0,0}, {13460,13458,13243 ,6671,6690,6690 ,0,0,0}, - {15074,15123,15124 ,6686,6722,6688 ,0,0,0}, {15071,15072,15125 ,6691,6723,6706 ,0,0,0}, - {13449,13448,13233 ,6669,6715,6669 ,0,0,0}, {13449,13233,13236 ,6669,6669,6716 ,0,0,0}, - {13448,13445,13231 ,6715,6686,6720 ,0,0,0}, {13445,13443,13229 ,6686,6691,6704 ,0,0,0}, - {13443,13442,13226 ,6691,6669,6718 ,0,0,0}, {13439,13224,13226 ,6298,6676,6718 ,0,0,0}, - {13437,13334,13224 ,6670,6676,6676 ,0,0,0}, {13436,13433,13336 ,6684,6719,6718 ,0,0,0}, - {13436,13336,13334 ,6684,6718,6676 ,0,0,0}, {13433,13431,13335 ,6719,6670,6691 ,0,0,0}, - {13431,13430,13339 ,6670,6721,6673 ,0,0,0}, {13430,13427,13341 ,6721,6669,6684 ,0,0,0}, - {13427,13425,13340 ,6669,6720,6714 ,0,0,0}, {13425,13424,13344 ,6720,6669,6691 ,0,0,0}, - {13421,13345,13344 ,6686,6692,6691 ,0,0,0}, {13419,13347,13345 ,6673,6710,6692 ,0,0,0}, - {13418,13415,13349 ,6689,6694,6672 ,0,0,0}, {13418,13349,13347 ,6689,6672,6710 ,0,0,0}, - {13415,13413,13255 ,6694,6697,6708 ,0,0,0}, {13413,13412,13256 ,6697,6709,6707 ,0,0,0}, - {13412,13409,13351 ,6709,6699,6698 ,0,0,0}, {13409,13408,13265 ,6699,6676,6705 ,0,0,0}, - {13408,13352,13217 ,6676,6703,6687 ,0,0,0}, {13356,13218,13217 ,6676,6702,6687 ,0,0,0}, - {13358,13270,13218 ,6699,6698,6702 ,0,0,0}, {13359,13362,13275 ,6700,6697,6696 ,0,0,0}, - {13359,13275,13270 ,6700,6696,6698 ,0,0,0}, {13362,13364,13276 ,6697,6694,6695 ,0,0,0}, - {13364,13365,13273 ,6694,6689,6672 ,0,0,0}, {13365,13368,13280 ,6689,6673,6693 ,0,0,0}, - {13368,13370,13281 ,6673,6672,6692 ,0,0,0}, {13370,13371,13278 ,6672,6669,6671 ,0,0,0}, - {13374,13287,13278 ,6670,6675,6671 ,0,0,0}, {13376,13283,13287 ,6669,6684,6675 ,0,0,0}, - {13377,13380,13284 ,6689,6674,6673 ,0,0,0}, {13377,13284,13283 ,6689,6673,6684 ,0,0,0}, - {13380,13382,13293 ,6674,6683,6671 ,0,0,0}, {13382,13383,13290 ,6683,6684,6669 ,0,0,0}, - {13383,13386,13288 ,6684,6670,6677 ,0,0,0}, {13386,13388,13316 ,6670,6298,6676 ,0,0,0}, - {13388,13389,13299 ,6298,6669,6669 ,0,0,0}, {13392,13304,13299 ,6671,6681,6669 ,0,0,0}, - {13394,13302,13304 ,6672,6670,6681 ,0,0,0}, {13395,13398,13308 ,6681,6669,6669 ,0,0,0}, - {13395,13308,13302 ,6681,6669,6670 ,0,0,0}, {13398,13399,13306 ,6669,6678,6679 ,0,0,0}, - {13399,13400,13310 ,6678,6682,6671 ,0,0,0}, {13400,13401,13311 ,6682,6298,6672 ,0,0,0}, - {13401,13406,13312 ,6298,6671,6679 ,0,0,0}, {13406,13407,13314 ,6671,6671,6671 ,0,0,0}, - {15080,15092,13314 ,6671,6672,6671 ,0,0,0}, {15030,15100,15092 ,6681,6671,6672 ,0,0,0}, - {15029,15028,15091 ,6671,6672,6681 ,0,0,0}, {15029,15091,15100 ,6671,6681,6671 ,0,0,0}, - {15028,15032,15090 ,6672,6672,6672 ,0,0,0}, {15032,15079,15096 ,6672,6671,6672 ,0,0,0}, - {15079,15031,15095 ,6671,6672,6672 ,0,0,0}, {15031,15036,15094 ,6672,6672,6672 ,0,0,0}, - {15036,15035,15093 ,6672,6672,6672 ,0,0,0}, {15034,15097,15093 ,6681,6671,6672 ,0,0,0}, - {15033,15081,15097 ,6672,6671,6671 ,0,0,0}, {15038,15078,15099 ,6671,6672,6672 ,0,0,0}, - {15038,15099,15081 ,6671,6672,6671 ,0,0,0}, {15078,15037,15098 ,6672,6671,6671 ,0,0,0}, - {15037,15077,15101 ,6671,6672,6681 ,0,0,0}, {15077,15041,15089 ,6672,6672,6672 ,0,0,0}, - {15041,15040,15088 ,6672,6672,6672 ,0,0,0}, {15040,15039,15102 ,6672,6672,6671 ,0,0,0}, - {15044,15087,15102 ,6671,6680,6671 ,0,0,0}, {15043,15084,15087 ,6672,6671,6680 ,0,0,0}, - {15042,15048,15103 ,6671,6671,6672 ,0,0,0}, {15042,15103,15084 ,6671,6672,6671 ,0,0,0}, - {15048,15047,15086 ,6671,6671,6671 ,0,0,0}, {15047,15046,15085 ,6671,6672,6672 ,0,0,0}, - {15046,15045,15104 ,6672,6671,6672 ,0,0,0}, {15045,15051,15083 ,6671,6672,6298 ,0,0,0}, - {15051,15049,15082 ,6672,6687,6324 ,0,0,0}, {15050,15105,15082 ,6686,6685,6324 ,0,0,0}, - {15053,15106,15105 ,6671,6688,6685 ,0,0,0}, {15052,15056,15109 ,6688,6690,6686 ,0,0,0}, - {15052,15109,15106 ,6688,6686,6688 ,0,0,0}, {15056,15055,15108 ,6690,6671,6690 ,0,0,0}, - {15055,15054,15107 ,6671,6691,6672 ,0,0,0}, {15054,15058,15110 ,6691,6686,6691 ,0,0,0}, - {15058,15057,15111 ,6686,6690,6690 ,0,0,0}, {15057,15061,15112 ,6690,6672,6691 ,0,0,0}, - {15060,15114,15112 ,6688,6688,6691 ,0,0,0}, {15063,15113,15059 ,6688,6672,6688 ,0,0,0}, - {15062,15126,15115 ,6691,6691,6701 ,0,0,0}, {15063,15115,15113 ,6688,6701,6672 ,0,0,0}, - {15116,15126,15064 ,6686,6691,6672 ,0,0,0}, {15062,15064,15126 ,6691,6672,6691 ,0,0,0}, - {15116,15065,15118 ,6686,6671,6671 ,0,0,0}, {15117,15066,15067 ,6671,6672,6704 ,0,0,0}, - {15118,15065,15066 ,6671,6671,6672 ,0,0,0}, {15119,15068,15069 ,6686,6672,6672 ,0,0,0}, - {15119,15117,15067 ,6686,6671,6704 ,0,0,0}, {15127,15120,15070 ,6688,6706,6686 ,0,0,0}, - {15120,15119,15069 ,6706,6686,6672 ,0,0,0}, {15127,15071,15125 ,6688,6691,6706 ,0,0,0}, - {15071,15127,15070 ,6691,6688,6686 ,0,0,0}, {15072,15124,15125 ,6723,6688,6706 ,0,0,0}, - {15074,15073,15123 ,6686,6671,6722 ,0,0,0}, {15072,15074,15124 ,6723,6686,6688 ,0,0,0}, - {15121,15075,15122 ,6690,6701,6686 ,0,0,0}, {15123,15073,15121 ,6722,6671,6690 ,0,0,0}, - {13243,15076,13460 ,6690,6690,6671 ,0,0,0}, {15122,15075,15076 ,6686,6701,6690 ,0,0,0}, - {15122,12820,14624 ,6724,6725,6726 ,0,0,0}, {14586,15123,15121 ,6727,6728,6729 ,0,0,0}, - {15125,14588,15127 ,6730,6731,6732 ,0,0,0}, {14729,15124,14727 ,6733,6734,6735 ,0,0,0}, - {15128,14738,15129 ,6736,6737,6738 ,0,0,0}, {14613,15128,15130 ,6739,6736,6736 ,0,0,0}, - {14654,15131,15132 ,6740,6741,6742 ,0,0,0}, {14653,15133,14612 ,6743,6744,6745 ,0,0,0}, - {14736,15134,15135 ,6746,6747,6748 ,0,0,0}, {14783,15136,14741 ,6749,6750,6751 ,0,0,0}, - {15137,15138,14781 ,6752,6753,6754 ,0,0,0}, {15134,14669,14782 ,6747,6755,6756 ,0,0,0}, - {15104,14705,14696 ,6757,6758,6759 ,0,0,0}, {13107,14705,15137 ,6760,6758,6752 ,0,0,0}, - {15086,14698,15103 ,6761,6762,6763 ,0,0,0}, {14697,15086,15085 ,6764,6761,6765 ,0,0,0}, - {14768,14703,15087 ,6766,6767,6768 ,0,0,0}, {14768,15084,14767 ,6766,6769,6770 ,0,0,0}, - {15102,14695,15088 ,6771,6772,6773 ,0,0,0}, {14695,15102,14703 ,6772,6771,6767 ,0,0,0}, - {15089,15088,14672 ,6774,6773,6775 ,0,0,0}, {14695,14672,15088 ,6772,6775,6773 ,0,0,0}, - {14670,15101,14671 ,6776,6777,6778 ,0,0,0}, {15089,14672,14671 ,6774,6775,6778 ,0,0,0}, - {14676,15099,14694 ,6779,6780,6781 ,0,0,0}, {15098,14670,14694 ,6782,6776,6781 ,0,0,0}, - {14675,15097,15081 ,6783,6784,6785 ,0,0,0}, {15094,15093,15139 ,6786,6787,6788 ,0,0,0}, - {15139,14693,15140 ,6788,6789,6788 ,0,0,0}, {15093,15097,14693 ,6787,6784,6789 ,0,0,0}, - {15141,14674,14647 ,6790,6791,6792 ,0,0,0}, {14674,15141,15140 ,6791,6790,6788 ,0,0,0}, - {14646,15142,14647 ,6793,6794,6792 ,0,0,0}, {15141,14647,15142 ,6790,6792,6794 ,0,0,0}, - {14646,14679,15143 ,6793,6795,6796 ,0,0,0}, {15143,15142,14646 ,6796,6794,6793 ,0,0,0}, - {15144,14679,14685 ,6797,6795,6798 ,0,0,0}, {14679,15144,15143 ,6795,6797,6796 ,0,0,0}, - {14689,15145,14685 ,6799,6800,6798 ,0,0,0}, {15144,14685,15145 ,6797,6798,6800 ,0,0,0}, - {14689,14682,15146 ,6799,6801,6802 ,0,0,0}, {15146,15145,14689 ,6802,6800,6799 ,0,0,0}, - {15147,14682,14691 ,6803,6801,6804 ,0,0,0}, {14682,15147,15146 ,6801,6803,6802 ,0,0,0}, - {12921,13324,14691 ,6805,6806,6804 ,0,0,0}, {15147,14691,13324 ,6803,6804,6806 ,0,0,0}, - {15091,15148,15149 ,6807,6808,6809 ,0,0,0}, {15093,14693,15139 ,6787,6789,6788 ,0,0,0}, - {15140,14693,14674 ,6788,6789,6791 ,0,0,0}, {14675,14693,15097 ,6783,6789,6784 ,0,0,0}, - {14676,14675,15081 ,6779,6783,6785 ,0,0,0}, {15081,15099,14676 ,6785,6780,6779 ,0,0,0}, - {14694,15099,15098 ,6781,6780,6782 ,0,0,0}, {14670,15098,15101 ,6776,6782,6777 ,0,0,0}, - {15101,15089,14671 ,6777,6774,6778 ,0,0,0}, {15139,15150,15094 ,6788,6810,6786 ,0,0,0}, - {15148,15091,15090 ,6808,6807,6811 ,0,0,0}, {15150,15095,15094 ,6810,6812,6786 ,0,0,0}, - {15149,15151,15100 ,6809,6813,6814 ,0,0,0}, {15100,15091,15149 ,6814,6807,6809 ,0,0,0}, - {15100,15152,15092 ,6814,6815,6816 ,0,0,0}, {15152,15100,15151 ,6815,6814,6813 ,0,0,0}, - {13314,15092,13315 ,6817,6816,6818 ,0,0,0}, {15152,13315,15092 ,6815,6818,6816 ,0,0,0}, - {15090,15153,15148 ,6811,6819,6808 ,0,0,0}, {14703,15102,15087 ,6767,6771,6768 ,0,0,0}, - {15153,15090,15096 ,6819,6811,6820 ,0,0,0}, {15154,15153,15096 ,6821,6819,6820 ,0,0,0}, - {15095,15150,15154 ,6812,6810,6821 ,0,0,0}, {15095,15154,15096 ,6812,6821,6820 ,0,0,0}, - {15087,15084,14768 ,6768,6769,6766 ,0,0,0}, {14734,15135,15136 ,6822,6748,6750 ,0,0,0}, - {14767,15103,14698 ,6770,6763,6762 ,0,0,0}, {15103,14767,15084 ,6763,6770,6769 ,0,0,0}, - {15086,14697,14698 ,6761,6764,6762 ,0,0,0}, {14696,14697,15085 ,6759,6764,6765 ,0,0,0}, - {15083,14705,15104 ,6823,6758,6757 ,0,0,0}, {15085,15104,14696 ,6765,6757,6759 ,0,0,0}, - {13107,15137,14781 ,6760,6752,6754 ,0,0,0}, {15083,15137,14705 ,6823,6752,6758 ,0,0,0}, - {15134,14736,14669 ,6747,6746,6755 ,0,0,0}, {15138,15134,14782 ,6753,6747,6756 ,0,0,0}, - {15136,14783,14734 ,6750,6749,6822 ,0,0,0}, {15155,14733,15156 ,6824,6825,6826 ,0,0,0}, - {15136,15156,14741 ,6750,6826,6751 ,0,0,0}, {15155,15131,14663 ,6824,6741,6827 ,0,0,0}, - {14733,15155,14663 ,6825,6824,6827 ,0,0,0}, {15132,15133,14653 ,6742,6744,6743 ,0,0,0}, - {14663,15131,14645 ,6827,6741,6828 ,0,0,0}, {15126,15116,15157 ,6829,6830,6831 ,0,0,0}, - {15117,15119,15130 ,6832,6833,6736 ,0,0,0}, {15133,15129,14732 ,6744,6738,6834 ,0,0,0}, - {15121,14624,14586 ,6729,6726,6727 ,0,0,0}, {15125,15124,14729 ,6730,6734,6733 ,0,0,0}, - {14589,14613,15120 ,6835,6739,6836 ,0,0,0}, {14747,15128,14613 ,6837,6736,6739 ,0,0,0}, - {15127,14589,15120 ,6732,6835,6836 ,0,0,0}, {14729,14588,15125 ,6733,6731,6730 ,0,0,0}, - {15127,14588,14589 ,6732,6731,6835 ,0,0,0}, {15123,14727,15124 ,6728,6735,6734 ,0,0,0}, - {14727,15123,14586 ,6735,6728,6727 ,0,0,0}, {14624,15121,15122 ,6726,6729,6724 ,0,0,0}, - {12820,15122,13243 ,6725,6724,6838 ,0,0,0}, {15105,15158,15082 ,6839,6840,6841 ,0,0,0}, - {15083,15082,15158 ,6823,6841,6840 ,0,0,0}, {15158,15105,15159 ,6840,6839,6842 ,0,0,0}, - {15083,15158,15137 ,6823,6840,6752 ,0,0,0}, {15160,15159,15106 ,6843,6842,6844 ,0,0,0}, - {14782,14781,15138 ,6756,6754,6753 ,0,0,0}, {15108,15160,15109 ,6845,6843,6846 ,0,0,0}, - {15108,15161,15160 ,6845,6847,6843 ,0,0,0}, {15162,15161,15107 ,6848,6847,6849 ,0,0,0}, - {14734,14736,15135 ,6822,6746,6748 ,0,0,0}, {15111,15162,15110 ,6850,6848,6851 ,0,0,0}, - {15111,15163,15162 ,6850,6852,6848 ,0,0,0}, {15164,15163,15112 ,6853,6852,6854 ,0,0,0}, - {14733,14741,15156 ,6825,6751,6826 ,0,0,0}, {15114,15165,15164 ,6855,6856,6853 ,0,0,0}, - {15113,15165,15114 ,6857,6856,6855 ,0,0,0}, {15166,15165,15115 ,6858,6856,6859 ,0,0,0}, - {14654,14645,15131 ,6740,6828,6741 ,0,0,0}, {15157,15166,15126 ,6831,6858,6829 ,0,0,0}, - {14653,14654,15132 ,6743,6740,6742 ,0,0,0}, {15167,15157,15118 ,6860,6831,6861 ,0,0,0}, - {14732,14612,15133 ,6834,6745,6744 ,0,0,0}, {15130,15167,15117 ,6736,6860,6832 ,0,0,0}, - {14738,14732,15129 ,6737,6834,6738 ,0,0,0}, {15120,14613,15130 ,6836,6739,6736 ,0,0,0}, - {14738,15128,14747 ,6737,6736,6837 ,0,0,0}, {15120,15130,15119 ,6836,6736,6833 ,0,0,0}, - {15118,15117,15167 ,6861,6832,6860 ,0,0,0}, {15116,15118,15157 ,6830,6861,6831 ,0,0,0}, - {15115,15126,15166 ,6859,6829,6858 ,0,0,0}, {15113,15115,15165 ,6857,6859,6856 ,0,0,0}, - {15112,15114,15164 ,6854,6855,6853 ,0,0,0}, {15111,15112,15163 ,6850,6854,6852 ,0,0,0}, - {15107,15110,15162 ,6849,6851,6848 ,0,0,0}, {15108,15107,15161 ,6845,6849,6847 ,0,0,0}, - {15106,15109,15160 ,6844,6846,6843 ,0,0,0}, {15105,15106,15159 ,6839,6844,6842 ,0,0,0}, - {15168,13115,13116 ,6862,6863,6864 ,0,0,0}, {14820,14809,14047 ,6865,6866,6867 ,0,0,0}, - {15169,14817,14816 ,6868,6869,6870 ,0,0,0}, {14819,14040,14806 ,6871,6872,6873 ,0,0,0}, - {14025,14799,14803 ,6874,6875,6876 ,0,0,0}, {14037,14822,14823 ,6877,6878,6879 ,0,0,0}, - {14833,14032,14031 ,6880,6881,6882 ,0,0,0}, {14830,14024,14027 ,6883,6884,6885 ,0,0,0}, - {15170,14843,14841 ,6886,6887,6888 ,0,0,0}, {15171,14837,14034 ,6889,6890,5525 ,0,0,0}, - {14854,14851,14110 ,6891,6892,6893 ,0,0,0}, {14847,15172,15173 ,6894,6895,6896 ,0,0,0}, - {14861,14099,14915 ,6897,6898,6899 ,0,0,0}, {14857,14105,14860 ,6900,6901,6902 ,0,0,0}, - {14146,14866,14144 ,6903,6904,6905 ,0,0,0}, {14909,14862,14142 ,6906,6907,6908 ,0,0,0}, - {14898,15174,14900 ,6909,6910,6911 ,0,0,0}, {14906,14147,14872 ,6912,6913,6914 ,0,0,0}, - {15175,14887,14879 ,6915,6916,6917 ,0,0,0}, {14897,15176,14884 ,6918,6919,6920 ,0,0,0}, - {15177,14894,14895 ,6921,6922,6923 ,0,0,0}, {14203,14206,14888 ,6924,6925,6926 ,0,0,0}, - {14203,14891,14204 ,6924,6927,5712 ,0,0,0}, {14191,14190,14881 ,6928,6929,6930 ,0,0,0}, - {14191,14896,14206 ,6928,6931,6925 ,0,0,0}, {14901,14903,14190 ,6932,6933,6929 ,0,0,0}, - {14190,14903,14881 ,6929,6933,6930 ,0,0,0}, {14901,14190,14235 ,6932,6929,6934 ,0,0,0}, - {14235,14237,14875 ,6934,6935,6936 ,0,0,0}, {14875,14901,14235 ,6936,6932,6934 ,0,0,0}, - {14907,14237,14239 ,6937,6935,6938 ,0,0,0}, {14237,14907,14875 ,6935,6937,6936 ,0,0,0}, - {14907,14239,14868 ,6937,6938,6939 ,0,0,0}, {14240,14869,14868 ,6940,6941,6939 ,0,0,0}, - {14868,14239,14240 ,6939,6938,6940 ,0,0,0}, {14869,14242,14913 ,6941,6942,6943 ,0,0,0}, - {14242,14869,14240 ,6942,6941,6940 ,0,0,0}, {14863,14913,14243 ,6944,6943,6945 ,0,0,0}, - {14242,14243,14913 ,6942,6945,6943 ,0,0,0}, {14243,15178,14858 ,6945,6946,6947 ,0,0,0}, - {14858,14863,14243 ,6947,6944,6945 ,0,0,0}, {14855,15178,15179 ,6948,6946,6949 ,0,0,0}, - {15178,14855,14858 ,6946,6948,6947 ,0,0,0}, {15180,14852,15179 ,6950,6951,6949 ,0,0,0}, - {14855,15179,14852 ,6948,6949,6951 ,0,0,0}, {15180,13213,13211 ,6950,126,3135 ,0,0,0}, - {13211,14852,15180 ,3135,6951,6950 ,0,0,0}, {14206,14896,14888 ,6925,6931,6926 ,0,0,0}, - {14191,14881,14896 ,6928,6930,6931 ,0,0,0}, {14891,14884,14204 ,6927,6920,5712 ,0,0,0}, - {14203,14888,14891 ,6924,6926,6927 ,0,0,0}, {15176,14897,14894 ,6919,6918,6922 ,0,0,0}, - {15176,14204,14884 ,6919,5712,6920 ,0,0,0}, {15177,14895,14887 ,6921,6923,6916 ,0,0,0}, - {15177,15176,14894 ,6921,6919,6922 ,0,0,0}, {15174,15175,14879 ,6910,6915,6917 ,0,0,0}, - {15175,15177,14887 ,6915,6921,6916 ,0,0,0}, {14149,15174,14898 ,6952,6910,6909 ,0,0,0}, - {14900,15174,14879 ,6911,6910,6917 ,0,0,0}, {14149,14872,14147 ,6952,6914,6913 ,0,0,0}, - {14872,14149,14898 ,6914,6952,6909 ,0,0,0}, {14904,14146,14147 ,6953,6903,6913 ,0,0,0}, - {14904,14147,14906 ,6953,6913,6912 ,0,0,0}, {14866,14911,14144 ,6904,6954,6905 ,0,0,0}, - {14904,14866,14146 ,6953,6904,6903 ,0,0,0}, {14909,14142,14911 ,6906,6908,6954 ,0,0,0}, - {14144,14911,14142 ,6905,6954,6908 ,0,0,0}, {14101,14862,14915 ,6955,6907,6899 ,0,0,0}, - {14142,14862,14101 ,6908,6907,6955 ,0,0,0}, {14111,14099,14861 ,6956,6898,6897 ,0,0,0}, - {14099,14101,14915 ,6898,6955,6899 ,0,0,0}, {14111,14860,14105 ,6956,6902,6901 ,0,0,0}, - {14860,14111,14861 ,6902,6956,6897 ,0,0,0}, {14854,14110,14105 ,6891,6893,6901 ,0,0,0}, - {14854,14105,14857 ,6891,6901,6900 ,0,0,0}, {14851,14849,15173 ,6892,6957,6896 ,0,0,0}, - {14851,15173,14110 ,6892,6896,6893 ,0,0,0}, {14847,14845,15172 ,6894,6958,6895 ,0,0,0}, - {14849,14847,15173 ,6957,6894,6896 ,0,0,0}, {14843,15170,14845 ,6887,6886,6958 ,0,0,0}, - {15172,14845,15170 ,6895,6958,6886 ,0,0,0}, {15171,14841,14839 ,6889,6888,6959 ,0,0,0}, - {15170,14841,15171 ,6886,6888,6889 ,0,0,0}, {14034,14837,14835 ,5525,6890,6960 ,0,0,0}, - {15171,14839,14837 ,6889,6959,6890 ,0,0,0}, {14835,14833,14031 ,6960,6880,6882 ,0,0,0}, - {14031,14034,14835 ,6882,5525,6960 ,0,0,0}, {14800,14027,14032 ,6961,6885,6881 ,0,0,0}, - {14800,14032,14833 ,6961,6881,6880 ,0,0,0}, {14830,14826,14024 ,6883,6962,6884 ,0,0,0}, - {14800,14830,14027 ,6961,6883,6885 ,0,0,0}, {14025,14024,14799 ,6874,6884,6875 ,0,0,0}, - {14826,14799,14024 ,6962,6875,6884 ,0,0,0}, {14030,14803,14822 ,6963,6876,6878 ,0,0,0}, - {14025,14803,14030 ,6874,6876,6963 ,0,0,0}, {14039,14037,14823 ,6964,6877,6879 ,0,0,0}, - {14037,14030,14822 ,6877,6963,6878 ,0,0,0}, {14039,14806,14040 ,6964,6873,6872 ,0,0,0}, - {14806,14039,14823 ,6873,6964,6879 ,0,0,0}, {14819,14820,14047 ,6871,6865,6867 ,0,0,0}, - {14819,14047,14040 ,6871,6867,6872 ,0,0,0}, {14809,14817,15181 ,6866,6869,6965 ,0,0,0}, - {14809,15181,14047 ,6866,6965,6867 ,0,0,0}, {15169,14816,15168 ,6868,6870,6862 ,0,0,0}, - {15181,14817,15169 ,6965,6869,6868 ,0,0,0}, {13115,15168,14816 ,6863,6862,6870 ,0,0,0}, - {13085,15182,14743 ,6966,6967,6968 ,0,0,0}, {15183,14787,15184 ,6969,6970,6971 ,0,0,0}, - {14655,14656,15185 ,6972,6973,6974 ,0,0,0}, {14789,15186,14790 ,6975,6976,6977 ,0,0,0}, - {15187,15188,14731 ,6978,6979,6980 ,0,0,0}, {15189,14786,15190 ,6981,6982,6983 ,0,0,0}, - {14788,14742,15191 ,6984,6985,6986 ,0,0,0}, {14793,15192,15193 ,6987,6988,6989 ,0,0,0}, - {14784,15194,14785 ,6990,6991,6992 ,0,0,0}, {14794,15195,14667 ,6993,6994,6995 ,0,0,0}, - {15196,14794,14735 ,6996,6993,6997 ,0,0,0}, {14668,15197,14795 ,6998,6999,7000 ,0,0,0}, - {15198,14668,14667 ,7001,6998,6995 ,0,0,0}, {14796,14795,15199 ,7002,7000,7003 ,0,0,0}, - {15197,15199,14795 ,6999,7003,7000 ,0,0,0}, {15200,14780,14796 ,7004,7005,7002 ,0,0,0}, - {14796,15199,15200 ,7002,7003,7004 ,0,0,0}, {14780,15201,14798 ,7005,7006,7007 ,0,0,0}, - {15201,14780,15200 ,7006,7005,7004 ,0,0,0}, {14797,14798,15202 ,7008,7007,7009 ,0,0,0}, - {15201,15202,14798 ,7006,7009,7007 ,0,0,0}, {15203,13107,14797 ,7010,82,7008 ,0,0,0}, - {14797,15202,15203 ,7008,7009,7010 ,0,0,0}, {13106,13107,15203 ,7011,82,7010 ,0,0,0}, - {14735,15193,15196 ,6997,6989,6996 ,0,0,0}, {15195,15198,14667 ,6994,7001,6995 ,0,0,0}, - {15198,15197,14668 ,7001,6999,6998 ,0,0,0}, {15195,14794,15196 ,6994,6993,6996 ,0,0,0}, - {15192,14793,14785 ,6988,6987,6992 ,0,0,0}, {15193,14735,14793 ,6989,6997,6987 ,0,0,0}, - {14785,15194,15192 ,6992,6991,6988 ,0,0,0}, {15189,15194,14784 ,6981,6991,6990 ,0,0,0}, - {15204,14790,15186 ,7012,6977,6976 ,0,0,0}, {14788,15190,14786 ,6984,6983,6982 ,0,0,0}, - {14784,14786,15189 ,6990,6982,6981 ,0,0,0}, {14742,14790,15204 ,6985,6977,7012 ,0,0,0}, - {14742,15204,15191 ,6985,7012,6986 ,0,0,0}, {15190,14788,15191 ,6983,6984,6986 ,0,0,0}, - {14787,14655,15184 ,6970,6972,6971 ,0,0,0}, {15186,14789,15188 ,6976,6975,6979 ,0,0,0}, - {15187,14731,14730 ,6978,6980,7013 ,0,0,0}, {14731,15188,14789 ,6980,6979,6975 ,0,0,0}, - {14730,14787,15183 ,7013,6970,6969 ,0,0,0}, {14730,15183,15187 ,7013,6969,6978 ,0,0,0}, - {14656,15182,15185 ,6973,6967,6974 ,0,0,0}, {15184,14655,15185 ,6971,6972,6974 ,0,0,0}, - {13085,14743,13082 ,6966,6968,7014 ,0,0,0}, {15182,14656,14743 ,6967,6973,6968 ,0,0,0}, - {15204,13100,15191 ,730,730,730 ,0,0,0}, {15199,15197,15195 ,730,730,730 ,0,0,0}, - {15197,15198,15195 ,730,730,730 ,0,0,0}, {15195,15196,15200 ,730,730,730 ,0,0,0}, - {15200,15199,15195 ,730,730,730 ,0,0,0}, {15201,15196,15193 ,730,730,730 ,0,0,0}, - {15196,15201,15200 ,730,730,730 ,0,0,0}, {15192,15202,15193 ,730,730,730 ,0,0,0}, - {15201,15193,15202 ,730,730,730 ,0,0,0}, {15203,15192,13106 ,730,730,730 ,0,0,0}, - {15203,15202,15192 ,730,730,730 ,0,0,0}, {15194,15189,13104 ,730,730,730 ,0,0,0}, - {15192,15194,13106 ,730,730,730 ,0,0,0}, {15186,13095,13098 ,730,730,7015 ,0,0,0}, - {13101,13104,15190 ,730,730,730 ,0,0,0}, {15183,13089,13092 ,7016,7015,7017 ,0,0,0}, - {15188,13092,13094 ,730,7017,7017 ,0,0,0}, {13086,13088,15185 ,730,730,730 ,0,0,0}, - {13085,13061,13063 ,730,730,730 ,0,0,0}, {13059,13086,15182 ,7015,730,730 ,0,0,0}, - {13065,13079,13077 ,730,730,7017 ,0,0,0}, {13061,13080,13067 ,730,7017,7015 ,0,0,0}, - {13073,13069,13074 ,730,730,730 ,0,0,0}, {13069,13077,13074 ,730,7017,730 ,0,0,0}, - {13070,13069,13073 ,730,730,730 ,0,0,0}, {13065,13067,13079 ,730,7015,730 ,0,0,0}, - {13069,13065,13077 ,730,730,7017 ,0,0,0}, {13080,13061,13084 ,7017,730,730 ,0,0,0}, - {13079,13067,13080 ,730,7015,7017 ,0,0,0}, {13085,13084,13061 ,730,730,730 ,0,0,0}, - {15182,13063,13059 ,730,730,7015 ,0,0,0}, {15182,13085,13063 ,730,730,730 ,0,0,0}, - {13088,15184,15185 ,730,7016,730 ,0,0,0}, {15185,15182,13086 ,730,730,730 ,0,0,0}, - {15183,15184,13089 ,7016,7016,7015 ,0,0,0}, {13088,13089,15184 ,730,7015,7016 ,0,0,0}, - {13092,15188,15187 ,7017,730,730 ,0,0,0}, {13092,15187,15183 ,7017,730,7016 ,0,0,0}, - {13094,13095,15186 ,7017,730,730 ,0,0,0}, {15188,13094,15186 ,730,7017,730 ,0,0,0}, - {13098,13100,15204 ,7015,730,730 ,0,0,0}, {15186,13098,15204 ,730,7015,730 ,0,0,0}, - {15191,13101,15190 ,730,730,730 ,0,0,0}, {15191,13100,13101 ,730,730,730 ,0,0,0}, - {15194,13104,13106 ,730,730,730 ,0,0,0}, {15189,15190,13104 ,730,730,730 ,0,0,0}, - {15205,15206,13057 ,7018,7019,7020 ,0,0,0}, {13057,15207,15205 ,7020,7021,7018 ,0,0,0}, - {13057,13040,15207 ,7020,7022,7021 ,0,0,0}, {13057,15208,15209 ,7020,7023,7024 ,0,0,0}, - {15206,15208,13057 ,7019,7023,7020 ,0,0,0}, {13057,15210,15211 ,7020,7025,7026 ,0,0,0}, - {15209,15210,13057 ,7024,7025,7020 ,0,0,0}, {15211,15212,13057 ,7026,7027,7020 ,0,0,0}, - {15213,13057,15214 ,7028,7020,7029 ,0,0,0}, {13057,15212,15214 ,7020,7027,7029 ,0,0,0}, - {15215,13057,15216 ,7030,7020,7031 ,0,0,0}, {13057,15213,15216 ,7020,7028,7031 ,0,0,0}, - {15217,13057,15218 ,7032,7020,7033 ,0,0,0}, {13057,15215,15218 ,7020,7030,7033 ,0,0,0}, - {13056,13057,15217 ,7034,7020,7032 ,0,0,0}, {13039,14712,15207 ,7035,7036,7037 ,0,0,0}, - {15209,15208,14702 ,7038,7039,7040 ,0,0,0}, {15206,15205,14711 ,7041,7042,7043 ,0,0,0}, - {15211,14769,15212 ,7044,7045,7046 ,0,0,0}, {14701,14714,15210 ,7047,7048,7049 ,0,0,0}, - {14770,14595,15213 ,7050,7051,7052 ,0,0,0}, {14770,15214,14661 ,7050,7053,7054 ,0,0,0}, - {14659,14718,15215 ,7055,7056,7057 ,0,0,0}, {15215,15216,14659 ,7057,7058,7055 ,0,0,0}, - {15218,14718,14704 ,7059,7056,7060 ,0,0,0}, {14718,15218,15215 ,7056,7059,7057 ,0,0,0}, - {14692,15217,14704 ,7061,7062,7060 ,0,0,0}, {15218,14704,15217 ,7059,7060,7062 ,0,0,0}, - {14692,13055,13056 ,7061,7063,4910 ,0,0,0}, {13056,15217,14692 ,4910,7062,7061 ,0,0,0}, - {14769,15211,14714 ,7045,7044,7048 ,0,0,0}, {14595,15216,15213 ,7051,7058,7052 ,0,0,0}, - {14659,15216,14595 ,7055,7058,7051 ,0,0,0}, {14702,15208,14710 ,7040,7039,7064 ,0,0,0}, - {14661,15214,15212 ,7054,7053,7046 ,0,0,0}, {14770,15213,15214 ,7050,7052,7053 ,0,0,0}, - {14769,14661,15212 ,7045,7054,7046 ,0,0,0}, {15210,14714,15211 ,7049,7048,7044 ,0,0,0}, - {15209,14702,14701 ,7038,7040,7047 ,0,0,0}, {14701,15210,15209 ,7047,7049,7038 ,0,0,0}, - {15205,14712,14711 ,7042,7036,7043 ,0,0,0}, {14710,15206,14711 ,7064,7041,7043 ,0,0,0}, - {15208,15206,14710 ,7039,7041,7064 ,0,0,0}, {13039,15207,13040 ,7035,7037,4929 ,0,0,0}, - {14712,15205,15207 ,7036,7042,7037 ,0,0,0}, {15219,15220,13023 ,7018,7019,7065 ,0,0,0}, - {13023,15221,15219 ,7065,7021,7018 ,0,0,0}, {13023,13006,15221 ,7065,7066,7021 ,0,0,0}, - {13023,15222,15223 ,7065,7023,7024 ,0,0,0}, {15220,15222,13023 ,7019,7023,7065 ,0,0,0}, - {13023,15224,15225 ,7065,7025,7026 ,0,0,0}, {15223,15224,13023 ,7024,7025,7065 ,0,0,0}, - {15225,15226,13023 ,7026,7027,7065 ,0,0,0}, {15227,13023,15228 ,7028,7065,7029 ,0,0,0}, - {13023,15226,15228 ,7065,7027,7029 ,0,0,0}, {15229,13023,15230 ,7030,7065,7031 ,0,0,0}, - {13023,15227,15230 ,7065,7028,7031 ,0,0,0}, {15231,13023,15232 ,7032,7065,7033 ,0,0,0}, - {13023,15229,15232 ,7065,7030,7033 ,0,0,0}, {13022,13023,15231 ,7067,7065,7032 ,0,0,0}, - {13005,14761,15221 ,7068,7069,7070 ,0,0,0}, {15223,15222,14602 ,7071,7072,7073 ,0,0,0}, - {15220,15219,14641 ,7074,7075,7076 ,0,0,0}, {15225,14621,15226 ,7077,7078,7079 ,0,0,0}, - {14603,14766,15224 ,7047,7080,7081 ,0,0,0}, {14585,14764,15227 ,7082,7083,7084 ,0,0,0}, - {14585,15228,14765 ,7082,7085,7086 ,0,0,0}, {14763,14639,15229 ,7087,7088,7089 ,0,0,0}, - {15229,15230,14763 ,7089,7090,7087 ,0,0,0}, {15232,14639,14640 ,7091,7088,7092 ,0,0,0}, - {14639,15232,15229 ,7088,7091,7089 ,0,0,0}, {14762,15231,14640 ,7093,7094,7092 ,0,0,0}, - {15232,14640,15231 ,7091,7092,7094 ,0,0,0}, {14762,13021,13022 ,7093,4831,4942 ,0,0,0}, - {13022,15231,14762 ,4942,7094,7093 ,0,0,0}, {14621,15225,14766 ,7078,7077,7080 ,0,0,0}, - {14764,15230,15227 ,7083,7090,7084 ,0,0,0}, {14763,15230,14764 ,7087,7090,7083 ,0,0,0}, - {14602,15222,14638 ,7073,7072,7095 ,0,0,0}, {14765,15228,15226 ,7086,7085,7079 ,0,0,0}, - {14585,15227,15228 ,7082,7084,7085 ,0,0,0}, {14621,14765,15226 ,7078,7086,7079 ,0,0,0}, - {15224,14766,15225 ,7081,7080,7077 ,0,0,0}, {15223,14602,14603 ,7071,7073,7047 ,0,0,0}, - {14603,15224,15223 ,7047,7081,7071 ,0,0,0}, {15219,14761,14641 ,7075,7069,7076 ,0,0,0}, - {14638,15220,14641 ,7095,7074,7076 ,0,0,0}, {15222,15220,14638 ,7072,7074,7095 ,0,0,0}, - {13005,15221,13006 ,7068,7070,4899 ,0,0,0}, {14761,15219,15221 ,7069,7075,7070 ,0,0,0}, - {15233,15234,12989 ,7018,7019,7065 ,0,0,0}, {12989,15235,15233 ,7065,7021,7018 ,0,0,0}, - {12989,12972,15235 ,7065,7096,7021 ,0,0,0}, {12989,15236,15237 ,7065,7023,7024 ,0,0,0}, - {15234,15236,12989 ,7019,7023,7065 ,0,0,0}, {12989,15238,15239 ,7065,7025,7026 ,0,0,0}, - {15237,15238,12989 ,7024,7025,7065 ,0,0,0}, {15239,15240,12989 ,7026,7027,7065 ,0,0,0}, - {15241,12989,15242 ,7028,7065,7029 ,0,0,0}, {12989,15240,15242 ,7065,7027,7029 ,0,0,0}, - {15243,12989,15244 ,7030,7065,7031 ,0,0,0}, {12989,15241,15244 ,7065,7028,7031 ,0,0,0}, - {15245,12989,15246 ,7032,7065,7033 ,0,0,0}, {12989,15243,15246 ,7065,7030,7033 ,0,0,0}, - {12988,12989,15245 ,7097,7065,7032 ,0,0,0}, {12971,14759,15235 ,7098,7099,7100 ,0,0,0}, - {15237,15236,14724 ,7101,7102,7103 ,0,0,0}, {15234,15233,14751 ,7104,7105,7076 ,0,0,0}, - {15239,14723,15240 ,7106,7107,7108 ,0,0,0}, {14758,14757,15238 ,7109,7110,7111 ,0,0,0}, - {14635,14632,15241 ,7112,7113,7114 ,0,0,0}, {14635,15242,14752 ,7112,7115,7116 ,0,0,0}, - {14637,14636,15243 ,7117,7118,7119 ,0,0,0}, {15243,15244,14637 ,7119,7120,7117 ,0,0,0}, - {15246,14636,14634 ,7121,7118,7122 ,0,0,0}, {14636,15246,15243 ,7118,7121,7119 ,0,0,0}, - {14633,15245,14634 ,7123,7124,7122 ,0,0,0}, {15246,14634,15245 ,7121,7122,7124 ,0,0,0}, - {14633,12987,12988 ,7123,4831,4831 ,0,0,0}, {12988,15245,14633 ,4831,7124,7123 ,0,0,0}, - {14723,15239,14757 ,7107,7106,7110 ,0,0,0}, {14632,15244,15241 ,7113,7120,7114 ,0,0,0}, - {14637,15244,14632 ,7117,7120,7113 ,0,0,0}, {14724,15236,14750 ,7103,7102,7125 ,0,0,0}, - {14752,15242,15240 ,7116,7115,7108 ,0,0,0}, {14635,15241,15242 ,7112,7114,7115 ,0,0,0}, - {14723,14752,15240 ,7107,7116,7108 ,0,0,0}, {15238,14757,15239 ,7111,7110,7106 ,0,0,0}, - {15237,14724,14758 ,7101,7103,7109 ,0,0,0}, {14758,15238,15237 ,7109,7111,7101 ,0,0,0}, - {15233,14759,14751 ,7105,7099,7076 ,0,0,0}, {14750,15234,14751 ,7125,7104,7076 ,0,0,0}, - {15236,15234,14750 ,7102,7104,7125 ,0,0,0}, {12971,15235,12972 ,7098,7100,4865 ,0,0,0}, - {14759,15233,15235 ,7099,7105,7100 ,0,0,0}, {15247,15248,12955 ,7018,7019,7126 ,0,0,0}, - {12955,15249,15247 ,7126,7021,7018 ,0,0,0}, {12955,12938,15249 ,7126,7127,7021 ,0,0,0}, - {12955,15250,15251 ,7126,7023,7024 ,0,0,0}, {15248,15250,12955 ,7019,7023,7126 ,0,0,0}, - {12955,15252,15253 ,7126,7025,7026 ,0,0,0}, {15251,15252,12955 ,7024,7025,7126 ,0,0,0}, - {15253,15254,12955 ,7026,7027,7126 ,0,0,0}, {15255,12955,15256 ,7028,7126,7029 ,0,0,0}, - {12955,15254,15256 ,7126,7027,7029 ,0,0,0}, {15257,12955,15258 ,7030,7126,7031 ,0,0,0}, - {12955,15255,15258 ,7126,7028,7031 ,0,0,0}, {15259,12955,15260 ,7032,7126,7033 ,0,0,0}, - {12955,15257,15260 ,7126,7030,7033 ,0,0,0}, {12954,12955,15259 ,7128,7126,7032 ,0,0,0}, - {12937,14740,15249 ,7129,7099,7130 ,0,0,0}, {15251,15250,14745 ,7131,7132,7133 ,0,0,0}, - {15248,15247,14739 ,7041,7075,7134 ,0,0,0}, {15253,14746,15254 ,7135,7107,7136 ,0,0,0}, - {14744,14772,15252 ,7137,7138,7139 ,0,0,0}, {14622,14623,15255 ,7140,7141,7142 ,0,0,0}, - {14622,15256,14728 ,7140,7143,7144 ,0,0,0}, {14706,14707,15257 ,7145,7146,7147 ,0,0,0}, - {15257,15258,14706 ,7147,7148,7145 ,0,0,0}, {15260,14707,14792 ,7149,7146,7150 ,0,0,0}, - {14707,15260,15257 ,7146,7149,7147 ,0,0,0}, {14791,15259,14792 ,7151,7152,7150 ,0,0,0}, - {15260,14792,15259 ,7149,7150,7152 ,0,0,0}, {14791,12953,12954 ,7151,7153,4831 ,0,0,0}, - {12954,15259,14791 ,4831,7152,7151 ,0,0,0}, {14746,15253,14772 ,7107,7135,7138 ,0,0,0}, - {14623,15258,15255 ,7141,7148,7142 ,0,0,0}, {14706,15258,14623 ,7145,7148,7141 ,0,0,0}, - {14745,15250,14748 ,7133,7132,7154 ,0,0,0}, {14728,15256,15254 ,7144,7143,7136 ,0,0,0}, - {14622,15255,15256 ,7140,7142,7143 ,0,0,0}, {14746,14728,15254 ,7107,7144,7136 ,0,0,0}, - {15252,14772,15253 ,7139,7138,7135 ,0,0,0}, {15251,14745,14744 ,7131,7133,7137 ,0,0,0}, - {14744,15252,15251 ,7137,7139,7131 ,0,0,0}, {15247,14740,14739 ,7075,7099,7134 ,0,0,0}, - {14748,15248,14739 ,7154,7041,7134 ,0,0,0}, {15250,15248,14748 ,7132,7041,7154 ,0,0,0}, - {12937,15249,12938 ,7129,7130,4929 ,0,0,0}, {14740,15247,15249 ,7099,7075,7130 ,0,0,0}, - {12898,12897,15261 ,4777,21,7155 ,0,0,0}, {14605,14618,15262 ,7156,7157,7158 ,0,0,0}, - {14614,15263,15264 ,7159,7160,7161 ,0,0,0}, {15265,15266,14596 ,7162,7163,7164 ,0,0,0}, - {15267,14662,14620 ,7165,7166,7167 ,0,0,0}, {14673,14717,15268 ,7168,7169,7170 ,0,0,0}, - {14658,15269,15270 ,7171,7172,7173 ,0,0,0}, {14648,15271,14680 ,7174,7175,7176 ,0,0,0}, - {15272,15273,14677 ,7177,7178,7179 ,0,0,0}, {15274,15275,14686 ,7180,7181,7182 ,0,0,0}, - {15276,14678,14680 ,7183,7184,7176 ,0,0,0}, {15277,15278,14687 ,7185,7186,7187 ,0,0,0}, - {15277,14684,15275 ,7185,7188,7181 ,0,0,0}, {14688,15278,15279 ,7189,7186,7190 ,0,0,0}, - {15278,14688,14687 ,7186,7189,7187 ,0,0,0}, {15280,14683,15279 ,7191,7192,7190 ,0,0,0}, - {14688,15279,14683 ,7189,7190,7192 ,0,0,0}, {15280,15281,14681 ,7191,7193,7194 ,0,0,0}, - {14681,14683,15280 ,7194,7192,7191 ,0,0,0}, {14690,15281,15282 ,7195,7193,7196 ,0,0,0}, - {15281,14690,14681 ,7193,7195,7194 ,0,0,0}, {12920,14691,15282 ,7197,7198,7196 ,0,0,0}, - {14690,15282,14691 ,7195,7196,7198 ,0,0,0}, {12921,14691,12920 ,7199,7198,7197 ,0,0,0}, - {14648,15273,15271 ,7174,7178,7175 ,0,0,0}, {14684,14686,15275 ,7188,7182,7181 ,0,0,0}, - {15277,14687,14684 ,7185,7187,7188 ,0,0,0}, {14678,15276,15274 ,7184,7183,7180 ,0,0,0}, - {15274,14686,14678 ,7180,7182,7184 ,0,0,0}, {15276,14680,15271 ,7183,7176,7175 ,0,0,0}, - {15273,14648,14677 ,7178,7174,7179 ,0,0,0}, {14673,15268,15272 ,7168,7170,7177 ,0,0,0}, - {14673,15272,14677 ,7168,7177,7179 ,0,0,0}, {14662,15265,14596 ,7166,7162,7164 ,0,0,0}, - {15270,14717,14658 ,7173,7169,7171 ,0,0,0}, {14717,15270,15268 ,7169,7173,7170 ,0,0,0}, - {14597,14596,15266 ,7200,7164,7163 ,0,0,0}, {14658,14597,15269 ,7171,7200,7172 ,0,0,0}, - {15269,14597,15266 ,7172,7200,7163 ,0,0,0}, {15267,15265,14662 ,7165,7162,7166 ,0,0,0}, - {15283,15267,14620 ,7201,7165,7167 ,0,0,0}, {14605,15262,15283 ,7156,7158,7201 ,0,0,0}, - {14605,15283,14620 ,7156,7201,7167 ,0,0,0}, {14719,15261,15263 ,7202,7155,7160 ,0,0,0}, - {15264,14618,14614 ,7161,7157,7159 ,0,0,0}, {14618,15264,15262 ,7157,7161,7158 ,0,0,0}, - {14719,15263,14614 ,7202,7160,7159 ,0,0,0}, {15261,14719,12898 ,7155,7202,4777 ,0,0,0}, - {12886,15274,12889 ,730,7015,730 ,0,0,0}, {15264,15263,15269 ,730,730,730 ,0,0,0}, - {12896,12892,15273 ,730,730,730 ,0,0,0}, {12890,15276,15271 ,730,730,7015 ,0,0,0}, - {15270,15269,15263 ,730,730,730 ,0,0,0}, {12897,15272,15261 ,730,730,730 ,0,0,0}, - {15267,15283,15262 ,730,730,730 ,0,0,0}, {15262,15264,15266 ,730,730,730 ,0,0,0}, - {15262,15266,15265 ,730,730,730 ,0,0,0}, {15267,15262,15265 ,730,730,730 ,0,0,0}, - {15263,15261,15270 ,730,730,730 ,0,0,0}, {15266,15264,15269 ,730,730,730 ,0,0,0}, - {15261,15268,15270 ,730,730,730 ,0,0,0}, {15272,12897,15273 ,730,730,730 ,0,0,0}, - {15268,15261,15272 ,730,730,730 ,0,0,0}, {15273,12892,15271 ,730,730,7015 ,0,0,0}, - {15273,12897,12896 ,730,730,730 ,0,0,0}, {15276,12890,12889 ,730,730,730 ,0,0,0}, - {15271,12892,12890 ,7015,730,730 ,0,0,0}, {15275,15274,12886 ,730,7015,730 ,0,0,0}, - {15274,15276,12889 ,7015,730,730 ,0,0,0}, {15277,12886,12885 ,7015,730,730 ,0,0,0}, - {12886,15277,15275 ,730,7015,730 ,0,0,0}, {15277,12885,15278 ,7015,730,730 ,0,0,0}, - {12878,15278,12882 ,730,730,730 ,0,0,0}, {15278,12885,12882 ,730,730,730 ,0,0,0}, - {12878,12877,15279 ,730,730,7015 ,0,0,0}, {15279,15278,12878 ,7015,730,730 ,0,0,0}, - {15279,12877,15280 ,7015,730,7015 ,0,0,0}, {12881,15281,15280 ,730,730,7015 ,0,0,0}, - {15280,12877,12881 ,7015,730,730 ,0,0,0}, {15281,12876,15282 ,730,730,7015 ,0,0,0}, - {12876,15281,12881 ,730,730,730 ,0,0,0}, {12872,12920,12876 ,730,7015,730 ,0,0,0}, - {15282,12876,12920 ,7015,730,7015 ,0,0,0}, {12919,12901,12917 ,7015,7015,730 ,0,0,0}, - {12872,12871,12919 ,730,730,7015 ,0,0,0}, {12913,12908,12911 ,7015,7015,7015 ,0,0,0}, - {12905,12914,12902 ,7015,7015,730 ,0,0,0}, {12913,12905,12907 ,7015,7015,7015 ,0,0,0}, - {12908,12913,12907 ,7015,7015,7015 ,0,0,0}, {12917,12902,12914 ,730,730,7015 ,0,0,0}, - {12914,12905,12913 ,7015,7015,7015 ,0,0,0}, {12919,12871,12901 ,7015,730,7015 ,0,0,0}, - {12917,12901,12902 ,730,7015,730 ,0,0,0}, {12919,12920,12872 ,7015,7015,730 ,0,0,0}, - {12848,14579,15284 ,126,7203,7204 ,0,0,0}, {15285,15286,14581 ,7205,7206,7207 ,0,0,0}, - {14631,15287,14699 ,7208,7209,7210 ,0,0,0}, {14720,14722,15288 ,7211,7212,7213 ,0,0,0}, - {15289,14592,15290 ,7214,7215,7216 ,0,0,0}, {15291,15292,14617 ,7217,7218,7219 ,0,0,0}, - {14642,15293,14760 ,7220,7221,7222 ,0,0,0}, {14611,15294,15295 ,7223,7224,7225 ,0,0,0}, - {14609,14610,15296 ,7226,7227,7228 ,0,0,0}, {14607,14601,15297 ,7229,7230,7231 ,0,0,0}, - {15298,14608,14607 ,7232,7233,7229 ,0,0,0}, {14599,14600,15299 ,7234,7235,7236 ,0,0,0}, - {15300,14601,14599 ,7237,7230,7234 ,0,0,0}, {14598,15301,14600 ,7238,7239,7235 ,0,0,0}, - {15299,14600,15301 ,7236,7235,7239 ,0,0,0}, {15302,14598,14591 ,7240,7238,7241 ,0,0,0}, - {14598,15302,15301 ,7238,7240,7239 ,0,0,0}, {14591,14590,15303 ,7241,7242,7243 ,0,0,0}, - {15303,15302,14591 ,7243,7240,7241 ,0,0,0}, {14587,15304,14590 ,7244,7245,7242 ,0,0,0}, - {15303,14590,15304 ,7243,7242,7245 ,0,0,0}, {15305,14587,12870 ,7246,7244,82 ,0,0,0}, - {14587,15305,15304 ,7244,7246,7245 ,0,0,0}, {12868,15305,12870 ,7011,7246,82 ,0,0,0}, - {14608,15298,15294 ,7233,7232,7224 ,0,0,0}, {15297,14601,15300 ,7231,7230,7237 ,0,0,0}, - {15300,14599,15299 ,7237,7234,7236 ,0,0,0}, {15297,15298,14607 ,7231,7232,7229 ,0,0,0}, - {15295,14610,14611 ,7225,7227,7223 ,0,0,0}, {15294,14611,14608 ,7224,7223,7233 ,0,0,0}, - {14610,15295,15296 ,7227,7225,7228 ,0,0,0}, {15291,14609,15296 ,7217,7226,7228 ,0,0,0}, - {15306,15288,14722 ,7247,7213,7212 ,0,0,0}, {14642,14617,15292 ,7220,7219,7218 ,0,0,0}, - {14609,15291,14617 ,7226,7217,7219 ,0,0,0}, {14760,15306,14722 ,7222,7247,7212 ,0,0,0}, - {14760,15293,15306 ,7222,7221,7247 ,0,0,0}, {15292,15293,14642 ,7218,7221,7220 ,0,0,0}, - {14581,15286,14631 ,7207,7206,7208 ,0,0,0}, {15288,15290,14720 ,7213,7216,7211 ,0,0,0}, - {15289,14594,14592 ,7214,7248,7215 ,0,0,0}, {14592,14720,15290 ,7215,7211,7216 ,0,0,0}, - {14594,15285,14581 ,7248,7205,7207 ,0,0,0}, {14594,15289,15285 ,7248,7214,7205 ,0,0,0}, - {14699,15287,15284 ,7210,7209,7204 ,0,0,0}, {15286,15287,14631 ,7206,7209,7208 ,0,0,0}, - {12848,12845,14579 ,126,4726,7203 ,0,0,0}, {15284,14579,14699 ,7204,7203,7210 ,0,0,0}, - {15299,15297,15300 ,7249,7250,7251 ,0,0,0}, {12850,15286,12852 ,726,726,7252 ,0,0,0}, - {15302,15297,15301 ,7253,7250,7253 ,0,0,0}, {15297,15299,15301 ,7250,7249,7253 ,0,0,0}, - {15298,15302,15303 ,7254,7253,7249 ,0,0,0}, {15302,15298,15297 ,7253,7254,7250 ,0,0,0}, - {15303,15304,15294 ,7249,7249,7255 ,0,0,0}, {15294,15298,15303 ,7255,7254,7249 ,0,0,0}, - {15304,15295,15294 ,7249,7256,7255 ,0,0,0}, {15305,12868,15295 ,7257,7257,7256 ,0,0,0}, - {15305,15295,15304 ,7257,7256,7249 ,0,0,0}, {15296,12867,15291 ,7258,726,7259 ,0,0,0}, - {15295,12868,15296 ,7256,7257,7258 ,0,0,0}, {15306,15293,12862 ,7260,7254,7257 ,0,0,0}, - {12864,15292,12867 ,7252,7261,726 ,0,0,0}, {12855,15290,12856 ,726,7262,7252 ,0,0,0}, - {12861,12858,15288 ,726,7252,7263 ,0,0,0}, {15287,12850,12849 ,7253,726,726 ,0,0,0}, - {15285,12855,12852 ,726,726,7252 ,0,0,0}, {12848,12825,12824 ,726,726,726 ,0,0,0}, - {12823,15284,12849 ,7264,7253,726 ,0,0,0}, {12829,12841,12842 ,726,7257,726 ,0,0,0}, - {12824,12830,12844 ,726,7264,726 ,0,0,0}, {12836,12838,12832 ,7257,726,7257 ,0,0,0}, - {12838,12841,12832 ,726,7257,7257 ,0,0,0}, {12836,12832,12834 ,7257,7257,7257 ,0,0,0}, - {12842,12830,12829 ,726,7264,726 ,0,0,0}, {12841,12829,12832 ,7257,726,7257 ,0,0,0}, - {12846,12824,12844 ,726,726,726 ,0,0,0}, {12844,12830,12842 ,726,7264,726 ,0,0,0}, - {12825,12848,15284 ,726,726,7253 ,0,0,0}, {12824,12846,12848 ,726,726,726 ,0,0,0}, - {12849,15284,15287 ,726,7253,7253 ,0,0,0}, {12825,15284,12823 ,726,7253,7264 ,0,0,0}, - {12852,15286,15285 ,7252,726,726 ,0,0,0}, {15286,12850,15287 ,726,726,7253 ,0,0,0}, - {15290,12855,15289 ,7262,726,7262 ,0,0,0}, {15289,12855,15285 ,7262,726,726 ,0,0,0}, - {12858,12856,15288 ,7252,7252,7263 ,0,0,0}, {12856,15290,15288 ,7252,7262,7263 ,0,0,0}, - {15288,15306,12861 ,7263,7260,726 ,0,0,0}, {12864,12862,15293 ,7252,7257,7254 ,0,0,0}, - {12862,12861,15306 ,7257,726,7260 ,0,0,0}, {12867,15292,15291 ,726,7261,7259 ,0,0,0}, - {12864,15293,15292 ,7252,7254,7261 ,0,0,0}, {12867,15296,12868 ,726,7258,7257 ,0,0,0}, - {12798,15307,14573 ,4799,7265,7266 ,0,0,0}, {15308,14575,15309 ,7267,7268,7269 ,0,0,0}, - {14574,14749,15310 ,7270,7271,7272 ,0,0,0}, {14756,15311,14583 ,7273,7274,7275 ,0,0,0}, - {15312,15313,14755 ,7276,7277,7278 ,0,0,0}, {15314,14753,15315 ,7279,7280,7281 ,0,0,0}, - {14773,14725,15316 ,7282,7283,7284 ,0,0,0}, {14774,15317,15318 ,7285,7286,7287 ,0,0,0}, - {14628,15319,14629 ,7288,7289,7290 ,0,0,0}, {14775,15320,14626 ,7291,7292,7293 ,0,0,0}, - {15321,14775,14584 ,7294,7291,7295 ,0,0,0}, {14625,15322,14776 ,7296,7297,7298 ,0,0,0}, - {15323,14625,14626 ,7299,7296,7293 ,0,0,0}, {14777,14776,15324 ,7300,7298,7301 ,0,0,0}, - {15322,15324,14776 ,7297,7301,7298 ,0,0,0}, {15325,14726,14777 ,7302,7303,7300 ,0,0,0}, - {14777,15324,15325 ,7300,7301,7302 ,0,0,0}, {14726,15326,14779 ,7303,7304,7305 ,0,0,0}, - {15326,14726,15325 ,7304,7303,7302 ,0,0,0}, {14778,14779,15327 ,7306,7305,7307 ,0,0,0}, - {15326,15327,14779 ,7304,7307,7305 ,0,0,0}, {15328,12820,14778 ,7308,21,7306 ,0,0,0}, - {14778,15327,15328 ,7306,7307,7308 ,0,0,0}, {12819,12820,15328 ,7309,21,7308 ,0,0,0}, - {14584,15318,15321 ,7295,7287,7294 ,0,0,0}, {15320,15323,14626 ,7292,7299,7293 ,0,0,0}, - {15323,15322,14625 ,7299,7297,7296 ,0,0,0}, {15320,14775,15321 ,7292,7291,7294 ,0,0,0}, - {15317,14774,14629 ,7286,7285,7290 ,0,0,0}, {15318,14584,14774 ,7287,7295,7285 ,0,0,0}, - {14629,15319,15317 ,7290,7289,7286 ,0,0,0}, {15314,15319,14628 ,7279,7289,7288 ,0,0,0}, - {15329,14583,15311 ,7310,7275,7274 ,0,0,0}, {14773,15315,14753 ,7282,7281,7280 ,0,0,0}, - {14628,14753,15314 ,7288,7280,7279 ,0,0,0}, {14725,14583,15329 ,7283,7275,7310 ,0,0,0}, - {14725,15329,15316 ,7283,7310,7284 ,0,0,0}, {15315,14773,15316 ,7281,7282,7284 ,0,0,0}, - {14575,14574,15309 ,7268,7270,7269 ,0,0,0}, {15311,14756,15313 ,7274,7273,7277 ,0,0,0}, - {15312,14755,14754 ,7276,7278,7311 ,0,0,0}, {14755,15313,14756 ,7278,7277,7273 ,0,0,0}, - {14754,14575,15308 ,7311,7268,7267 ,0,0,0}, {14754,15308,15312 ,7311,7267,7276 ,0,0,0}, - {14749,15307,15310 ,7271,7265,7272 ,0,0,0}, {15309,14574,15310 ,7269,7270,7272 ,0,0,0}, - {12798,14573,12795 ,4799,7266,7199 ,0,0,0}, {15307,14749,14573 ,7265,7271,7266 ,0,0,0}, - {15320,12790,12787 ,730,7312,6103 ,0,0,0}, {12783,15324,12786 ,7313,730,730 ,0,0,0}, - {12793,15317,12797 ,7314,7015,7315 ,0,0,0}, {15321,15318,12792 ,730,730,7316 ,0,0,0}, - {15316,15310,15315 ,730,7317,7313 ,0,0,0}, {15319,15307,12798 ,730,7318,7319 ,0,0,0}, - {15308,15309,15329 ,7320,7316,7316 ,0,0,0}, {15311,15313,15308 ,7320,6103,7320 ,0,0,0}, - {15312,15308,15313 ,6111,7320,6103 ,0,0,0}, {15316,15329,15309 ,730,7316,7316 ,0,0,0}, - {15329,15311,15308 ,7316,7320,7320 ,0,0,0}, {15307,15315,15310 ,7318,7313,7317 ,0,0,0}, - {15310,15316,15309 ,7317,730,7316 ,0,0,0}, {15319,15314,15307 ,730,7316,7318 ,0,0,0}, - {15307,15314,15315 ,7318,7316,7313 ,0,0,0}, {12797,15317,12798 ,7315,7015,7319 ,0,0,0}, - {12798,15317,15319 ,7319,7015,730 ,0,0,0}, {12792,15318,12793 ,7316,730,7314 ,0,0,0}, - {12793,15318,15317 ,7314,730,7015 ,0,0,0}, {15321,12792,12790 ,730,7316,7312 ,0,0,0}, - {12787,15323,15320 ,6103,7017,730 ,0,0,0}, {12790,15320,15321 ,7312,730,730 ,0,0,0}, - {15323,12787,15322 ,7017,6103,7017 ,0,0,0}, {12786,15324,15322 ,730,730,7017 ,0,0,0}, - {15322,12787,12786 ,7017,6103,730 ,0,0,0}, {15324,12783,12782 ,730,7313,730 ,0,0,0}, - {12782,12778,15325 ,730,7316,730 ,0,0,0}, {15325,15324,12782 ,730,730,730 ,0,0,0}, - {15326,12778,12780 ,7016,7316,7313 ,0,0,0}, {12778,15326,15325 ,7316,7016,730 ,0,0,0}, - {12774,15327,12780 ,7015,730,7313 ,0,0,0}, {15326,12780,15327 ,7016,7313,730 ,0,0,0}, - {15328,12774,12819 ,730,7015,730 ,0,0,0}, {15328,15327,12774 ,730,730,7015 ,0,0,0}, - {12774,12776,12819 ,7015,7015,730 ,0,0,0}, {12817,12799,12814 ,730,730,730 ,0,0,0}, - {12776,12772,12817 ,7015,730,730 ,0,0,0}, {12811,12807,12808 ,730,730,7017 ,0,0,0}, - {12802,12813,12801 ,7015,7016,730 ,0,0,0}, {12811,12802,12805 ,730,7015,730 ,0,0,0}, - {12807,12811,12805 ,730,730,730 ,0,0,0}, {12814,12801,12813 ,730,730,7016 ,0,0,0}, - {12813,12802,12811 ,7016,7015,730 ,0,0,0}, {12817,12772,12799 ,730,730,730 ,0,0,0}, - {12814,12799,12801 ,730,730,730 ,0,0,0}, {12817,12819,12776 ,730,730,7015 ,0,0,0}, - {13330,15330,15331 ,7321,1711,7322 ,0,0,0}, {13320,13317,15332 ,7323,7324,7325 ,0,0,0}, - {15333,13319,13328 ,7326,7327,7328 ,0,0,0}, {15146,15334,15145 ,7329,7330,7331 ,0,0,0}, - {15335,15336,13324 ,7332,7333,7334 ,0,0,0}, {15143,15337,15142 ,7335,7336,7337 ,0,0,0}, - {15337,15144,15338 ,7336,7338,7339 ,0,0,0}, {15141,15142,15339 ,7340,7337,7341 ,0,0,0}, - {15337,15339,15142 ,7336,7341,7337 ,0,0,0}, {15340,15140,15141 ,1359,1359,7340 ,0,0,0}, - {15141,15339,15340 ,7340,7341,1359 ,0,0,0}, {15338,15144,15145 ,7339,7338,7331 ,0,0,0}, - {15337,15143,15144 ,7336,7335,7338 ,0,0,0}, {15334,15146,15147 ,7330,7329,7342 ,0,0,0}, - {15334,15338,15145 ,7330,7339,7331 ,0,0,0}, {15147,13324,15336 ,7342,7334,7333 ,0,0,0}, - {15336,15334,15147 ,7333,7330,7342 ,0,0,0}, {13323,15332,15335 ,7343,7325,7332 ,0,0,0}, - {13323,15335,13324 ,7343,7332,7334 ,0,0,0}, {13317,15341,15332 ,7324,7344,7325 ,0,0,0}, - {13323,13320,15332 ,7343,7323,7325 ,0,0,0}, {15333,15341,13319 ,7326,7344,7327 ,0,0,0}, - {13317,13319,15341 ,7324,7327,7344 ,0,0,0}, {15333,13327,15331 ,7326,7345,7322 ,0,0,0}, - {13328,13327,15333 ,7328,7345,7326 ,0,0,0}, {15330,13330,13296 ,1711,7321,1711 ,0,0,0}, - {15331,13327,13330 ,7322,7345,7321 ,0,0,0}, {15330,13298,15342 ,2197,7346,7346 ,0,0,0}, - {13298,15330,13296 ,7346,2197,2197 ,0,0,0}, {15343,15344,15150 ,1435,7347,7348 ,0,0,0}, - {15151,15149,15345 ,7349,7350,7351 ,0,0,0}, {15148,15153,15346 ,7352,7353,7354 ,0,0,0}, - {13309,15347,13307 ,7355,7356,7357 ,0,0,0}, {15348,15349,13315 ,7358,7359,7360 ,0,0,0}, - {13303,15350,13301 ,7361,7362,7363 ,0,0,0}, {13303,13305,15350 ,7361,7364,7362 ,0,0,0}, - {13300,13301,15351 ,7365,7363,7366 ,0,0,0}, {15350,15351,13301 ,7362,7366,7363 ,0,0,0}, - {15342,13298,13300 ,1790,1790,7365 ,0,0,0}, {13300,15351,15342 ,7365,7366,1790 ,0,0,0}, - {13307,15352,13305 ,7357,7367,7364 ,0,0,0}, {15350,13305,15352 ,7362,7364,7367 ,0,0,0}, - {15148,15353,15149 ,7352,7368,7350 ,0,0,0}, {13309,13313,15347 ,7355,7369,7356 ,0,0,0}, - {15347,15352,13307 ,7356,7367,7357 ,0,0,0}, {13313,13315,15349 ,7369,7360,7359 ,0,0,0}, - {15349,15347,13313 ,7359,7356,7369 ,0,0,0}, {15348,13315,15152 ,7358,7360,7370 ,0,0,0}, - {15345,15152,15151 ,7351,7370,7349 ,0,0,0}, {15152,15345,15348 ,7370,7351,7358 ,0,0,0}, - {15353,15345,15149 ,7368,7351,7350 ,0,0,0}, {15346,15154,15344 ,7354,7371,7347 ,0,0,0}, - {15154,15346,15153 ,7371,7354,7353 ,0,0,0}, {15353,15148,15346 ,7368,7352,7354 ,0,0,0}, - {15343,15150,15139 ,1435,7348,1435 ,0,0,0}, {15344,15154,15150 ,7347,7371,7348 ,0,0,0}, - {15139,15340,15343 ,1398,7372,1398 ,0,0,0}, {15340,15139,15140 ,7372,1398,7372 ,0,0,0}, - {15340,15344,15343 ,7373,730,730 ,0,0,0}, {15341,15350,15352 ,730,730,730 ,0,0,0}, - {15338,15345,15353 ,7374,7375,7375 ,0,0,0}, {15353,15346,15337 ,7375,730,7373 ,0,0,0}, - {15336,15349,15348 ,7375,7375,7375 ,0,0,0}, {15348,15345,15334 ,7375,7375,730 ,0,0,0}, - {15352,15347,15332 ,730,730,7376 ,0,0,0}, {15347,15349,15335 ,730,7375,7375 ,0,0,0}, - {15331,15351,15333 ,730,730,730 ,0,0,0}, {15350,15333,15351 ,730,730,730 ,0,0,0}, - {15331,15330,15342 ,730,730,730 ,0,0,0}, {15342,15351,15331 ,730,730,730 ,0,0,0}, - {15352,15332,15341 ,730,7376,730 ,0,0,0}, {15350,15341,15333 ,730,730,730 ,0,0,0}, - {15347,15335,15332 ,730,7375,7376 ,0,0,0}, {15349,15336,15335 ,7375,7375,7375 ,0,0,0}, - {15348,15334,15336 ,7375,730,7375 ,0,0,0}, {15345,15338,15334 ,7375,7374,730 ,0,0,0}, - {15353,15337,15338 ,7375,7373,7374 ,0,0,0}, {15346,15339,15337 ,730,730,7373 ,0,0,0}, - {15340,15339,15344 ,7373,730,730 ,0,0,0}, {15346,15344,15339 ,730,730,730 ,0,0,0}, - {15354,13228,15355 ,7377,1435,1435 ,0,0,0}, {15356,13244,15357 ,7378,7379,7379 ,0,0,0}, - {15358,13219,13223 ,7380,7380,7377 ,0,0,0}, {13251,15359,15360 ,7381,7381,7382 ,0,0,0}, - {13246,15361,13249 ,7378,7383,7383 ,0,0,0}, {13258,15362,13260 ,7384,7385,7385 ,0,0,0}, - {15363,13258,13253 ,7384,7384,7382 ,0,0,0}, {13263,13260,15364 ,7386,7385,7386 ,0,0,0}, - {15362,15364,13260 ,7385,7386,7385 ,0,0,0}, {15365,13266,13263 ,7387,7388,7386 ,0,0,0}, - {13263,15364,15365 ,7386,7386,7387 ,0,0,0}, {15360,15363,13253 ,7382,7384,7382 ,0,0,0}, - {15363,15362,13258 ,7384,7385,7384 ,0,0,0}, {13249,15359,13251 ,7383,7381,7381 ,0,0,0}, - {13251,15360,13253 ,7381,7382,7382 ,0,0,0}, {13246,15356,15361 ,7378,7378,7383 ,0,0,0}, - {13249,15361,15359 ,7383,7383,7381 ,0,0,0}, {13244,13219,15357 ,7379,7380,7379 ,0,0,0}, - {13246,13244,15356 ,7378,7379,7378 ,0,0,0}, {15358,13223,15354 ,7380,7377,7377 ,0,0,0}, - {15357,13219,15358 ,7379,7380,7380 ,0,0,0}, {13228,15354,13223 ,1435,7377,7377 ,0,0,0}, - {15355,13225,15366 ,1398,1398,1398 ,0,0,0}, {13225,15355,13228 ,1398,1398,1398 ,0,0,0}, - {15367,15368,13350 ,7389,7390,7390 ,0,0,0}, {15369,13346,15370 ,7391,7391,7392 ,0,0,0}, - {13348,13257,15371 ,7392,7393,7393 ,0,0,0}, {13338,15372,15373 ,7394,7395,7394 ,0,0,0}, - {13343,15374,13342 ,7396,7396,7395 ,0,0,0}, {13333,15375,15376 ,7397,7398,7397 ,0,0,0}, - {15375,13333,13337 ,7398,7397,7398 ,0,0,0}, {15377,13331,15376 ,7399,7399,7397 ,0,0,0}, - {13333,15376,13331 ,7397,7397,7399 ,0,0,0}, {15377,15366,13225 ,7399,1359,1359 ,0,0,0}, - {13225,13331,15377 ,1359,7399,7399 ,0,0,0}, {15370,13348,15371 ,7392,7392,7393 ,0,0,0}, - {13337,13338,15373 ,7398,7394,7394 ,0,0,0}, {15373,15375,13337 ,7394,7398,7398 ,0,0,0}, - {15372,13338,13342 ,7395,7394,7395 ,0,0,0}, {15369,15374,13343 ,7391,7396,7396 ,0,0,0}, - {13342,15374,15372 ,7395,7396,7395 ,0,0,0}, {13348,15370,13346 ,7392,7392,7391 ,0,0,0}, - {13343,13346,15369 ,7396,7391,7391 ,0,0,0}, {13350,15368,13257 ,7390,7390,7393 ,0,0,0}, - {13257,15368,15371 ,7393,7390,7393 ,0,0,0}, {15367,13350,13216 ,7389,7390,7400 ,0,0,0}, - {15365,15367,13216 ,7401,7402,7402 ,0,0,0}, {15365,13216,13266 ,7401,7402,7401 ,0,0,0}, - {15377,15358,15354 ,7403,7403,7404 ,0,0,0}, {15363,15371,15362 ,7375,7375,730 ,0,0,0}, - {15359,15369,15360 ,7375,730,730 ,0,0,0}, {15370,15363,15360 ,730,7375,730 ,0,0,0}, - {15356,15372,15361 ,7373,7375,7373 ,0,0,0}, {15374,15359,15361 ,730,7375,7373 ,0,0,0}, - {15357,15376,15375 ,7405,7406,730 ,0,0,0}, {15373,15356,15357 ,7373,7373,7405 ,0,0,0}, - {15377,15376,15358 ,7403,7406,7403 ,0,0,0}, {15354,15355,15366 ,7404,730,7407 ,0,0,0}, - {15366,15377,15354 ,7407,7403,7404 ,0,0,0}, {15376,15357,15358 ,7406,7405,7403 ,0,0,0}, - {15373,15357,15375 ,7373,7405,730 ,0,0,0}, {15372,15356,15373 ,7375,7373,7373 ,0,0,0}, - {15374,15361,15372 ,730,7373,7375 ,0,0,0}, {15369,15359,15374 ,730,7375,730 ,0,0,0}, - {15370,15360,15369 ,730,730,730 ,0,0,0}, {15371,15363,15370 ,7375,7375,730 ,0,0,0}, - {15368,15362,15371 ,730,730,7375 ,0,0,0}, {15364,15368,15367 ,7373,730,730 ,0,0,0}, - {15368,15364,15362 ,730,7373,730 ,0,0,0}, {15364,15367,15365 ,7373,730,7405 ,0,0,0}, - {15378,15137,15379 ,7408,7409,7410 ,0,0,0}, {15380,15135,15381 ,7411,7412,7412 ,0,0,0}, - {15382,15134,15138 ,7413,7413,7408 ,0,0,0}, {15155,15383,15384 ,7414,7414,7415 ,0,0,0}, - {15136,15385,15156 ,7411,7416,7416 ,0,0,0}, {15132,15386,15133 ,7417,7418,7418 ,0,0,0}, - {15387,15132,15131 ,7417,7417,7415 ,0,0,0}, {15129,15133,15388 ,7419,7418,7419 ,0,0,0}, - {15386,15388,15133 ,7418,7419,7418 ,0,0,0}, {15389,15128,15129 ,1790,1790,7419 ,0,0,0}, - {15129,15388,15389 ,7419,7419,1790 ,0,0,0}, {15384,15387,15131 ,7415,7417,7415 ,0,0,0}, - {15387,15386,15132 ,7417,7418,7417 ,0,0,0}, {15156,15383,15155 ,7416,7414,7414 ,0,0,0}, - {15155,15384,15131 ,7414,7415,7415 ,0,0,0}, {15136,15380,15385 ,7411,7411,7416 ,0,0,0}, - {15156,15385,15383 ,7416,7416,7414 ,0,0,0}, {15135,15134,15381 ,7412,7413,7412 ,0,0,0}, - {15136,15135,15380 ,7411,7412,7411 ,0,0,0}, {15382,15138,15378 ,7413,7408,7408 ,0,0,0}, - {15381,15134,15382 ,7412,7413,7413 ,0,0,0}, {15137,15378,15138 ,7409,7408,7408 ,0,0,0}, - {15158,15390,15379 ,7420,7420,7421 ,0,0,0}, {15158,15379,15137 ,7420,7421,7421 ,0,0,0}, - {15391,15392,15167 ,1711,7422,7422 ,0,0,0}, {15393,15165,15394 ,7423,7423,7424 ,0,0,0}, - {15166,15157,15395 ,7424,7425,7425 ,0,0,0}, {15162,15396,15397 ,7426,7427,7426 ,0,0,0}, - {15164,15398,15163 ,7428,7428,7427 ,0,0,0}, {15160,15399,15400 ,7429,7430,7429 ,0,0,0}, - {15399,15160,15161 ,7430,7429,7430 ,0,0,0}, {15401,15159,15400 ,7431,7431,7429 ,0,0,0}, - {15160,15400,15159 ,7429,7429,7431 ,0,0,0}, {15401,15390,15158 ,7431,7432,82 ,0,0,0}, - {15158,15159,15401 ,82,7431,7431 ,0,0,0}, {15394,15166,15395 ,7424,7424,7425 ,0,0,0}, - {15161,15162,15397 ,7430,7426,7426 ,0,0,0}, {15397,15399,15161 ,7426,7430,7430 ,0,0,0}, - {15396,15162,15163 ,7427,7426,7427 ,0,0,0}, {15393,15398,15164 ,7423,7428,7428 ,0,0,0}, - {15163,15398,15396 ,7427,7428,7427 ,0,0,0}, {15166,15394,15165 ,7424,7424,7423 ,0,0,0}, - {15164,15165,15393 ,7428,7423,7423 ,0,0,0}, {15167,15392,15157 ,7422,7422,7425 ,0,0,0}, - {15157,15392,15395 ,7425,7422,7425 ,0,0,0}, {15391,15167,15130 ,1711,7422,1711 ,0,0,0}, - {15130,15389,15391 ,2197,2197,2197 ,0,0,0}, {15389,15130,15128 ,2197,2197,2197 ,0,0,0}, - {15389,15392,15391 ,7433,730,730 ,0,0,0}, {15380,15381,15397 ,7375,7375,730 ,0,0,0}, - {15384,15394,15387 ,730,730,730 ,0,0,0}, {15394,15395,15386 ,730,7376,730 ,0,0,0}, - {15385,15398,15383 ,730,730,7376 ,0,0,0}, {15393,15384,15383 ,730,730,7376 ,0,0,0}, - {15396,15385,15380 ,7376,730,7375 ,0,0,0}, {15400,15382,15378 ,7375,7376,7376 ,0,0,0}, - {15381,15382,15399 ,7375,7376,7375 ,0,0,0}, {15379,15401,15378 ,7374,7376,7376 ,0,0,0}, - {15400,15378,15401 ,7375,7376,7376 ,0,0,0}, {15390,15401,15379 ,730,7376,7374 ,0,0,0}, - {15399,15382,15400 ,7375,7376,7375 ,0,0,0}, {15397,15381,15399 ,730,7375,7375 ,0,0,0}, - {15396,15380,15397 ,7376,7375,730 ,0,0,0}, {15398,15385,15396 ,730,730,7376 ,0,0,0}, - {15393,15383,15398 ,730,7376,730 ,0,0,0}, {15394,15384,15393 ,730,730,730 ,0,0,0}, - {15394,15386,15387 ,730,730,730 ,0,0,0}, {15395,15388,15386 ,7376,7433,730 ,0,0,0}, - {15389,15388,15392 ,7433,7433,730 ,0,0,0}, {15395,15392,15388 ,7376,730,7433 ,0,0,0}, - {14565,12738,12736 ,7434,4326,7435 ,0,0,0}, {14737,14665,14562 ,7436,7437,7438 ,0,0,0}, - {14566,14664,14567 ,7439,7440,7441 ,0,0,0}, {14572,14560,14708 ,7442,7443,7444 ,0,0,0}, - {14570,14713,14771 ,7445,7446,7447 ,0,0,0}, {14716,14715,14550 ,7448,7449,7450 ,0,0,0}, - {14700,14568,14569 ,7451,7452,7453 ,0,0,0}, {14544,14543,14615 ,7454,7455,7456 ,0,0,0}, - {14546,14604,14606 ,7457,7458,7459 ,0,0,0}, {14534,14651,14538 ,7460,7461,7462 ,0,0,0}, - {14657,14616,14542 ,7463,7464,7465 ,0,0,0}, {14649,14576,14528 ,7466,7467,7468 ,0,0,0}, - {14652,14530,14576 ,7469,7470,7467 ,0,0,0}, {14721,14525,14532 ,7471,7472,7473 ,0,0,0}, - {14529,14525,14650 ,7474,7472,7475 ,0,0,0}, {14644,14533,14537 ,7476,7477,7478 ,0,0,0}, - {14532,14533,14643 ,7473,7477,7479 ,0,0,0}, {14540,14627,14537 ,7480,7481,7478 ,0,0,0}, - {14644,14537,14627 ,7476,7478,7481 ,0,0,0}, {14540,14549,14619 ,7480,7482,7483 ,0,0,0}, - {14619,14627,14540 ,7483,7481,7480 ,0,0,0}, {14593,14549,14548 ,7484,7482,7485 ,0,0,0}, - {14549,14593,14619 ,7482,7484,7483 ,0,0,0}, {14552,14582,14548 ,7486,7487,7485 ,0,0,0}, - {14593,14548,14582 ,7484,7485,7487 ,0,0,0}, {14552,14557,14580 ,7486,7488,7489 ,0,0,0}, - {14580,14582,14552 ,7489,7487,7486 ,0,0,0}, {14630,14557,14556 ,7490,7488,7491 ,0,0,0}, - {14557,14630,14580 ,7488,7490,7489 ,0,0,0}, {12770,14578,14556 ,82,7492,7491 ,0,0,0}, - {14630,14556,14578 ,7490,7491,7492 ,0,0,0}, {12769,14578,12770 ,82,7492,82 ,0,0,0}, - {14643,14721,14532 ,7479,7471,7473 ,0,0,0}, {14643,14533,14644 ,7479,7477,7476 ,0,0,0}, - {14529,14650,14649 ,7474,7475,7466 ,0,0,0}, {14650,14525,14721 ,7475,7472,7471 ,0,0,0}, - {14576,14530,14528 ,7467,7470,7468 ,0,0,0}, {14649,14528,14529 ,7466,7468,7474 ,0,0,0}, - {14652,14651,14534 ,7469,7461,7460 ,0,0,0}, {14652,14534,14530 ,7469,7460,7470 ,0,0,0}, - {14538,14657,14542 ,7462,7463,7465 ,0,0,0}, {14651,14657,14538 ,7461,7463,7462 ,0,0,0}, - {14543,14616,14615 ,7455,7464,7456 ,0,0,0}, {14542,14616,14543 ,7465,7464,7455 ,0,0,0}, - {14546,14544,14604 ,7457,7454,7458 ,0,0,0}, {14544,14615,14604 ,7454,7456,7458 ,0,0,0}, - {14716,14551,14606 ,7448,7493,7459 ,0,0,0}, {14551,14546,14606 ,7493,7457,7459 ,0,0,0}, - {14715,14569,14550 ,7449,7453,7450 ,0,0,0}, {14716,14550,14551 ,7448,7450,7493 ,0,0,0}, - {14700,14709,14568 ,7451,7494,7452 ,0,0,0}, {14715,14700,14569 ,7449,7451,7453 ,0,0,0}, - {14708,14560,14709 ,7444,7443,7494 ,0,0,0}, {14568,14709,14560 ,7452,7494,7443 ,0,0,0}, - {14570,14572,14713 ,7445,7442,7446 ,0,0,0}, {14572,14708,14713 ,7442,7444,7446 ,0,0,0}, - {14737,14561,14771 ,7436,7495,7447 ,0,0,0}, {14561,14570,14771 ,7495,7445,7447 ,0,0,0}, - {14665,14566,14562 ,7437,7439,7438 ,0,0,0}, {14737,14562,14561 ,7436,7438,7495 ,0,0,0}, - {14664,14666,14567 ,7440,7496,7441 ,0,0,0}, {14665,14664,14566 ,7437,7440,7439 ,0,0,0}, - {12738,14565,14666 ,4326,7434,7496 ,0,0,0}, {14567,14666,14565 ,7441,7496,7434 ,0,0,0}, - {15402,12686,12685 ,7497,763,7498 ,0,0,0}, {15403,14558,15404 ,7499,7500,7501 ,0,0,0}, - {15405,14571,14563 ,7502,7503,7504 ,0,0,0}, {15406,15407,14547 ,7505,7506,7507 ,0,0,0}, - {15408,15409,14555 ,7508,7509,7510 ,0,0,0}, {15410,14535,15411 ,7511,7512,7513 ,0,0,0}, - {14539,15412,15411 ,7514,7515,7513 ,0,0,0}, {15413,14527,15414 ,7516,7517,7518 ,0,0,0}, - {14526,15410,15414 ,7519,7511,7518 ,0,0,0}, {15415,14541,14536 ,7520,7521,7522 ,0,0,0}, - {14536,15413,15415 ,7522,7516,7520 ,0,0,0}, {14541,15416,14553 ,7521,7523,7524 ,0,0,0}, - {15416,14541,15415 ,7523,7521,7520 ,0,0,0}, {14554,14553,15417 ,7525,7524,7526 ,0,0,0}, - {15416,15417,14553 ,7523,7526,7524 ,0,0,0}, {12704,14554,15418 ,761,7525,7527 ,0,0,0}, - {14554,15417,15418 ,7525,7526,7527 ,0,0,0}, {12703,14554,12704 ,761,7525,761 ,0,0,0}, - {14526,15414,14527 ,7519,7518,7517 ,0,0,0}, {14536,14527,15413 ,7522,7517,7516 ,0,0,0}, - {14531,14535,15410 ,7528,7512,7511 ,0,0,0}, {14526,14531,15410 ,7519,7528,7511 ,0,0,0}, - {14545,15412,14539 ,7529,7515,7514 ,0,0,0}, {14535,14539,15411 ,7512,7514,7513 ,0,0,0}, - {14547,15407,14545 ,7507,7506,7529 ,0,0,0}, {15412,14545,15407 ,7515,7529,7506 ,0,0,0}, - {14555,15409,14547 ,7510,7509,7507 ,0,0,0}, {15409,15406,14547 ,7509,7505,7507 ,0,0,0}, - {14559,15403,15408 ,7530,7499,7508 ,0,0,0}, {14559,15408,14555 ,7530,7508,7510 ,0,0,0}, - {14558,14571,15404 ,7500,7503,7501 ,0,0,0}, {14559,14558,15403 ,7530,7500,7499 ,0,0,0}, - {15405,14563,15402 ,7502,7504,7497 ,0,0,0}, {15404,14571,15405 ,7501,7503,7502 ,0,0,0}, - {12686,15402,14564 ,763,7497,7531 ,0,0,0}, {15402,14563,14564 ,7497,7504,7531 ,0,0,0}, - {15417,15416,15415 ,7015,7532,7017 ,0,0,0}, {12690,15404,15405 ,7016,7015,7015 ,0,0,0}, - {15410,15413,15414 ,7533,7534,7535 ,0,0,0}, {15415,15410,15417 ,7017,7533,7015 ,0,0,0}, - {15417,15410,15418 ,7015,7533,7016 ,0,0,0}, {15410,15415,15413 ,7533,7017,7534 ,0,0,0}, - {15411,15418,15410 ,7536,7016,7533 ,0,0,0}, {15418,15412,12704 ,7016,730,7015 ,0,0,0}, - {15412,15418,15411 ,730,7016,7536 ,0,0,0}, {15409,12699,15406 ,7535,730,7320 ,0,0,0}, - {15412,15407,12704 ,730,6104,7015 ,0,0,0}, {15403,12693,15408 ,730,730,7534 ,0,0,0}, - {12696,15409,15408 ,7537,7535,7534 ,0,0,0}, {15402,12685,12689 ,7016,7015,730 ,0,0,0}, - {15405,12691,12690 ,7015,730,7016 ,0,0,0}, {12682,12670,12684 ,730,730,730 ,0,0,0}, - {12684,12668,12685 ,730,7016,7015 ,0,0,0}, {12681,12678,12682 ,730,730,730 ,0,0,0}, - {12670,12676,12675 ,730,7016,7016 ,0,0,0}, {12678,12670,12682 ,730,730,730 ,0,0,0}, - {12670,12669,12684 ,730,730,730 ,0,0,0}, {12670,12678,12676 ,730,730,7016 ,0,0,0}, - {12668,12689,12685 ,7016,730,7015 ,0,0,0}, {12669,12668,12684 ,730,7016,730 ,0,0,0}, - {12691,15405,12689 ,730,7015,730 ,0,0,0}, {12689,15405,15402 ,730,7015,7016 ,0,0,0}, - {12690,12693,15404 ,7016,730,7015 ,0,0,0}, {15408,12693,12695 ,7534,730,7537 ,0,0,0}, - {15404,12693,15403 ,7015,730,730 ,0,0,0}, {15408,12695,12696 ,7534,7537,7537 ,0,0,0}, - {12699,15407,15406 ,730,6104,7320 ,0,0,0}, {15409,12696,12699 ,7535,7537,730 ,0,0,0}, - {12704,15407,12701 ,7015,6104,730 ,0,0,0}, {12699,12701,15407 ,730,730,6104 ,0,0,0}, - {13613,13612,15419 ,7538,7539,7540 ,0,0,0}, {15420,13604,13613 ,7541,7542,7538 ,0,0,0}, - {15420,15421,13604 ,7541,82,7542 ,0,0,0}, {15419,15420,13613 ,7540,7541,7538 ,0,0,0}, - {13612,13983,15422 ,7539,7543,7544 ,0,0,0}, {13642,13641,15423 ,7545,7546,7547 ,0,0,0}, - {15424,15422,13983 ,7548,7544,7543 ,0,0,0}, {13983,13642,15424 ,7543,7545,7548 ,0,0,0}, - {15423,15424,13642 ,7547,7548,7545 ,0,0,0}, {13612,15422,15419 ,7539,7544,7540 ,0,0,0}, - {15423,13641,15425 ,7547,7546,7549 ,0,0,0}, {13640,15426,15425 ,7550,7551,7549 ,0,0,0}, - {15425,13641,13640 ,7549,7546,7550 ,0,0,0}, {15426,13640,13615 ,7551,7550,7552 ,0,0,0}, - {13628,15427,13615 ,7553,7554,7552 ,0,0,0}, {13628,13618,15428 ,7553,7555,7556 ,0,0,0}, - {13628,15428,15427 ,7553,7556,7554 ,0,0,0}, {15429,13609,15430 ,7557,7558,7559 ,0,0,0}, - {15428,13618,15429 ,7556,7555,7557 ,0,0,0}, {15429,13618,13609 ,7557,7555,7558 ,0,0,0}, - {13609,13611,15430 ,7558,7559,7559 ,0,0,0}, {15426,13615,15427 ,7551,7552,7554 ,0,0,0}, - {13605,15421,15431 ,7560,82,7561 ,0,0,0}, {15421,13605,13604 ,82,7560,7542 ,0,0,0}, - {15432,13647,15431 ,7562,7563,7561 ,0,0,0}, {13605,15431,13647 ,7560,7561,7563 ,0,0,0}, - {15432,15433,13861 ,7562,7564,7565 ,0,0,0}, {13861,13647,15432 ,7565,7563,7562 ,0,0,0}, - {13686,15433,15434 ,7566,7564,7567 ,0,0,0}, {15433,13686,13861 ,7564,7566,7565 ,0,0,0}, - {15435,13687,15434 ,7568,7569,7567 ,0,0,0}, {13686,15434,13687 ,7566,7567,7569 ,0,0,0}, - {15435,15436,13683 ,7568,7570,7571 ,0,0,0}, {13683,13687,15435 ,7571,7569,7568 ,0,0,0}, - {13651,15436,15437 ,7572,7570,7573 ,0,0,0}, {15436,13651,13683 ,7570,7572,7571 ,0,0,0}, - {15438,13670,15437 ,7574,7575,7573 ,0,0,0}, {13651,15437,13670 ,7572,7573,7575 ,0,0,0}, - {15438,15439,13671 ,7574,7576,7577 ,0,0,0}, {13671,13670,15438 ,7577,7575,7574 ,0,0,0}, - {13673,15439,15440 ,7578,7576,7579 ,0,0,0}, {15439,13673,13671 ,7576,7578,7577 ,0,0,0}, - {13673,15440,13674 ,7578,7579,7580 ,0,0,0}, {13674,15440,15441 ,7580,7579,7580 ,0,0,0}, - {14499,14505,15441 ,7581,7581,7581 ,0,0,0}, {15441,13111,14490 ,7581,7581,7581 ,0,0,0}, - {14490,14496,15441 ,7581,7581,7581 ,0,0,0}, {14510,15441,14505 ,7581,7581,7581 ,0,0,0}, - {14496,14499,15441 ,7581,7581,7581 ,0,0,0}, {14514,14473,15441 ,7581,7581,7581 ,0,0,0}, - {14514,15441,14510 ,7581,7581,7581 ,0,0,0}, {14473,14485,15441 ,7581,7581,7581 ,0,0,0}, - {13674,15441,14484 ,7581,7581,7581 ,0,0,0}, {14485,14484,15441 ,7581,7581,7581 ,0,0,0}, - {15430,13611,14057 ,7582,7582,7582 ,0,0,0}, {14057,14084,15430 ,7582,7582,7582 ,0,0,0}, - {15430,14070,14050 ,7582,7582,7582 ,0,0,0}, {14084,14070,15430 ,7582,7582,7582 ,0,0,0}, - {15430,14052,14066 ,7582,7582,7582 ,0,0,0}, {14050,14052,15430 ,7582,7582,7582 ,0,0,0}, - {15430,14059,14043 ,7582,7582,7582 ,0,0,0}, {14066,14059,15430 ,7582,7582,7582 ,0,0,0}, - {14047,15430,14042 ,7582,7582,7582 ,0,0,0}, {14043,14042,15430 ,7582,7582,7582 ,0,0,0}, - {15438,13116,13114 ,726,726,726 ,0,0,0}, {15431,15421,13116 ,726,726,726 ,0,0,0}, - {15440,15439,13114 ,726,726,726 ,0,0,0}, {13114,15439,15438 ,726,726,726 ,0,0,0}, - {13114,13108,15441 ,726,726,726 ,0,0,0}, {15441,15440,13114 ,726,726,726 ,0,0,0}, - {13117,13111,15441 ,7583,7583,726 ,0,0,0}, {13117,15441,13108 ,7583,726,726 ,0,0,0}, - {15438,15437,13116 ,726,726,726 ,0,0,0}, {13116,15436,15435 ,726,726,726 ,0,0,0}, - {15437,15436,13116 ,726,726,726 ,0,0,0}, {13116,15434,15433 ,726,726,726 ,0,0,0}, - {15435,15434,13116 ,726,726,726 ,0,0,0}, {13116,15432,15431 ,726,726,726 ,0,0,0}, - {15433,15432,13116 ,726,726,726 ,0,0,0}, {15420,13116,15421 ,726,726,726 ,0,0,0}, - {15419,15422,13116 ,726,726,726 ,0,0,0}, {15419,13116,15420 ,726,726,726 ,0,0,0}, - {15424,15423,13116 ,726,726,726 ,0,0,0}, {15424,13116,15422 ,726,726,726 ,0,0,0}, - {15425,15426,13116 ,726,726,726 ,0,0,0}, {15425,13116,15423 ,726,726,726 ,0,0,0}, - {15427,15428,13116 ,726,726,726 ,0,0,0}, {15427,13116,15426 ,726,726,726 ,0,0,0}, - {13116,15428,15168 ,726,726,726 ,0,0,0}, {15430,15168,15429 ,726,726,726 ,0,0,0}, - {15168,15428,15429 ,726,726,726 ,0,0,0}, {15169,15168,15430 ,726,726,726 ,0,0,0}, - {14047,15181,15430 ,7583,726,726 ,0,0,0}, {15169,15430,15181 ,726,726,726 ,0,0,0}, - {12646,15442,13900 ,7584,7585,7586 ,0,0,0}, {15443,13873,15444 ,7587,7588,7589 ,0,0,0}, - {13911,13833,15445 ,7590,7591,7592 ,0,0,0}, {13600,15446,13862 ,7593,7594,7595 ,0,0,0}, - {15447,15448,13603 ,4334,7596,7597 ,0,0,0}, {15449,13608,15450 ,7598,7599,7600 ,0,0,0}, - {13607,13865,15451 ,7601,7602,7603 ,0,0,0}, {13665,13657,15452 ,7604,7605,7606 ,0,0,0}, - {13661,15453,13657 ,7607,7608,7605 ,0,0,0}, {13662,15454,15455 ,7609,7610,7611 ,0,0,0}, - {13665,15456,13664 ,7604,7612,7613 ,0,0,0}, {15457,13675,15455 ,7614,7615,7611 ,0,0,0}, - {13662,15455,13675 ,7609,7611,7615 ,0,0,0}, {15457,15458,13668 ,7614,7616,7617 ,0,0,0}, - {13668,13675,15457 ,7617,7615,7614 ,0,0,0}, {13677,15458,15459 ,7618,7616,7619 ,0,0,0}, - {15458,13677,13668 ,7616,7618,7617 ,0,0,0}, {15460,13637,15459 ,7620,7621,7619 ,0,0,0}, - {13677,15459,13637 ,7618,7619,7621 ,0,0,0}, {15460,12665,12666 ,7620,7622,4289 ,0,0,0}, - {12666,13637,15460 ,4289,7621,7620 ,0,0,0}, {15452,13657,15453 ,7606,7605,7608 ,0,0,0}, - {15454,13664,15456 ,7610,7613,7612 ,0,0,0}, {13664,15454,13662 ,7613,7610,7609 ,0,0,0}, - {15452,15456,13665 ,7606,7612,7604 ,0,0,0}, {15449,15453,13661 ,7598,7608,7607 ,0,0,0}, - {13607,15451,15450 ,7601,7603,7600 ,0,0,0}, {13607,15450,13608 ,7601,7600,7599 ,0,0,0}, - {13661,13608,15449 ,7607,7599,7598 ,0,0,0}, {13865,15461,15451 ,7602,7623,7603 ,0,0,0}, - {15461,13865,13862 ,7623,7602,7595 ,0,0,0}, {15448,15446,13600 ,7596,7594,7593 ,0,0,0}, - {15446,15461,13862 ,7594,7623,7595 ,0,0,0}, {13603,15448,13600 ,7597,7596,7593 ,0,0,0}, - {13901,15443,15447 ,7624,7587,4334 ,0,0,0}, {13901,15447,13603 ,7624,4334,7597 ,0,0,0}, - {13873,13911,15444 ,7588,7590,7589 ,0,0,0}, {13901,13873,15443 ,7624,7588,7587 ,0,0,0}, - {13833,15442,15445 ,7591,7585,7592 ,0,0,0}, {15444,13911,15445 ,7589,7590,7592 ,0,0,0}, - {12646,13900,12644 ,7584,7586,4535 ,0,0,0}, {15442,13833,13900 ,7585,7591,7586 ,0,0,0}, - {15448,12657,15446 ,726,7625,726 ,0,0,0}, {15457,15455,15458 ,726,726,726 ,0,0,0}, - {15460,15459,15458 ,726,726,726 ,0,0,0}, {15456,15452,15454 ,726,726,726 ,0,0,0}, - {15458,15455,15452 ,726,726,726 ,0,0,0}, {15458,15452,15453 ,726,726,726 ,0,0,0}, - {15454,15452,15455 ,726,726,726 ,0,0,0}, {15453,15449,15460 ,726,726,726 ,0,0,0}, - {15460,15458,15453 ,726,726,726 ,0,0,0}, {15449,15450,12663 ,726,726,7626 ,0,0,0}, - {15449,12665,15460 ,726,726,726 ,0,0,0}, {15461,12659,12660 ,726,726,726 ,0,0,0}, - {12660,12663,15451 ,726,7626,726 ,0,0,0}, {15444,12648,12651 ,726,7627,726 ,0,0,0}, - {12653,12654,15447 ,726,7625,726 ,0,0,0}, {15445,12647,12648 ,7626,7627,7627 ,0,0,0}, - {12643,12628,12627 ,7626,7625,726 ,0,0,0}, {12646,12627,15442 ,726,726,726 ,0,0,0}, - {12639,12630,12640 ,726,7627,7625 ,0,0,0}, {12630,12639,12637 ,7627,726,726 ,0,0,0}, - {12639,12640,12634 ,726,7625,7627 ,0,0,0}, {12640,12643,12642 ,7625,7626,7628 ,0,0,0}, - {12630,12628,12640 ,7627,7625,7625 ,0,0,0}, {12630,12637,12631 ,7627,726,726 ,0,0,0}, - {12646,12643,12627 ,726,7626,726 ,0,0,0}, {12643,12640,12628 ,7626,7625,7625 ,0,0,0}, - {12625,15442,12627 ,726,726,726 ,0,0,0}, {15445,15442,12647 ,7626,726,7627 ,0,0,0}, - {12625,12647,15442 ,726,7627,726 ,0,0,0}, {15444,12651,15443 ,726,726,726 ,0,0,0}, - {12648,15444,15445 ,7627,726,7626 ,0,0,0}, {12653,15447,15443 ,726,726,726 ,0,0,0}, - {15443,12651,12653 ,726,726,726 ,0,0,0}, {12654,12657,15448 ,7625,7625,726 ,0,0,0}, - {15447,12654,15448 ,726,7625,726 ,0,0,0}, {15446,12659,15461 ,726,726,726 ,0,0,0}, - {15446,12657,12659 ,726,7625,726 ,0,0,0}, {12663,15450,15451 ,7626,726,726 ,0,0,0}, - {15451,15461,12660 ,726,726,726 ,0,0,0}, {12663,12665,15449 ,7626,726,726 ,0,0,0}, - {12607,15462,13881 ,4303,7629,7630 ,0,0,0}, {13804,13838,15463 ,7631,7632,7633 ,0,0,0}, - {13970,13882,15464 ,7634,7635,7636 ,0,0,0}, {13866,15465,13867 ,7637,7638,7639 ,0,0,0}, - {15466,15467,13803 ,7640,7641,7642 ,0,0,0}, {15468,15469,13648 ,7643,7644,7645 ,0,0,0}, - {15468,13868,15470 ,7643,7646,7647 ,0,0,0}, {15471,15472,13646 ,7648,7649,7650 ,0,0,0}, - {13646,13645,15471 ,7650,7651,7648 ,0,0,0}, {13829,15472,15473 ,7652,7649,7653 ,0,0,0}, - {15472,13829,13646 ,7649,7652,7650 ,0,0,0}, {15474,13828,15473 ,7654,7655,7653 ,0,0,0}, - {13829,15473,13828 ,7652,7653,7655 ,0,0,0}, {15474,12621,12622 ,7654,126,7656 ,0,0,0}, - {12622,13828,15474 ,7656,7655,7654 ,0,0,0}, {15465,13866,15467 ,7638,7637,7641 ,0,0,0}, - {15469,13645,13648 ,7644,7651,7645 ,0,0,0}, {15471,13645,15469 ,7648,7651,7644 ,0,0,0}, - {15463,13838,15475 ,7633,7632,7657 ,0,0,0}, {15470,13868,13867 ,7647,7646,7639 ,0,0,0}, - {15468,13648,13868 ,7643,7645,7646 ,0,0,0}, {15465,15470,13867 ,7638,7647,7639 ,0,0,0}, - {13803,15467,13866 ,7642,7641,7637 ,0,0,0}, {13804,15463,15466 ,7631,7633,7640 ,0,0,0}, - {15466,13803,13804 ,7640,7642,7631 ,0,0,0}, {13882,15462,15464 ,7635,7629,7636 ,0,0,0}, - {15475,13970,15464 ,7657,7634,7636 ,0,0,0}, {13838,13970,15475 ,7632,7634,7657 ,0,0,0}, - {12607,13881,12608 ,4303,7630,82 ,0,0,0}, {15462,13882,13881 ,7629,7635,7630 ,0,0,0}, - {15469,15468,12604 ,726,7658,7659 ,0,0,0}, {15462,15467,15463 ,7660,7661,726 ,0,0,0}, - {15462,15465,15467 ,7660,7661,7661 ,0,0,0}, {12606,15470,12607 ,7659,726,726 ,0,0,0}, - {15466,15463,15467 ,7661,726,7661 ,0,0,0}, {15464,15462,15463 ,7659,7660,726 ,0,0,0}, - {15465,15462,12607 ,7661,7660,726 ,0,0,0}, {15475,15464,15463 ,726,7659,726 ,0,0,0}, - {15465,12607,15470 ,7661,726,726 ,0,0,0}, {12604,15468,12606 ,7659,7658,7659 ,0,0,0}, - {12606,15468,15470 ,7659,7658,726 ,0,0,0}, {12602,15471,15469 ,726,5488,726 ,0,0,0}, - {12604,12602,15469 ,7659,726,726 ,0,0,0}, {12600,15471,12602 ,726,5488,726 ,0,0,0}, - {12600,15472,15471 ,726,7662,5488 ,0,0,0}, {15473,15472,12597 ,5471,7662,7661 ,0,0,0}, - {12600,12597,15472 ,726,7661,7662 ,0,0,0}, {12596,15473,12597 ,726,5471,7661 ,0,0,0}, - {15474,12596,12594 ,7663,726,7661 ,0,0,0}, {12596,15474,15473 ,726,7663,5471 ,0,0,0}, - {12593,12621,12594 ,7658,726,7661 ,0,0,0}, {15474,12594,12621 ,7663,7661,726 ,0,0,0}, - {12613,12609,12610 ,7658,7664,726 ,0,0,0}, {12613,12619,12609 ,7658,7665,7664 ,0,0,0}, - {12616,12613,12615 ,7666,7658,7667 ,0,0,0}, {12616,12619,12613 ,7666,7665,7658 ,0,0,0}, - {12621,12593,12619 ,726,7658,7665 ,0,0,0}, {12609,12619,12593 ,7664,7665,7658 ,0,0,0}, - {15476,13147,15477 ,726,726,726 ,0,0,0}, {13147,15478,15477 ,726,726,726 ,0,0,0}, - {15479,15480,13147 ,726,726,726 ,0,0,0}, {13147,15476,15479 ,726,726,726 ,0,0,0}, - {15481,15482,13147 ,726,726,726 ,0,0,0}, {15481,13147,15480 ,726,726,726 ,0,0,0}, - {13139,15483,15484 ,7583,726,7661 ,0,0,0}, {13147,15485,15486 ,726,726,726 ,0,0,0}, - {13139,15487,15488 ,7583,7658,7661 ,0,0,0}, {15489,13139,15490 ,726,7583,726 ,0,0,0}, - {15491,15492,13139 ,726,726,7583 ,0,0,0}, {15493,15490,13139 ,726,726,7583 ,0,0,0}, - {13139,15489,15494 ,7583,726,5489 ,0,0,0}, {15491,13139,15495 ,726,7583,7583 ,0,0,0}, - {13139,15492,15493 ,7583,726,726 ,0,0,0}, {13139,15496,15487 ,7583,726,7658 ,0,0,0}, - {15488,15495,13139 ,7661,7583,7583 ,0,0,0}, {15486,15483,13139 ,726,726,7583 ,0,0,0}, - {15496,13139,15484 ,726,7583,7661 ,0,0,0}, {13147,15482,15485 ,726,726,726 ,0,0,0}, - {13147,15486,13139 ,726,726,7583 ,0,0,0}, {13140,15494,13135 ,726,5489,7668 ,0,0,0}, - {15494,13140,13139 ,5489,726,7583 ,0,0,0}, {15478,13147,15497 ,726,726,726 ,0,0,0}, - {15498,13147,13145 ,726,726,726 ,0,0,0}, {13147,15498,15497 ,726,726,726 ,0,0,0}, - {15498,13145,13151 ,726,726,726 ,0,0,0}, {13601,13864,15496 ,7669,7670,7671 ,0,0,0}, - {15484,13602,13601 ,7672,7673,7669 ,0,0,0}, {15484,15483,13602 ,7672,7673,7673 ,0,0,0}, - {15496,15484,13601 ,7671,7672,7669 ,0,0,0}, {13864,13863,15487 ,7670,7674,7675 ,0,0,0}, - {13606,13660,15495 ,7676,7677,7678 ,0,0,0}, {15488,15487,13863 ,7679,7675,7674 ,0,0,0}, - {13863,13606,15488 ,7674,7676,7679 ,0,0,0}, {15495,15488,13606 ,7678,7679,7676 ,0,0,0}, - {13864,15487,15496 ,7670,7675,7671 ,0,0,0}, {15495,13660,15491 ,7678,7677,7680 ,0,0,0}, - {13659,15492,15491 ,7681,7682,7680 ,0,0,0}, {15491,13660,13659 ,7680,7677,7681 ,0,0,0}, - {15492,13659,13658 ,7682,7681,7683 ,0,0,0}, {13652,15493,13658 ,7684,7685,7683 ,0,0,0}, - {13652,13654,15490 ,7684,7686,7687 ,0,0,0}, {13652,15490,15493 ,7684,7687,7685 ,0,0,0}, - {15489,13655,15494 ,7688,7689,7690 ,0,0,0}, {15490,13654,15489 ,7687,7686,7688 ,0,0,0}, - {15489,13654,13655 ,7688,7686,7689 ,0,0,0}, {13655,13656,15494 ,7689,7690,7690 ,0,0,0}, - {15492,13658,15493 ,7682,7683,7685 ,0,0,0}, {13649,15483,15486 ,7691,7673,7692 ,0,0,0}, - {15483,13649,13602 ,7673,7691,7673 ,0,0,0}, {15485,13650,15486 ,7693,7694,7692 ,0,0,0}, - {13649,15486,13650 ,7691,7692,7694 ,0,0,0}, {15485,15482,13681 ,7693,7695,7696 ,0,0,0}, - {13681,13650,15485 ,7696,7694,7693 ,0,0,0}, {13682,15482,15481 ,7697,7695,7698 ,0,0,0}, - {15482,13682,13681 ,7695,7697,7696 ,0,0,0}, {15480,13904,15481 ,7699,7700,7698 ,0,0,0}, - {13682,15481,13904 ,7697,7698,7700 ,0,0,0}, {15480,15479,13685 ,7699,7701,7702 ,0,0,0}, - {13685,13904,15480 ,7702,7700,7699 ,0,0,0}, {13684,15479,15476 ,7703,7701,7704 ,0,0,0}, - {15479,13684,13685 ,7701,7703,7702 ,0,0,0}, {15477,13707,15476 ,7705,7706,7704 ,0,0,0}, - {13684,15476,13707 ,7703,7704,7706 ,0,0,0}, {15477,15478,13710 ,7705,7707,7708 ,0,0,0}, - {13710,13707,15477 ,7708,7706,7705 ,0,0,0}, {13711,15478,15497 ,7709,7707,7710 ,0,0,0}, - {15478,13711,13710 ,7707,7709,7708 ,0,0,0}, {13711,15497,13712 ,7709,7710,7711 ,0,0,0}, - {13712,15497,15498 ,7711,7710,7711 ,0,0,0}, {14413,15498,13151 ,7712,7712,7712 ,0,0,0}, - {15498,14414,14417 ,7712,7712,7712 ,0,0,0}, {14413,14414,15498 ,7712,7712,7712 ,0,0,0}, - {15498,14423,14428 ,7712,7712,7712 ,0,0,0}, {14417,14423,15498 ,7712,7712,7712 ,0,0,0}, - {15498,14432,14396 ,7712,7712,7712 ,0,0,0}, {14428,14432,15498 ,7712,7712,7712 ,0,0,0}, - {15498,14400,14399 ,7712,7712,7712 ,0,0,0}, {14396,14400,15498 ,7712,7712,7712 ,0,0,0}, - {15498,14399,13712 ,7712,7712,7712 ,0,0,0}, {14465,15494,13656 ,7713,7713,7713 ,0,0,0}, - {14465,14515,15494 ,7713,7713,7713 ,0,0,0}, {15494,14515,14501 ,7713,7713,7713 ,0,0,0}, - {14461,14467,15494 ,7713,7713,7713 ,0,0,0}, {14461,15494,14501 ,7713,7713,7713 ,0,0,0}, - {14467,14497,15494 ,7713,7713,7713 ,0,0,0}, {15494,14453,14452 ,7713,7713,7713 ,0,0,0}, - {14497,14453,15494 ,7713,7713,7713 ,0,0,0}, {13135,15494,14457 ,7713,7713,7713 ,0,0,0}, - {14452,14457,15494 ,7713,7713,7713 ,0,0,0}, {12570,15499,13919 ,1435,7714,7715 ,0,0,0}, - {15500,13910,15501 ,7716,7717,7718 ,0,0,0}, {13929,13918,15502 ,7719,7720,7721 ,0,0,0}, - {13590,15503,13691 ,7722,7723,7724 ,0,0,0}, {15504,15505,13932 ,7725,7726,7727 ,0,0,0}, - {15506,13713,15507 ,7728,7729,7730 ,0,0,0}, {13715,13692,15508 ,7731,7732,7733 ,0,0,0}, - {13597,13696,15509 ,7734,7735,7736 ,0,0,0}, {13701,15510,13696 ,7737,7738,7735 ,0,0,0}, - {13697,15511,15512 ,7739,7740,7741 ,0,0,0}, {13597,15513,13699 ,7734,7742,7743 ,0,0,0}, - {15514,13706,15512 ,7744,7745,7741 ,0,0,0}, {13697,15512,13706 ,7739,7741,7745 ,0,0,0}, - {15514,15515,13704 ,7744,7746,7747 ,0,0,0}, {13704,13706,15514 ,7747,7745,7744 ,0,0,0}, - {13717,15515,15516 ,7748,7746,7749 ,0,0,0}, {15515,13717,13704 ,7746,7748,7747 ,0,0,0}, - {15517,13703,15516 ,7750,7751,7749 ,0,0,0}, {13717,15516,13703 ,7748,7749,7751 ,0,0,0}, - {15517,12589,12590 ,7750,1359,1359 ,0,0,0}, {12590,13703,15517 ,1359,7751,7750 ,0,0,0}, - {15509,13696,15510 ,7736,7735,7738 ,0,0,0}, {15511,13699,15513 ,7740,7743,7742 ,0,0,0}, - {13699,15511,13697 ,7743,7740,7739 ,0,0,0}, {15509,15513,13597 ,7736,7742,7734 ,0,0,0}, - {15506,15510,13701 ,7728,7738,7737 ,0,0,0}, {13715,15508,15507 ,7731,7733,7730 ,0,0,0}, - {13715,15507,13713 ,7731,7730,7729 ,0,0,0}, {13701,13713,15506 ,7737,7729,7728 ,0,0,0}, - {13692,15518,15508 ,7732,7752,7733 ,0,0,0}, {15518,13692,13691 ,7752,7732,7724 ,0,0,0}, - {15505,15503,13590 ,7726,7723,7722 ,0,0,0}, {15503,15518,13691 ,7723,7752,7724 ,0,0,0}, - {13932,15505,13590 ,7727,7726,7722 ,0,0,0}, {13920,15500,15504 ,7753,7716,7725 ,0,0,0}, - {13920,15504,13932 ,7753,7725,7727 ,0,0,0}, {13910,13929,15501 ,7717,7719,7718 ,0,0,0}, - {13920,13910,15500 ,7753,7717,7716 ,0,0,0}, {13918,15499,15502 ,7720,7714,7721 ,0,0,0}, - {15501,13929,15502 ,7718,7719,7721 ,0,0,0}, {12570,13919,12568 ,1435,7715,1435 ,0,0,0}, - {15499,13918,13919 ,7714,7720,7715 ,0,0,0}, {15517,15516,15515 ,726,7628,7628 ,0,0,0}, - {12572,15512,12571 ,7627,7628,726 ,0,0,0}, {12551,12549,15513 ,7754,7625,7626 ,0,0,0}, - {15512,15511,12571 ,7628,726,726 ,0,0,0}, {12554,15506,12555 ,7755,726,7756 ,0,0,0}, - {12551,15513,15509 ,7754,7626,7626 ,0,0,0}, {15508,15518,12563 ,726,7628,7757 ,0,0,0}, - {15508,12561,15507 ,726,7758,7626 ,0,0,0}, {12564,12558,15503 ,7759,7760,7628 ,0,0,0}, - {15500,15501,15502 ,7625,7754,726 ,0,0,0}, {12567,12564,15505 ,7628,7759,7627 ,0,0,0}, - {12570,12567,15499 ,7628,7628,7761 ,0,0,0}, {15499,15500,15502 ,7761,7625,726 ,0,0,0}, - {12567,15504,15500 ,7628,7628,7625 ,0,0,0}, {15499,12567,15500 ,7761,7628,7625 ,0,0,0}, - {12567,12566,12564 ,7628,7762,7759 ,0,0,0}, {12567,15505,15504 ,7628,7627,7628 ,0,0,0}, - {12563,15503,12558 ,7757,7628,7760 ,0,0,0}, {15503,15505,12564 ,7628,7627,7759 ,0,0,0}, - {12563,15518,15503 ,7757,7628,7628 ,0,0,0}, {15507,12561,12555 ,7626,7758,7756 ,0,0,0}, - {12563,12561,15508 ,7757,7758,726 ,0,0,0}, {15510,15506,12554 ,7628,726,7755 ,0,0,0}, - {15506,15507,12555 ,726,7626,7756 ,0,0,0}, {15510,12552,15509 ,7628,7628,7626 ,0,0,0}, - {12552,15510,12554 ,7628,7628,7755 ,0,0,0}, {15511,15513,12549 ,726,7626,7625 ,0,0,0}, - {12552,12551,15509 ,7628,7754,7626 ,0,0,0}, {12575,15512,12572 ,7625,7628,7627 ,0,0,0}, - {12549,12571,15511 ,7625,726,726 ,0,0,0}, {15515,15514,12575 ,7628,7628,7625 ,0,0,0}, - {12575,15514,15512 ,7625,7628,7628 ,0,0,0}, {12577,15517,15515 ,7628,726,7628 ,0,0,0}, - {15515,12575,12577 ,7628,7625,7628 ,0,0,0}, {12577,12578,15517 ,7628,7628,726 ,0,0,0}, - {12581,12584,12587 ,7628,7628,7628 ,0,0,0}, {12578,12581,15517 ,7628,7628,726 ,0,0,0}, - {12587,15517,12581 ,7628,726,7628 ,0,0,0}, {12581,12583,12584 ,7628,726,7628 ,0,0,0}, - {15517,12587,12589 ,726,7628,7628 ,0,0,0}, {12531,15519,13880 ,1435,7763,7764 ,0,0,0}, - {13907,13909,15520 ,7765,7766,7767 ,0,0,0}, {13913,13914,15521 ,7768,7769,7770 ,0,0,0}, - {13879,15522,13878 ,7771,7772,7773 ,0,0,0}, {15523,15524,13908 ,7774,4221,7775 ,0,0,0}, - {15525,15526,13906 ,7776,7777,7778 ,0,0,0}, {15525,13905,15527 ,7776,7779,7780 ,0,0,0}, - {15528,15529,13722 ,7781,7782,7783 ,0,0,0}, {13722,13721,15528 ,7783,7784,7781 ,0,0,0}, - {13596,15529,15530 ,7785,7782,7786 ,0,0,0}, {15529,13596,13722 ,7782,7785,7783 ,0,0,0}, - {15531,13595,15530 ,7787,7788,7786 ,0,0,0}, {13596,15530,13595 ,7785,7786,7788 ,0,0,0}, - {15531,12545,12546 ,7787,1359,1359 ,0,0,0}, {12546,13595,15531 ,1359,7788,7787 ,0,0,0}, - {15522,13879,15524 ,7772,7771,4221 ,0,0,0}, {15526,13721,13906 ,7777,7784,7778 ,0,0,0}, - {15528,13721,15526 ,7781,7784,7777 ,0,0,0}, {15520,13909,15532 ,7767,7766,4227 ,0,0,0}, - {15527,13905,13878 ,7780,7779,7773 ,0,0,0}, {15525,13906,13905 ,7776,7778,7779 ,0,0,0}, - {15522,15527,13878 ,7772,7780,7773 ,0,0,0}, {13908,15524,13879 ,7775,4221,7771 ,0,0,0}, - {13907,15520,15523 ,7765,7767,7774 ,0,0,0}, {15523,13908,13907 ,7774,7775,7765 ,0,0,0}, - {13914,15519,15521 ,7769,7763,7770 ,0,0,0}, {15532,13913,15521 ,4227,7768,7770 ,0,0,0}, - {13909,13913,15532 ,7766,7768,4227 ,0,0,0}, {12531,13880,12532 ,1435,7764,1435 ,0,0,0}, - {15519,13914,13880 ,7763,7769,7764 ,0,0,0}, {12530,12539,12531 ,726,5471,7661 ,0,0,0}, - {15522,15525,15527 ,726,726,726 ,0,0,0}, {15528,15526,15525 ,7658,726,726 ,0,0,0}, - {15525,15522,15528 ,726,726,7658 ,0,0,0}, {15528,15524,15529 ,7658,726,7658 ,0,0,0}, - {15524,15528,15522 ,726,7658,726 ,0,0,0}, {15530,15529,15523 ,7658,7658,726 ,0,0,0}, - {15524,15523,15529 ,726,726,7658 ,0,0,0}, {15520,15531,15530 ,7658,7661,7658 ,0,0,0}, - {15530,15523,15520 ,7658,726,7658 ,0,0,0}, {15531,15532,12545 ,7661,7661,7664 ,0,0,0}, - {15532,15531,15520 ,7661,7661,7658 ,0,0,0}, {15532,15521,12545 ,7661,726,7664 ,0,0,0}, - {15521,15519,12543 ,726,726,7662 ,0,0,0}, {12537,12530,12528 ,7789,726,7658 ,0,0,0}, - {12518,12517,12524 ,5488,7668,7661 ,0,0,0}, {12534,12526,12533 ,7790,7664,7791 ,0,0,0}, - {12518,12524,12520 ,5488,7661,7792 ,0,0,0}, {12521,12520,12524 ,5488,7792,7661 ,0,0,0}, - {12526,12524,12533 ,7664,7661,7791 ,0,0,0}, {12533,12524,12517 ,7791,7661,7668 ,0,0,0}, - {12526,12534,12528 ,7664,7790,7658 ,0,0,0}, {12539,12530,12537 ,5471,726,7789 ,0,0,0}, - {12537,12528,12534 ,7789,7658,7790 ,0,0,0}, {12531,12540,15519 ,7661,7583,726 ,0,0,0}, - {12531,12539,12540 ,7661,5471,7583 ,0,0,0}, {15521,12543,12545 ,726,7662,7664 ,0,0,0}, - {12540,12543,15519 ,7583,7662,726 ,0,0,0}, {15533,13176,15534 ,7583,726,726 ,0,0,0}, - {15535,13172,15536 ,7668,726,5470 ,0,0,0}, {15535,15537,13172 ,7668,726,726 ,0,0,0}, - {13172,15538,15536 ,726,726,5470 ,0,0,0}, {15537,15539,13172 ,726,5489,726 ,0,0,0}, - {13172,15540,15541 ,726,7793,7794 ,0,0,0}, {15539,15540,13172 ,5489,7793,726 ,0,0,0}, - {13176,15542,13172 ,726,5470,726 ,0,0,0}, {15542,15538,13172 ,5470,726,726 ,0,0,0}, - {15543,15542,13176 ,726,5470,726 ,0,0,0}, {15544,13172,15541 ,7795,726,7794 ,0,0,0}, - {13176,15545,15543 ,726,5488,726 ,0,0,0}, {15544,15546,13172 ,7795,726,726 ,0,0,0}, - {15547,13172,15548 ,5485,726,7796 ,0,0,0}, {13172,15546,15548 ,726,726,7796 ,0,0,0}, - {13176,15549,15545 ,726,7583,5488 ,0,0,0}, {15550,13172,15547 ,7583,726,5485 ,0,0,0}, - {13176,15551,15549 ,726,726,7583 ,0,0,0}, {13176,15552,15553 ,726,5488,7583 ,0,0,0}, - {13176,15553,15551 ,726,7583,726 ,0,0,0}, {13173,15550,13168 ,5489,7583,7797 ,0,0,0}, - {13176,15533,15552 ,726,7583,5488 ,0,0,0}, {15550,13173,13172 ,7583,5489,726 ,0,0,0}, - {15534,13176,15554 ,726,726,7583 ,0,0,0}, {15555,13176,13183 ,726,726,726 ,0,0,0}, - {13176,15555,15554 ,726,726,7583 ,0,0,0}, {15555,13183,13182 ,726,726,726 ,0,0,0}, - {13591,13693,15535 ,7798,7799,7800 ,0,0,0}, {15536,13589,13591 ,7801,7802,7798 ,0,0,0}, - {15536,15538,13589 ,7801,7802,7802 ,0,0,0}, {15535,15536,13591 ,7800,7801,7798 ,0,0,0}, - {13693,13902,15537 ,7799,7803,7804 ,0,0,0}, {13714,13700,15540 ,7805,7806,7807 ,0,0,0}, - {15539,15537,13902 ,7808,7804,7803 ,0,0,0}, {13902,13714,15539 ,7803,7805,7808 ,0,0,0}, - {15540,15539,13714 ,7807,7808,7805 ,0,0,0}, {13693,15537,15535 ,7799,7804,7800 ,0,0,0}, - {15540,13700,15541 ,7807,7806,7809 ,0,0,0}, {13695,15544,15541 ,7810,7811,7809 ,0,0,0}, - {15541,13700,13695 ,7809,7806,7810 ,0,0,0}, {15544,13695,13694 ,7811,7810,7812 ,0,0,0}, - {13599,15546,13694 ,7813,7814,7812 ,0,0,0}, {13599,13678,15548 ,7813,7815,7816 ,0,0,0}, - {13599,15548,15546 ,7813,7816,7814 ,0,0,0}, {15547,13680,15550 ,7817,7818,7819 ,0,0,0}, - {15548,13678,15547 ,7816,7815,7817 ,0,0,0}, {15547,13678,13680 ,7817,7815,7818 ,0,0,0}, - {13680,13709,15550 ,7818,7819,7819 ,0,0,0}, {15544,13694,15546 ,7811,7812,7814 ,0,0,0}, - {13723,15538,15542 ,7820,7802,7821 ,0,0,0}, {15538,13723,13589 ,7802,7820,7802 ,0,0,0}, - {15543,13727,15542 ,7822,7823,7821 ,0,0,0}, {13723,15542,13727 ,7820,7821,7823 ,0,0,0}, - {15543,15545,13688 ,7822,7824,7825 ,0,0,0}, {13688,13727,15543 ,7825,7823,7822 ,0,0,0}, - {13689,15545,15549 ,7826,7824,7827 ,0,0,0}, {15545,13689,13688 ,7824,7826,7825 ,0,0,0}, - {15551,13764,15549 ,7828,7829,7827 ,0,0,0}, {13689,15549,13764 ,7826,7827,7829 ,0,0,0}, - {15551,15553,13592 ,7828,7830,7831 ,0,0,0}, {13592,13764,15551 ,7831,7829,7828 ,0,0,0}, - {13593,15553,15552 ,7832,7830,7833 ,0,0,0}, {15553,13593,13592 ,7830,7832,7831 ,0,0,0}, - {15533,13751,15552 ,7834,7835,7833 ,0,0,0}, {13593,15552,13751 ,7832,7833,7835 ,0,0,0}, - {15533,15534,13754 ,7834,7836,7837 ,0,0,0}, {13754,13751,15533 ,7837,7835,7834 ,0,0,0}, - {13758,15534,15554 ,7838,7836,7839 ,0,0,0}, {15534,13758,13754 ,7836,7838,7837 ,0,0,0}, - {13758,15554,13759 ,7838,7839,7840 ,0,0,0}, {13759,15554,15555 ,7840,7839,7840 ,0,0,0}, - {14326,15555,13182 ,7841,7841,7841 ,0,0,0}, {15555,14332,14335 ,7841,7841,7841 ,0,0,0}, - {14326,14332,15555 ,7841,7841,7841 ,0,0,0}, {15555,14341,14346 ,7841,7841,7841 ,0,0,0}, - {14335,14341,15555 ,7841,7841,7841 ,0,0,0}, {15555,14350,14309 ,7841,7841,7841 ,0,0,0}, - {14346,14350,15555 ,7841,7841,7841 ,0,0,0}, {15555,14321,14320 ,7841,7841,7841 ,0,0,0}, - {14309,14321,15555 ,7841,7841,7841 ,0,0,0}, {15555,14320,13759 ,7841,7841,7841 ,0,0,0}, - {14387,15550,13709 ,7842,7842,7842 ,0,0,0}, {14387,14433,15550 ,7842,7842,7842 ,0,0,0}, - {15550,14433,14419 ,7842,7842,7842 ,0,0,0}, {14381,14374,15550 ,7842,7842,7842 ,0,0,0}, - {14381,15550,14419 ,7842,7842,7842 ,0,0,0}, {14374,14415,15550 ,7842,7842,7842 ,0,0,0}, - {15550,14407,14369 ,7842,7842,7842 ,0,0,0}, {14415,14407,15550 ,7842,7842,7842 ,0,0,0}, - {13168,15550,14370 ,7842,7842,7842 ,0,0,0}, {14369,14370,15550 ,7842,7842,7842 ,0,0,0}, - {12494,15556,13944 ,1790,7843,4204 ,0,0,0}, {15557,13941,15558 ,7844,4198,4199 ,0,0,0}, - {13930,13943,15559 ,7845,7846,7847 ,0,0,0}, {13921,15560,13739 ,7848,7849,7850 ,0,0,0}, - {15561,15562,13954 ,7851,7852,7853 ,0,0,0}, {15563,13718,15564 ,7854,7855,7856 ,0,0,0}, - {13720,13737,15565 ,7857,7858,7859 ,0,0,0}, {13586,13585,15566 ,7860,7861,7862 ,0,0,0}, - {13741,15567,13585 ,7863,7864,7861 ,0,0,0}, {13745,15568,15569 ,7865,7866,7867 ,0,0,0}, - {13586,15570,13744 ,7860,7868,7869 ,0,0,0}, {15571,13750,15569 ,7870,7871,7867 ,0,0,0}, - {13745,15569,13750 ,7865,7867,7871 ,0,0,0}, {15571,15572,13748 ,7870,7872,7873 ,0,0,0}, - {13748,13750,15571 ,7873,7871,7870 ,0,0,0}, {13733,15572,15573 ,7874,7872,7875 ,0,0,0}, - {15572,13733,13748 ,7872,7874,7873 ,0,0,0}, {15574,13731,15573 ,7876,7877,7875 ,0,0,0}, - {13733,15573,13731 ,7874,7875,7877 ,0,0,0}, {15574,12513,12514 ,7876,1711,1711 ,0,0,0}, - {12514,13731,15574 ,1711,7877,7876 ,0,0,0}, {15566,13585,15567 ,7862,7861,7864 ,0,0,0}, - {15568,13744,15570 ,7866,7869,7868 ,0,0,0}, {13744,15568,13745 ,7869,7866,7865 ,0,0,0}, - {15566,15570,13586 ,7862,7868,7860 ,0,0,0}, {15563,15567,13741 ,7854,7864,7863 ,0,0,0}, - {13720,15565,15564 ,7857,7859,7856 ,0,0,0}, {13720,15564,13718 ,7857,7856,7855 ,0,0,0}, - {13741,13718,15563 ,7863,7855,7854 ,0,0,0}, {13737,15575,15565 ,7858,7878,7859 ,0,0,0}, - {15575,13737,13739 ,7878,7858,7850 ,0,0,0}, {15562,15560,13921 ,7852,7849,7848 ,0,0,0}, - {15560,15575,13739 ,7849,7878,7850 ,0,0,0}, {13954,15562,13921 ,7853,7852,7848 ,0,0,0}, - {13942,15557,15561 ,7879,7844,7851 ,0,0,0}, {13942,15561,13954 ,7879,7851,7853 ,0,0,0}, - {13941,13930,15558 ,4198,7845,4199 ,0,0,0}, {13942,13941,15557 ,7879,4198,7844 ,0,0,0}, - {13943,15556,15559 ,7846,7843,7847 ,0,0,0}, {15558,13930,15559 ,4199,7845,7847 ,0,0,0}, - {12494,13944,12492 ,1790,4204,1790 ,0,0,0}, {15556,13943,13944 ,7843,7846,4204 ,0,0,0}, - {15566,15567,15561 ,726,7880,7881 ,0,0,0}, {15556,15571,15569 ,7882,7627,7625 ,0,0,0}, - {15562,15563,15560 ,7883,7758,726 ,0,0,0}, {15575,15560,15563 ,7884,726,7758 ,0,0,0}, - {15564,15565,15575 ,7880,7761,7884 ,0,0,0}, {15563,15562,15567 ,7758,7883,7880 ,0,0,0}, - {15564,15575,15563 ,7880,7884,7758 ,0,0,0}, {15566,15561,15557 ,726,7881,7885 ,0,0,0}, - {15567,15562,15561 ,7880,7883,7881 ,0,0,0}, {15557,15558,15570 ,7885,7886,7758 ,0,0,0}, - {15570,15566,15557 ,7758,726,7885 ,0,0,0}, {15568,15558,15559 ,726,7886,7887 ,0,0,0}, - {15558,15568,15570 ,7886,726,7758 ,0,0,0}, {15569,15568,15559 ,7625,726,7887 ,0,0,0}, - {12494,15571,15556 ,7758,7627,7882 ,0,0,0}, {15556,15569,15559 ,7882,7625,7887 ,0,0,0}, - {15572,12494,12491 ,7627,7758,7755 ,0,0,0}, {12494,15572,15571 ,7758,7627,7627 ,0,0,0}, - {12490,15573,12491 ,7625,726,7755 ,0,0,0}, {15572,12491,15573 ,7627,7755,726 ,0,0,0}, - {12490,12488,15574 ,7625,7761,726 ,0,0,0}, {15574,15573,12490 ,726,726,7625 ,0,0,0}, - {12513,12488,12482 ,7627,7761,7625 ,0,0,0}, {12488,12513,15574 ,7761,7627,726 ,0,0,0}, - {12479,12507,12485 ,726,7627,7625 ,0,0,0}, {12487,12511,12482 ,7880,726,7625 ,0,0,0}, - {12505,12478,12502 ,7625,726,726 ,0,0,0}, {12499,12475,12496 ,7627,7625,7625 ,0,0,0}, - {12501,12502,12476 ,726,726,7625 ,0,0,0}, {12496,12473,12495 ,7625,7625,726 ,0,0,0}, - {12475,12499,12501 ,7625,7627,726 ,0,0,0}, {12476,12475,12501 ,7625,7625,726 ,0,0,0}, - {12496,12475,12473 ,7625,7625,7625 ,0,0,0}, {12479,12478,12505 ,726,726,7625 ,0,0,0}, - {12476,12502,12478 ,7625,726,726 ,0,0,0}, {12508,12485,12507 ,726,7625,7627 ,0,0,0}, - {12507,12479,12505 ,7627,726,7625 ,0,0,0}, {12487,12508,12511 ,7880,726,726 ,0,0,0}, - {12508,12487,12485 ,726,7880,7625 ,0,0,0}, {12511,12513,12482 ,726,7627,7625 ,0,0,0}, - {12455,15576,13874 ,1790,7888,7889 ,0,0,0}, {13926,13915,15577 ,7890,7891,7892 ,0,0,0}, - {13928,13875,15578 ,7893,7894,7895 ,0,0,0}, {13916,15579,13917 ,7896,7897,4137 ,0,0,0}, - {15580,15581,13927 ,7898,7899,7900 ,0,0,0}, {15582,15583,13925 ,7901,7902,7903 ,0,0,0}, - {15582,13924,15584 ,7901,7904,7905 ,0,0,0}, {15585,15586,13760 ,7906,7907,7908 ,0,0,0}, - {13760,13761,15585 ,7908,7909,7906 ,0,0,0}, {13923,15586,15587 ,7910,7907,7911 ,0,0,0}, - {15586,13923,13760 ,7907,7910,7908 ,0,0,0}, {15588,13734,15587 ,7912,7913,7911 ,0,0,0}, - {13923,15587,13734 ,7910,7911,7913 ,0,0,0}, {15588,12469,12470 ,7912,1711,1711 ,0,0,0}, - {12470,13734,15588 ,1711,7913,7912 ,0,0,0}, {15579,13916,15581 ,7897,7896,7899 ,0,0,0}, - {15583,13761,13925 ,7902,7909,7903 ,0,0,0}, {15585,13761,15583 ,7906,7909,7902 ,0,0,0}, - {15577,13915,15589 ,7892,7891,7914 ,0,0,0}, {15584,13924,13917 ,7905,7904,4137 ,0,0,0}, - {15582,13925,13924 ,7901,7903,7904 ,0,0,0}, {15579,15584,13917 ,7897,7905,4137 ,0,0,0}, - {13927,15581,13916 ,7900,7899,7896 ,0,0,0}, {13926,15577,15580 ,7890,7892,7898 ,0,0,0}, - {15580,13927,13926 ,7898,7900,7890 ,0,0,0}, {13875,15576,15578 ,7894,7888,7895 ,0,0,0}, - {15589,13928,15578 ,7914,7893,7895 ,0,0,0}, {13915,13928,15589 ,7891,7893,7914 ,0,0,0}, - {12455,13874,12456 ,1790,7889,1790 ,0,0,0}, {15576,13875,13874 ,7888,7894,7889 ,0,0,0}, - {15582,12463,15583 ,726,7658,726 ,0,0,0}, {15587,15586,12467 ,726,726,7660 ,0,0,0}, - {12469,15588,15587 ,726,7660,726 ,0,0,0}, {15582,15584,12461 ,726,726,7658 ,0,0,0}, - {12464,12467,15585 ,7660,7660,7659 ,0,0,0}, {15581,15580,12441 ,7659,726,7661 ,0,0,0}, - {15581,12457,15579 ,7659,726,726 ,0,0,0}, {12444,12442,15577 ,7915,7916,726 ,0,0,0}, - {15576,12450,12448 ,7658,7917,5475 ,0,0,0}, {15578,12445,15589 ,7658,726,7659 ,0,0,0}, - {12455,12454,12450 ,7918,7918,7917 ,0,0,0}, {12452,12450,12454 ,7661,7917,7918 ,0,0,0}, - {15578,15576,12448 ,7658,7658,5475 ,0,0,0}, {15576,12455,12450 ,7658,7918,7917 ,0,0,0}, - {12445,15578,12448 ,726,7658,5475 ,0,0,0}, {15589,12445,12444 ,7659,726,7915 ,0,0,0}, - {15577,12442,15580 ,726,7916,726 ,0,0,0}, {15589,12444,15577 ,7659,7915,726 ,0,0,0}, - {15581,12441,12457 ,7659,7661,726 ,0,0,0}, {15580,12442,12441 ,726,7916,7661 ,0,0,0}, - {12458,15584,15579 ,7664,726,726 ,0,0,0}, {12457,12458,15579 ,726,7664,726 ,0,0,0}, - {12463,15582,12461 ,7658,726,7658 ,0,0,0}, {12461,15584,12458 ,7658,726,7664 ,0,0,0}, - {15583,12464,15585 ,726,7660,7659 ,0,0,0}, {15583,12463,12464 ,726,7658,7660 ,0,0,0}, - {15587,12467,12469 ,726,7660,726 ,0,0,0}, {15586,15585,12467 ,726,7659,7660 ,0,0,0}, - {13213,15590,15591 ,726,5469,7919 ,0,0,0}, {15592,13213,15593 ,7920,726,7921 ,0,0,0}, - {13213,15592,15590 ,726,7920,5469 ,0,0,0}, {13213,15594,15593 ,726,726,7921 ,0,0,0}, - {15595,13213,15591 ,7922,726,7919 ,0,0,0}, {15594,13213,15596 ,726,726,7920 ,0,0,0}, - {15595,15597,13213 ,7922,7923,726 ,0,0,0}, {13213,15598,15599 ,726,7924,7925 ,0,0,0}, - {15599,15600,13213 ,7925,7926,726 ,0,0,0}, {15597,15598,13213 ,7923,7924,726 ,0,0,0}, - {15601,15602,13213 ,5472,7927,726 ,0,0,0}, {15601,13213,15600 ,5472,726,7926 ,0,0,0}, - {15603,15604,13213 ,7928,7929,726 ,0,0,0}, {15603,13213,15602 ,7928,726,7927 ,0,0,0}, - {15605,15606,13213 ,726,5489,726 ,0,0,0}, {15605,13213,15604 ,726,726,7929 ,0,0,0}, - {13213,15607,13212 ,726,5488,7583 ,0,0,0}, {15607,13213,15606 ,5488,726,5489 ,0,0,0}, - {13212,15608,15609 ,7583,5470,5489 ,0,0,0}, {15607,15608,13212 ,5488,5470,7583 ,0,0,0}, - {13208,13209,15609 ,5489,5488,5489 ,0,0,0}, {13212,15609,13209 ,7583,5489,5488 ,0,0,0}, - {13203,13208,15609 ,5489,5489,5489 ,0,0,0}, {13213,15180,15596 ,726,5489,7920 ,0,0,0}, - {15180,15610,15611 ,5489,5470,5488 ,0,0,0}, {15596,15180,15611 ,7920,5489,5488 ,0,0,0}, - {15612,15180,15179 ,5489,5489,726 ,0,0,0}, {15180,15612,15610 ,5489,5489,5470 ,0,0,0}, - {14243,15612,15178 ,5489,5489,7583 ,0,0,0}, {15179,15178,15612 ,726,7583,5489 ,0,0,0}, - {13777,13738,15600 ,7930,7931,7932 ,0,0,0}, {15599,13779,13777 ,7933,7934,7930 ,0,0,0}, - {15599,15598,13779 ,7933,7935,7934 ,0,0,0}, {15600,15599,13777 ,7932,7933,7930 ,0,0,0}, - {13738,13922,15601 ,7931,7936,7937 ,0,0,0}, {13719,13740,15603 ,7938,7939,7940 ,0,0,0}, - {15602,15601,13922 ,7941,7937,7936 ,0,0,0}, {13922,13719,15602 ,7936,7938,7941 ,0,0,0}, - {15603,15602,13719 ,7940,7941,7938 ,0,0,0}, {13738,15601,15600 ,7931,7937,7932 ,0,0,0}, - {15603,13740,15604 ,7940,7939,7942 ,0,0,0}, {13742,15605,15604 ,7943,7944,7942 ,0,0,0}, - {15604,13740,13742 ,7942,7939,7943 ,0,0,0}, {15605,13742,13587 ,7944,7943,7945 ,0,0,0}, - {13730,15606,13587 ,7946,7947,7945 ,0,0,0}, {13730,13743,15607 ,7946,7948,7949 ,0,0,0}, - {13730,15607,15606 ,7946,7949,7947 ,0,0,0}, {15608,13735,15609 ,7950,7951,7952 ,0,0,0}, - {15607,13743,15608 ,7949,7948,7950 ,0,0,0}, {15608,13743,13735 ,7950,7948,7951 ,0,0,0}, - {13735,13736,15609 ,7951,7952,7952 ,0,0,0}, {15605,13587,15606 ,7944,7945,7947 ,0,0,0}, - {13899,15598,15597 ,7953,7935,7954 ,0,0,0}, {15598,13899,13779 ,7935,7953,7934 ,0,0,0}, - {15595,13778,15597 ,7955,7956,7954 ,0,0,0}, {13899,15597,13778 ,7953,7954,7956 ,0,0,0}, - {15595,15591,13762 ,7955,7957,7958 ,0,0,0}, {13762,13778,15595 ,7958,7956,7955 ,0,0,0}, - {13763,15591,15590 ,7959,7957,7960 ,0,0,0}, {15591,13763,13762 ,7957,7959,7958 ,0,0,0}, - {15592,13936,15590 ,7961,7962,7960 ,0,0,0}, {13763,15590,13936 ,7959,7960,7962 ,0,0,0}, - {15592,15593,13876 ,7961,7963,7964 ,0,0,0}, {13876,13936,15592 ,7964,7962,7961 ,0,0,0}, - {13877,15593,15594 ,7965,7963,7966 ,0,0,0}, {15593,13877,13876 ,7963,7965,7964 ,0,0,0}, - {15596,13770,15594 ,7967,7968,7966 ,0,0,0}, {13877,15594,13770 ,7965,7966,7968 ,0,0,0}, - {15596,15611,13798 ,7967,7969,7970 ,0,0,0}, {13798,13770,15596 ,7970,7968,7967 ,0,0,0}, - {13799,15611,15610 ,7971,7969,7972 ,0,0,0}, {15611,13799,13798 ,7969,7971,7970 ,0,0,0}, - {13799,15610,13801 ,7971,7972,7973 ,0,0,0}, {13801,15610,15612 ,7973,7972,7973 ,0,0,0}, - {14253,14259,15612 ,7974,7974,7974 ,0,0,0}, {15612,14243,14244 ,7974,7974,7974 ,0,0,0}, - {14244,14250,15612 ,7974,7974,7974 ,0,0,0}, {14264,15612,14259 ,7974,7974,7974 ,0,0,0}, - {14250,14253,15612 ,7974,7974,7974 ,0,0,0}, {14268,14221,15612 ,7974,7974,7974 ,0,0,0}, - {14268,15612,14264 ,7974,7974,7974 ,0,0,0}, {14221,14233,15612 ,7974,7974,7974 ,0,0,0}, - {13801,15612,14232 ,7974,7974,7974 ,0,0,0}, {14233,14232,15612 ,7974,7974,7974 ,0,0,0}, - {15609,13736,14301 ,7975,7975,7975 ,0,0,0}, {14301,14351,15609 ,7975,7975,7975 ,0,0,0}, - {15609,14337,14297 ,7975,7975,7975 ,0,0,0}, {14351,14337,15609 ,7975,7975,7975 ,0,0,0}, - {15609,14303,14333 ,7975,7975,7975 ,0,0,0}, {14297,14303,15609 ,7975,7975,7975 ,0,0,0}, - {15609,14289,14288 ,7975,7975,7975 ,0,0,0}, {14333,14289,15609 ,7975,7975,7975 ,0,0,0}, - {13203,15609,14293 ,7975,7975,7975 ,0,0,0}, {14288,14293,15609 ,7975,7975,7975 ,0,0,0}, - {12418,15613,13949 ,126,7976,7977 ,0,0,0}, {15614,13951,15615 ,7978,7979,7980 ,0,0,0}, - {13965,13952,15616 ,7981,7982,7983 ,0,0,0}, {13766,15617,13757 ,7984,7985,7986 ,0,0,0}, - {15618,15619,13933 ,7987,7988,7989 ,0,0,0}, {15620,13784,15621 ,7990,7991,7992 ,0,0,0}, - {13802,13769,15622 ,7993,7994,7995 ,0,0,0}, {13794,13795,15623 ,7996,7997,7998 ,0,0,0}, - {13785,15624,13795 ,7999,8000,7997 ,0,0,0}, {13786,15625,15626 ,8001,8002,8003 ,0,0,0}, - {13794,15627,13788 ,7996,8004,8005 ,0,0,0}, {15628,13789,15626 ,8006,8007,8003 ,0,0,0}, - {13786,15626,13789 ,8001,8003,8007 ,0,0,0}, {15628,15629,13792 ,8006,8008,8009 ,0,0,0}, - {13792,13789,15628 ,8009,8007,8006 ,0,0,0}, {13831,15629,15630 ,8010,8008,8011 ,0,0,0}, - {15629,13831,13792 ,8008,8010,8009 ,0,0,0}, {15631,13793,15630 ,8012,8013,8011 ,0,0,0}, - {13831,15630,13793 ,8010,8011,8013 ,0,0,0}, {15631,12437,12438 ,8012,8014,4346 ,0,0,0}, - {12438,13793,15631 ,4346,8013,8012 ,0,0,0}, {15623,13795,15624 ,7998,7997,8000 ,0,0,0}, - {15625,13788,15627 ,8002,8005,8004 ,0,0,0}, {13788,15625,13786 ,8005,8002,8001 ,0,0,0}, - {15623,15627,13794 ,7998,8004,7996 ,0,0,0}, {15620,15624,13785 ,7990,8000,7999 ,0,0,0}, - {13802,15622,15621 ,7993,7995,7992 ,0,0,0}, {13802,15621,13784 ,7993,7992,7991 ,0,0,0}, - {13785,13784,15620 ,7999,7991,7990 ,0,0,0}, {13769,15632,15622 ,7994,8015,7995 ,0,0,0}, - {15632,13769,13757 ,8015,7994,7986 ,0,0,0}, {15619,15617,13766 ,7988,7985,7984 ,0,0,0}, - {15617,15632,13757 ,7985,8015,7986 ,0,0,0}, {13933,15619,13766 ,7989,7988,7984 ,0,0,0}, - {13950,15614,15618 ,8016,7978,7987 ,0,0,0}, {13950,15618,13933 ,8016,7987,7989 ,0,0,0}, - {13951,13965,15615 ,7979,7981,7980 ,0,0,0}, {13950,13951,15614 ,8016,7979,7978 ,0,0,0}, - {13952,15613,15616 ,7982,7976,7983 ,0,0,0}, {15615,13965,15616 ,7980,7981,7983 ,0,0,0}, - {12418,13949,12416 ,126,7977,4289 ,0,0,0}, {15613,13952,13949 ,7976,7982,7977 ,0,0,0}, - {15631,15630,15629 ,7625,7880,7758 ,0,0,0}, {12423,15614,15615 ,7626,7880,726 ,0,0,0}, - {15629,15626,15623 ,7758,8017,8018 ,0,0,0}, {15629,15628,15626 ,7758,7758,8017 ,0,0,0}, - {15625,15623,15626 ,8017,8018,8017 ,0,0,0}, {15625,15627,15623 ,8017,7758,8018 ,0,0,0}, - {15624,15629,15623 ,8019,7758,8018 ,0,0,0}, {15624,15620,15631 ,8019,7884,7625 ,0,0,0}, - {15631,15629,15624 ,7625,7758,8019 ,0,0,0}, {15620,15621,12435 ,7884,8020,7625 ,0,0,0}, - {15620,12437,15631 ,7884,7625,7625 ,0,0,0}, {15632,12431,12432 ,8021,7625,726 ,0,0,0}, - {12432,12435,15622 ,726,7625,7257 ,0,0,0}, {12425,12426,15618 ,726,726,8017 ,0,0,0}, - {12429,15617,15619 ,7625,8022,7761 ,0,0,0}, {12420,15616,12419 ,7626,726,7626 ,0,0,0}, - {15615,12420,12423 ,726,7626,7626 ,0,0,0}, {12415,12400,12399 ,7625,726,726 ,0,0,0}, - {12418,12399,15613 ,7625,726,7625 ,0,0,0}, {12411,12402,12412 ,726,726,7625 ,0,0,0}, - {12402,12411,12409 ,726,726,726 ,0,0,0}, {12406,12411,12412 ,7625,726,7625 ,0,0,0}, - {12414,12412,12415 ,7625,7625,7625 ,0,0,0}, {12412,12402,12400 ,7625,726,726 ,0,0,0}, - {12403,12402,12409 ,726,726,726 ,0,0,0}, {12399,12418,12415 ,726,7625,7625 ,0,0,0}, - {12400,12415,12412 ,726,7625,7625 ,0,0,0}, {15613,12397,12419 ,7625,726,7626 ,0,0,0}, - {12397,15613,12399 ,726,7625,726 ,0,0,0}, {15616,12420,15615 ,726,7626,726 ,0,0,0}, - {15613,12419,15616 ,7625,7626,726 ,0,0,0}, {12423,12425,15614 ,7626,726,7880 ,0,0,0}, - {15618,12426,15619 ,8017,726,7761 ,0,0,0}, {15614,12425,15618 ,7880,726,8017 ,0,0,0}, - {15619,12426,12429 ,7761,726,7625 ,0,0,0}, {15617,12431,15632 ,8022,7625,8021 ,0,0,0}, - {15617,12429,12431 ,8022,7625,7625 ,0,0,0}, {12435,15621,15622 ,7625,8020,7257 ,0,0,0}, - {15622,15632,12432 ,7257,8021,726 ,0,0,0}, {12435,12437,15620 ,7625,7625,7884 ,0,0,0}, - {12379,15633,13948 ,8023,8024,8025 ,0,0,0}, {13690,13893,15634 ,8026,8027,8028 ,0,0,0}, - {14000,13946,15635 ,8029,8030,8031 ,0,0,0}, {13939,15636,13931 ,8032,8033,8034 ,0,0,0}, - {15637,15638,13898 ,8035,8036,8037 ,0,0,0}, {15639,15640,13938 ,8038,8039,8040 ,0,0,0}, - {15639,13940,15641 ,8038,8041,8042 ,0,0,0}, {15642,15643,13937 ,8043,8044,8045 ,0,0,0}, - {13937,13837,15642 ,8045,8046,8043 ,0,0,0}, {13834,15643,15644 ,8047,8044,8048 ,0,0,0}, - {15643,13834,13937 ,8044,8047,8045 ,0,0,0}, {15645,13835,15644 ,8049,8050,8048 ,0,0,0}, - {13834,15644,13835 ,8047,8048,8050 ,0,0,0}, {15645,12393,12394 ,8049,82,82 ,0,0,0}, - {12394,13835,15645 ,82,8050,8049 ,0,0,0}, {15636,13939,15638 ,8033,8032,8036 ,0,0,0}, - {15640,13837,13938 ,8039,8046,8040 ,0,0,0}, {15642,13837,15640 ,8043,8046,8039 ,0,0,0}, - {15634,13893,15646 ,8028,8027,8051 ,0,0,0}, {15641,13940,13931 ,8042,8041,8034 ,0,0,0}, - {15639,13938,13940 ,8038,8040,8041 ,0,0,0}, {15636,15641,13931 ,8033,8042,8034 ,0,0,0}, - {13898,15638,13939 ,8037,8036,8032 ,0,0,0}, {13690,15634,15637 ,8026,8028,8035 ,0,0,0}, - {15637,13898,13690 ,8035,8037,8026 ,0,0,0}, {13946,15633,15635 ,8030,8024,8031 ,0,0,0}, - {15646,14000,15635 ,8051,8029,8031 ,0,0,0}, {13893,14000,15646 ,8027,8029,8051 ,0,0,0}, - {12379,13948,12380 ,8023,8025,8052 ,0,0,0}, {15633,13946,13948 ,8024,8030,8025 ,0,0,0}, - {15639,12376,15640 ,726,726,726 ,0,0,0}, {15643,12372,12369 ,726,7661,726 ,0,0,0}, - {15636,15638,15633 ,726,7660,726 ,0,0,0}, {15641,12379,12378 ,726,726,726 ,0,0,0}, - {15635,15633,15634 ,7661,726,726 ,0,0,0}, {15634,15646,15635 ,726,7658,7661 ,0,0,0}, - {15634,15638,15637 ,726,7660,726 ,0,0,0}, {15633,12379,15636 ,726,726,726 ,0,0,0}, - {15638,15634,15633 ,7660,726,726 ,0,0,0}, {15641,12378,15639 ,726,726,726 ,0,0,0}, - {15636,12379,15641 ,726,726,726 ,0,0,0}, {15639,12378,12376 ,726,726,726 ,0,0,0}, - {15640,12374,15642 ,726,7658,726 ,0,0,0}, {15640,12376,12374 ,726,726,7658 ,0,0,0}, - {15643,15642,12372 ,726,726,7661 ,0,0,0}, {12374,12372,15642 ,7658,7661,726 ,0,0,0}, - {15643,12369,15644 ,726,726,726 ,0,0,0}, {12368,15645,15644 ,726,726,726 ,0,0,0}, - {15644,12369,12368 ,726,726,726 ,0,0,0}, {15645,12366,12393 ,726,726,726 ,0,0,0}, - {12366,15645,12368 ,726,726,726 ,0,0,0}, {12366,12365,12393 ,726,726,726 ,0,0,0}, - {12385,12381,12382 ,7659,726,726 ,0,0,0}, {12385,12391,12381 ,7659,726,726 ,0,0,0}, - {12388,12385,12387 ,726,7659,726 ,0,0,0}, {12388,12391,12385 ,726,726,7659 ,0,0,0}, - {12393,12365,12391 ,726,726,726 ,0,0,0}, {12381,12391,12365 ,726,726,726 ,0,0,0}, - {15647,15648,15175 ,726,8053,7583 ,0,0,0}, {15177,15649,15176 ,726,726,726 ,0,0,0}, - {15648,15650,15175 ,8053,7922,7583 ,0,0,0}, {15647,15175,15651 ,726,7583,5472 ,0,0,0}, - {15175,15652,15653 ,7583,7664,5488 ,0,0,0}, {15650,15652,15175 ,7922,7664,7583 ,0,0,0}, - {15654,15655,15175 ,7920,726,7583 ,0,0,0}, {15653,15656,15175 ,5488,5471,7583 ,0,0,0}, - {15657,15658,15177 ,7664,7583,726 ,0,0,0}, {15177,15659,15660 ,726,5488,7664 ,0,0,0}, - {15661,15177,15662 ,726,726,726 ,0,0,0}, {15663,15664,15177 ,7664,7664,726 ,0,0,0}, - {15665,15662,15177 ,726,726,726 ,0,0,0}, {15177,15661,15649 ,726,726,726 ,0,0,0}, - {15663,15177,15666 ,7664,726,7664 ,0,0,0}, {15177,15664,15665 ,726,7664,726 ,0,0,0}, - {15177,15658,15666 ,726,7583,7664 ,0,0,0}, {15177,15660,15667 ,726,7664,726 ,0,0,0}, - {15177,15667,15657 ,726,726,7664 ,0,0,0}, {15655,15177,15175 ,726,726,7583 ,0,0,0}, - {15655,15659,15177 ,726,5488,726 ,0,0,0}, {15175,15656,15654 ,7583,5471,7920 ,0,0,0}, - {14204,15176,15649 ,726,726,726 ,0,0,0}, {15651,15175,15668 ,5472,7583,7793 ,0,0,0}, - {15669,15175,15174 ,5471,7583,7664 ,0,0,0}, {15175,15669,15668 ,7583,5471,7793 ,0,0,0}, - {15669,15174,14149 ,5471,7664,7920 ,0,0,0}, {13756,13755,15667 ,8054,8055,8056 ,0,0,0}, - {15660,13765,13756 ,8057,8058,8054 ,0,0,0}, {15660,15659,13765 ,8057,8058,8058 ,0,0,0}, - {15667,15660,13756 ,8056,8057,8054 ,0,0,0}, {13755,13934,15657 ,8055,8059,8060 ,0,0,0}, - {13832,13776,15666 ,8061,8062,8063 ,0,0,0}, {15658,15657,13934 ,8064,8060,8059 ,0,0,0}, - {13934,13832,15658 ,8059,8061,8064 ,0,0,0}, {15666,15658,13832 ,8063,8064,8061 ,0,0,0}, - {13755,15657,15667 ,8055,8060,8056 ,0,0,0}, {15666,13776,15663 ,8063,8062,8065 ,0,0,0}, - {13775,15664,15663 ,8066,8067,8065 ,0,0,0}, {15663,13776,13775 ,8065,8062,8066 ,0,0,0}, - {15664,13775,13935 ,8067,8066,8068 ,0,0,0}, {13783,15665,13935 ,8069,8070,8068 ,0,0,0}, - {13783,13782,15662 ,8069,8071,8072 ,0,0,0}, {13783,15662,15665 ,8069,8072,8070 ,0,0,0}, - {15661,13797,15649 ,8073,8074,8075 ,0,0,0}, {15662,13782,15661 ,8072,8071,8073 ,0,0,0}, - {15661,13782,13797 ,8073,8071,8074 ,0,0,0}, {13797,13800,15649 ,8074,8075,8075 ,0,0,0}, - {15664,13935,15665 ,8067,8068,8070 ,0,0,0}, {13588,15659,15655 ,8076,8058,8077 ,0,0,0}, - {15659,13588,13765 ,8058,8076,8058 ,0,0,0}, {15654,13836,15655 ,8078,8079,8077 ,0,0,0}, - {13588,15655,13836 ,8076,8077,8079 ,0,0,0}, {15654,15656,13780 ,8078,8080,8081 ,0,0,0}, - {13780,13836,15654 ,8081,8079,8078 ,0,0,0}, {13781,15656,15653 ,8082,8080,8083 ,0,0,0}, - {15656,13781,13780 ,8080,8082,8081 ,0,0,0}, {15652,13958,15653 ,8084,8085,8083 ,0,0,0}, - {13781,15653,13958 ,8082,8083,8085 ,0,0,0}, {15652,15650,13726 ,8084,8086,8087 ,0,0,0}, - {13726,13958,15652 ,8087,8085,8084 ,0,0,0}, {13725,15650,15648 ,8088,8086,8089 ,0,0,0}, - {15650,13725,13726 ,8086,8088,8087 ,0,0,0}, {15647,13809,15648 ,8090,8091,8089 ,0,0,0}, - {13725,15648,13809 ,8088,8089,8091 ,0,0,0}, {15647,15651,13849 ,8090,8092,8093 ,0,0,0}, - {13849,13809,15647 ,8093,8091,8090 ,0,0,0}, {13850,15651,15668 ,8094,8092,8095 ,0,0,0}, - {15651,13850,13849 ,8092,8094,8093 ,0,0,0}, {13850,15668,13851 ,8094,8095,8096 ,0,0,0}, - {13851,15668,15669 ,8096,8095,8096 ,0,0,0}, {14156,15669,14149 ,8097,8098,8097 ,0,0,0}, - {15669,14157,14160 ,8098,8097,8098 ,0,0,0}, {14156,14157,15669 ,8097,8097,8098 ,0,0,0}, - {15669,14166,14171 ,8098,8098,8097 ,0,0,0}, {14160,14166,15669 ,8098,8098,8098 ,0,0,0}, - {15669,14175,14134 ,8098,8098,8097 ,0,0,0}, {14171,14175,15669 ,8097,8098,8098 ,0,0,0}, - {15669,14138,14137 ,8098,8097,8097 ,0,0,0}, {14134,14138,15669 ,8097,8097,8098 ,0,0,0}, - {15669,14137,13851 ,8098,8097,8098 ,0,0,0}, {14213,15649,13800 ,8099,8099,8099 ,0,0,0}, - {14213,14269,15649 ,8099,8099,8099 ,0,0,0}, {15649,14269,14255 ,8099,8099,8099 ,0,0,0}, - {14209,14215,15649 ,8099,8099,8099 ,0,0,0}, {14209,15649,14255 ,8099,8099,8099 ,0,0,0}, - {14215,14251,15649 ,8099,8099,8099 ,0,0,0}, {15649,14198,14197 ,8099,8099,8099 ,0,0,0}, - {14251,14198,15649 ,8099,8099,8099 ,0,0,0}, {14204,15649,14202 ,8099,8099,8099 ,0,0,0}, - {14197,14202,15649 ,8099,8099,8099 ,0,0,0}, {12342,15670,13992 ,1359,8100,4482 ,0,0,0}, - {15671,13991,15672 ,4475,8101,8102 ,0,0,0}, {13993,13990,15673 ,8103,8104,4478 ,0,0,0}, - {13824,15674,13816 ,8105,8106,8107 ,0,0,0}, {15675,15676,13996 ,4472,8108,8109 ,0,0,0}, - {15677,13853,15678 ,8110,8111,8112 ,0,0,0}, {13852,13814,15679 ,8113,8114,8115 ,0,0,0}, - {13827,13820,15680 ,8116,8117,8118 ,0,0,0}, {13855,15681,13820 ,8119,8120,8117 ,0,0,0}, - {13845,15682,15683 ,8121,8122,8123 ,0,0,0}, {13827,15684,13847 ,8116,8124,8125 ,0,0,0}, - {15685,13844,15683 ,8126,8127,8123 ,0,0,0}, {13845,15683,13844 ,8121,8123,8127 ,0,0,0}, - {15685,15686,13842 ,8126,8128,8129 ,0,0,0}, {13842,13844,15685 ,8129,8127,8126 ,0,0,0}, - {13839,15686,15687 ,8130,8128,8131 ,0,0,0}, {15686,13839,13842 ,8128,8130,8129 ,0,0,0}, - {15688,13840,15687 ,8132,8133,8131 ,0,0,0}, {13839,15687,13840 ,8130,8131,8133 ,0,0,0}, - {15688,12361,12362 ,8132,1435,1435 ,0,0,0}, {12362,13840,15688 ,1435,8133,8132 ,0,0,0}, - {15680,13820,15681 ,8118,8117,8120 ,0,0,0}, {15682,13847,15684 ,8122,8125,8124 ,0,0,0}, - {13847,15682,13845 ,8125,8122,8121 ,0,0,0}, {15680,15684,13827 ,8118,8124,8116 ,0,0,0}, - {15677,15681,13855 ,8110,8120,8119 ,0,0,0}, {13852,15679,15678 ,8113,8115,8112 ,0,0,0}, - {13852,15678,13853 ,8113,8112,8111 ,0,0,0}, {13855,13853,15677 ,8119,8111,8110 ,0,0,0}, - {13814,15689,15679 ,8114,8134,8115 ,0,0,0}, {15689,13814,13816 ,8134,8114,8107 ,0,0,0}, - {15676,15674,13824 ,8108,8106,8105 ,0,0,0}, {15674,15689,13816 ,8106,8134,8107 ,0,0,0}, - {13996,15676,13824 ,8109,8108,8105 ,0,0,0}, {13972,15671,15675 ,4474,4475,4472 ,0,0,0}, - {13972,15675,13996 ,4474,4472,8109 ,0,0,0}, {13991,13993,15672 ,8101,8103,8102 ,0,0,0}, - {13972,13991,15671 ,4474,8101,4475 ,0,0,0}, {13990,15670,15673 ,8104,8100,4478 ,0,0,0}, - {15672,13993,15673 ,8102,8103,4478 ,0,0,0}, {12342,13992,12340 ,1359,4482,1359 ,0,0,0}, - {15670,13990,13992 ,8100,8104,4482 ,0,0,0}, {12336,15674,15676 ,726,726,726 ,0,0,0}, - {15682,12343,15683 ,726,7626,7758 ,0,0,0}, {15688,15687,15686 ,7625,7625,726 ,0,0,0}, - {15684,15680,12323 ,8135,7628,7626 ,0,0,0}, {12323,12321,15684 ,7626,7626,8135 ,0,0,0}, - {12333,15678,15679 ,726,7627,726 ,0,0,0}, {12326,15677,12327 ,726,7628,726 ,0,0,0}, - {12330,15674,12336 ,726,726,726 ,0,0,0}, {15679,15689,12335 ,726,726,726 ,0,0,0}, - {15671,15672,15673 ,7628,7628,726 ,0,0,0}, {12339,12336,15676 ,726,726,726 ,0,0,0}, - {12342,12339,15670 ,726,726,726 ,0,0,0}, {15670,15671,15673 ,726,7628,726 ,0,0,0}, - {15670,12339,15671 ,726,726,7628 ,0,0,0}, {15676,15675,12339 ,726,726,726 ,0,0,0}, - {12339,15675,15671 ,726,726,7628 ,0,0,0}, {15674,12330,12335 ,726,726,726 ,0,0,0}, - {12339,12338,12336 ,726,726,726 ,0,0,0}, {12335,12333,15679 ,726,726,726 ,0,0,0}, - {12335,15689,15674 ,726,726,726 ,0,0,0}, {15677,15678,12327 ,7628,7627,726 ,0,0,0}, - {12327,15678,12333 ,726,7627,726 ,0,0,0}, {12324,15681,12326 ,726,726,726 ,0,0,0}, - {12326,15681,15677 ,726,726,7628 ,0,0,0}, {12324,12323,15680 ,726,7626,7628 ,0,0,0}, - {15680,15681,12324 ,7628,726,726 ,0,0,0}, {12321,12343,15682 ,7626,7626,726 ,0,0,0}, - {12321,15682,15684 ,7626,726,8135 ,0,0,0}, {12344,15683,12343 ,7626,7758,7626 ,0,0,0}, - {15685,15683,12347 ,8135,7758,7628 ,0,0,0}, {12344,12347,15683 ,7626,7628,7758 ,0,0,0}, - {12347,12349,15686 ,7628,726,726 ,0,0,0}, {15686,15685,12347 ,726,8135,7628 ,0,0,0}, - {15688,12349,12350 ,7625,726,7626 ,0,0,0}, {12349,15688,15686 ,726,7625,726 ,0,0,0}, - {12353,12356,12359 ,7626,726,7626 ,0,0,0}, {12350,12353,15688 ,7626,7626,7625 ,0,0,0}, - {12359,15688,12353 ,7626,7625,7626 ,0,0,0}, {12353,12355,12356 ,7626,7627,726 ,0,0,0}, - {15688,12359,12361 ,7625,7626,8135 ,0,0,0}, {12303,15690,13978 ,1359,8136,8137 ,0,0,0}, - {13961,13963,15691 ,8138,8139,8140 ,0,0,0}, {13980,13982,15692 ,8141,8142,8143 ,0,0,0}, - {13768,15693,13767 ,8144,8145,8146 ,0,0,0}, {15694,15695,13962 ,8147,8148,8149 ,0,0,0}, - {15696,15697,13960 ,8150,8151,8152 ,0,0,0}, {15696,13959,15698 ,8150,8153,8154 ,0,0,0}, - {15699,15700,13892 ,8155,8156,8157 ,0,0,0}, {13892,13891,15699 ,8157,8158,8155 ,0,0,0}, - {13806,15700,15701 ,8159,8156,8160 ,0,0,0}, {15700,13806,13892 ,8156,8159,8157 ,0,0,0}, - {15702,13805,15701 ,8161,8162,8160 ,0,0,0}, {13806,15701,13805 ,8159,8160,8162 ,0,0,0}, - {15702,12317,12318 ,8161,1435,1435 ,0,0,0}, {12318,13805,15702 ,1435,8162,8161 ,0,0,0}, - {15693,13768,15695 ,8145,8144,8148 ,0,0,0}, {15697,13891,13960 ,8151,8158,8152 ,0,0,0}, - {15699,13891,15697 ,8155,8158,8151 ,0,0,0}, {15691,13963,15703 ,8140,8139,8163 ,0,0,0}, - {15698,13959,13767 ,8154,8153,8146 ,0,0,0}, {15696,13960,13959 ,8150,8152,8153 ,0,0,0}, - {15693,15698,13767 ,8145,8154,8146 ,0,0,0}, {13962,15695,13768 ,8149,8148,8144 ,0,0,0}, - {13961,15691,15694 ,8138,8140,8147 ,0,0,0}, {15694,13962,13961 ,8147,8149,8138 ,0,0,0}, - {13982,15690,15692 ,8142,8136,8143 ,0,0,0}, {15703,13980,15692 ,8163,8141,8143 ,0,0,0}, - {13963,13980,15703 ,8139,8141,8163 ,0,0,0}, {12303,13978,12304 ,1359,8137,1359 ,0,0,0}, - {15690,13982,13978 ,8136,8142,8137 ,0,0,0}, {15700,15695,15694 ,726,7661,7661 ,0,0,0}, - {15696,15698,15699 ,7661,7658,726 ,0,0,0}, {15699,15697,15696 ,726,726,7661 ,0,0,0}, - {15693,15695,15699 ,7658,7661,726 ,0,0,0}, {15693,15699,15698 ,7658,726,7658 ,0,0,0}, - {15694,15701,15700 ,7661,726,726 ,0,0,0}, {15695,15700,15699 ,7661,726,726 ,0,0,0}, - {15701,15694,15691 ,726,7661,7658 ,0,0,0}, {15691,15703,15702 ,7658,7661,726 ,0,0,0}, - {15702,15701,15691 ,726,726,7658 ,0,0,0}, {12317,15703,15692 ,726,7661,7658 ,0,0,0}, - {15703,12317,15702 ,7661,726,726 ,0,0,0}, {12302,12311,12303 ,7658,726,726 ,0,0,0}, - {15690,12315,15692 ,7658,7660,7658 ,0,0,0}, {12309,12302,12300 ,726,7658,726 ,0,0,0}, - {12290,12289,12296 ,726,726,726 ,0,0,0}, {12306,12298,12305 ,726,726,726 ,0,0,0}, - {12296,12293,12292 ,726,726,726 ,0,0,0}, {12296,12289,12305 ,726,726,726 ,0,0,0}, - {12290,12296,12292 ,726,726,726 ,0,0,0}, {12300,12298,12306 ,726,726,726 ,0,0,0}, - {12298,12296,12305 ,726,726,726 ,0,0,0}, {12311,12302,12309 ,726,7658,726 ,0,0,0}, - {12309,12300,12306 ,726,726,726 ,0,0,0}, {12303,12312,15690 ,726,726,7658 ,0,0,0}, - {12303,12311,12312 ,726,726,726 ,0,0,0}, {15692,12315,12317 ,7658,7660,726 ,0,0,0}, - {12312,12315,15690 ,726,7660,7658 ,0,0,0}, {15704,15705,15172 ,726,726,7664 ,0,0,0}, - {15706,15704,15172 ,726,726,7664 ,0,0,0}, {15706,15172,15707 ,726,7664,726 ,0,0,0}, - {15708,15172,15705 ,726,7664,726 ,0,0,0}, {15709,15710,15172 ,726,726,7664 ,0,0,0}, - {15709,15172,15708 ,726,7664,726 ,0,0,0}, {15711,15172,15170 ,726,7664,726 ,0,0,0}, - {15707,15172,15711 ,726,7664,726 ,0,0,0}, {15712,15172,15710 ,726,7664,726 ,0,0,0}, - {15172,15712,15713 ,7664,726,726 ,0,0,0}, {15711,15170,15714 ,726,726,726 ,0,0,0}, - {15715,15172,15713 ,726,7664,726 ,0,0,0}, {15716,15714,15170 ,7583,726,726 ,0,0,0}, - {15170,15717,15716 ,726,7664,7583 ,0,0,0}, {15172,15715,15718 ,7664,726,726 ,0,0,0}, - {15172,15718,15719 ,7664,726,726 ,0,0,0}, {15720,15717,15170 ,726,7664,726 ,0,0,0}, - {15721,15722,15170 ,726,726,726 ,0,0,0}, {15722,15720,15170 ,726,726,726 ,0,0,0}, - {15723,15170,15724 ,726,726,726 ,0,0,0}, {15723,15721,15170 ,726,726,726 ,0,0,0}, - {15173,15719,14110 ,7664,726,726 ,0,0,0}, {15719,15173,15172 ,726,7664,7664 ,0,0,0}, - {15724,15170,15725 ,726,726,726 ,0,0,0}, {15726,15170,15171 ,726,726,7664 ,0,0,0}, - {15170,15726,15725 ,726,726,726 ,0,0,0}, {15726,15171,14034 ,726,7664,5488 ,0,0,0}, - {13822,13815,15704 ,8164,8165,8166 ,0,0,0}, {15706,13823,13822 ,8167,8168,8164 ,0,0,0}, - {15706,15707,13823 ,8167,8168,8168 ,0,0,0}, {15704,15706,13822 ,8166,8167,8164 ,0,0,0}, - {13815,13956,15705 ,8165,8169,8170 ,0,0,0}, {13854,13856,15709 ,8171,8172,8173 ,0,0,0}, - {15708,15705,13956 ,8174,8170,8169 ,0,0,0}, {13956,13854,15708 ,8169,8171,8174 ,0,0,0}, - {15709,15708,13854 ,8173,8174,8171 ,0,0,0}, {13815,15705,15704 ,8165,8170,8166 ,0,0,0}, - {15709,13856,15710 ,8173,8172,8175 ,0,0,0}, {13819,15712,15710 ,8176,8177,8175 ,0,0,0}, - {15710,13856,13819 ,8175,8172,8176 ,0,0,0}, {15712,13819,13821 ,8177,8176,8178 ,0,0,0}, - {13826,15713,13821 ,8179,8180,8178 ,0,0,0}, {13826,13858,15715 ,8179,8181,8182 ,0,0,0}, - {13826,15715,15713 ,8179,8182,8180 ,0,0,0}, {15718,13860,15719 ,8183,8184,8185 ,0,0,0}, - {15715,13858,15718 ,8182,8181,8183 ,0,0,0}, {15718,13858,13860 ,8183,8181,8184 ,0,0,0}, - {13860,13859,15719 ,8184,8185,8185 ,0,0,0}, {15712,13821,15713 ,8177,8178,8180 ,0,0,0}, - {13818,15707,15711 ,8186,8168,8187 ,0,0,0}, {15707,13818,13823 ,8168,8186,8168 ,0,0,0}, - {15714,13817,15711 ,8188,8189,8187 ,0,0,0}, {13818,15711,13817 ,8186,8187,8189 ,0,0,0}, - {15714,15716,13984 ,8188,8190,8191 ,0,0,0}, {13984,13817,15714 ,8191,8189,8188 ,0,0,0}, - {13812,15716,15717 ,8192,8190,8193 ,0,0,0}, {15716,13812,13984 ,8190,8192,8191 ,0,0,0}, - {15720,13813,15717 ,8194,8195,8193 ,0,0,0}, {13812,15717,13813 ,8192,8193,8195 ,0,0,0}, - {15720,15722,13886 ,8194,8196,8197 ,0,0,0}, {13886,13813,15720 ,8197,8195,8194 ,0,0,0}, - {13887,15722,15721 ,8198,8196,8199 ,0,0,0}, {15722,13887,13886 ,8196,8198,8197 ,0,0,0}, - {15723,13630,15721 ,8200,8201,8199 ,0,0,0}, {13887,15721,13630 ,8198,8199,8201 ,0,0,0}, - {15723,15724,13633 ,8200,8202,8203 ,0,0,0}, {13633,13630,15723 ,8203,8201,8200 ,0,0,0}, - {13634,15724,15725 ,8204,8202,8205 ,0,0,0}, {15724,13634,13633 ,8202,8204,8203 ,0,0,0}, - {13634,15725,13635 ,8204,8205,8206 ,0,0,0}, {13635,15725,15726 ,8206,8205,8206 ,0,0,0}, - {14035,15726,14034 ,8207,8207,8207 ,0,0,0}, {15726,14065,14068 ,8207,8207,8207 ,0,0,0}, - {14035,14065,15726 ,8207,8207,8207 ,0,0,0}, {15726,14074,14079 ,8207,8207,8207 ,0,0,0}, - {14068,14074,15726 ,8207,8207,8207 ,0,0,0}, {15726,14083,14013 ,8207,8207,8207 ,0,0,0}, - {14079,14083,15726 ,8207,8207,8207 ,0,0,0}, {15726,14016,14015 ,8207,8207,8207 ,0,0,0}, - {14013,14016,15726 ,8207,8207,8207 ,0,0,0}, {15726,14015,13635 ,8207,8207,8207 ,0,0,0}, - {14125,15719,13859 ,8208,8208,8208 ,0,0,0}, {14125,14176,15719 ,8208,8208,8208 ,0,0,0}, - {15719,14176,14162 ,8208,8208,8208 ,0,0,0}, {14119,14112,15719 ,8208,8208,8208 ,0,0,0}, - {14119,15719,14162 ,8208,8208,8208 ,0,0,0}, {14112,14158,15719 ,8208,8208,8208 ,0,0,0}, - {15719,14150,14104 ,8208,8208,8208 ,0,0,0}, {14158,14150,15719 ,8208,8208,8208 ,0,0,0}, - {14110,15719,14106 ,8208,8208,8208 ,0,0,0}, {14104,14106,15719 ,8208,8208,8208 ,0,0,0}, - {12266,15727,13622 ,1711,8209,4414 ,0,0,0}, {15728,13885,15729 ,8210,8211,8212 ,0,0,0}, - {13870,13623,15730 ,8213,8214,4410 ,0,0,0}, {13884,15731,13614 ,4402,8215,8216 ,0,0,0}, - {15732,15733,13883 ,8217,8218,8219 ,0,0,0}, {15734,13644,15735 ,8220,8221,8222 ,0,0,0}, - {13643,13869,15736 ,8223,8224,8225 ,0,0,0}, {13617,13616,15737 ,8226,8227,8228 ,0,0,0}, - {13639,15738,13616 ,8229,8230,8227 ,0,0,0}, {13620,15739,15740 ,8231,8232,8233 ,0,0,0}, - {13617,15741,13619 ,8226,8234,8235 ,0,0,0}, {15742,13636,15740 ,8236,8237,8233 ,0,0,0}, - {13620,15740,13636 ,8231,8233,8237 ,0,0,0}, {15742,15743,13624 ,8236,8238,8239 ,0,0,0}, - {13624,13636,15742 ,8239,8237,8236 ,0,0,0}, {13872,15743,15744 ,8240,8238,8241 ,0,0,0}, - {15743,13872,13624 ,8238,8240,8239 ,0,0,0}, {15745,13632,15744 ,8242,8243,8241 ,0,0,0}, - {13872,15744,13632 ,8240,8241,8243 ,0,0,0}, {15745,12285,12286 ,8242,1790,1790 ,0,0,0}, - {12286,13632,15745 ,1790,8243,8242 ,0,0,0}, {15737,13616,15738 ,8228,8227,8230 ,0,0,0}, - {15739,13619,15741 ,8232,8235,8234 ,0,0,0}, {13619,15739,13620 ,8235,8232,8231 ,0,0,0}, - {15737,15741,13617 ,8228,8234,8226 ,0,0,0}, {15734,15738,13639 ,8220,8230,8229 ,0,0,0}, - {13643,15736,15735 ,8223,8225,8222 ,0,0,0}, {13643,15735,13644 ,8223,8222,8221 ,0,0,0}, - {13639,13644,15734 ,8229,8221,8220 ,0,0,0}, {13869,15746,15736 ,8224,8244,8225 ,0,0,0}, - {15746,13869,13614 ,8244,8224,8216 ,0,0,0}, {15733,15731,13884 ,8218,8215,4402 ,0,0,0}, - {15731,15746,13614 ,8215,8244,8216 ,0,0,0}, {13883,15733,13884 ,8219,8218,4402 ,0,0,0}, - {13584,15728,15732 ,8245,8210,8217 ,0,0,0}, {13584,15732,13883 ,8245,8217,8219 ,0,0,0}, - {13885,13870,15729 ,8211,8213,8212 ,0,0,0}, {13584,13885,15728 ,8245,8211,8210 ,0,0,0}, - {13623,15727,15730 ,8214,8209,4410 ,0,0,0}, {15729,13870,15730 ,8212,8213,4410 ,0,0,0}, - {12266,13622,12264 ,1711,4414,1711 ,0,0,0}, {15727,13623,13622 ,8209,8214,4414 ,0,0,0}, - {15732,15737,15738 ,726,726,7626 ,0,0,0}, {15746,15735,15736 ,726,726,726 ,0,0,0}, - {15734,15746,15731 ,726,726,726 ,0,0,0}, {15733,15734,15731 ,726,726,726 ,0,0,0}, - {15733,15738,15734 ,726,7626,726 ,0,0,0}, {15746,15734,15735 ,726,726,726 ,0,0,0}, - {15733,15732,15738 ,726,726,7626 ,0,0,0}, {15728,15741,15737 ,726,726,726 ,0,0,0}, - {15732,15728,15737 ,726,726,726 ,0,0,0}, {15741,15729,15739 ,726,726,7626 ,0,0,0}, - {15729,15741,15728 ,726,726,726 ,0,0,0}, {15740,15739,15730 ,7628,7626,726 ,0,0,0}, - {15729,15730,15739 ,726,726,7626 ,0,0,0}, {15727,15742,15740 ,726,726,7628 ,0,0,0}, - {15740,15730,15727 ,7628,726,726 ,0,0,0}, {15742,12266,15743 ,726,726,726 ,0,0,0}, - {12266,15742,15727 ,726,726,726 ,0,0,0}, {15744,15743,12263 ,7625,726,726 ,0,0,0}, - {12266,12263,15743 ,726,726,726 ,0,0,0}, {15744,12263,12262 ,7625,726,726 ,0,0,0}, - {15745,15744,12262 ,726,7625,726 ,0,0,0}, {12262,12260,15745 ,726,726,726 ,0,0,0}, - {12254,12285,12260 ,726,726,726 ,0,0,0}, {15745,12260,12285 ,726,726,726 ,0,0,0}, - {12257,12251,12279 ,726,726,7625 ,0,0,0}, {12254,12259,12283 ,726,726,726 ,0,0,0}, - {12248,12273,12274 ,7626,726,726 ,0,0,0}, {12274,12277,12250 ,726,726,726 ,0,0,0}, - {12273,12247,12271 ,726,7625,7625 ,0,0,0}, {12247,12268,12271 ,7625,726,7625 ,0,0,0}, - {12245,12268,12247 ,726,726,7625 ,0,0,0}, {12245,12267,12268 ,726,726,726 ,0,0,0}, - {12250,12248,12274 ,726,7626,726 ,0,0,0}, {12247,12273,12248 ,7625,726,7626 ,0,0,0}, - {12277,12279,12251 ,726,7625,726 ,0,0,0}, {12250,12277,12251 ,726,726,726 ,0,0,0}, - {12257,12280,12259 ,726,726,726 ,0,0,0}, {12257,12279,12280 ,726,7625,726 ,0,0,0}, - {12254,12283,12285 ,726,726,726 ,0,0,0}, {12280,12283,12259 ,726,726,726 ,0,0,0}, - {12227,15747,13896 ,1711,8246,8247 ,0,0,0}, {13955,13969,15748 ,8248,8249,8250 ,0,0,0}, - {13968,13897,15749 ,8251,8252,8253 ,0,0,0}, {13808,15750,13807 ,8254,8255,8256 ,0,0,0}, - {15751,15752,13989 ,8257,8258,8259 ,0,0,0}, {15753,15754,13987 ,8260,8261,8262 ,0,0,0}, - {15753,13986,15755 ,8260,8263,8264 ,0,0,0}, {15756,15757,13889 ,8265,8266,8267 ,0,0,0}, - {13889,13890,15756 ,8267,8268,8265 ,0,0,0}, {13985,15757,15758 ,8269,8266,8270 ,0,0,0}, - {15757,13985,13889 ,8266,8269,8267 ,0,0,0}, {15759,13888,15758 ,8271,8272,8270 ,0,0,0}, - {13985,15758,13888 ,8269,8270,8272 ,0,0,0}, {15759,12241,12242 ,8271,1790,1790 ,0,0,0}, - {12242,13888,15759 ,1790,8272,8271 ,0,0,0}, {15750,13808,15752 ,8255,8254,8258 ,0,0,0}, - {15754,13890,13987 ,8261,8268,8262 ,0,0,0}, {15756,13890,15754 ,8265,8268,8261 ,0,0,0}, - {15748,13969,15760 ,8250,8249,8273 ,0,0,0}, {15755,13986,13807 ,8264,8263,8256 ,0,0,0}, - {15753,13987,13986 ,8260,8262,8263 ,0,0,0}, {15750,15755,13807 ,8255,8264,8256 ,0,0,0}, - {13989,15752,13808 ,8259,8258,8254 ,0,0,0}, {13955,15748,15751 ,8248,8250,8257 ,0,0,0}, - {15751,13989,13955 ,8257,8259,8248 ,0,0,0}, {13897,15747,15749 ,8252,8246,8253 ,0,0,0}, - {15760,13968,15749 ,8273,8251,8253 ,0,0,0}, {13969,13968,15760 ,8249,8251,8273 ,0,0,0}, - {12227,13896,12228 ,1711,8247,1711 ,0,0,0}, {15747,13897,13896 ,8246,8252,8247 ,0,0,0}, - {12241,15759,15758 ,726,7658,726 ,0,0,0}, {15760,12216,15748 ,726,726,726 ,0,0,0}, - {12239,15758,15757 ,7660,726,7660 ,0,0,0}, {15753,12235,15754 ,7660,726,7660 ,0,0,0}, - {12236,12239,15756 ,7660,7660,7583 ,0,0,0}, {12229,15750,15752 ,7660,7661,7661 ,0,0,0}, - {12233,15753,15755 ,726,7660,7658 ,0,0,0}, {12214,15748,12216 ,726,726,726 ,0,0,0}, - {15752,15751,12213 ,7661,726,726 ,0,0,0}, {15747,12222,12220 ,726,726,726 ,0,0,0}, - {15749,12217,15760 ,726,726,726 ,0,0,0}, {12227,12226,12222 ,726,726,726 ,0,0,0}, - {12224,12222,12226 ,726,726,726 ,0,0,0}, {12222,15747,12227 ,726,726,726 ,0,0,0}, - {15749,12220,12217 ,726,726,726 ,0,0,0}, {15749,15747,12220 ,726,726,726 ,0,0,0}, - {15751,15748,12214 ,726,726,726 ,0,0,0}, {12216,15760,12217 ,726,726,726 ,0,0,0}, - {12213,12229,15752 ,726,7660,7661 ,0,0,0}, {12214,12213,15751 ,726,726,726 ,0,0,0}, - {15755,15750,12230 ,7658,7661,7659 ,0,0,0}, {12230,15750,12229 ,7659,7661,7660 ,0,0,0}, - {12233,15755,12230 ,726,7658,7659 ,0,0,0}, {12236,15754,12235 ,7660,7660,726 ,0,0,0}, - {15753,12233,12235 ,7660,726,726 ,0,0,0}, {12239,15757,15756 ,7660,7660,7583 ,0,0,0}, - {12236,15756,15754 ,7660,7583,7660 ,0,0,0}, {12239,12241,15758 ,7660,726,726 ,0,0,0}, - {13994,12186,15761 ,8274,8275,8276 ,0,0,0}, {13995,13971,15762 ,8277,8278,8279 ,0,0,0}, - {15763,13971,13988 ,8280,8278,8281 ,0,0,0}, {15764,15765,13895 ,8282,8283,8284 ,0,0,0}, - {15766,13967,13966 ,8285,8286,8287 ,0,0,0}, {13976,13964,15767 ,8288,8289,8290 ,0,0,0}, - {13975,15768,15769 ,8291,8292,8293 ,0,0,0}, {13998,15770,13981 ,8294,8295,8296 ,0,0,0}, - {15771,15772,13977 ,1631,8297,1631 ,0,0,0}, {15773,15774,13979 ,8298,8299,8300 ,0,0,0}, - {15773,13999,15775 ,8298,8301,8302 ,0,0,0}, {15776,15777,13974 ,8303,8304,8305 ,0,0,0}, - {15776,13973,15774 ,8303,8306,8299 ,0,0,0}, {13912,15777,15778 ,8307,8304,8308 ,0,0,0}, - {15777,13912,13974 ,8304,8307,8305 ,0,0,0}, {15779,13953,15778 ,8309,8310,8308 ,0,0,0}, - {13912,15778,13953 ,8307,8308,8310 ,0,0,0}, {13894,15779,13947 ,8311,8309,8312 ,0,0,0}, - {13894,13953,15779 ,8311,8310,8309 ,0,0,0}, {13945,13947,15780 ,8313,8312,8314 ,0,0,0}, - {15779,15780,13947 ,8309,8314,8312 ,0,0,0}, {15781,12210,13945 ,8315,126,8313 ,0,0,0}, - {13945,15780,15781 ,8313,8314,8315 ,0,0,0}, {12208,12210,15781 ,126,126,8315 ,0,0,0}, - {13973,13979,15774 ,8306,8300,8299 ,0,0,0}, {15776,13974,13973 ,8303,8305,8306 ,0,0,0}, - {13999,13981,15775 ,8301,8296,8302 ,0,0,0}, {15773,13979,13999 ,8298,8300,8301 ,0,0,0}, - {15772,15770,13998 ,8297,8295,8294 ,0,0,0}, {15770,15775,13981 ,8295,8302,8296 ,0,0,0}, - {13976,15771,13977 ,8288,1631,1631 ,0,0,0}, {13977,15772,13998 ,1631,8297,8294 ,0,0,0}, - {13964,15769,15767 ,8289,8293,8290 ,0,0,0}, {13976,15767,15771 ,8288,8290,1631 ,0,0,0}, - {13975,13997,15768 ,8291,8316,8292 ,0,0,0}, {13964,13975,15769 ,8289,8291,8293 ,0,0,0}, - {13895,15765,13997 ,8284,8283,8316 ,0,0,0}, {15768,13997,15765 ,8292,8316,8283 ,0,0,0}, - {15766,15764,13967 ,8285,8282,8286 ,0,0,0}, {15764,13895,13967 ,8282,8284,8286 ,0,0,0}, - {13995,15782,13966 ,8277,8317,8287 ,0,0,0}, {15782,15766,13966 ,8317,8285,8287 ,0,0,0}, - {13971,15783,15762 ,8278,8318,8279 ,0,0,0}, {13995,15762,15782 ,8277,8279,8317 ,0,0,0}, - {15763,13988,15761 ,8280,8281,8276 ,0,0,0}, {15783,13971,15763 ,8318,8278,8280 ,0,0,0}, - {12186,13994,12185 ,8275,8274,4114 ,0,0,0}, {15761,13988,13994 ,8276,8281,8274 ,0,0,0}, - {15773,15784,15774 ,726,726,726 ,0,0,0}, {15785,12159,15781 ,726,726,726 ,0,0,0}, - {15786,15777,15787 ,726,726,726 ,0,0,0}, {12190,12144,12143 ,726,726,7661 ,0,0,0}, - {12199,12201,12153 ,726,726,726 ,0,0,0}, {15788,15780,15779 ,726,726,726 ,0,0,0}, - {12204,12207,12158 ,726,726,726 ,0,0,0}, {12208,12159,12207 ,726,726,726 ,0,0,0}, - {12156,12154,12205 ,7658,726,726 ,0,0,0}, {12204,12158,12156 ,726,726,7658 ,0,0,0}, - {15788,15785,15780 ,726,726,726 ,0,0,0}, {12201,12202,12154 ,726,726,726 ,0,0,0}, - {12199,12153,12150 ,726,726,726 ,0,0,0}, {12195,12148,12193 ,726,726,726 ,0,0,0}, - {12196,12150,12148 ,726,726,726 ,0,0,0}, {12144,12190,12193 ,726,726,726 ,0,0,0}, - {15786,15779,15778 ,726,726,726 ,0,0,0}, {15774,15789,15776 ,726,7661,726 ,0,0,0}, - {15776,15789,15787 ,726,7661,726 ,0,0,0}, {12123,12163,12162 ,7658,726,7658 ,0,0,0}, - {12189,12143,12123 ,726,7661,7658 ,0,0,0}, {15790,15784,15775 ,726,726,726 ,0,0,0}, - {12163,12127,12164 ,726,7658,726 ,0,0,0}, {12166,12128,12129 ,7661,7658,726 ,0,0,0}, - {15770,15772,15791 ,726,7661,726 ,0,0,0}, {15770,15791,15790 ,726,726,726 ,0,0,0}, - {15772,15771,15792 ,7661,7658,7658 ,0,0,0}, {12170,12169,12129 ,726,726,726 ,0,0,0}, - {12133,12172,12130 ,726,7583,726 ,0,0,0}, {15793,15794,15769 ,726,726,726 ,0,0,0}, - {15794,15792,15767 ,726,7658,726 ,0,0,0}, {12182,12136,12139 ,7664,726,7664 ,0,0,0}, - {15793,15769,15768 ,726,726,7661 ,0,0,0}, {15795,15768,15765 ,726,7661,7664 ,0,0,0}, - {12142,12186,12184 ,726,726,7664 ,0,0,0}, {15796,15761,12142 ,7664,726,726 ,0,0,0}, - {15795,15764,15797 ,726,7583,726 ,0,0,0}, {15763,15798,15783 ,7664,7664,726 ,0,0,0}, - {12164,12127,12128 ,726,7658,7658 ,0,0,0}, {15762,15783,15799 ,7664,726,7664 ,0,0,0}, - {15798,15799,15783 ,7664,7664,726 ,0,0,0}, {15763,15761,15796 ,7664,726,7664 ,0,0,0}, - {15763,15796,15798 ,7664,7664,7664 ,0,0,0}, {15800,15797,15766 ,7664,726,7583 ,0,0,0}, - {15800,15766,15782 ,7664,7583,7664 ,0,0,0}, {12186,12142,15761 ,726,726,726 ,0,0,0}, - {12135,12136,12178 ,726,726,726 ,0,0,0}, {12133,12135,12175 ,726,726,7664 ,0,0,0}, - {15800,15782,15799 ,7664,7664,7664 ,0,0,0}, {15782,15762,15799 ,7664,7664,7664 ,0,0,0}, - {15764,15766,15797 ,7583,7583,726 ,0,0,0}, {15765,15764,15795 ,7664,7583,726 ,0,0,0}, - {15793,15768,15795 ,726,7661,726 ,0,0,0}, {15767,15769,15794 ,726,726,726 ,0,0,0}, - {15771,15767,15792 ,7658,726,7658 ,0,0,0}, {15791,15772,15792 ,726,7661,7658 ,0,0,0}, - {15775,15770,15790 ,726,726,726 ,0,0,0}, {15773,15775,15784 ,726,726,726 ,0,0,0}, - {15789,15774,15784 ,7661,726,726 ,0,0,0}, {15777,15776,15787 ,726,726,726 ,0,0,0}, - {15778,15777,15786 ,726,726,726 ,0,0,0}, {15788,15779,15786 ,726,726,726 ,0,0,0}, - {15781,15780,15785 ,726,726,726 ,0,0,0}, {12208,15781,12159 ,726,726,726 ,0,0,0}, - {12158,12207,12159 ,726,726,726 ,0,0,0}, {12205,12204,12156 ,726,726,7658 ,0,0,0}, - {12202,12205,12154 ,726,726,726 ,0,0,0}, {12153,12201,12154 ,726,726,726 ,0,0,0}, - {12196,12199,12150 ,726,726,726 ,0,0,0}, {12195,12196,12148 ,726,726,726 ,0,0,0}, - {12144,12193,12148 ,726,726,726 ,0,0,0}, {12189,12190,12143 ,726,726,7661 ,0,0,0}, - {12162,12189,12123 ,7658,726,7658 ,0,0,0}, {12127,12163,12123 ,7658,726,7658 ,0,0,0}, - {12169,12166,12129 ,726,7661,726 ,0,0,0}, {12166,12164,12128 ,7661,726,7658 ,0,0,0}, - {12130,12170,12129 ,726,726,726 ,0,0,0}, {12133,12175,12172 ,726,7664,7583 ,0,0,0}, - {12130,12172,12170 ,726,7583,726 ,0,0,0}, {12135,12176,12175 ,726,7664,7664 ,0,0,0}, - {12178,12136,12182 ,726,726,7664 ,0,0,0}, {12176,12135,12178 ,7664,726,726 ,0,0,0}, - {12182,12139,12184 ,7664,7664,7664 ,0,0,0}, {12142,12184,12139 ,726,7664,7664 ,0,0,0}, - {15801,15802,12126 ,726,726,726 ,0,0,0}, {12145,12147,12155 ,726,726,726 ,0,0,0}, - {12124,12145,12160 ,726,726,726 ,0,0,0}, {12126,12125,15801 ,726,726,726 ,0,0,0}, - {12151,12152,12155 ,726,726,726 ,0,0,0}, {12146,12149,12147 ,726,726,726 ,0,0,0}, - {12151,12155,12149 ,726,726,726 ,0,0,0}, {12147,12149,12155 ,726,726,726 ,0,0,0}, - {12155,12157,12145 ,726,726,726 ,0,0,0}, {15801,12124,12160 ,726,726,726 ,0,0,0}, - {12160,12145,12157 ,726,726,726 ,0,0,0}, {12126,15802,15803 ,726,726,726 ,0,0,0}, - {15801,12125,12124 ,726,726,726 ,0,0,0}, {12131,15803,15804 ,726,726,726 ,0,0,0}, - {15803,12131,12126 ,726,726,726 ,0,0,0}, {15804,12134,12132 ,726,726,7658 ,0,0,0}, - {12131,15804,12132 ,726,726,7658 ,0,0,0}, {15805,12134,15804 ,726,726,726 ,0,0,0}, - {12134,15806,12137 ,726,726,7661 ,0,0,0}, {15806,12134,15805 ,726,726,726 ,0,0,0}, - {15806,15807,12137 ,726,726,7661 ,0,0,0}, {12138,15807,12140 ,726,726,7661 ,0,0,0}, - {12138,12137,15807 ,726,7661,726 ,0,0,0}, {12140,15808,15809 ,7661,726,726 ,0,0,0}, - {15807,15808,12140 ,726,726,7661 ,0,0,0}, {15810,12141,15809 ,726,7658,726 ,0,0,0}, - {12140,15809,12141 ,7661,726,7658 ,0,0,0}, {15811,15812,15813 ,726,726,7660 ,0,0,0}, - {15813,15814,15811 ,7660,726,726 ,0,0,0}, {15812,15815,15816 ,726,726,7658 ,0,0,0}, - {15812,15810,15813 ,726,726,7660 ,0,0,0}, {15812,15817,15810 ,726,7661,726 ,0,0,0}, - {15812,15811,15815 ,726,726,726 ,0,0,0}, {15810,15817,12141 ,726,7661,7658 ,0,0,0}, - {15817,12142,12141 ,8319,81,8320 ,0,0,0}, {15815,15800,15816 ,8321,8322,8323 ,0,0,0}, - {15812,15799,15798 ,8324,8325,8326 ,0,0,0}, {15813,15810,15793 ,8327,8328,8329 ,0,0,0}, - {15811,15814,15795 ,8330,8331,8332 ,0,0,0}, {15807,15791,15808 ,8333,8334,8335 ,0,0,0}, - {15792,15809,15808 ,8336,8337,8335 ,0,0,0}, {15805,15789,15806 ,7530,8338,8339 ,0,0,0}, - {15784,15807,15806 ,8340,8333,8339 ,0,0,0}, {15804,15786,15787 ,8341,8342,8343 ,0,0,0}, - {15787,15805,15804 ,8343,7530,8341 ,0,0,0}, {15786,15803,15788 ,8342,8344,8345 ,0,0,0}, - {15803,15786,15804 ,8344,8342,8341 ,0,0,0}, {15785,15788,15802 ,8346,8345,8347 ,0,0,0}, - {15803,15802,15788 ,8344,8347,8345 ,0,0,0}, {12160,15785,15801 ,96,8346,8348 ,0,0,0}, - {15785,15802,15801 ,8346,8347,8348 ,0,0,0}, {12159,15785,12160 ,96,8346,96 ,0,0,0}, - {15784,15806,15789 ,8340,8339,8338 ,0,0,0}, {15787,15789,15805 ,8343,8338,7530 ,0,0,0}, - {15790,15791,15807 ,8349,8334,8333 ,0,0,0}, {15784,15790,15807 ,8340,8349,8333 ,0,0,0}, - {15794,15809,15792 ,8350,8337,8336 ,0,0,0}, {15791,15792,15808 ,8334,8336,8335 ,0,0,0}, - {15793,15810,15794 ,8329,8328,8350 ,0,0,0}, {15809,15794,15810 ,8337,8350,8328 ,0,0,0}, - {15795,15814,15793 ,8332,8331,8329 ,0,0,0}, {15814,15813,15793 ,8331,8327,8329 ,0,0,0}, - {15797,15815,15811 ,7516,8321,8330 ,0,0,0}, {15797,15811,15795 ,7516,8330,8332 ,0,0,0}, - {15800,15799,15816 ,8322,8325,8323 ,0,0,0}, {15797,15800,15815 ,7516,8322,8321 ,0,0,0}, - {15812,15798,15817 ,8324,8326,8319 ,0,0,0}, {15816,15799,15812 ,8323,8325,8324 ,0,0,0}, - {12142,15817,15796 ,81,8319,8351 ,0,0,0}, {15817,15798,15796 ,8319,8326,8351 ,0,0,0} -// MotorHacker.prt - , {15818,15819,15820 ,4056,4057,4058 ,0,0,0}, {15821,15822,15820 ,4059,4060,4058 ,0,0,0}, - {15818,15820,15822 ,4056,4058,4060 ,0,0,0}, {15823,15821,15824 ,4061,4059,4062 ,0,0,0}, - {15823,15822,15821 ,4061,4060,4059 ,0,0,0}, {15825,15824,15826 ,4063,4062,4064 ,0,0,0}, - {15821,15826,15824 ,4059,4064,4062 ,0,0,0}, {15827,15828,15825 ,4065,4066,4063 ,0,0,0}, - {15825,15826,15827 ,4063,4064,4065 ,0,0,0}, {15828,15829,15830 ,4066,4067,4068 ,0,0,0}, - {15829,15828,15827 ,4067,4066,4065 ,0,0,0}, {15831,15830,15832 ,4069,4068,4070 ,0,0,0}, - {15829,15832,15830 ,4067,4070,4068 ,0,0,0}, {15833,15834,15831 ,4071,4072,4069 ,0,0,0}, - {15831,15832,15833 ,4069,4070,4071 ,0,0,0}, {15835,15836,15834 ,4073,81,4072 ,0,0,0}, - {15835,15834,15833 ,4073,4072,4071 ,0,0,0}, {15836,15837,15834 ,81,81,4072 ,0,0,0}, - {15838,15819,15818 ,4074,4057,4056 ,0,0,0}, {15838,15839,15840 ,4074,4075,4076 ,0,0,0}, - {15840,15819,15838 ,4076,4057,4074 ,0,0,0}, {15841,15842,15839 ,4077,4078,4075 ,0,0,0}, - {15839,15842,15840 ,4075,4078,4076 ,0,0,0}, {15843,15844,15841 ,4079,4080,4077 ,0,0,0}, - {15841,15839,15843 ,4077,4075,4079 ,0,0,0}, {15844,15845,15846 ,4080,4081,4082 ,0,0,0}, - {15845,15844,15843 ,4081,4080,4079 ,0,0,0}, {15847,15846,15848 ,4083,4082,4084 ,0,0,0}, - {15845,15848,15846 ,4081,4084,4082 ,0,0,0}, {15849,15850,15847 ,4085,4086,4083 ,0,0,0}, - {15847,15848,15849 ,4083,4084,4085 ,0,0,0}, {15850,15851,15852 ,4086,4087,4088 ,0,0,0}, - {15851,15850,15849 ,4087,4086,4085 ,0,0,0}, {15852,15853,15854 ,4088,4089,4090 ,0,0,0}, - {15851,15853,15852 ,4087,4089,4088 ,0,0,0}, {15852,15854,15855 ,4088,4090,4091 ,0,0,0}, - {15856,15857,15858 ,2394,2394,4092 ,0,0,0}, {15859,15860,15858 ,4093,4094,4092 ,0,0,0}, - {15856,15858,15860 ,2394,4092,4094 ,0,0,0}, {15859,15861,15862 ,4093,4095,4096 ,0,0,0}, - {15862,15860,15859 ,4096,4094,4093 ,0,0,0}, {15863,15861,15864 ,4097,4095,4098 ,0,0,0}, - {15861,15863,15862 ,4095,4097,4096 ,0,0,0}, {15865,15866,15864 ,4099,4100,4098 ,0,0,0}, - {15863,15864,15866 ,4097,4098,4100 ,0,0,0}, {15865,15867,15868 ,4099,4101,4102 ,0,0,0}, - {15868,15866,15865 ,4102,4100,4099 ,0,0,0}, {15869,15867,15870 ,4103,4101,4104 ,0,0,0}, - {15867,15869,15868 ,4101,4103,4102 ,0,0,0}, {15871,15872,15870 ,4105,4106,4104 ,0,0,0}, - {15869,15870,15872 ,4103,4104,4106 ,0,0,0}, {15871,15873,15874 ,4105,4107,4108 ,0,0,0}, - {15874,15872,15871 ,4108,4106,4105 ,0,0,0}, {15875,15876,15873 ,4109,4110,4107 ,0,0,0}, - {15873,15876,15874 ,4107,4110,4108 ,0,0,0}, {15877,15878,15875 ,4111,4112,4109 ,0,0,0}, - {15875,15873,15877 ,4109,4107,4111 ,0,0,0}, {15878,15879,15880 ,4112,4113,4114 ,0,0,0}, - {15879,15878,15877 ,4113,4112,4111 ,0,0,0}, {15879,15881,15880 ,4113,4114,4114 ,0,0,0}, - {15882,15857,15856 ,4115,2394,2394 ,0,0,0}, {15882,15883,15884 ,4115,4116,4117 ,0,0,0}, - {15884,15857,15882 ,4117,2394,4115 ,0,0,0}, {15885,15883,15886 ,4118,4116,4119 ,0,0,0}, - {15883,15885,15884 ,4116,4118,4117 ,0,0,0}, {15887,15888,15886 ,4120,4121,4119 ,0,0,0}, - {15885,15886,15888 ,4118,4119,4121 ,0,0,0}, {15887,15889,15890 ,4120,4122,4123 ,0,0,0}, - {15890,15888,15887 ,4123,4121,4120 ,0,0,0}, {15891,15889,15892 ,4124,4122,4125 ,0,0,0}, - {15889,15891,15890 ,4122,4124,4123 ,0,0,0}, {15893,15894,15892 ,4126,4127,4125 ,0,0,0}, - {15891,15892,15894 ,4124,4125,4127 ,0,0,0}, {15893,15895,15896 ,4126,4128,4129 ,0,0,0}, - {15896,15894,15893 ,4129,4127,4126 ,0,0,0}, {15897,15895,15898 ,4130,4128,4131 ,0,0,0}, - {15895,15897,15896 ,4128,4130,4129 ,0,0,0}, {15898,15899,15900 ,4131,4132,4133 ,0,0,0}, - {15897,15898,15900 ,4130,4131,4133 ,0,0,0}, {15899,15901,15902 ,4132,4134,4135 ,0,0,0}, - {15901,15899,15898 ,4134,4132,4131 ,0,0,0}, {15903,15902,15904 ,126,4135,4136 ,0,0,0}, - {15901,15904,15902 ,4134,4136,4135 ,0,0,0}, {15903,15904,15905 ,126,4136,126 ,0,0,0}, - {15906,15907,15908 ,4137,4138,4139 ,0,0,0}, {15906,15909,15910 ,4137,4140,4141 ,0,0,0}, - {15909,15911,15910 ,4140,4142,4141 ,0,0,0}, {15908,15909,15906 ,4139,4140,4137 ,0,0,0}, - {15912,15913,15914 ,4143,4144,4145 ,0,0,0}, {15911,15912,15914 ,4142,4143,4145 ,0,0,0}, - {15913,15915,15916 ,4144,4146,4147 ,0,0,0}, {15915,15913,15912 ,4146,4144,4143 ,0,0,0}, - {15916,15915,15917 ,4147,4146,4148 ,0,0,0}, {15918,15916,15917 ,4149,4147,4148 ,0,0,0}, - {15918,15919,15920 ,4149,4150,4151 ,0,0,0}, {15918,15917,15919 ,4149,4148,4150 ,0,0,0}, - {15914,15910,15911 ,4145,4141,4142 ,0,0,0}, {15921,15922,15923 ,4152,1711,1711 ,0,0,0}, - {15921,15923,15920 ,4152,1711,4151 ,0,0,0}, {15919,15921,15920 ,4150,4152,4151 ,0,0,0}, - {15908,15907,15924 ,4139,4138,4153 ,0,0,0}, {15925,15924,15926 ,4154,4153,4155 ,0,0,0}, - {15907,15926,15924 ,4138,4155,4153 ,0,0,0}, {15927,15928,15925 ,4156,4157,4154 ,0,0,0}, - {15925,15926,15927 ,4154,4155,4156 ,0,0,0}, {15928,15929,15930 ,4157,4158,4159 ,0,0,0}, - {15929,15928,15927 ,4158,4157,4156 ,0,0,0}, {15931,15930,15932 ,4160,4159,4161 ,0,0,0}, - {15929,15932,15930 ,4158,4161,4159 ,0,0,0}, {15933,15934,15931 ,4162,4163,4160 ,0,0,0}, - {15931,15932,15933 ,4160,4161,4162 ,0,0,0}, {15934,15935,15936 ,4163,4164,1790 ,0,0,0}, - {15935,15934,15933 ,4164,4163,4162 ,0,0,0}, {15935,15937,15936 ,4164,1790,1790 ,0,0,0}, - {15938,15939,15940 ,4165,4166,4167 ,0,0,0}, {15941,15942,15943 ,4168,4169,4170 ,0,0,0}, - {15942,15938,15940 ,4169,4165,4167 ,0,0,0}, {15944,15941,15943 ,4171,4168,4170 ,0,0,0}, - {15942,15941,15938 ,4169,4168,4165 ,0,0,0}, {15944,15943,15945 ,4171,4170,4172 ,0,0,0}, - {15945,15946,15947 ,4172,4173,4174 ,0,0,0}, {15948,15947,15946 ,4175,4174,4173 ,0,0,0}, - {15949,15950,15951 ,4176,4177,4178 ,0,0,0}, {15946,15952,15948 ,4173,4179,4175 ,0,0,0}, - {15951,15953,15954 ,4178,4180,4181 ,0,0,0}, {15953,15952,15954 ,4180,4179,4181 ,0,0,0}, - {15948,15952,15953 ,4175,4179,4180 ,0,0,0}, {15951,15954,15949 ,4178,4181,4176 ,0,0,0}, - {15950,15949,15955 ,4177,4176,4182 ,0,0,0}, {15950,15955,15956 ,4177,4182,4183 ,0,0,0}, - {15957,15956,15955 ,4184,4183,4182 ,0,0,0}, {15958,15959,15960 ,4185,1711,4186 ,0,0,0}, - {15960,15956,15957 ,4186,4183,4184 ,0,0,0}, {15958,15960,15957 ,4185,4186,4184 ,0,0,0}, - {15958,15961,15959 ,4185,1711,1711 ,0,0,0}, {15944,15945,15947 ,4171,4172,4174 ,0,0,0}, - {15940,15939,15962 ,4167,4166,4187 ,0,0,0}, {15963,15962,15964 ,4188,4187,4189 ,0,0,0}, - {15939,15964,15962 ,4166,4189,4187 ,0,0,0}, {15965,15966,15963 ,4190,4191,4188 ,0,0,0}, - {15963,15964,15965 ,4188,4189,4190 ,0,0,0}, {15966,15967,15968 ,4191,4192,4193 ,0,0,0}, - {15967,15966,15965 ,4192,4191,4190 ,0,0,0}, {15969,15968,15970 ,4194,4193,4195 ,0,0,0}, - {15967,15970,15968 ,4192,4195,4193 ,0,0,0}, {15971,15972,15969 ,4196,4197,4194 ,0,0,0}, - {15969,15970,15971 ,4194,4195,4196 ,0,0,0}, {15972,15973,15974 ,4197,4198,4199 ,0,0,0}, - {15973,15972,15971 ,4198,4197,4196 ,0,0,0}, {15975,15974,15976 ,4200,4199,4201 ,0,0,0}, - {15973,15976,15974 ,4198,4201,4199 ,0,0,0}, {15977,15978,15975 ,4202,4203,4200 ,0,0,0}, - {15975,15976,15977 ,4200,4201,4202 ,0,0,0}, {15978,15979,15980 ,4203,4204,1790 ,0,0,0}, - {15979,15978,15977 ,4204,4203,4202 ,0,0,0}, {15979,15981,15980 ,4204,1790,1790 ,0,0,0}, - {15982,15983,15984 ,4205,4206,4207 ,0,0,0}, {15982,15985,15986 ,4205,4208,4209 ,0,0,0}, - {15985,15987,15986 ,4208,4210,4209 ,0,0,0}, {15984,15985,15982 ,4207,4208,4205 ,0,0,0}, - {15988,15989,15990 ,4211,4212,4213 ,0,0,0}, {15987,15988,15990 ,4210,4211,4213 ,0,0,0}, - {15989,15991,15992 ,4212,4214,4215 ,0,0,0}, {15991,15989,15988 ,4214,4212,4211 ,0,0,0}, - {15992,15991,15993 ,4215,4214,4216 ,0,0,0}, {15994,15992,15993 ,4217,4215,4216 ,0,0,0}, - {15994,15995,15996 ,4217,4218,4219 ,0,0,0}, {15994,15993,15995 ,4217,4216,4218 ,0,0,0}, - {15990,15986,15987 ,4213,4209,4210 ,0,0,0}, {15997,15998,15999 ,4220,1359,1359 ,0,0,0}, - {15997,15999,15996 ,4220,1359,4219 ,0,0,0}, {15995,15997,15996 ,4218,4220,4219 ,0,0,0}, - {15984,15983,16000 ,4207,4206,4221 ,0,0,0}, {16001,16000,16002 ,4222,4221,4223 ,0,0,0}, - {15983,16002,16000 ,4206,4223,4221 ,0,0,0}, {16003,16004,16001 ,4224,4225,4222 ,0,0,0}, - {16001,16002,16003 ,4222,4223,4224 ,0,0,0}, {16004,16005,16006 ,4225,4226,4227 ,0,0,0}, - {16005,16004,16003 ,4226,4225,4224 ,0,0,0}, {16007,16006,16008 ,4228,4227,4229 ,0,0,0}, - {16005,16008,16006 ,4226,4229,4227 ,0,0,0}, {16009,16010,16007 ,4230,4231,4228 ,0,0,0}, - {16007,16008,16009 ,4228,4229,4230 ,0,0,0}, {16010,16011,16012 ,4231,4232,1435 ,0,0,0}, - {16011,16010,16009 ,4232,4231,4230 ,0,0,0}, {16011,16013,16012 ,4232,1435,1435 ,0,0,0}, - {16014,16015,16016 ,4233,4234,4235 ,0,0,0}, {16017,16018,16019 ,4236,4237,4238 ,0,0,0}, - {16018,16014,16016 ,4237,4233,4235 ,0,0,0}, {16020,16017,16019 ,4239,4236,4238 ,0,0,0}, - {16018,16017,16014 ,4237,4236,4233 ,0,0,0}, {16020,16019,16021 ,4239,4238,4240 ,0,0,0}, - {16021,16022,16023 ,4240,4241,4242 ,0,0,0}, {16024,16023,16022 ,4243,4242,4241 ,0,0,0}, - {16025,16026,16027 ,4244,4245,4246 ,0,0,0}, {16022,16028,16024 ,4241,4247,4243 ,0,0,0}, - {16027,16029,16030 ,4246,4248,4249 ,0,0,0}, {16029,16028,16030 ,4248,4247,4249 ,0,0,0}, - {16024,16028,16029 ,4243,4247,4248 ,0,0,0}, {16027,16030,16025 ,4246,4249,4244 ,0,0,0}, - {16026,16025,16031 ,4245,4244,4250 ,0,0,0}, {16026,16031,16032 ,4245,4250,4251 ,0,0,0}, - {16033,16032,16031 ,4252,4251,4250 ,0,0,0}, {16034,16035,16036 ,4253,1359,4254 ,0,0,0}, - {16036,16032,16033 ,4254,4251,4252 ,0,0,0}, {16034,16036,16033 ,4253,4254,4252 ,0,0,0}, - {16034,16037,16035 ,4253,1359,1359 ,0,0,0}, {16020,16021,16023 ,4239,4240,4242 ,0,0,0}, - {16016,16015,16038 ,4235,4234,4255 ,0,0,0}, {16039,16038,16040 ,4256,4255,4257 ,0,0,0}, - {16015,16040,16038 ,4234,4257,4255 ,0,0,0}, {16041,16042,16039 ,4258,4259,4256 ,0,0,0}, - {16039,16040,16041 ,4256,4257,4258 ,0,0,0}, {16042,16043,16044 ,4259,4260,4261 ,0,0,0}, - {16043,16042,16041 ,4260,4259,4258 ,0,0,0}, {16045,16044,16046 ,4262,4261,4263 ,0,0,0}, - {16043,16046,16044 ,4260,4263,4261 ,0,0,0}, {16047,16048,16045 ,4264,4265,4262 ,0,0,0}, - {16045,16046,16047 ,4262,4263,4264 ,0,0,0}, {16048,16049,16050 ,4265,4266,4267 ,0,0,0}, - {16049,16048,16047 ,4266,4265,4264 ,0,0,0}, {16051,16050,16052 ,4268,4267,4269 ,0,0,0}, - {16049,16052,16050 ,4266,4269,4267 ,0,0,0}, {16053,16054,16051 ,4270,4271,4268 ,0,0,0}, - {16051,16052,16053 ,4268,4269,4270 ,0,0,0}, {16054,16055,16056 ,4271,4272,1435 ,0,0,0}, - {16055,16054,16053 ,4272,4271,4270 ,0,0,0}, {16055,16057,16056 ,4272,1435,1435 ,0,0,0}, - {16058,16059,16060 ,4273,4274,4275 ,0,0,0}, {16058,16061,16062 ,4273,4276,4277 ,0,0,0}, - {16061,16063,16062 ,4276,4278,4277 ,0,0,0}, {16060,16061,16058 ,4275,4276,4273 ,0,0,0}, - {16064,16065,16066 ,4279,4280,4281 ,0,0,0}, {16063,16064,16066 ,4278,4279,4281 ,0,0,0}, - {16065,16067,16068 ,4280,4282,4283 ,0,0,0}, {16067,16065,16064 ,4282,4280,4279 ,0,0,0}, - {16068,16067,16069 ,4283,4282,4284 ,0,0,0}, {16070,16068,16069 ,4285,4283,4284 ,0,0,0}, - {16070,16071,16072 ,4285,4286,4287 ,0,0,0}, {16070,16069,16071 ,4285,4284,4286 ,0,0,0}, - {16066,16062,16063 ,4281,4277,4278 ,0,0,0}, {16073,16074,16075 ,4288,126,4289 ,0,0,0}, - {16073,16075,16072 ,4288,4289,4287 ,0,0,0}, {16071,16073,16072 ,4286,4288,4287 ,0,0,0}, - {16060,16059,16076 ,4275,4274,4290 ,0,0,0}, {16077,16076,16078 ,4291,4290,4292 ,0,0,0}, - {16059,16078,16076 ,4274,4292,4290 ,0,0,0}, {16079,16080,16077 ,4293,4294,4291 ,0,0,0}, - {16077,16078,16079 ,4291,4292,4293 ,0,0,0}, {16080,16081,16082 ,4294,4295,4296 ,0,0,0}, - {16081,16080,16079 ,4295,4294,4293 ,0,0,0}, {16083,16082,16084 ,4297,4296,4298 ,0,0,0}, - {16081,16084,16082 ,4295,4298,4296 ,0,0,0}, {16085,16086,16083 ,4299,4300,4297 ,0,0,0}, - {16083,16084,16085 ,4297,4298,4299 ,0,0,0}, {16086,16087,16088 ,4300,4301,4302 ,0,0,0}, - {16087,16086,16085 ,4301,4300,4299 ,0,0,0}, {16087,16089,16088 ,4301,4303,4302 ,0,0,0}, - {16090,16091,16092 ,4304,4305,4306 ,0,0,0}, {16093,16094,16095 ,4307,4308,4309 ,0,0,0}, - {16094,16090,16092 ,4308,4304,4306 ,0,0,0}, {16096,16093,16095 ,4310,4307,4309 ,0,0,0}, - {16094,16093,16090 ,4308,4307,4304 ,0,0,0}, {16096,16095,16097 ,4310,4309,4311 ,0,0,0}, - {16097,16098,16099 ,4311,4312,4313 ,0,0,0}, {16100,16099,16098 ,4314,4313,4312 ,0,0,0}, - {16101,16102,16103 ,4315,4316,4317 ,0,0,0}, {16098,16104,16100 ,4312,4318,4314 ,0,0,0}, - {16103,16105,16106 ,4317,4319,4320 ,0,0,0}, {16105,16104,16106 ,4319,4318,4320 ,0,0,0}, - {16100,16104,16105 ,4314,4318,4319 ,0,0,0}, {16103,16106,16101 ,4317,4320,4315 ,0,0,0}, - {16102,16101,16107 ,4316,4315,4321 ,0,0,0}, {16102,16107,16108 ,4316,4321,4322 ,0,0,0}, - {16109,16108,16107 ,4323,4322,4321 ,0,0,0}, {16110,16111,16112 ,4324,126,4325 ,0,0,0}, - {16112,16108,16109 ,4325,4322,4323 ,0,0,0}, {16110,16112,16109 ,4324,4325,4323 ,0,0,0}, - {16110,16113,16111 ,4324,4326,126 ,0,0,0}, {16096,16097,16099 ,4310,4311,4313 ,0,0,0}, - {16092,16091,16114 ,4306,4305,4327 ,0,0,0}, {16115,16114,16116 ,4328,4327,4329 ,0,0,0}, - {16091,16116,16114 ,4305,4329,4327 ,0,0,0}, {16117,16118,16115 ,4330,4331,4328 ,0,0,0}, - {16115,16116,16117 ,4328,4329,4330 ,0,0,0}, {16118,16119,16120 ,4331,4332,4333 ,0,0,0}, - {16119,16118,16117 ,4332,4331,4330 ,0,0,0}, {16121,16120,16122 ,4334,4333,4335 ,0,0,0}, - {16119,16122,16120 ,4332,4335,4333 ,0,0,0}, {16123,16124,16121 ,4336,4337,4334 ,0,0,0}, - {16121,16122,16123 ,4334,4335,4336 ,0,0,0}, {16124,16125,16126 ,4337,4338,4339 ,0,0,0}, - {16125,16124,16123 ,4338,4337,4336 ,0,0,0}, {16127,16126,16128 ,4340,4339,4341 ,0,0,0}, - {16125,16128,16126 ,4338,4341,4339 ,0,0,0}, {16129,16130,16127 ,4342,4343,4340 ,0,0,0}, - {16127,16128,16129 ,4340,4341,4342 ,0,0,0}, {16130,16131,16132 ,4343,4344,4345 ,0,0,0}, - {16131,16130,16129 ,4344,4343,4342 ,0,0,0}, {16131,16133,16132 ,4344,4346,4345 ,0,0,0}, - {16134,16135,16136 ,4347,4348,4349 ,0,0,0}, {16134,16137,16138 ,4347,4350,4351 ,0,0,0}, - {16137,16139,16138 ,4350,4352,4351 ,0,0,0}, {16136,16137,16134 ,4349,4350,4347 ,0,0,0}, - {16140,16141,16142 ,4353,4354,4355 ,0,0,0}, {16139,16140,16142 ,4352,4353,4355 ,0,0,0}, - {16141,16143,16144 ,4354,4356,4357 ,0,0,0}, {16143,16141,16140 ,4356,4354,4353 ,0,0,0}, - {16144,16143,16145 ,4357,4356,4358 ,0,0,0}, {16146,16144,16145 ,4359,4357,4358 ,0,0,0}, - {16146,16147,16148 ,4359,4360,4361 ,0,0,0}, {16146,16145,16147 ,4359,4358,4360 ,0,0,0}, - {16142,16138,16139 ,4355,4351,4352 ,0,0,0}, {16149,16150,16151 ,4362,1790,1790 ,0,0,0}, - {16149,16151,16148 ,4362,1790,4361 ,0,0,0}, {16147,16149,16148 ,4360,4362,4361 ,0,0,0}, - {16136,16135,16152 ,4349,4348,4363 ,0,0,0}, {16153,16152,16154 ,4364,4363,4365 ,0,0,0}, - {16135,16154,16152 ,4348,4365,4363 ,0,0,0}, {16155,16156,16153 ,4366,4367,4364 ,0,0,0}, - {16153,16154,16155 ,4364,4365,4366 ,0,0,0}, {16156,16157,16158 ,4367,4368,4369 ,0,0,0}, - {16157,16156,16155 ,4368,4367,4366 ,0,0,0}, {16159,16158,16160 ,4370,4369,4371 ,0,0,0}, - {16157,16160,16158 ,4368,4371,4369 ,0,0,0}, {16161,16162,16159 ,4372,4373,4370 ,0,0,0}, - {16159,16160,16161 ,4370,4371,4372 ,0,0,0}, {16162,16163,16164 ,4373,4374,1711 ,0,0,0}, - {16163,16162,16161 ,4374,4373,4372 ,0,0,0}, {16163,16165,16164 ,4374,1711,1711 ,0,0,0}, - {16166,16167,16168 ,4375,4376,4377 ,0,0,0}, {16169,16170,16171 ,4378,4379,4380 ,0,0,0}, - {16170,16166,16168 ,4379,4375,4377 ,0,0,0}, {16172,16169,16171 ,4381,4378,4380 ,0,0,0}, - {16170,16169,16166 ,4379,4378,4375 ,0,0,0}, {16172,16171,16173 ,4381,4380,4382 ,0,0,0}, - {16173,16174,16175 ,4382,4383,4384 ,0,0,0}, {16176,16175,16174 ,4385,4384,4383 ,0,0,0}, - {16177,16178,16179 ,4386,4387,4388 ,0,0,0}, {16174,16180,16176 ,4383,4389,4385 ,0,0,0}, - {16179,16181,16182 ,4388,4390,4391 ,0,0,0}, {16181,16180,16182 ,4390,4389,4391 ,0,0,0}, - {16176,16180,16181 ,4385,4389,4390 ,0,0,0}, {16179,16182,16177 ,4388,4391,4386 ,0,0,0}, - {16178,16177,16183 ,4387,4386,4392 ,0,0,0}, {16178,16183,16184 ,4387,4392,4393 ,0,0,0}, - {16185,16184,16183 ,4394,4393,4392 ,0,0,0}, {16186,16187,16188 ,4395,1790,4396 ,0,0,0}, - {16188,16184,16185 ,4396,4393,4394 ,0,0,0}, {16186,16188,16185 ,4395,4396,4394 ,0,0,0}, - {16186,16189,16187 ,4395,1790,1790 ,0,0,0}, {16172,16173,16175 ,4381,4382,4384 ,0,0,0}, - {16168,16167,16190 ,4377,4376,4397 ,0,0,0}, {16191,16190,16192 ,4398,4397,4399 ,0,0,0}, - {16167,16192,16190 ,4376,4399,4397 ,0,0,0}, {16193,16194,16191 ,4400,4401,4398 ,0,0,0}, - {16191,16192,16193 ,4398,4399,4400 ,0,0,0}, {16194,16195,16196 ,4401,4402,4403 ,0,0,0}, - {16195,16194,16193 ,4402,4401,4400 ,0,0,0}, {16197,16196,16198 ,4404,4403,4405 ,0,0,0}, - {16195,16198,16196 ,4402,4405,4403 ,0,0,0}, {16199,16200,16197 ,4406,4407,4404 ,0,0,0}, - {16197,16198,16199 ,4404,4405,4406 ,0,0,0}, {16200,16201,16202 ,4407,4408,4409 ,0,0,0}, - {16201,16200,16199 ,4408,4407,4406 ,0,0,0}, {16203,16202,16204 ,4410,4409,4411 ,0,0,0}, - {16201,16204,16202 ,4408,4411,4409 ,0,0,0}, {16205,16206,16203 ,4412,4413,4410 ,0,0,0}, - {16203,16204,16205 ,4410,4411,4412 ,0,0,0}, {16206,16207,16208 ,4413,4414,1711 ,0,0,0}, - {16207,16206,16205 ,4414,4413,4412 ,0,0,0}, {16207,16209,16208 ,4414,1711,1711 ,0,0,0}, - {16210,16211,16212 ,4415,4416,4417 ,0,0,0}, {16210,16213,16214 ,4415,4418,4419 ,0,0,0}, - {16213,16215,16214 ,4418,4420,4419 ,0,0,0}, {16212,16213,16210 ,4417,4418,4415 ,0,0,0}, - {16216,16217,16218 ,4421,4422,4423 ,0,0,0}, {16215,16216,16218 ,4420,4421,4423 ,0,0,0}, - {16217,16219,16220 ,4422,4424,4425 ,0,0,0}, {16219,16217,16216 ,4424,4422,4421 ,0,0,0}, - {16220,16219,16221 ,4425,4424,4426 ,0,0,0}, {16222,16220,16221 ,4427,4425,4426 ,0,0,0}, - {16222,16223,16224 ,4427,4428,4429 ,0,0,0}, {16222,16221,16223 ,4427,4426,4428 ,0,0,0}, - {16218,16214,16215 ,4423,4419,4420 ,0,0,0}, {16225,16226,16227 ,4430,1435,1435 ,0,0,0}, - {16225,16227,16224 ,4430,1435,4429 ,0,0,0}, {16223,16225,16224 ,4428,4430,4429 ,0,0,0}, - {16212,16211,16228 ,4417,4416,4431 ,0,0,0}, {16229,16228,16230 ,4432,4431,4433 ,0,0,0}, - {16211,16230,16228 ,4416,4433,4431 ,0,0,0}, {16231,16232,16229 ,4434,4435,4432 ,0,0,0}, - {16229,16230,16231 ,4432,4433,4434 ,0,0,0}, {16232,16233,16234 ,4435,4436,4437 ,0,0,0}, - {16233,16232,16231 ,4436,4435,4434 ,0,0,0}, {16235,16234,16236 ,4438,4437,4439 ,0,0,0}, - {16233,16236,16234 ,4436,4439,4437 ,0,0,0}, {16237,16238,16235 ,4440,4441,4438 ,0,0,0}, - {16235,16236,16237 ,4438,4439,4440 ,0,0,0}, {16238,16239,16240 ,4441,4442,1359 ,0,0,0}, - {16239,16238,16237 ,4442,4441,4440 ,0,0,0}, {16239,16241,16240 ,4442,1359,1359 ,0,0,0}, - {16242,16243,16244 ,4443,4444,4445 ,0,0,0}, {16245,16246,16247 ,4446,4447,4448 ,0,0,0}, - {16246,16242,16244 ,4447,4443,4445 ,0,0,0}, {16248,16245,16247 ,4449,4446,4448 ,0,0,0}, - {16246,16245,16242 ,4447,4446,4443 ,0,0,0}, {16248,16247,16249 ,4449,4448,4450 ,0,0,0}, - {16249,16250,16251 ,4450,4451,4452 ,0,0,0}, {16252,16251,16250 ,4453,4452,4451 ,0,0,0}, - {16253,16254,16255 ,4454,4455,4456 ,0,0,0}, {16250,16256,16252 ,4451,4457,4453 ,0,0,0}, - {16255,16257,16258 ,4456,4458,4459 ,0,0,0}, {16257,16256,16258 ,4458,4457,4459 ,0,0,0}, - {16252,16256,16257 ,4453,4457,4458 ,0,0,0}, {16255,16258,16253 ,4456,4459,4454 ,0,0,0}, - {16254,16253,16259 ,4455,4454,4460 ,0,0,0}, {16254,16259,16260 ,4455,4460,4461 ,0,0,0}, - {16261,16260,16259 ,4462,4461,4460 ,0,0,0}, {16262,16263,16264 ,4463,1435,4464 ,0,0,0}, - {16264,16260,16261 ,4464,4461,4462 ,0,0,0}, {16262,16264,16261 ,4463,4464,4462 ,0,0,0}, - {16262,16265,16263 ,4463,1435,1435 ,0,0,0}, {16248,16249,16251 ,4449,4450,4452 ,0,0,0}, - {16244,16243,16266 ,4445,4444,4465 ,0,0,0}, {16267,16266,16268 ,4466,4465,4467 ,0,0,0}, - {16243,16268,16266 ,4444,4467,4465 ,0,0,0}, {16269,16270,16267 ,4468,4469,4466 ,0,0,0}, - {16267,16268,16269 ,4466,4467,4468 ,0,0,0}, {16270,16271,16272 ,4469,4470,4471 ,0,0,0}, - {16271,16270,16269 ,4470,4469,4468 ,0,0,0}, {16273,16272,16274 ,4472,4471,4473 ,0,0,0}, - {16271,16274,16272 ,4470,4473,4471 ,0,0,0}, {16275,16276,16273 ,4474,4475,4472 ,0,0,0}, - {16273,16274,16275 ,4472,4473,4474 ,0,0,0}, {16276,16277,16278 ,4475,4476,4477 ,0,0,0}, - {16277,16276,16275 ,4476,4475,4474 ,0,0,0}, {16279,16278,16280 ,4478,4477,4479 ,0,0,0}, - {16277,16280,16278 ,4476,4479,4477 ,0,0,0}, {16281,16282,16279 ,4480,4481,4478 ,0,0,0}, - {16279,16280,16281 ,4478,4479,4480 ,0,0,0}, {16282,16283,16284 ,4481,4482,1359 ,0,0,0}, - {16283,16282,16281 ,4482,4481,4480 ,0,0,0}, {16283,16285,16284 ,4482,1359,1359 ,0,0,0}, - {16286,16287,16288 ,4483,4484,4485 ,0,0,0}, {16286,16289,16290 ,4483,4486,4487 ,0,0,0}, - {16289,16291,16290 ,4486,4488,4487 ,0,0,0}, {16288,16289,16286 ,4485,4486,4483 ,0,0,0}, - {16292,16293,16294 ,4489,4490,4491 ,0,0,0}, {16291,16292,16294 ,4488,4489,4491 ,0,0,0}, - {16293,16295,16296 ,4490,4492,4493 ,0,0,0}, {16295,16293,16292 ,4492,4490,4489 ,0,0,0}, - {16296,16295,16297 ,4493,4492,4494 ,0,0,0}, {16298,16296,16297 ,4495,4493,4494 ,0,0,0}, - {16298,16299,16300 ,4495,4496,4497 ,0,0,0}, {16298,16297,16299 ,4495,4494,4496 ,0,0,0}, - {16294,16290,16291 ,4491,4487,4488 ,0,0,0}, {16301,16302,16303 ,4498,4499,82 ,0,0,0}, - {16301,16303,16300 ,4498,82,4497 ,0,0,0}, {16299,16301,16300 ,4496,4498,4497 ,0,0,0}, - {16288,16287,16304 ,4485,4484,4500 ,0,0,0}, {16305,16304,16306 ,4501,4500,4502 ,0,0,0}, - {16287,16306,16304 ,4484,4502,4500 ,0,0,0}, {16307,16308,16305 ,4503,4504,4501 ,0,0,0}, - {16305,16306,16307 ,4501,4502,4503 ,0,0,0}, {16308,16309,16310 ,4504,4505,4506 ,0,0,0}, - {16309,16308,16307 ,4505,4504,4503 ,0,0,0}, {16311,16310,16312 ,4507,4506,4508 ,0,0,0}, - {16309,16312,16310 ,4505,4508,4506 ,0,0,0}, {16313,16314,16311 ,4509,4510,4507 ,0,0,0}, - {16311,16312,16313 ,4507,4508,4509 ,0,0,0}, {16314,16315,16316 ,4510,4511,4512 ,0,0,0}, - {16315,16314,16313 ,4511,4510,4509 ,0,0,0}, {16315,16317,16316 ,4511,4513,4512 ,0,0,0}, - {16318,16319,16320 ,4514,4515,4516 ,0,0,0}, {16321,16322,16323 ,4517,4518,4519 ,0,0,0}, - {16322,16318,16320 ,4518,4514,4516 ,0,0,0}, {16324,16321,16323 ,4520,4517,4519 ,0,0,0}, - {16322,16321,16318 ,4518,4517,4514 ,0,0,0}, {16324,16323,16325 ,4520,4519,4521 ,0,0,0}, - {16325,16326,16327 ,4521,4522,4523 ,0,0,0}, {16328,16327,16326 ,4524,4523,4522 ,0,0,0}, - {16329,16330,16331 ,4525,4526,4527 ,0,0,0}, {16326,16332,16328 ,4522,4528,4524 ,0,0,0}, - {16331,16333,16334 ,4527,4529,4530 ,0,0,0}, {16333,16332,16334 ,4529,4528,4530 ,0,0,0}, - {16328,16332,16333 ,4524,4528,4529 ,0,0,0}, {16331,16334,16329 ,4527,4530,4525 ,0,0,0}, - {16330,16329,16335 ,4526,4525,4531 ,0,0,0}, {16330,16335,16336 ,4526,4531,4532 ,0,0,0}, - {16337,16336,16335 ,4533,4532,4531 ,0,0,0}, {16338,16339,16340 ,4534,4535,4536 ,0,0,0}, - {16340,16336,16337 ,4536,4532,4533 ,0,0,0}, {16338,16340,16337 ,4534,4536,4533 ,0,0,0}, - {16338,16341,16339 ,4534,4537,4535 ,0,0,0}, {16324,16325,16327 ,4520,4521,4523 ,0,0,0}, - {16320,16319,16342 ,4516,4515,4538 ,0,0,0}, {16343,16342,16344 ,4539,4538,4540 ,0,0,0}, - {16319,16344,16342 ,4515,4540,4538 ,0,0,0}, {16345,16346,16343 ,4541,4542,4539 ,0,0,0}, - {16343,16344,16345 ,4539,4540,4541 ,0,0,0}, {16346,16347,16348 ,4542,4543,4544 ,0,0,0}, - {16347,16346,16345 ,4543,4542,4541 ,0,0,0}, {16349,16348,16350 ,4545,4544,4546 ,0,0,0}, - {16347,16350,16348 ,4543,4546,4544 ,0,0,0}, {16351,16352,16349 ,4547,4548,4545 ,0,0,0}, - {16349,16350,16351 ,4545,4546,4547 ,0,0,0}, {16352,16353,16354 ,4548,4549,4550 ,0,0,0}, - {16353,16352,16351 ,4549,4548,4547 ,0,0,0}, {16355,16354,16356 ,4551,4550,4552 ,0,0,0}, - {16353,16356,16354 ,4549,4552,4550 ,0,0,0}, {16357,16358,16355 ,4553,4554,4551 ,0,0,0}, - {16355,16356,16357 ,4551,4552,4553 ,0,0,0}, {16358,16359,16360 ,4554,4555,4556 ,0,0,0}, - {16359,16358,16357 ,4555,4554,4553 ,0,0,0}, {16359,16361,16360 ,4555,126,4556 ,0,0,0}, - {16362,16363,16364 ,4557,4558,4559 ,0,0,0}, {16365,16366,16364 ,4560,4561,4559 ,0,0,0}, - {16362,16364,16366 ,4557,4559,4561 ,0,0,0}, {16367,16365,16368 ,4562,4560,4563 ,0,0,0}, - {16367,16366,16365 ,4562,4561,4560 ,0,0,0}, {16369,16368,16370 ,4564,4563,4565 ,0,0,0}, - {16365,16370,16368 ,4560,4565,4563 ,0,0,0}, {16371,16372,16369 ,4081,4566,4564 ,0,0,0}, - {16369,16370,16371 ,4564,4565,4081 ,0,0,0}, {16372,16373,16374 ,4566,4567,4568 ,0,0,0}, - {16373,16372,16371 ,4567,4566,4081 ,0,0,0}, {16375,16374,16376 ,4569,4568,4570 ,0,0,0}, - {16373,16376,16374 ,4567,4570,4568 ,0,0,0}, {16377,16378,16375 ,4571,4572,4569 ,0,0,0}, - {16375,16376,16377 ,4569,4570,4571 ,0,0,0}, {16379,16380,16378 ,4573,763,4572 ,0,0,0}, - {16379,16378,16377 ,4573,4572,4571 ,0,0,0}, {16380,16381,16378 ,763,763,4572 ,0,0,0}, - {16382,16363,16362 ,4574,4558,4557 ,0,0,0}, {16382,16383,16384 ,4574,4575,4576 ,0,0,0}, - {16384,16363,16382 ,4576,4558,4574 ,0,0,0}, {16385,16386,16383 ,4577,4578,4575 ,0,0,0}, - {16383,16386,16384 ,4575,4578,4576 ,0,0,0}, {16387,16388,16385 ,4579,4580,4577 ,0,0,0}, - {16385,16383,16387 ,4577,4575,4579 ,0,0,0}, {16388,16389,16390 ,4580,4065,4581 ,0,0,0}, - {16389,16388,16387 ,4065,4580,4579 ,0,0,0}, {16391,16390,16392 ,4582,4581,4583 ,0,0,0}, - {16389,16392,16390 ,4065,4583,4581 ,0,0,0}, {16393,16394,16391 ,4584,4585,4582 ,0,0,0}, - {16391,16392,16393 ,4582,4583,4584 ,0,0,0}, {16394,16395,16396 ,4585,4586,4587 ,0,0,0}, - {16395,16394,16393 ,4586,4585,4584 ,0,0,0}, {16396,16397,16398 ,4587,4588,54 ,0,0,0}, - {16395,16397,16396 ,4586,4588,4587 ,0,0,0}, {16396,16398,16399 ,4587,54,4589 ,0,0,0}, - {16400,16401,16402 ,4590,4591,4557 ,0,0,0}, {16403,16401,16404 ,4592,4591,4593 ,0,0,0}, - {16401,16403,16402 ,4591,4592,4557 ,0,0,0}, {16405,16406,16404 ,4594,4595,4593 ,0,0,0}, - {16403,16404,16406 ,4592,4593,4595 ,0,0,0}, {16405,16407,16408 ,4594,4596,4597 ,0,0,0}, - {16408,16406,16405 ,4597,4595,4594 ,0,0,0}, {16409,16407,16410 ,4598,4596,4599 ,0,0,0}, - {16407,16409,16408 ,4596,4598,4597 ,0,0,0}, {16411,16412,16410 ,4600,4601,4599 ,0,0,0}, - {16409,16410,16412 ,4598,4599,4601 ,0,0,0}, {16411,16413,16414 ,4600,4602,4603 ,0,0,0}, - {16414,16412,16411 ,4603,4601,4600 ,0,0,0}, {16415,16413,16416 ,4604,4602,4605 ,0,0,0}, - {16413,16415,16414 ,4602,4604,4603 ,0,0,0}, {16417,16418,16416 ,4606,4607,4605 ,0,0,0}, - {16415,16416,16418 ,4604,4605,4607 ,0,0,0}, {16417,16419,16420 ,4606,4608,4609 ,0,0,0}, - {16420,16418,16417 ,4609,4607,4606 ,0,0,0}, {16421,16419,16422 ,4610,4608,4611 ,0,0,0}, - {16419,16421,16420 ,4608,4610,4609 ,0,0,0}, {16423,16424,16422 ,4612,4613,4611 ,0,0,0}, - {16421,16422,16424 ,4610,4611,4613 ,0,0,0}, {16423,16425,16426 ,4612,4614,4615 ,0,0,0}, - {16426,16424,16423 ,4615,4613,4612 ,0,0,0}, {16427,16425,16428 ,4616,4614,4617 ,0,0,0}, - {16425,16427,16426 ,4614,4616,4615 ,0,0,0}, {16429,16430,16428 ,4618,4619,4617 ,0,0,0}, - {16427,16428,16430 ,4616,4617,4619 ,0,0,0}, {16429,16431,16432 ,4618,4620,4621 ,0,0,0}, - {16432,16430,16429 ,4621,4619,4618 ,0,0,0}, {16431,16433,16432 ,4620,4620,4621 ,0,0,0}, - {16434,16400,16402 ,4622,4590,4557 ,0,0,0}, {16435,16436,16434 ,4623,4624,4622 ,0,0,0}, - {16400,16434,16436 ,4590,4622,4624 ,0,0,0}, {16435,16437,16438 ,4623,4625,4626 ,0,0,0}, - {16438,16436,16435 ,4626,4624,4623 ,0,0,0}, {16439,16437,16440 ,4627,4625,4628 ,0,0,0}, - {16437,16439,16438 ,4625,4627,4626 ,0,0,0}, {16441,16442,16440 ,4629,4630,4628 ,0,0,0}, - {16439,16440,16442 ,4627,4628,4630 ,0,0,0}, {16441,16443,16444 ,4629,4631,4632 ,0,0,0}, - {16444,16442,16441 ,4632,4630,4629 ,0,0,0}, {16445,16443,16446 ,4633,4631,4634 ,0,0,0}, - {16443,16445,16444 ,4631,4633,4632 ,0,0,0}, {16447,16448,16446 ,4635,4636,4634 ,0,0,0}, - {16445,16446,16448 ,4633,4634,4636 ,0,0,0}, {16447,16449,16450 ,4635,4637,4638 ,0,0,0}, - {16450,16448,16447 ,4638,4636,4635 ,0,0,0}, {16451,16449,16452 ,4639,4637,4640 ,0,0,0}, - {16449,16451,16450 ,4637,4639,4638 ,0,0,0}, {16453,16454,16452 ,4641,4642,4640 ,0,0,0}, - {16451,16452,16454 ,4639,4640,4642 ,0,0,0}, {16453,16455,16456 ,4641,4643,4644 ,0,0,0}, - {16456,16454,16453 ,4644,4642,4641 ,0,0,0}, {16457,16455,16458 ,4645,4643,4646 ,0,0,0}, - {16455,16457,16456 ,4643,4645,4644 ,0,0,0}, {16459,16460,16458 ,4647,4648,4646 ,0,0,0}, - {16457,16458,16460 ,4645,4646,4648 ,0,0,0}, {16459,16461,16462 ,4647,4649,4650 ,0,0,0}, - {16462,16460,16459 ,4650,4648,4647 ,0,0,0}, {16463,16461,16464 ,4651,4649,82 ,0,0,0}, - {16461,16463,16462 ,4649,4651,4650 ,0,0,0}, {16463,16464,16465 ,4651,82,4652 ,0,0,0}, - {16466,16467,16468 ,4653,4654,4655 ,0,0,0}, {16469,16470,16471 ,4656,4657,4658 ,0,0,0}, - {16468,16471,16470 ,4655,4658,4657 ,0,0,0}, {16472,16473,16474 ,4659,4660,4661 ,0,0,0}, - {16475,16476,16469 ,4662,4663,4656 ,0,0,0}, {16472,16476,16475 ,4659,4663,4662 ,0,0,0}, - {16475,16473,16472 ,4662,4660,4659 ,0,0,0}, {16476,16470,16469 ,4663,4657,4656 ,0,0,0}, - {16477,16478,16479 ,4664,4665,4666 ,0,0,0}, {16478,16480,16479 ,4665,4667,4666 ,0,0,0}, - {16481,16482,16483 ,4668,4669,4670 ,0,0,0}, {16481,16483,16480 ,4668,4670,4667 ,0,0,0}, - {16478,16481,16480 ,4665,4668,4667 ,0,0,0}, {16473,16477,16474 ,4660,4664,4661 ,0,0,0}, - {16477,16479,16474 ,4664,4666,4661 ,0,0,0}, {16484,16485,16486 ,4671,4672,4673 ,0,0,0}, - {16487,16488,16489 ,4674,4675,4676 ,0,0,0}, {16486,16485,16487 ,4673,4672,4674 ,0,0,0}, - {16490,16491,16492 ,4677,4678,4679 ,0,0,0}, {16486,16487,16489 ,4673,4674,4676 ,0,0,0}, - {16492,16491,16488 ,4679,4678,4675 ,0,0,0}, {16491,16489,16488 ,4678,4676,4675 ,0,0,0}, - {16482,16485,16484 ,4669,4672,4671 ,0,0,0}, {16493,16490,16492 ,4677,4677,4679 ,0,0,0}, - {16483,16482,16484 ,4670,4669,4671 ,0,0,0}, {16467,16471,16468 ,4654,4658,4655 ,0,0,0}, - {16494,16467,16466 ,4680,4654,4653 ,0,0,0}, {16494,16495,16496 ,4680,4681,4682 ,0,0,0}, - {16495,16494,16466 ,4681,4680,4653 ,0,0,0}, {16497,16496,16498 ,4683,4682,4684 ,0,0,0}, - {16495,16498,16496 ,4681,4684,4682 ,0,0,0}, {16499,16500,16497 ,4685,4686,4683 ,0,0,0}, - {16497,16498,16499 ,4683,4684,4685 ,0,0,0}, {16500,16501,16502 ,4686,4687,4688 ,0,0,0}, - {16501,16500,16499 ,4687,4686,4685 ,0,0,0}, {16503,16502,16504 ,4689,4688,4690 ,0,0,0}, - {16501,16504,16502 ,4687,4690,4688 ,0,0,0}, {16505,16506,16503 ,4691,4692,4689 ,0,0,0}, - {16503,16504,16505 ,4689,4690,4691 ,0,0,0}, {16506,16507,16508 ,4692,4693,4694 ,0,0,0}, - {16507,16506,16505 ,4693,4692,4691 ,0,0,0}, {16509,16508,16510 ,4695,4694,4696 ,0,0,0}, - {16507,16510,16508 ,4693,4696,4694 ,0,0,0}, {16511,16512,16509 ,4697,4698,4695 ,0,0,0}, - {16509,16510,16511 ,4695,4696,4697 ,0,0,0}, {16512,16513,16514 ,4698,4699,4700 ,0,0,0}, - {16513,16512,16511 ,4699,4698,4697 ,0,0,0}, {16513,16515,16514 ,4699,4701,4700 ,0,0,0}, - {16516,16517,16518 ,4702,4703,4704 ,0,0,0}, {16519,16520,16521 ,4705,4706,4707 ,0,0,0}, - {16517,16521,16520 ,4703,4707,4706 ,0,0,0}, {16522,16523,16524 ,4708,4709,4710 ,0,0,0}, - {16525,16519,16526 ,4711,4705,4712 ,0,0,0}, {16522,16525,16526 ,4708,4711,4712 ,0,0,0}, - {16525,16522,16524 ,4711,4708,4710 ,0,0,0}, {16526,16519,16521 ,4712,4705,4707 ,0,0,0}, - {16527,16528,16529 ,4713,4714,4715 ,0,0,0}, {16529,16528,16530 ,4715,4714,4716 ,0,0,0}, - {16531,16532,16533 ,4717,4718,4719 ,0,0,0}, {16531,16530,16532 ,4717,4716,4718 ,0,0,0}, - {16529,16530,16531 ,4715,4716,4717 ,0,0,0}, {16524,16523,16527 ,4710,4709,4713 ,0,0,0}, - {16527,16523,16528 ,4713,4709,4714 ,0,0,0}, {16534,16535,16536 ,4720,4721,4722 ,0,0,0}, - {16537,16538,16539 ,4723,4724,4725 ,0,0,0}, {16535,16537,16536 ,4721,4723,4722 ,0,0,0}, - {16540,16541,16542 ,4726,4727,4728 ,0,0,0}, {16535,16538,16537 ,4721,4724,4723 ,0,0,0}, - {16541,16539,16542 ,4727,4725,4728 ,0,0,0}, {16542,16539,16538 ,4728,4725,4724 ,0,0,0}, - {16533,16534,16536 ,4719,4720,4722 ,0,0,0}, {16543,16541,16540 ,4726,4727,4726 ,0,0,0}, - {16532,16534,16533 ,4718,4720,4719 ,0,0,0}, {16518,16517,16520 ,4704,4703,4706 ,0,0,0}, - {16544,16516,16518 ,4729,4702,4704 ,0,0,0}, {16544,16545,16546 ,4729,4730,4731 ,0,0,0}, - {16546,16516,16544 ,4731,4702,4729 ,0,0,0}, {16547,16548,16545 ,4732,4733,4730 ,0,0,0}, - {16546,16545,16548 ,4731,4730,4733 ,0,0,0}, {16549,16547,16550 ,4734,4732,4735 ,0,0,0}, - {16547,16549,16548 ,4732,4734,4733 ,0,0,0}, {16550,16551,16552 ,4735,4736,4737 ,0,0,0}, - {16552,16549,16550 ,4737,4734,4735 ,0,0,0}, {16553,16554,16551 ,4738,4739,4736 ,0,0,0}, - {16552,16551,16554 ,4737,4736,4739 ,0,0,0}, {16555,16553,16556 ,4740,4738,4741 ,0,0,0}, - {16553,16555,16554 ,4738,4740,4739 ,0,0,0}, {16556,16557,16558 ,4741,4742,4743 ,0,0,0}, - {16558,16555,16556 ,4743,4740,4741 ,0,0,0}, {16559,16560,16557 ,4744,4745,4742 ,0,0,0}, - {16558,16557,16560 ,4743,4742,4745 ,0,0,0}, {16561,16559,16562 ,4746,4744,4747 ,0,0,0}, - {16559,16561,16560 ,4744,4746,4745 ,0,0,0}, {16562,16563,16564 ,4747,4748,4749 ,0,0,0}, - {16564,16561,16562 ,4749,4746,4747 ,0,0,0}, {16564,16563,16565 ,4749,4748,4750 ,0,0,0}, - {16566,16567,16568 ,4751,4752,4753 ,0,0,0}, {16569,16570,16571 ,4754,4755,4756 ,0,0,0}, - {16567,16571,16570 ,4752,4756,4755 ,0,0,0}, {16572,16573,16574 ,4757,4758,4759 ,0,0,0}, - {16575,16569,16576 ,4760,4754,4761 ,0,0,0}, {16575,16576,16572 ,4760,4761,4757 ,0,0,0}, - {16572,16574,16575 ,4757,4759,4760 ,0,0,0}, {16569,16571,16576 ,4754,4756,4761 ,0,0,0}, - {16577,16578,16579 ,4762,4763,4764 ,0,0,0}, {16580,16578,16577 ,4765,4763,4762 ,0,0,0}, - {16581,16582,16583 ,4766,4767,4768 ,0,0,0}, {16581,16583,16580 ,4766,4768,4765 ,0,0,0}, - {16580,16583,16578 ,4765,4768,4763 ,0,0,0}, {16573,16579,16574 ,4758,4764,4759 ,0,0,0}, - {16577,16579,16573 ,4762,4764,4758 ,0,0,0}, {16584,16585,16586 ,4769,4770,4771 ,0,0,0}, - {16587,16588,16589 ,4772,4773,4774 ,0,0,0}, {16586,16585,16589 ,4771,4770,4774 ,0,0,0}, - {16590,16591,16592 ,4775,4776,4777 ,0,0,0}, {16585,16587,16589 ,4770,4772,4774 ,0,0,0}, - {16590,16588,16591 ,4775,4773,4776 ,0,0,0}, {16588,16587,16591 ,4773,4772,4776 ,0,0,0}, - {16584,16586,16582 ,4769,4771,4767 ,0,0,0}, {16593,16590,16592 ,4777,4775,4777 ,0,0,0}, - {16581,16584,16582 ,4766,4769,4767 ,0,0,0}, {16567,16570,16568 ,4752,4755,4753 ,0,0,0}, - {16566,16568,16594 ,4751,4753,4778 ,0,0,0}, {16594,16595,16596 ,4778,4779,4780 ,0,0,0}, - {16596,16566,16594 ,4780,4751,4778 ,0,0,0}, {16597,16595,16598 ,4781,4779,4782 ,0,0,0}, - {16595,16597,16596 ,4779,4781,4780 ,0,0,0}, {16599,16600,16598 ,4783,4784,4782 ,0,0,0}, - {16597,16598,16600 ,4781,4782,4784 ,0,0,0}, {16599,16601,16602 ,4783,4785,4786 ,0,0,0}, - {16602,16600,16599 ,4786,4784,4783 ,0,0,0}, {16603,16601,16604 ,4787,4785,4788 ,0,0,0}, - {16601,16603,16602 ,4785,4787,4786 ,0,0,0}, {16605,16606,16604 ,4789,4790,4788 ,0,0,0}, - {16603,16604,16606 ,4787,4788,4790 ,0,0,0}, {16605,16607,16608 ,4789,4791,4792 ,0,0,0}, - {16608,16606,16605 ,4792,4790,4789 ,0,0,0}, {16609,16607,16610 ,4793,4791,4794 ,0,0,0}, - {16607,16609,16608 ,4791,4793,4792 ,0,0,0}, {16611,16612,16610 ,4795,4796,4794 ,0,0,0}, - {16609,16610,16612 ,4793,4794,4796 ,0,0,0}, {16611,16613,16614 ,4795,4797,4798 ,0,0,0}, - {16614,16612,16611 ,4798,4796,4795 ,0,0,0}, {16613,16615,16614 ,4797,4799,4798 ,0,0,0}, - {16613,16616,16615 ,4797,324,4799 ,0,0,0}, {16617,16618,16619 ,82,4800,4801 ,0,0,0}, - {16619,16620,16621 ,4801,4802,4803 ,0,0,0}, {16620,16622,16621 ,4802,4804,4803 ,0,0,0}, - {16619,16621,16617 ,4801,4803,82 ,0,0,0}, {16623,16624,16625 ,4805,4806,4807 ,0,0,0}, - {16625,16624,16622 ,4807,4806,4804 ,0,0,0}, {16623,16626,16627 ,4805,4808,4809 ,0,0,0}, - {16627,16624,16623 ,4809,4806,4805 ,0,0,0}, {16627,16626,16628 ,4809,4808,4810 ,0,0,0}, - {16628,16626,16629 ,4810,4808,4811 ,0,0,0}, {16629,16630,16631 ,4811,4812,4813 ,0,0,0}, - {16628,16629,16631 ,4810,4811,4813 ,0,0,0}, {16622,16620,16625 ,4804,4802,4807 ,0,0,0}, - {16632,16633,16634 ,4814,4815,4816 ,0,0,0}, {16632,16634,16630 ,4814,4816,4812 ,0,0,0}, - {16630,16634,16631 ,4812,4816,4813 ,0,0,0}, {16617,16635,16618 ,82,4817,4800 ,0,0,0}, - {16636,16635,16637 ,4818,4817,4819 ,0,0,0}, {16635,16636,16618 ,4817,4818,4800 ,0,0,0}, - {16638,16639,16637 ,4820,4821,4819 ,0,0,0}, {16636,16637,16639 ,4818,4819,4821 ,0,0,0}, - {16638,16640,16641 ,4820,4822,4823 ,0,0,0}, {16641,16639,16638 ,4823,4821,4820 ,0,0,0}, - {16642,16640,16643 ,4824,4822,4825 ,0,0,0}, {16640,16642,16641 ,4822,4824,4823 ,0,0,0}, - {16644,16645,16643 ,4826,4827,4825 ,0,0,0}, {16642,16643,16645 ,4824,4825,4827 ,0,0,0}, - {16644,16646,16647 ,4826,4828,4829 ,0,0,0}, {16647,16645,16644 ,4829,4827,4826 ,0,0,0}, - {16648,16646,16649 ,4830,4828,4831 ,0,0,0}, {16646,16648,16647 ,4828,4830,4829 ,0,0,0}, - {16644,16643,16650 ,4832,4833,4834 ,0,0,0}, {16650,16646,16644 ,4834,4835,4832 ,0,0,0}, - {16650,16649,16646 ,4834,4836,4835 ,0,0,0}, {16650,16640,16638 ,4834,4837,4838 ,0,0,0}, - {16643,16640,16650 ,4833,4837,4834 ,0,0,0}, {16650,16637,16635 ,4834,4839,4840 ,0,0,0}, - {16638,16637,16650 ,4838,4839,4834 ,0,0,0}, {16635,16617,16650 ,4840,4841,4834 ,0,0,0}, - {16622,16650,16621 ,4842,4834,4843 ,0,0,0}, {16650,16617,16621 ,4834,4841,4843 ,0,0,0}, - {16627,16650,16624 ,4844,4834,4845 ,0,0,0}, {16650,16622,16624 ,4834,4842,4845 ,0,0,0}, - {16631,16650,16628 ,4846,4834,4847 ,0,0,0}, {16650,16627,16628 ,4834,4844,4847 ,0,0,0}, - {16633,16650,16634 ,4848,4834,4849 ,0,0,0}, {16650,16631,16634 ,4834,4846,4849 ,0,0,0}, - {16651,16652,16653 ,82,4850,4851 ,0,0,0}, {16653,16654,16655 ,4851,4852,4853 ,0,0,0}, - {16654,16656,16655 ,4852,4854,4853 ,0,0,0}, {16653,16655,16651 ,4851,4853,82 ,0,0,0}, - {16657,16658,16659 ,4855,4856,4857 ,0,0,0}, {16659,16658,16656 ,4857,4856,4854 ,0,0,0}, - {16657,16660,16661 ,4855,4858,4859 ,0,0,0}, {16661,16658,16657 ,4859,4856,4855 ,0,0,0}, - {16661,16660,16662 ,4859,4858,4860 ,0,0,0}, {16662,16660,16663 ,4860,4858,4861 ,0,0,0}, - {16663,16664,16665 ,4861,4862,4863 ,0,0,0}, {16662,16663,16665 ,4860,4861,4863 ,0,0,0}, - {16656,16654,16659 ,4854,4852,4857 ,0,0,0}, {16666,16667,16668 ,4864,4865,4866 ,0,0,0}, - {16666,16668,16664 ,4864,4866,4862 ,0,0,0}, {16664,16668,16665 ,4862,4866,4863 ,0,0,0}, - {16651,16669,16652 ,82,4867,4850 ,0,0,0}, {16670,16669,16671 ,4868,4867,4869 ,0,0,0}, - {16669,16670,16652 ,4867,4868,4850 ,0,0,0}, {16672,16673,16671 ,4870,4871,4869 ,0,0,0}, - {16670,16671,16673 ,4868,4869,4871 ,0,0,0}, {16672,16674,16675 ,4870,4872,4873 ,0,0,0}, - {16675,16673,16672 ,4873,4871,4870 ,0,0,0}, {16676,16674,16677 ,4874,4872,4875 ,0,0,0}, - {16674,16676,16675 ,4872,4874,4873 ,0,0,0}, {16678,16679,16677 ,4876,4877,4875 ,0,0,0}, - {16676,16677,16679 ,4874,4875,4877 ,0,0,0}, {16678,16680,16681 ,4876,4878,4829 ,0,0,0}, - {16681,16679,16678 ,4829,4877,4876 ,0,0,0}, {16682,16680,16683 ,4879,4878,4831 ,0,0,0}, - {16680,16682,16681 ,4878,4879,4829 ,0,0,0}, {16678,16677,16684 ,4832,4833,4880 ,0,0,0}, - {16684,16680,16678 ,4880,4835,4832 ,0,0,0}, {16684,16683,16680 ,4880,4881,4835 ,0,0,0}, - {16684,16674,16672 ,4880,4837,4838 ,0,0,0}, {16677,16674,16684 ,4833,4837,4880 ,0,0,0}, - {16684,16671,16669 ,4880,4839,4840 ,0,0,0}, {16672,16671,16684 ,4838,4839,4880 ,0,0,0}, - {16669,16651,16684 ,4840,4882,4880 ,0,0,0}, {16656,16684,16655 ,4842,4880,4843 ,0,0,0}, - {16684,16651,16655 ,4880,4882,4843 ,0,0,0}, {16661,16684,16658 ,4844,4880,4845 ,0,0,0}, - {16684,16656,16658 ,4880,4842,4845 ,0,0,0}, {16665,16684,16662 ,4846,4880,4847 ,0,0,0}, - {16684,16661,16662 ,4880,4844,4847 ,0,0,0}, {16667,16684,16668 ,4883,4880,4849 ,0,0,0}, - {16684,16665,16668 ,4880,4846,4849 ,0,0,0}, {16685,16686,16687 ,4884,4885,4886 ,0,0,0}, - {16687,16688,16689 ,4886,4887,4888 ,0,0,0}, {16688,16690,16689 ,4887,4889,4888 ,0,0,0}, - {16687,16689,16685 ,4886,4888,4884 ,0,0,0}, {16691,16692,16693 ,4890,4891,4857 ,0,0,0}, - {16693,16692,16690 ,4857,4891,4889 ,0,0,0}, {16691,16694,16695 ,4890,4892,4893 ,0,0,0}, - {16695,16692,16691 ,4893,4891,4890 ,0,0,0}, {16695,16694,16696 ,4893,4892,4894 ,0,0,0}, - {16696,16694,16697 ,4894,4892,4895 ,0,0,0}, {16697,16698,16699 ,4895,4896,4897 ,0,0,0}, - {16696,16697,16699 ,4894,4895,4897 ,0,0,0}, {16690,16688,16693 ,4889,4887,4857 ,0,0,0}, - {16700,16701,16702 ,4898,4899,4900 ,0,0,0}, {16700,16702,16698 ,4898,4900,4896 ,0,0,0}, - {16698,16702,16699 ,4896,4900,4897 ,0,0,0}, {16685,16703,16686 ,4884,4901,4885 ,0,0,0}, - {16704,16703,16705 ,4868,4901,4902 ,0,0,0}, {16703,16704,16686 ,4901,4868,4885 ,0,0,0}, - {16706,16707,16705 ,4820,4903,4902 ,0,0,0}, {16704,16705,16707 ,4868,4902,4903 ,0,0,0}, - {16706,16708,16709 ,4820,4904,4905 ,0,0,0}, {16709,16707,16706 ,4905,4903,4820 ,0,0,0}, - {16710,16708,16711 ,4906,4904,4907 ,0,0,0}, {16708,16710,16709 ,4904,4906,4905 ,0,0,0}, - {16712,16713,16711 ,4826,4877,4907 ,0,0,0}, {16710,16711,16713 ,4906,4907,4877 ,0,0,0}, - {16712,16714,16715 ,4826,4828,4908 ,0,0,0}, {16715,16713,16712 ,4908,4877,4826 ,0,0,0}, - {16716,16714,16717 ,4909,4828,4910 ,0,0,0}, {16714,16716,16715 ,4828,4909,4908 ,0,0,0}, - {16712,16711,16718 ,4832,4833,4880 ,0,0,0}, {16718,16714,16712 ,4880,4835,4832 ,0,0,0}, - {16718,16717,16714 ,4880,4911,4835 ,0,0,0}, {16718,16708,16706 ,4880,4837,4838 ,0,0,0}, - {16711,16708,16718 ,4833,4837,4880 ,0,0,0}, {16718,16705,16703 ,4880,4839,4840 ,0,0,0}, - {16706,16705,16718 ,4838,4839,4880 ,0,0,0}, {16703,16685,16718 ,4840,4912,4880 ,0,0,0}, - {16690,16718,16689 ,4842,4880,4843 ,0,0,0}, {16718,16685,16689 ,4880,4912,4843 ,0,0,0}, - {16695,16718,16692 ,4844,4880,4845 ,0,0,0}, {16718,16690,16692 ,4880,4842,4845 ,0,0,0}, - {16699,16718,16696 ,4846,4880,4847 ,0,0,0}, {16718,16695,16696 ,4880,4844,4847 ,0,0,0}, - {16701,16718,16702 ,4913,4880,4849 ,0,0,0}, {16718,16699,16702 ,4880,4846,4849 ,0,0,0}, - {16719,16720,16721 ,4914,4915,4916 ,0,0,0}, {16721,16722,16723 ,4916,4917,4918 ,0,0,0}, - {16722,16724,16723 ,4917,4919,4918 ,0,0,0}, {16721,16723,16719 ,4916,4918,4914 ,0,0,0}, - {16725,16726,16727 ,4920,4921,4922 ,0,0,0}, {16727,16726,16724 ,4922,4921,4919 ,0,0,0}, - {16725,16728,16729 ,4920,4923,4924 ,0,0,0}, {16729,16726,16725 ,4924,4921,4920 ,0,0,0}, - {16729,16728,16730 ,4924,4923,4925 ,0,0,0}, {16730,16728,16731 ,4925,4923,4926 ,0,0,0}, - {16731,16732,16733 ,4926,4927,4928 ,0,0,0}, {16730,16731,16733 ,4925,4926,4928 ,0,0,0}, - {16724,16722,16727 ,4919,4917,4922 ,0,0,0}, {16734,16735,16736 ,4929,4815,4930 ,0,0,0}, - {16734,16736,16732 ,4929,4930,4927 ,0,0,0}, {16732,16736,16733 ,4927,4930,4928 ,0,0,0}, - {16719,16737,16720 ,4914,4931,4915 ,0,0,0}, {16738,16737,16739 ,4932,4931,4933 ,0,0,0}, - {16737,16738,16720 ,4931,4932,4915 ,0,0,0}, {16740,16741,16739 ,4934,4821,4933 ,0,0,0}, - {16738,16739,16741 ,4932,4933,4821 ,0,0,0}, {16740,16742,16743 ,4934,4935,4936 ,0,0,0}, - {16743,16741,16740 ,4936,4821,4934 ,0,0,0}, {16744,16742,16745 ,4937,4935,4938 ,0,0,0}, - {16742,16744,16743 ,4935,4937,4936 ,0,0,0}, {16746,16747,16745 ,4826,4877,4938 ,0,0,0}, - {16744,16745,16747 ,4937,4938,4877 ,0,0,0}, {16746,16748,16749 ,4826,4939,4940 ,0,0,0}, - {16749,16747,16746 ,4940,4877,4826 ,0,0,0}, {16750,16748,16751 ,4941,4939,4942 ,0,0,0}, - {16748,16750,16749 ,4939,4941,4940 ,0,0,0}, {16746,16745,16752 ,4832,4833,4943 ,0,0,0}, - {16752,16748,16746 ,4943,4835,4832 ,0,0,0}, {16752,16751,16748 ,4943,4944,4835 ,0,0,0}, - {16752,16742,16740 ,4943,4837,4838 ,0,0,0}, {16745,16742,16752 ,4833,4837,4943 ,0,0,0}, - {16752,16739,16737 ,4943,4839,4840 ,0,0,0}, {16740,16739,16752 ,4838,4839,4943 ,0,0,0}, - {16737,16719,16752 ,4840,4945,4943 ,0,0,0}, {16724,16752,16723 ,4842,4943,4843 ,0,0,0}, - {16752,16719,16723 ,4943,4945,4843 ,0,0,0}, {16729,16752,16726 ,4844,4943,4845 ,0,0,0}, - {16752,16724,16726 ,4943,4842,4845 ,0,0,0}, {16733,16752,16730 ,4846,4943,4847 ,0,0,0}, - {16752,16729,16730 ,4943,4844,4847 ,0,0,0}, {16735,16752,16736 ,4946,4943,4849 ,0,0,0}, - {16752,16733,16736 ,4943,4846,4849 ,0,0,0}, {16753,16754,16755 ,4947,4948,4949 ,0,0,0}, - {16756,16757,16758 ,4950,4951,4952 ,0,0,0}, {16755,16758,16757 ,4949,4952,4951 ,0,0,0}, - {16759,16760,16761 ,4953,4954,4955 ,0,0,0}, {16762,16763,16756 ,4956,4957,4950 ,0,0,0}, - {16759,16763,16762 ,4953,4957,4956 ,0,0,0}, {16762,16760,16759 ,4956,4954,4953 ,0,0,0}, - {16763,16757,16756 ,4957,4951,4950 ,0,0,0}, {16764,16765,16766 ,4958,4959,4960 ,0,0,0}, - {16765,16767,16766 ,4959,4961,4960 ,0,0,0}, {16768,16769,16770 ,4962,4963,4964 ,0,0,0}, - {16768,16770,16767 ,4962,4964,4961 ,0,0,0}, {16765,16768,16767 ,4959,4962,4961 ,0,0,0}, - {16760,16764,16761 ,4954,4958,4955 ,0,0,0}, {16764,16766,16761 ,4958,4960,4955 ,0,0,0}, - {16771,16772,16773 ,4965,4966,4967 ,0,0,0}, {16774,16775,16776 ,4968,4969,4970 ,0,0,0}, - {16773,16772,16774 ,4967,4966,4968 ,0,0,0}, {16777,16778,16779 ,4726,4971,4972 ,0,0,0}, - {16773,16774,16776 ,4967,4968,4970 ,0,0,0}, {16779,16778,16775 ,4972,4971,4969 ,0,0,0}, - {16778,16776,16775 ,4971,4970,4969 ,0,0,0}, {16769,16772,16771 ,4963,4966,4965 ,0,0,0}, - {16780,16777,16779 ,4726,4726,4972 ,0,0,0}, {16770,16769,16771 ,4964,4963,4965 ,0,0,0}, - {16754,16758,16755 ,4948,4952,4949 ,0,0,0}, {16781,16754,16753 ,4973,4948,4947 ,0,0,0}, - {16781,16782,16783 ,4973,4974,4975 ,0,0,0}, {16782,16781,16753 ,4974,4973,4947 ,0,0,0}, - {16784,16783,16785 ,4976,4975,4977 ,0,0,0}, {16782,16785,16783 ,4974,4977,4975 ,0,0,0}, - {16786,16787,16784 ,4978,4979,4976 ,0,0,0}, {16784,16785,16786 ,4976,4977,4978 ,0,0,0}, - {16787,16788,16789 ,4979,4980,4981 ,0,0,0}, {16788,16787,16786 ,4980,4979,4978 ,0,0,0}, - {16790,16789,16791 ,4982,4981,4983 ,0,0,0}, {16788,16791,16789 ,4980,4983,4981 ,0,0,0}, - {16792,16793,16790 ,4984,4985,4982 ,0,0,0}, {16790,16791,16792 ,4982,4983,4984 ,0,0,0}, - {16793,16794,16795 ,4985,4986,4987 ,0,0,0}, {16794,16793,16792 ,4986,4985,4984 ,0,0,0}, - {16796,16795,16797 ,4988,4987,4989 ,0,0,0}, {16794,16797,16795 ,4986,4989,4987 ,0,0,0}, - {16798,16799,16796 ,4990,4991,4988 ,0,0,0}, {16796,16797,16798 ,4988,4989,4990 ,0,0,0}, - {16799,16800,16801 ,4991,4992,4748 ,0,0,0}, {16800,16799,16798 ,4992,4991,4990 ,0,0,0}, - {16800,16802,16801 ,4992,4750,4748 ,0,0,0}, {16803,16804,16805 ,4993,4994,4995 ,0,0,0}, - {16806,16807,16808 ,4996,4997,4998 ,0,0,0}, {16804,16809,16810 ,4994,4999,5000 ,0,0,0}, - {16809,16804,16803 ,4999,4994,4993 ,0,0,0}, {16809,16811,16810 ,4999,5001,5000 ,0,0,0}, - {16805,16812,16803 ,4995,5002,4993 ,0,0,0}, {16806,16812,16813 ,4996,5002,5003 ,0,0,0}, - {16805,16813,16812 ,4995,5003,5002 ,0,0,0}, {16814,16815,16816 ,5004,5005,5006 ,0,0,0}, - {16806,16813,16807 ,4996,5003,4997 ,0,0,0}, {16817,16818,16819 ,5007,5008,5009 ,0,0,0}, - {16820,16821,16822 ,5010,5011,5012 ,0,0,0}, {16823,16824,16825 ,5013,5014,5015 ,0,0,0}, - {16826,16827,16828 ,5016,5017,5018 ,0,0,0}, {16829,16830,16831 ,5019,5020,5021 ,0,0,0}, - {16832,16833,16824 ,5022,5023,5014 ,0,0,0}, {16834,16835,16836 ,5024,5025,5026 ,0,0,0}, - {16835,16830,16837 ,5025,5020,5027 ,0,0,0}, {16838,16839,16840 ,5028,5029,5030 ,0,0,0}, - {16841,16842,16834 ,5031,5032,5024 ,0,0,0}, {16843,16844,16845 ,5033,5034,5035 ,0,0,0}, - {16846,16840,16847 ,5036,5030,5037 ,0,0,0}, {16848,16849,16850 ,5038,5039,5040 ,0,0,0}, - {16851,16849,16852 ,5041,5039,5042 ,0,0,0}, {16853,16854,16855 ,5043,5044,5045 ,0,0,0}, - {16850,16856,16853 ,5040,5046,5043 ,0,0,0}, {16857,16858,16859 ,5047,5048,5049 ,0,0,0}, - {16857,16860,16861 ,5047,5050,5051 ,0,0,0}, {16862,16863,16864 ,5052,5053,5054 ,0,0,0}, - {16865,16866,16864 ,5055,5056,5054 ,0,0,0}, {16867,16868,16869 ,5057,5058,5059 ,0,0,0}, - {16868,16862,16870 ,5058,5052,5060 ,0,0,0}, {16871,16872,16873 ,5061,5062,5063 ,0,0,0}, - {16867,16874,16871 ,5057,5064,5061 ,0,0,0}, {16875,16876,16877 ,5065,5066,5067 ,0,0,0}, - {16875,16878,16879 ,5065,5068,5069 ,0,0,0}, {16880,16881,16882 ,5070,5071,5072 ,0,0,0}, - {16880,16883,16876 ,5070,5073,5066 ,0,0,0}, {16884,16881,16885 ,5074,5071,5075 ,0,0,0}, - {16881,16884,16882 ,5071,5074,5072 ,0,0,0}, {16886,16887,16885 ,5076,5077,5075 ,0,0,0}, - {16884,16885,16887 ,5074,5075,5077 ,0,0,0}, {16888,16889,16887 ,5078,5079,5077 ,0,0,0}, - {16887,16886,16888 ,5077,5076,5078 ,0,0,0}, {16889,16890,16891 ,5079,5080,5081 ,0,0,0}, - {16890,16889,16888 ,5080,5079,5078 ,0,0,0}, {16892,16891,16893 ,5082,5081,5083 ,0,0,0}, - {16890,16893,16891 ,5080,5083,5081 ,0,0,0}, {16894,16895,16892 ,5084,5085,5082 ,0,0,0}, - {16892,16893,16894 ,5082,5083,5084 ,0,0,0}, {16895,16896,16897 ,5085,5086,5087 ,0,0,0}, - {16896,16895,16894 ,5086,5085,5084 ,0,0,0}, {16898,16897,16899 ,5088,5087,5089 ,0,0,0}, - {16896,16899,16897 ,5086,5089,5087 ,0,0,0}, {16900,16898,16901 ,5090,5088,5091 ,0,0,0}, - {16898,16899,16901 ,5088,5089,5091 ,0,0,0}, {16900,16902,16903 ,5090,5092,5093 ,0,0,0}, - {16903,16898,16900 ,5093,5088,5090 ,0,0,0}, {16904,16902,16905 ,5094,5092,5095 ,0,0,0}, - {16902,16904,16903 ,5092,5094,5093 ,0,0,0}, {16906,16907,16905 ,126,5096,5095 ,0,0,0}, - {16904,16905,16907 ,5094,5095,5096 ,0,0,0}, {16908,16907,16906 ,126,5096,126 ,0,0,0}, - {16877,16876,16883 ,5067,5066,5073 ,0,0,0}, {16880,16882,16883 ,5070,5072,5073 ,0,0,0}, - {16873,16878,16871 ,5063,5068,5061 ,0,0,0}, {16875,16877,16878 ,5065,5067,5068 ,0,0,0}, - {16873,16879,16878 ,5063,5069,5068 ,0,0,0}, {16869,16874,16867 ,5059,5064,5057 ,0,0,0}, - {16871,16874,16872 ,5061,5064,5062 ,0,0,0}, {16863,16862,16868 ,5053,5052,5058 ,0,0,0}, - {16868,16870,16869 ,5058,5060,5059 ,0,0,0}, {16865,16858,16866 ,5055,5048,5056 ,0,0,0}, - {16863,16865,16864 ,5053,5055,5054 ,0,0,0}, {16857,16859,16860 ,5047,5049,5050 ,0,0,0}, - {16858,16865,16859 ,5048,5055,5049 ,0,0,0}, {16854,16861,16855 ,5044,5051,5045 ,0,0,0}, - {16861,16860,16855 ,5051,5050,5045 ,0,0,0}, {16850,16853,16848 ,5040,5043,5038 ,0,0,0}, - {16856,16854,16853 ,5046,5044,5043 ,0,0,0}, {16843,16851,16844 ,5033,5041,5034 ,0,0,0}, - {16852,16849,16848 ,5042,5039,5038 ,0,0,0}, {16844,16851,16852 ,5034,5041,5042 ,0,0,0}, - {16845,16846,16847 ,5035,5036,5037 ,0,0,0}, {16844,16846,16845 ,5034,5036,5035 ,0,0,0}, - {16840,16842,16838 ,5030,5032,5028 ,0,0,0}, {16847,16840,16839 ,5037,5030,5029 ,0,0,0}, - {16909,16841,16834 ,5097,5031,5024 ,0,0,0}, {16841,16838,16842 ,5031,5028,5032 ,0,0,0}, - {16910,16835,16837 ,5098,5025,5027 ,0,0,0}, {16834,16836,16909 ,5024,5026,5097 ,0,0,0}, - {16835,16910,16836 ,5025,5098,5026 ,0,0,0}, {16831,16832,16829 ,5021,5022,5019 ,0,0,0}, - {16837,16830,16829 ,5027,5020,5019 ,0,0,0}, {16825,16828,16823 ,5015,5018,5013 ,0,0,0}, - {16832,16831,16833 ,5022,5021,5023 ,0,0,0}, {16824,16833,16825 ,5014,5023,5015 ,0,0,0}, - {16817,16826,16828 ,5007,5016,5018 ,0,0,0}, {16827,16823,16828 ,5017,5013,5018 ,0,0,0}, - {16818,16822,16819 ,5008,5012,5009 ,0,0,0}, {16817,16819,16826 ,5007,5009,5016 ,0,0,0}, - {16820,16814,16821 ,5010,5004,5011 ,0,0,0}, {16818,16820,16822 ,5008,5010,5012 ,0,0,0}, - {16816,16815,16808 ,5006,5005,4998 ,0,0,0}, {16821,16814,16816 ,5011,5004,5006 ,0,0,0}, - {16806,16808,16815 ,4996,4998,5005 ,0,0,0}, {16911,16912,16913 ,5099,5100,5101 ,0,0,0}, - {16914,16915,16916 ,5102,5103,5104 ,0,0,0}, {16917,16915,16914 ,5105,5103,5102 ,0,0,0}, - {16918,16914,16916 ,5106,5102,5104 ,0,0,0}, {16919,16920,16921 ,5107,5108,5109 ,0,0,0}, - {16922,16923,16918 ,5110,5108,5106 ,0,0,0}, {16920,16924,16921 ,5108,5111,5109 ,0,0,0}, - {16920,16923,16924 ,5108,5108,5111 ,0,0,0}, {16924,16925,16926 ,5111,5112,5113 ,0,0,0}, - {16925,16927,16926 ,5112,5114,5113 ,0,0,0}, {16926,16927,16928 ,5113,5114,5115 ,0,0,0}, - {16927,16929,16928 ,5114,5116,5115 ,0,0,0}, {16930,16931,16929 ,5117,5118,5116 ,0,0,0}, - {16930,16932,16933 ,5117,5119,5120 ,0,0,0}, {16934,16933,16932 ,5121,5120,5119 ,0,0,0}, - {16934,16932,16935 ,5121,5119,5122 ,0,0,0}, {16935,16936,16934 ,5122,5123,5121 ,0,0,0}, - {16931,16928,16929 ,5118,5115,5116 ,0,0,0}, {16933,16931,16930 ,5120,5118,5117 ,0,0,0}, - {16936,16937,16938 ,5123,5124,5125 ,0,0,0}, {16937,16936,16935 ,5124,5123,5122 ,0,0,0}, - {16515,16938,16937 ,5126,5125,5124 ,0,0,0}, {16917,16914,16939 ,5105,5102,5127 ,0,0,0}, - {16940,16941,16942 ,5128,5129,5130 ,0,0,0}, {16940,16939,16941 ,5128,5127,5129 ,0,0,0}, - {16941,16943,16942 ,5129,5131,5130 ,0,0,0}, {16943,16941,16944 ,5131,5129,5132 ,0,0,0}, - {16945,16946,16947 ,5133,5134,5135 ,0,0,0}, {16945,16944,16946 ,5133,5132,5134 ,0,0,0}, - {16948,16947,16946 ,5136,5135,5134 ,0,0,0}, {16947,16948,16949 ,5135,5136,5137 ,0,0,0}, - {16950,16951,16952 ,5138,5139,5140 ,0,0,0}, {16953,16954,16948 ,5141,5142,5136 ,0,0,0}, - {16955,16956,16953 ,5143,5144,5141 ,0,0,0}, {16956,16955,16957 ,5144,5143,5145 ,0,0,0}, - {16958,16959,16955 ,5146,5147,5143 ,0,0,0}, {16912,16911,16960 ,5100,5099,5148 ,0,0,0}, - {16961,16962,16958 ,5149,5150,5146 ,0,0,0}, {16963,16964,16965 ,5151,5152,5153 ,0,0,0}, - {16966,16967,16968 ,5154,5155,5156 ,0,0,0}, {16969,16970,16971 ,5157,5158,5159 ,0,0,0}, - {16972,16973,16974 ,5160,5161,5162 ,0,0,0}, {16975,16976,16977 ,5163,5164,5165 ,0,0,0}, - {16978,16979,16980 ,5166,5167,5168 ,0,0,0}, {16978,16981,16982 ,5166,5169,5170 ,0,0,0}, - {16983,16984,16985 ,5171,5172,5173 ,0,0,0}, {16986,16987,16988 ,5174,5175,5176 ,0,0,0}, - {16989,16990,16991 ,5177,5178,5179 ,0,0,0}, {16992,16984,16983 ,5180,5172,5171 ,0,0,0}, - {16993,16994,16995 ,5179,5181,5182 ,0,0,0}, {16993,16991,16990 ,5179,5179,5178 ,0,0,0}, - {16996,16997,16998 ,5183,5184,5185 ,0,0,0}, {16999,16996,16995 ,5186,5183,5182 ,0,0,0}, - {17000,17001,17002 ,5187,5188,5189 ,0,0,0}, {17003,17000,16998 ,5190,5187,5185 ,0,0,0}, - {17004,17005,17006 ,5191,5192,5193 ,0,0,0}, {17005,17004,17002 ,5192,5191,5189 ,0,0,0}, - {17007,17008,17006 ,5194,5195,5193 ,0,0,0}, {17004,17006,17008 ,5191,5193,5195 ,0,0,0}, - {17007,17009,17010 ,5194,5196,5197 ,0,0,0}, {17010,17008,17007 ,5197,5195,5194 ,0,0,0}, - {17003,17001,17000 ,5190,5188,5187 ,0,0,0}, {17001,17005,17002 ,5188,5192,5189 ,0,0,0}, - {16997,17003,16998 ,5184,5190,5185 ,0,0,0}, {16999,16997,16996 ,5186,5184,5183 ,0,0,0}, - {16994,16999,16995 ,5181,5186,5182 ,0,0,0}, {16994,16993,16990 ,5181,5179,5178 ,0,0,0}, - {16990,17011,16994 ,5178,5198,5181 ,0,0,0}, {16983,17011,16992 ,5171,5198,5180 ,0,0,0}, - {17011,16990,16992 ,5198,5178,5180 ,0,0,0}, {17012,17013,17014 ,5199,5200,5201 ,0,0,0}, - {16985,16984,16986 ,5173,5172,5174 ,0,0,0}, {17012,17015,17016 ,5199,5202,5203 ,0,0,0}, - {17016,17013,17012 ,5203,5200,5199 ,0,0,0}, {17017,17015,17018 ,5204,5202,5205 ,0,0,0}, - {17015,17017,17016 ,5202,5204,5203 ,0,0,0}, {17019,16613,17018 ,5206,5207,5205 ,0,0,0}, - {17017,17018,16613 ,5204,5205,5207 ,0,0,0}, {16616,16613,17019 ,5197,5207,5206 ,0,0,0}, - {17014,17013,17020 ,5201,5200,5208 ,0,0,0}, {17021,17022,17023 ,5209,5210,5211 ,0,0,0}, - {17014,17020,17023 ,5201,5208,5211 ,0,0,0}, {17021,17024,17022 ,5209,5212,5210 ,0,0,0}, - {17023,17020,17021 ,5211,5208,5209 ,0,0,0}, {16987,16979,16988 ,5175,5167,5176 ,0,0,0}, - {17024,17025,17022 ,5212,5213,5210 ,0,0,0}, {16991,17025,16989 ,5179,5213,5177 ,0,0,0}, - {17024,16989,17025 ,5212,5177,5213 ,0,0,0}, {16986,16988,16985 ,5174,5176,5173 ,0,0,0}, - {16977,16966,16975 ,5165,5154,5163 ,0,0,0}, {16978,16980,16981 ,5166,5168,5169 ,0,0,0}, - {16979,16987,16980 ,5167,5175,5168 ,0,0,0}, {16981,16974,16982 ,5169,5162,5170 ,0,0,0}, - {16976,16973,16972 ,5164,5161,5160 ,0,0,0}, {16973,16982,16974 ,5161,5170,5162 ,0,0,0}, - {16977,16976,16972 ,5165,5164,5160 ,0,0,0}, {16963,16970,16969 ,5151,5158,5157 ,0,0,0}, - {16966,16968,16975 ,5154,5156,5163 ,0,0,0}, {16967,16971,16968 ,5155,5159,5156 ,0,0,0}, - {16965,16970,16963 ,5153,5158,5151 ,0,0,0}, {16967,16969,16971 ,5155,5157,5159 ,0,0,0}, - {16913,16965,16964 ,5101,5153,5152 ,0,0,0}, {16964,16565,16961 ,5152,5214,5149 ,0,0,0}, - {16919,17026,16920 ,5107,5215,5108 ,0,0,0}, {16925,16924,16923 ,5112,5111,5108 ,0,0,0}, - {16922,17027,16923 ,5110,5216,5108 ,0,0,0}, {16925,16923,17027 ,5112,5108,5216 ,0,0,0}, - {17028,17026,17029 ,5217,5215,5218 ,0,0,0}, {16916,16922,16918 ,5104,5110,5106 ,0,0,0}, - {17030,17028,17031 ,5219,5217,5220 ,0,0,0}, {17030,17032,17028 ,5219,5221,5217 ,0,0,0}, - {17033,17032,17034 ,5222,5221,5223 ,0,0,0}, {16940,16917,16939 ,5128,5105,5127 ,0,0,0}, - {17035,17033,17036 ,5224,5222,5225 ,0,0,0}, {17035,17037,17033 ,5224,5226,5222 ,0,0,0}, - {17038,17037,17039 ,5227,5226,5228 ,0,0,0}, {16945,16943,16944 ,5133,5131,5132 ,0,0,0}, - {17040,17041,17038 ,5229,5230,5227 ,0,0,0}, {17042,17041,17040 ,5231,5230,5229 ,0,0,0}, - {17043,17041,17044 ,5232,5230,5233 ,0,0,0}, {16954,16949,16948 ,5142,5137,5136 ,0,0,0}, - {16952,17043,16950 ,5140,5232,5138 ,0,0,0}, {16956,16954,16953 ,5144,5142,5141 ,0,0,0}, - {17045,16952,17046 ,5234,5140,5235 ,0,0,0}, {16959,16957,16955 ,5147,5145,5143 ,0,0,0}, - {16911,17045,16960 ,5099,5234,5148 ,0,0,0}, {16962,16959,16958 ,5150,5147,5146 ,0,0,0}, - {16962,16961,16565 ,5150,5149,5214 ,0,0,0}, {16964,16961,16913 ,5152,5149,5101 ,0,0,0}, - {16913,16961,16911 ,5101,5149,5099 ,0,0,0}, {17046,16960,17045 ,5235,5148,5234 ,0,0,0}, - {16951,17046,16952 ,5139,5235,5140 ,0,0,0}, {17044,16950,17043 ,5233,5138,5232 ,0,0,0}, - {17042,17044,17041 ,5231,5233,5230 ,0,0,0}, {17039,17040,17038 ,5228,5229,5227 ,0,0,0}, - {17035,17039,17037 ,5224,5228,5226 ,0,0,0}, {17034,17036,17033 ,5223,5225,5222 ,0,0,0}, - {17030,17034,17032 ,5219,5223,5221 ,0,0,0}, {17029,17031,17028 ,5218,5220,5217 ,0,0,0}, - {16919,17029,17026 ,5107,5218,5215 ,0,0,0}, {17047,17048,17049 ,5236,5237,5238 ,0,0,0}, - {17050,17051,17049 ,5239,5240,5238 ,0,0,0}, {17047,17049,17051 ,5236,5238,5240 ,0,0,0}, - {17050,17052,17053 ,5239,5241,5242 ,0,0,0}, {17053,17051,17050 ,5242,5240,5239 ,0,0,0}, - {17054,17052,17055 ,5243,5241,5244 ,0,0,0}, {17052,17054,17053 ,5241,5243,5242 ,0,0,0}, - {17056,17057,17055 ,5245,5246,5244 ,0,0,0}, {17054,17055,17057 ,5243,5244,5246 ,0,0,0}, - {17056,17058,17059 ,5245,5247,5248 ,0,0,0}, {17059,17057,17056 ,5248,5246,5245 ,0,0,0}, - {17060,17058,17061 ,5249,5247,5250 ,0,0,0}, {17058,17060,17059 ,5247,5249,5248 ,0,0,0}, - {17062,17063,17061 ,5251,5252,5250 ,0,0,0}, {17060,17061,17063 ,5249,5250,5252 ,0,0,0}, - {17062,17064,17065 ,5251,5253,5254 ,0,0,0}, {17065,17063,17062 ,5254,5252,5251 ,0,0,0}, - {17066,17064,17067 ,5255,5253,5256 ,0,0,0}, {17064,17066,17065 ,5253,5255,5254 ,0,0,0}, - {17068,17069,17067 ,5257,5258,5256 ,0,0,0}, {17066,17067,17069 ,5255,5256,5258 ,0,0,0}, - {17068,17070,17071 ,5257,5259,5260 ,0,0,0}, {17071,17069,17068 ,5260,5258,5257 ,0,0,0}, - {17072,17070,17073 ,5261,5259,5262 ,0,0,0}, {17070,17072,17071 ,5259,5261,5260 ,0,0,0}, - {17074,17075,17073 ,5263,5264,5262 ,0,0,0}, {17072,17073,17075 ,5261,5262,5264 ,0,0,0}, - {17074,17076,17077 ,5263,5265,5266 ,0,0,0}, {17077,17075,17074 ,5266,5264,5263 ,0,0,0}, - {17078,17076,17079 ,5267,5265,5268 ,0,0,0}, {17076,17078,17077 ,5265,5267,5266 ,0,0,0}, - {17080,17081,17079 ,5269,5270,5268 ,0,0,0}, {17078,17079,17081 ,5267,5268,5270 ,0,0,0}, - {17080,17082,17083 ,5269,5271,5272 ,0,0,0}, {17083,17081,17080 ,5272,5270,5269 ,0,0,0}, - {17084,17082,17085 ,5273,5271,5274 ,0,0,0}, {17082,17084,17083 ,5271,5273,5272 ,0,0,0}, - {17086,17087,17085 ,5275,5276,5274 ,0,0,0}, {17084,17085,17087 ,5273,5274,5276 ,0,0,0}, - {17086,17088,17089 ,5275,5277,5278 ,0,0,0}, {17089,17087,17086 ,5278,5276,5275 ,0,0,0}, - {17090,17088,17091 ,5279,5277,5280 ,0,0,0}, {17088,17090,17089 ,5277,5279,5278 ,0,0,0}, - {17092,17093,17091 ,5281,5282,5280 ,0,0,0}, {17090,17091,17093 ,5279,5280,5282 ,0,0,0}, - {17094,17092,17095 ,5283,5281,5284 ,0,0,0}, {17094,17093,17092 ,5283,5282,5281 ,0,0,0}, - {17096,17095,17097 ,5285,5284,5286 ,0,0,0}, {17092,17097,17095 ,5281,5286,5284 ,0,0,0}, - {17098,17096,17099 ,5287,5285,5288 ,0,0,0}, {17096,17097,17099 ,5285,5286,5288 ,0,0,0}, - {17098,17100,17101 ,5287,5289,5290 ,0,0,0}, {17101,17096,17098 ,5290,5285,5287 ,0,0,0}, - {17100,17102,17101 ,5289,5291,5290 ,0,0,0}, {17103,17048,17047 ,5292,5237,5236 ,0,0,0}, - {17103,17104,17105 ,5292,5293,5294 ,0,0,0}, {17105,17048,17103 ,5294,5237,5292 ,0,0,0}, - {17106,17104,17107 ,5295,5293,5296 ,0,0,0}, {17104,17106,17105 ,5293,5295,5294 ,0,0,0}, - {17108,17109,17107 ,5297,5298,5296 ,0,0,0}, {17106,17107,17109 ,5295,5296,5298 ,0,0,0}, - {17108,17110,17111 ,5297,5299,5300 ,0,0,0}, {17111,17109,17108 ,5300,5298,5297 ,0,0,0}, - {17112,17110,17113 ,5301,5299,5302 ,0,0,0}, {17110,17112,17111 ,5299,5301,5300 ,0,0,0}, - {17114,17115,17113 ,5303,5304,5302 ,0,0,0}, {17112,17113,17115 ,5301,5302,5304 ,0,0,0}, - {17114,17116,17117 ,5303,5305,5306 ,0,0,0}, {17117,17115,17114 ,5306,5304,5303 ,0,0,0}, - {17118,17116,17119 ,5307,5305,5308 ,0,0,0}, {17116,17118,17117 ,5305,5307,5306 ,0,0,0}, - {17120,17121,17119 ,5309,5310,5308 ,0,0,0}, {17118,17119,17121 ,5307,5308,5310 ,0,0,0}, - {17120,17122,17123 ,5309,5311,5312 ,0,0,0}, {17123,17121,17120 ,5312,5310,5309 ,0,0,0}, - {17124,17122,17125 ,5313,5311,5314 ,0,0,0}, {17122,17124,17123 ,5311,5313,5312 ,0,0,0}, - {17126,17127,17125 ,5315,5316,5314 ,0,0,0}, {17124,17125,17127 ,5313,5314,5316 ,0,0,0}, - {17126,17128,17129 ,5315,5317,5318 ,0,0,0}, {17129,17127,17126 ,5318,5316,5315 ,0,0,0}, - {17130,17128,17131 ,5319,5317,5320 ,0,0,0}, {17128,17130,17129 ,5317,5319,5318 ,0,0,0}, - {17132,17133,17131 ,5321,5322,5320 ,0,0,0}, {17130,17131,17133 ,5319,5320,5322 ,0,0,0}, - {17132,17134,17135 ,5321,5323,5324 ,0,0,0}, {17135,17133,17132 ,5324,5322,5321 ,0,0,0}, - {17136,17134,17137 ,5325,5323,5326 ,0,0,0}, {17134,17136,17135 ,5323,5325,5324 ,0,0,0}, - {17138,17139,17137 ,5327,5328,5326 ,0,0,0}, {17136,17137,17139 ,5325,5326,5328 ,0,0,0}, - {17138,17140,17141 ,5327,5329,5330 ,0,0,0}, {17141,17139,17138 ,5330,5328,5327 ,0,0,0}, - {17142,17140,17143 ,5331,5329,5332 ,0,0,0}, {17140,17142,17141 ,5329,5331,5330 ,0,0,0}, - {17144,17145,17143 ,5333,5334,5332 ,0,0,0}, {17142,17143,17145 ,5331,5332,5334 ,0,0,0}, - {17144,17146,17147 ,5333,5335,5336 ,0,0,0}, {17147,17145,17144 ,5336,5334,5333 ,0,0,0}, - {17148,17149,17146 ,5337,5338,5335 ,0,0,0}, {17146,17149,17147 ,5335,5338,5336 ,0,0,0}, - {17150,17151,17148 ,5339,5340,5337 ,0,0,0}, {17148,17146,17150 ,5337,5335,5339 ,0,0,0}, - {17152,17153,17151 ,5341,5342,5340 ,0,0,0}, {17152,17151,17150 ,5341,5340,5339 ,0,0,0}, - {17154,17153,17155 ,5343,5342,5344 ,0,0,0}, {17153,17154,17151 ,5342,5343,5340 ,0,0,0}, - {17154,17155,17156 ,5343,5344,5345 ,0,0,0}, {17157,17158,17159 ,5346,5347,5348 ,0,0,0}, - {17160,17161,17159 ,5349,5350,5348 ,0,0,0}, {17157,17159,17161 ,5346,5348,5350 ,0,0,0}, - {17160,17162,17163 ,5349,5351,5352 ,0,0,0}, {17163,17161,17160 ,5352,5350,5349 ,0,0,0}, - {17164,17162,17165 ,5353,5351,5354 ,0,0,0}, {17162,17164,17163 ,5351,5353,5352 ,0,0,0}, - {17166,17167,17165 ,5355,5356,5354 ,0,0,0}, {17164,17165,17167 ,5353,5354,5356 ,0,0,0}, - {17166,17168,17169 ,5355,5357,5358 ,0,0,0}, {17169,17167,17166 ,5358,5356,5355 ,0,0,0}, - {17170,17168,17171 ,5359,5357,5360 ,0,0,0}, {17168,17170,17169 ,5357,5359,5358 ,0,0,0}, - {17172,17173,17171 ,5361,5362,5360 ,0,0,0}, {17170,17171,17173 ,5359,5360,5362 ,0,0,0}, - {17172,17174,17175 ,5361,5363,5364 ,0,0,0}, {17175,17173,17172 ,5364,5362,5361 ,0,0,0}, - {17176,17174,17177 ,5365,5363,5366 ,0,0,0}, {17174,17176,17175 ,5363,5365,5364 ,0,0,0}, - {17178,17179,17177 ,5367,5368,5366 ,0,0,0}, {17176,17177,17179 ,5365,5366,5368 ,0,0,0}, - {17178,17180,17181 ,5367,5369,5370 ,0,0,0}, {17181,17179,17178 ,5370,5368,5367 ,0,0,0}, - {17182,17180,17183 ,5371,5369,5372 ,0,0,0}, {17180,17182,17181 ,5369,5371,5370 ,0,0,0}, - {17184,17185,17183 ,5373,5374,5372 ,0,0,0}, {17182,17183,17185 ,5371,5372,5374 ,0,0,0}, - {17184,17186,17187 ,5373,5375,5376 ,0,0,0}, {17187,17185,17184 ,5376,5374,5373 ,0,0,0}, - {17188,17186,17189 ,5377,5375,5378 ,0,0,0}, {17186,17188,17187 ,5375,5377,5376 ,0,0,0}, - {17190,17191,17189 ,5379,5380,5378 ,0,0,0}, {17188,17189,17191 ,5377,5378,5380 ,0,0,0}, - {17190,17192,17193 ,5379,5381,5382 ,0,0,0}, {17193,17191,17190 ,5382,5380,5379 ,0,0,0}, - {17194,17192,17195 ,5383,5381,5384 ,0,0,0}, {17192,17194,17193 ,5381,5383,5382 ,0,0,0}, - {17196,17197,17195 ,5385,5386,5384 ,0,0,0}, {17194,17195,17197 ,5383,5384,5386 ,0,0,0}, - {17196,17198,17199 ,5385,5387,5388 ,0,0,0}, {17199,17197,17196 ,5388,5386,5385 ,0,0,0}, - {17200,17198,17201 ,5389,5387,5390 ,0,0,0}, {17198,17200,17199 ,5387,5389,5388 ,0,0,0}, - {17202,17203,17201 ,5391,5392,5390 ,0,0,0}, {17200,17201,17203 ,5389,5390,5392 ,0,0,0}, - {17202,17204,17205 ,5391,5393,5394 ,0,0,0}, {17205,17203,17202 ,5394,5392,5391 ,0,0,0}, - {17206,17204,17207 ,5395,5393,5396 ,0,0,0}, {17204,17206,17205 ,5393,5395,5394 ,0,0,0}, - {17208,17209,17207 ,5397,5398,5396 ,0,0,0}, {17206,17207,17209 ,5395,5396,5398 ,0,0,0}, - {17208,17210,17211 ,5397,5399,5400 ,0,0,0}, {17211,17209,17208 ,5400,5398,5397 ,0,0,0}, - {17212,17210,17213 ,5401,5399,5402 ,0,0,0}, {17210,17212,17211 ,5399,5401,5400 ,0,0,0}, - {17214,17215,17213 ,5403,5404,5402 ,0,0,0}, {17212,17213,17215 ,5401,5402,5404 ,0,0,0}, - {17214,17216,17217 ,5403,5405,5406 ,0,0,0}, {17217,17215,17214 ,5406,5404,5403 ,0,0,0}, - {17216,17218,17217 ,5405,5407,5406 ,0,0,0}, {17219,17158,17157 ,5408,5347,5346 ,0,0,0}, - {17219,17220,17221 ,5408,5409,5410 ,0,0,0}, {17221,17158,17219 ,5410,5347,5408 ,0,0,0}, - {17222,17220,17223 ,5411,5409,5412 ,0,0,0}, {17220,17222,17221 ,5409,5411,5410 ,0,0,0}, - {17224,17225,17223 ,5413,5414,5412 ,0,0,0}, {17222,17223,17225 ,5411,5412,5414 ,0,0,0}, - {17224,17226,17227 ,5413,5415,5416 ,0,0,0}, {17227,17225,17224 ,5416,5414,5413 ,0,0,0}, - {17228,17226,17229 ,5417,5415,5418 ,0,0,0}, {17226,17228,17227 ,5415,5417,5416 ,0,0,0}, - {17230,17231,17229 ,5419,5420,5418 ,0,0,0}, {17228,17229,17231 ,5417,5418,5420 ,0,0,0}, - {17230,17232,17233 ,5419,5421,5422 ,0,0,0}, {17233,17231,17230 ,5422,5420,5419 ,0,0,0}, - {17234,17232,17235 ,5423,5421,5424 ,0,0,0}, {17232,17234,17233 ,5421,5423,5422 ,0,0,0}, - {17236,17237,17235 ,5425,5426,5424 ,0,0,0}, {17234,17235,17237 ,5423,5424,5426 ,0,0,0}, - {17236,17238,17239 ,5425,5427,5428 ,0,0,0}, {17239,17237,17236 ,5428,5426,5425 ,0,0,0}, - {17240,17238,17241 ,5429,5427,5430 ,0,0,0}, {17238,17240,17239 ,5427,5429,5428 ,0,0,0}, - {17242,17243,17241 ,5431,5432,5430 ,0,0,0}, {17240,17241,17243 ,5429,5430,5432 ,0,0,0}, - {17242,17244,17245 ,5431,5433,5434 ,0,0,0}, {17245,17243,17242 ,5434,5432,5431 ,0,0,0}, - {17246,17244,17247 ,5435,5433,5436 ,0,0,0}, {17244,17246,17245 ,5433,5435,5434 ,0,0,0}, - {17248,17249,17247 ,5437,5438,5436 ,0,0,0}, {17246,17247,17249 ,5435,5436,5438 ,0,0,0}, - {17248,17250,17251 ,5437,5439,5440 ,0,0,0}, {17251,17249,17248 ,5440,5438,5437 ,0,0,0}, - {17252,17250,17253 ,5441,5439,5442 ,0,0,0}, {17250,17252,17251 ,5439,5441,5440 ,0,0,0}, - {17254,17255,17253 ,5443,5444,5442 ,0,0,0}, {17252,17253,17255 ,5441,5442,5444 ,0,0,0}, - {17254,17256,17257 ,5443,5445,5446 ,0,0,0}, {17257,17255,17254 ,5446,5444,5443 ,0,0,0}, - {17258,17256,17259 ,5447,5445,5448 ,0,0,0}, {17256,17258,17257 ,5445,5447,5446 ,0,0,0}, - {17260,17261,17259 ,5449,5450,5448 ,0,0,0}, {17258,17259,17261 ,5447,5448,5450 ,0,0,0}, - {17260,17262,17263 ,5449,5451,5452 ,0,0,0}, {17263,17261,17260 ,5452,5450,5449 ,0,0,0}, - {17264,17262,17265 ,5453,5451,5454 ,0,0,0}, {17262,17264,17263 ,5451,5453,5452 ,0,0,0}, - {17266,17267,17265 ,5455,5456,5454 ,0,0,0}, {17264,17265,17267 ,5453,5454,5456 ,0,0,0}, - {17266,17268,17269 ,5455,5457,5458 ,0,0,0}, {17269,17267,17266 ,5458,5456,5455 ,0,0,0}, - {17270,17268,17271 ,5459,5457,5460 ,0,0,0}, {17268,17270,17269 ,5457,5459,5458 ,0,0,0}, - {17272,17273,17271 ,5461,5462,5460 ,0,0,0}, {17270,17271,17273 ,5459,5460,5462 ,0,0,0}, - {17272,17274,17275 ,5461,5463,5464 ,0,0,0}, {17275,17273,17272 ,5464,5462,5461 ,0,0,0}, - {17276,17274,17277 ,5465,5463,5466 ,0,0,0}, {17274,17276,17275 ,5463,5465,5464 ,0,0,0}, - {17276,17277,17278 ,5465,5466,5467 ,0,0,0}, {17279,16313,16312 ,5468,5469,5469 ,0,0,0}, - {17280,17281,17282 ,726,726,726 ,0,0,0}, {17283,16046,16043 ,726,5470,726 ,0,0,0}, - {17284,17285,17286 ,5471,726,726 ,0,0,0}, {17287,17288,17289 ,726,726,726 ,0,0,0}, - {17290,16268,17291 ,5468,5471,5469 ,0,0,0}, {17292,17293,17294 ,5470,726,726 ,0,0,0}, - {17295,17296,17297 ,5471,5469,5469 ,0,0,0}, {17298,17297,16241 ,5468,5469,5469 ,0,0,0}, - {17299,17300,16347 ,5469,5472,5468 ,0,0,0}, {17301,17302,17303 ,5469,5468,5471 ,0,0,0}, - {17304,17305,17306 ,5473,5474,726 ,0,0,0}, {17307,17308,17309 ,5475,5476,5471 ,0,0,0}, - {17310,17311,17312 ,5477,5478,5469 ,0,0,0}, {17305,17304,17313 ,5474,5473,5479 ,0,0,0}, - {17314,17315,17316 ,5471,5469,726 ,0,0,0}, {17317,17318,16306 ,5468,5469,5471 ,0,0,0}, - {17319,17320,17321 ,726,5480,5481 ,0,0,0}, {17312,17322,17323 ,5469,726,5468 ,0,0,0}, - {17324,17325,17326 ,5475,5475,5482 ,0,0,0}, {17327,15981,17324 ,5468,5483,5475 ,0,0,0}, - {17326,17328,17329 ,5482,5482,5482 ,0,0,0}, {17325,17328,17326 ,5475,5482,5482 ,0,0,0}, - {17329,17330,17326 ,5482,5475,5482 ,0,0,0}, {17321,17315,17331 ,5481,5469,5475 ,0,0,0}, - {17332,16361,17333 ,726,5471,5484 ,0,0,0}, {17305,17313,17323 ,5474,5479,5468 ,0,0,0}, - {17334,17335,17336 ,5475,5485,5468 ,0,0,0}, {17337,17338,17339 ,5486,5483,5468 ,0,0,0}, - {17322,17305,17323 ,726,5474,5468 ,0,0,0}, {16306,17318,16307 ,5471,5469,726 ,0,0,0}, - {16313,17279,16315 ,5469,5468,726 ,0,0,0}, {16319,16318,17340 ,5471,5471,726 ,0,0,0}, - {16347,16317,17299 ,5468,5468,5469 ,0,0,0}, {16345,16317,16347 ,5471,5468,5468 ,0,0,0}, - {16319,17341,16344 ,5471,5471,5469 ,0,0,0}, {17342,16351,16350 ,5468,5478,726 ,0,0,0}, - {16318,17343,17340 ,5471,726,726 ,0,0,0}, {16274,17344,17345 ,5471,5468,726 ,0,0,0}, - {17346,16361,16359 ,5475,5471,726 ,0,0,0}, {17347,17348,17349 ,5469,5482,5483 ,0,0,0}, - {17350,17348,17351 ,5468,5482,5475 ,0,0,0}, {17352,17353,17354 ,726,5468,5468 ,0,0,0}, - {17355,17303,17356 ,726,5471,5469 ,0,0,0}, {17357,17358,17359 ,5475,5475,726 ,0,0,0}, - {17353,17352,17360 ,5468,726,5483 ,0,0,0}, {17361,17362,17363 ,5480,5487,5475 ,0,0,0}, - {17360,17364,17347 ,5483,5478,5469 ,0,0,0}, {17365,17366,17367 ,5475,5479,5474 ,0,0,0}, - {17367,17333,17365 ,5474,5484,5475 ,0,0,0}, {17368,17369,17367 ,5473,726,5474 ,0,0,0}, - {17368,17367,17366 ,5473,5474,5479 ,0,0,0}, {17350,17349,17348 ,5468,5483,5482 ,0,0,0}, - {17362,17357,17370 ,5487,5475,726 ,0,0,0}, {17348,17347,17364 ,5482,5469,5478 ,0,0,0}, - {17371,17372,17332 ,5486,5478,726 ,0,0,0}, {17355,17356,17354 ,726,5469,5468 ,0,0,0}, - {16271,17344,16274 ,726,5468,5471 ,0,0,0}, {17365,17333,16361 ,5475,5484,5471 ,0,0,0}, - {17373,17374,17375 ,726,726,726 ,0,0,0}, {17376,17377,16277 ,5468,5469,726 ,0,0,0}, - {17346,16359,17378 ,5475,726,5482 ,0,0,0}, {17379,16283,17380 ,726,726,5470 ,0,0,0}, - {16356,17381,17382 ,5475,5485,5475 ,0,0,0}, {17383,17384,16201 ,5471,726,5471 ,0,0,0}, - {16105,17385,16100 ,726,5470,726 ,0,0,0}, {17386,17387,17388 ,5470,5471,5471 ,0,0,0}, - {17389,17390,17391 ,726,726,5470 ,0,0,0}, {17391,17292,17389 ,5470,5470,726 ,0,0,0}, - {17373,17294,17374 ,726,726,726 ,0,0,0}, {17392,17393,17394 ,726,726,5470 ,0,0,0}, - {17286,17386,17388 ,726,5470,5471 ,0,0,0}, {17390,17395,17396 ,726,726,726 ,0,0,0}, - {16285,17397,17398 ,726,5470,726 ,0,0,0}, {17399,17400,17401 ,5470,726,726 ,0,0,0}, - {17374,17294,17293 ,726,726,726 ,0,0,0}, {17397,17402,17403 ,5470,726,5468 ,0,0,0}, - {17374,17404,17375 ,726,726,726 ,0,0,0}, {17403,17405,17406 ,5468,5468,726 ,0,0,0}, - {17402,17405,17403 ,726,5468,5468 ,0,0,0}, {17406,17407,17403 ,726,5471,5468 ,0,0,0}, - {17408,17409,17410 ,726,726,5471 ,0,0,0}, {16285,17402,17397 ,726,726,5470 ,0,0,0}, - {17398,17411,17412 ,726,726,726 ,0,0,0}, {17413,17414,17415 ,726,5488,5489 ,0,0,0}, - {16243,17416,17417 ,5471,5470,726 ,0,0,0}, {16271,17297,17344 ,726,5469,5468 ,0,0,0}, - {17418,16198,16195 ,726,726,5471 ,0,0,0}, {17419,16122,16119 ,726,726,726 ,0,0,0}, - {17420,16055,17421 ,726,5470,726 ,0,0,0}, {17422,16198,17418 ,726,726,726 ,0,0,0}, - {17423,17424,17425 ,726,726,726 ,0,0,0}, {17426,17427,17428 ,5489,726,726 ,0,0,0}, - {16192,17429,16193 ,726,5471,726 ,0,0,0}, {17430,17424,17431 ,726,726,726 ,0,0,0}, - {17432,17433,17434 ,726,726,5489 ,0,0,0}, {17435,17436,17437 ,726,726,726 ,0,0,0}, - {17438,17424,17430 ,726,726,726 ,0,0,0}, {17280,17282,17437 ,726,726,726 ,0,0,0}, - {17439,17440,17441 ,726,726,5489 ,0,0,0}, {17281,17423,17425 ,726,726,726 ,0,0,0}, - {17442,17443,17444 ,726,726,726 ,0,0,0}, {17440,17445,17442 ,726,5488,726 ,0,0,0}, - {17438,17425,17424 ,726,726,726 ,0,0,0}, {17289,17426,16209 ,726,5489,726 ,0,0,0}, - {17446,17447,17448 ,5489,726,726 ,0,0,0}, {17446,17449,17447 ,5489,5488,726 ,0,0,0}, - {17450,17451,17452 ,726,5471,726 ,0,0,0}, {17447,17449,17453 ,726,5488,726 ,0,0,0}, - {17454,17447,17453 ,726,726,726 ,0,0,0}, {17455,16167,17456 ,726,726,726 ,0,0,0}, - {16125,17457,17458 ,726,726,726 ,0,0,0}, {16283,16281,17380 ,726,726,5470 ,0,0,0}, - {17289,16205,17459 ,726,726,726 ,0,0,0}, {17451,17460,17461 ,5471,5471,726 ,0,0,0}, - {17462,16023,17463 ,726,5470,726 ,0,0,0}, {17452,17464,17450 ,726,5471,726 ,0,0,0}, - {16133,17465,17466 ,5489,726,726 ,0,0,0}, {17467,17468,17469 ,726,726,726 ,0,0,0}, - {17470,17471,17469 ,726,5471,726 ,0,0,0}, {17434,17433,17472 ,5489,726,5488 ,0,0,0}, - {17419,17473,16122 ,726,726,726 ,0,0,0}, {17427,17289,17448 ,726,726,726 ,0,0,0}, - {17474,17419,17472 ,726,726,5488 ,0,0,0}, {16049,17475,17476 ,726,5471,726 ,0,0,0}, - {17477,17478,17468 ,726,5488,726 ,0,0,0}, {17469,17479,17480 ,726,5471,726 ,0,0,0}, - {17481,17482,17483 ,726,726,5488 ,0,0,0}, {17484,17485,17481 ,726,726,726 ,0,0,0}, - {17486,17485,17487 ,726,726,726 ,0,0,0}, {17488,16133,17466 ,726,5489,726 ,0,0,0}, - {17489,17469,17490 ,726,726,726 ,0,0,0}, {17466,17465,17491 ,726,726,726 ,0,0,0}, - {17468,17492,17477 ,726,726,726 ,0,0,0}, {17493,17491,17465 ,726,726,726 ,0,0,0}, - {17468,17478,17469 ,726,5488,726 ,0,0,0}, {17493,17494,17491 ,726,5488,726 ,0,0,0}, - {17495,17492,17468 ,726,726,726 ,0,0,0}, {17491,17494,17496 ,726,5488,726 ,0,0,0}, - {17469,17497,17479 ,726,726,5471 ,0,0,0}, {16328,17498,16327 ,5469,5468,5468 ,0,0,0}, - {16328,16333,17499 ,5469,726,726 ,0,0,0}, {17500,16040,17501 ,726,5471,5471 ,0,0,0}, - {17502,15947,17503 ,5470,5468,5468 ,0,0,0}, {16057,17504,17505 ,5470,726,726 ,0,0,0}, - {17506,17507,17508 ,5468,726,5469 ,0,0,0}, {17509,17510,17511 ,5471,5468,726 ,0,0,0}, - {17512,17506,17513 ,5468,5468,726 ,0,0,0}, {17514,17515,17516 ,726,5470,5469 ,0,0,0}, - {17517,17518,17519 ,726,5469,726 ,0,0,0}, {17520,17521,17522 ,5471,5469,726 ,0,0,0}, - {17523,16344,17524 ,726,5469,5470 ,0,0,0}, {17488,17525,17526 ,726,5489,726 ,0,0,0}, - {17469,17471,17527 ,726,5471,726 ,0,0,0}, {17528,16231,16230 ,5468,726,5469 ,0,0,0}, - {17529,17530,17419 ,5470,5471,726 ,0,0,0}, {17283,17531,16046 ,726,726,5470 ,0,0,0}, - {17532,16091,16090 ,5471,726,726 ,0,0,0}, {17533,16333,16331 ,726,726,5468 ,0,0,0}, - {17534,17535,17536 ,726,5470,5471 ,0,0,0}, {17537,17538,17539 ,5471,726,5470 ,0,0,0}, - {17540,17541,17542 ,726,5470,726 ,0,0,0}, {17504,17543,17505 ,726,726,726 ,0,0,0}, - {17543,17504,17544 ,726,726,726 ,0,0,0}, {17505,17535,16057 ,726,5470,5470 ,0,0,0}, - {17543,17544,17545 ,726,726,726 ,0,0,0}, {17517,17511,17510 ,726,726,5468 ,0,0,0}, - {17543,17545,17546 ,726,726,726 ,0,0,0}, {17547,17548,17549 ,5471,5471,5468 ,0,0,0}, - {17515,17522,17516 ,5470,726,5469 ,0,0,0}, {17550,17514,17551 ,726,726,726 ,0,0,0}, - {17552,17553,17521 ,5468,5469,5469 ,0,0,0}, {17521,17520,17552 ,5469,5471,5468 ,0,0,0}, - {17554,17555,17552 ,5471,726,5468 ,0,0,0}, {17552,17555,17553 ,5468,726,5469 ,0,0,0}, - {16351,17556,16353 ,5478,5487,5468 ,0,0,0}, {16285,16283,17379 ,726,726,726 ,0,0,0}, - {17378,16359,16357 ,5482,726,5468 ,0,0,0}, {17377,16280,16277 ,5469,726,726 ,0,0,0}, - {17298,17295,17297 ,5468,5471,5469 ,0,0,0}, {17557,17296,17295 ,5468,5469,5471 ,0,0,0}, - {17302,17301,17558 ,5468,5469,5469 ,0,0,0}, {17296,17557,17559 ,5469,5468,5470 ,0,0,0}, - {17301,17303,17355 ,5469,5471,726 ,0,0,0}, {17558,17559,17560 ,5469,5470,5469 ,0,0,0}, - {17354,17356,17352 ,5468,5469,726 ,0,0,0}, {17360,17347,17353 ,5483,5469,5468 ,0,0,0}, - {17358,17364,17359 ,5475,5478,726 ,0,0,0}, {17364,17360,17359 ,5478,5483,726 ,0,0,0}, - {17371,17361,17372 ,5486,5480,5478 ,0,0,0}, {17362,17358,17357 ,5487,5475,5475 ,0,0,0}, - {17361,17363,17372 ,5480,5475,5478 ,0,0,0}, {17363,17362,17370 ,5475,5487,726 ,0,0,0}, - {17333,17371,17332 ,5484,5486,726 ,0,0,0}, {17346,17365,16361 ,5475,5475,5471 ,0,0,0}, - {17378,16357,17382 ,5482,5468,5475 ,0,0,0}, {17382,16357,16356 ,5475,5468,5475 ,0,0,0}, - {16353,17556,17381 ,5468,5487,5485 ,0,0,0}, {17381,16356,16353 ,5485,5475,5468 ,0,0,0}, - {17342,17556,16351 ,5468,5487,5478 ,0,0,0}, {17300,17342,16350 ,5472,5468,726 ,0,0,0}, - {17524,16344,17341 ,5470,5469,5471 ,0,0,0}, {16347,17300,16350 ,5468,5472,726 ,0,0,0}, - {17561,17562,16327 ,5471,5470,5468 ,0,0,0}, {16324,17562,17563 ,726,5470,726 ,0,0,0}, - {17309,17564,17307 ,5471,5468,5475 ,0,0,0}, {17318,17565,16307 ,5469,5469,726 ,0,0,0}, - {17566,17567,17327 ,5472,5482,5468 ,0,0,0}, {16290,15959,16286 ,5468,5468,5468 ,0,0,0}, - {15967,15965,17506 ,5471,726,5468 ,0,0,0}, {16222,15869,16220 ,5471,726,5469 ,0,0,0}, - {16233,17568,16236 ,5471,726,726 ,0,0,0}, {17418,16195,17284 ,726,5471,5471 ,0,0,0}, - {15889,17569,17570 ,726,726,5470 ,0,0,0}, {17571,17572,16131 ,726,726,726 ,0,0,0}, - {17573,16251,17574 ,726,726,5471 ,0,0,0}, {15866,17575,15863 ,5471,5471,5471 ,0,0,0}, - {15878,17576,17577 ,726,5469,5469 ,0,0,0}, {16217,16330,16336 ,5471,5469,5469 ,0,0,0}, - {16324,16327,17562 ,726,5468,5470 ,0,0,0}, {16340,16218,16336 ,5468,726,5469 ,0,0,0}, - {16330,15874,16331 ,5469,5471,5468 ,0,0,0}, {17533,17499,16333 ,726,726,726 ,0,0,0}, - {17499,17498,16328 ,726,5468,5469 ,0,0,0}, {17498,17561,16327 ,5468,5471,5468 ,0,0,0}, - {16321,16324,17563 ,726,726,726 ,0,0,0}, {16317,16345,17523 ,5468,5471,726 ,0,0,0}, - {16321,17343,16318 ,726,726,5471 ,0,0,0}, {17343,16321,17563 ,726,726,726 ,0,0,0}, - {17340,17341,16319 ,726,5471,5471 ,0,0,0}, {16344,17523,16345 ,5469,726,5471 ,0,0,0}, - {16315,17578,16317 ,726,5468,5468 ,0,0,0}, {17308,17299,17579 ,5476,5469,5468 ,0,0,0}, - {17578,17299,16317 ,5468,5469,5468 ,0,0,0}, {16307,17565,16309 ,726,5469,5470 ,0,0,0}, - {16312,16309,17580 ,5469,5470,726 ,0,0,0}, {17565,17580,16309 ,5469,726,5470 ,0,0,0}, - {17311,17310,17335 ,5478,5477,5485 ,0,0,0}, {16287,15959,17317 ,726,5468,5468 ,0,0,0}, - {16287,17317,16306 ,726,5468,5471 ,0,0,0}, {17581,17582,15979 ,5470,5470,5468 ,0,0,0}, - {15981,17325,17324 ,5483,5475,5475 ,0,0,0}, {17583,15965,15964 ,5468,726,5468 ,0,0,0}, - {17584,15939,17585 ,5469,5468,5471 ,0,0,0}, {16053,17421,16055 ,726,726,5470 ,0,0,0}, - {17586,17587,16015 ,5471,5471,5471 ,0,0,0}, {17588,16103,17589 ,726,726,5471 ,0,0,0}, - {17590,17591,17592 ,5471,5470,5471 ,0,0,0}, {16099,16100,17593 ,726,726,726 ,0,0,0}, - {16043,17460,17283 ,726,5471,726 ,0,0,0}, {17473,17419,17594 ,726,726,726 ,0,0,0}, - {16339,17595,16211 ,726,5468,5469 ,0,0,0}, {16236,17596,16237 ,726,726,5468 ,0,0,0}, - {16205,17289,16207 ,726,726,726 ,0,0,0}, {17384,16204,16201 ,726,5471,5471 ,0,0,0}, - {16165,17285,17284 ,726,726,5471 ,0,0,0}, {17286,17285,17386 ,726,726,5470 ,0,0,0}, - {17395,17408,17396 ,726,726,726 ,0,0,0}, {17410,17597,17387 ,5471,726,5471 ,0,0,0}, - {17388,17387,17597 ,5471,5471,726 ,0,0,0}, {17409,17408,17395 ,726,726,726 ,0,0,0}, - {17409,17597,17410 ,726,726,5471 ,0,0,0}, {17396,17391,17390 ,726,5470,726 ,0,0,0}, - {17292,17294,17389 ,5470,726,726 ,0,0,0}, {17393,17293,17394 ,726,726,5470 ,0,0,0}, - {17293,17292,17394 ,726,5470,5470 ,0,0,0}, {17400,17412,17411 ,726,726,726 ,0,0,0}, - {17392,17401,17598 ,726,726,5471 ,0,0,0}, {17598,17393,17392 ,5471,726,726 ,0,0,0}, - {17400,17399,17412 ,726,5470,726 ,0,0,0}, {17401,17400,17598 ,726,726,5471 ,0,0,0}, - {17397,17411,17398 ,5470,726,726 ,0,0,0}, {17379,17402,16285 ,726,726,726 ,0,0,0}, - {16271,16269,17297 ,726,726,5469 ,0,0,0}, {17380,16281,17599 ,5470,726,5470 ,0,0,0}, - {16280,17377,17599 ,726,5469,5470 ,0,0,0}, {17599,16281,16280 ,5470,726,726 ,0,0,0}, - {17376,16275,17345 ,5468,726,726 ,0,0,0}, {16275,17376,16277 ,726,5468,726 ,0,0,0}, - {16274,17345,16275 ,5471,726,726 ,0,0,0}, {17417,16268,16243 ,726,5471,5471 ,0,0,0}, - {16243,16242,17416 ,5471,5471,5470 ,0,0,0}, {17291,16268,17417 ,5469,5471,726 ,0,0,0}, - {17600,17601,16245 ,5470,5470,726 ,0,0,0}, {17573,16248,16251 ,726,5470,726 ,0,0,0}, - {17601,16242,16245 ,5470,5471,726 ,0,0,0}, {16252,16257,17602 ,726,726,726 ,0,0,0}, - {16252,17603,16251 ,726,5470,726 ,0,0,0}, {17604,16257,16255 ,726,726,5470 ,0,0,0}, - {16144,16146,15883 ,726,726,726 ,0,0,0}, {16260,16141,16254 ,726,726,5471 ,0,0,0}, - {16157,17605,16160 ,726,726,5470 ,0,0,0}, {16231,17606,16233 ,726,5471,5471 ,0,0,0}, - {17607,15989,15992 ,5471,5470,726 ,0,0,0}, {17608,15862,17609 ,726,726,5470 ,0,0,0}, - {16179,15893,17610 ,5471,5470,5470 ,0,0,0}, {17611,17612,16175 ,726,5471,726 ,0,0,0}, - {15869,16222,15868 ,726,5471,726 ,0,0,0}, {16340,16339,16214 ,5468,726,5471 ,0,0,0}, - {16264,16142,16260 ,5470,5471,726 ,0,0,0}, {16155,16154,17613 ,726,726,726 ,0,0,0}, - {15882,15856,16254 ,5470,5471,5471 ,0,0,0}, {17604,17602,16257 ,726,726,726 ,0,0,0}, - {17602,17603,16252 ,726,5470,726 ,0,0,0}, {17603,17574,16251 ,5470,5471,726 ,0,0,0}, - {16248,17600,16245 ,5470,5470,726 ,0,0,0}, {17600,16248,17573 ,5470,5470,726 ,0,0,0}, - {17298,16241,16239 ,5468,5469,726 ,0,0,0}, {17601,17416,16242 ,5470,5470,5471 ,0,0,0}, - {16269,16241,17297 ,726,5469,5469 ,0,0,0}, {17290,16269,16268 ,5468,726,5471 ,0,0,0}, - {17290,16241,16269 ,5468,5469,726 ,0,0,0}, {16239,16237,17596 ,726,5468,726 ,0,0,0}, - {16239,17596,17298 ,726,726,5468 ,0,0,0}, {16236,17568,17596 ,726,726,726 ,0,0,0}, - {16233,17606,17568 ,5471,5471,726 ,0,0,0}, {16230,17595,17528 ,5469,5468,5468 ,0,0,0}, - {16231,17528,17606 ,726,5468,5471 ,0,0,0}, {16211,16210,16339 ,5469,5468,726 ,0,0,0}, - {16230,16211,17595 ,5469,5469,5468 ,0,0,0}, {16214,16218,16340 ,5471,726,5468 ,0,0,0}, - {16210,16214,16339 ,5468,5471,726 ,0,0,0}, {16218,16217,16336 ,726,5471,5469 ,0,0,0}, - {15869,15872,16220 ,726,726,5469 ,0,0,0}, {15868,16222,16224 ,726,5471,5470 ,0,0,0}, - {17575,17609,15863 ,5471,5470,5471 ,0,0,0}, {15866,15868,16224 ,5471,726,5470 ,0,0,0}, - {17608,17604,15860 ,726,726,5470 ,0,0,0}, {16263,17614,16135 ,5470,5470,726 ,0,0,0}, - {16160,17615,16161 ,5470,5470,5470 ,0,0,0}, {17572,16133,16131 ,726,5489,726 ,0,0,0}, - {17458,16128,16125 ,726,726,726 ,0,0,0}, {17616,17472,17419 ,5489,5488,726 ,0,0,0}, - {17472,17616,17434 ,5488,5489,5489 ,0,0,0}, {17435,17413,17436 ,726,726,726 ,0,0,0}, - {17415,17617,17432 ,5489,726,726 ,0,0,0}, {17433,17432,17617 ,726,726,726 ,0,0,0}, - {17414,17413,17435 ,5488,726,726 ,0,0,0}, {17414,17617,17415 ,5488,726,5489 ,0,0,0}, - {17436,17280,17437 ,726,726,726 ,0,0,0}, {17281,17425,17282 ,726,726,726 ,0,0,0}, - {17441,17423,17439 ,5489,726,726 ,0,0,0}, {17423,17281,17439 ,726,726,726 ,0,0,0}, - {17427,17444,17428 ,726,726,726 ,0,0,0}, {17442,17441,17440 ,726,5489,726 ,0,0,0}, - {17444,17443,17428 ,726,726,726 ,0,0,0}, {17443,17442,17445 ,726,726,5488 ,0,0,0}, - {17427,17426,17289 ,726,5489,726 ,0,0,0}, {17448,17289,17446 ,726,726,5489 ,0,0,0}, - {16195,16193,17284 ,5471,726,5471 ,0,0,0}, {17289,17459,17287 ,726,726,726 ,0,0,0}, - {16204,17384,17459 ,5471,726,726 ,0,0,0}, {17459,16205,16204 ,726,726,5471 ,0,0,0}, - {17383,16199,17422 ,5471,726,726 ,0,0,0}, {16199,17383,16201 ,726,5471,5471 ,0,0,0}, - {16198,17422,16199 ,726,726,726 ,0,0,0}, {17618,16167,17455 ,5471,726,726 ,0,0,0}, - {16167,16166,17456 ,726,726,726 ,0,0,0}, {16192,16167,17618 ,726,726,5471 ,0,0,0}, - {17619,17620,16169 ,726,726,726 ,0,0,0}, {17612,16172,16175 ,5471,726,726 ,0,0,0}, - {17620,16166,16169 ,726,726,726 ,0,0,0}, {16176,16181,17621 ,726,726,726 ,0,0,0}, - {16176,17622,16175 ,726,5471,726 ,0,0,0}, {17610,16181,16179 ,5470,726,5471 ,0,0,0}, - {15898,16065,16068 ,5471,5471,726 ,0,0,0}, {16184,16065,16178 ,726,5471,726 ,0,0,0}, - {17623,15893,15892 ,5471,5470,726 ,0,0,0}, {16157,16155,17624 ,726,726,726 ,0,0,0}, - {15898,15895,16178 ,5471,726,726 ,0,0,0}, {16079,17625,16081 ,726,5470,726 ,0,0,0}, - {15986,16112,16111 ,5470,726,726 ,0,0,0}, {16099,17626,16096 ,726,726,5471 ,0,0,0}, - {16146,15886,15883 ,726,726,726 ,0,0,0}, {16264,16263,16138 ,5470,5470,726 ,0,0,0}, - {16188,16066,16184 ,5471,726,726 ,0,0,0}, {17588,16105,16103 ,726,726,726 ,0,0,0}, - {16178,15895,16179 ,726,726,5471 ,0,0,0}, {17610,17621,16181 ,5470,726,726 ,0,0,0}, - {17621,17622,16176 ,726,5471,726 ,0,0,0}, {17622,17611,16175 ,5471,726,726 ,0,0,0}, - {16172,17619,16169 ,726,726,726 ,0,0,0}, {17619,16172,17612 ,726,726,5471 ,0,0,0}, - {17627,16165,16163 ,5470,726,726 ,0,0,0}, {17620,17456,16166 ,726,726,726 ,0,0,0}, - {16193,16165,17284 ,726,726,5471 ,0,0,0}, {16165,16193,17429 ,726,726,5471 ,0,0,0}, - {17618,17429,16192 ,5471,5471,726 ,0,0,0}, {16165,17627,17285 ,726,5470,726 ,0,0,0}, - {16163,16161,17615 ,726,5470,5470 ,0,0,0}, {16163,17615,17627 ,726,5470,5470 ,0,0,0}, - {16160,17605,17615 ,5470,726,5470 ,0,0,0}, {16157,17624,17605 ,726,726,726 ,0,0,0}, - {16154,17614,17613 ,726,5470,726 ,0,0,0}, {16155,17613,17624 ,726,726,726 ,0,0,0}, - {16135,16134,16263 ,726,5470,5470 ,0,0,0}, {16154,16135,17614 ,726,726,5470 ,0,0,0}, - {16138,16142,16264 ,726,5471,5470 ,0,0,0}, {16134,16138,16263 ,5470,726,5470 ,0,0,0}, - {16142,16141,16260 ,5471,726,726 ,0,0,0}, {15883,15882,16144 ,726,5470,726 ,0,0,0}, - {15886,16148,15887 ,726,726,5471 ,0,0,0}, {15889,15887,17569 ,726,5471,726 ,0,0,0}, - {16146,16148,15886 ,726,726,726 ,0,0,0}, {17610,15893,17623 ,5470,5470,5471 ,0,0,0}, - {16129,17571,16131 ,5488,726,726 ,0,0,0}, {16331,15876,17533 ,5468,5470,726 ,0,0,0}, - {16055,17420,16057 ,5470,726,5470 ,0,0,0}, {17476,16052,16049 ,726,726,726 ,0,0,0}, - {17460,17628,17461 ,5471,726,726 ,0,0,0}, {17451,17461,17452 ,5471,726,726 ,0,0,0}, - {17497,17629,17464 ,726,5471,5471 ,0,0,0}, {17450,17464,17629 ,726,5471,5471 ,0,0,0}, - {17469,17527,17497 ,726,726,726 ,0,0,0}, {17527,17629,17497 ,726,5471,726 ,0,0,0}, - {17480,17490,17469 ,726,726,726 ,0,0,0}, {17630,17470,17469 ,726,726,726 ,0,0,0}, - {17467,17469,17482 ,726,726,726 ,0,0,0}, {17483,17482,17469 ,5488,726,726 ,0,0,0}, - {17525,17486,17526 ,5489,726,726 ,0,0,0}, {17485,17482,17481 ,726,726,726 ,0,0,0}, - {17486,17487,17526 ,726,726,726 ,0,0,0}, {17487,17485,17484 ,726,726,726 ,0,0,0}, - {17466,17525,17488 ,726,5489,726 ,0,0,0}, {17572,17465,16133 ,726,726,5489 ,0,0,0}, - {16117,16116,17419 ,726,5471,726 ,0,0,0}, {16128,17631,16129 ,726,726,5488 ,0,0,0}, - {17571,16129,17631 ,726,5488,726 ,0,0,0}, {17457,16123,17473 ,726,726,726 ,0,0,0}, - {17458,17631,16128 ,726,726,726 ,0,0,0}, {16123,17457,16125 ,726,726,726 ,0,0,0}, - {16122,17473,16123 ,726,726,726 ,0,0,0}, {17529,17419,17632 ,5470,726,5471 ,0,0,0}, - {17632,16091,17532 ,5471,726,5471 ,0,0,0}, {17632,17419,16091 ,5471,726,726 ,0,0,0}, - {16093,17633,16090 ,5471,726,726 ,0,0,0}, {16099,17634,17626 ,726,726,726 ,0,0,0}, - {16093,17635,17633 ,5471,726,726 ,0,0,0}, {17636,16084,16081 ,5471,726,726 ,0,0,0}, - {16084,17637,16085 ,726,726,726 ,0,0,0}, {17638,16079,16078 ,726,726,5471 ,0,0,0}, - {16187,17639,16059 ,5471,5471,5471 ,0,0,0}, {16062,16188,16187 ,726,5471,5471 ,0,0,0}, - {15898,16178,16065 ,5471,726,5471 ,0,0,0}, {17640,17641,17642 ,5470,726,726 ,0,0,0}, - {17643,15905,16075 ,726,5470,5471 ,0,0,0}, {16111,17644,15983 ,726,726,726 ,0,0,0}, - {17645,16009,16008 ,5471,5470,5471 ,0,0,0}, {16008,16005,17646 ,5471,726,726 ,0,0,0}, - {16108,15989,16102 ,726,5470,726 ,0,0,0}, {15901,16068,16070 ,5471,726,726 ,0,0,0}, - {16112,15990,16108 ,726,5471,726 ,0,0,0}, {16002,17647,16003 ,726,726,5471 ,0,0,0}, - {16102,17648,16103 ,726,726,726 ,0,0,0}, {17588,17385,16105 ,726,5470,726 ,0,0,0}, - {17385,17593,16100 ,5470,726,726 ,0,0,0}, {17593,17634,16099 ,726,726,726 ,0,0,0}, - {16096,17635,16093 ,5471,726,5471 ,0,0,0}, {17635,16096,17626 ,726,5471,726 ,0,0,0}, - {17637,17649,16087 ,726,726,726 ,0,0,0}, {16087,17649,17419 ,726,726,726 ,0,0,0}, - {17633,17532,16090 ,726,5471,726 ,0,0,0}, {16119,16117,17419 ,726,726,726 ,0,0,0}, - {17419,16116,16091 ,726,5471,726 ,0,0,0}, {16089,17419,17530 ,5471,726,5471 ,0,0,0}, - {17649,17616,17419 ,726,5489,726 ,0,0,0}, {16087,16085,17637 ,726,726,726 ,0,0,0}, - {16084,17636,17637 ,726,5471,726 ,0,0,0}, {16081,17625,17636 ,726,5470,5471 ,0,0,0}, - {16078,17639,17638 ,5471,5471,726 ,0,0,0}, {16079,17638,17625 ,726,726,5470 ,0,0,0}, - {16059,16058,16187 ,5471,726,5471 ,0,0,0}, {16078,16059,17639 ,5471,5471,5471 ,0,0,0}, - {16062,16066,16188 ,726,726,5471 ,0,0,0}, {16058,16062,16187 ,726,726,5471 ,0,0,0}, - {16066,16065,16184 ,726,5471,726 ,0,0,0}, {15901,15898,16068 ,5471,5471,726 ,0,0,0}, - {15901,16070,15904 ,5471,726,726 ,0,0,0}, {16072,15905,15904 ,726,5470,726 ,0,0,0}, - {16072,15904,16070 ,726,726,726 ,0,0,0}, {16072,16075,15905 ,726,5471,5470 ,0,0,0}, - {17650,15948,15953 ,5468,5469,5470 ,0,0,0}, {17506,17518,17513 ,5468,5469,726 ,0,0,0}, - {16293,15956,16294 ,5468,5471,5469 ,0,0,0}, {15976,15973,17506 ,5469,5471,5468 ,0,0,0}, - {15937,17519,17518 ,5469,726,5469 ,0,0,0}, {17517,17519,17511 ,726,726,726 ,0,0,0}, - {17551,17548,17550 ,726,5471,726 ,0,0,0}, {17547,17651,17509 ,5471,5468,5471 ,0,0,0}, - {17510,17509,17651 ,5468,5471,5468 ,0,0,0}, {17549,17548,17551 ,5468,5471,726 ,0,0,0}, - {17549,17651,17547 ,5468,5468,5471 ,0,0,0}, {17550,17515,17514 ,726,5470,726 ,0,0,0}, - {17522,17521,17516 ,726,5469,5469 ,0,0,0}, {17541,17520,17542 ,5470,5471,726 ,0,0,0}, - {17520,17522,17542 ,5471,726,726 ,0,0,0}, {17538,17534,17536 ,726,726,5471 ,0,0,0}, - {17540,17539,17652 ,726,5470,726 ,0,0,0}, {17652,17541,17540 ,726,5470,726 ,0,0,0}, - {17538,17537,17534 ,726,5471,726 ,0,0,0}, {17539,17538,17652 ,5470,726,726 ,0,0,0}, - {17505,17536,17535 ,726,5471,5470 ,0,0,0}, {17420,17504,16057 ,726,726,5470 ,0,0,0}, - {16043,16041,17460 ,726,5470,5471 ,0,0,0}, {16052,17653,16053 ,726,726,726 ,0,0,0}, - {17421,16053,17653 ,726,726,726 ,0,0,0}, {17475,16047,17531 ,5471,5470,726 ,0,0,0}, - {17476,17653,16052 ,726,726,726 ,0,0,0}, {16047,17475,16049 ,5470,5471,726 ,0,0,0}, - {16046,17531,16047 ,5470,726,5470 ,0,0,0}, {17587,16040,16015 ,5471,5471,5471 ,0,0,0}, - {16015,16014,17586 ,5471,726,5471 ,0,0,0}, {17501,16040,17587 ,5471,5471,5471 ,0,0,0}, - {17654,17655,16017 ,5471,726,726 ,0,0,0}, {17462,16020,16023 ,726,5470,5470 ,0,0,0}, - {17655,16014,16017 ,726,726,726 ,0,0,0}, {16024,16029,17656 ,5470,726,726 ,0,0,0}, - {16024,17657,16023 ,5470,726,5470 ,0,0,0}, {17658,16029,16027 ,726,726,726 ,0,0,0}, - {15916,15918,17659 ,726,5471,5471 ,0,0,0}, {16003,17660,16005 ,5471,726,726 ,0,0,0}, - {17661,17662,17663 ,5471,726,726 ,0,0,0}, {15951,17661,17664 ,5471,5471,5471 ,0,0,0}, - {17533,15876,17665 ,726,5470,5469 ,0,0,0}, {16293,16296,17666 ,5468,5468,5470 ,0,0,0}, - {15932,17667,15933 ,726,726,5471 ,0,0,0}, {15951,17664,15953 ,5471,5471,5470 ,0,0,0}, - {16032,15913,16026 ,726,5470,5470 ,0,0,0}, {15994,17668,17669 ,5470,5471,726 ,0,0,0}, - {16036,15914,16032 ,726,5471,726 ,0,0,0}, {17670,17659,15918 ,5471,5471,5471 ,0,0,0}, - {17671,17672,16026 ,726,5471,5470 ,0,0,0}, {17658,17656,16029 ,726,726,726 ,0,0,0}, - {17656,17657,16024 ,726,726,5470 ,0,0,0}, {17657,17463,16023 ,726,726,5470 ,0,0,0}, - {16020,17654,16017 ,5470,5471,726 ,0,0,0}, {17654,16020,17462 ,5471,5470,726 ,0,0,0}, - {16011,17645,17628 ,5471,5471,726 ,0,0,0}, {17628,16013,16011 ,726,726,5471 ,0,0,0}, - {17655,17586,16014 ,726,5471,726 ,0,0,0}, {16041,16013,17460 ,5470,726,5471 ,0,0,0}, - {17500,16041,16040 ,726,5470,5471 ,0,0,0}, {17500,16013,16041 ,726,726,5470 ,0,0,0}, - {17460,16013,17628 ,5471,726,726 ,0,0,0}, {16011,16009,17645 ,5471,5470,5471 ,0,0,0}, - {16008,17646,17645 ,5471,726,5471 ,0,0,0}, {16005,17660,17646 ,726,726,726 ,0,0,0}, - {16002,17644,17647 ,726,726,726 ,0,0,0}, {16003,17647,17660 ,5471,726,726 ,0,0,0}, - {15983,15982,16111 ,726,5471,726 ,0,0,0}, {16002,15983,17644 ,726,726,726 ,0,0,0}, - {15986,15990,16112 ,5470,5471,726 ,0,0,0}, {15982,15986,16111 ,5471,5470,726 ,0,0,0}, - {15990,15989,16108 ,5471,5470,726 ,0,0,0}, {17669,17607,15992 ,726,5471,726 ,0,0,0}, - {16102,15989,17607 ,726,5470,5471 ,0,0,0}, {15999,17673,17674 ,726,726,726 ,0,0,0}, - {17668,15996,17674 ,5471,726,726 ,0,0,0}, {17675,17676,17677 ,5470,5470,5471 ,0,0,0}, - {15979,17582,15981 ,5468,5470,5483 ,0,0,0}, {16287,16286,15959 ,726,5468,5468 ,0,0,0}, - {15979,15977,17581 ,5468,5469,5470 ,0,0,0}, {16315,17279,17578 ,726,5468,5468 ,0,0,0}, - {16312,17580,17279 ,5469,726,5468 ,0,0,0}, {17578,17579,17299 ,5468,5468,5469 ,0,0,0}, - {17308,17579,17309 ,5476,5468,5471 ,0,0,0}, {17336,17339,17334 ,5468,5468,5475 ,0,0,0}, - {17338,17678,17564 ,5483,726,5468 ,0,0,0}, {17307,17564,17678 ,5475,5468,726 ,0,0,0}, - {17337,17339,17336 ,5486,5468,5468 ,0,0,0}, {17337,17678,17338 ,5486,726,5483 ,0,0,0}, - {17334,17311,17335 ,5475,5478,5485 ,0,0,0}, {17312,17323,17310 ,5469,5468,5477 ,0,0,0}, - {17316,17322,17314 ,726,726,5471 ,0,0,0}, {17322,17312,17314 ,726,5469,5471 ,0,0,0}, - {17566,17320,17567 ,5472,5480,5482 ,0,0,0}, {17321,17316,17315 ,5481,726,5469 ,0,0,0}, - {17320,17319,17567 ,5480,726,5482 ,0,0,0}, {17319,17321,17331 ,726,5481,5475 ,0,0,0}, - {17324,17566,17327 ,5475,5472,5468 ,0,0,0}, {17582,17325,15981 ,5470,5475,5483 ,0,0,0}, - {17506,15965,17583 ,5468,726,5468 ,0,0,0}, {15976,17508,15977 ,5469,5469,5469 ,0,0,0}, - {17581,15977,17508 ,5470,5469,5469 ,0,0,0}, {17679,17507,17506 ,5468,726,5468 ,0,0,0}, - {17508,15976,17506 ,5469,5469,5468 ,0,0,0}, {17506,15973,15971 ,5468,5471,5470 ,0,0,0}, - {17506,15970,15967 ,5468,5469,5471 ,0,0,0}, {17680,15939,17584 ,5469,5468,5469 ,0,0,0}, - {15939,15938,17585 ,5468,5471,5471 ,0,0,0}, {15964,15939,17680 ,5468,5468,5469 ,0,0,0}, - {17681,17682,15941 ,5470,5471,5468 ,0,0,0}, {17502,15944,15947 ,5470,726,5468 ,0,0,0}, - {17682,15938,15941 ,5471,5471,5468 ,0,0,0}, {16296,16298,17683 ,5468,5468,5468 ,0,0,0}, - {15910,16036,16035 ,5471,726,726 ,0,0,0}, {15948,17684,15947 ,5469,5469,5468 ,0,0,0}, - {17685,15927,15926 ,726,5471,726 ,0,0,0}, {17686,15932,15929 ,726,726,5470 ,0,0,0}, - {17687,15907,16035 ,726,5470,726 ,0,0,0}, {17688,15929,15927 ,726,5470,5471 ,0,0,0}, - {16293,15950,15956 ,5468,5469,5471 ,0,0,0}, {16296,17683,17666 ,5468,5468,5470 ,0,0,0}, - {15956,15960,16294 ,5471,726,5469 ,0,0,0}, {15959,16290,15960 ,5468,5468,726 ,0,0,0}, - {16294,15960,16290 ,5469,726,5468 ,0,0,0}, {15875,17577,17665 ,5469,5469,5469 ,0,0,0}, - {16300,15880,17689 ,5471,5470,726 ,0,0,0}, {15880,17576,15878 ,5470,5469,726 ,0,0,0}, - {15950,17690,15951 ,5469,5471,5471 ,0,0,0}, {17664,17650,15953 ,5471,5468,5470 ,0,0,0}, - {17650,17684,15948 ,5468,5469,5469 ,0,0,0}, {17684,17503,15947 ,5469,5468,5468 ,0,0,0}, - {15944,17681,15941 ,726,5470,5468 ,0,0,0}, {17681,15944,17502 ,5470,726,5470 ,0,0,0}, - {15935,17667,17691 ,726,726,5471 ,0,0,0}, {17691,15937,15935 ,5471,5469,726 ,0,0,0}, - {17682,17585,15938 ,5471,5471,5471 ,0,0,0}, {15937,17518,17506 ,5469,5469,5468 ,0,0,0}, - {17506,17583,15937 ,5468,5468,5469 ,0,0,0}, {17680,17583,15964 ,5469,5468,5468 ,0,0,0}, - {15937,17691,17519 ,5469,5471,726 ,0,0,0}, {15935,15933,17667 ,726,5471,726 ,0,0,0}, - {15932,17686,17667 ,726,726,726 ,0,0,0}, {15929,17688,17686 ,5470,726,726 ,0,0,0}, - {15926,17687,17685 ,726,726,726 ,0,0,0}, {15927,17685,17688 ,5471,726,726 ,0,0,0}, - {15907,15906,16035 ,5470,726,726 ,0,0,0}, {15926,15907,17687 ,726,5470,726 ,0,0,0}, - {15910,15914,16036 ,5471,5471,726 ,0,0,0}, {15906,15910,16035 ,726,5471,726 ,0,0,0}, - {15914,15913,16032 ,5471,5470,726 ,0,0,0}, {17659,17671,15916 ,5471,726,726 ,0,0,0}, - {17670,15920,17692 ,5471,726,726 ,0,0,0}, {17590,17692,17591 ,5471,726,5470 ,0,0,0}, - {15918,15920,17670 ,5471,726,5471 ,0,0,0}, {17664,17661,17663 ,5471,5471,726 ,0,0,0}, - {17658,16027,17693 ,726,726,5471 ,0,0,0}, {17604,16255,15860 ,726,5470,5470 ,0,0,0}, - {17658,17693,17675 ,726,5471,5470 ,0,0,0}, {15895,15893,16179 ,726,5470,5471 ,0,0,0}, - {15889,17570,15892 ,726,5470,726 ,0,0,0}, {17623,15892,17570 ,5471,726,5470 ,0,0,0}, - {16255,16254,15856 ,5470,5471,5471 ,0,0,0}, {16151,15887,16148 ,726,5471,726 ,0,0,0}, - {16151,17569,15887 ,726,726,5471 ,0,0,0}, {15882,16254,16141 ,5470,5471,726 ,0,0,0}, - {16141,16144,15882 ,726,726,5470 ,0,0,0}, {16255,15856,15860 ,5470,5471,5470 ,0,0,0}, - {17608,15860,15862 ,726,5470,726 ,0,0,0}, {15874,16330,15872 ,5471,5469,726 ,0,0,0}, - {17609,15862,15863 ,5470,726,5471 ,0,0,0}, {16227,15866,16224 ,726,5471,5470 ,0,0,0}, - {16227,17575,15866 ,726,5471,5471 ,0,0,0}, {16330,16217,15872 ,5469,5471,726 ,0,0,0}, - {16217,16220,15872 ,5471,5469,726 ,0,0,0}, {15874,15876,16331 ,5471,5470,5468 ,0,0,0}, - {17665,15876,15875 ,5469,5470,5469 ,0,0,0}, {17690,15950,17666 ,5471,5469,5470 ,0,0,0}, - {17577,15875,15878 ,5469,5469,726 ,0,0,0}, {16303,15880,16300 ,5469,5470,5471 ,0,0,0}, - {16303,17576,15880 ,5469,5469,5470 ,0,0,0}, {17666,15950,16293 ,5470,5469,5468 ,0,0,0}, - {17689,17683,16298 ,726,5468,5468 ,0,0,0}, {17689,16298,16300 ,726,5468,5471 ,0,0,0}, - {17690,17661,15951 ,5471,5471,5471 ,0,0,0}, {17590,17592,17662 ,5471,5471,726 ,0,0,0}, - {17663,17662,17592 ,726,726,5471 ,0,0,0}, {16027,16026,17672 ,726,5470,5471 ,0,0,0}, - {15923,17692,15920 ,726,726,726 ,0,0,0}, {15923,17591,17692 ,726,5470,726 ,0,0,0}, - {17671,16026,15913 ,726,5470,5470 ,0,0,0}, {15913,15916,17671 ,5470,726,726 ,0,0,0}, - {16027,17672,17693 ,726,5471,5471 ,0,0,0}, {17677,17676,17694 ,5471,5470,726 ,0,0,0}, - {17675,17693,17676 ,5470,5471,5470 ,0,0,0}, {17694,17674,17673 ,726,726,726 ,0,0,0}, - {17673,17677,17694 ,726,5471,726 ,0,0,0}, {17674,15996,15999 ,726,726,726 ,0,0,0}, - {17668,15994,15996 ,5471,5470,726 ,0,0,0}, {17669,15992,15994 ,726,726,5470 ,0,0,0}, - {16102,17607,17648 ,726,5471,726 ,0,0,0}, {17589,17695,17588 ,5471,5471,726 ,0,0,0}, - {16103,17648,17589 ,726,726,5471 ,0,0,0}, {17641,17695,17642 ,726,5471,726 ,0,0,0}, - {17589,17642,17695 ,5471,726,5471 ,0,0,0}, {17641,17640,17643 ,726,5470,726 ,0,0,0}, - {15905,17643,17640 ,5470,726,5470 ,0,0,0}, {17679,17506,17512 ,5468,5468,5468 ,0,0,0}, - {15971,15970,17506 ,5470,5469,5468 ,0,0,0}, {17469,17489,17483 ,726,726,5488 ,0,0,0}, - {17478,17630,17469 ,5488,726,726 ,0,0,0}, {17419,16089,16087 ,726,5471,726 ,0,0,0}, - {17594,17419,17474 ,726,726,726 ,0,0,0}, {17560,17559,17557 ,5469,5470,5468 ,0,0,0}, - {17560,17302,17558 ,5469,5468,5469 ,0,0,0}, {17446,17289,17288 ,5489,726,726 ,0,0,0}, - {16209,16207,17289 ,726,726,726 ,0,0,0}, {17696,17697,17698 ,5490,5491,5492 ,0,0,0}, - {17699,17700,17701 ,5493,5494,5495 ,0,0,0}, {17702,17700,17703 ,5496,5494,5497 ,0,0,0}, - {17704,17705,17706 ,5498,5499,5500 ,0,0,0}, {17707,17708,17709 ,5501,5502,5503 ,0,0,0}, - {17710,17711,17712 ,5504,5505,5506 ,0,0,0}, {17713,17714,17715 ,5507,5508,5509 ,0,0,0}, - {17326,17330,17710 ,5510,5511,5504 ,0,0,0}, {17716,17717,17718 ,5512,5513,5514 ,0,0,0}, - {17707,17712,17711 ,5501,5506,5505 ,0,0,0}, {17719,17720,17717 ,5515,5516,5513 ,0,0,0}, - {17721,17719,17717 ,5517,5515,5513 ,0,0,0}, {17721,17722,17719 ,5517,5518,5515 ,0,0,0}, - {17722,17721,17723 ,5518,5517,5519 ,0,0,0}, {17724,17720,17725 ,5520,5516,5521 ,0,0,0}, - {17726,17727,17728 ,5522,5523,5524 ,0,0,0}, {17717,17720,17724 ,5513,5516,5520 ,0,0,0}, - {17728,17727,17723 ,5524,5523,5519 ,0,0,0}, {17729,17726,17730 ,5525,5522,5526 ,0,0,0}, - {17731,17732,17733 ,5527,5528,5529 ,0,0,0}, {17731,17724,17725 ,5527,5520,5521 ,0,0,0}, - {17734,17735,17736 ,5530,5531,5532 ,0,0,0}, {17731,17725,17732 ,5527,5521,5528 ,0,0,0}, - {17732,17734,17733 ,5528,5530,5529 ,0,0,0}, {17737,17738,17736 ,5533,5534,5532 ,0,0,0}, - {17714,17739,17715 ,5508,5535,5509 ,0,0,0}, {17736,17735,17737 ,5532,5531,5533 ,0,0,0}, - {17740,17699,17741 ,5536,5493,5537 ,0,0,0}, {17735,17742,17737 ,5531,5538,5533 ,0,0,0}, - {17714,17718,17739 ,5508,5514,5535 ,0,0,0}, {17743,17718,17724 ,5539,5514,5520 ,0,0,0}, - {17744,17745,17746 ,5540,5541,5542 ,0,0,0}, {17747,17744,17748 ,5543,5540,5544 ,0,0,0}, - {17305,17322,17697 ,5545,5546,5491 ,0,0,0}, {17749,17750,17751 ,5547,5548,5549 ,0,0,0}, - {17305,17696,17306 ,5545,5490,726 ,0,0,0}, {17752,17306,17696 ,5550,726,5490 ,0,0,0}, - {17753,17738,17754 ,5551,5534,5552 ,0,0,0}, {17734,17736,17733 ,5530,5532,5529 ,0,0,0}, - {17736,17738,17753 ,5532,5534,5551 ,0,0,0}, {17754,17755,17753 ,5552,5553,5551 ,0,0,0}, - {17756,17733,17753 ,5554,5529,5551 ,0,0,0}, {17718,17743,17739 ,5514,5539,5535 ,0,0,0}, - {17756,17743,17731 ,5554,5539,5527 ,0,0,0}, {17721,17757,17723 ,5517,5555,5519 ,0,0,0}, - {17731,17743,17724 ,5527,5539,5520 ,0,0,0}, {17758,17759,17728 ,5556,5557,5524 ,0,0,0}, - {17717,17724,17718 ,5513,5520,5514 ,0,0,0}, {17757,17721,17716 ,5555,5517,5512 ,0,0,0}, - {17726,17728,17730 ,5522,5524,5526 ,0,0,0}, {17722,17723,17727 ,5518,5519,5523 ,0,0,0}, - {17723,17757,17758 ,5519,5555,5556 ,0,0,0}, {17760,17730,17728 ,5558,5526,5524 ,0,0,0}, - {17736,17753,17733 ,5532,5551,5529 ,0,0,0}, {17761,17755,17754 ,5559,5553,5552 ,0,0,0}, - {17761,17748,17755 ,5559,5544,5553 ,0,0,0}, {17733,17756,17731 ,5529,5554,5527 ,0,0,0}, - {17755,17762,17756 ,5553,5560,5554 ,0,0,0}, {17714,17703,17716 ,5508,5497,5512 ,0,0,0}, - {17762,17739,17743 ,5560,5535,5539 ,0,0,0}, {17699,17759,17758 ,5493,5557,5556 ,0,0,0}, - {17740,17759,17699 ,5536,5557,5493 ,0,0,0}, {17717,17716,17721 ,5513,5512,5517 ,0,0,0}, - {17718,17714,17716 ,5514,5508,5512 ,0,0,0}, {17723,17758,17728 ,5519,5556,5524 ,0,0,0}, - {17703,17700,17757 ,5497,5494,5555 ,0,0,0}, {17728,17759,17760 ,5524,5557,5558 ,0,0,0}, - {17758,17700,17699 ,5556,5494,5493 ,0,0,0}, {17763,17760,17759 ,5561,5558,5557 ,0,0,0}, - {17753,17755,17756 ,5551,5553,5554 ,0,0,0}, {17747,17748,17761 ,5543,5544,5559 ,0,0,0}, - {17764,17746,17765 ,5562,5542,5563 ,0,0,0}, {17756,17762,17743 ,5554,5560,5539 ,0,0,0}, - {17766,17762,17748 ,5564,5560,5544 ,0,0,0}, {17703,17714,17713 ,5497,5508,5507 ,0,0,0}, - {17766,17715,17739 ,5564,5509,5535 ,0,0,0}, {17767,17741,17701 ,5565,5537,5495 ,0,0,0}, - {17757,17700,17758 ,5555,5494,5556 ,0,0,0}, {17716,17703,17757 ,5512,5497,5555 ,0,0,0}, - {17703,17713,17702 ,5497,5507,5496 ,0,0,0}, {17740,17741,17768 ,5536,5537,5566 ,0,0,0}, - {17702,17701,17700 ,5496,5495,5494 ,0,0,0}, {17759,17740,17763 ,5557,5536,5561 ,0,0,0}, - {17699,17701,17741 ,5493,5495,5537 ,0,0,0}, {17769,17763,17740 ,5567,5561,5536 ,0,0,0}, - {17755,17748,17762 ,5553,5544,5560 ,0,0,0}, {17745,17744,17747 ,5541,5540,5543 ,0,0,0}, - {17715,17770,17713 ,5509,5568,5507 ,0,0,0}, {17762,17766,17739 ,5560,5564,5535 ,0,0,0}, - {17771,17766,17744 ,5569,5564,5540 ,0,0,0}, {17713,17772,17702 ,5507,5570,5496 ,0,0,0}, - {17771,17770,17715 ,5569,5568,5509 ,0,0,0}, {17702,17773,17701 ,5496,5571,5495 ,0,0,0}, - {17772,17713,17770 ,5570,5507,5568 ,0,0,0}, {17741,17704,17768 ,5537,5498,5566 ,0,0,0}, - {17773,17702,17772 ,5571,5496,5570 ,0,0,0}, {17774,17768,17706 ,5572,5566,5500 ,0,0,0}, - {17767,17701,17773 ,5565,5495,5571 ,0,0,0}, {17740,17768,17769 ,5536,5566,5567 ,0,0,0}, - {17741,17767,17704 ,5537,5565,5498 ,0,0,0}, {17774,17769,17768 ,5572,5567,5566 ,0,0,0}, - {17748,17744,17766 ,5544,5540,5564 ,0,0,0}, {17765,17746,17745 ,5563,5542,5541 ,0,0,0}, - {17770,17750,17772 ,5568,5548,5570 ,0,0,0}, {17766,17771,17715 ,5564,5569,5509 ,0,0,0}, - {17746,17775,17771 ,5542,5573,5569 ,0,0,0}, {17772,17749,17773 ,5570,5547,5571 ,0,0,0}, - {17775,17750,17770 ,5573,5548,5568 ,0,0,0}, {17773,17776,17767 ,5571,5574,5565 ,0,0,0}, - {17750,17749,17772 ,5548,5547,5570 ,0,0,0}, {17777,17704,17767 ,5575,5498,5565 ,0,0,0}, - {17776,17773,17749 ,5574,5571,5547 ,0,0,0}, {17778,17706,17709 ,5576,5500,5503 ,0,0,0}, - {17767,17776,17777 ,5565,5574,5575 ,0,0,0}, {17777,17705,17704 ,5575,5499,5498 ,0,0,0}, - {17774,17706,17778 ,5572,5500,5576 ,0,0,0}, {17768,17704,17706 ,5566,5498,5500 ,0,0,0}, - {17744,17746,17771 ,5540,5542,5569 ,0,0,0}, {17779,17764,17765 ,5577,5562,5563 ,0,0,0}, - {17780,17776,17749 ,5578,5574,5547 ,0,0,0}, {17771,17775,17770 ,5569,5573,5568 ,0,0,0}, - {17764,17698,17775 ,5562,5492,5573 ,0,0,0}, {17781,17777,17776 ,5579,5575,5574 ,0,0,0}, - {17698,17751,17750 ,5492,5549,5548 ,0,0,0}, {17782,17705,17777 ,5580,5499,5575 ,0,0,0}, - {17751,17780,17749 ,5549,5578,5547 ,0,0,0}, {17712,17707,17783 ,5506,5501,5581 ,0,0,0}, - {17780,17781,17776 ,5578,5579,5574 ,0,0,0}, {17709,17705,17784 ,5503,5499,5582 ,0,0,0}, - {17782,17777,17781 ,5580,5575,5579 ,0,0,0}, {17784,17705,17782 ,5582,5499,5580 ,0,0,0}, - {17778,17709,17708 ,5576,5503,5502 ,0,0,0}, {17706,17705,17709 ,5500,5499,5503 ,0,0,0}, - {17746,17764,17775 ,5542,5562,5573 ,0,0,0}, {17696,17779,17752 ,5490,5577,5550 ,0,0,0}, - {17697,17785,17751 ,5491,5583,5549 ,0,0,0}, {17775,17698,17750 ,5573,5492,5548 ,0,0,0}, - {17697,17751,17698 ,5491,5549,5492 ,0,0,0}, {17785,17786,17780 ,5583,5584,5578 ,0,0,0}, - {17785,17780,17751 ,5583,5578,5549 ,0,0,0}, {17786,17787,17781 ,5584,5585,5579 ,0,0,0}, - {17786,17781,17780 ,5584,5579,5578 ,0,0,0}, {17787,17788,17782 ,5585,5586,5580 ,0,0,0}, - {17787,17782,17781 ,5585,5580,5579 ,0,0,0}, {17788,17783,17784 ,5586,5581,5582 ,0,0,0}, - {17784,17782,17788 ,5582,5580,5586 ,0,0,0}, {17783,17707,17784 ,5581,5501,5582 ,0,0,0}, - {17708,17707,17711 ,5502,5501,5505 ,0,0,0}, {17709,17784,17707 ,5503,5582,5501 ,0,0,0}, - {17779,17696,17764 ,5577,5490,5562 ,0,0,0}, {17698,17764,17696 ,5492,5562,5490 ,0,0,0}, - {17785,17322,17316 ,5583,5546,5587 ,0,0,0}, {17305,17697,17696 ,5545,5491,5490 ,0,0,0}, - {17786,17316,17321 ,5584,5587,5588 ,0,0,0}, {17322,17785,17697 ,5546,5583,5491 ,0,0,0}, - {17787,17321,17320 ,5585,5588,5589 ,0,0,0}, {17316,17786,17785 ,5587,5584,5583 ,0,0,0}, - {17788,17320,17566 ,5586,5589,5590 ,0,0,0}, {17321,17787,17786 ,5588,5585,5584 ,0,0,0}, - {17783,17566,17324 ,5581,5590,5591 ,0,0,0}, {17320,17788,17787 ,5589,5586,5585 ,0,0,0}, - {17712,17324,17326 ,5506,5591,5510 ,0,0,0}, {17566,17783,17788 ,5590,5581,5586 ,0,0,0}, - {17326,17710,17712 ,5510,5504,5506 ,0,0,0}, {17324,17712,17783 ,5591,5506,5581 ,0,0,0}, - {17789,17790,17791 ,5592,5593,5594 ,0,0,0}, {17792,17793,17794 ,5595,5596,5597 ,0,0,0}, - {17790,17795,17791 ,5593,5598,5594 ,0,0,0}, {17796,17794,17793 ,5599,5597,5596 ,0,0,0}, - {17797,17798,17799 ,5600,5601,5602 ,0,0,0}, {17800,17801,17798 ,5603,5604,5601 ,0,0,0}, - {17802,17803,17804 ,5605,5606,5607 ,0,0,0}, {17805,17801,17800 ,5608,5604,5603 ,0,0,0}, - {17801,17799,17798 ,5604,5602,5601 ,0,0,0}, {17806,17798,17792 ,5609,5601,5595 ,0,0,0}, - {17807,17808,17809 ,5610,5611,5612 ,0,0,0}, {17810,17811,17812 ,5613,5614,5615 ,0,0,0}, - {17813,17808,17814 ,5616,5611,5617 ,0,0,0}, {17815,17816,17789 ,5618,5619,5592 ,0,0,0}, - {17803,17552,17520 ,5606,5620,5621 ,0,0,0}, {17817,17818,17819 ,5622,5623,5624 ,0,0,0}, - {17820,17554,17802 ,5625,5626,5605 ,0,0,0}, {17552,17802,17554 ,5620,5605,5626 ,0,0,0}, - {17821,17822,17823 ,5627,5628,5629 ,0,0,0}, {17795,17824,17791 ,5598,5630,5594 ,0,0,0}, - {17825,17826,17827 ,5631,5632,5633 ,0,0,0}, {17828,17829,17830 ,5634,5635,5636 ,0,0,0}, - {17819,17822,17831 ,5624,5628,5637 ,0,0,0}, {17832,17833,17834 ,5638,5639,5640 ,0,0,0}, - {17835,17789,17836 ,5641,5592,5642 ,0,0,0}, {17833,17828,17834 ,5639,5634,5640 ,0,0,0}, - {17815,17796,17793 ,5618,5599,5596 ,0,0,0}, {17543,17546,17832 ,5643,5644,5638 ,0,0,0}, - {17796,17815,17837 ,5599,5618,5645 ,0,0,0}, {17837,17815,17835 ,5645,5618,5641 ,0,0,0}, - {17838,17839,17835 ,5646,5647,5641 ,0,0,0}, {17815,17793,17816 ,5618,5596,5619 ,0,0,0}, - {17838,17840,17841 ,5646,5648,5649 ,0,0,0}, {17841,17839,17838 ,5649,5647,5646 ,0,0,0}, - {17842,17843,17844 ,5650,5651,5652 ,0,0,0}, {17843,17842,17840 ,5651,5650,5648 ,0,0,0}, - {17800,17798,17806 ,5603,5601,5609 ,0,0,0}, {17845,17797,17799 ,5653,5600,5602 ,0,0,0}, - {17845,17846,17797 ,5653,5654,5600 ,0,0,0}, {17806,17792,17794 ,5609,5595,5597 ,0,0,0}, - {17847,17792,17797 ,5655,5595,5600 ,0,0,0}, {17789,17816,17790 ,5592,5619,5593 ,0,0,0}, - {17847,17816,17793 ,5655,5619,5596 ,0,0,0}, {17838,17848,17840 ,5646,5656,5648 ,0,0,0}, - {17849,17843,17850 ,5657,5651,5658 ,0,0,0}, {17837,17835,17839 ,5645,5641,5647 ,0,0,0}, - {17835,17815,17789 ,5641,5618,5592 ,0,0,0}, {17841,17840,17842 ,5649,5648,5650 ,0,0,0}, - {17836,17848,17838 ,5642,5656,5646 ,0,0,0}, {17843,17851,17844 ,5651,5659,5652 ,0,0,0}, - {17840,17848,17850 ,5648,5656,5658 ,0,0,0}, {17852,17851,17843 ,5660,5659,5651 ,0,0,0}, - {17798,17797,17792 ,5601,5600,5595 ,0,0,0}, {17853,17846,17845 ,5661,5654,5653 ,0,0,0}, - {17853,17809,17846 ,5661,5612,5654 ,0,0,0}, {17792,17847,17793 ,5595,5655,5596 ,0,0,0}, - {17846,17854,17847 ,5654,5662,5655 ,0,0,0}, {17791,17823,17836 ,5594,5629,5642 ,0,0,0}, - {17854,17790,17816 ,5662,5593,5619 ,0,0,0}, {17819,17849,17850 ,5624,5657,5658 ,0,0,0}, - {17818,17849,17819 ,5623,5657,5624 ,0,0,0}, {17835,17836,17838 ,5641,5642,5646 ,0,0,0}, - {17789,17791,17836 ,5592,5594,5642 ,0,0,0}, {17840,17850,17843 ,5648,5658,5651 ,0,0,0}, - {17823,17822,17848 ,5629,5628,5656 ,0,0,0}, {17843,17849,17852 ,5651,5657,5660 ,0,0,0}, - {17850,17822,17819 ,5658,5628,5624 ,0,0,0}, {17855,17852,17849 ,5663,5660,5657 ,0,0,0}, - {17797,17846,17847 ,5600,5654,5655 ,0,0,0}, {17807,17809,17853 ,5610,5612,5661 ,0,0,0}, - {17856,17813,17857 ,5664,5616,5665 ,0,0,0}, {17847,17854,17816 ,5655,5662,5619 ,0,0,0}, - {17858,17854,17809 ,5666,5662,5612 ,0,0,0}, {17823,17791,17824 ,5629,5594,5630 ,0,0,0}, - {17858,17795,17790 ,5666,5598,5593 ,0,0,0}, {17859,17817,17831 ,5667,5622,5637 ,0,0,0}, - {17848,17822,17850 ,5656,5628,5658 ,0,0,0}, {17836,17823,17848 ,5642,5629,5656 ,0,0,0}, - {17823,17824,17821 ,5629,5630,5627 ,0,0,0}, {17818,17817,17860 ,5623,5622,5668 ,0,0,0}, - {17821,17831,17822 ,5627,5637,5628 ,0,0,0}, {17849,17818,17855 ,5657,5623,5663 ,0,0,0}, - {17819,17831,17817 ,5624,5637,5622 ,0,0,0}, {17861,17855,17818 ,5669,5663,5623 ,0,0,0}, - {17846,17809,17854 ,5654,5612,5662 ,0,0,0}, {17814,17808,17807 ,5617,5611,5610 ,0,0,0}, - {17795,17862,17824 ,5598,5670,5630 ,0,0,0}, {17854,17858,17790 ,5662,5666,5593 ,0,0,0}, - {17863,17858,17808 ,5671,5666,5611 ,0,0,0}, {17824,17864,17821 ,5630,5672,5627 ,0,0,0}, - {17863,17862,17795 ,5671,5670,5598 ,0,0,0}, {17821,17865,17831 ,5627,5673,5637 ,0,0,0}, - {17864,17824,17862 ,5672,5630,5670 ,0,0,0}, {17817,17826,17860 ,5622,5632,5668 ,0,0,0}, - {17865,17821,17864 ,5673,5627,5672 ,0,0,0}, {17866,17860,17825 ,5674,5668,5631 ,0,0,0}, - {17859,17831,17865 ,5667,5637,5673 ,0,0,0}, {17818,17860,17861 ,5623,5668,5669 ,0,0,0}, - {17817,17859,17826 ,5622,5667,5632 ,0,0,0}, {17866,17861,17860 ,5674,5669,5668 ,0,0,0}, - {17809,17808,17858 ,5612,5611,5666 ,0,0,0}, {17857,17813,17814 ,5665,5616,5617 ,0,0,0}, - {17862,17810,17864 ,5670,5613,5672 ,0,0,0}, {17858,17863,17795 ,5666,5671,5598 ,0,0,0}, - {17813,17867,17863 ,5616,5675,5671 ,0,0,0}, {17864,17812,17865 ,5672,5615,5673 ,0,0,0}, - {17867,17810,17862 ,5675,5613,5670 ,0,0,0}, {17865,17868,17859 ,5673,5676,5667 ,0,0,0}, - {17810,17812,17864 ,5613,5615,5672 ,0,0,0}, {17869,17826,17859 ,5677,5632,5667 ,0,0,0}, - {17868,17865,17812 ,5676,5673,5615 ,0,0,0}, {17870,17825,17830 ,5678,5631,5636 ,0,0,0}, - {17859,17868,17869 ,5667,5676,5677 ,0,0,0}, {17869,17827,17826 ,5677,5633,5632 ,0,0,0}, - {17866,17825,17870 ,5674,5631,5678 ,0,0,0}, {17860,17826,17825 ,5668,5632,5631 ,0,0,0}, - {17808,17813,17863 ,5611,5616,5671 ,0,0,0}, {17871,17856,17857 ,5679,5664,5665 ,0,0,0}, - {17872,17868,17812 ,5680,5676,5615 ,0,0,0}, {17863,17867,17862 ,5671,5675,5670 ,0,0,0}, - {17856,17804,17867 ,5664,5607,5675 ,0,0,0}, {17873,17869,17868 ,5681,5677,5676 ,0,0,0}, - {17804,17811,17810 ,5607,5614,5613 ,0,0,0}, {17874,17827,17869 ,5682,5633,5677 ,0,0,0}, - {17811,17872,17812 ,5614,5680,5615 ,0,0,0}, {17834,17828,17875 ,5640,5634,5683 ,0,0,0}, - {17872,17873,17868 ,5680,5681,5676 ,0,0,0}, {17830,17827,17876 ,5636,5633,5684 ,0,0,0}, - {17874,17869,17873 ,5682,5677,5681 ,0,0,0}, {17876,17827,17874 ,5684,5633,5682 ,0,0,0}, - {17870,17830,17829 ,5678,5636,5635 ,0,0,0}, {17825,17827,17830 ,5631,5633,5636 ,0,0,0}, - {17813,17856,17867 ,5616,5664,5675 ,0,0,0}, {17802,17871,17820 ,5605,5679,5625 ,0,0,0}, - {17803,17877,17811 ,5606,5685,5614 ,0,0,0}, {17867,17804,17810 ,5675,5607,5613 ,0,0,0}, - {17803,17811,17804 ,5606,5614,5607 ,0,0,0}, {17877,17878,17872 ,5685,5686,5680 ,0,0,0}, - {17877,17872,17811 ,5685,5680,5614 ,0,0,0}, {17878,17879,17873 ,5686,5687,5681 ,0,0,0}, - {17878,17873,17872 ,5686,5681,5680 ,0,0,0}, {17879,17880,17874 ,5687,5688,5682 ,0,0,0}, - {17879,17874,17873 ,5687,5682,5681 ,0,0,0}, {17880,17875,17876 ,5688,5683,5684 ,0,0,0}, - {17876,17874,17880 ,5684,5682,5688 ,0,0,0}, {17875,17828,17876 ,5683,5634,5684 ,0,0,0}, - {17829,17828,17833 ,5635,5634,5639 ,0,0,0}, {17830,17876,17828 ,5636,5684,5634 ,0,0,0}, - {17871,17802,17856 ,5679,5605,5664 ,0,0,0}, {17804,17856,17802 ,5607,5664,5605 ,0,0,0}, - {17877,17520,17541 ,5685,5621,5689 ,0,0,0}, {17552,17803,17802 ,5620,5606,5605 ,0,0,0}, - {17878,17541,17652 ,5686,5689,5690 ,0,0,0}, {17520,17877,17803 ,5621,5685,5606 ,0,0,0}, - {17879,17652,17538 ,5687,5690,5691 ,0,0,0}, {17541,17878,17877 ,5689,5686,5685 ,0,0,0}, - {17880,17538,17536 ,5688,5691,5692 ,0,0,0}, {17652,17879,17878 ,5690,5687,5686 ,0,0,0}, - {17875,17536,17505 ,5683,5692,5693 ,0,0,0}, {17538,17880,17879 ,5691,5688,5687 ,0,0,0}, - {17834,17505,17543 ,5640,5693,5643 ,0,0,0}, {17536,17875,17880 ,5692,5683,5688 ,0,0,0}, - {17543,17832,17834 ,5643,5638,5640 ,0,0,0}, {17505,17834,17875 ,5693,5640,5683 ,0,0,0}, - {17881,17882,17883 ,5694,5695,5696 ,0,0,0}, {17884,17885,17886 ,5697,5698,5699 ,0,0,0}, - {17883,17887,17888 ,5696,5700,5701 ,0,0,0}, {17887,17889,17888 ,5700,5702,5701 ,0,0,0}, - {17890,17891,17892 ,5703,5704,5705 ,0,0,0}, {17892,17893,17890 ,5705,5706,5703 ,0,0,0}, - {17894,17895,17896 ,5707,5708,5709 ,0,0,0}, {17897,17891,17898 ,5710,5704,5711 ,0,0,0}, - {17897,17892,17891 ,5710,5705,5704 ,0,0,0}, {17898,17899,17897 ,5711,5712,5710 ,0,0,0}, - {17900,17886,17901 ,5713,5699,5714 ,0,0,0}, {17902,17903,17904 ,5715,5716,5717 ,0,0,0}, - {17894,17468,17467 ,5707,5718,5719 ,0,0,0}, {17905,17906,17907 ,5720,5721,5722 ,0,0,0}, - {17908,17495,17896 ,5723,5724,5709 ,0,0,0}, {17909,17910,17903 ,5725,5726,5716 ,0,0,0}, - {17468,17896,17495 ,5718,5709,5724 ,0,0,0}, {17911,17912,17913 ,5727,5728,5729 ,0,0,0}, - {17914,17888,17889 ,5730,5701,5702 ,0,0,0}, {17915,17916,17917 ,5731,5732,5733 ,0,0,0}, - {17918,17919,17883 ,5734,5735,5696 ,0,0,0}, {17920,17921,17922 ,5736,5737,5738 ,0,0,0}, - {17913,17923,17924 ,5729,5739,5740 ,0,0,0}, {17925,17923,17926 ,5741,5739,5742 ,0,0,0}, - {17927,17928,17929 ,5743,5744,5745 ,0,0,0}, {17881,17885,17884 ,5694,5698,5697 ,0,0,0}, - {17928,17915,17929 ,5744,5731,5745 ,0,0,0}, {17919,17930,17881 ,5735,5746,5694 ,0,0,0}, - {17491,17496,17927 ,5747,5748,5743 ,0,0,0}, {17931,17932,17919 ,5749,5750,5735 ,0,0,0}, - {17930,17885,17881 ,5746,5698,5694 ,0,0,0}, {17931,17933,17934 ,5749,5751,5752 ,0,0,0}, - {17919,17932,17930 ,5735,5750,5746 ,0,0,0}, {17935,17936,17937 ,5753,5754,5755 ,0,0,0}, - {17932,17931,17934 ,5750,5749,5752 ,0,0,0}, {17938,17937,17939 ,5756,5755,5757 ,0,0,0}, - {17936,17935,17933 ,5754,5753,5751 ,0,0,0}, {17901,17891,17900 ,5714,5704,5713 ,0,0,0}, - {17891,17901,17898 ,5704,5714,5711 ,0,0,0}, {17893,17940,17890 ,5706,5758,5703 ,0,0,0}, - {17900,17884,17886 ,5713,5697,5699 ,0,0,0}, {17941,17900,17890 ,5759,5713,5703 ,0,0,0}, - {17883,17882,17887 ,5696,5695,5700 ,0,0,0}, {17941,17882,17884 ,5759,5695,5697 ,0,0,0}, - {17931,17942,17933 ,5749,5760,5751 ,0,0,0}, {17884,17882,17881 ,5697,5695,5694 ,0,0,0}, - {17943,17944,17936 ,5761,5762,5754 ,0,0,0}, {17919,17881,17883 ,5735,5694,5696 ,0,0,0}, - {17942,17931,17918 ,5760,5749,5734 ,0,0,0}, {17937,17936,17939 ,5755,5754,5757 ,0,0,0}, - {17934,17933,17935 ,5752,5751,5753 ,0,0,0}, {17933,17942,17943 ,5751,5760,5761 ,0,0,0}, - {17945,17939,17936 ,5763,5757,5754 ,0,0,0}, {17891,17890,17900 ,5704,5703,5713 ,0,0,0}, - {17946,17940,17893 ,5764,5758,5706 ,0,0,0}, {17946,17909,17940 ,5764,5725,5758 ,0,0,0}, - {17900,17941,17884 ,5713,5759,5697 ,0,0,0}, {17940,17947,17941 ,5758,5765,5759 ,0,0,0}, - {17888,17926,17918 ,5701,5742,5734 ,0,0,0}, {17947,17887,17882 ,5765,5700,5695 ,0,0,0}, - {17913,17944,17943 ,5729,5762,5761 ,0,0,0}, {17912,17944,17913 ,5728,5762,5729 ,0,0,0}, - {17919,17918,17931 ,5735,5734,5749 ,0,0,0}, {17883,17888,17918 ,5696,5701,5734 ,0,0,0}, - {17933,17943,17936 ,5751,5761,5754 ,0,0,0}, {17926,17923,17942 ,5742,5739,5760 ,0,0,0}, - {17936,17944,17945 ,5754,5762,5763 ,0,0,0}, {17943,17923,17913 ,5761,5739,5729 ,0,0,0}, - {17948,17945,17944 ,5766,5763,5762 ,0,0,0}, {17890,17940,17941 ,5703,5758,5759 ,0,0,0}, - {17910,17909,17946 ,5726,5725,5764 ,0,0,0}, {17949,17902,17950 ,5767,5715,5768 ,0,0,0}, - {17941,17947,17882 ,5759,5765,5695 ,0,0,0}, {17951,17947,17909 ,5769,5765,5725 ,0,0,0}, - {17926,17888,17914 ,5742,5701,5730 ,0,0,0}, {17951,17889,17887 ,5769,5702,5700 ,0,0,0}, - {17952,17911,17924 ,5770,5727,5740 ,0,0,0}, {17942,17923,17943 ,5760,5739,5761 ,0,0,0}, - {17918,17926,17942 ,5734,5742,5760 ,0,0,0}, {17926,17914,17925 ,5742,5730,5741 ,0,0,0}, - {17912,17911,17953 ,5728,5727,5771 ,0,0,0}, {17925,17924,17923 ,5741,5740,5739 ,0,0,0}, - {17944,17912,17948 ,5762,5728,5766 ,0,0,0}, {17913,17924,17911 ,5729,5740,5727 ,0,0,0}, - {17954,17948,17912 ,5772,5766,5728 ,0,0,0}, {17940,17909,17947 ,5758,5725,5765 ,0,0,0}, - {17904,17903,17910 ,5717,5716,5726 ,0,0,0}, {17889,17955,17914 ,5702,5773,5730 ,0,0,0}, - {17947,17951,17887 ,5765,5769,5700 ,0,0,0}, {17956,17951,17903 ,5774,5769,5716 ,0,0,0}, - {17914,17957,17925 ,5730,5775,5741 ,0,0,0}, {17956,17955,17889 ,5774,5773,5702 ,0,0,0}, - {17925,17958,17924 ,5741,5776,5740 ,0,0,0}, {17957,17914,17955 ,5775,5730,5773 ,0,0,0}, - {17911,17921,17953 ,5727,5737,5771 ,0,0,0}, {17958,17925,17957 ,5776,5741,5775 ,0,0,0}, - {17959,17953,17920 ,5777,5771,5736 ,0,0,0}, {17952,17924,17958 ,5770,5740,5776 ,0,0,0}, - {17912,17953,17954 ,5728,5771,5772 ,0,0,0}, {17911,17952,17921 ,5727,5770,5737 ,0,0,0}, - {17959,17954,17953 ,5777,5772,5771 ,0,0,0}, {17909,17903,17951 ,5725,5716,5769 ,0,0,0}, - {17950,17902,17904 ,5768,5715,5717 ,0,0,0}, {17955,17906,17957 ,5773,5721,5775 ,0,0,0}, - {17951,17956,17889 ,5769,5774,5702 ,0,0,0}, {17902,17960,17956 ,5715,5778,5774 ,0,0,0}, - {17957,17905,17958 ,5775,5720,5776 ,0,0,0}, {17960,17906,17955 ,5778,5721,5773 ,0,0,0}, - {17958,17961,17952 ,5776,5779,5770 ,0,0,0}, {17906,17905,17957 ,5721,5720,5775 ,0,0,0}, - {17962,17921,17952 ,5780,5737,5770 ,0,0,0}, {17961,17958,17905 ,5779,5776,5720 ,0,0,0}, - {17963,17920,17917 ,5781,5736,5733 ,0,0,0}, {17952,17961,17962 ,5770,5779,5780 ,0,0,0}, - {17962,17922,17921 ,5780,5738,5737 ,0,0,0}, {17959,17920,17963 ,5777,5736,5781 ,0,0,0}, - {17953,17921,17920 ,5771,5737,5736 ,0,0,0}, {17903,17902,17956 ,5716,5715,5774 ,0,0,0}, - {17964,17949,17950 ,5782,5767,5768 ,0,0,0}, {17965,17961,17905 ,5783,5779,5720 ,0,0,0}, - {17956,17960,17955 ,5774,5778,5773 ,0,0,0}, {17949,17895,17960 ,5767,5708,5778 ,0,0,0}, - {17966,17962,17961 ,5784,5780,5779 ,0,0,0}, {17895,17907,17906 ,5708,5722,5721 ,0,0,0}, - {17967,17922,17962 ,5785,5738,5780 ,0,0,0}, {17907,17965,17905 ,5722,5783,5720 ,0,0,0}, - {17929,17915,17968 ,5745,5731,5786 ,0,0,0}, {17965,17966,17961 ,5783,5784,5779 ,0,0,0}, - {17917,17922,17969 ,5733,5738,5787 ,0,0,0}, {17967,17962,17966 ,5785,5780,5784 ,0,0,0}, - {17969,17922,17967 ,5787,5738,5785 ,0,0,0}, {17963,17917,17916 ,5781,5733,5732 ,0,0,0}, - {17920,17922,17917 ,5736,5738,5733 ,0,0,0}, {17902,17949,17960 ,5715,5767,5778 ,0,0,0}, - {17896,17964,17908 ,5709,5782,5723 ,0,0,0}, {17894,17970,17907 ,5707,5788,5722 ,0,0,0}, - {17960,17895,17906 ,5778,5708,5721 ,0,0,0}, {17894,17907,17895 ,5707,5722,5708 ,0,0,0}, - {17970,17971,17965 ,5788,5789,5783 ,0,0,0}, {17970,17965,17907 ,5788,5783,5722 ,0,0,0}, - {17971,17972,17966 ,5789,5790,5784 ,0,0,0}, {17971,17966,17965 ,5789,5784,5783 ,0,0,0}, - {17972,17973,17967 ,5790,5791,5785 ,0,0,0}, {17972,17967,17966 ,5790,5785,5784 ,0,0,0}, - {17973,17968,17969 ,5791,5786,5787 ,0,0,0}, {17969,17967,17973 ,5787,5785,5791 ,0,0,0}, - {17968,17915,17969 ,5786,5731,5787 ,0,0,0}, {17916,17915,17928 ,5732,5731,5744 ,0,0,0}, - {17917,17969,17915 ,5733,5787,5731 ,0,0,0}, {17964,17896,17949 ,5782,5709,5767 ,0,0,0}, - {17895,17949,17896 ,5708,5767,5709 ,0,0,0}, {17970,17467,17482 ,5788,5719,5792 ,0,0,0}, - {17468,17894,17896 ,5718,5707,5709 ,0,0,0}, {17971,17482,17485 ,5789,5792,5793 ,0,0,0}, - {17467,17970,17894 ,5719,5788,5707 ,0,0,0}, {17972,17485,17486 ,5790,5793,5794 ,0,0,0}, - {17482,17971,17970 ,5792,5789,5788 ,0,0,0}, {17973,17486,17525 ,5791,5794,5795 ,0,0,0}, - {17485,17972,17971 ,5793,5790,5789 ,0,0,0}, {17968,17525,17466 ,5786,5795,5796 ,0,0,0}, - {17486,17973,17972 ,5794,5791,5790 ,0,0,0}, {17929,17466,17491 ,5745,5796,5747 ,0,0,0}, - {17525,17968,17973 ,5795,5786,5791 ,0,0,0}, {17491,17927,17929 ,5747,5743,5745 ,0,0,0}, - {17466,17929,17968 ,5796,5745,5786 ,0,0,0}, {17974,17975,17976 ,5797,5798,5799 ,0,0,0}, - {17977,16891,16892 ,5800,5801,5802 ,0,0,0}, {17976,17978,17979 ,5799,5803,5804 ,0,0,0}, - {17978,17980,17979 ,5803,5805,5804 ,0,0,0}, {17981,17982,17983 ,5806,5807,5808 ,0,0,0}, - {17983,17984,17981 ,5808,5809,5806 ,0,0,0}, {17985,17986,17987 ,5810,5811,5812 ,0,0,0}, - {17988,17982,16897 ,5813,5807,5814 ,0,0,0}, {17988,17983,17982 ,5813,5808,5807 ,0,0,0}, - {16897,16898,17988 ,5814,5815,5813 ,0,0,0}, {17989,16892,16895 ,5816,5802,5817 ,0,0,0}, - {17990,17991,17992 ,5818,5819,5820 ,0,0,0}, {17985,17424,17423 ,5810,5821,5822 ,0,0,0}, - {17993,17994,17995 ,5823,5824,5825 ,0,0,0}, {17996,17431,17987 ,5826,5827,5812 ,0,0,0}, - {17997,17998,17991 ,5828,5829,5819 ,0,0,0}, {17424,17987,17431 ,5821,5812,5827 ,0,0,0}, - {17999,18000,18001 ,5830,5831,5832 ,0,0,0}, {18002,17979,17980 ,5833,5804,5805 ,0,0,0}, - {18003,18004,18005 ,5834,5835,5836 ,0,0,0}, {18006,18007,17976 ,5837,5838,5799 ,0,0,0}, - {18008,18009,18010 ,5839,5840,5841 ,0,0,0}, {18001,18011,18012 ,5832,5842,5843 ,0,0,0}, - {18013,18011,18014 ,5844,5842,5845 ,0,0,0}, {18015,18016,18017 ,5846,5847,5848 ,0,0,0}, - {17974,16891,17977 ,5797,5801,5800 ,0,0,0}, {18016,18003,18017 ,5847,5834,5848 ,0,0,0}, - {18007,16889,17974 ,5838,5849,5797 ,0,0,0}, {17447,17454,18015 ,5850,5851,5846 ,0,0,0}, - {18018,16887,18007 ,5852,5853,5838 ,0,0,0}, {16889,16891,17974 ,5849,5801,5797 ,0,0,0}, - {18018,18019,16884 ,5852,5854,5855 ,0,0,0}, {18007,16887,16889 ,5838,5853,5849 ,0,0,0}, - {16882,18020,16883 ,5856,5857,5858 ,0,0,0}, {16887,18018,16884 ,5853,5852,5855 ,0,0,0}, - {16877,16883,18021 ,5067,5858,5859 ,0,0,0}, {18020,16882,18019 ,5857,5856,5854 ,0,0,0}, - {16895,17982,17989 ,5817,5807,5816 ,0,0,0}, {17982,16895,16897 ,5807,5817,5814 ,0,0,0}, - {17984,18022,17981 ,5809,5860,5806 ,0,0,0}, {17989,17977,16892 ,5816,5800,5802 ,0,0,0}, - {18023,17989,17981 ,5861,5816,5806 ,0,0,0}, {17976,17975,17978 ,5799,5798,5803 ,0,0,0}, - {18023,17975,17977 ,5861,5798,5800 ,0,0,0}, {18018,18024,18019 ,5852,5862,5854 ,0,0,0}, - {17977,17975,17974 ,5800,5798,5797 ,0,0,0}, {18025,18026,18020 ,5863,5864,5857 ,0,0,0}, - {18007,17974,17976 ,5838,5797,5799 ,0,0,0}, {18024,18018,18006 ,5862,5852,5837 ,0,0,0}, - {16883,18020,18021 ,5858,5857,5859 ,0,0,0}, {16884,18019,16882 ,5855,5854,5856 ,0,0,0}, - {18019,18024,18025 ,5854,5862,5863 ,0,0,0}, {18027,18021,18020 ,5865,5859,5857 ,0,0,0}, - {17982,17981,17989 ,5807,5806,5816 ,0,0,0}, {18028,18022,17984 ,5866,5860,5809 ,0,0,0}, - {18028,17997,18022 ,5866,5828,5860 ,0,0,0}, {17989,18023,17977 ,5816,5861,5800 ,0,0,0}, - {18022,18029,18023 ,5860,5867,5861 ,0,0,0}, {17979,18014,18006 ,5804,5845,5837 ,0,0,0}, - {18029,17978,17975 ,5867,5803,5798 ,0,0,0}, {18001,18026,18025 ,5832,5864,5863 ,0,0,0}, - {18000,18026,18001 ,5831,5864,5832 ,0,0,0}, {18007,18006,18018 ,5838,5837,5852 ,0,0,0}, - {17976,17979,18006 ,5799,5804,5837 ,0,0,0}, {18019,18025,18020 ,5854,5863,5857 ,0,0,0}, - {18014,18011,18024 ,5845,5842,5862 ,0,0,0}, {18020,18026,18027 ,5857,5864,5865 ,0,0,0}, - {18025,18011,18001 ,5863,5842,5832 ,0,0,0}, {18030,18027,18026 ,5868,5865,5864 ,0,0,0}, - {17981,18022,18023 ,5806,5860,5861 ,0,0,0}, {17998,17997,18028 ,5829,5828,5866 ,0,0,0}, - {18031,17990,18032 ,5869,5818,5870 ,0,0,0}, {18023,18029,17975 ,5861,5867,5798 ,0,0,0}, - {18033,18029,17997 ,5871,5867,5828 ,0,0,0}, {18014,17979,18002 ,5845,5804,5833 ,0,0,0}, - {18033,17980,17978 ,5871,5805,5803 ,0,0,0}, {18034,17999,18012 ,5872,5830,5843 ,0,0,0}, - {18024,18011,18025 ,5862,5842,5863 ,0,0,0}, {18006,18014,18024 ,5837,5845,5862 ,0,0,0}, - {18014,18002,18013 ,5845,5833,5844 ,0,0,0}, {18000,17999,18035 ,5831,5830,5873 ,0,0,0}, - {18013,18012,18011 ,5844,5843,5842 ,0,0,0}, {18026,18000,18030 ,5864,5831,5868 ,0,0,0}, - {18001,18012,17999 ,5832,5843,5830 ,0,0,0}, {18036,18030,18000 ,5874,5868,5831 ,0,0,0}, - {18022,17997,18029 ,5860,5828,5867 ,0,0,0}, {17992,17991,17998 ,5820,5819,5829 ,0,0,0}, - {17980,18037,18002 ,5805,5875,5833 ,0,0,0}, {18029,18033,17978 ,5867,5871,5803 ,0,0,0}, - {18038,18033,17991 ,5876,5871,5819 ,0,0,0}, {18002,18039,18013 ,5833,5877,5844 ,0,0,0}, - {18038,18037,17980 ,5876,5875,5805 ,0,0,0}, {18013,18040,18012 ,5844,5878,5843 ,0,0,0}, - {18039,18002,18037 ,5877,5833,5875 ,0,0,0}, {17999,18009,18035 ,5830,5840,5873 ,0,0,0}, - {18040,18013,18039 ,5878,5844,5877 ,0,0,0}, {18041,18035,18008 ,5879,5873,5839 ,0,0,0}, - {18034,18012,18040 ,5872,5843,5878 ,0,0,0}, {18000,18035,18036 ,5831,5873,5874 ,0,0,0}, - {17999,18034,18009 ,5830,5872,5840 ,0,0,0}, {18041,18036,18035 ,5879,5874,5873 ,0,0,0}, - {17997,17991,18033 ,5828,5819,5871 ,0,0,0}, {18032,17990,17992 ,5870,5818,5820 ,0,0,0}, - {18037,17994,18039 ,5875,5824,5877 ,0,0,0}, {18033,18038,17980 ,5871,5876,5805 ,0,0,0}, - {17990,18042,18038 ,5818,5880,5876 ,0,0,0}, {18039,17993,18040 ,5877,5823,5878 ,0,0,0}, - {18042,17994,18037 ,5880,5824,5875 ,0,0,0}, {18040,18043,18034 ,5878,5881,5872 ,0,0,0}, - {17994,17993,18039 ,5824,5823,5877 ,0,0,0}, {18044,18009,18034 ,5882,5840,5872 ,0,0,0}, - {18043,18040,17993 ,5881,5878,5823 ,0,0,0}, {18045,18008,18005 ,5883,5839,5836 ,0,0,0}, - {18034,18043,18044 ,5872,5881,5882 ,0,0,0}, {18044,18010,18009 ,5882,5841,5840 ,0,0,0}, - {18041,18008,18045 ,5879,5839,5883 ,0,0,0}, {18035,18009,18008 ,5873,5840,5839 ,0,0,0}, - {17991,17990,18038 ,5819,5818,5876 ,0,0,0}, {18046,18031,18032 ,5884,5869,5870 ,0,0,0}, - {18047,18043,17993 ,5885,5881,5823 ,0,0,0}, {18038,18042,18037 ,5876,5880,5875 ,0,0,0}, - {18031,17986,18042 ,5869,5811,5880 ,0,0,0}, {18048,18044,18043 ,5886,5882,5881 ,0,0,0}, - {17986,17995,17994 ,5811,5825,5824 ,0,0,0}, {18049,18010,18044 ,5887,5841,5882 ,0,0,0}, - {17995,18047,17993 ,5825,5885,5823 ,0,0,0}, {18017,18003,18050 ,5848,5834,5888 ,0,0,0}, - {18047,18048,18043 ,5885,5886,5881 ,0,0,0}, {18005,18010,18051 ,5836,5841,5889 ,0,0,0}, - {18049,18044,18048 ,5887,5882,5886 ,0,0,0}, {18051,18010,18049 ,5889,5841,5887 ,0,0,0}, - {18045,18005,18004 ,5883,5836,5835 ,0,0,0}, {18008,18010,18005 ,5839,5841,5836 ,0,0,0}, - {17990,18031,18042 ,5818,5869,5880 ,0,0,0}, {17987,18046,17996 ,5812,5884,5826 ,0,0,0}, - {17985,18052,17995 ,5810,5890,5825 ,0,0,0}, {18042,17986,17994 ,5880,5811,5824 ,0,0,0}, - {17985,17995,17986 ,5810,5825,5811 ,0,0,0}, {18052,18053,18047 ,5890,5891,5885 ,0,0,0}, - {18052,18047,17995 ,5890,5885,5825 ,0,0,0}, {18053,18054,18048 ,5891,5892,5886 ,0,0,0}, - {18053,18048,18047 ,5891,5886,5885 ,0,0,0}, {18054,18055,18049 ,5892,5893,5887 ,0,0,0}, - {18054,18049,18048 ,5892,5887,5886 ,0,0,0}, {18055,18050,18051 ,5893,5888,5889 ,0,0,0}, - {18051,18049,18055 ,5889,5887,5893 ,0,0,0}, {18050,18003,18051 ,5888,5834,5889 ,0,0,0}, - {18004,18003,18016 ,5835,5834,5847 ,0,0,0}, {18005,18051,18003 ,5836,5889,5834 ,0,0,0}, - {18046,17987,18031 ,5884,5812,5869 ,0,0,0}, {17986,18031,17987 ,5811,5869,5812 ,0,0,0}, - {18052,17423,17441 ,5890,5822,5894 ,0,0,0}, {17424,17985,17987 ,5821,5810,5812 ,0,0,0}, - {18053,17441,17442 ,5891,5894,5895 ,0,0,0}, {17423,18052,17985 ,5822,5890,5810 ,0,0,0}, - {18054,17442,17444 ,5892,5895,5896 ,0,0,0}, {17441,18053,18052 ,5894,5891,5890 ,0,0,0}, - {18055,17444,17427 ,5893,5896,5897 ,0,0,0}, {17442,18054,18053 ,5895,5892,5891 ,0,0,0}, - {18050,17427,17448 ,5888,5897,5898 ,0,0,0}, {17444,18055,18054 ,5896,5893,5892 ,0,0,0}, - {18017,17448,17447 ,5848,5898,5850 ,0,0,0}, {17427,18050,18055 ,5897,5888,5893 ,0,0,0}, - {17447,18015,18017 ,5850,5846,5848 ,0,0,0}, {17448,18017,18050 ,5898,5848,5888 ,0,0,0}, - {18056,18057,18058 ,5899,5900,5901 ,0,0,0}, {18059,18060,16860 ,5902,5903,5904 ,0,0,0}, - {18057,18061,18058 ,5900,5905,5901 ,0,0,0}, {16855,16860,18060 ,5906,5904,5903 ,0,0,0}, - {18062,18063,18064 ,5907,5908,5909 ,0,0,0}, {16865,18065,18063 ,5910,5911,5908 ,0,0,0}, - {18066,18067,18068 ,5912,5913,5914 ,0,0,0}, {16863,18065,16865 ,5915,5911,5910 ,0,0,0}, - {18065,18064,18063 ,5911,5909,5908 ,0,0,0}, {16859,18063,18059 ,5916,5908,5902 ,0,0,0}, - {18069,18070,18071 ,5917,5918,5919 ,0,0,0}, {18072,18073,18074 ,5920,5921,5922 ,0,0,0}, - {18075,18070,18076 ,5923,5918,5924 ,0,0,0}, {18077,18078,18056 ,5925,5926,5899 ,0,0,0}, - {18067,17374,17293 ,5913,5927,5928 ,0,0,0}, {18079,18080,18081 ,5929,5930,5931 ,0,0,0}, - {18082,17404,18066 ,5932,5933,5912 ,0,0,0}, {17374,18066,17404 ,5927,5912,5933 ,0,0,0}, - {18083,18084,18085 ,5934,5935,5936 ,0,0,0}, {18061,18086,18058 ,5905,5937,5901 ,0,0,0}, - {18087,18088,18089 ,5938,5939,5940 ,0,0,0}, {18090,18091,18092 ,5941,5942,5943 ,0,0,0}, - {18081,18084,18093 ,5931,5935,5944 ,0,0,0}, {18094,18095,18096 ,5945,5946,5947 ,0,0,0}, - {18097,18056,18098 ,5948,5899,5949 ,0,0,0}, {18095,18090,18096 ,5946,5941,5947 ,0,0,0}, - {18077,16855,18060 ,5925,5906,5903 ,0,0,0}, {17403,17407,18094 ,5950,5951,5945 ,0,0,0}, - {16855,18077,16853 ,5906,5925,5952 ,0,0,0}, {16853,18077,18097 ,5952,5925,5948 ,0,0,0}, - {18099,16848,18097 ,5953,5954,5948 ,0,0,0}, {18077,18060,18078 ,5925,5903,5926 ,0,0,0}, - {18099,18100,16852 ,5953,5955,5956 ,0,0,0}, {16852,16848,18099 ,5956,5954,5953 ,0,0,0}, - {16844,18101,16846 ,5957,5958,5959 ,0,0,0}, {18101,16844,18100 ,5958,5957,5955 ,0,0,0}, - {16865,18063,16859 ,5910,5908,5916 ,0,0,0}, {18102,18062,18064 ,5960,5907,5909 ,0,0,0}, - {18102,18103,18062 ,5960,5961,5907 ,0,0,0}, {16859,18059,16860 ,5916,5902,5904 ,0,0,0}, - {18104,18059,18062 ,5962,5902,5907 ,0,0,0}, {18056,18078,18057 ,5899,5926,5900 ,0,0,0}, - {18104,18078,18060 ,5962,5926,5903 ,0,0,0}, {18099,18105,18100 ,5953,5963,5955 ,0,0,0}, - {18106,18101,18107 ,5964,5958,5965 ,0,0,0}, {16853,18097,16848 ,5952,5948,5954 ,0,0,0}, - {18097,18077,18056 ,5948,5925,5899 ,0,0,0}, {16852,18100,16844 ,5956,5955,5957 ,0,0,0}, - {18098,18105,18099 ,5949,5963,5953 ,0,0,0}, {18101,18108,16846 ,5958,5966,5959 ,0,0,0}, - {18100,18105,18107 ,5955,5963,5965 ,0,0,0}, {18109,18108,18101 ,5967,5966,5958 ,0,0,0}, - {18063,18062,18059 ,5908,5907,5902 ,0,0,0}, {18110,18103,18102 ,5968,5961,5960 ,0,0,0}, - {18110,18071,18103 ,5968,5919,5961 ,0,0,0}, {18059,18104,18060 ,5902,5962,5903 ,0,0,0}, - {18103,18111,18104 ,5961,5969,5962 ,0,0,0}, {18058,18085,18098 ,5901,5936,5949 ,0,0,0}, - {18111,18057,18078 ,5969,5900,5926 ,0,0,0}, {18081,18106,18107 ,5931,5964,5965 ,0,0,0}, - {18080,18106,18081 ,5930,5964,5931 ,0,0,0}, {18097,18098,18099 ,5948,5949,5953 ,0,0,0}, - {18056,18058,18098 ,5899,5901,5949 ,0,0,0}, {18100,18107,18101 ,5955,5965,5958 ,0,0,0}, - {18085,18084,18105 ,5936,5935,5963 ,0,0,0}, {18101,18106,18109 ,5958,5964,5967 ,0,0,0}, - {18107,18084,18081 ,5965,5935,5931 ,0,0,0}, {18112,18109,18106 ,5970,5967,5964 ,0,0,0}, - {18062,18103,18104 ,5907,5961,5962 ,0,0,0}, {18069,18071,18110 ,5917,5919,5968 ,0,0,0}, - {18113,18075,18114 ,5971,5923,5972 ,0,0,0}, {18104,18111,18078 ,5962,5969,5926 ,0,0,0}, - {18115,18111,18071 ,5973,5969,5919 ,0,0,0}, {18085,18058,18086 ,5936,5901,5937 ,0,0,0}, - {18115,18061,18057 ,5973,5905,5900 ,0,0,0}, {18116,18079,18093 ,5974,5929,5944 ,0,0,0}, - {18105,18084,18107 ,5963,5935,5965 ,0,0,0}, {18098,18085,18105 ,5949,5936,5963 ,0,0,0}, - {18085,18086,18083 ,5936,5937,5934 ,0,0,0}, {18080,18079,18117 ,5930,5929,5975 ,0,0,0}, - {18083,18093,18084 ,5934,5944,5935 ,0,0,0}, {18106,18080,18112 ,5964,5930,5970 ,0,0,0}, - {18081,18093,18079 ,5931,5944,5929 ,0,0,0}, {18118,18112,18080 ,5976,5970,5930 ,0,0,0}, - {18103,18071,18111 ,5961,5919,5969 ,0,0,0}, {18076,18070,18069 ,5924,5918,5917 ,0,0,0}, - {18061,18119,18086 ,5905,5977,5937 ,0,0,0}, {18111,18115,18057 ,5969,5973,5900 ,0,0,0}, - {18120,18115,18070 ,5978,5973,5918 ,0,0,0}, {18086,18121,18083 ,5937,5979,5934 ,0,0,0}, - {18120,18119,18061 ,5978,5977,5905 ,0,0,0}, {18083,18122,18093 ,5934,5980,5944 ,0,0,0}, - {18121,18086,18119 ,5979,5937,5977 ,0,0,0}, {18079,18088,18117 ,5929,5939,5975 ,0,0,0}, - {18122,18083,18121 ,5980,5934,5979 ,0,0,0}, {18123,18117,18087 ,5981,5975,5938 ,0,0,0}, - {18116,18093,18122 ,5974,5944,5980 ,0,0,0}, {18080,18117,18118 ,5930,5975,5976 ,0,0,0}, - {18079,18116,18088 ,5929,5974,5939 ,0,0,0}, {18123,18118,18117 ,5981,5976,5975 ,0,0,0}, - {18071,18070,18115 ,5919,5918,5973 ,0,0,0}, {18114,18075,18076 ,5972,5923,5924 ,0,0,0}, - {18119,18072,18121 ,5977,5920,5979 ,0,0,0}, {18115,18120,18061 ,5973,5978,5905 ,0,0,0}, - {18075,18124,18120 ,5923,5982,5978 ,0,0,0}, {18121,18074,18122 ,5979,5922,5980 ,0,0,0}, - {18124,18072,18119 ,5982,5920,5977 ,0,0,0}, {18122,18125,18116 ,5980,5983,5974 ,0,0,0}, - {18072,18074,18121 ,5920,5922,5979 ,0,0,0}, {18126,18088,18116 ,5984,5939,5974 ,0,0,0}, - {18125,18122,18074 ,5983,5980,5922 ,0,0,0}, {18127,18087,18092 ,5985,5938,5943 ,0,0,0}, - {18116,18125,18126 ,5974,5983,5984 ,0,0,0}, {18126,18089,18088 ,5984,5940,5939 ,0,0,0}, - {18123,18087,18127 ,5981,5938,5985 ,0,0,0}, {18117,18088,18087 ,5975,5939,5938 ,0,0,0}, - {18070,18075,18120 ,5918,5923,5978 ,0,0,0}, {18128,18113,18114 ,5986,5971,5972 ,0,0,0}, - {18129,18125,18074 ,5987,5983,5922 ,0,0,0}, {18120,18124,18119 ,5978,5982,5977 ,0,0,0}, - {18113,18068,18124 ,5971,5914,5982 ,0,0,0}, {18130,18126,18125 ,5988,5984,5983 ,0,0,0}, - {18068,18073,18072 ,5914,5921,5920 ,0,0,0}, {18131,18089,18126 ,5989,5940,5984 ,0,0,0}, - {18073,18129,18074 ,5921,5987,5922 ,0,0,0}, {18096,18090,18132 ,5947,5941,5990 ,0,0,0}, - {18129,18130,18125 ,5987,5988,5983 ,0,0,0}, {18092,18089,18133 ,5943,5940,5991 ,0,0,0}, - {18131,18126,18130 ,5989,5984,5988 ,0,0,0}, {18133,18089,18131 ,5991,5940,5989 ,0,0,0}, - {18127,18092,18091 ,5985,5943,5942 ,0,0,0}, {18087,18089,18092 ,5938,5940,5943 ,0,0,0}, - {18075,18113,18124 ,5923,5971,5982 ,0,0,0}, {18066,18128,18082 ,5912,5986,5932 ,0,0,0}, - {18067,18134,18073 ,5913,5992,5921 ,0,0,0}, {18124,18068,18072 ,5982,5914,5920 ,0,0,0}, - {18067,18073,18068 ,5913,5921,5914 ,0,0,0}, {18134,18135,18129 ,5992,5993,5987 ,0,0,0}, - {18134,18129,18073 ,5992,5987,5921 ,0,0,0}, {18135,18136,18130 ,5993,5994,5988 ,0,0,0}, - {18135,18130,18129 ,5993,5988,5987 ,0,0,0}, {18136,18137,18131 ,5994,5995,5989 ,0,0,0}, - {18136,18131,18130 ,5994,5989,5988 ,0,0,0}, {18137,18132,18133 ,5995,5990,5991 ,0,0,0}, - {18133,18131,18137 ,5991,5989,5995 ,0,0,0}, {18132,18090,18133 ,5990,5941,5991 ,0,0,0}, - {18091,18090,18095 ,5942,5941,5946 ,0,0,0}, {18092,18133,18090 ,5943,5991,5941 ,0,0,0}, - {18128,18066,18113 ,5986,5912,5971 ,0,0,0}, {18068,18113,18066 ,5914,5971,5912 ,0,0,0}, - {18134,17293,17393 ,5992,5928,5996 ,0,0,0}, {17374,18067,18066 ,5927,5913,5912 ,0,0,0}, - {18135,17393,17598 ,5993,5996,5997 ,0,0,0}, {17293,18134,18067 ,5928,5992,5913 ,0,0,0}, - {18136,17598,17400 ,5994,5997,5998 ,0,0,0}, {17393,18135,18134 ,5996,5993,5992 ,0,0,0}, - {18137,17400,17411 ,5995,5998,5999 ,0,0,0}, {17598,18136,18135 ,5997,5994,5993 ,0,0,0}, - {18132,17411,17397 ,5990,5999,6000 ,0,0,0}, {17400,18137,18136 ,5998,5995,5994 ,0,0,0}, - {18096,17397,17403 ,5947,6000,5950 ,0,0,0}, {17411,18132,18137 ,5999,5990,5995 ,0,0,0}, - {17403,18094,18096 ,5950,5945,5947 ,0,0,0}, {17397,18096,18132 ,6000,5947,5990 ,0,0,0}, - {18138,18139,18140 ,6001,6002,6003 ,0,0,0}, {18141,16828,16825 ,6004,6005,6006 ,0,0,0}, - {18140,18142,18143 ,6003,6007,6008 ,0,0,0}, {18142,18144,18143 ,6007,6009,6008 ,0,0,0}, - {18145,18146,18147 ,6010,6011,6012 ,0,0,0}, {18147,18148,18145 ,6012,6013,6010 ,0,0,0}, - {18149,18150,18151 ,6014,6015,6016 ,0,0,0}, {18152,18146,16831 ,6017,6011,6018 ,0,0,0}, - {18152,18147,18146 ,6017,6012,6011 ,0,0,0}, {16831,16830,18152 ,6018,5020,6017 ,0,0,0}, - {18153,16825,16833 ,6019,6006,6020 ,0,0,0}, {18154,18155,18156 ,6021,6022,6023 ,0,0,0}, - {18149,17348,17364 ,6014,6024,6025 ,0,0,0}, {18157,18158,18159 ,6026,6027,6028 ,0,0,0}, - {18160,17351,18151 ,6029,6030,6016 ,0,0,0}, {18161,18162,18155 ,6031,6032,6022 ,0,0,0}, - {17348,18151,17351 ,6024,6016,6030 ,0,0,0}, {18163,18164,18165 ,6033,6034,6035 ,0,0,0}, - {18166,18143,18144 ,6036,6008,6009 ,0,0,0}, {18167,18168,18169 ,6037,6038,6039 ,0,0,0}, - {18170,18171,18140 ,6040,6041,6003 ,0,0,0}, {18172,18173,18174 ,6042,6043,6044 ,0,0,0}, - {18165,18175,18176 ,6035,6045,6046 ,0,0,0}, {18177,18175,18178 ,6047,6045,6048 ,0,0,0}, - {18179,18180,18181 ,6049,6050,6051 ,0,0,0}, {18138,16828,18141 ,6001,6005,6004 ,0,0,0}, - {18180,18167,18181 ,6050,6037,6051 ,0,0,0}, {18171,16817,18138 ,6041,6052,6001 ,0,0,0}, - {17367,17369,18179 ,6053,6054,6049 ,0,0,0}, {18182,16818,18171 ,6055,6056,6041 ,0,0,0}, - {16817,16828,18138 ,6052,6005,6001 ,0,0,0}, {18182,18183,16820 ,6055,6057,6058 ,0,0,0}, - {18171,16818,16817 ,6041,6056,6052 ,0,0,0}, {16814,18184,16815 ,6059,6060,6061 ,0,0,0}, - {16818,18182,16820 ,6056,6055,6058 ,0,0,0}, {16806,16815,18185 ,6062,6061,6063 ,0,0,0}, - {18184,16814,18183 ,6060,6059,6057 ,0,0,0}, {16833,18146,18153 ,6020,6011,6019 ,0,0,0}, - {18146,16833,16831 ,6011,6020,6018 ,0,0,0}, {18148,18186,18145 ,6013,6064,6010 ,0,0,0}, - {18153,18141,16825 ,6019,6004,6006 ,0,0,0}, {18187,18153,18145 ,6065,6019,6010 ,0,0,0}, - {18140,18139,18142 ,6003,6002,6007 ,0,0,0}, {18187,18139,18141 ,6065,6002,6004 ,0,0,0}, - {18182,18188,18183 ,6055,6066,6057 ,0,0,0}, {18141,18139,18138 ,6004,6002,6001 ,0,0,0}, - {18189,18190,18184 ,6067,6068,6060 ,0,0,0}, {18171,18138,18140 ,6041,6001,6003 ,0,0,0}, - {18188,18182,18170 ,6066,6055,6040 ,0,0,0}, {16815,18184,18185 ,6061,6060,6063 ,0,0,0}, - {16820,18183,16814 ,6058,6057,6059 ,0,0,0}, {18183,18188,18189 ,6057,6066,6067 ,0,0,0}, - {18191,18185,18184 ,6069,6063,6060 ,0,0,0}, {18146,18145,18153 ,6011,6010,6019 ,0,0,0}, - {18192,18186,18148 ,6070,6064,6013 ,0,0,0}, {18192,18161,18186 ,6070,6031,6064 ,0,0,0}, - {18153,18187,18141 ,6019,6065,6004 ,0,0,0}, {18186,18193,18187 ,6064,6071,6065 ,0,0,0}, - {18143,18178,18170 ,6008,6048,6040 ,0,0,0}, {18193,18142,18139 ,6071,6007,6002 ,0,0,0}, - {18165,18190,18189 ,6035,6068,6067 ,0,0,0}, {18164,18190,18165 ,6034,6068,6035 ,0,0,0}, - {18171,18170,18182 ,6041,6040,6055 ,0,0,0}, {18140,18143,18170 ,6003,6008,6040 ,0,0,0}, - {18183,18189,18184 ,6057,6067,6060 ,0,0,0}, {18178,18175,18188 ,6048,6045,6066 ,0,0,0}, - {18184,18190,18191 ,6060,6068,6069 ,0,0,0}, {18189,18175,18165 ,6067,6045,6035 ,0,0,0}, - {18194,18191,18190 ,6072,6069,6068 ,0,0,0}, {18145,18186,18187 ,6010,6064,6065 ,0,0,0}, - {18162,18161,18192 ,6032,6031,6070 ,0,0,0}, {18195,18154,18196 ,6073,6021,6074 ,0,0,0}, - {18187,18193,18139 ,6065,6071,6002 ,0,0,0}, {18197,18193,18161 ,6075,6071,6031 ,0,0,0}, - {18178,18143,18166 ,6048,6008,6036 ,0,0,0}, {18197,18144,18142 ,6075,6009,6007 ,0,0,0}, - {18198,18163,18176 ,6076,6033,6046 ,0,0,0}, {18188,18175,18189 ,6066,6045,6067 ,0,0,0}, - {18170,18178,18188 ,6040,6048,6066 ,0,0,0}, {18178,18166,18177 ,6048,6036,6047 ,0,0,0}, - {18164,18163,18199 ,6034,6033,6077 ,0,0,0}, {18177,18176,18175 ,6047,6046,6045 ,0,0,0}, - {18190,18164,18194 ,6068,6034,6072 ,0,0,0}, {18165,18176,18163 ,6035,6046,6033 ,0,0,0}, - {18200,18194,18164 ,6078,6072,6034 ,0,0,0}, {18186,18161,18193 ,6064,6031,6071 ,0,0,0}, - {18156,18155,18162 ,6023,6022,6032 ,0,0,0}, {18144,18201,18166 ,6009,6079,6036 ,0,0,0}, - {18193,18197,18142 ,6071,6075,6007 ,0,0,0}, {18202,18197,18155 ,6080,6075,6022 ,0,0,0}, - {18166,18203,18177 ,6036,6081,6047 ,0,0,0}, {18202,18201,18144 ,6080,6079,6009 ,0,0,0}, - {18177,18204,18176 ,6047,6082,6046 ,0,0,0}, {18203,18166,18201 ,6081,6036,6079 ,0,0,0}, - {18163,18173,18199 ,6033,6043,6077 ,0,0,0}, {18204,18177,18203 ,6082,6047,6081 ,0,0,0}, - {18205,18199,18172 ,6083,6077,6042 ,0,0,0}, {18198,18176,18204 ,6076,6046,6082 ,0,0,0}, - {18164,18199,18200 ,6034,6077,6078 ,0,0,0}, {18163,18198,18173 ,6033,6076,6043 ,0,0,0}, - {18205,18200,18199 ,6083,6078,6077 ,0,0,0}, {18161,18155,18197 ,6031,6022,6075 ,0,0,0}, - {18196,18154,18156 ,6074,6021,6023 ,0,0,0}, {18201,18158,18203 ,6079,6027,6081 ,0,0,0}, - {18197,18202,18144 ,6075,6080,6009 ,0,0,0}, {18154,18206,18202 ,6021,6084,6080 ,0,0,0}, - {18203,18157,18204 ,6081,6026,6082 ,0,0,0}, {18206,18158,18201 ,6084,6027,6079 ,0,0,0}, - {18204,18207,18198 ,6082,6085,6076 ,0,0,0}, {18158,18157,18203 ,6027,6026,6081 ,0,0,0}, - {18208,18173,18198 ,6086,6043,6076 ,0,0,0}, {18207,18204,18157 ,6085,6082,6026 ,0,0,0}, - {18209,18172,18169 ,6087,6042,6039 ,0,0,0}, {18198,18207,18208 ,6076,6085,6086 ,0,0,0}, - {18208,18174,18173 ,6086,6044,6043 ,0,0,0}, {18205,18172,18209 ,6083,6042,6087 ,0,0,0}, - {18199,18173,18172 ,6077,6043,6042 ,0,0,0}, {18155,18154,18202 ,6022,6021,6080 ,0,0,0}, - {18210,18195,18196 ,6088,6073,6074 ,0,0,0}, {18211,18207,18157 ,6089,6085,6026 ,0,0,0}, - {18202,18206,18201 ,6080,6084,6079 ,0,0,0}, {18195,18150,18206 ,6073,6015,6084 ,0,0,0}, - {18212,18208,18207 ,6090,6086,6085 ,0,0,0}, {18150,18159,18158 ,6015,6028,6027 ,0,0,0}, - {18213,18174,18208 ,6091,6044,6086 ,0,0,0}, {18159,18211,18157 ,6028,6089,6026 ,0,0,0}, - {18181,18167,18214 ,6051,6037,6092 ,0,0,0}, {18211,18212,18207 ,6089,6090,6085 ,0,0,0}, - {18169,18174,18215 ,6039,6044,6093 ,0,0,0}, {18213,18208,18212 ,6091,6086,6090 ,0,0,0}, - {18215,18174,18213 ,6093,6044,6091 ,0,0,0}, {18209,18169,18168 ,6087,6039,6038 ,0,0,0}, - {18172,18174,18169 ,6042,6044,6039 ,0,0,0}, {18154,18195,18206 ,6021,6073,6084 ,0,0,0}, - {18151,18210,18160 ,6016,6088,6029 ,0,0,0}, {18149,18216,18159 ,6014,6094,6028 ,0,0,0}, - {18206,18150,18158 ,6084,6015,6027 ,0,0,0}, {18149,18159,18150 ,6014,6028,6015 ,0,0,0}, - {18216,18217,18211 ,6094,6095,6089 ,0,0,0}, {18216,18211,18159 ,6094,6089,6028 ,0,0,0}, - {18217,18218,18212 ,6095,6096,6090 ,0,0,0}, {18217,18212,18211 ,6095,6090,6089 ,0,0,0}, - {18218,18219,18213 ,6096,6097,6091 ,0,0,0}, {18218,18213,18212 ,6096,6091,6090 ,0,0,0}, - {18219,18214,18215 ,6097,6092,6093 ,0,0,0}, {18215,18213,18219 ,6093,6091,6097 ,0,0,0}, - {18214,18167,18215 ,6092,6037,6093 ,0,0,0}, {18168,18167,18180 ,6038,6037,6050 ,0,0,0}, - {18169,18215,18167 ,6039,6093,6037 ,0,0,0}, {18210,18151,18195 ,6088,6016,6073 ,0,0,0}, - {18150,18195,18151 ,6015,6073,6016 ,0,0,0}, {18216,17364,17358 ,6094,6025,6098 ,0,0,0}, - {17348,18149,18151 ,6024,6014,6016 ,0,0,0}, {18217,17358,17362 ,6095,6098,6099 ,0,0,0}, - {17364,18216,18149 ,6025,6094,6014 ,0,0,0}, {18218,17362,17361 ,6096,6099,6100 ,0,0,0}, - {17358,18217,18216 ,6098,6095,6094 ,0,0,0}, {18219,17361,17371 ,6097,6100,6101 ,0,0,0}, - {17362,18218,18217 ,6099,6096,6095 ,0,0,0}, {18214,17371,17333 ,6092,6101,6102 ,0,0,0}, - {17361,18219,18218 ,6100,6097,6096 ,0,0,0}, {18181,17333,17367 ,6051,6102,6053 ,0,0,0}, - {17371,18214,18219 ,6101,6092,6097 ,0,0,0}, {17367,18179,18181 ,6053,6049,6051 ,0,0,0}, - {17333,18181,18214 ,6102,6051,6092 ,0,0,0}, {18220,18221,18222 ,730,6103,6103 ,0,0,0}, - {16450,16392,16389 ,6103,730,730 ,0,0,0}, {18223,18221,18224 ,6104,6103,6105 ,0,0,0}, - {18223,18225,18226 ,6104,6106,6103 ,0,0,0}, {18227,18222,18228 ,6107,6103,6108 ,0,0,0}, - {18225,18229,18230 ,6106,6109,6110 ,0,0,0}, {18231,18232,18228 ,6103,6111,6108 ,0,0,0}, - {18230,18233,18234 ,6110,6112,6110 ,0,0,0}, {18235,18231,18236 ,6111,6103,6103 ,0,0,0}, - {18234,18237,18238 ,6110,6113,6112 ,0,0,0}, {18238,18239,18240 ,6112,6109,6110 ,0,0,0}, - {18240,18241,18242 ,6110,6106,6114 ,0,0,0}, {18236,18243,18244 ,6103,730,6115 ,0,0,0}, - {18245,18242,18246 ,6105,6114,6104 ,0,0,0}, {18247,18248,18249 ,6111,730,6111 ,0,0,0}, - {18250,18242,18245 ,6111,6114,6105 ,0,0,0}, {18249,18251,18252 ,6111,6110,6114 ,0,0,0}, - {18253,18254,18255 ,730,6114,6108 ,0,0,0}, {16398,16463,16465 ,6110,6111,6110 ,0,0,0}, - {18256,18257,18258 ,6115,730,6111 ,0,0,0}, {16462,16397,16460 ,730,730,6114 ,0,0,0}, - {18259,18260,16381 ,6111,6110,6110 ,0,0,0}, {16393,16456,16395 ,730,6114,6103 ,0,0,0}, - {16378,16428,16425 ,730,730,6114 ,0,0,0}, {16392,16451,16454 ,730,730,6103 ,0,0,0}, - {16422,16374,16423 ,6114,730,730 ,0,0,0}, {16448,16450,16389 ,730,6103,730 ,0,0,0}, - {16372,16416,16369 ,6103,6103,730 ,0,0,0}, {16442,16444,16383 ,730,730,730 ,0,0,0}, - {16410,16407,16368 ,730,730,730 ,0,0,0}, {16436,16382,16362 ,730,730,730 ,0,0,0}, - {16366,16405,16404 ,730,730,730 ,0,0,0}, {16366,16367,16405 ,730,730,730 ,0,0,0}, - {16368,16407,16367 ,730,730,730 ,0,0,0}, {16436,16362,16400 ,730,730,730 ,0,0,0}, - {16362,16366,16401 ,730,730,730 ,0,0,0}, {16411,16369,16413 ,6103,730,730 ,0,0,0}, - {16368,16369,16411 ,730,730,6103 ,0,0,0}, {16382,16439,16383 ,730,730,730 ,0,0,0}, - {16382,16438,16439 ,730,730,730 ,0,0,0}, {16372,16374,16419 ,6103,730,6103 ,0,0,0}, - {16372,16419,16417 ,6103,6103,730 ,0,0,0}, {16389,16387,16445 ,730,730,6103 ,0,0,0}, - {16444,16387,16383 ,730,730,730 ,0,0,0}, {16378,16425,16375 ,730,6114,6103 ,0,0,0}, - {16374,16375,16423 ,730,6103,730 ,0,0,0}, {16392,16450,16451 ,730,6103,730 ,0,0,0}, - {16431,16429,16381 ,6110,6111,6110 ,0,0,0}, {16378,16381,16429 ,730,6110,6111 ,0,0,0}, - {16393,16454,16456 ,730,6103,6114 ,0,0,0}, {16392,16454,16393 ,730,6103,730 ,0,0,0}, - {18258,18261,18259 ,6111,6111,6111 ,0,0,0}, {18262,18259,18261 ,6114,6111,6111 ,0,0,0}, - {16456,16457,16395 ,6114,730,6103 ,0,0,0}, {16395,16460,16397 ,6103,6114,730 ,0,0,0}, - {16457,16460,16395 ,730,6114,6103 ,0,0,0}, {16462,16463,16397 ,730,6111,730 ,0,0,0}, - {18263,18255,18254 ,6107,6108,6114 ,0,0,0}, {16398,16397,16463 ,6110,730,6111 ,0,0,0}, - {16465,18251,16398 ,6110,6110,6110 ,0,0,0}, {18254,18250,18264 ,6114,6111,730 ,0,0,0}, - {18265,18266,18253 ,6111,6110,730 ,0,0,0}, {18266,18256,18258 ,6110,6115,6111 ,0,0,0}, - {18239,18241,18240 ,6109,6106,6110 ,0,0,0}, {16448,16389,16445 ,730,730,6103 ,0,0,0}, - {16445,16387,16444 ,6103,730,730 ,0,0,0}, {16442,16383,16439 ,730,730,730 ,0,0,0}, - {16438,16382,16436 ,730,730,730 ,0,0,0}, {16400,16362,16401 ,730,730,730 ,0,0,0}, - {16401,16366,16404 ,730,730,730 ,0,0,0}, {16405,16367,16407 ,730,730,730 ,0,0,0}, - {16410,16368,16411 ,730,730,6103 ,0,0,0}, {16413,16369,16416 ,730,730,6103 ,0,0,0}, - {16416,16372,16417 ,6103,6103,730 ,0,0,0}, {16419,16374,16422 ,6103,730,6114 ,0,0,0}, - {16423,16375,16425 ,730,6103,6114 ,0,0,0}, {16428,16378,16429 ,730,730,6111 ,0,0,0}, - {16431,16381,18260 ,6110,6110,6110 ,0,0,0}, {18260,18259,18262 ,6110,6111,6114 ,0,0,0}, - {18261,18258,18257 ,6111,6111,730 ,0,0,0}, {18256,18266,18265 ,6115,6110,6111 ,0,0,0}, - {18267,18253,18255 ,6111,730,6108 ,0,0,0}, {18253,18267,18265 ,730,6111,6111 ,0,0,0}, - {18263,18254,18264 ,6107,6114,730 ,0,0,0}, {18264,18250,18245 ,730,6111,6105 ,0,0,0}, - {18246,18242,18241 ,6104,6114,6106 ,0,0,0}, {18240,18234,18238 ,6110,6110,6112 ,0,0,0}, - {18237,18234,18233 ,6113,6110,6112 ,0,0,0}, {18233,18230,18229 ,6112,6110,6109 ,0,0,0}, - {18225,18230,18226 ,6106,6110,6103 ,0,0,0}, {18223,18226,18221 ,6104,6103,6103 ,0,0,0}, - {18220,18224,18221 ,730,6105,6103 ,0,0,0}, {18227,18220,18222 ,6107,730,6103 ,0,0,0}, - {18231,18228,18222 ,6103,6108,6103 ,0,0,0}, {18231,18235,18232 ,6103,6111,6111 ,0,0,0}, - {18236,18244,18235 ,6103,6115,6111 ,0,0,0}, {18236,18248,18243 ,6103,730,730 ,0,0,0}, - {18247,18249,18252 ,6111,6111,6114 ,0,0,0}, {18243,18248,18247 ,730,730,6111 ,0,0,0}, - {18251,18249,16398 ,6110,6111,6110 ,0,0,0}, {16434,16402,18268 ,6116,6117,6118 ,0,0,0}, - {16437,18269,18270 ,6119,6120,6121 ,0,0,0}, {18271,18272,16589 ,6122,6123,6124 ,0,0,0}, - {16679,16449,16676 ,6125,6126,6127 ,0,0,0}, {16605,16604,17016 ,6128,6129,6130 ,0,0,0}, - {16535,16538,16459 ,6131,6132,6122 ,0,0,0}, {18273,16540,18274 ,6133,6134,6135 ,0,0,0}, - {18275,18276,18277 ,6136,6137,6138 ,0,0,0}, {16406,16486,16489 ,6122,6120,6139 ,0,0,0}, - {18272,16574,16579 ,6123,6140,6141 ,0,0,0}, {18278,16657,16659 ,6139,6142,6143 ,0,0,0}, - {16929,18279,16930 ,6144,6145,6146 ,0,0,0}, {16987,18280,16980 ,6147,6148,6149 ,0,0,0}, - {16507,18281,16510 ,6150,6144,6150 ,0,0,0}, {18282,16565,16964 ,6151,6134,6152 ,0,0,0}, - {18283,16466,18284 ,6145,6153,6154 ,0,0,0}, {18282,16964,18285 ,6151,6152,6155 ,0,0,0}, - {18286,16964,16963 ,6156,6152,6157 ,0,0,0}, {18287,18288,18289 ,6158,6144,6159 ,0,0,0}, - {18290,18291,18292 ,6160,6161,6162 ,0,0,0}, {16963,18293,18286 ,6157,6163,6156 ,0,0,0}, - {18294,18295,16963 ,6158,6164,6157 ,0,0,0}, {16969,18296,18294 ,6155,6165,6158 ,0,0,0}, - {18297,16974,18298 ,6166,6167,6116 ,0,0,0}, {16969,18294,16963 ,6155,6158,6157 ,0,0,0}, - {16981,18298,16974 ,6168,6116,6167 ,0,0,0}, {18289,18277,18276 ,6159,6138,6137 ,0,0,0}, - {18299,18300,18301 ,6122,6169,6170 ,0,0,0}, {18302,16969,16967 ,6171,6155,6172 ,0,0,0}, - {16967,18303,18302 ,6172,6118,6171 ,0,0,0}, {18304,18305,16977 ,6173,6174,6175 ,0,0,0}, - {16967,16966,18303 ,6172,6176,6118 ,0,0,0}, {16966,18305,18306 ,6176,6174,6177 ,0,0,0}, - {18307,16630,16629 ,6120,6146,6154 ,0,0,0}, {16966,16977,18305 ,6176,6175,6174 ,0,0,0}, - {18304,16977,16972 ,6173,6175,6178 ,0,0,0}, {18284,16468,18308 ,6154,6120,6145 ,0,0,0}, - {18309,18310,18311 ,6177,6179,6180 ,0,0,0}, {18312,18304,16972 ,6181,6173,6178 ,0,0,0}, - {18310,18313,18299 ,6179,6182,6122 ,0,0,0}, {18287,18314,18288 ,6158,6183,6144 ,0,0,0}, - {18301,18300,18315 ,6170,6169,6184 ,0,0,0}, {16981,16980,18316 ,6168,6149,6185 ,0,0,0}, - {18317,16414,18318 ,6186,6187,6119 ,0,0,0}, {16510,18319,16511 ,6150,6144,6188 ,0,0,0}, - {18320,16932,18321 ,6145,6144,6150 ,0,0,0}, {18314,16697,18322 ,6183,6189,6190 ,0,0,0}, - {16927,18323,18324 ,6154,6120,6127 ,0,0,0}, {16664,16663,17027 ,6191,6142,6192 ,0,0,0}, - {18269,16437,16435 ,6120,6119,6122 ,0,0,0}, {17021,16595,16594 ,6193,6194,6195 ,0,0,0}, - {16666,16922,16916 ,6196,6186,6197 ,0,0,0}, {16542,16464,16461 ,6196,6134,6138 ,0,0,0}, - {18272,16693,16688 ,6123,6198,6199 ,0,0,0}, {16459,16538,16461 ,6122,6132,6138 ,0,0,0}, - {16534,16535,16458 ,6157,6131,6137 ,0,0,0}, {16534,16458,16455 ,6157,6137,6131 ,0,0,0}, - {16453,16532,16455 ,6200,6143,6131 ,0,0,0}, {16441,16652,16670 ,6117,6201,6202 ,0,0,0}, - {18275,18325,18326 ,6136,6200,6156 ,0,0,0}, {16526,18327,16521 ,6118,6203,6132 ,0,0,0}, - {18328,16528,16530 ,6133,6204,6133 ,0,0,0}, {16458,16535,16459 ,6137,6131,6122 ,0,0,0}, - {16538,16542,16461 ,6132,6196,6138 ,0,0,0}, {16528,18329,16523 ,6204,6153,6201 ,0,0,0}, - {18330,16521,18327 ,6201,6132,6203 ,0,0,0}, {16443,16441,16670 ,6187,6117,6202 ,0,0,0}, - {16455,16532,16534 ,6131,6143,6157 ,0,0,0}, {16517,16947,16949 ,6132,6144,6205 ,0,0,0}, - {16530,16682,18328 ,6133,6201,6133 ,0,0,0}, {16453,16682,16532 ,6200,6201,6143 ,0,0,0}, - {16954,16516,16949 ,6206,6116,6205 ,0,0,0}, {16548,16954,16956 ,6207,6206,6204 ,0,0,0}, - {18331,18332,16522 ,6132,6119,6207 ,0,0,0}, {16947,16517,16521 ,6144,6132,6132 ,0,0,0}, - {16516,16954,16546 ,6116,6206,6121 ,0,0,0}, {16516,16517,16949 ,6116,6132,6205 ,0,0,0}, - {16957,16552,16956 ,6208,6207,6204 ,0,0,0}, {16548,16546,16954 ,6207,6121,6206 ,0,0,0}, - {16549,16548,16956 ,6209,6207,6204 ,0,0,0}, {16957,16959,16555 ,6208,6142,6196 ,0,0,0}, - {16552,16549,16956 ,6207,6209,6204 ,0,0,0}, {16554,16552,16957 ,6133,6207,6208 ,0,0,0}, - {16957,16555,16554 ,6208,6196,6133 ,0,0,0}, {16959,16558,16555 ,6142,6134,6196 ,0,0,0}, - {16962,16560,16959 ,6148,6131,6142 ,0,0,0}, {16959,16560,16558 ,6142,6131,6134 ,0,0,0}, - {16962,16561,16560 ,6148,6205,6131 ,0,0,0}, {16561,16962,16564 ,6205,6148,6204 ,0,0,0}, - {16962,16565,16564 ,6148,6134,6204 ,0,0,0}, {18286,18285,16964 ,6156,6155,6152 ,0,0,0}, - {18302,18296,16969 ,6171,6165,6155 ,0,0,0}, {18295,18293,16963 ,6164,6163,6157 ,0,0,0}, - {18303,16966,18306 ,6118,6176,6177 ,0,0,0}, {18297,18333,16972 ,6166,6210,6178 ,0,0,0}, - {18334,16986,18335 ,6157,6190,6211 ,0,0,0}, {18312,18336,18337 ,6181,6212,6182 ,0,0,0}, - {16578,18272,16579 ,6174,6123,6141 ,0,0,0}, {18338,18339,18272 ,6213,6214,6123 ,0,0,0}, - {17024,17021,16568 ,6215,6193,6216 ,0,0,0}, {16707,16709,16569 ,6217,6218,6219 ,0,0,0}, - {16594,16568,17021 ,6195,6216,6193 ,0,0,0}, {16599,16598,17013 ,6220,6221,6222 ,0,0,0}, - {16595,17020,16598 ,6194,6223,6221 ,0,0,0}, {17016,16604,16601 ,6130,6129,6181 ,0,0,0}, - {16601,17013,17016 ,6181,6222,6130 ,0,0,0}, {16610,17017,16611 ,6224,6225,6226 ,0,0,0}, - {16607,17016,17017 ,6227,6130,6225 ,0,0,0}, {16687,18272,16688 ,6212,6123,6199 ,0,0,0}, - {16618,18340,16619 ,6203,6228,6201 ,0,0,0}, {16709,16570,16569 ,6218,6229,6219 ,0,0,0}, - {18341,18342,18343 ,6230,6231,6232 ,0,0,0}, {16709,16710,16989 ,6218,6200,6233 ,0,0,0}, - {16610,16607,17017 ,6224,6227,6225 ,0,0,0}, {17017,16613,16611 ,6225,6234,6226 ,0,0,0}, - {16607,16605,17016 ,6227,6128,6130 ,0,0,0}, {16687,16686,18272 ,6212,6235,6123 ,0,0,0}, - {16599,17013,16601 ,6220,6222,6181 ,0,0,0}, {17020,17013,16598 ,6223,6222,6221 ,0,0,0}, - {17021,17020,16595 ,6193,6223,6194 ,0,0,0}, {16570,17024,16568 ,6229,6215,6216 ,0,0,0}, - {17024,16570,16989 ,6215,6229,6233 ,0,0,0}, {18339,16694,18272 ,6214,6236,6123 ,0,0,0}, - {16697,16694,18322 ,6189,6236,6190 ,0,0,0}, {18272,18344,18345 ,6123,6170,6214 ,0,0,0}, - {16586,18272,16582 ,6237,6123,6167 ,0,0,0}, {18271,18344,18272 ,6122,6170,6123 ,0,0,0}, - {16588,18346,18347 ,6238,6180,6179 ,0,0,0}, {18348,16625,18349 ,6197,6165,6196 ,0,0,0}, - {18350,16430,18351 ,6131,6122,6132 ,0,0,0}, {16593,18352,18346 ,6239,6240,6180 ,0,0,0}, - {18353,18354,18292 ,6171,6152,6162 ,0,0,0}, {16421,18355,16420 ,6204,6208,6126 ,0,0,0}, - {18356,18315,18357 ,6241,6184,6136 ,0,0,0}, {18358,16636,16639 ,6179,6179,6202 ,0,0,0}, - {16648,18355,16647 ,6127,6208,6242 ,0,0,0}, {16773,18359,18360 ,6156,6200,6136 ,0,0,0}, - {16776,16778,18361 ,6137,6135,6133 ,0,0,0}, {18362,18363,18364 ,6207,6133,6208 ,0,0,0}, - {16734,16767,16770 ,6196,6158,6159 ,0,0,0}, {16757,16727,16722 ,6181,6243,6139 ,0,0,0}, - {16741,16743,18365 ,6244,6245,6246 ,0,0,0}, {16720,18366,18367 ,6247,6190,6136 ,0,0,0}, - {18368,18342,18369 ,6248,6231,6170 ,0,0,0}, {18370,18371,16749 ,6152,6249,6250 ,0,0,0}, - {18372,18342,18368 ,6251,6231,6248 ,0,0,0}, {18373,18374,18375 ,6252,6253,6254 ,0,0,0}, - {18374,18341,18375 ,6253,6230,6254 ,0,0,0}, {18376,18377,18378 ,6255,6256,6257 ,0,0,0}, - {18379,18380,18381 ,6258,6259,6260 ,0,0,0}, {18374,18373,18381 ,6253,6252,6260 ,0,0,0}, - {18381,18380,18374 ,6260,6259,6253 ,0,0,0}, {18380,18379,18382 ,6259,6258,6261 ,0,0,0}, - {18383,18378,18384 ,6262,6257,6263 ,0,0,0}, {18382,18384,18380 ,6261,6263,6259 ,0,0,0}, - {18378,18377,18384 ,6257,6256,6263 ,0,0,0}, {18385,18386,18377 ,6264,6265,6256 ,0,0,0}, - {18382,18383,18384 ,6261,6262,6263 ,0,0,0}, {18376,18385,18377 ,6255,6264,6256 ,0,0,0}, - {18375,18341,18343 ,6254,6230,6232 ,0,0,0}, {18387,18388,16750 ,6138,6134,6266 ,0,0,0}, - {18343,18342,18372 ,6232,6231,6251 ,0,0,0}, {18369,18388,18387 ,6170,6134,6138 ,0,0,0}, - {18389,16743,16744 ,6267,6245,6268 ,0,0,0}, {16721,18367,18390 ,6167,6136,6199 ,0,0,0}, - {16738,16741,18366 ,6235,6244,6190 ,0,0,0}, {18391,16792,18392 ,6197,6164,6191 ,0,0,0}, - {16786,16785,18393 ,6171,6118,6269 ,0,0,0}, {16731,16728,16761 ,6270,6270,6174 ,0,0,0}, - {18391,16794,16792 ,6197,6163,6164 ,0,0,0}, {16766,16731,16761 ,6127,6270,6174 ,0,0,0}, - {18394,18326,18325 ,6137,6156,6200 ,0,0,0}, {18395,18396,18397 ,6213,6271,6169 ,0,0,0}, - {16755,16757,18398 ,6173,6181,6272 ,0,0,0}, {16797,16794,18391 ,6156,6163,6197 ,0,0,0}, - {18387,18399,18369 ,6138,6273,6170 ,0,0,0}, {18400,16798,16797 ,6201,6155,6156 ,0,0,0}, - {18400,16802,16800 ,6201,6134,6151 ,0,0,0}, {18401,18355,18402 ,6214,6208,6133 ,0,0,0}, - {18401,16415,16418 ,6214,6208,6117 ,0,0,0}, {18403,18404,18405 ,6190,6214,6199 ,0,0,0}, - {16792,16791,18392 ,6164,6158,6191 ,0,0,0}, {16786,18393,18392 ,6171,6269,6191 ,0,0,0}, - {18406,18407,18408 ,6274,6118,6183 ,0,0,0}, {18409,18410,18411 ,6149,6275,6214 ,0,0,0}, - {18412,18368,18399 ,6243,6248,6273 ,0,0,0}, {18412,18399,18413 ,6243,6273,6276 ,0,0,0}, - {18411,18301,18315 ,6214,6170,6184 ,0,0,0}, {18299,18313,18300 ,6122,6182,6169 ,0,0,0}, - {18311,18414,18309 ,6180,6244,6177 ,0,0,0}, {18310,18309,18313 ,6179,6177,6182 ,0,0,0}, - {18287,18415,16698 ,6158,6127,6249 ,0,0,0}, {16593,18414,18352 ,6239,6244,6240 ,0,0,0}, - {18311,18352,18414 ,6180,6240,6244 ,0,0,0}, {16593,18346,16590 ,6239,6180,6277 ,0,0,0}, - {18287,16698,16697 ,6158,6249,6189 ,0,0,0}, {16589,16588,18347 ,6124,6238,6179 ,0,0,0}, - {16588,16590,18346 ,6238,6277,6180 ,0,0,0}, {16716,16984,16992 ,6278,6279,6280 ,0,0,0}, - {16984,18335,16986 ,6279,6211,6190 ,0,0,0}, {18271,16589,18347 ,6122,6124,6179 ,0,0,0}, - {18416,18272,18345 ,6275,6123,6214 ,0,0,0}, {16589,18272,16586 ,6124,6123,6237 ,0,0,0}, - {16990,16713,16992 ,6281,6282,6280 ,0,0,0}, {16700,18415,18417 ,6283,6127,6174 ,0,0,0}, - {16698,18415,16700 ,6249,6127,6283 ,0,0,0}, {18288,18277,18289 ,6144,6138,6159 ,0,0,0}, - {18275,18326,18276 ,6136,6156,6137 ,0,0,0}, {18394,18273,18274 ,6137,6133,6135 ,0,0,0}, - {18273,18394,18325 ,6133,6137,6200 ,0,0,0}, {18273,16464,16540 ,6133,6134,6134 ,0,0,0}, - {16947,18330,16945 ,6144,6201,6209 ,0,0,0}, {16540,16464,16542 ,6134,6134,6196 ,0,0,0}, - {16682,16453,16681 ,6201,6200,6158 ,0,0,0}, {16446,16443,16673 ,6208,6187,6284 ,0,0,0}, - {16679,16681,16452 ,6125,6158,6204 ,0,0,0}, {18418,16942,16943 ,6191,6165,6179 ,0,0,0}, - {16940,18419,16917 ,6142,6172,6197 ,0,0,0}, {16664,16922,16666 ,6191,6186,6196 ,0,0,0}, - {17027,16922,16664 ,6192,6186,6191 ,0,0,0}, {17027,16663,16925 ,6192,6142,6285 ,0,0,0}, - {18420,16660,16657 ,6192,6228,6142 ,0,0,0}, {16486,16406,16408 ,6120,6122,6119 ,0,0,0}, - {16409,16484,16408 ,6171,6202,6119 ,0,0,0}, {18421,16937,16935 ,6150,6144,6150 ,0,0,0}, - {18281,16507,16505 ,6144,6150,6187 ,0,0,0}, {16513,16511,18319 ,6150,6188,6144 ,0,0,0}, - {16505,18422,18281 ,6187,6144,6144 ,0,0,0}, {16479,18317,18423 ,6165,6186,6286 ,0,0,0}, - {18422,16501,18424 ,6144,6192,6144 ,0,0,0}, {16499,16498,18424 ,6145,6145,6144 ,0,0,0}, - {18425,18426,18355 ,6143,6133,6208 ,0,0,0}, {18307,18427,16630 ,6120,6176,6146 ,0,0,0}, - {18350,16427,16430 ,6131,6137,6122 ,0,0,0}, {16433,16778,16777 ,6134,6135,6134 ,0,0,0}, - {18349,16620,16619 ,6196,6139,6201 ,0,0,0}, {18348,16626,16623 ,6197,6286,6165 ,0,0,0}, - {18358,16639,18428 ,6179,6202,6139 ,0,0,0}, {16642,18428,16641 ,6203,6139,6228 ,0,0,0}, - {16776,18361,18359 ,6137,6133,6200 ,0,0,0}, {18359,16773,16776 ,6200,6156,6137 ,0,0,0}, - {18429,18430,18431 ,6209,6207,6166 ,0,0,0}, {18432,16771,18360 ,6138,6137,6136 ,0,0,0}, - {18427,16632,16630 ,6176,6191,6146 ,0,0,0}, {18433,18434,18435 ,6186,6228,6287 ,0,0,0}, - {16626,18348,18307 ,6286,6197,6120 ,0,0,0}, {16626,18307,16629 ,6286,6120,6154 ,0,0,0}, - {16625,18348,16623 ,6165,6197,6165 ,0,0,0}, {16620,18349,16625 ,6139,6196,6165 ,0,0,0}, - {18340,16618,16636 ,6228,6203,6179 ,0,0,0}, {18340,18349,16619 ,6228,6196,6201 ,0,0,0}, - {16424,18355,16421 ,6200,6208,6204 ,0,0,0}, {18358,18340,16636 ,6179,6228,6179 ,0,0,0}, - {18436,18428,16642 ,6133,6139,6203 ,0,0,0}, {16641,18428,16639 ,6228,6139,6202 ,0,0,0}, - {16424,16426,18355 ,6200,6131,6208 ,0,0,0}, {18355,18437,16647 ,6208,6207,6242 ,0,0,0}, - {16432,16777,18438 ,6138,6134,6196 ,0,0,0}, {18355,16426,16427 ,6208,6131,6137 ,0,0,0}, - {18355,16418,16420 ,6208,6117,6126 ,0,0,0}, {16415,18401,18318 ,6208,6214,6119 ,0,0,0}, - {18355,18401,16418 ,6208,6214,6117 ,0,0,0}, {18283,16495,16466 ,6145,6120,6153 ,0,0,0}, - {18439,18440,16470 ,6201,6121,6288 ,0,0,0}, {16414,16415,18318 ,6187,6208,6119 ,0,0,0}, - {18441,16472,16474 ,6139,6192,6131 ,0,0,0}, {18308,16470,18440 ,6145,6288,6121 ,0,0,0}, - {16505,16504,18422 ,6187,6145,6144 ,0,0,0}, {16504,16501,18422 ,6145,6192,6144 ,0,0,0}, - {16498,16495,18283 ,6145,6120,6145 ,0,0,0}, {18440,18442,18308 ,6121,6289,6145 ,0,0,0}, - {18433,18442,18443 ,6186,6289,6191 ,0,0,0}, {18440,18443,18442 ,6121,6191,6289 ,0,0,0}, - {18433,18435,18427 ,6186,6287,6176 ,0,0,0}, {18433,18443,18434 ,6186,6191,6228 ,0,0,0}, - {16632,18427,18435 ,6191,6176,6287 ,0,0,0}, {18444,16435,16434 ,6202,6122,6116 ,0,0,0}, - {18445,18446,16915 ,6165,6191,6187 ,0,0,0}, {18447,16943,16945 ,6126,6179,6209 ,0,0,0}, - {18448,18323,16925 ,6154,6120,6285 ,0,0,0}, {16652,16441,18449 ,6201,6117,6120 ,0,0,0}, - {18450,18451,16654 ,6197,6201,6207 ,0,0,0}, {18270,18449,16440 ,6121,6120,6171 ,0,0,0}, - {16403,16491,16490 ,6116,6120,6201 ,0,0,0}, {18270,16440,16437 ,6121,6171,6119 ,0,0,0}, - {16443,16670,16673 ,6187,6202,6284 ,0,0,0}, {16673,16675,16446 ,6284,6140,6208 ,0,0,0}, - {16447,16675,16676 ,6117,6140,6127 ,0,0,0}, {16447,16676,16449 ,6117,6127,6126 ,0,0,0}, - {16449,16679,16452 ,6126,6125,6204 ,0,0,0}, {16453,16452,16681 ,6200,6204,6158 ,0,0,0}, - {16530,16532,16682 ,6133,6143,6201 ,0,0,0}, {16526,16522,18332 ,6118,6207,6119 ,0,0,0}, - {16528,18328,18329 ,6204,6133,6153 ,0,0,0}, {18331,16522,16523 ,6132,6207,6201 ,0,0,0}, - {18331,16523,18329 ,6132,6201,6153 ,0,0,0}, {18327,16526,18332 ,6203,6118,6119 ,0,0,0}, - {16521,18330,16947 ,6132,6201,6144 ,0,0,0}, {18447,16945,18330 ,6126,6209,6201 ,0,0,0}, - {18452,16942,18418 ,6242,6165,6191 ,0,0,0}, {18418,16943,18447 ,6191,6179,6126 ,0,0,0}, - {16940,18452,18453 ,6142,6242,6197 ,0,0,0}, {18452,16940,16942 ,6242,6142,6165 ,0,0,0}, - {18419,18445,16917 ,6172,6165,6197 ,0,0,0}, {18453,18419,16940 ,6197,6172,6142 ,0,0,0}, - {16915,18446,16916 ,6187,6191,6197 ,0,0,0}, {16917,18445,16915 ,6197,6165,6187 ,0,0,0}, - {16666,16916,18454 ,6196,6197,6202 ,0,0,0}, {16916,18446,18454 ,6197,6191,6202 ,0,0,0}, - {18314,18287,16697 ,6183,6158,6189 ,0,0,0}, {18417,18455,18456 ,6174,6118,6273 ,0,0,0}, - {16691,18272,16694 ,6290,6123,6236 ,0,0,0}, {18339,18322,16694 ,6214,6190,6236 ,0,0,0}, - {16691,16693,18272 ,6290,6198,6123 ,0,0,0}, {16583,18272,16578 ,6152,6123,6174 ,0,0,0}, - {16704,16707,16575 ,6124,6217,6291 ,0,0,0}, {16686,16574,18272 ,6235,6140,6123 ,0,0,0}, - {16704,16575,16574 ,6124,6291,6140 ,0,0,0}, {16704,16574,16686 ,6124,6140,6235 ,0,0,0}, - {16707,16569,16575 ,6217,6219,6291 ,0,0,0}, {16709,16989,16570 ,6218,6233,6229 ,0,0,0}, - {16710,16713,16990 ,6200,6282,6281 ,0,0,0}, {16710,16990,16989 ,6200,6281,6233 ,0,0,0}, - {16715,16716,16992 ,6269,6278,6280 ,0,0,0}, {16713,16715,16992 ,6282,6269,6280 ,0,0,0}, - {16984,16716,18457 ,6279,6278,6292 ,0,0,0}, {18457,18335,16984 ,6292,6211,6279 ,0,0,0}, - {18458,16986,18334 ,6293,6190,6157 ,0,0,0}, {16987,18458,18459 ,6147,6293,6266 ,0,0,0}, - {18458,16987,16986 ,6293,6147,6190 ,0,0,0}, {18280,18460,16980 ,6148,6273,6149 ,0,0,0}, - {18459,18280,16987 ,6266,6148,6147 ,0,0,0}, {18316,18461,16981 ,6185,6294,6168 ,0,0,0}, - {18460,18316,16980 ,6273,6185,6149 ,0,0,0}, {16972,16974,18297 ,6178,6167,6166 ,0,0,0}, - {18461,18298,16981 ,6294,6116,6168 ,0,0,0}, {18333,18312,16972 ,6210,6181,6178 ,0,0,0}, - {18337,18336,18455 ,6182,6212,6118 ,0,0,0}, {18333,18336,18312 ,6210,6212,6181 ,0,0,0}, - {18417,18456,16700 ,6174,6273,6283 ,0,0,0}, {18455,18336,18456 ,6118,6212,6273 ,0,0,0}, - {16722,18390,18398 ,6139,6199,6272 ,0,0,0}, {16753,18462,16782 ,6174,6295,6177 ,0,0,0}, - {18353,18412,18413 ,6171,6243,6276 ,0,0,0}, {16788,16786,18392 ,6165,6171,6191 ,0,0,0}, - {18462,16753,18463 ,6295,6174,6162 ,0,0,0}, {18398,16757,16722 ,6272,6181,6139 ,0,0,0}, - {16721,18390,16722 ,6167,6199,6139 ,0,0,0}, {16720,18367,16721 ,6247,6136,6167 ,0,0,0}, - {16738,18366,16720 ,6235,6190,6247 ,0,0,0}, {18365,18366,16741 ,6246,6190,6244 ,0,0,0}, - {18389,18365,16743 ,6267,6246,6245 ,0,0,0}, {16744,16747,18371 ,6268,6185,6249 ,0,0,0}, - {18371,18389,16744 ,6249,6267,6268 ,0,0,0}, {16750,18370,16749 ,6266,6152,6250 ,0,0,0}, - {16749,18371,16747 ,6250,6249,6185 ,0,0,0}, {16750,18388,18370 ,6266,6134,6152 ,0,0,0}, - {18368,18369,18399 ,6248,6170,6273 ,0,0,0}, {18356,18464,18315 ,6241,6296,6184 ,0,0,0}, - {18353,18413,18354 ,6171,6276,6152 ,0,0,0}, {18356,18357,18465 ,6241,6136,6200 ,0,0,0}, - {18465,18291,18290 ,6200,6161,6160 ,0,0,0}, {18290,18292,18354 ,6160,6162,6152 ,0,0,0}, - {18465,18357,18291 ,6200,6136,6161 ,0,0,0}, {18464,18409,18411 ,6296,6149,6214 ,0,0,0}, - {18411,18315,18464 ,6214,6184,6296 ,0,0,0}, {18396,18410,18409 ,6271,6275,6149 ,0,0,0}, - {18397,18404,18395 ,6169,6214,6213 ,0,0,0}, {18396,18395,18410 ,6271,6213,6275 ,0,0,0}, - {18405,18406,18403 ,6199,6274,6190 ,0,0,0}, {18397,18405,18404 ,6169,6199,6214 ,0,0,0}, - {18408,18407,18466 ,6183,6118,6144 ,0,0,0}, {18403,18406,18408 ,6190,6274,6183 ,0,0,0}, - {16734,18466,18407 ,6196,6144,6118 ,0,0,0}, {16409,16412,16483 ,6171,6117,6139 ,0,0,0}, - {18319,16515,16513 ,6144,6150,6150 ,0,0,0}, {18319,16510,18281 ,6144,6150,6144 ,0,0,0}, - {16480,16483,16412 ,6197,6139,6117 ,0,0,0}, {16414,18317,16480 ,6187,6186,6197 ,0,0,0}, - {18283,18424,16498 ,6145,6144,6145 ,0,0,0}, {16501,16499,18424 ,6192,6145,6144 ,0,0,0}, - {16468,16470,18308 ,6120,6288,6145 ,0,0,0}, {16466,16468,18284 ,6153,6120,6154 ,0,0,0}, - {16474,16479,18423 ,6131,6165,6286 ,0,0,0}, {16476,18467,18439 ,6144,6242,6201 ,0,0,0}, - {18439,16470,16476 ,6201,6288,6144 ,0,0,0}, {18423,18441,16474 ,6286,6139,6131 ,0,0,0}, - {16472,18441,18467 ,6192,6139,6242 ,0,0,0}, {16472,18467,16476 ,6192,6242,6144 ,0,0,0}, - {16479,16480,18317 ,6165,6197,6186 ,0,0,0}, {16412,16414,16480 ,6117,6187,6197 ,0,0,0}, - {16409,16483,16484 ,6171,6139,6202 ,0,0,0}, {16408,16484,16486 ,6119,6202,6120 ,0,0,0}, - {16491,16403,16489 ,6120,6116,6139 ,0,0,0}, {16406,16489,16403 ,6122,6139,6116 ,0,0,0}, - {16403,16490,16402 ,6116,6201,6117 ,0,0,0}, {16435,18444,18269 ,6122,6202,6120 ,0,0,0}, - {16402,16490,18268 ,6117,6201,6118 ,0,0,0}, {18444,16434,18268 ,6202,6116,6118 ,0,0,0}, - {18449,16441,16440 ,6120,6117,6171 ,0,0,0}, {18450,16653,18449 ,6197,6197,6120 ,0,0,0}, - {16652,18449,16653 ,6201,6120,6197 ,0,0,0}, {16660,18468,16663 ,6228,6145,6142 ,0,0,0}, - {16659,16654,18451 ,6143,6207,6201 ,0,0,0}, {16654,16653,18450 ,6207,6197,6197 ,0,0,0}, - {18420,16657,18278 ,6192,6142,6139 ,0,0,0}, {18278,16659,18451 ,6139,6143,6201 ,0,0,0}, - {16660,18420,18468 ,6228,6192,6145 ,0,0,0}, {18448,16925,16663 ,6154,6285,6142 ,0,0,0}, - {18448,16663,18468 ,6154,6142,6145 ,0,0,0}, {18323,16927,16925 ,6120,6154,6285 ,0,0,0}, - {16929,18324,18469 ,6144,6127,6187 ,0,0,0}, {18324,16929,16927 ,6127,6144,6154 ,0,0,0}, - {18469,18279,16929 ,6187,6145,6144 ,0,0,0}, {16930,18470,18321 ,6146,6145,6150 ,0,0,0}, - {18279,18470,16930 ,6145,6145,6146 ,0,0,0}, {16930,18321,16932 ,6146,6150,6144 ,0,0,0}, - {16935,16932,18471 ,6150,6144,6146 ,0,0,0}, {18320,18471,16932 ,6145,6146,6144 ,0,0,0}, - {16935,18472,18421 ,6150,6144,6150 ,0,0,0}, {16935,18471,18472 ,6150,6146,6144 ,0,0,0}, - {18473,16937,18474 ,6150,6144,6150 ,0,0,0}, {16937,18421,18474 ,6144,6150,6150 ,0,0,0}, - {16515,16937,18473 ,6150,6144,6150 ,0,0,0}, {18475,18476,18477 ,6131,6203,6207 ,0,0,0}, - {18432,18466,16770 ,6138,6144,6159 ,0,0,0}, {18400,16797,18391 ,6201,6156,6197 ,0,0,0}, - {18400,16800,16798 ,6201,6151,6155 ,0,0,0}, {18466,16734,16770 ,6144,6196,6159 ,0,0,0}, - {16755,18463,16753 ,6173,6162,6174 ,0,0,0}, {16782,18462,16785 ,6177,6295,6118 ,0,0,0}, - {16791,16788,18392 ,6158,6165,6191 ,0,0,0}, {18462,18393,16785 ,6295,6269,6118 ,0,0,0}, - {18463,16755,18398 ,6162,6173,6272 ,0,0,0}, {16757,16763,16727 ,6181,6182,6243 ,0,0,0}, - {16766,16767,16732 ,6127,6158,6297 ,0,0,0}, {16759,16725,16763 ,6118,6155,6182 ,0,0,0}, - {16727,16763,16725 ,6243,6182,6155 ,0,0,0}, {16759,16761,16728 ,6118,6174,6270 ,0,0,0}, - {16728,16725,16759 ,6270,6155,6118 ,0,0,0}, {16731,16766,16732 ,6270,6127,6297 ,0,0,0}, - {16734,16732,16767 ,6196,6297,6158 ,0,0,0}, {18432,16770,16771 ,6138,6159,6137 ,0,0,0}, - {18360,16771,16773 ,6136,6137,6156 ,0,0,0}, {18478,18479,18480 ,6205,6132,6116 ,0,0,0}, - {18479,18436,18481 ,6132,6133,6132 ,0,0,0}, {16427,18350,18355 ,6137,6131,6208 ,0,0,0}, - {18361,16778,16433 ,6133,6135,6134 ,0,0,0}, {16432,18438,18351 ,6138,6196,6132 ,0,0,0}, - {16432,16433,16777 ,6138,6134,6134 ,0,0,0}, {18351,16430,16432 ,6132,6122,6138 ,0,0,0}, - {18355,18350,18482 ,6208,6131,6157 ,0,0,0}, {18482,18425,18355 ,6157,6143,6208 ,0,0,0}, - {18481,16645,18483 ,6132,6172,6118 ,0,0,0}, {18484,18485,18355 ,6204,6201,6208 ,0,0,0}, - {18355,18486,18487 ,6208,6172,6214 ,0,0,0}, {18355,18485,18437 ,6208,6201,6207 ,0,0,0}, - {18486,18355,16648 ,6172,6208,6127 ,0,0,0}, {16647,18437,16645 ,6242,6207,6172 ,0,0,0}, - {18483,16645,18437 ,6118,6172,6207 ,0,0,0}, {18481,18436,16642 ,6132,6133,6203 ,0,0,0}, - {16642,16645,18481 ,6203,6172,6132 ,0,0,0}, {18479,18478,18436 ,6132,6205,6133 ,0,0,0}, - {18429,18480,18488 ,6209,6116,6121 ,0,0,0}, {18480,18429,18478 ,6116,6209,6205 ,0,0,0}, - {18488,18430,18429 ,6121,6207,6209 ,0,0,0}, {18431,18489,18362 ,6166,6209,6207 ,0,0,0}, - {18430,18489,18431 ,6207,6209,6166 ,0,0,0}, {18431,18362,18364 ,6166,6207,6208 ,0,0,0}, - {18477,18364,18490 ,6207,6208,6196 ,0,0,0}, {18363,18490,18364 ,6133,6196,6208 ,0,0,0}, - {18477,18491,18475 ,6207,6134,6131 ,0,0,0}, {18477,18490,18491 ,6207,6196,6134 ,0,0,0}, - {18492,18476,18493 ,6204,6203,6205 ,0,0,0}, {18476,18475,18493 ,6203,6131,6205 ,0,0,0}, - {16802,18476,18492 ,6134,6203,6204 ,0,0,0}, {18272,16583,16582 ,6123,6152,6167 ,0,0,0}, - {18272,18416,18338 ,6123,6275,6213 ,0,0,0}, {16675,16447,16446 ,6140,6117,6208 ,0,0,0}, - {18355,18426,18484 ,6208,6133,6204 ,0,0,0}, {18355,18487,18402 ,6208,6214,6133 ,0,0,0}, - {18494,17178,17177 ,6298,6299,6299 ,0,0,0}, {17183,18495,17184 ,6298,6298,6300 ,0,0,0}, - {18496,18497,16875 ,6301,6302,6302 ,0,0,0}, {17177,17174,18498 ,6299,6300,6303 ,0,0,0}, - {16872,18499,18500 ,6304,6304,6305 ,0,0,0}, {17168,18501,17171 ,6301,6299,6306 ,0,0,0}, - {16870,18502,18503 ,6305,6307,6308 ,0,0,0}, {18504,17165,17162 ,6298,6298,6309 ,0,0,0}, - {18505,16858,18506 ,6310,6311,6312 ,0,0,0}, {18507,18508,16864 ,6308,6313,6314 ,0,0,0}, - {16854,17278,18509 ,6315,6316,6317 ,0,0,0}, {18509,18510,16861 ,6317,6318,6319 ,0,0,0}, - {16849,17273,17275 ,6320,6321,6322 ,0,0,0}, {17233,16816,17231 ,6299,6303,6323 ,0,0,0}, - {17237,17239,16819 ,6324,6298,6306 ,0,0,0}, {16839,17263,17264 ,6325,6326,6327 ,0,0,0}, - {17240,17243,16827 ,6298,6328,6324 ,0,0,0}, {17255,17257,16836 ,6301,6329,6330 ,0,0,0}, - {17255,16910,17252 ,6301,6324,6331 ,0,0,0}, {16829,17249,17251 ,6332,6328,6333 ,0,0,0}, - {17249,16832,17246 ,6328,6334,6335 ,0,0,0}, {17258,16909,17257 ,6336,6298,6329 ,0,0,0}, - {17252,16837,17251 ,6331,6337,6333 ,0,0,0}, {16838,17261,17263 ,6338,6339,6326 ,0,0,0}, - {17258,17261,16841 ,6336,6339,6324 ,0,0,0}, {17243,17245,16823 ,6328,6328,6299 ,0,0,0}, - {17245,17246,16824 ,6328,6335,6340 ,0,0,0}, {16845,17267,17269 ,6341,6342,6343 ,0,0,0}, - {16847,17264,17267 ,6344,6327,6342 ,0,0,0}, {17269,17270,16843 ,6343,6345,6346 ,0,0,0}, - {17239,17240,16826 ,6298,6298,6347 ,0,0,0}, {17234,17237,16822 ,6348,6324,6316 ,0,0,0}, - {16851,17270,17273 ,6349,6345,6321 ,0,0,0}, {16850,17275,17276 ,6350,6322,6351 ,0,0,0}, - {16821,17234,16822 ,6324,6348,6316 ,0,0,0}, {16807,17228,16808 ,6300,6352,6353 ,0,0,0}, - {16856,17276,17278 ,6354,6351,6316 ,0,0,0}, {16804,17222,16805 ,6355,6299,6298 ,0,0,0}, - {17227,16813,17225 ,6299,6356,6357 ,0,0,0}, {18507,16866,18505 ,6308,6358,6310 ,0,0,0}, - {18510,18506,16857 ,6318,6312,6359 ,0,0,0}, {17160,17159,18511 ,6316,6306,6360 ,0,0,0}, - {18511,17159,16810 ,6360,6306,6299 ,0,0,0}, {18511,18512,17160 ,6360,6298,6316 ,0,0,0}, - {18508,18502,16862 ,6313,6307,6304 ,0,0,0}, {16869,18503,18513 ,6336,6308,6311 ,0,0,0}, - {16816,17233,16821 ,6303,6299,6324 ,0,0,0}, {18513,18499,16874 ,6311,6304,6314 ,0,0,0}, - {17168,17166,18514 ,6301,6300,6340 ,0,0,0}, {18515,17166,17165 ,6301,6300,6298 ,0,0,0}, - {18516,18496,16879 ,6301,6301,6333 ,0,0,0}, {16873,18500,18516 ,6361,6305,6301 ,0,0,0}, - {18517,17174,17172 ,6300,6300,6357 ,0,0,0}, {17171,18518,17172 ,6306,6355,6357 ,0,0,0}, - {18519,18520,16880 ,6353,6311,6301 ,0,0,0}, {16876,18497,18519 ,6362,6302,6353 ,0,0,0}, - {17180,17178,18521 ,6300,6299,6300 ,0,0,0}, {16881,18520,18522 ,6300,6311,6363 ,0,0,0}, - {16885,18522,18523 ,6301,6363,6353 ,0,0,0}, {16886,18523,18524 ,6300,6353,6328 ,0,0,0}, - {17180,18525,17183 ,6300,6300,6298 ,0,0,0}, {18526,16888,18524 ,6303,6352,6328 ,0,0,0}, - {18526,18527,16890 ,6303,6352,6340 ,0,0,0}, {18528,17186,17184 ,6299,6316,6300 ,0,0,0}, - {18529,16893,18527 ,6300,6340,6352 ,0,0,0}, {18530,17189,17186 ,6298,6364,6316 ,0,0,0}, - {16894,18529,18531 ,6316,6300,6306 ,0,0,0}, {18532,17190,17189 ,6364,6298,6364 ,0,0,0}, - {18531,18533,16896 ,6306,6340,6340 ,0,0,0}, {18534,17192,17190 ,6300,6300,6298 ,0,0,0}, - {18535,16899,18533 ,6323,6340,6340 ,0,0,0}, {18536,17195,17192 ,6298,6300,6300 ,0,0,0}, - {16901,18535,18537 ,6300,6323,6340 ,0,0,0}, {18538,17196,17195 ,6364,6300,6300 ,0,0,0}, - {18537,18539,16900 ,6340,6303,6303 ,0,0,0}, {18540,17198,17196 ,6300,6365,6300 ,0,0,0}, - {18541,16902,18539 ,6300,6300,6303 ,0,0,0}, {18542,17201,17198 ,6366,6300,6365 ,0,0,0}, - {16905,18541,18543 ,6300,6300,6316 ,0,0,0}, {18544,17202,17201 ,6367,6367,6300 ,0,0,0}, - {18543,18545,16906 ,6316,6300,6300 ,0,0,0}, {18546,17204,17202 ,6300,6300,6367 ,0,0,0}, - {18547,16906,18548 ,6301,6300,6300 ,0,0,0}, {18549,17207,17204 ,6368,6300,6300 ,0,0,0}, - {18550,18547,18551 ,6300,6301,6300 ,0,0,0}, {18552,17208,17207 ,6369,6367,6300 ,0,0,0}, - {18553,18550,18554 ,6316,6300,6300 ,0,0,0}, {17208,18555,17210 ,6367,6367,6300 ,0,0,0}, - {17213,17210,18556 ,6364,6300,6370 ,0,0,0}, {18557,17216,17214 ,6300,6316,6300 ,0,0,0}, - {18558,18553,18559 ,6300,6316,6316 ,0,0,0}, {18560,18561,18562 ,6300,6371,6300 ,0,0,0}, - {18563,18564,18565 ,6306,6300,6303 ,0,0,0}, {18566,18567,18568 ,6369,6300,6367 ,0,0,0}, - {18569,18570,18571 ,6301,6301,6300 ,0,0,0}, {18572,18573,18574 ,6300,6369,6367 ,0,0,0}, - {18575,18576,18577 ,6316,6316,6300 ,0,0,0}, {18578,18579,18580 ,6364,6300,6300 ,0,0,0}, - {18581,18572,18582 ,6364,6300,6316 ,0,0,0}, {18583,18584,18585 ,6300,6364,6316 ,0,0,0}, - {18580,18586,18585 ,6300,6316,6316 ,0,0,0}, {18587,18588,18589 ,6364,6372,6364 ,0,0,0}, - {18588,18581,18590 ,6372,6364,6300 ,0,0,0}, {18575,18584,18591 ,6316,6364,6367 ,0,0,0}, - {18592,18578,18587 ,6370,6364,6364 ,0,0,0}, {18568,18593,18594 ,6367,6367,6316 ,0,0,0}, - {18595,18573,18594 ,6316,6369,6316 ,0,0,0}, {18596,18569,18597 ,6306,6301,6303 ,0,0,0}, - {18597,18577,18598 ,6303,6300,6340 ,0,0,0}, {18599,18600,18562 ,6371,6300,6300 ,0,0,0}, - {18601,18566,18600 ,6300,6369,6300 ,0,0,0}, {18602,18563,18603 ,6300,6306,6300 ,0,0,0}, - {18602,18603,18571 ,6300,6300,6300 ,0,0,0}, {18604,18605,17216 ,6300,6300,6316 ,0,0,0}, - {18560,18605,18606 ,6300,6300,6316 ,0,0,0}, {18558,18607,18608 ,6300,6303,6301 ,0,0,0}, - {18564,18608,18609 ,6300,6301,6301 ,0,0,0}, {17214,17213,18610 ,6300,6364,6369 ,0,0,0}, - {17159,17158,16810 ,6306,6298,6299 ,0,0,0}, {16810,17158,17221 ,6299,6298,6340 ,0,0,0}, - {18512,18504,17162 ,6298,6298,6309 ,0,0,0}, {18512,17162,17160 ,6298,6309,6316 ,0,0,0}, - {18504,18515,17165 ,6298,6301,6298 ,0,0,0}, {18515,18514,17166 ,6301,6340,6300 ,0,0,0}, - {18514,18501,17168 ,6340,6299,6301 ,0,0,0}, {18501,18518,17171 ,6299,6355,6306 ,0,0,0}, - {18518,18517,17172 ,6355,6300,6357 ,0,0,0}, {18517,18498,17174 ,6300,6303,6300 ,0,0,0}, - {18498,18494,17177 ,6303,6298,6299 ,0,0,0}, {18494,18521,17178 ,6298,6300,6299 ,0,0,0}, - {18521,18525,17180 ,6300,6300,6300 ,0,0,0}, {18525,18495,17183 ,6300,6298,6298 ,0,0,0}, - {18495,18528,17184 ,6298,6299,6300 ,0,0,0}, {18528,18530,17186 ,6299,6298,6316 ,0,0,0}, - {18530,18532,17189 ,6298,6364,6364 ,0,0,0}, {18532,18534,17190 ,6364,6300,6298 ,0,0,0}, - {18534,18536,17192 ,6300,6298,6300 ,0,0,0}, {18536,18538,17195 ,6298,6364,6300 ,0,0,0}, - {18538,18540,17196 ,6364,6300,6300 ,0,0,0}, {18540,18542,17198 ,6300,6366,6365 ,0,0,0}, - {18542,18544,17201 ,6366,6367,6300 ,0,0,0}, {18544,18546,17202 ,6367,6300,6367 ,0,0,0}, - {18546,18549,17204 ,6300,6368,6300 ,0,0,0}, {18549,18552,17207 ,6368,6369,6300 ,0,0,0}, - {18552,18555,17208 ,6369,6367,6367 ,0,0,0}, {18555,18556,17210 ,6367,6370,6300 ,0,0,0}, - {18556,18610,17213 ,6370,6369,6364 ,0,0,0}, {18610,18557,17214 ,6369,6300,6300 ,0,0,0}, - {18557,18604,17216 ,6300,6300,6316 ,0,0,0}, {18604,18606,18605 ,6300,6316,6300 ,0,0,0}, - {18606,18561,18560 ,6316,6371,6300 ,0,0,0}, {18561,18599,18562 ,6371,6371,6300 ,0,0,0}, - {18599,18601,18600 ,6371,6300,6300 ,0,0,0}, {18601,18567,18566 ,6300,6300,6369 ,0,0,0}, - {18567,18593,18568 ,6300,6367,6367 ,0,0,0}, {18593,18595,18594 ,6367,6316,6316 ,0,0,0}, - {18595,18574,18573 ,6316,6367,6369 ,0,0,0}, {18574,18582,18572 ,6367,6316,6300 ,0,0,0}, - {18582,18590,18581 ,6316,6300,6364 ,0,0,0}, {18590,18589,18588 ,6300,6364,6372 ,0,0,0}, - {18589,18592,18587 ,6364,6370,6364 ,0,0,0}, {18592,18579,18578 ,6370,6300,6364 ,0,0,0}, - {18579,18586,18580 ,6300,6316,6300 ,0,0,0}, {18586,18583,18585 ,6316,6300,6316 ,0,0,0}, - {18583,18591,18584 ,6300,6367,6364 ,0,0,0}, {18591,18576,18575 ,6367,6316,6316 ,0,0,0}, - {18576,18598,18577 ,6316,6340,6300 ,0,0,0}, {18598,18596,18597 ,6340,6306,6303 ,0,0,0}, - {18596,18570,18569 ,6306,6301,6301 ,0,0,0}, {18570,18602,18571 ,6301,6300,6300 ,0,0,0}, - {18563,18565,18603 ,6306,6303,6300 ,0,0,0}, {18564,18609,18565 ,6300,6301,6303 ,0,0,0}, - {18608,18607,18609 ,6301,6303,6301 ,0,0,0}, {18558,18559,18607 ,6300,6316,6303 ,0,0,0}, - {18553,18554,18559 ,6316,6300,6316 ,0,0,0}, {18550,18551,18554 ,6300,6300,6300 ,0,0,0}, - {18547,18548,18551 ,6301,6300,6300 ,0,0,0}, {16906,18545,18548 ,6300,6300,6300 ,0,0,0}, - {16906,16905,18543 ,6300,6300,6316 ,0,0,0}, {16905,16902,18541 ,6300,6300,6300 ,0,0,0}, - {16902,16900,18539 ,6300,6303,6303 ,0,0,0}, {16900,16901,18537 ,6303,6300,6340 ,0,0,0}, - {16901,16899,18535 ,6300,6340,6323 ,0,0,0}, {16899,16896,18533 ,6340,6340,6340 ,0,0,0}, - {16896,16894,18531 ,6340,6316,6306 ,0,0,0}, {16894,16893,18529 ,6316,6340,6300 ,0,0,0}, - {16893,16890,18527 ,6340,6340,6352 ,0,0,0}, {16890,16888,18526 ,6340,6352,6303 ,0,0,0}, - {16888,16886,18524 ,6352,6300,6328 ,0,0,0}, {16886,16885,18523 ,6300,6301,6353 ,0,0,0}, - {16885,16881,18522 ,6301,6300,6363 ,0,0,0}, {16881,16880,18520 ,6300,6301,6311 ,0,0,0}, - {16880,16876,18519 ,6301,6362,6353 ,0,0,0}, {16876,16875,18497 ,6362,6302,6302 ,0,0,0}, - {16875,16879,18496 ,6302,6333,6301 ,0,0,0}, {16879,16873,18516 ,6333,6361,6301 ,0,0,0}, - {16873,16872,18500 ,6361,6304,6305 ,0,0,0}, {16872,16874,18499 ,6304,6314,6304 ,0,0,0}, - {16874,16869,18513 ,6314,6336,6311 ,0,0,0}, {16869,16870,18503 ,6336,6305,6308 ,0,0,0}, - {16870,16862,18502 ,6305,6304,6307 ,0,0,0}, {16862,16864,18508 ,6304,6314,6313 ,0,0,0}, - {16864,16866,18507 ,6314,6358,6308 ,0,0,0}, {16866,16858,18505 ,6358,6311,6310 ,0,0,0}, - {16858,16857,18506 ,6311,6359,6312 ,0,0,0}, {16857,16861,18510 ,6359,6319,6318 ,0,0,0}, - {16861,16854,18509 ,6319,6315,6317 ,0,0,0}, {16854,16856,17278 ,6315,6354,6316 ,0,0,0}, - {16856,16850,17276 ,6354,6350,6351 ,0,0,0}, {16850,16849,17275 ,6350,6320,6322 ,0,0,0}, - {16849,16851,17273 ,6320,6349,6321 ,0,0,0}, {16851,16843,17270 ,6349,6346,6345 ,0,0,0}, - {16843,16845,17269 ,6346,6341,6343 ,0,0,0}, {16845,16847,17267 ,6341,6344,6342 ,0,0,0}, - {16847,16839,17264 ,6344,6325,6327 ,0,0,0}, {16839,16838,17263 ,6325,6338,6326 ,0,0,0}, - {16838,16841,17261 ,6338,6324,6339 ,0,0,0}, {16841,16909,17258 ,6324,6298,6336 ,0,0,0}, - {16909,16836,17257 ,6298,6330,6329 ,0,0,0}, {16836,16910,17255 ,6330,6324,6301 ,0,0,0}, - {16910,16837,17252 ,6324,6337,6331 ,0,0,0}, {16837,16829,17251 ,6337,6332,6333 ,0,0,0}, - {16829,16832,17249 ,6332,6334,6328 ,0,0,0}, {16832,16824,17246 ,6334,6340,6335 ,0,0,0}, - {16824,16823,17245 ,6340,6299,6328 ,0,0,0}, {16823,16827,17243 ,6299,6324,6328 ,0,0,0}, - {16827,16826,17240 ,6324,6347,6298 ,0,0,0}, {16826,16819,17239 ,6347,6306,6298 ,0,0,0}, - {16819,16822,17237 ,6306,6316,6324 ,0,0,0}, {16821,17233,17234 ,6324,6299,6348 ,0,0,0}, - {16808,17231,16816 ,6353,6323,6303 ,0,0,0}, {16807,17227,17228 ,6300,6299,6352 ,0,0,0}, - {16808,17228,17231 ,6353,6352,6323 ,0,0,0}, {16813,16805,17225 ,6356,6298,6357 ,0,0,0}, - {16807,16813,17227 ,6300,6356,6299 ,0,0,0}, {17222,16804,17221 ,6299,6355,6340 ,0,0,0}, - {17225,16805,17222 ,6357,6298,6299 ,0,0,0}, {16810,17221,16804 ,6299,6340,6355 ,0,0,0}, - {18605,17218,17216 ,6373,6374,6375 ,0,0,0}, {18611,18612,18600 ,6376,6377,6378 ,0,0,0}, - {18562,18613,18560 ,6379,6380,6381 ,0,0,0}, {18594,18573,18614 ,6382,6383,6384 ,0,0,0}, - {18566,18568,18615 ,6385,6386,6387 ,0,0,0}, {18616,18617,18588 ,6388,6389,6390 ,0,0,0}, - {18618,18619,18572 ,6391,6392,6393 ,0,0,0}, {18580,18585,18620 ,6394,6395,6396 ,0,0,0}, - {18587,18578,18621 ,6397,6398,6399 ,0,0,0}, {18622,18623,18577 ,6400,6401,6402 ,0,0,0}, - {18624,18625,18584 ,6403,6404,6405 ,0,0,0}, {18571,18603,18626 ,6406,6407,6408 ,0,0,0}, - {18597,18569,18627 ,6409,6410,6411 ,0,0,0}, {18628,18629,18607 ,6412,6413,6414 ,0,0,0}, - {18630,18631,18565 ,6415,6416,6417 ,0,0,0}, {18632,18551,18633 ,6418,6419,6420 ,0,0,0}, - {18559,18554,18634 ,6421,6422,6423 ,0,0,0}, {18543,18635,18636 ,6424,6425,6426 ,0,0,0}, - {18545,18637,18548 ,6427,6428,6429 ,0,0,0}, {18638,18639,18537 ,6430,6431,6432 ,0,0,0}, - {18640,18541,18539 ,6433,6434,6435 ,0,0,0}, {18641,18533,18531 ,6436,6437,6438 ,0,0,0}, - {18535,18533,18642 ,6439,6437,6440 ,0,0,0}, {18643,18527,18644 ,6441,6442,6443 ,0,0,0}, - {18529,18643,18645 ,6444,6441,6445 ,0,0,0}, {18524,18523,18646 ,6446,6447,6448 ,0,0,0}, - {18526,18647,18644 ,6449,6450,6443 ,0,0,0}, {18522,18520,18648 ,6451,6452,6453 ,0,0,0}, - {18522,18649,18523 ,6451,6454,6447 ,0,0,0}, {18519,18497,18650 ,6455,6456,6457 ,0,0,0}, - {18519,18651,18520 ,6455,6458,6452 ,0,0,0}, {18652,18497,18496 ,6459,6456,6460 ,0,0,0}, - {18497,18652,18650 ,6456,6459,6457 ,0,0,0}, {18516,18653,18496 ,6461,6462,6460 ,0,0,0}, - {18652,18496,18653 ,6459,6460,6462 ,0,0,0}, {18516,18500,18654 ,6461,6463,6464 ,0,0,0}, - {18654,18653,18516 ,6464,6462,6461 ,0,0,0}, {18655,18500,18499 ,6465,6463,6466 ,0,0,0}, - {18500,18655,18654 ,6463,6465,6464 ,0,0,0}, {18513,18656,18499 ,6467,6468,6466 ,0,0,0}, - {18655,18499,18656 ,6465,6466,6468 ,0,0,0}, {18513,18503,18657 ,6467,6469,6470 ,0,0,0}, - {18657,18656,18513 ,6470,6468,6467 ,0,0,0}, {18658,18503,18502 ,6471,6469,6472 ,0,0,0}, - {18503,18658,18657 ,6469,6471,6470 ,0,0,0}, {18508,18659,18502 ,6473,6474,6472 ,0,0,0}, - {18658,18502,18659 ,6471,6472,6474 ,0,0,0}, {18508,18507,18660 ,6473,6475,6476 ,0,0,0}, - {18660,18659,18508 ,6476,6474,6473 ,0,0,0}, {18661,18507,18505 ,6477,6475,6478 ,0,0,0}, - {18507,18661,18660 ,6475,6477,6476 ,0,0,0}, {18506,18662,18505 ,6479,6480,6478 ,0,0,0}, - {18661,18505,18662 ,6477,6478,6480 ,0,0,0}, {18506,18510,18663 ,6479,6481,6482 ,0,0,0}, - {18663,18662,18506 ,6482,6480,6479 ,0,0,0}, {18664,18510,18509 ,6483,6481,6484 ,0,0,0}, - {18510,18664,18663 ,6481,6483,6482 ,0,0,0}, {17278,18665,18509 ,6485,6486,6484 ,0,0,0}, - {18664,18509,18665 ,6483,6484,6486 ,0,0,0}, {17277,18665,17278 ,6487,6486,6485 ,0,0,0}, - {18651,18648,18520 ,6458,6453,6452 ,0,0,0}, {18519,18650,18651 ,6455,6457,6458 ,0,0,0}, - {18649,18646,18523 ,6454,6448,6447 ,0,0,0}, {18522,18648,18649 ,6451,6453,6454 ,0,0,0}, - {18526,18524,18647 ,6449,6446,6450 ,0,0,0}, {18524,18646,18647 ,6446,6448,6450 ,0,0,0}, - {18527,18643,18529 ,6442,6441,6444 ,0,0,0}, {18527,18526,18644 ,6442,6449,6443 ,0,0,0}, - {18641,18531,18645 ,6436,6438,6445 ,0,0,0}, {18531,18529,18645 ,6438,6444,6445 ,0,0,0}, - {18535,18642,18638 ,6439,6440,6430 ,0,0,0}, {18642,18533,18641 ,6440,6437,6436 ,0,0,0}, - {18639,18539,18537 ,6431,6435,6432 ,0,0,0}, {18638,18537,18535 ,6430,6432,6439 ,0,0,0}, - {18640,18635,18541 ,6433,6425,6434 ,0,0,0}, {18639,18640,18539 ,6431,6433,6435 ,0,0,0}, - {18543,18636,18545 ,6424,6426,6427 ,0,0,0}, {18541,18635,18543 ,6434,6425,6424 ,0,0,0}, - {18548,18637,18633 ,6429,6428,6420 ,0,0,0}, {18545,18636,18637 ,6427,6426,6428 ,0,0,0}, - {18554,18551,18632 ,6422,6419,6418 ,0,0,0}, {18551,18548,18633 ,6419,6429,6420 ,0,0,0}, - {18628,18559,18634 ,6412,6421,6423 ,0,0,0}, {18634,18554,18632 ,6423,6422,6418 ,0,0,0}, - {18629,18609,18607 ,6413,6488,6414 ,0,0,0}, {18628,18607,18559 ,6412,6414,6421 ,0,0,0}, - {18565,18609,18630 ,6417,6488,6415 ,0,0,0}, {18629,18630,18609 ,6413,6415,6488 ,0,0,0}, - {18603,18631,18626 ,6407,6416,6408 ,0,0,0}, {18565,18631,18603 ,6417,6416,6407 ,0,0,0}, - {18569,18571,18666 ,6410,6406,6489 ,0,0,0}, {18571,18626,18666 ,6406,6408,6489 ,0,0,0}, - {18622,18597,18627 ,6400,6409,6411 ,0,0,0}, {18627,18569,18666 ,6411,6410,6489 ,0,0,0}, - {18623,18575,18577 ,6401,6490,6402 ,0,0,0}, {18622,18577,18597 ,6400,6402,6409 ,0,0,0}, - {18584,18575,18624 ,6405,6490,6403 ,0,0,0}, {18623,18624,18575 ,6401,6403,6490 ,0,0,0}, - {18585,18625,18620 ,6395,6404,6396 ,0,0,0}, {18584,18625,18585 ,6405,6404,6395 ,0,0,0}, - {18578,18580,18667 ,6398,6394,6491 ,0,0,0}, {18580,18620,18667 ,6394,6396,6491 ,0,0,0}, - {18616,18587,18621 ,6388,6397,6399 ,0,0,0}, {18621,18578,18667 ,6399,6398,6491 ,0,0,0}, - {18617,18581,18588 ,6389,6492,6390 ,0,0,0}, {18616,18588,18587 ,6388,6390,6397 ,0,0,0}, - {18572,18581,18618 ,6393,6492,6391 ,0,0,0}, {18617,18618,18581 ,6389,6391,6492 ,0,0,0}, - {18573,18619,18614 ,6383,6392,6384 ,0,0,0}, {18572,18619,18573 ,6393,6392,6383 ,0,0,0}, - {18568,18594,18668 ,6386,6382,6493 ,0,0,0}, {18594,18614,18668 ,6382,6384,6493 ,0,0,0}, - {18611,18566,18615 ,6376,6385,6387 ,0,0,0}, {18615,18568,18668 ,6387,6386,6493 ,0,0,0}, - {18612,18562,18600 ,6377,6379,6378 ,0,0,0}, {18611,18600,18566 ,6376,6378,6385 ,0,0,0}, - {18613,18669,18560 ,6380,6494,6381 ,0,0,0}, {18612,18613,18562 ,6377,6380,6379 ,0,0,0}, - {17218,18605,18669 ,6374,6373,6494 ,0,0,0}, {18560,18669,18605 ,6381,6494,6373 ,0,0,0}, - {17229,17115,17230 ,6495,6495,6496 ,0,0,0}, {17236,17235,17121 ,6497,6496,6496 ,0,0,0}, - {18624,18623,18670 ,6498,6499,6500 ,0,0,0}, {17112,17229,17226 ,6501,6495,6501 ,0,0,0}, - {18621,18667,18671 ,6502,6503,6503 ,0,0,0}, {17223,17106,17109 ,6496,6504,6501 ,0,0,0}, - {18672,18614,18619 ,6498,6505,6506 ,0,0,0}, {17048,17157,17161 ,6507,6495,6495 ,0,0,0}, - {17058,17056,17170 ,6508,6509,6504 ,0,0,0}, {18673,18612,18611 ,6510,6511,6512 ,0,0,0}, - {17217,17100,17098 ,6513,6500,6514 ,0,0,0}, {17218,17100,17217 ,6515,6500,6513 ,0,0,0}, - {17212,17215,17099 ,6516,6517,6518 ,0,0,0}, {17179,17181,17064 ,6519,6520,6497 ,0,0,0}, - {17185,17187,17070 ,6521,6522,6523 ,0,0,0}, {17209,17092,17091 ,6524,6525,6526 ,0,0,0}, - {17188,17074,17073 ,6527,6500,6498 ,0,0,0}, {17205,17086,17203 ,6528,6522,6529 ,0,0,0}, - {17203,17085,17200 ,6529,6530,6531 ,0,0,0}, {17080,17197,17082 ,6532,6533,6502 ,0,0,0}, - {17194,17080,17079 ,6534,6532,6495 ,0,0,0}, {17206,17088,17205 ,6535,6502,6528 ,0,0,0}, - {17199,17200,17082 ,6533,6531,6502 ,0,0,0}, {17209,17091,17206 ,6524,6526,6535 ,0,0,0}, - {17088,17206,17091 ,6502,6535,6526 ,0,0,0}, {17191,17076,17074 ,6503,6514,6500 ,0,0,0}, - {17079,17076,17193 ,6495,6514,6530 ,0,0,0}, {17097,17092,17211 ,6536,6525,6537 ,0,0,0}, - {17092,17209,17211 ,6525,6524,6537 ,0,0,0}, {17097,17211,17212 ,6536,6537,6516 ,0,0,0}, - {17188,17073,17187 ,6527,6498,6522 ,0,0,0}, {17185,17068,17182 ,6521,6501,6509 ,0,0,0}, - {17212,17099,17097 ,6516,6518,6536 ,0,0,0}, {17099,17215,17098 ,6518,6517,6514 ,0,0,0}, - {17182,17067,17181 ,6509,6500,6520 ,0,0,0}, {17062,17176,17064 ,6508,6509,6497 ,0,0,0}, - {17217,17098,17215 ,6513,6514,6517 ,0,0,0}, {17058,17173,17061 ,6508,6508,6495 ,0,0,0}, - {17061,17175,17062 ,6495,6530,6508 ,0,0,0}, {18674,18613,18675 ,6538,6539,6540 ,0,0,0}, - {18669,17100,17218 ,6541,6500,6515 ,0,0,0}, {17169,17055,17167 ,6495,6496,6542 ,0,0,0}, - {17056,17055,17169 ,6509,6496,6495 ,0,0,0}, {17163,17164,17050 ,6542,6504,6507 ,0,0,0}, - {18668,18614,18676 ,6543,6505,6500 ,0,0,0}, {18677,18618,18678 ,6503,6533,6500 ,0,0,0}, - {17161,17163,17049 ,6495,6542,6495 ,0,0,0}, {18679,18678,18616 ,6508,6500,6538 ,0,0,0}, - {17106,17220,17105 ,6504,6542,6501 ,0,0,0}, {17048,17105,17219 ,6507,6501,6495 ,0,0,0}, - {18625,18680,18681 ,6527,6530,6498 ,0,0,0}, {18667,18620,18682 ,6503,6527,6499 ,0,0,0}, - {17112,17226,17111 ,6501,6501,6544 ,0,0,0}, {17224,17109,17111 ,6504,6501,6544 ,0,0,0}, - {18627,18683,18684 ,6508,6530,6544 ,0,0,0}, {18685,18622,18684 ,6498,6500,6544 ,0,0,0}, - {17117,17232,17230 ,6495,6495,6496 ,0,0,0}, {18666,18626,18683 ,6523,6504,6530 ,0,0,0}, - {18631,18686,18626 ,6500,6504,6504 ,0,0,0}, {18631,18630,18687 ,6500,6522,6500 ,0,0,0}, - {17235,17232,17118 ,6496,6495,6496 ,0,0,0}, {18688,18630,18629 ,6515,6522,6504 ,0,0,0}, - {18628,18689,18629 ,6508,6500,6504 ,0,0,0}, {17238,17121,17123 ,6495,6496,6508 ,0,0,0}, - {18689,18628,18690 ,6500,6508,6498 ,0,0,0}, {17241,17123,17124 ,6504,6508,6507 ,0,0,0}, - {18691,18690,18634 ,6515,6498,6545 ,0,0,0}, {17242,17124,17127 ,6507,6507,6495 ,0,0,0}, - {18692,18691,18632 ,6498,6515,6504 ,0,0,0}, {17244,17127,17129 ,6504,6495,6495 ,0,0,0}, - {18693,18692,18633 ,6504,6498,6504 ,0,0,0}, {17129,17130,17247 ,6495,6504,6504 ,0,0,0}, - {18694,18693,18637 ,6504,6504,6498 ,0,0,0}, {17248,17247,17130 ,6504,6504,6504 ,0,0,0}, - {18694,18636,18635 ,6504,6504,6504 ,0,0,0}, {17250,17248,17133 ,6546,6504,6504 ,0,0,0}, - {18695,18635,18640 ,6508,6504,6504 ,0,0,0}, {17253,17250,17135 ,6507,6546,6504 ,0,0,0}, - {18696,18640,18639 ,6508,6504,6508 ,0,0,0}, {17254,17253,17136 ,6547,6507,6548 ,0,0,0}, - {18697,18639,18638 ,6498,6508,6498 ,0,0,0}, {17256,17254,17139 ,6546,6547,6548 ,0,0,0}, - {18698,18638,18642 ,6504,6498,6498 ,0,0,0}, {17141,17259,17139 ,6549,6547,6548 ,0,0,0}, - {18642,18699,18698 ,6498,6504,6504 ,0,0,0}, {17260,17141,17142 ,6549,6549,6550 ,0,0,0}, - {18699,18641,18700 ,6504,6504,6498 ,0,0,0}, {17142,17145,17262 ,6550,6549,6504 ,0,0,0}, - {17265,17145,17147 ,6549,6549,6545 ,0,0,0}, {17268,17266,17149 ,6549,6504,6504 ,0,0,0}, - {18700,18645,18701 ,6498,6504,6504 ,0,0,0}, {17274,17272,17154 ,6551,6504,6515 ,0,0,0}, - {18646,18702,18647 ,6504,6508,6515 ,0,0,0}, {18703,18664,18704 ,6504,6545,6515 ,0,0,0}, - {18705,18648,18651 ,6508,6552,6504 ,0,0,0}, {18661,18706,18707 ,6553,6504,6554 ,0,0,0}, - {18708,18709,18652 ,6555,6504,6515 ,0,0,0}, {18656,18657,18710 ,6504,6504,6504 ,0,0,0}, - {18661,18707,18660 ,6553,6554,6504 ,0,0,0}, {18654,18711,18712 ,6504,6504,6515 ,0,0,0}, - {18710,18711,18655 ,6504,6504,6515 ,0,0,0}, {18659,18713,18658 ,6548,6504,6504 ,0,0,0}, - {18659,18660,18714 ,6548,6504,6549 ,0,0,0}, {18708,18653,18712 ,6555,6504,6515 ,0,0,0}, - {18715,18657,18658 ,6504,6504,6504 ,0,0,0}, {18716,18663,18703 ,6504,6548,6504 ,0,0,0}, - {18706,18662,18716 ,6504,6548,6504 ,0,0,0}, {18650,18717,18651 ,6504,6544,6504 ,0,0,0}, - {18650,18709,18717 ,6504,6504,6544 ,0,0,0}, {17277,17274,17156 ,6515,6551,6554 ,0,0,0}, - {17156,18704,18665 ,6554,6515,6545 ,0,0,0}, {18649,18718,18646 ,6515,6504,6504 ,0,0,0}, - {18719,18649,18648 ,6508,6515,6552 ,0,0,0}, {17271,17268,17148 ,6504,6549,6549 ,0,0,0}, - {17151,17272,17271 ,6545,6504,6504 ,0,0,0}, {18643,18720,18701 ,6508,6498,6504 ,0,0,0}, - {18702,18720,18644 ,6508,6498,6498 ,0,0,0}, {17266,17147,17149 ,6504,6545,6504 ,0,0,0}, - {17164,17167,17052 ,6504,6542,6504 ,0,0,0}, {18721,18615,18722 ,6556,6557,6558 ,0,0,0}, - {18670,18623,18685 ,6500,6499,6498 ,0,0,0}, {17086,17205,17088 ,6522,6528,6502 ,0,0,0}, - {17085,17203,17086 ,6530,6529,6522 ,0,0,0}, {17082,17200,17085 ,6502,6531,6530 ,0,0,0}, - {17082,17197,17199 ,6502,6533,6533 ,0,0,0}, {17080,17194,17197 ,6532,6534,6533 ,0,0,0}, - {17079,17193,17194 ,6495,6530,6534 ,0,0,0}, {17076,17191,17193 ,6514,6503,6530 ,0,0,0}, - {17074,17188,17191 ,6500,6527,6503 ,0,0,0}, {17070,17187,17073 ,6523,6522,6498 ,0,0,0}, - {17068,17185,17070 ,6501,6521,6523 ,0,0,0}, {17067,17182,17068 ,6500,6509,6501 ,0,0,0}, - {17064,17181,17067 ,6497,6520,6500 ,0,0,0}, {17064,17176,17179 ,6497,6509,6519 ,0,0,0}, - {17062,17175,17176 ,6508,6530,6509 ,0,0,0}, {17061,17173,17175 ,6495,6508,6530 ,0,0,0}, - {17058,17170,17173 ,6508,6504,6508 ,0,0,0}, {17056,17169,17170 ,6509,6495,6504 ,0,0,0}, - {17052,17167,17055 ,6504,6542,6496 ,0,0,0}, {17050,17164,17052 ,6507,6504,6504 ,0,0,0}, - {17049,17163,17050 ,6495,6542,6507 ,0,0,0}, {17048,17161,17049 ,6507,6495,6495 ,0,0,0}, - {17048,17219,17157 ,6507,6495,6495 ,0,0,0}, {17105,17220,17219 ,6501,6542,6495 ,0,0,0}, - {17106,17223,17220 ,6504,6496,6542 ,0,0,0}, {17109,17224,17223 ,6501,6504,6496 ,0,0,0}, - {17111,17226,17224 ,6544,6501,6504 ,0,0,0}, {17115,17229,17112 ,6495,6495,6501 ,0,0,0}, - {17117,17230,17115 ,6495,6496,6495 ,0,0,0}, {17118,17232,17117 ,6496,6495,6495 ,0,0,0}, - {17121,17235,17118 ,6496,6496,6496 ,0,0,0}, {17121,17238,17236 ,6496,6495,6497 ,0,0,0}, - {17123,17241,17238 ,6508,6504,6495 ,0,0,0}, {17124,17242,17241 ,6507,6507,6504 ,0,0,0}, - {17127,17244,17242 ,6495,6504,6507 ,0,0,0}, {17129,17247,17244 ,6495,6504,6504 ,0,0,0}, - {17133,17248,17130 ,6504,6504,6504 ,0,0,0}, {17135,17250,17133 ,6504,6546,6504 ,0,0,0}, - {17136,17253,17135 ,6548,6507,6504 ,0,0,0}, {17139,17254,17136 ,6548,6547,6548 ,0,0,0}, - {17139,17259,17256 ,6548,6547,6546 ,0,0,0}, {17141,17260,17259 ,6549,6549,6547 ,0,0,0}, - {17142,17262,17260 ,6550,6504,6549 ,0,0,0}, {17145,17265,17262 ,6549,6549,6504 ,0,0,0}, - {17147,17266,17265 ,6545,6504,6549 ,0,0,0}, {17148,17268,17149 ,6549,6549,6504 ,0,0,0}, - {17151,17271,17148 ,6545,6504,6549 ,0,0,0}, {17154,17272,17151 ,6515,6504,6545 ,0,0,0}, - {17156,17274,17154 ,6554,6551,6515 ,0,0,0}, {17156,18665,17277 ,6554,6545,6515 ,0,0,0}, - {18704,18664,18665 ,6515,6545,6545 ,0,0,0}, {18703,18663,18664 ,6504,6548,6545 ,0,0,0}, - {18716,18662,18663 ,6504,6548,6548 ,0,0,0}, {18706,18661,18662 ,6504,6553,6548 ,0,0,0}, - {18714,18660,18707 ,6549,6504,6554 ,0,0,0}, {18713,18659,18714 ,6504,6548,6549 ,0,0,0}, - {18715,18658,18713 ,6504,6504,6504 ,0,0,0}, {18710,18657,18715 ,6504,6504,6504 ,0,0,0}, - {18710,18655,18656 ,6504,6515,6504 ,0,0,0}, {18711,18654,18655 ,6504,6504,6515 ,0,0,0}, - {18712,18653,18654 ,6515,6504,6504 ,0,0,0}, {18708,18652,18653 ,6555,6515,6504 ,0,0,0}, - {18709,18650,18652 ,6504,6504,6515 ,0,0,0}, {18705,18651,18717 ,6508,6504,6544 ,0,0,0}, - {18719,18648,18705 ,6508,6552,6508 ,0,0,0}, {18718,18649,18719 ,6504,6515,6508 ,0,0,0}, - {18702,18646,18718 ,6508,6504,6504 ,0,0,0}, {18702,18644,18647 ,6508,6498,6515 ,0,0,0}, - {18720,18643,18644 ,6498,6508,6498 ,0,0,0}, {18701,18645,18643 ,6504,6504,6508 ,0,0,0}, - {18700,18641,18645 ,6498,6504,6504 ,0,0,0}, {18699,18642,18641 ,6504,6498,6504 ,0,0,0}, - {18697,18638,18698 ,6498,6498,6504 ,0,0,0}, {18696,18639,18697 ,6508,6508,6498 ,0,0,0}, - {18695,18640,18696 ,6508,6504,6508 ,0,0,0}, {18694,18635,18695 ,6504,6504,6508 ,0,0,0}, - {18694,18637,18636 ,6504,6498,6504 ,0,0,0}, {18693,18633,18637 ,6504,6504,6498 ,0,0,0}, - {18692,18632,18633 ,6498,6504,6504 ,0,0,0}, {18691,18634,18632 ,6515,6545,6504 ,0,0,0}, - {18690,18628,18634 ,6498,6508,6545 ,0,0,0}, {18688,18629,18689 ,6515,6504,6500 ,0,0,0}, - {18687,18630,18688 ,6500,6522,6515 ,0,0,0}, {18686,18631,18687 ,6504,6500,6500 ,0,0,0}, - {18683,18626,18686 ,6530,6504,6504 ,0,0,0}, {18683,18627,18666 ,6530,6508,6523 ,0,0,0}, - {18684,18622,18627 ,6544,6500,6508 ,0,0,0}, {18685,18623,18622 ,6498,6499,6500 ,0,0,0}, - {18680,18624,18670 ,6530,6498,6500 ,0,0,0}, {18681,18620,18625 ,6498,6527,6527 ,0,0,0}, - {18680,18625,18624 ,6530,6527,6498 ,0,0,0}, {18682,18671,18667 ,6499,6503,6503 ,0,0,0}, - {18681,18682,18620 ,6498,6499,6527 ,0,0,0}, {18671,18679,18621 ,6503,6508,6502 ,0,0,0}, - {18616,18678,18617 ,6538,6500,6559 ,0,0,0}, {18621,18679,18616 ,6502,6508,6538 ,0,0,0}, - {18619,18618,18677 ,6506,6533,6503 ,0,0,0}, {18618,18617,18678 ,6533,6559,6500 ,0,0,0}, - {18676,18614,18672 ,6500,6505,6498 ,0,0,0}, {18672,18619,18677 ,6498,6506,6503 ,0,0,0}, - {18722,18668,18676 ,6558,6543,6500 ,0,0,0}, {18721,18611,18615 ,6556,6512,6557 ,0,0,0}, - {18722,18615,18668 ,6558,6557,6543 ,0,0,0}, {18673,18675,18612 ,6510,6540,6511 ,0,0,0}, - {18721,18673,18611 ,6556,6510,6512 ,0,0,0}, {18613,18674,18669 ,6539,6538,6541 ,0,0,0}, - {18612,18675,18613 ,6511,6540,6539 ,0,0,0}, {17100,18669,18674 ,6500,6541,6538 ,0,0,0}, - {18674,17102,17100 ,6560,6561,6562 ,0,0,0}, {18721,18723,18673 ,6563,6564,6565 ,0,0,0}, - {18675,18724,18725 ,6566,6567,6568 ,0,0,0}, {18672,18677,18726 ,6569,6570,6571 ,0,0,0}, - {18722,18676,18727 ,6572,6573,6574 ,0,0,0}, {18728,18729,18671 ,6575,6576,6577 ,0,0,0}, - {18730,18731,18678 ,6578,6579,6580 ,0,0,0}, {18680,18670,18732 ,6581,6582,6583 ,0,0,0}, - {18682,18681,18733 ,6584,6585,6586 ,0,0,0}, {18734,18735,18683 ,6587,6588,6589 ,0,0,0}, - {18736,18685,18684 ,6590,6591,6592 ,0,0,0}, {18688,18689,18737 ,6593,6594,6595 ,0,0,0}, - {18687,18738,18739 ,6596,6597,6598 ,0,0,0}, {18740,18741,18692 ,6599,6600,6601 ,0,0,0}, - {18742,18743,18690 ,6602,6603,6604 ,0,0,0}, {18744,18695,18745 ,6605,6606,6607 ,0,0,0}, - {18693,18694,18746 ,6608,6609,6610 ,0,0,0}, {18697,18698,18747 ,6611,6612,6613 ,0,0,0}, - {18697,18748,18696 ,6611,6614,6615 ,0,0,0}, {18701,18749,18700 ,6616,6617,6618 ,0,0,0}, - {18750,18751,18699 ,6619,6620,6621 ,0,0,0}, {18702,18752,18720 ,6622,6623,6624 ,0,0,0}, - {18753,18701,18720 ,6625,6616,6624 ,0,0,0}, {18754,18755,18719 ,6626,6627,6628 ,0,0,0}, - {18756,18718,18755 ,6629,6630,6627 ,0,0,0}, {18757,18758,18717 ,6631,6632,6633 ,0,0,0}, - {18754,18705,18758 ,6626,6634,6632 ,0,0,0}, {18708,18759,18709 ,6635,6636,6637 ,0,0,0}, - {18757,18709,18759 ,6631,6637,6636 ,0,0,0}, {18708,18712,18760 ,6635,6638,6639 ,0,0,0}, - {18760,18759,18708 ,6639,6636,6635 ,0,0,0}, {18761,18712,18711 ,6640,6638,6641 ,0,0,0}, - {18712,18761,18760 ,6638,6640,6639 ,0,0,0}, {18710,18762,18711 ,6642,6643,6641 ,0,0,0}, - {18761,18711,18762 ,6640,6641,6643 ,0,0,0}, {18710,18715,18763 ,6642,6644,6645 ,0,0,0}, - {18763,18762,18710 ,6645,6643,6642 ,0,0,0}, {18764,18715,18713 ,6646,6644,6647 ,0,0,0}, - {18715,18764,18763 ,6644,6646,6645 ,0,0,0}, {18714,18765,18713 ,6648,6649,6647 ,0,0,0}, - {18764,18713,18765 ,6646,6647,6649 ,0,0,0}, {18714,18707,18766 ,6648,6650,6651 ,0,0,0}, - {18766,18765,18714 ,6651,6649,6648 ,0,0,0}, {18767,18707,18706 ,6652,6650,6653 ,0,0,0}, - {18707,18767,18766 ,6650,6652,6651 ,0,0,0}, {18706,18768,18769 ,6653,6654,6655 ,0,0,0}, - {18767,18706,18769 ,6652,6653,6655 ,0,0,0}, {18768,18716,18770 ,6654,6656,6657 ,0,0,0}, - {18716,18768,18706 ,6656,6654,6653 ,0,0,0}, {18770,18703,18704 ,6657,6658,6659 ,0,0,0}, - {18716,18703,18770 ,6656,6658,6657 ,0,0,0}, {17156,18771,18704 ,6660,6661,6659 ,0,0,0}, - {18770,18704,18771 ,6657,6659,6661 ,0,0,0}, {17155,18771,17156 ,6660,6661,6660 ,0,0,0}, - {18705,18717,18758 ,6634,6633,6632 ,0,0,0}, {18757,18717,18709 ,6631,6633,6637 ,0,0,0}, - {18718,18719,18755 ,6630,6628,6627 ,0,0,0}, {18754,18719,18705 ,6626,6628,6634 ,0,0,0}, - {18756,18752,18702 ,6629,6623,6622 ,0,0,0}, {18756,18702,18718 ,6629,6622,6630 ,0,0,0}, - {18749,18701,18753 ,6617,6616,6625 ,0,0,0}, {18752,18753,18720 ,6623,6625,6624 ,0,0,0}, - {18700,18750,18699 ,6618,6619,6621 ,0,0,0}, {18749,18750,18700 ,6617,6619,6618 ,0,0,0}, - {18698,18751,18747 ,6612,6620,6613 ,0,0,0}, {18699,18751,18698 ,6621,6620,6612 ,0,0,0}, - {18748,18745,18696 ,6614,6607,6615 ,0,0,0}, {18697,18747,18748 ,6611,6613,6614 ,0,0,0}, - {18694,18695,18744 ,6609,6606,6605 ,0,0,0}, {18695,18696,18745 ,6606,6615,6607 ,0,0,0}, - {18740,18693,18746 ,6599,6608,6610 ,0,0,0}, {18746,18694,18744 ,6610,6609,6605 ,0,0,0}, - {18741,18691,18692 ,6600,6662,6601 ,0,0,0}, {18740,18692,18693 ,6599,6601,6608 ,0,0,0}, - {18690,18691,18742 ,6604,6662,6602 ,0,0,0}, {18741,18742,18691 ,6600,6602,6662 ,0,0,0}, - {18689,18743,18737 ,6594,6603,6595 ,0,0,0}, {18690,18743,18689 ,6604,6603,6594 ,0,0,0}, - {18687,18688,18738 ,6596,6593,6597 ,0,0,0}, {18688,18737,18738 ,6593,6595,6597 ,0,0,0}, - {18734,18686,18739 ,6587,6663,6598 ,0,0,0}, {18686,18687,18739 ,6663,6596,6598 ,0,0,0}, - {18735,18684,18683 ,6588,6592,6589 ,0,0,0}, {18734,18683,18686 ,6587,6589,6663 ,0,0,0}, - {18736,18772,18685 ,6590,6664,6591 ,0,0,0}, {18735,18736,18684 ,6588,6590,6592 ,0,0,0}, - {18732,18670,18772 ,6583,6582,6664 ,0,0,0}, {18685,18772,18670 ,6591,6664,6582 ,0,0,0}, - {18681,18680,18773 ,6585,6581,6665 ,0,0,0}, {18680,18732,18773 ,6581,6583,6665 ,0,0,0}, - {18728,18682,18733 ,6575,6584,6586 ,0,0,0}, {18733,18681,18773 ,6586,6585,6665 ,0,0,0}, - {18729,18679,18671 ,6576,6666,6577 ,0,0,0}, {18728,18671,18682 ,6575,6577,6584 ,0,0,0}, - {18678,18679,18730 ,6580,6666,6578 ,0,0,0}, {18729,18730,18679 ,6576,6578,6666 ,0,0,0}, - {18677,18731,18726 ,6570,6579,6571 ,0,0,0}, {18678,18731,18677 ,6580,6579,6570 ,0,0,0}, - {18676,18672,18774 ,6573,6569,6667 ,0,0,0}, {18672,18726,18774 ,6569,6571,6667 ,0,0,0}, - {18723,18722,18727 ,6564,6572,6574 ,0,0,0}, {18727,18676,18774 ,6574,6573,6667 ,0,0,0}, - {18723,18724,18673 ,6564,6567,6565 ,0,0,0}, {18723,18721,18722 ,6564,6563,6572 ,0,0,0}, - {18725,18775,18675 ,6568,6668,6566 ,0,0,0}, {18673,18724,18675 ,6565,6567,6566 ,0,0,0}, - {17102,18674,18775 ,6561,6560,6668 ,0,0,0}, {18675,18775,18674 ,6566,6668,6560 ,0,0,0}, - {17066,17069,16973 ,6669,6670,6671 ,0,0,0}, {18728,18733,18776 ,6672,6671,6671 ,0,0,0}, - {16979,17075,16988 ,6673,6674,6671 ,0,0,0}, {17069,17071,16982 ,6670,6669,6675 ,0,0,0}, - {17081,17011,16983 ,6670,6676,6677 ,0,0,0}, {18777,18778,18746 ,6324,6298,6672 ,0,0,0}, - {18779,18738,18737 ,6671,6672,6671 ,0,0,0}, {18780,18781,18742 ,6672,6671,6671 ,0,0,0}, - {17094,17005,17001 ,6678,6671,6679 ,0,0,0}, {18739,18738,18782 ,6671,6672,6680 ,0,0,0}, - {17007,17101,17009 ,6679,6671,6671 ,0,0,0}, {18783,18784,18736 ,6672,6672,6672 ,0,0,0}, - {18785,18786,18723 ,6672,6681,6672 ,0,0,0}, {18775,18725,18787 ,6671,6681,6672 ,0,0,0}, - {18788,18730,18729 ,6672,6672,6681 ,0,0,0}, {18726,18789,18790 ,6672,6672,6672 ,0,0,0}, - {18791,18774,18790 ,6672,6671,6672 ,0,0,0}, {18728,18792,18729 ,6672,6671,6681 ,0,0,0}, - {18731,18788,18789 ,6672,6672,6672 ,0,0,0}, {18785,18727,18791 ,6672,6672,6672 ,0,0,0}, - {18793,18794,18773 ,6671,6672,6672 ,0,0,0}, {18725,18724,18795 ,6681,6671,6671 ,0,0,0}, - {18732,18796,18793 ,6671,6681,6671 ,0,0,0}, {17102,18775,17009 ,6671,6671,6671 ,0,0,0}, - {18772,18784,18796 ,6672,6672,6681 ,0,0,0}, {17005,17095,17006 ,6671,6682,6672 ,0,0,0}, - {17007,17006,17096 ,6679,6672,6298 ,0,0,0}, {18739,18797,18734 ,6671,6671,6672 ,0,0,0}, - {18797,18783,18735 ,6671,6672,6672 ,0,0,0}, {17089,17090,16997 ,6672,6681,6670 ,0,0,0}, - {17001,17003,17093 ,6679,6669,6669 ,0,0,0}, {18781,18798,18743 ,6671,6672,6671 ,0,0,0}, - {17087,17089,16999 ,6671,6672,6681 ,0,0,0}, {16994,17011,17083 ,6669,6676,6298 ,0,0,0}, - {16994,17084,17087 ,6669,6669,6671 ,0,0,0}, {18799,18740,18778 ,6672,6671,6298 ,0,0,0}, - {18799,18780,18741 ,6672,6672,6672 ,0,0,0}, {17077,16985,16988 ,6683,6669,6671 ,0,0,0}, - {16983,16985,17078 ,6677,6669,6684 ,0,0,0}, {18748,18800,18745 ,6671,6685,6686 ,0,0,0}, - {18777,18744,18745 ,6324,6687,6686 ,0,0,0}, {18748,18747,18801 ,6671,6688,6688 ,0,0,0}, - {17071,17072,16978 ,6669,6689,6684 ,0,0,0}, {18802,18803,18750 ,6672,6690,6671 ,0,0,0}, - {18803,18804,18751 ,6690,6686,6690 ,0,0,0}, {18805,18802,18749 ,6691,6672,6691 ,0,0,0}, - {16973,16976,17065 ,6671,6692,6672 ,0,0,0}, {16975,17063,16976 ,6693,6673,6692 ,0,0,0}, - {16968,17060,16975 ,6672,6689,6693 ,0,0,0}, {18753,18806,18805 ,6686,6690,6691 ,0,0,0}, - {17059,16968,16971 ,6694,6672,6695 ,0,0,0}, {18752,18807,18806 ,6690,6691,6690 ,0,0,0}, - {16971,16970,17057 ,6695,6696,6697 ,0,0,0}, {18807,18756,18755 ,6691,6672,6688 ,0,0,0}, - {16965,17053,17054 ,6698,6699,6700 ,0,0,0}, {18808,18809,18754 ,6672,6688,6688 ,0,0,0}, - {18758,18757,18810 ,6688,6691,6701 ,0,0,0}, {18811,18759,18760 ,6686,6672,6671 ,0,0,0}, - {17051,17053,16913 ,6676,6699,6702 ,0,0,0}, {18761,18812,18813 ,6672,6671,6671 ,0,0,0}, - {17051,16912,17047 ,6676,6687,6703 ,0,0,0}, {18814,18762,18763 ,6686,6704,6672 ,0,0,0}, - {16912,16960,17103 ,6687,6705,6676 ,0,0,0}, {18765,18815,18764 ,6686,6706,6672 ,0,0,0}, - {17046,17104,16960 ,6698,6699,6705 ,0,0,0}, {17108,16951,16950 ,6697,6707,6708 ,0,0,0}, - {17107,17046,16951 ,6709,6698,6707 ,0,0,0}, {18816,18768,18770 ,6690,6671,6701 ,0,0,0}, - {16950,17044,17110 ,6708,6672,6694 ,0,0,0}, {18771,16938,18817 ,6690,6690,6686 ,0,0,0}, - {17114,17113,17042 ,6673,6689,6710 ,0,0,0}, {16936,16938,17153 ,6711,6690,6690 ,0,0,0}, - {17116,17114,17040 ,6686,6673,6692 ,0,0,0}, {17150,16934,17152 ,6712,6713,6685 ,0,0,0}, - {17035,17036,17122 ,6714,6684,6669 ,0,0,0}, {17146,16931,16933 ,6715,6716,6717 ,0,0,0}, - {17031,17128,17030 ,6718,6719,6691 ,0,0,0}, {17134,17132,16919 ,6298,6670,6676 ,0,0,0}, - {17140,16924,16926 ,6686,6704,6720 ,0,0,0}, {16926,16928,17143 ,6720,6669,6715 ,0,0,0}, - {17134,16921,17137 ,6298,6718,6669 ,0,0,0}, {16921,16924,17138 ,6718,6704,6691 ,0,0,0}, - {18809,18755,18754 ,6688,6688,6688 ,0,0,0}, {17029,17132,17131 ,6676,6670,6684 ,0,0,0}, - {17146,17144,16931 ,6715,6669,6716 ,0,0,0}, {16933,16934,17150 ,6717,6713,6712 ,0,0,0}, - {16933,17150,17146 ,6717,6712,6715 ,0,0,0}, {17034,17125,17036 ,6673,6721,6684 ,0,0,0}, - {17034,17030,17126 ,6673,6691,6670 ,0,0,0}, {16936,17153,17152 ,6711,6690,6685 ,0,0,0}, - {16936,17152,16934 ,6711,6685,6713 ,0,0,0}, {17039,17119,17116 ,6691,6669,6686 ,0,0,0}, - {17120,17039,17035 ,6720,6691,6714 ,0,0,0}, {17155,17153,16938 ,6671,6690,6690 ,0,0,0}, - {18769,18818,18819 ,6686,6722,6688 ,0,0,0}, {18766,18767,18820 ,6691,6723,6706 ,0,0,0}, - {17144,17143,16928 ,6669,6715,6669 ,0,0,0}, {17144,16928,16931 ,6669,6669,6716 ,0,0,0}, - {17143,17140,16926 ,6715,6686,6720 ,0,0,0}, {17140,17138,16924 ,6686,6691,6704 ,0,0,0}, - {17138,17137,16921 ,6691,6669,6718 ,0,0,0}, {17134,16919,16921 ,6298,6676,6718 ,0,0,0}, - {17132,17029,16919 ,6670,6676,6676 ,0,0,0}, {17131,17128,17031 ,6684,6719,6718 ,0,0,0}, - {17131,17031,17029 ,6684,6718,6676 ,0,0,0}, {17128,17126,17030 ,6719,6670,6691 ,0,0,0}, - {17126,17125,17034 ,6670,6721,6673 ,0,0,0}, {17125,17122,17036 ,6721,6669,6684 ,0,0,0}, - {17122,17120,17035 ,6669,6720,6714 ,0,0,0}, {17120,17119,17039 ,6720,6669,6691 ,0,0,0}, - {17116,17040,17039 ,6686,6692,6691 ,0,0,0}, {17114,17042,17040 ,6673,6710,6692 ,0,0,0}, - {17113,17110,17044 ,6689,6694,6672 ,0,0,0}, {17113,17044,17042 ,6689,6672,6710 ,0,0,0}, - {17110,17108,16950 ,6694,6697,6708 ,0,0,0}, {17108,17107,16951 ,6697,6709,6707 ,0,0,0}, - {17107,17104,17046 ,6709,6699,6698 ,0,0,0}, {17104,17103,16960 ,6699,6676,6705 ,0,0,0}, - {17103,17047,16912 ,6676,6703,6687 ,0,0,0}, {17051,16913,16912 ,6676,6702,6687 ,0,0,0}, - {17053,16965,16913 ,6699,6698,6702 ,0,0,0}, {17054,17057,16970 ,6700,6697,6696 ,0,0,0}, - {17054,16970,16965 ,6700,6696,6698 ,0,0,0}, {17057,17059,16971 ,6697,6694,6695 ,0,0,0}, - {17059,17060,16968 ,6694,6689,6672 ,0,0,0}, {17060,17063,16975 ,6689,6673,6693 ,0,0,0}, - {17063,17065,16976 ,6673,6672,6692 ,0,0,0}, {17065,17066,16973 ,6672,6669,6671 ,0,0,0}, - {17069,16982,16973 ,6670,6675,6671 ,0,0,0}, {17071,16978,16982 ,6669,6684,6675 ,0,0,0}, - {17072,17075,16979 ,6689,6674,6673 ,0,0,0}, {17072,16979,16978 ,6689,6673,6684 ,0,0,0}, - {17075,17077,16988 ,6674,6683,6671 ,0,0,0}, {17077,17078,16985 ,6683,6684,6669 ,0,0,0}, - {17078,17081,16983 ,6684,6670,6677 ,0,0,0}, {17081,17083,17011 ,6670,6298,6676 ,0,0,0}, - {17083,17084,16994 ,6298,6669,6669 ,0,0,0}, {17087,16999,16994 ,6671,6681,6669 ,0,0,0}, - {17089,16997,16999 ,6672,6670,6681 ,0,0,0}, {17090,17093,17003 ,6681,6669,6669 ,0,0,0}, - {17090,17003,16997 ,6681,6669,6670 ,0,0,0}, {17093,17094,17001 ,6669,6678,6679 ,0,0,0}, - {17094,17095,17005 ,6678,6682,6671 ,0,0,0}, {17095,17096,17006 ,6682,6298,6672 ,0,0,0}, - {17096,17101,17007 ,6298,6671,6679 ,0,0,0}, {17101,17102,17009 ,6671,6671,6671 ,0,0,0}, - {18775,18787,17009 ,6671,6672,6671 ,0,0,0}, {18725,18795,18787 ,6681,6671,6672 ,0,0,0}, - {18724,18723,18786 ,6671,6672,6681 ,0,0,0}, {18724,18786,18795 ,6671,6681,6671 ,0,0,0}, - {18723,18727,18785 ,6672,6672,6672 ,0,0,0}, {18727,18774,18791 ,6672,6671,6672 ,0,0,0}, - {18774,18726,18790 ,6671,6672,6672 ,0,0,0}, {18726,18731,18789 ,6672,6672,6672 ,0,0,0}, - {18731,18730,18788 ,6672,6672,6672 ,0,0,0}, {18729,18792,18788 ,6681,6671,6672 ,0,0,0}, - {18728,18776,18792 ,6672,6671,6671 ,0,0,0}, {18733,18773,18794 ,6671,6672,6672 ,0,0,0}, - {18733,18794,18776 ,6671,6672,6671 ,0,0,0}, {18773,18732,18793 ,6672,6671,6671 ,0,0,0}, - {18732,18772,18796 ,6671,6672,6681 ,0,0,0}, {18772,18736,18784 ,6672,6672,6672 ,0,0,0}, - {18736,18735,18783 ,6672,6672,6672 ,0,0,0}, {18735,18734,18797 ,6672,6672,6671 ,0,0,0}, - {18739,18782,18797 ,6671,6680,6671 ,0,0,0}, {18738,18779,18782 ,6672,6671,6680 ,0,0,0}, - {18737,18743,18798 ,6671,6671,6672 ,0,0,0}, {18737,18798,18779 ,6671,6672,6671 ,0,0,0}, - {18743,18742,18781 ,6671,6671,6671 ,0,0,0}, {18742,18741,18780 ,6671,6672,6672 ,0,0,0}, - {18741,18740,18799 ,6672,6671,6672 ,0,0,0}, {18740,18746,18778 ,6671,6672,6298 ,0,0,0}, - {18746,18744,18777 ,6672,6687,6324 ,0,0,0}, {18745,18800,18777 ,6686,6685,6324 ,0,0,0}, - {18748,18801,18800 ,6671,6688,6685 ,0,0,0}, {18747,18751,18804 ,6688,6690,6686 ,0,0,0}, - {18747,18804,18801 ,6688,6686,6688 ,0,0,0}, {18751,18750,18803 ,6690,6671,6690 ,0,0,0}, - {18750,18749,18802 ,6671,6691,6672 ,0,0,0}, {18749,18753,18805 ,6691,6686,6691 ,0,0,0}, - {18753,18752,18806 ,6686,6690,6690 ,0,0,0}, {18752,18756,18807 ,6690,6672,6691 ,0,0,0}, - {18755,18809,18807 ,6688,6688,6691 ,0,0,0}, {18758,18808,18754 ,6688,6672,6688 ,0,0,0}, - {18757,18821,18810 ,6691,6691,6701 ,0,0,0}, {18758,18810,18808 ,6688,6701,6672 ,0,0,0}, - {18811,18821,18759 ,6686,6691,6672 ,0,0,0}, {18757,18759,18821 ,6691,6672,6691 ,0,0,0}, - {18811,18760,18813 ,6686,6671,6671 ,0,0,0}, {18812,18761,18762 ,6671,6672,6704 ,0,0,0}, - {18813,18760,18761 ,6671,6671,6672 ,0,0,0}, {18814,18763,18764 ,6686,6672,6672 ,0,0,0}, - {18814,18812,18762 ,6686,6671,6704 ,0,0,0}, {18822,18815,18765 ,6688,6706,6686 ,0,0,0}, - {18815,18814,18764 ,6706,6686,6672 ,0,0,0}, {18822,18766,18820 ,6688,6691,6706 ,0,0,0}, - {18766,18822,18765 ,6691,6688,6686 ,0,0,0}, {18767,18819,18820 ,6723,6688,6706 ,0,0,0}, - {18769,18768,18818 ,6686,6671,6722 ,0,0,0}, {18767,18769,18819 ,6723,6686,6688 ,0,0,0}, - {18816,18770,18817 ,6690,6701,6686 ,0,0,0}, {18818,18768,18816 ,6722,6671,6690 ,0,0,0}, - {16938,18771,17155 ,6690,6690,6671 ,0,0,0}, {18817,18770,18771 ,6686,6701,6690 ,0,0,0}, - {18817,16515,18319 ,6724,6725,6726 ,0,0,0}, {18281,18818,18816 ,6727,6728,6729 ,0,0,0}, - {18820,18283,18822 ,6730,6731,6732 ,0,0,0}, {18424,18819,18422 ,6733,6734,6735 ,0,0,0}, - {18823,18433,18824 ,6736,6737,6738 ,0,0,0}, {18308,18823,18825 ,6739,6736,6736 ,0,0,0}, - {18349,18826,18827 ,6740,6741,6742 ,0,0,0}, {18348,18828,18307 ,6743,6744,6745 ,0,0,0}, - {18431,18829,18830 ,6746,6747,6748 ,0,0,0}, {18478,18831,18436 ,6749,6750,6751 ,0,0,0}, - {18832,18833,18476 ,6752,6753,6754 ,0,0,0}, {18829,18364,18477 ,6747,6755,6756 ,0,0,0}, - {18799,18400,18391 ,6757,6758,6759 ,0,0,0}, {16802,18400,18832 ,6760,6758,6752 ,0,0,0}, - {18781,18393,18798 ,6761,6762,6763 ,0,0,0}, {18392,18781,18780 ,6764,6761,6765 ,0,0,0}, - {18463,18398,18782 ,6766,6767,6768 ,0,0,0}, {18463,18779,18462 ,6766,6769,6770 ,0,0,0}, - {18797,18390,18783 ,6771,6772,6773 ,0,0,0}, {18390,18797,18398 ,6772,6771,6767 ,0,0,0}, - {18784,18783,18367 ,6774,6773,6775 ,0,0,0}, {18390,18367,18783 ,6772,6775,6773 ,0,0,0}, - {18365,18796,18366 ,6776,6777,6778 ,0,0,0}, {18784,18367,18366 ,6774,6775,6778 ,0,0,0}, - {18371,18794,18389 ,6779,6780,6781 ,0,0,0}, {18793,18365,18389 ,6782,6776,6781 ,0,0,0}, - {18370,18792,18776 ,6783,6784,6785 ,0,0,0}, {18789,18788,18834 ,6786,6787,6788 ,0,0,0}, - {18834,18388,18835 ,6788,6789,6788 ,0,0,0}, {18788,18792,18388 ,6787,6784,6789 ,0,0,0}, - {18836,18369,18342 ,6790,6791,6792 ,0,0,0}, {18369,18836,18835 ,6791,6790,6788 ,0,0,0}, - {18341,18837,18342 ,6793,6794,6792 ,0,0,0}, {18836,18342,18837 ,6790,6792,6794 ,0,0,0}, - {18341,18374,18838 ,6793,6795,6796 ,0,0,0}, {18838,18837,18341 ,6796,6794,6793 ,0,0,0}, - {18839,18374,18380 ,6797,6795,6798 ,0,0,0}, {18374,18839,18838 ,6795,6797,6796 ,0,0,0}, - {18384,18840,18380 ,6799,6800,6798 ,0,0,0}, {18839,18380,18840 ,6797,6798,6800 ,0,0,0}, - {18384,18377,18841 ,6799,6801,6802 ,0,0,0}, {18841,18840,18384 ,6802,6800,6799 ,0,0,0}, - {18842,18377,18386 ,6803,6801,6804 ,0,0,0}, {18377,18842,18841 ,6801,6803,6802 ,0,0,0}, - {16616,17019,18386 ,6805,6806,6804 ,0,0,0}, {18842,18386,17019 ,6803,6804,6806 ,0,0,0}, - {18786,18843,18844 ,6807,6808,6809 ,0,0,0}, {18788,18388,18834 ,6787,6789,6788 ,0,0,0}, - {18835,18388,18369 ,6788,6789,6791 ,0,0,0}, {18370,18388,18792 ,6783,6789,6784 ,0,0,0}, - {18371,18370,18776 ,6779,6783,6785 ,0,0,0}, {18776,18794,18371 ,6785,6780,6779 ,0,0,0}, - {18389,18794,18793 ,6781,6780,6782 ,0,0,0}, {18365,18793,18796 ,6776,6782,6777 ,0,0,0}, - {18796,18784,18366 ,6777,6774,6778 ,0,0,0}, {18834,18845,18789 ,6788,6810,6786 ,0,0,0}, - {18843,18786,18785 ,6808,6807,6811 ,0,0,0}, {18845,18790,18789 ,6810,6812,6786 ,0,0,0}, - {18844,18846,18795 ,6809,6813,6814 ,0,0,0}, {18795,18786,18844 ,6814,6807,6809 ,0,0,0}, - {18795,18847,18787 ,6814,6815,6816 ,0,0,0}, {18847,18795,18846 ,6815,6814,6813 ,0,0,0}, - {17009,18787,17010 ,6817,6816,6818 ,0,0,0}, {18847,17010,18787 ,6815,6818,6816 ,0,0,0}, - {18785,18848,18843 ,6811,6819,6808 ,0,0,0}, {18398,18797,18782 ,6767,6771,6768 ,0,0,0}, - {18848,18785,18791 ,6819,6811,6820 ,0,0,0}, {18849,18848,18791 ,6821,6819,6820 ,0,0,0}, - {18790,18845,18849 ,6812,6810,6821 ,0,0,0}, {18790,18849,18791 ,6812,6821,6820 ,0,0,0}, - {18782,18779,18463 ,6768,6769,6766 ,0,0,0}, {18429,18830,18831 ,6822,6748,6750 ,0,0,0}, - {18462,18798,18393 ,6770,6763,6762 ,0,0,0}, {18798,18462,18779 ,6763,6770,6769 ,0,0,0}, - {18781,18392,18393 ,6761,6764,6762 ,0,0,0}, {18391,18392,18780 ,6759,6764,6765 ,0,0,0}, - {18778,18400,18799 ,6823,6758,6757 ,0,0,0}, {18780,18799,18391 ,6765,6757,6759 ,0,0,0}, - {16802,18832,18476 ,6760,6752,6754 ,0,0,0}, {18778,18832,18400 ,6823,6752,6758 ,0,0,0}, - {18829,18431,18364 ,6747,6746,6755 ,0,0,0}, {18833,18829,18477 ,6753,6747,6756 ,0,0,0}, - {18831,18478,18429 ,6750,6749,6822 ,0,0,0}, {18850,18428,18851 ,6824,6825,6826 ,0,0,0}, - {18831,18851,18436 ,6750,6826,6751 ,0,0,0}, {18850,18826,18358 ,6824,6741,6827 ,0,0,0}, - {18428,18850,18358 ,6825,6824,6827 ,0,0,0}, {18827,18828,18348 ,6742,6744,6743 ,0,0,0}, - {18358,18826,18340 ,6827,6741,6828 ,0,0,0}, {18821,18811,18852 ,6829,6830,6831 ,0,0,0}, - {18812,18814,18825 ,6832,6833,6736 ,0,0,0}, {18828,18824,18427 ,6744,6738,6834 ,0,0,0}, - {18816,18319,18281 ,6729,6726,6727 ,0,0,0}, {18820,18819,18424 ,6730,6734,6733 ,0,0,0}, - {18284,18308,18815 ,6835,6739,6836 ,0,0,0}, {18442,18823,18308 ,6837,6736,6739 ,0,0,0}, - {18822,18284,18815 ,6732,6835,6836 ,0,0,0}, {18424,18283,18820 ,6733,6731,6730 ,0,0,0}, - {18822,18283,18284 ,6732,6731,6835 ,0,0,0}, {18818,18422,18819 ,6728,6735,6734 ,0,0,0}, - {18422,18818,18281 ,6735,6728,6727 ,0,0,0}, {18319,18816,18817 ,6726,6729,6724 ,0,0,0}, - {16515,18817,16938 ,6725,6724,6838 ,0,0,0}, {18800,18853,18777 ,6839,6840,6841 ,0,0,0}, - {18778,18777,18853 ,6823,6841,6840 ,0,0,0}, {18853,18800,18854 ,6840,6839,6842 ,0,0,0}, - {18778,18853,18832 ,6823,6840,6752 ,0,0,0}, {18855,18854,18801 ,6843,6842,6844 ,0,0,0}, - {18477,18476,18833 ,6756,6754,6753 ,0,0,0}, {18803,18855,18804 ,6845,6843,6846 ,0,0,0}, - {18803,18856,18855 ,6845,6847,6843 ,0,0,0}, {18857,18856,18802 ,6848,6847,6849 ,0,0,0}, - {18429,18431,18830 ,6822,6746,6748 ,0,0,0}, {18806,18857,18805 ,6850,6848,6851 ,0,0,0}, - {18806,18858,18857 ,6850,6852,6848 ,0,0,0}, {18859,18858,18807 ,6853,6852,6854 ,0,0,0}, - {18428,18436,18851 ,6825,6751,6826 ,0,0,0}, {18809,18860,18859 ,6855,6856,6853 ,0,0,0}, - {18808,18860,18809 ,6857,6856,6855 ,0,0,0}, {18861,18860,18810 ,6858,6856,6859 ,0,0,0}, - {18349,18340,18826 ,6740,6828,6741 ,0,0,0}, {18852,18861,18821 ,6831,6858,6829 ,0,0,0}, - {18348,18349,18827 ,6743,6740,6742 ,0,0,0}, {18862,18852,18813 ,6860,6831,6861 ,0,0,0}, - {18427,18307,18828 ,6834,6745,6744 ,0,0,0}, {18825,18862,18812 ,6736,6860,6832 ,0,0,0}, - {18433,18427,18824 ,6737,6834,6738 ,0,0,0}, {18815,18308,18825 ,6836,6739,6736 ,0,0,0}, - {18433,18823,18442 ,6737,6736,6837 ,0,0,0}, {18815,18825,18814 ,6836,6736,6833 ,0,0,0}, - {18813,18812,18862 ,6861,6832,6860 ,0,0,0}, {18811,18813,18852 ,6830,6861,6831 ,0,0,0}, - {18810,18821,18861 ,6859,6829,6858 ,0,0,0}, {18808,18810,18860 ,6857,6859,6856 ,0,0,0}, - {18807,18809,18859 ,6854,6855,6853 ,0,0,0}, {18806,18807,18858 ,6850,6854,6852 ,0,0,0}, - {18802,18805,18857 ,6849,6851,6848 ,0,0,0}, {18803,18802,18856 ,6845,6849,6847 ,0,0,0}, - {18801,18804,18855 ,6844,6846,6843 ,0,0,0}, {18800,18801,18854 ,6839,6844,6842 ,0,0,0}, - {18863,16810,16811 ,6862,6863,6864 ,0,0,0}, {18515,18504,17742 ,6865,6866,6867 ,0,0,0}, - {18864,18512,18511 ,6868,6869,6870 ,0,0,0}, {18514,17735,18501 ,6871,6872,6873 ,0,0,0}, - {17720,18494,18498 ,6874,6875,6876 ,0,0,0}, {17732,18517,18518 ,6877,6878,6879 ,0,0,0}, - {18528,17727,17726 ,6880,6881,6882 ,0,0,0}, {18525,17719,17722 ,6883,6884,6885 ,0,0,0}, - {18865,18538,18536 ,6886,6887,6888 ,0,0,0}, {18866,18532,17729 ,6889,6890,5525 ,0,0,0}, - {18549,18546,17805 ,6891,6892,6893 ,0,0,0}, {18542,18867,18868 ,6894,6895,6896 ,0,0,0}, - {18556,17794,18610 ,6897,6898,6899 ,0,0,0}, {18552,17800,18555 ,6900,6901,6902 ,0,0,0}, - {17841,18561,17839 ,6903,6904,6905 ,0,0,0}, {18604,18557,17837 ,6906,6907,6908 ,0,0,0}, - {18593,18869,18595 ,6909,6910,6911 ,0,0,0}, {18601,17842,18567 ,6912,6913,6914 ,0,0,0}, - {18870,18582,18574 ,6915,6916,6917 ,0,0,0}, {18592,18871,18579 ,6918,6919,6920 ,0,0,0}, - {18872,18589,18590 ,6921,6922,6923 ,0,0,0}, {17898,17901,18583 ,6924,6925,6926 ,0,0,0}, - {17898,18586,17899 ,6924,6927,5712 ,0,0,0}, {17886,17885,18576 ,6928,6929,6930 ,0,0,0}, - {17886,18591,17901 ,6928,6931,6925 ,0,0,0}, {18596,18598,17885 ,6932,6933,6929 ,0,0,0}, - {17885,18598,18576 ,6929,6933,6930 ,0,0,0}, {18596,17885,17930 ,6932,6929,6934 ,0,0,0}, - {17930,17932,18570 ,6934,6935,6936 ,0,0,0}, {18570,18596,17930 ,6936,6932,6934 ,0,0,0}, - {18602,17932,17934 ,6937,6935,6938 ,0,0,0}, {17932,18602,18570 ,6935,6937,6936 ,0,0,0}, - {18602,17934,18563 ,6937,6938,6939 ,0,0,0}, {17935,18564,18563 ,6940,6941,6939 ,0,0,0}, - {18563,17934,17935 ,6939,6938,6940 ,0,0,0}, {18564,17937,18608 ,6941,6942,6943 ,0,0,0}, - {17937,18564,17935 ,6942,6941,6940 ,0,0,0}, {18558,18608,17938 ,6944,6943,6945 ,0,0,0}, - {17937,17938,18608 ,6942,6945,6943 ,0,0,0}, {17938,18873,18553 ,6945,6946,6947 ,0,0,0}, - {18553,18558,17938 ,6947,6944,6945 ,0,0,0}, {18550,18873,18874 ,6948,6946,6949 ,0,0,0}, - {18873,18550,18553 ,6946,6948,6947 ,0,0,0}, {18875,18547,18874 ,6950,6951,6949 ,0,0,0}, - {18550,18874,18547 ,6948,6949,6951 ,0,0,0}, {18875,16908,16906 ,6950,126,3135 ,0,0,0}, - {16906,18547,18875 ,3135,6951,6950 ,0,0,0}, {17901,18591,18583 ,6925,6931,6926 ,0,0,0}, - {17886,18576,18591 ,6928,6930,6931 ,0,0,0}, {18586,18579,17899 ,6927,6920,5712 ,0,0,0}, - {17898,18583,18586 ,6924,6926,6927 ,0,0,0}, {18871,18592,18589 ,6919,6918,6922 ,0,0,0}, - {18871,17899,18579 ,6919,5712,6920 ,0,0,0}, {18872,18590,18582 ,6921,6923,6916 ,0,0,0}, - {18872,18871,18589 ,6921,6919,6922 ,0,0,0}, {18869,18870,18574 ,6910,6915,6917 ,0,0,0}, - {18870,18872,18582 ,6915,6921,6916 ,0,0,0}, {17844,18869,18593 ,6952,6910,6909 ,0,0,0}, - {18595,18869,18574 ,6911,6910,6917 ,0,0,0}, {17844,18567,17842 ,6952,6914,6913 ,0,0,0}, - {18567,17844,18593 ,6914,6952,6909 ,0,0,0}, {18599,17841,17842 ,6953,6903,6913 ,0,0,0}, - {18599,17842,18601 ,6953,6913,6912 ,0,0,0}, {18561,18606,17839 ,6904,6954,6905 ,0,0,0}, - {18599,18561,17841 ,6953,6904,6903 ,0,0,0}, {18604,17837,18606 ,6906,6908,6954 ,0,0,0}, - {17839,18606,17837 ,6905,6954,6908 ,0,0,0}, {17796,18557,18610 ,6955,6907,6899 ,0,0,0}, - {17837,18557,17796 ,6908,6907,6955 ,0,0,0}, {17806,17794,18556 ,6956,6898,6897 ,0,0,0}, - {17794,17796,18610 ,6898,6955,6899 ,0,0,0}, {17806,18555,17800 ,6956,6902,6901 ,0,0,0}, - {18555,17806,18556 ,6902,6956,6897 ,0,0,0}, {18549,17805,17800 ,6891,6893,6901 ,0,0,0}, - {18549,17800,18552 ,6891,6901,6900 ,0,0,0}, {18546,18544,18868 ,6892,6957,6896 ,0,0,0}, - {18546,18868,17805 ,6892,6896,6893 ,0,0,0}, {18542,18540,18867 ,6894,6958,6895 ,0,0,0}, - {18544,18542,18868 ,6957,6894,6896 ,0,0,0}, {18538,18865,18540 ,6887,6886,6958 ,0,0,0}, - {18867,18540,18865 ,6895,6958,6886 ,0,0,0}, {18866,18536,18534 ,6889,6888,6959 ,0,0,0}, - {18865,18536,18866 ,6886,6888,6889 ,0,0,0}, {17729,18532,18530 ,5525,6890,6960 ,0,0,0}, - {18866,18534,18532 ,6889,6959,6890 ,0,0,0}, {18530,18528,17726 ,6960,6880,6882 ,0,0,0}, - {17726,17729,18530 ,6882,5525,6960 ,0,0,0}, {18495,17722,17727 ,6961,6885,6881 ,0,0,0}, - {18495,17727,18528 ,6961,6881,6880 ,0,0,0}, {18525,18521,17719 ,6883,6962,6884 ,0,0,0}, - {18495,18525,17722 ,6961,6883,6885 ,0,0,0}, {17720,17719,18494 ,6874,6884,6875 ,0,0,0}, - {18521,18494,17719 ,6962,6875,6884 ,0,0,0}, {17725,18498,18517 ,6963,6876,6878 ,0,0,0}, - {17720,18498,17725 ,6874,6876,6963 ,0,0,0}, {17734,17732,18518 ,6964,6877,6879 ,0,0,0}, - {17732,17725,18517 ,6877,6963,6878 ,0,0,0}, {17734,18501,17735 ,6964,6873,6872 ,0,0,0}, - {18501,17734,18518 ,6873,6964,6879 ,0,0,0}, {18514,18515,17742 ,6871,6865,6867 ,0,0,0}, - {18514,17742,17735 ,6871,6867,6872 ,0,0,0}, {18504,18512,18876 ,6866,6869,6965 ,0,0,0}, - {18504,18876,17742 ,6866,6965,6867 ,0,0,0}, {18864,18511,18863 ,6868,6870,6862 ,0,0,0}, - {18876,18512,18864 ,6965,6869,6868 ,0,0,0}, {16810,18863,18511 ,6863,6862,6870 ,0,0,0}, - {16780,18877,18438 ,6966,6967,6968 ,0,0,0}, {18878,18482,18879 ,6969,6970,6971 ,0,0,0}, - {18350,18351,18880 ,6972,6973,6974 ,0,0,0}, {18484,18881,18485 ,6975,6976,6977 ,0,0,0}, - {18882,18883,18426 ,6978,6979,6980 ,0,0,0}, {18884,18481,18885 ,6981,6982,6983 ,0,0,0}, - {18483,18437,18886 ,6984,6985,6986 ,0,0,0}, {18488,18887,18888 ,6987,6988,6989 ,0,0,0}, - {18479,18889,18480 ,6990,6991,6992 ,0,0,0}, {18489,18890,18362 ,6993,6994,6995 ,0,0,0}, - {18891,18489,18430 ,6996,6993,6997 ,0,0,0}, {18363,18892,18490 ,6998,6999,7000 ,0,0,0}, - {18893,18363,18362 ,7001,6998,6995 ,0,0,0}, {18491,18490,18894 ,7002,7000,7003 ,0,0,0}, - {18892,18894,18490 ,6999,7003,7000 ,0,0,0}, {18895,18475,18491 ,7004,7005,7002 ,0,0,0}, - {18491,18894,18895 ,7002,7003,7004 ,0,0,0}, {18475,18896,18493 ,7005,7006,7007 ,0,0,0}, - {18896,18475,18895 ,7006,7005,7004 ,0,0,0}, {18492,18493,18897 ,7008,7007,7009 ,0,0,0}, - {18896,18897,18493 ,7006,7009,7007 ,0,0,0}, {18898,16802,18492 ,7010,82,7008 ,0,0,0}, - {18492,18897,18898 ,7008,7009,7010 ,0,0,0}, {16801,16802,18898 ,7011,82,7010 ,0,0,0}, - {18430,18888,18891 ,6997,6989,6996 ,0,0,0}, {18890,18893,18362 ,6994,7001,6995 ,0,0,0}, - {18893,18892,18363 ,7001,6999,6998 ,0,0,0}, {18890,18489,18891 ,6994,6993,6996 ,0,0,0}, - {18887,18488,18480 ,6988,6987,6992 ,0,0,0}, {18888,18430,18488 ,6989,6997,6987 ,0,0,0}, - {18480,18889,18887 ,6992,6991,6988 ,0,0,0}, {18884,18889,18479 ,6981,6991,6990 ,0,0,0}, - {18899,18485,18881 ,7012,6977,6976 ,0,0,0}, {18483,18885,18481 ,6984,6983,6982 ,0,0,0}, - {18479,18481,18884 ,6990,6982,6981 ,0,0,0}, {18437,18485,18899 ,6985,6977,7012 ,0,0,0}, - {18437,18899,18886 ,6985,7012,6986 ,0,0,0}, {18885,18483,18886 ,6983,6984,6986 ,0,0,0}, - {18482,18350,18879 ,6970,6972,6971 ,0,0,0}, {18881,18484,18883 ,6976,6975,6979 ,0,0,0}, - {18882,18426,18425 ,6978,6980,7013 ,0,0,0}, {18426,18883,18484 ,6980,6979,6975 ,0,0,0}, - {18425,18482,18878 ,7013,6970,6969 ,0,0,0}, {18425,18878,18882 ,7013,6969,6978 ,0,0,0}, - {18351,18877,18880 ,6973,6967,6974 ,0,0,0}, {18879,18350,18880 ,6971,6972,6974 ,0,0,0}, - {16780,18438,16777 ,6966,6968,7014 ,0,0,0}, {18877,18351,18438 ,6967,6973,6968 ,0,0,0}, - {18899,16795,18886 ,730,730,730 ,0,0,0}, {18894,18892,18890 ,730,730,730 ,0,0,0}, - {18892,18893,18890 ,730,730,730 ,0,0,0}, {18890,18891,18895 ,730,730,730 ,0,0,0}, - {18895,18894,18890 ,730,730,730 ,0,0,0}, {18896,18891,18888 ,730,730,730 ,0,0,0}, - {18891,18896,18895 ,730,730,730 ,0,0,0}, {18887,18897,18888 ,730,730,730 ,0,0,0}, - {18896,18888,18897 ,730,730,730 ,0,0,0}, {18898,18887,16801 ,730,730,730 ,0,0,0}, - {18898,18897,18887 ,730,730,730 ,0,0,0}, {18889,18884,16799 ,730,730,730 ,0,0,0}, - {18887,18889,16801 ,730,730,730 ,0,0,0}, {18881,16790,16793 ,730,730,7015 ,0,0,0}, - {16796,16799,18885 ,730,730,730 ,0,0,0}, {18878,16784,16787 ,7016,7015,7017 ,0,0,0}, - {18883,16787,16789 ,730,7017,7017 ,0,0,0}, {16781,16783,18880 ,730,730,730 ,0,0,0}, - {16780,16756,16758 ,730,730,730 ,0,0,0}, {16754,16781,18877 ,7015,730,730 ,0,0,0}, - {16760,16774,16772 ,730,730,7017 ,0,0,0}, {16756,16775,16762 ,730,7017,7015 ,0,0,0}, - {16768,16764,16769 ,730,730,730 ,0,0,0}, {16764,16772,16769 ,730,7017,730 ,0,0,0}, - {16765,16764,16768 ,730,730,730 ,0,0,0}, {16760,16762,16774 ,730,7015,730 ,0,0,0}, - {16764,16760,16772 ,730,730,7017 ,0,0,0}, {16775,16756,16779 ,7017,730,730 ,0,0,0}, - {16774,16762,16775 ,730,7015,7017 ,0,0,0}, {16780,16779,16756 ,730,730,730 ,0,0,0}, - {18877,16758,16754 ,730,730,7015 ,0,0,0}, {18877,16780,16758 ,730,730,730 ,0,0,0}, - {16783,18879,18880 ,730,7016,730 ,0,0,0}, {18880,18877,16781 ,730,730,730 ,0,0,0}, - {18878,18879,16784 ,7016,7016,7015 ,0,0,0}, {16783,16784,18879 ,730,7015,7016 ,0,0,0}, - {16787,18883,18882 ,7017,730,730 ,0,0,0}, {16787,18882,18878 ,7017,730,7016 ,0,0,0}, - {16789,16790,18881 ,7017,730,730 ,0,0,0}, {18883,16789,18881 ,730,7017,730 ,0,0,0}, - {16793,16795,18899 ,7015,730,730 ,0,0,0}, {18881,16793,18899 ,730,7015,730 ,0,0,0}, - {18886,16796,18885 ,730,730,730 ,0,0,0}, {18886,16795,16796 ,730,730,730 ,0,0,0}, - {18889,16799,16801 ,730,730,730 ,0,0,0}, {18884,18885,16799 ,730,730,730 ,0,0,0}, - {18900,18901,16752 ,7018,7019,7020 ,0,0,0}, {16752,18902,18900 ,7020,7021,7018 ,0,0,0}, - {16752,16735,18902 ,7020,7022,7021 ,0,0,0}, {16752,18903,18904 ,7020,7023,7024 ,0,0,0}, - {18901,18903,16752 ,7019,7023,7020 ,0,0,0}, {16752,18905,18906 ,7020,7025,7026 ,0,0,0}, - {18904,18905,16752 ,7024,7025,7020 ,0,0,0}, {18906,18907,16752 ,7026,7027,7020 ,0,0,0}, - {18908,16752,18909 ,7028,7020,7029 ,0,0,0}, {16752,18907,18909 ,7020,7027,7029 ,0,0,0}, - {18910,16752,18911 ,7030,7020,7031 ,0,0,0}, {16752,18908,18911 ,7020,7028,7031 ,0,0,0}, - {18912,16752,18913 ,7032,7020,7033 ,0,0,0}, {16752,18910,18913 ,7020,7030,7033 ,0,0,0}, - {16751,16752,18912 ,7034,7020,7032 ,0,0,0}, {16734,18407,18902 ,7035,7036,7037 ,0,0,0}, - {18904,18903,18397 ,7038,7039,7040 ,0,0,0}, {18901,18900,18406 ,7041,7042,7043 ,0,0,0}, - {18906,18464,18907 ,7044,7045,7046 ,0,0,0}, {18396,18409,18905 ,7047,7048,7049 ,0,0,0}, - {18465,18290,18908 ,7050,7051,7052 ,0,0,0}, {18465,18909,18356 ,7050,7053,7054 ,0,0,0}, - {18354,18413,18910 ,7055,7056,7057 ,0,0,0}, {18910,18911,18354 ,7057,7058,7055 ,0,0,0}, - {18913,18413,18399 ,7059,7056,7060 ,0,0,0}, {18413,18913,18910 ,7056,7059,7057 ,0,0,0}, - {18387,18912,18399 ,7061,7062,7060 ,0,0,0}, {18913,18399,18912 ,7059,7060,7062 ,0,0,0}, - {18387,16750,16751 ,7061,7063,4910 ,0,0,0}, {16751,18912,18387 ,4910,7062,7061 ,0,0,0}, - {18464,18906,18409 ,7045,7044,7048 ,0,0,0}, {18290,18911,18908 ,7051,7058,7052 ,0,0,0}, - {18354,18911,18290 ,7055,7058,7051 ,0,0,0}, {18397,18903,18405 ,7040,7039,7064 ,0,0,0}, - {18356,18909,18907 ,7054,7053,7046 ,0,0,0}, {18465,18908,18909 ,7050,7052,7053 ,0,0,0}, - {18464,18356,18907 ,7045,7054,7046 ,0,0,0}, {18905,18409,18906 ,7049,7048,7044 ,0,0,0}, - {18904,18397,18396 ,7038,7040,7047 ,0,0,0}, {18396,18905,18904 ,7047,7049,7038 ,0,0,0}, - {18900,18407,18406 ,7042,7036,7043 ,0,0,0}, {18405,18901,18406 ,7064,7041,7043 ,0,0,0}, - {18903,18901,18405 ,7039,7041,7064 ,0,0,0}, {16734,18902,16735 ,7035,7037,4929 ,0,0,0}, - {18407,18900,18902 ,7036,7042,7037 ,0,0,0}, {18914,18915,16718 ,7018,7019,7065 ,0,0,0}, - {16718,18916,18914 ,7065,7021,7018 ,0,0,0}, {16718,16701,18916 ,7065,7066,7021 ,0,0,0}, - {16718,18917,18918 ,7065,7023,7024 ,0,0,0}, {18915,18917,16718 ,7019,7023,7065 ,0,0,0}, - {16718,18919,18920 ,7065,7025,7026 ,0,0,0}, {18918,18919,16718 ,7024,7025,7065 ,0,0,0}, - {18920,18921,16718 ,7026,7027,7065 ,0,0,0}, {18922,16718,18923 ,7028,7065,7029 ,0,0,0}, - {16718,18921,18923 ,7065,7027,7029 ,0,0,0}, {18924,16718,18925 ,7030,7065,7031 ,0,0,0}, - {16718,18922,18925 ,7065,7028,7031 ,0,0,0}, {18926,16718,18927 ,7032,7065,7033 ,0,0,0}, - {16718,18924,18927 ,7065,7030,7033 ,0,0,0}, {16717,16718,18926 ,7067,7065,7032 ,0,0,0}, - {16700,18456,18916 ,7068,7069,7070 ,0,0,0}, {18918,18917,18297 ,7071,7072,7073 ,0,0,0}, - {18915,18914,18336 ,7074,7075,7076 ,0,0,0}, {18920,18316,18921 ,7077,7078,7079 ,0,0,0}, - {18298,18461,18919 ,7047,7080,7081 ,0,0,0}, {18280,18459,18922 ,7082,7083,7084 ,0,0,0}, - {18280,18923,18460 ,7082,7085,7086 ,0,0,0}, {18458,18334,18924 ,7087,7088,7089 ,0,0,0}, - {18924,18925,18458 ,7089,7090,7087 ,0,0,0}, {18927,18334,18335 ,7091,7088,7092 ,0,0,0}, - {18334,18927,18924 ,7088,7091,7089 ,0,0,0}, {18457,18926,18335 ,7093,7094,7092 ,0,0,0}, - {18927,18335,18926 ,7091,7092,7094 ,0,0,0}, {18457,16716,16717 ,7093,4831,4942 ,0,0,0}, - {16717,18926,18457 ,4942,7094,7093 ,0,0,0}, {18316,18920,18461 ,7078,7077,7080 ,0,0,0}, - {18459,18925,18922 ,7083,7090,7084 ,0,0,0}, {18458,18925,18459 ,7087,7090,7083 ,0,0,0}, - {18297,18917,18333 ,7073,7072,7095 ,0,0,0}, {18460,18923,18921 ,7086,7085,7079 ,0,0,0}, - {18280,18922,18923 ,7082,7084,7085 ,0,0,0}, {18316,18460,18921 ,7078,7086,7079 ,0,0,0}, - {18919,18461,18920 ,7081,7080,7077 ,0,0,0}, {18918,18297,18298 ,7071,7073,7047 ,0,0,0}, - {18298,18919,18918 ,7047,7081,7071 ,0,0,0}, {18914,18456,18336 ,7075,7069,7076 ,0,0,0}, - {18333,18915,18336 ,7095,7074,7076 ,0,0,0}, {18917,18915,18333 ,7072,7074,7095 ,0,0,0}, - {16700,18916,16701 ,7068,7070,4899 ,0,0,0}, {18456,18914,18916 ,7069,7075,7070 ,0,0,0}, - {18928,18929,16684 ,7018,7019,7065 ,0,0,0}, {16684,18930,18928 ,7065,7021,7018 ,0,0,0}, - {16684,16667,18930 ,7065,7096,7021 ,0,0,0}, {16684,18931,18932 ,7065,7023,7024 ,0,0,0}, - {18929,18931,16684 ,7019,7023,7065 ,0,0,0}, {16684,18933,18934 ,7065,7025,7026 ,0,0,0}, - {18932,18933,16684 ,7024,7025,7065 ,0,0,0}, {18934,18935,16684 ,7026,7027,7065 ,0,0,0}, - {18936,16684,18937 ,7028,7065,7029 ,0,0,0}, {16684,18935,18937 ,7065,7027,7029 ,0,0,0}, - {18938,16684,18939 ,7030,7065,7031 ,0,0,0}, {16684,18936,18939 ,7065,7028,7031 ,0,0,0}, - {18940,16684,18941 ,7032,7065,7033 ,0,0,0}, {16684,18938,18941 ,7065,7030,7033 ,0,0,0}, - {16683,16684,18940 ,7097,7065,7032 ,0,0,0}, {16666,18454,18930 ,7098,7099,7100 ,0,0,0}, - {18932,18931,18419 ,7101,7102,7103 ,0,0,0}, {18929,18928,18446 ,7104,7105,7076 ,0,0,0}, - {18934,18418,18935 ,7106,7107,7108 ,0,0,0}, {18453,18452,18933 ,7109,7110,7111 ,0,0,0}, - {18330,18327,18936 ,7112,7113,7114 ,0,0,0}, {18330,18937,18447 ,7112,7115,7116 ,0,0,0}, - {18332,18331,18938 ,7117,7118,7119 ,0,0,0}, {18938,18939,18332 ,7119,7120,7117 ,0,0,0}, - {18941,18331,18329 ,7121,7118,7122 ,0,0,0}, {18331,18941,18938 ,7118,7121,7119 ,0,0,0}, - {18328,18940,18329 ,7123,7124,7122 ,0,0,0}, {18941,18329,18940 ,7121,7122,7124 ,0,0,0}, - {18328,16682,16683 ,7123,4831,4831 ,0,0,0}, {16683,18940,18328 ,4831,7124,7123 ,0,0,0}, - {18418,18934,18452 ,7107,7106,7110 ,0,0,0}, {18327,18939,18936 ,7113,7120,7114 ,0,0,0}, - {18332,18939,18327 ,7117,7120,7113 ,0,0,0}, {18419,18931,18445 ,7103,7102,7125 ,0,0,0}, - {18447,18937,18935 ,7116,7115,7108 ,0,0,0}, {18330,18936,18937 ,7112,7114,7115 ,0,0,0}, - {18418,18447,18935 ,7107,7116,7108 ,0,0,0}, {18933,18452,18934 ,7111,7110,7106 ,0,0,0}, - {18932,18419,18453 ,7101,7103,7109 ,0,0,0}, {18453,18933,18932 ,7109,7111,7101 ,0,0,0}, - {18928,18454,18446 ,7105,7099,7076 ,0,0,0}, {18445,18929,18446 ,7125,7104,7076 ,0,0,0}, - {18931,18929,18445 ,7102,7104,7125 ,0,0,0}, {16666,18930,16667 ,7098,7100,4865 ,0,0,0}, - {18454,18928,18930 ,7099,7105,7100 ,0,0,0}, {18942,18943,16650 ,7018,7019,7126 ,0,0,0}, - {16650,18944,18942 ,7126,7021,7018 ,0,0,0}, {16650,16633,18944 ,7126,7127,7021 ,0,0,0}, - {16650,18945,18946 ,7126,7023,7024 ,0,0,0}, {18943,18945,16650 ,7019,7023,7126 ,0,0,0}, - {16650,18947,18948 ,7126,7025,7026 ,0,0,0}, {18946,18947,16650 ,7024,7025,7126 ,0,0,0}, - {18948,18949,16650 ,7026,7027,7126 ,0,0,0}, {18950,16650,18951 ,7028,7126,7029 ,0,0,0}, - {16650,18949,18951 ,7126,7027,7029 ,0,0,0}, {18952,16650,18953 ,7030,7126,7031 ,0,0,0}, - {16650,18950,18953 ,7126,7028,7031 ,0,0,0}, {18954,16650,18955 ,7032,7126,7033 ,0,0,0}, - {16650,18952,18955 ,7126,7030,7033 ,0,0,0}, {16649,16650,18954 ,7128,7126,7032 ,0,0,0}, - {16632,18435,18944 ,7129,7099,7130 ,0,0,0}, {18946,18945,18440 ,7131,7132,7133 ,0,0,0}, - {18943,18942,18434 ,7041,7075,7134 ,0,0,0}, {18948,18441,18949 ,7135,7107,7136 ,0,0,0}, - {18439,18467,18947 ,7137,7138,7139 ,0,0,0}, {18317,18318,18950 ,7140,7141,7142 ,0,0,0}, - {18317,18951,18423 ,7140,7143,7144 ,0,0,0}, {18401,18402,18952 ,7145,7146,7147 ,0,0,0}, - {18952,18953,18401 ,7147,7148,7145 ,0,0,0}, {18955,18402,18487 ,7149,7146,7150 ,0,0,0}, - {18402,18955,18952 ,7146,7149,7147 ,0,0,0}, {18486,18954,18487 ,7151,7152,7150 ,0,0,0}, - {18955,18487,18954 ,7149,7150,7152 ,0,0,0}, {18486,16648,16649 ,7151,7153,4831 ,0,0,0}, - {16649,18954,18486 ,4831,7152,7151 ,0,0,0}, {18441,18948,18467 ,7107,7135,7138 ,0,0,0}, - {18318,18953,18950 ,7141,7148,7142 ,0,0,0}, {18401,18953,18318 ,7145,7148,7141 ,0,0,0}, - {18440,18945,18443 ,7133,7132,7154 ,0,0,0}, {18423,18951,18949 ,7144,7143,7136 ,0,0,0}, - {18317,18950,18951 ,7140,7142,7143 ,0,0,0}, {18441,18423,18949 ,7107,7144,7136 ,0,0,0}, - {18947,18467,18948 ,7139,7138,7135 ,0,0,0}, {18946,18440,18439 ,7131,7133,7137 ,0,0,0}, - {18439,18947,18946 ,7137,7139,7131 ,0,0,0}, {18942,18435,18434 ,7075,7099,7134 ,0,0,0}, - {18443,18943,18434 ,7154,7041,7134 ,0,0,0}, {18945,18943,18443 ,7132,7041,7154 ,0,0,0}, - {16632,18944,16633 ,7129,7130,4929 ,0,0,0}, {18435,18942,18944 ,7099,7075,7130 ,0,0,0}, - {16593,16592,18956 ,4777,21,7155 ,0,0,0}, {18300,18313,18957 ,7156,7157,7158 ,0,0,0}, - {18309,18958,18959 ,7159,7160,7161 ,0,0,0}, {18960,18961,18291 ,7162,7163,7164 ,0,0,0}, - {18962,18357,18315 ,7165,7166,7167 ,0,0,0}, {18368,18412,18963 ,7168,7169,7170 ,0,0,0}, - {18353,18964,18965 ,7171,7172,7173 ,0,0,0}, {18343,18966,18375 ,7174,7175,7176 ,0,0,0}, - {18967,18968,18372 ,7177,7178,7179 ,0,0,0}, {18969,18970,18381 ,7180,7181,7182 ,0,0,0}, - {18971,18373,18375 ,7183,7184,7176 ,0,0,0}, {18972,18973,18382 ,7185,7186,7187 ,0,0,0}, - {18972,18379,18970 ,7185,7188,7181 ,0,0,0}, {18383,18973,18974 ,7189,7186,7190 ,0,0,0}, - {18973,18383,18382 ,7186,7189,7187 ,0,0,0}, {18975,18378,18974 ,7191,7192,7190 ,0,0,0}, - {18383,18974,18378 ,7189,7190,7192 ,0,0,0}, {18975,18976,18376 ,7191,7193,7194 ,0,0,0}, - {18376,18378,18975 ,7194,7192,7191 ,0,0,0}, {18385,18976,18977 ,7195,7193,7196 ,0,0,0}, - {18976,18385,18376 ,7193,7195,7194 ,0,0,0}, {16615,18386,18977 ,7197,7198,7196 ,0,0,0}, - {18385,18977,18386 ,7195,7196,7198 ,0,0,0}, {16616,18386,16615 ,7199,7198,7197 ,0,0,0}, - {18343,18968,18966 ,7174,7178,7175 ,0,0,0}, {18379,18381,18970 ,7188,7182,7181 ,0,0,0}, - {18972,18382,18379 ,7185,7187,7188 ,0,0,0}, {18373,18971,18969 ,7184,7183,7180 ,0,0,0}, - {18969,18381,18373 ,7180,7182,7184 ,0,0,0}, {18971,18375,18966 ,7183,7176,7175 ,0,0,0}, - {18968,18343,18372 ,7178,7174,7179 ,0,0,0}, {18368,18963,18967 ,7168,7170,7177 ,0,0,0}, - {18368,18967,18372 ,7168,7177,7179 ,0,0,0}, {18357,18960,18291 ,7166,7162,7164 ,0,0,0}, - {18965,18412,18353 ,7173,7169,7171 ,0,0,0}, {18412,18965,18963 ,7169,7173,7170 ,0,0,0}, - {18292,18291,18961 ,7200,7164,7163 ,0,0,0}, {18353,18292,18964 ,7171,7200,7172 ,0,0,0}, - {18964,18292,18961 ,7172,7200,7163 ,0,0,0}, {18962,18960,18357 ,7165,7162,7166 ,0,0,0}, - {18978,18962,18315 ,7201,7165,7167 ,0,0,0}, {18300,18957,18978 ,7156,7158,7201 ,0,0,0}, - {18300,18978,18315 ,7156,7201,7167 ,0,0,0}, {18414,18956,18958 ,7202,7155,7160 ,0,0,0}, - {18959,18313,18309 ,7161,7157,7159 ,0,0,0}, {18313,18959,18957 ,7157,7161,7158 ,0,0,0}, - {18414,18958,18309 ,7202,7160,7159 ,0,0,0}, {18956,18414,16593 ,7155,7202,4777 ,0,0,0}, - {16581,18969,16584 ,730,7015,730 ,0,0,0}, {18959,18958,18964 ,730,730,730 ,0,0,0}, - {16591,16587,18968 ,730,730,730 ,0,0,0}, {16585,18971,18966 ,730,730,7015 ,0,0,0}, - {18965,18964,18958 ,730,730,730 ,0,0,0}, {16592,18967,18956 ,730,730,730 ,0,0,0}, - {18962,18978,18957 ,730,730,730 ,0,0,0}, {18957,18959,18961 ,730,730,730 ,0,0,0}, - {18957,18961,18960 ,730,730,730 ,0,0,0}, {18962,18957,18960 ,730,730,730 ,0,0,0}, - {18958,18956,18965 ,730,730,730 ,0,0,0}, {18961,18959,18964 ,730,730,730 ,0,0,0}, - {18956,18963,18965 ,730,730,730 ,0,0,0}, {18967,16592,18968 ,730,730,730 ,0,0,0}, - {18963,18956,18967 ,730,730,730 ,0,0,0}, {18968,16587,18966 ,730,730,7015 ,0,0,0}, - {18968,16592,16591 ,730,730,730 ,0,0,0}, {18971,16585,16584 ,730,730,730 ,0,0,0}, - {18966,16587,16585 ,7015,730,730 ,0,0,0}, {18970,18969,16581 ,730,7015,730 ,0,0,0}, - {18969,18971,16584 ,7015,730,730 ,0,0,0}, {18972,16581,16580 ,7015,730,730 ,0,0,0}, - {16581,18972,18970 ,730,7015,730 ,0,0,0}, {18972,16580,18973 ,7015,730,730 ,0,0,0}, - {16573,18973,16577 ,730,730,730 ,0,0,0}, {18973,16580,16577 ,730,730,730 ,0,0,0}, - {16573,16572,18974 ,730,730,7015 ,0,0,0}, {18974,18973,16573 ,7015,730,730 ,0,0,0}, - {18974,16572,18975 ,7015,730,7015 ,0,0,0}, {16576,18976,18975 ,730,730,7015 ,0,0,0}, - {18975,16572,16576 ,7015,730,730 ,0,0,0}, {18976,16571,18977 ,730,730,7015 ,0,0,0}, - {16571,18976,16576 ,730,730,730 ,0,0,0}, {16567,16615,16571 ,730,7015,730 ,0,0,0}, - {18977,16571,16615 ,7015,730,7015 ,0,0,0}, {16614,16596,16612 ,7015,7015,730 ,0,0,0}, - {16567,16566,16614 ,730,730,7015 ,0,0,0}, {16608,16603,16606 ,7015,7015,7015 ,0,0,0}, - {16600,16609,16597 ,7015,7015,730 ,0,0,0}, {16608,16600,16602 ,7015,7015,7015 ,0,0,0}, - {16603,16608,16602 ,7015,7015,7015 ,0,0,0}, {16612,16597,16609 ,730,730,7015 ,0,0,0}, - {16609,16600,16608 ,7015,7015,7015 ,0,0,0}, {16614,16566,16596 ,7015,730,7015 ,0,0,0}, - {16612,16596,16597 ,730,7015,730 ,0,0,0}, {16614,16615,16567 ,7015,7015,730 ,0,0,0}, - {16543,18274,18979 ,126,7203,7204 ,0,0,0}, {18980,18981,18276 ,7205,7206,7207 ,0,0,0}, - {18326,18982,18394 ,7208,7209,7210 ,0,0,0}, {18415,18417,18983 ,7211,7212,7213 ,0,0,0}, - {18984,18287,18985 ,7214,7215,7216 ,0,0,0}, {18986,18987,18312 ,7217,7218,7219 ,0,0,0}, - {18337,18988,18455 ,7220,7221,7222 ,0,0,0}, {18306,18989,18990 ,7223,7224,7225 ,0,0,0}, - {18304,18305,18991 ,7226,7227,7228 ,0,0,0}, {18302,18296,18992 ,7229,7230,7231 ,0,0,0}, - {18993,18303,18302 ,7232,7233,7229 ,0,0,0}, {18294,18295,18994 ,7234,7235,7236 ,0,0,0}, - {18995,18296,18294 ,7237,7230,7234 ,0,0,0}, {18293,18996,18295 ,7238,7239,7235 ,0,0,0}, - {18994,18295,18996 ,7236,7235,7239 ,0,0,0}, {18997,18293,18286 ,7240,7238,7241 ,0,0,0}, - {18293,18997,18996 ,7238,7240,7239 ,0,0,0}, {18286,18285,18998 ,7241,7242,7243 ,0,0,0}, - {18998,18997,18286 ,7243,7240,7241 ,0,0,0}, {18282,18999,18285 ,7244,7245,7242 ,0,0,0}, - {18998,18285,18999 ,7243,7242,7245 ,0,0,0}, {19000,18282,16565 ,7246,7244,82 ,0,0,0}, - {18282,19000,18999 ,7244,7246,7245 ,0,0,0}, {16563,19000,16565 ,7011,7246,82 ,0,0,0}, - {18303,18993,18989 ,7233,7232,7224 ,0,0,0}, {18992,18296,18995 ,7231,7230,7237 ,0,0,0}, - {18995,18294,18994 ,7237,7234,7236 ,0,0,0}, {18992,18993,18302 ,7231,7232,7229 ,0,0,0}, - {18990,18305,18306 ,7225,7227,7223 ,0,0,0}, {18989,18306,18303 ,7224,7223,7233 ,0,0,0}, - {18305,18990,18991 ,7227,7225,7228 ,0,0,0}, {18986,18304,18991 ,7217,7226,7228 ,0,0,0}, - {19001,18983,18417 ,7247,7213,7212 ,0,0,0}, {18337,18312,18987 ,7220,7219,7218 ,0,0,0}, - {18304,18986,18312 ,7226,7217,7219 ,0,0,0}, {18455,19001,18417 ,7222,7247,7212 ,0,0,0}, - {18455,18988,19001 ,7222,7221,7247 ,0,0,0}, {18987,18988,18337 ,7218,7221,7220 ,0,0,0}, - {18276,18981,18326 ,7207,7206,7208 ,0,0,0}, {18983,18985,18415 ,7213,7216,7211 ,0,0,0}, - {18984,18289,18287 ,7214,7248,7215 ,0,0,0}, {18287,18415,18985 ,7215,7211,7216 ,0,0,0}, - {18289,18980,18276 ,7248,7205,7207 ,0,0,0}, {18289,18984,18980 ,7248,7214,7205 ,0,0,0}, - {18394,18982,18979 ,7210,7209,7204 ,0,0,0}, {18981,18982,18326 ,7206,7209,7208 ,0,0,0}, - {16543,16540,18274 ,126,4726,7203 ,0,0,0}, {18979,18274,18394 ,7204,7203,7210 ,0,0,0}, - {18994,18992,18995 ,7249,7250,7251 ,0,0,0}, {16545,18981,16547 ,726,726,7252 ,0,0,0}, - {18997,18992,18996 ,7253,7250,7253 ,0,0,0}, {18992,18994,18996 ,7250,7249,7253 ,0,0,0}, - {18993,18997,18998 ,7254,7253,7249 ,0,0,0}, {18997,18993,18992 ,7253,7254,7250 ,0,0,0}, - {18998,18999,18989 ,7249,7249,7255 ,0,0,0}, {18989,18993,18998 ,7255,7254,7249 ,0,0,0}, - {18999,18990,18989 ,7249,7256,7255 ,0,0,0}, {19000,16563,18990 ,7257,7257,7256 ,0,0,0}, - {19000,18990,18999 ,7257,7256,7249 ,0,0,0}, {18991,16562,18986 ,7258,726,7259 ,0,0,0}, - {18990,16563,18991 ,7256,7257,7258 ,0,0,0}, {19001,18988,16557 ,7260,7254,7257 ,0,0,0}, - {16559,18987,16562 ,7252,7261,726 ,0,0,0}, {16550,18985,16551 ,726,7262,7252 ,0,0,0}, - {16556,16553,18983 ,726,7252,7263 ,0,0,0}, {18982,16545,16544 ,7253,726,726 ,0,0,0}, - {18980,16550,16547 ,726,726,7252 ,0,0,0}, {16543,16520,16519 ,726,726,726 ,0,0,0}, - {16518,18979,16544 ,7264,7253,726 ,0,0,0}, {16524,16536,16537 ,726,7257,726 ,0,0,0}, - {16519,16525,16539 ,726,7264,726 ,0,0,0}, {16531,16533,16527 ,7257,726,7257 ,0,0,0}, - {16533,16536,16527 ,726,7257,7257 ,0,0,0}, {16531,16527,16529 ,7257,7257,7257 ,0,0,0}, - {16537,16525,16524 ,726,7264,726 ,0,0,0}, {16536,16524,16527 ,7257,726,7257 ,0,0,0}, - {16541,16519,16539 ,726,726,726 ,0,0,0}, {16539,16525,16537 ,726,7264,726 ,0,0,0}, - {16520,16543,18979 ,726,726,7253 ,0,0,0}, {16519,16541,16543 ,726,726,726 ,0,0,0}, - {16544,18979,18982 ,726,7253,7253 ,0,0,0}, {16520,18979,16518 ,726,7253,7264 ,0,0,0}, - {16547,18981,18980 ,7252,726,726 ,0,0,0}, {18981,16545,18982 ,726,726,7253 ,0,0,0}, - {18985,16550,18984 ,7262,726,7262 ,0,0,0}, {18984,16550,18980 ,7262,726,726 ,0,0,0}, - {16553,16551,18983 ,7252,7252,7263 ,0,0,0}, {16551,18985,18983 ,7252,7262,7263 ,0,0,0}, - {18983,19001,16556 ,7263,7260,726 ,0,0,0}, {16559,16557,18988 ,7252,7257,7254 ,0,0,0}, - {16557,16556,19001 ,7257,726,7260 ,0,0,0}, {16562,18987,18986 ,726,7261,7259 ,0,0,0}, - {16559,18988,18987 ,7252,7254,7261 ,0,0,0}, {16562,18991,16563 ,726,7258,7257 ,0,0,0}, - {16493,19002,18268 ,4799,7265,7266 ,0,0,0}, {19003,18270,19004 ,7267,7268,7269 ,0,0,0}, - {18269,18444,19005 ,7270,7271,7272 ,0,0,0}, {18451,19006,18278 ,7273,7274,7275 ,0,0,0}, - {19007,19008,18450 ,7276,7277,7278 ,0,0,0}, {19009,18448,19010 ,7279,7280,7281 ,0,0,0}, - {18468,18420,19011 ,7282,7283,7284 ,0,0,0}, {18469,19012,19013 ,7285,7286,7287 ,0,0,0}, - {18323,19014,18324 ,7288,7289,7290 ,0,0,0}, {18470,19015,18321 ,7291,7292,7293 ,0,0,0}, - {19016,18470,18279 ,7294,7291,7295 ,0,0,0}, {18320,19017,18471 ,7296,7297,7298 ,0,0,0}, - {19018,18320,18321 ,7299,7296,7293 ,0,0,0}, {18472,18471,19019 ,7300,7298,7301 ,0,0,0}, - {19017,19019,18471 ,7297,7301,7298 ,0,0,0}, {19020,18421,18472 ,7302,7303,7300 ,0,0,0}, - {18472,19019,19020 ,7300,7301,7302 ,0,0,0}, {18421,19021,18474 ,7303,7304,7305 ,0,0,0}, - {19021,18421,19020 ,7304,7303,7302 ,0,0,0}, {18473,18474,19022 ,7306,7305,7307 ,0,0,0}, - {19021,19022,18474 ,7304,7307,7305 ,0,0,0}, {19023,16515,18473 ,7308,21,7306 ,0,0,0}, - {18473,19022,19023 ,7306,7307,7308 ,0,0,0}, {16514,16515,19023 ,7309,21,7308 ,0,0,0}, - {18279,19013,19016 ,7295,7287,7294 ,0,0,0}, {19015,19018,18321 ,7292,7299,7293 ,0,0,0}, - {19018,19017,18320 ,7299,7297,7296 ,0,0,0}, {19015,18470,19016 ,7292,7291,7294 ,0,0,0}, - {19012,18469,18324 ,7286,7285,7290 ,0,0,0}, {19013,18279,18469 ,7287,7295,7285 ,0,0,0}, - {18324,19014,19012 ,7290,7289,7286 ,0,0,0}, {19009,19014,18323 ,7279,7289,7288 ,0,0,0}, - {19024,18278,19006 ,7310,7275,7274 ,0,0,0}, {18468,19010,18448 ,7282,7281,7280 ,0,0,0}, - {18323,18448,19009 ,7288,7280,7279 ,0,0,0}, {18420,18278,19024 ,7283,7275,7310 ,0,0,0}, - {18420,19024,19011 ,7283,7310,7284 ,0,0,0}, {19010,18468,19011 ,7281,7282,7284 ,0,0,0}, - {18270,18269,19004 ,7268,7270,7269 ,0,0,0}, {19006,18451,19008 ,7274,7273,7277 ,0,0,0}, - {19007,18450,18449 ,7276,7278,7311 ,0,0,0}, {18450,19008,18451 ,7278,7277,7273 ,0,0,0}, - {18449,18270,19003 ,7311,7268,7267 ,0,0,0}, {18449,19003,19007 ,7311,7267,7276 ,0,0,0}, - {18444,19002,19005 ,7271,7265,7272 ,0,0,0}, {19004,18269,19005 ,7269,7270,7272 ,0,0,0}, - {16493,18268,16490 ,4799,7266,7199 ,0,0,0}, {19002,18444,18268 ,7265,7271,7266 ,0,0,0}, - {19015,16485,16482 ,730,7312,6103 ,0,0,0}, {16478,19019,16481 ,7313,730,730 ,0,0,0}, - {16488,19012,16492 ,7314,7015,7315 ,0,0,0}, {19016,19013,16487 ,730,730,7316 ,0,0,0}, - {19011,19005,19010 ,730,7317,7313 ,0,0,0}, {19014,19002,16493 ,730,7318,7319 ,0,0,0}, - {19003,19004,19024 ,7320,7316,7316 ,0,0,0}, {19006,19008,19003 ,7320,6103,7320 ,0,0,0}, - {19007,19003,19008 ,6111,7320,6103 ,0,0,0}, {19011,19024,19004 ,730,7316,7316 ,0,0,0}, - {19024,19006,19003 ,7316,7320,7320 ,0,0,0}, {19002,19010,19005 ,7318,7313,7317 ,0,0,0}, - {19005,19011,19004 ,7317,730,7316 ,0,0,0}, {19014,19009,19002 ,730,7316,7318 ,0,0,0}, - {19002,19009,19010 ,7318,7316,7313 ,0,0,0}, {16492,19012,16493 ,7315,7015,7319 ,0,0,0}, - {16493,19012,19014 ,7319,7015,730 ,0,0,0}, {16487,19013,16488 ,7316,730,7314 ,0,0,0}, - {16488,19013,19012 ,7314,730,7015 ,0,0,0}, {19016,16487,16485 ,730,7316,7312 ,0,0,0}, - {16482,19018,19015 ,6103,7017,730 ,0,0,0}, {16485,19015,19016 ,7312,730,730 ,0,0,0}, - {19018,16482,19017 ,7017,6103,7017 ,0,0,0}, {16481,19019,19017 ,730,730,7017 ,0,0,0}, - {19017,16482,16481 ,7017,6103,730 ,0,0,0}, {19019,16478,16477 ,730,7313,730 ,0,0,0}, - {16477,16473,19020 ,730,7316,730 ,0,0,0}, {19020,19019,16477 ,730,730,730 ,0,0,0}, - {19021,16473,16475 ,7016,7316,7313 ,0,0,0}, {16473,19021,19020 ,7316,7016,730 ,0,0,0}, - {16469,19022,16475 ,7015,730,7313 ,0,0,0}, {19021,16475,19022 ,7016,7313,730 ,0,0,0}, - {19023,16469,16514 ,730,7015,730 ,0,0,0}, {19023,19022,16469 ,730,730,7015 ,0,0,0}, - {16469,16471,16514 ,7015,7015,730 ,0,0,0}, {16512,16494,16509 ,730,730,730 ,0,0,0}, - {16471,16467,16512 ,7015,730,730 ,0,0,0}, {16506,16502,16503 ,730,730,7017 ,0,0,0}, - {16497,16508,16496 ,7015,7016,730 ,0,0,0}, {16506,16497,16500 ,730,7015,730 ,0,0,0}, - {16502,16506,16500 ,730,730,730 ,0,0,0}, {16509,16496,16508 ,730,730,7016 ,0,0,0}, - {16508,16497,16506 ,7016,7015,730 ,0,0,0}, {16512,16467,16494 ,730,730,730 ,0,0,0}, - {16509,16494,16496 ,730,730,730 ,0,0,0}, {16512,16514,16471 ,730,730,7015 ,0,0,0}, - {17025,19025,19026 ,7321,1711,7322 ,0,0,0}, {17015,17012,19027 ,7323,7324,7325 ,0,0,0}, - {19028,17014,17023 ,7326,7327,7328 ,0,0,0}, {18841,19029,18840 ,7329,7330,7331 ,0,0,0}, - {19030,19031,17019 ,7332,7333,7334 ,0,0,0}, {18838,19032,18837 ,7335,7336,7337 ,0,0,0}, - {19032,18839,19033 ,7336,7338,7339 ,0,0,0}, {18836,18837,19034 ,7340,7337,7341 ,0,0,0}, - {19032,19034,18837 ,7336,7341,7337 ,0,0,0}, {19035,18835,18836 ,1359,1359,7340 ,0,0,0}, - {18836,19034,19035 ,7340,7341,1359 ,0,0,0}, {19033,18839,18840 ,7339,7338,7331 ,0,0,0}, - {19032,18838,18839 ,7336,7335,7338 ,0,0,0}, {19029,18841,18842 ,7330,7329,7342 ,0,0,0}, - {19029,19033,18840 ,7330,7339,7331 ,0,0,0}, {18842,17019,19031 ,7342,7334,7333 ,0,0,0}, - {19031,19029,18842 ,7333,7330,7342 ,0,0,0}, {17018,19027,19030 ,7343,7325,7332 ,0,0,0}, - {17018,19030,17019 ,7343,7332,7334 ,0,0,0}, {17012,19036,19027 ,7324,7344,7325 ,0,0,0}, - {17018,17015,19027 ,7343,7323,7325 ,0,0,0}, {19028,19036,17014 ,7326,7344,7327 ,0,0,0}, - {17012,17014,19036 ,7324,7327,7344 ,0,0,0}, {19028,17022,19026 ,7326,7345,7322 ,0,0,0}, - {17023,17022,19028 ,7328,7345,7326 ,0,0,0}, {19025,17025,16991 ,1711,7321,1711 ,0,0,0}, - {19026,17022,17025 ,7322,7345,7321 ,0,0,0}, {19025,16993,19037 ,2197,7346,7346 ,0,0,0}, - {16993,19025,16991 ,7346,2197,2197 ,0,0,0}, {19038,19039,18845 ,1435,7347,7348 ,0,0,0}, - {18846,18844,19040 ,7349,7350,7351 ,0,0,0}, {18843,18848,19041 ,7352,7353,7354 ,0,0,0}, - {17004,19042,17002 ,7355,7356,7357 ,0,0,0}, {19043,19044,17010 ,7358,7359,7360 ,0,0,0}, - {16998,19045,16996 ,7361,7362,7363 ,0,0,0}, {16998,17000,19045 ,7361,7364,7362 ,0,0,0}, - {16995,16996,19046 ,7365,7363,7366 ,0,0,0}, {19045,19046,16996 ,7362,7366,7363 ,0,0,0}, - {19037,16993,16995 ,1790,1790,7365 ,0,0,0}, {16995,19046,19037 ,7365,7366,1790 ,0,0,0}, - {17002,19047,17000 ,7357,7367,7364 ,0,0,0}, {19045,17000,19047 ,7362,7364,7367 ,0,0,0}, - {18843,19048,18844 ,7352,7368,7350 ,0,0,0}, {17004,17008,19042 ,7355,7369,7356 ,0,0,0}, - {19042,19047,17002 ,7356,7367,7357 ,0,0,0}, {17008,17010,19044 ,7369,7360,7359 ,0,0,0}, - {19044,19042,17008 ,7359,7356,7369 ,0,0,0}, {19043,17010,18847 ,7358,7360,7370 ,0,0,0}, - {19040,18847,18846 ,7351,7370,7349 ,0,0,0}, {18847,19040,19043 ,7370,7351,7358 ,0,0,0}, - {19048,19040,18844 ,7368,7351,7350 ,0,0,0}, {19041,18849,19039 ,7354,7371,7347 ,0,0,0}, - {18849,19041,18848 ,7371,7354,7353 ,0,0,0}, {19048,18843,19041 ,7368,7352,7354 ,0,0,0}, - {19038,18845,18834 ,1435,7348,1435 ,0,0,0}, {19039,18849,18845 ,7347,7371,7348 ,0,0,0}, - {18834,19035,19038 ,1398,7372,1398 ,0,0,0}, {19035,18834,18835 ,7372,1398,7372 ,0,0,0}, - {19035,19039,19038 ,7373,730,730 ,0,0,0}, {19036,19045,19047 ,730,730,730 ,0,0,0}, - {19033,19040,19048 ,7374,7375,7375 ,0,0,0}, {19048,19041,19032 ,7375,730,7373 ,0,0,0}, - {19031,19044,19043 ,7375,7375,7375 ,0,0,0}, {19043,19040,19029 ,7375,7375,730 ,0,0,0}, - {19047,19042,19027 ,730,730,7376 ,0,0,0}, {19042,19044,19030 ,730,7375,7375 ,0,0,0}, - {19026,19046,19028 ,730,730,730 ,0,0,0}, {19045,19028,19046 ,730,730,730 ,0,0,0}, - {19026,19025,19037 ,730,730,730 ,0,0,0}, {19037,19046,19026 ,730,730,730 ,0,0,0}, - {19047,19027,19036 ,730,7376,730 ,0,0,0}, {19045,19036,19028 ,730,730,730 ,0,0,0}, - {19042,19030,19027 ,730,7375,7376 ,0,0,0}, {19044,19031,19030 ,7375,7375,7375 ,0,0,0}, - {19043,19029,19031 ,7375,730,7375 ,0,0,0}, {19040,19033,19029 ,7375,7374,730 ,0,0,0}, - {19048,19032,19033 ,7375,7373,7374 ,0,0,0}, {19041,19034,19032 ,730,730,7373 ,0,0,0}, - {19035,19034,19039 ,7373,730,730 ,0,0,0}, {19041,19039,19034 ,730,730,730 ,0,0,0}, - {19049,16923,19050 ,7377,1435,1435 ,0,0,0}, {19051,16939,19052 ,7378,7379,7379 ,0,0,0}, - {19053,16914,16918 ,7380,7380,7377 ,0,0,0}, {16946,19054,19055 ,7381,7381,7382 ,0,0,0}, - {16941,19056,16944 ,7378,7383,7383 ,0,0,0}, {16953,19057,16955 ,7384,7385,7385 ,0,0,0}, - {19058,16953,16948 ,7384,7384,7382 ,0,0,0}, {16958,16955,19059 ,7386,7385,7386 ,0,0,0}, - {19057,19059,16955 ,7385,7386,7385 ,0,0,0}, {19060,16961,16958 ,7387,7388,7386 ,0,0,0}, - {16958,19059,19060 ,7386,7386,7387 ,0,0,0}, {19055,19058,16948 ,7382,7384,7382 ,0,0,0}, - {19058,19057,16953 ,7384,7385,7384 ,0,0,0}, {16944,19054,16946 ,7383,7381,7381 ,0,0,0}, - {16946,19055,16948 ,7381,7382,7382 ,0,0,0}, {16941,19051,19056 ,7378,7378,7383 ,0,0,0}, - {16944,19056,19054 ,7383,7383,7381 ,0,0,0}, {16939,16914,19052 ,7379,7380,7379 ,0,0,0}, - {16941,16939,19051 ,7378,7379,7378 ,0,0,0}, {19053,16918,19049 ,7380,7377,7377 ,0,0,0}, - {19052,16914,19053 ,7379,7380,7380 ,0,0,0}, {16923,19049,16918 ,1435,7377,7377 ,0,0,0}, - {19050,16920,19061 ,1398,1398,1398 ,0,0,0}, {16920,19050,16923 ,1398,1398,1398 ,0,0,0}, - {19062,19063,17045 ,7389,7390,7390 ,0,0,0}, {19064,17041,19065 ,7391,7391,7392 ,0,0,0}, - {17043,16952,19066 ,7392,7393,7393 ,0,0,0}, {17033,19067,19068 ,7394,7395,7394 ,0,0,0}, - {17038,19069,17037 ,7396,7396,7395 ,0,0,0}, {17028,19070,19071 ,7397,7398,7397 ,0,0,0}, - {19070,17028,17032 ,7398,7397,7398 ,0,0,0}, {19072,17026,19071 ,7399,7399,7397 ,0,0,0}, - {17028,19071,17026 ,7397,7397,7399 ,0,0,0}, {19072,19061,16920 ,7399,1359,1359 ,0,0,0}, - {16920,17026,19072 ,1359,7399,7399 ,0,0,0}, {19065,17043,19066 ,7392,7392,7393 ,0,0,0}, - {17032,17033,19068 ,7398,7394,7394 ,0,0,0}, {19068,19070,17032 ,7394,7398,7398 ,0,0,0}, - {19067,17033,17037 ,7395,7394,7395 ,0,0,0}, {19064,19069,17038 ,7391,7396,7396 ,0,0,0}, - {17037,19069,19067 ,7395,7396,7395 ,0,0,0}, {17043,19065,17041 ,7392,7392,7391 ,0,0,0}, - {17038,17041,19064 ,7396,7391,7391 ,0,0,0}, {17045,19063,16952 ,7390,7390,7393 ,0,0,0}, - {16952,19063,19066 ,7393,7390,7393 ,0,0,0}, {19062,17045,16911 ,7389,7390,7400 ,0,0,0}, - {19060,19062,16911 ,7401,7402,7402 ,0,0,0}, {19060,16911,16961 ,7401,7402,7401 ,0,0,0}, - {19072,19053,19049 ,7403,7403,7404 ,0,0,0}, {19058,19066,19057 ,7375,7375,730 ,0,0,0}, - {19054,19064,19055 ,7375,730,730 ,0,0,0}, {19065,19058,19055 ,730,7375,730 ,0,0,0}, - {19051,19067,19056 ,7373,7375,7373 ,0,0,0}, {19069,19054,19056 ,730,7375,7373 ,0,0,0}, - {19052,19071,19070 ,7405,7406,730 ,0,0,0}, {19068,19051,19052 ,7373,7373,7405 ,0,0,0}, - {19072,19071,19053 ,7403,7406,7403 ,0,0,0}, {19049,19050,19061 ,7404,730,7407 ,0,0,0}, - {19061,19072,19049 ,7407,7403,7404 ,0,0,0}, {19071,19052,19053 ,7406,7405,7403 ,0,0,0}, - {19068,19052,19070 ,7373,7405,730 ,0,0,0}, {19067,19051,19068 ,7375,7373,7373 ,0,0,0}, - {19069,19056,19067 ,730,7373,7375 ,0,0,0}, {19064,19054,19069 ,730,7375,730 ,0,0,0}, - {19065,19055,19064 ,730,730,730 ,0,0,0}, {19066,19058,19065 ,7375,7375,730 ,0,0,0}, - {19063,19057,19066 ,730,730,7375 ,0,0,0}, {19059,19063,19062 ,7373,730,730 ,0,0,0}, - {19063,19059,19057 ,730,7373,730 ,0,0,0}, {19059,19062,19060 ,7373,730,7405 ,0,0,0}, - {19073,18832,19074 ,7408,7409,7410 ,0,0,0}, {19075,18830,19076 ,7411,7412,7412 ,0,0,0}, - {19077,18829,18833 ,7413,7413,7408 ,0,0,0}, {18850,19078,19079 ,7414,7414,7415 ,0,0,0}, - {18831,19080,18851 ,7411,7416,7416 ,0,0,0}, {18827,19081,18828 ,7417,7418,7418 ,0,0,0}, - {19082,18827,18826 ,7417,7417,7415 ,0,0,0}, {18824,18828,19083 ,7419,7418,7419 ,0,0,0}, - {19081,19083,18828 ,7418,7419,7418 ,0,0,0}, {19084,18823,18824 ,1790,1790,7419 ,0,0,0}, - {18824,19083,19084 ,7419,7419,1790 ,0,0,0}, {19079,19082,18826 ,7415,7417,7415 ,0,0,0}, - {19082,19081,18827 ,7417,7418,7417 ,0,0,0}, {18851,19078,18850 ,7416,7414,7414 ,0,0,0}, - {18850,19079,18826 ,7414,7415,7415 ,0,0,0}, {18831,19075,19080 ,7411,7411,7416 ,0,0,0}, - {18851,19080,19078 ,7416,7416,7414 ,0,0,0}, {18830,18829,19076 ,7412,7413,7412 ,0,0,0}, - {18831,18830,19075 ,7411,7412,7411 ,0,0,0}, {19077,18833,19073 ,7413,7408,7408 ,0,0,0}, - {19076,18829,19077 ,7412,7413,7413 ,0,0,0}, {18832,19073,18833 ,7409,7408,7408 ,0,0,0}, - {18853,19085,19074 ,7420,7420,7421 ,0,0,0}, {18853,19074,18832 ,7420,7421,7421 ,0,0,0}, - {19086,19087,18862 ,1711,7422,7422 ,0,0,0}, {19088,18860,19089 ,7423,7423,7424 ,0,0,0}, - {18861,18852,19090 ,7424,7425,7425 ,0,0,0}, {18857,19091,19092 ,7426,7427,7426 ,0,0,0}, - {18859,19093,18858 ,7428,7428,7427 ,0,0,0}, {18855,19094,19095 ,7429,7430,7429 ,0,0,0}, - {19094,18855,18856 ,7430,7429,7430 ,0,0,0}, {19096,18854,19095 ,7431,7431,7429 ,0,0,0}, - {18855,19095,18854 ,7429,7429,7431 ,0,0,0}, {19096,19085,18853 ,7431,7432,82 ,0,0,0}, - {18853,18854,19096 ,82,7431,7431 ,0,0,0}, {19089,18861,19090 ,7424,7424,7425 ,0,0,0}, - {18856,18857,19092 ,7430,7426,7426 ,0,0,0}, {19092,19094,18856 ,7426,7430,7430 ,0,0,0}, - {19091,18857,18858 ,7427,7426,7427 ,0,0,0}, {19088,19093,18859 ,7423,7428,7428 ,0,0,0}, - {18858,19093,19091 ,7427,7428,7427 ,0,0,0}, {18861,19089,18860 ,7424,7424,7423 ,0,0,0}, - {18859,18860,19088 ,7428,7423,7423 ,0,0,0}, {18862,19087,18852 ,7422,7422,7425 ,0,0,0}, - {18852,19087,19090 ,7425,7422,7425 ,0,0,0}, {19086,18862,18825 ,1711,7422,1711 ,0,0,0}, - {18825,19084,19086 ,2197,2197,2197 ,0,0,0}, {19084,18825,18823 ,2197,2197,2197 ,0,0,0}, - {19084,19087,19086 ,7433,730,730 ,0,0,0}, {19075,19076,19092 ,7375,7375,730 ,0,0,0}, - {19079,19089,19082 ,730,730,730 ,0,0,0}, {19089,19090,19081 ,730,7376,730 ,0,0,0}, - {19080,19093,19078 ,730,730,7376 ,0,0,0}, {19088,19079,19078 ,730,730,7376 ,0,0,0}, - {19091,19080,19075 ,7376,730,7375 ,0,0,0}, {19095,19077,19073 ,7375,7376,7376 ,0,0,0}, - {19076,19077,19094 ,7375,7376,7375 ,0,0,0}, {19074,19096,19073 ,7374,7376,7376 ,0,0,0}, - {19095,19073,19096 ,7375,7376,7376 ,0,0,0}, {19085,19096,19074 ,730,7376,7374 ,0,0,0}, - {19094,19077,19095 ,7375,7376,7375 ,0,0,0}, {19092,19076,19094 ,730,7375,7375 ,0,0,0}, - {19091,19075,19092 ,7376,7375,730 ,0,0,0}, {19093,19080,19091 ,730,730,7376 ,0,0,0}, - {19088,19078,19093 ,730,7376,730 ,0,0,0}, {19089,19079,19088 ,730,730,730 ,0,0,0}, - {19089,19081,19082 ,730,730,730 ,0,0,0}, {19090,19083,19081 ,7376,7433,730 ,0,0,0}, - {19084,19083,19087 ,7433,7433,730 ,0,0,0}, {19090,19087,19083 ,7376,730,7433 ,0,0,0}, - {18260,16433,16431 ,7434,4326,7435 ,0,0,0}, {18432,18360,18257 ,7436,7437,7438 ,0,0,0}, - {18261,18359,18262 ,7439,7440,7441 ,0,0,0}, {18267,18255,18403 ,7442,7443,7444 ,0,0,0}, - {18265,18408,18466 ,7445,7446,7447 ,0,0,0}, {18411,18410,18245 ,7448,7449,7450 ,0,0,0}, - {18395,18263,18264 ,7451,7452,7453 ,0,0,0}, {18239,18238,18310 ,7454,7455,7456 ,0,0,0}, - {18241,18299,18301 ,7457,7458,7459 ,0,0,0}, {18229,18346,18233 ,7460,7461,7462 ,0,0,0}, - {18352,18311,18237 ,7463,7464,7465 ,0,0,0}, {18344,18271,18223 ,7466,7467,7468 ,0,0,0}, - {18347,18225,18271 ,7469,7470,7467 ,0,0,0}, {18416,18220,18227 ,7471,7472,7473 ,0,0,0}, - {18224,18220,18345 ,7474,7472,7475 ,0,0,0}, {18339,18228,18232 ,7476,7477,7478 ,0,0,0}, - {18227,18228,18338 ,7473,7477,7479 ,0,0,0}, {18235,18322,18232 ,7480,7481,7478 ,0,0,0}, - {18339,18232,18322 ,7476,7478,7481 ,0,0,0}, {18235,18244,18314 ,7480,7482,7483 ,0,0,0}, - {18314,18322,18235 ,7483,7481,7480 ,0,0,0}, {18288,18244,18243 ,7484,7482,7485 ,0,0,0}, - {18244,18288,18314 ,7482,7484,7483 ,0,0,0}, {18247,18277,18243 ,7486,7487,7485 ,0,0,0}, - {18288,18243,18277 ,7484,7485,7487 ,0,0,0}, {18247,18252,18275 ,7486,7488,7489 ,0,0,0}, - {18275,18277,18247 ,7489,7487,7486 ,0,0,0}, {18325,18252,18251 ,7490,7488,7491 ,0,0,0}, - {18252,18325,18275 ,7488,7490,7489 ,0,0,0}, {16465,18273,18251 ,82,7492,7491 ,0,0,0}, - {18325,18251,18273 ,7490,7491,7492 ,0,0,0}, {16464,18273,16465 ,82,7492,82 ,0,0,0}, - {18338,18416,18227 ,7479,7471,7473 ,0,0,0}, {18338,18228,18339 ,7479,7477,7476 ,0,0,0}, - {18224,18345,18344 ,7474,7475,7466 ,0,0,0}, {18345,18220,18416 ,7475,7472,7471 ,0,0,0}, - {18271,18225,18223 ,7467,7470,7468 ,0,0,0}, {18344,18223,18224 ,7466,7468,7474 ,0,0,0}, - {18347,18346,18229 ,7469,7461,7460 ,0,0,0}, {18347,18229,18225 ,7469,7460,7470 ,0,0,0}, - {18233,18352,18237 ,7462,7463,7465 ,0,0,0}, {18346,18352,18233 ,7461,7463,7462 ,0,0,0}, - {18238,18311,18310 ,7455,7464,7456 ,0,0,0}, {18237,18311,18238 ,7465,7464,7455 ,0,0,0}, - {18241,18239,18299 ,7457,7454,7458 ,0,0,0}, {18239,18310,18299 ,7454,7456,7458 ,0,0,0}, - {18411,18246,18301 ,7448,7493,7459 ,0,0,0}, {18246,18241,18301 ,7493,7457,7459 ,0,0,0}, - {18410,18264,18245 ,7449,7453,7450 ,0,0,0}, {18411,18245,18246 ,7448,7450,7493 ,0,0,0}, - {18395,18404,18263 ,7451,7494,7452 ,0,0,0}, {18410,18395,18264 ,7449,7451,7453 ,0,0,0}, - {18403,18255,18404 ,7444,7443,7494 ,0,0,0}, {18263,18404,18255 ,7452,7494,7443 ,0,0,0}, - {18265,18267,18408 ,7445,7442,7446 ,0,0,0}, {18267,18403,18408 ,7442,7444,7446 ,0,0,0}, - {18432,18256,18466 ,7436,7495,7447 ,0,0,0}, {18256,18265,18466 ,7495,7445,7447 ,0,0,0}, - {18360,18261,18257 ,7437,7439,7438 ,0,0,0}, {18432,18257,18256 ,7436,7438,7495 ,0,0,0}, - {18359,18361,18262 ,7440,7496,7441 ,0,0,0}, {18360,18359,18261 ,7437,7440,7439 ,0,0,0}, - {16433,18260,18361 ,4326,7434,7496 ,0,0,0}, {18262,18361,18260 ,7441,7496,7434 ,0,0,0}, - {19097,16381,16380 ,7497,763,7498 ,0,0,0}, {19098,18253,19099 ,7499,7500,7501 ,0,0,0}, - {19100,18266,18258 ,7502,7503,7504 ,0,0,0}, {19101,19102,18242 ,7505,7506,7507 ,0,0,0}, - {19103,19104,18250 ,7508,7509,7510 ,0,0,0}, {19105,18230,19106 ,7511,7512,7513 ,0,0,0}, - {18234,19107,19106 ,7514,7515,7513 ,0,0,0}, {19108,18222,19109 ,7516,7517,7518 ,0,0,0}, - {18221,19105,19109 ,7519,7511,7518 ,0,0,0}, {19110,18236,18231 ,7520,7521,7522 ,0,0,0}, - {18231,19108,19110 ,7522,7516,7520 ,0,0,0}, {18236,19111,18248 ,7521,7523,7524 ,0,0,0}, - {19111,18236,19110 ,7523,7521,7520 ,0,0,0}, {18249,18248,19112 ,7525,7524,7526 ,0,0,0}, - {19111,19112,18248 ,7523,7526,7524 ,0,0,0}, {16399,18249,19113 ,761,7525,7527 ,0,0,0}, - {18249,19112,19113 ,7525,7526,7527 ,0,0,0}, {16398,18249,16399 ,761,7525,761 ,0,0,0}, - {18221,19109,18222 ,7519,7518,7517 ,0,0,0}, {18231,18222,19108 ,7522,7517,7516 ,0,0,0}, - {18226,18230,19105 ,7528,7512,7511 ,0,0,0}, {18221,18226,19105 ,7519,7528,7511 ,0,0,0}, - {18240,19107,18234 ,7529,7515,7514 ,0,0,0}, {18230,18234,19106 ,7512,7514,7513 ,0,0,0}, - {18242,19102,18240 ,7507,7506,7529 ,0,0,0}, {19107,18240,19102 ,7515,7529,7506 ,0,0,0}, - {18250,19104,18242 ,7510,7509,7507 ,0,0,0}, {19104,19101,18242 ,7509,7505,7507 ,0,0,0}, - {18254,19098,19103 ,7530,7499,7508 ,0,0,0}, {18254,19103,18250 ,7530,7508,7510 ,0,0,0}, - {18253,18266,19099 ,7500,7503,7501 ,0,0,0}, {18254,18253,19098 ,7530,7500,7499 ,0,0,0}, - {19100,18258,19097 ,7502,7504,7497 ,0,0,0}, {19099,18266,19100 ,7501,7503,7502 ,0,0,0}, - {16381,19097,18259 ,763,7497,7531 ,0,0,0}, {19097,18258,18259 ,7497,7504,7531 ,0,0,0}, - {19112,19111,19110 ,7015,7532,7017 ,0,0,0}, {16385,19099,19100 ,7016,7015,7015 ,0,0,0}, - {19105,19108,19109 ,7533,7534,7535 ,0,0,0}, {19110,19105,19112 ,7017,7533,7015 ,0,0,0}, - {19112,19105,19113 ,7015,7533,7016 ,0,0,0}, {19105,19110,19108 ,7533,7017,7534 ,0,0,0}, - {19106,19113,19105 ,7536,7016,7533 ,0,0,0}, {19113,19107,16399 ,7016,730,7015 ,0,0,0}, - {19107,19113,19106 ,730,7016,7536 ,0,0,0}, {19104,16394,19101 ,7535,730,7320 ,0,0,0}, - {19107,19102,16399 ,730,6104,7015 ,0,0,0}, {19098,16388,19103 ,730,730,7534 ,0,0,0}, - {16391,19104,19103 ,7537,7535,7534 ,0,0,0}, {19097,16380,16384 ,7016,7015,730 ,0,0,0}, - {19100,16386,16385 ,7015,730,7016 ,0,0,0}, {16377,16365,16379 ,730,730,730 ,0,0,0}, - {16379,16363,16380 ,730,7016,7015 ,0,0,0}, {16376,16373,16377 ,730,730,730 ,0,0,0}, - {16365,16371,16370 ,730,7016,7016 ,0,0,0}, {16373,16365,16377 ,730,730,730 ,0,0,0}, - {16365,16364,16379 ,730,730,730 ,0,0,0}, {16365,16373,16371 ,730,730,7016 ,0,0,0}, - {16363,16384,16380 ,7016,730,7015 ,0,0,0}, {16364,16363,16379 ,730,7016,730 ,0,0,0}, - {16386,19100,16384 ,730,7015,730 ,0,0,0}, {16384,19100,19097 ,730,7015,7016 ,0,0,0}, - {16385,16388,19099 ,7016,730,7015 ,0,0,0}, {19103,16388,16390 ,7534,730,7537 ,0,0,0}, - {19099,16388,19098 ,7015,730,730 ,0,0,0}, {19103,16390,16391 ,7534,7537,7537 ,0,0,0}, - {16394,19102,19101 ,730,6104,7320 ,0,0,0}, {19104,16391,16394 ,7535,7537,730 ,0,0,0}, - {16399,19102,16396 ,7015,6104,730 ,0,0,0}, {16394,16396,19102 ,730,730,6104 ,0,0,0}, - {17308,17307,19114 ,7538,7539,7540 ,0,0,0}, {19115,17299,17308 ,7541,7542,7538 ,0,0,0}, - {19115,19116,17299 ,7541,82,7542 ,0,0,0}, {19114,19115,17308 ,7540,7541,7538 ,0,0,0}, - {17307,17678,19117 ,7539,7543,7544 ,0,0,0}, {17337,17336,19118 ,7545,7546,7547 ,0,0,0}, - {19119,19117,17678 ,7548,7544,7543 ,0,0,0}, {17678,17337,19119 ,7543,7545,7548 ,0,0,0}, - {19118,19119,17337 ,7547,7548,7545 ,0,0,0}, {17307,19117,19114 ,7539,7544,7540 ,0,0,0}, - {19118,17336,19120 ,7547,7546,7549 ,0,0,0}, {17335,19121,19120 ,7550,7551,7549 ,0,0,0}, - {19120,17336,17335 ,7549,7546,7550 ,0,0,0}, {19121,17335,17310 ,7551,7550,7552 ,0,0,0}, - {17323,19122,17310 ,7553,7554,7552 ,0,0,0}, {17323,17313,19123 ,7553,7555,7556 ,0,0,0}, - {17323,19123,19122 ,7553,7556,7554 ,0,0,0}, {19124,17304,19125 ,7557,7558,7559 ,0,0,0}, - {19123,17313,19124 ,7556,7555,7557 ,0,0,0}, {19124,17313,17304 ,7557,7555,7558 ,0,0,0}, - {17304,17306,19125 ,7558,7559,7559 ,0,0,0}, {19121,17310,19122 ,7551,7552,7554 ,0,0,0}, - {17300,19116,19126 ,7560,82,7561 ,0,0,0}, {19116,17300,17299 ,82,7560,7542 ,0,0,0}, - {19127,17342,19126 ,7562,7563,7561 ,0,0,0}, {17300,19126,17342 ,7560,7561,7563 ,0,0,0}, - {19127,19128,17556 ,7562,7564,7565 ,0,0,0}, {17556,17342,19127 ,7565,7563,7562 ,0,0,0}, - {17381,19128,19129 ,7566,7564,7567 ,0,0,0}, {19128,17381,17556 ,7564,7566,7565 ,0,0,0}, - {19130,17382,19129 ,7568,7569,7567 ,0,0,0}, {17381,19129,17382 ,7566,7567,7569 ,0,0,0}, - {19130,19131,17378 ,7568,7570,7571 ,0,0,0}, {17378,17382,19130 ,7571,7569,7568 ,0,0,0}, - {17346,19131,19132 ,7572,7570,7573 ,0,0,0}, {19131,17346,17378 ,7570,7572,7571 ,0,0,0}, - {19133,17365,19132 ,7574,7575,7573 ,0,0,0}, {17346,19132,17365 ,7572,7573,7575 ,0,0,0}, - {19133,19134,17366 ,7574,7576,7577 ,0,0,0}, {17366,17365,19133 ,7577,7575,7574 ,0,0,0}, - {17368,19134,19135 ,7578,7576,7579 ,0,0,0}, {19134,17368,17366 ,7576,7578,7577 ,0,0,0}, - {17368,19135,17369 ,7578,7579,7580 ,0,0,0}, {17369,19135,19136 ,7580,7579,7580 ,0,0,0}, - {18194,18200,19136 ,7581,7581,7581 ,0,0,0}, {19136,16806,18185 ,7581,7581,7581 ,0,0,0}, - {18185,18191,19136 ,7581,7581,7581 ,0,0,0}, {18205,19136,18200 ,7581,7581,7581 ,0,0,0}, - {18191,18194,19136 ,7581,7581,7581 ,0,0,0}, {18209,18168,19136 ,7581,7581,7581 ,0,0,0}, - {18209,19136,18205 ,7581,7581,7581 ,0,0,0}, {18168,18180,19136 ,7581,7581,7581 ,0,0,0}, - {17369,19136,18179 ,7581,7581,7581 ,0,0,0}, {18180,18179,19136 ,7581,7581,7581 ,0,0,0}, - {19125,17306,17752 ,7582,7582,7582 ,0,0,0}, {17752,17779,19125 ,7582,7582,7582 ,0,0,0}, - {19125,17765,17745 ,7582,7582,7582 ,0,0,0}, {17779,17765,19125 ,7582,7582,7582 ,0,0,0}, - {19125,17747,17761 ,7582,7582,7582 ,0,0,0}, {17745,17747,19125 ,7582,7582,7582 ,0,0,0}, - {19125,17754,17738 ,7582,7582,7582 ,0,0,0}, {17761,17754,19125 ,7582,7582,7582 ,0,0,0}, - {17742,19125,17737 ,7582,7582,7582 ,0,0,0}, {17738,17737,19125 ,7582,7582,7582 ,0,0,0}, - {19133,16811,16809 ,726,726,726 ,0,0,0}, {19126,19116,16811 ,726,726,726 ,0,0,0}, - {19135,19134,16809 ,726,726,726 ,0,0,0}, {16809,19134,19133 ,726,726,726 ,0,0,0}, - {16809,16803,19136 ,726,726,726 ,0,0,0}, {19136,19135,16809 ,726,726,726 ,0,0,0}, - {16812,16806,19136 ,7583,7583,726 ,0,0,0}, {16812,19136,16803 ,7583,726,726 ,0,0,0}, - {19133,19132,16811 ,726,726,726 ,0,0,0}, {16811,19131,19130 ,726,726,726 ,0,0,0}, - {19132,19131,16811 ,726,726,726 ,0,0,0}, {16811,19129,19128 ,726,726,726 ,0,0,0}, - {19130,19129,16811 ,726,726,726 ,0,0,0}, {16811,19127,19126 ,726,726,726 ,0,0,0}, - {19128,19127,16811 ,726,726,726 ,0,0,0}, {19115,16811,19116 ,726,726,726 ,0,0,0}, - {19114,19117,16811 ,726,726,726 ,0,0,0}, {19114,16811,19115 ,726,726,726 ,0,0,0}, - {19119,19118,16811 ,726,726,726 ,0,0,0}, {19119,16811,19117 ,726,726,726 ,0,0,0}, - {19120,19121,16811 ,726,726,726 ,0,0,0}, {19120,16811,19118 ,726,726,726 ,0,0,0}, - {19122,19123,16811 ,726,726,726 ,0,0,0}, {19122,16811,19121 ,726,726,726 ,0,0,0}, - {16811,19123,18863 ,726,726,726 ,0,0,0}, {19125,18863,19124 ,726,726,726 ,0,0,0}, - {18863,19123,19124 ,726,726,726 ,0,0,0}, {18864,18863,19125 ,726,726,726 ,0,0,0}, - {17742,18876,19125 ,7583,726,726 ,0,0,0}, {18864,19125,18876 ,726,726,726 ,0,0,0}, - {16341,19137,17595 ,7584,7585,7586 ,0,0,0}, {19138,17568,19139 ,7587,7588,7589 ,0,0,0}, - {17606,17528,19140 ,7590,7591,7592 ,0,0,0}, {17295,19141,17557 ,7593,7594,7595 ,0,0,0}, - {19142,19143,17298 ,4334,7596,7597 ,0,0,0}, {19144,17303,19145 ,7598,7599,7600 ,0,0,0}, - {17302,17560,19146 ,7601,7602,7603 ,0,0,0}, {17360,17352,19147 ,7604,7605,7606 ,0,0,0}, - {17356,19148,17352 ,7607,7608,7605 ,0,0,0}, {17357,19149,19150 ,7609,7610,7611 ,0,0,0}, - {17360,19151,17359 ,7604,7612,7613 ,0,0,0}, {19152,17370,19150 ,7614,7615,7611 ,0,0,0}, - {17357,19150,17370 ,7609,7611,7615 ,0,0,0}, {19152,19153,17363 ,7614,7616,7617 ,0,0,0}, - {17363,17370,19152 ,7617,7615,7614 ,0,0,0}, {17372,19153,19154 ,7618,7616,7619 ,0,0,0}, - {19153,17372,17363 ,7616,7618,7617 ,0,0,0}, {19155,17332,19154 ,7620,7621,7619 ,0,0,0}, - {17372,19154,17332 ,7618,7619,7621 ,0,0,0}, {19155,16360,16361 ,7620,7622,4289 ,0,0,0}, - {16361,17332,19155 ,4289,7621,7620 ,0,0,0}, {19147,17352,19148 ,7606,7605,7608 ,0,0,0}, - {19149,17359,19151 ,7610,7613,7612 ,0,0,0}, {17359,19149,17357 ,7613,7610,7609 ,0,0,0}, - {19147,19151,17360 ,7606,7612,7604 ,0,0,0}, {19144,19148,17356 ,7598,7608,7607 ,0,0,0}, - {17302,19146,19145 ,7601,7603,7600 ,0,0,0}, {17302,19145,17303 ,7601,7600,7599 ,0,0,0}, - {17356,17303,19144 ,7607,7599,7598 ,0,0,0}, {17560,19156,19146 ,7602,7623,7603 ,0,0,0}, - {19156,17560,17557 ,7623,7602,7595 ,0,0,0}, {19143,19141,17295 ,7596,7594,7593 ,0,0,0}, - {19141,19156,17557 ,7594,7623,7595 ,0,0,0}, {17298,19143,17295 ,7597,7596,7593 ,0,0,0}, - {17596,19138,19142 ,7624,7587,4334 ,0,0,0}, {17596,19142,17298 ,7624,4334,7597 ,0,0,0}, - {17568,17606,19139 ,7588,7590,7589 ,0,0,0}, {17596,17568,19138 ,7624,7588,7587 ,0,0,0}, - {17528,19137,19140 ,7591,7585,7592 ,0,0,0}, {19139,17606,19140 ,7589,7590,7592 ,0,0,0}, - {16341,17595,16339 ,7584,7586,4535 ,0,0,0}, {19137,17528,17595 ,7585,7591,7586 ,0,0,0}, - {19143,16352,19141 ,726,7625,726 ,0,0,0}, {19152,19150,19153 ,726,726,726 ,0,0,0}, - {19155,19154,19153 ,726,726,726 ,0,0,0}, {19151,19147,19149 ,726,726,726 ,0,0,0}, - {19153,19150,19147 ,726,726,726 ,0,0,0}, {19153,19147,19148 ,726,726,726 ,0,0,0}, - {19149,19147,19150 ,726,726,726 ,0,0,0}, {19148,19144,19155 ,726,726,726 ,0,0,0}, - {19155,19153,19148 ,726,726,726 ,0,0,0}, {19144,19145,16358 ,726,726,7626 ,0,0,0}, - {19144,16360,19155 ,726,726,726 ,0,0,0}, {19156,16354,16355 ,726,726,726 ,0,0,0}, - {16355,16358,19146 ,726,7626,726 ,0,0,0}, {19139,16343,16346 ,726,7627,726 ,0,0,0}, - {16348,16349,19142 ,726,7625,726 ,0,0,0}, {19140,16342,16343 ,7626,7627,7627 ,0,0,0}, - {16338,16323,16322 ,7626,7625,726 ,0,0,0}, {16341,16322,19137 ,726,726,726 ,0,0,0}, - {16334,16325,16335 ,726,7627,7625 ,0,0,0}, {16325,16334,16332 ,7627,726,726 ,0,0,0}, - {16334,16335,16329 ,726,7625,7627 ,0,0,0}, {16335,16338,16337 ,7625,7626,7628 ,0,0,0}, - {16325,16323,16335 ,7627,7625,7625 ,0,0,0}, {16325,16332,16326 ,7627,726,726 ,0,0,0}, - {16341,16338,16322 ,726,7626,726 ,0,0,0}, {16338,16335,16323 ,7626,7625,7625 ,0,0,0}, - {16320,19137,16322 ,726,726,726 ,0,0,0}, {19140,19137,16342 ,7626,726,7627 ,0,0,0}, - {16320,16342,19137 ,726,7627,726 ,0,0,0}, {19139,16346,19138 ,726,726,726 ,0,0,0}, - {16343,19139,19140 ,7627,726,7626 ,0,0,0}, {16348,19142,19138 ,726,726,726 ,0,0,0}, - {19138,16346,16348 ,726,726,726 ,0,0,0}, {16349,16352,19143 ,7625,7625,726 ,0,0,0}, - {19142,16349,19143 ,726,7625,726 ,0,0,0}, {19141,16354,19156 ,726,726,726 ,0,0,0}, - {19141,16352,16354 ,726,7625,726 ,0,0,0}, {16358,19145,19146 ,7626,726,726 ,0,0,0}, - {19146,19156,16355 ,726,726,726 ,0,0,0}, {16358,16360,19144 ,7626,726,726 ,0,0,0}, - {16302,19157,17576 ,4303,7629,7630 ,0,0,0}, {17499,17533,19158 ,7631,7632,7633 ,0,0,0}, - {17665,17577,19159 ,7634,7635,7636 ,0,0,0}, {17561,19160,17562 ,7637,7638,7639 ,0,0,0}, - {19161,19162,17498 ,7640,7641,7642 ,0,0,0}, {19163,19164,17343 ,7643,7644,7645 ,0,0,0}, - {19163,17563,19165 ,7643,7646,7647 ,0,0,0}, {19166,19167,17341 ,7648,7649,7650 ,0,0,0}, - {17341,17340,19166 ,7650,7651,7648 ,0,0,0}, {17524,19167,19168 ,7652,7649,7653 ,0,0,0}, - {19167,17524,17341 ,7649,7652,7650 ,0,0,0}, {19169,17523,19168 ,7654,7655,7653 ,0,0,0}, - {17524,19168,17523 ,7652,7653,7655 ,0,0,0}, {19169,16316,16317 ,7654,126,7656 ,0,0,0}, - {16317,17523,19169 ,7656,7655,7654 ,0,0,0}, {19160,17561,19162 ,7638,7637,7641 ,0,0,0}, - {19164,17340,17343 ,7644,7651,7645 ,0,0,0}, {19166,17340,19164 ,7648,7651,7644 ,0,0,0}, - {19158,17533,19170 ,7633,7632,7657 ,0,0,0}, {19165,17563,17562 ,7647,7646,7639 ,0,0,0}, - {19163,17343,17563 ,7643,7645,7646 ,0,0,0}, {19160,19165,17562 ,7638,7647,7639 ,0,0,0}, - {17498,19162,17561 ,7642,7641,7637 ,0,0,0}, {17499,19158,19161 ,7631,7633,7640 ,0,0,0}, - {19161,17498,17499 ,7640,7642,7631 ,0,0,0}, {17577,19157,19159 ,7635,7629,7636 ,0,0,0}, - {19170,17665,19159 ,7657,7634,7636 ,0,0,0}, {17533,17665,19170 ,7632,7634,7657 ,0,0,0}, - {16302,17576,16303 ,4303,7630,82 ,0,0,0}, {19157,17577,17576 ,7629,7635,7630 ,0,0,0}, - {19164,19163,16299 ,726,7658,7659 ,0,0,0}, {19157,19162,19158 ,7660,7661,726 ,0,0,0}, - {19157,19160,19162 ,7660,7661,7661 ,0,0,0}, {16301,19165,16302 ,7659,726,726 ,0,0,0}, - {19161,19158,19162 ,7661,726,7661 ,0,0,0}, {19159,19157,19158 ,7659,7660,726 ,0,0,0}, - {19160,19157,16302 ,7661,7660,726 ,0,0,0}, {19170,19159,19158 ,726,7659,726 ,0,0,0}, - {19160,16302,19165 ,7661,726,726 ,0,0,0}, {16299,19163,16301 ,7659,7658,7659 ,0,0,0}, - {16301,19163,19165 ,7659,7658,726 ,0,0,0}, {16297,19166,19164 ,726,5488,726 ,0,0,0}, - {16299,16297,19164 ,7659,726,726 ,0,0,0}, {16295,19166,16297 ,726,5488,726 ,0,0,0}, - {16295,19167,19166 ,726,7662,5488 ,0,0,0}, {19168,19167,16292 ,5471,7662,7661 ,0,0,0}, - {16295,16292,19167 ,726,7661,7662 ,0,0,0}, {16291,19168,16292 ,726,5471,7661 ,0,0,0}, - {19169,16291,16289 ,7663,726,7661 ,0,0,0}, {16291,19169,19168 ,726,7663,5471 ,0,0,0}, - {16288,16316,16289 ,7658,726,7661 ,0,0,0}, {19169,16289,16316 ,7663,7661,726 ,0,0,0}, - {16308,16304,16305 ,7658,7664,726 ,0,0,0}, {16308,16314,16304 ,7658,7665,7664 ,0,0,0}, - {16311,16308,16310 ,7666,7658,7667 ,0,0,0}, {16311,16314,16308 ,7666,7665,7658 ,0,0,0}, - {16316,16288,16314 ,726,7658,7665 ,0,0,0}, {16304,16314,16288 ,7664,7665,7658 ,0,0,0}, - {19171,16842,19172 ,726,726,726 ,0,0,0}, {16842,19173,19172 ,726,726,726 ,0,0,0}, - {19174,19175,16842 ,726,726,726 ,0,0,0}, {16842,19171,19174 ,726,726,726 ,0,0,0}, - {19176,19177,16842 ,726,726,726 ,0,0,0}, {19176,16842,19175 ,726,726,726 ,0,0,0}, - {16834,19178,19179 ,7583,726,7661 ,0,0,0}, {16842,19180,19181 ,726,726,726 ,0,0,0}, - {16834,19182,19183 ,7583,7658,7661 ,0,0,0}, {19184,16834,19185 ,726,7583,726 ,0,0,0}, - {19186,19187,16834 ,726,726,7583 ,0,0,0}, {19188,19185,16834 ,726,726,7583 ,0,0,0}, - {16834,19184,19189 ,7583,726,5489 ,0,0,0}, {19186,16834,19190 ,726,7583,7583 ,0,0,0}, - {16834,19187,19188 ,7583,726,726 ,0,0,0}, {16834,19191,19182 ,7583,726,7658 ,0,0,0}, - {19183,19190,16834 ,7661,7583,7583 ,0,0,0}, {19181,19178,16834 ,726,726,7583 ,0,0,0}, - {19191,16834,19179 ,726,7583,7661 ,0,0,0}, {16842,19177,19180 ,726,726,726 ,0,0,0}, - {16842,19181,16834 ,726,726,7583 ,0,0,0}, {16835,19189,16830 ,726,5489,7668 ,0,0,0}, - {19189,16835,16834 ,5489,726,7583 ,0,0,0}, {19173,16842,19192 ,726,726,726 ,0,0,0}, - {19193,16842,16840 ,726,726,726 ,0,0,0}, {16842,19193,19192 ,726,726,726 ,0,0,0}, - {19193,16840,16846 ,726,726,726 ,0,0,0}, {17296,17559,19191 ,7669,7670,7671 ,0,0,0}, - {19179,17297,17296 ,7672,7673,7669 ,0,0,0}, {19179,19178,17297 ,7672,7673,7673 ,0,0,0}, - {19191,19179,17296 ,7671,7672,7669 ,0,0,0}, {17559,17558,19182 ,7670,7674,7675 ,0,0,0}, - {17301,17355,19190 ,7676,7677,7678 ,0,0,0}, {19183,19182,17558 ,7679,7675,7674 ,0,0,0}, - {17558,17301,19183 ,7674,7676,7679 ,0,0,0}, {19190,19183,17301 ,7678,7679,7676 ,0,0,0}, - {17559,19182,19191 ,7670,7675,7671 ,0,0,0}, {19190,17355,19186 ,7678,7677,7680 ,0,0,0}, - {17354,19187,19186 ,7681,7682,7680 ,0,0,0}, {19186,17355,17354 ,7680,7677,7681 ,0,0,0}, - {19187,17354,17353 ,7682,7681,7683 ,0,0,0}, {17347,19188,17353 ,7684,7685,7683 ,0,0,0}, - {17347,17349,19185 ,7684,7686,7687 ,0,0,0}, {17347,19185,19188 ,7684,7687,7685 ,0,0,0}, - {19184,17350,19189 ,7688,7689,7690 ,0,0,0}, {19185,17349,19184 ,7687,7686,7688 ,0,0,0}, - {19184,17349,17350 ,7688,7686,7689 ,0,0,0}, {17350,17351,19189 ,7689,7690,7690 ,0,0,0}, - {19187,17353,19188 ,7682,7683,7685 ,0,0,0}, {17344,19178,19181 ,7691,7673,7692 ,0,0,0}, - {19178,17344,17297 ,7673,7691,7673 ,0,0,0}, {19180,17345,19181 ,7693,7694,7692 ,0,0,0}, - {17344,19181,17345 ,7691,7692,7694 ,0,0,0}, {19180,19177,17376 ,7693,7695,7696 ,0,0,0}, - {17376,17345,19180 ,7696,7694,7693 ,0,0,0}, {17377,19177,19176 ,7697,7695,7698 ,0,0,0}, - {19177,17377,17376 ,7695,7697,7696 ,0,0,0}, {19175,17599,19176 ,7699,7700,7698 ,0,0,0}, - {17377,19176,17599 ,7697,7698,7700 ,0,0,0}, {19175,19174,17380 ,7699,7701,7702 ,0,0,0}, - {17380,17599,19175 ,7702,7700,7699 ,0,0,0}, {17379,19174,19171 ,7703,7701,7704 ,0,0,0}, - {19174,17379,17380 ,7701,7703,7702 ,0,0,0}, {19172,17402,19171 ,7705,7706,7704 ,0,0,0}, - {17379,19171,17402 ,7703,7704,7706 ,0,0,0}, {19172,19173,17405 ,7705,7707,7708 ,0,0,0}, - {17405,17402,19172 ,7708,7706,7705 ,0,0,0}, {17406,19173,19192 ,7709,7707,7710 ,0,0,0}, - {19173,17406,17405 ,7707,7709,7708 ,0,0,0}, {17406,19192,17407 ,7709,7710,7711 ,0,0,0}, - {17407,19192,19193 ,7711,7710,7711 ,0,0,0}, {18108,19193,16846 ,7712,7712,7712 ,0,0,0}, - {19193,18109,18112 ,7712,7712,7712 ,0,0,0}, {18108,18109,19193 ,7712,7712,7712 ,0,0,0}, - {19193,18118,18123 ,7712,7712,7712 ,0,0,0}, {18112,18118,19193 ,7712,7712,7712 ,0,0,0}, - {19193,18127,18091 ,7712,7712,7712 ,0,0,0}, {18123,18127,19193 ,7712,7712,7712 ,0,0,0}, - {19193,18095,18094 ,7712,7712,7712 ,0,0,0}, {18091,18095,19193 ,7712,7712,7712 ,0,0,0}, - {19193,18094,17407 ,7712,7712,7712 ,0,0,0}, {18160,19189,17351 ,7713,7713,7713 ,0,0,0}, - {18160,18210,19189 ,7713,7713,7713 ,0,0,0}, {19189,18210,18196 ,7713,7713,7713 ,0,0,0}, - {18156,18162,19189 ,7713,7713,7713 ,0,0,0}, {18156,19189,18196 ,7713,7713,7713 ,0,0,0}, - {18162,18192,19189 ,7713,7713,7713 ,0,0,0}, {19189,18148,18147 ,7713,7713,7713 ,0,0,0}, - {18192,18148,19189 ,7713,7713,7713 ,0,0,0}, {16830,19189,18152 ,7713,7713,7713 ,0,0,0}, - {18147,18152,19189 ,7713,7713,7713 ,0,0,0}, {16265,19194,17614 ,1435,7714,7715 ,0,0,0}, - {19195,17605,19196 ,7716,7717,7718 ,0,0,0}, {17624,17613,19197 ,7719,7720,7721 ,0,0,0}, - {17285,19198,17386 ,7722,7723,7724 ,0,0,0}, {19199,19200,17627 ,7725,7726,7727 ,0,0,0}, - {19201,17408,19202 ,7728,7729,7730 ,0,0,0}, {17410,17387,19203 ,7731,7732,7733 ,0,0,0}, - {17292,17391,19204 ,7734,7735,7736 ,0,0,0}, {17396,19205,17391 ,7737,7738,7735 ,0,0,0}, - {17392,19206,19207 ,7739,7740,7741 ,0,0,0}, {17292,19208,17394 ,7734,7742,7743 ,0,0,0}, - {19209,17401,19207 ,7744,7745,7741 ,0,0,0}, {17392,19207,17401 ,7739,7741,7745 ,0,0,0}, - {19209,19210,17399 ,7744,7746,7747 ,0,0,0}, {17399,17401,19209 ,7747,7745,7744 ,0,0,0}, - {17412,19210,19211 ,7748,7746,7749 ,0,0,0}, {19210,17412,17399 ,7746,7748,7747 ,0,0,0}, - {19212,17398,19211 ,7750,7751,7749 ,0,0,0}, {17412,19211,17398 ,7748,7749,7751 ,0,0,0}, - {19212,16284,16285 ,7750,1359,1359 ,0,0,0}, {16285,17398,19212 ,1359,7751,7750 ,0,0,0}, - {19204,17391,19205 ,7736,7735,7738 ,0,0,0}, {19206,17394,19208 ,7740,7743,7742 ,0,0,0}, - {17394,19206,17392 ,7743,7740,7739 ,0,0,0}, {19204,19208,17292 ,7736,7742,7734 ,0,0,0}, - {19201,19205,17396 ,7728,7738,7737 ,0,0,0}, {17410,19203,19202 ,7731,7733,7730 ,0,0,0}, - {17410,19202,17408 ,7731,7730,7729 ,0,0,0}, {17396,17408,19201 ,7737,7729,7728 ,0,0,0}, - {17387,19213,19203 ,7732,7752,7733 ,0,0,0}, {19213,17387,17386 ,7752,7732,7724 ,0,0,0}, - {19200,19198,17285 ,7726,7723,7722 ,0,0,0}, {19198,19213,17386 ,7723,7752,7724 ,0,0,0}, - {17627,19200,17285 ,7727,7726,7722 ,0,0,0}, {17615,19195,19199 ,7753,7716,7725 ,0,0,0}, - {17615,19199,17627 ,7753,7725,7727 ,0,0,0}, {17605,17624,19196 ,7717,7719,7718 ,0,0,0}, - {17615,17605,19195 ,7753,7717,7716 ,0,0,0}, {17613,19194,19197 ,7720,7714,7721 ,0,0,0}, - {19196,17624,19197 ,7718,7719,7721 ,0,0,0}, {16265,17614,16263 ,1435,7715,1435 ,0,0,0}, - {19194,17613,17614 ,7714,7720,7715 ,0,0,0}, {19212,19211,19210 ,726,7628,7628 ,0,0,0}, - {16267,19207,16266 ,7627,7628,726 ,0,0,0}, {16246,16244,19208 ,7754,7625,7626 ,0,0,0}, - {19207,19206,16266 ,7628,726,726 ,0,0,0}, {16249,19201,16250 ,7755,726,7756 ,0,0,0}, - {16246,19208,19204 ,7754,7626,7626 ,0,0,0}, {19203,19213,16258 ,726,7628,7757 ,0,0,0}, - {19203,16256,19202 ,726,7758,7626 ,0,0,0}, {16259,16253,19198 ,7759,7760,7628 ,0,0,0}, - {19195,19196,19197 ,7625,7754,726 ,0,0,0}, {16262,16259,19200 ,7628,7759,7627 ,0,0,0}, - {16265,16262,19194 ,7628,7628,7761 ,0,0,0}, {19194,19195,19197 ,7761,7625,726 ,0,0,0}, - {16262,19199,19195 ,7628,7628,7625 ,0,0,0}, {19194,16262,19195 ,7761,7628,7625 ,0,0,0}, - {16262,16261,16259 ,7628,7762,7759 ,0,0,0}, {16262,19200,19199 ,7628,7627,7628 ,0,0,0}, - {16258,19198,16253 ,7757,7628,7760 ,0,0,0}, {19198,19200,16259 ,7628,7627,7759 ,0,0,0}, - {16258,19213,19198 ,7757,7628,7628 ,0,0,0}, {19202,16256,16250 ,7626,7758,7756 ,0,0,0}, - {16258,16256,19203 ,7757,7758,726 ,0,0,0}, {19205,19201,16249 ,7628,726,7755 ,0,0,0}, - {19201,19202,16250 ,726,7626,7756 ,0,0,0}, {19205,16247,19204 ,7628,7628,7626 ,0,0,0}, - {16247,19205,16249 ,7628,7628,7755 ,0,0,0}, {19206,19208,16244 ,726,7626,7625 ,0,0,0}, - {16247,16246,19204 ,7628,7754,7626 ,0,0,0}, {16270,19207,16267 ,7625,7628,7627 ,0,0,0}, - {16244,16266,19206 ,7625,726,726 ,0,0,0}, {19210,19209,16270 ,7628,7628,7625 ,0,0,0}, - {16270,19209,19207 ,7625,7628,7628 ,0,0,0}, {16272,19212,19210 ,7628,726,7628 ,0,0,0}, - {19210,16270,16272 ,7628,7625,7628 ,0,0,0}, {16272,16273,19212 ,7628,7628,726 ,0,0,0}, - {16276,16279,16282 ,7628,7628,7628 ,0,0,0}, {16273,16276,19212 ,7628,7628,726 ,0,0,0}, - {16282,19212,16276 ,7628,726,7628 ,0,0,0}, {16276,16278,16279 ,7628,726,7628 ,0,0,0}, - {19212,16282,16284 ,726,7628,7628 ,0,0,0}, {16226,19214,17575 ,1435,7763,7764 ,0,0,0}, - {17602,17604,19215 ,7765,7766,7767 ,0,0,0}, {17608,17609,19216 ,7768,7769,7770 ,0,0,0}, - {17574,19217,17573 ,7771,7772,7773 ,0,0,0}, {19218,19219,17603 ,7774,4221,7775 ,0,0,0}, - {19220,19221,17601 ,7776,7777,7778 ,0,0,0}, {19220,17600,19222 ,7776,7779,7780 ,0,0,0}, - {19223,19224,17417 ,7781,7782,7783 ,0,0,0}, {17417,17416,19223 ,7783,7784,7781 ,0,0,0}, - {17291,19224,19225 ,7785,7782,7786 ,0,0,0}, {19224,17291,17417 ,7782,7785,7783 ,0,0,0}, - {19226,17290,19225 ,7787,7788,7786 ,0,0,0}, {17291,19225,17290 ,7785,7786,7788 ,0,0,0}, - {19226,16240,16241 ,7787,1359,1359 ,0,0,0}, {16241,17290,19226 ,1359,7788,7787 ,0,0,0}, - {19217,17574,19219 ,7772,7771,4221 ,0,0,0}, {19221,17416,17601 ,7777,7784,7778 ,0,0,0}, - {19223,17416,19221 ,7781,7784,7777 ,0,0,0}, {19215,17604,19227 ,7767,7766,4227 ,0,0,0}, - {19222,17600,17573 ,7780,7779,7773 ,0,0,0}, {19220,17601,17600 ,7776,7778,7779 ,0,0,0}, - {19217,19222,17573 ,7772,7780,7773 ,0,0,0}, {17603,19219,17574 ,7775,4221,7771 ,0,0,0}, - {17602,19215,19218 ,7765,7767,7774 ,0,0,0}, {19218,17603,17602 ,7774,7775,7765 ,0,0,0}, - {17609,19214,19216 ,7769,7763,7770 ,0,0,0}, {19227,17608,19216 ,4227,7768,7770 ,0,0,0}, - {17604,17608,19227 ,7766,7768,4227 ,0,0,0}, {16226,17575,16227 ,1435,7764,1435 ,0,0,0}, - {19214,17609,17575 ,7763,7769,7764 ,0,0,0}, {16225,16234,16226 ,726,5471,7661 ,0,0,0}, - {19217,19220,19222 ,726,726,726 ,0,0,0}, {19223,19221,19220 ,7658,726,726 ,0,0,0}, - {19220,19217,19223 ,726,726,7658 ,0,0,0}, {19223,19219,19224 ,7658,726,7658 ,0,0,0}, - {19219,19223,19217 ,726,7658,726 ,0,0,0}, {19225,19224,19218 ,7658,7658,726 ,0,0,0}, - {19219,19218,19224 ,726,726,7658 ,0,0,0}, {19215,19226,19225 ,7658,7661,7658 ,0,0,0}, - {19225,19218,19215 ,7658,726,7658 ,0,0,0}, {19226,19227,16240 ,7661,7661,7664 ,0,0,0}, - {19227,19226,19215 ,7661,7661,7658 ,0,0,0}, {19227,19216,16240 ,7661,726,7664 ,0,0,0}, - {19216,19214,16238 ,726,726,7662 ,0,0,0}, {16232,16225,16223 ,7789,726,7658 ,0,0,0}, - {16213,16212,16219 ,5488,7668,7661 ,0,0,0}, {16229,16221,16228 ,7790,7664,7791 ,0,0,0}, - {16213,16219,16215 ,5488,7661,7792 ,0,0,0}, {16216,16215,16219 ,5488,7792,7661 ,0,0,0}, - {16221,16219,16228 ,7664,7661,7791 ,0,0,0}, {16228,16219,16212 ,7791,7661,7668 ,0,0,0}, - {16221,16229,16223 ,7664,7790,7658 ,0,0,0}, {16234,16225,16232 ,5471,726,7789 ,0,0,0}, - {16232,16223,16229 ,7789,7658,7790 ,0,0,0}, {16226,16235,19214 ,7661,7583,726 ,0,0,0}, - {16226,16234,16235 ,7661,5471,7583 ,0,0,0}, {19216,16238,16240 ,726,7662,7664 ,0,0,0}, - {16235,16238,19214 ,7583,7662,726 ,0,0,0}, {19228,16871,19229 ,7583,726,726 ,0,0,0}, - {19230,16867,19231 ,7668,726,5470 ,0,0,0}, {19230,19232,16867 ,7668,726,726 ,0,0,0}, - {16867,19233,19231 ,726,726,5470 ,0,0,0}, {19232,19234,16867 ,726,5489,726 ,0,0,0}, - {16867,19235,19236 ,726,7793,7794 ,0,0,0}, {19234,19235,16867 ,5489,7793,726 ,0,0,0}, - {16871,19237,16867 ,726,5470,726 ,0,0,0}, {19237,19233,16867 ,5470,726,726 ,0,0,0}, - {19238,19237,16871 ,726,5470,726 ,0,0,0}, {19239,16867,19236 ,7795,726,7794 ,0,0,0}, - {16871,19240,19238 ,726,5488,726 ,0,0,0}, {19239,19241,16867 ,7795,726,726 ,0,0,0}, - {19242,16867,19243 ,5485,726,7796 ,0,0,0}, {16867,19241,19243 ,726,726,7796 ,0,0,0}, - {16871,19244,19240 ,726,7583,5488 ,0,0,0}, {19245,16867,19242 ,7583,726,5485 ,0,0,0}, - {16871,19246,19244 ,726,726,7583 ,0,0,0}, {16871,19247,19248 ,726,5488,7583 ,0,0,0}, - {16871,19248,19246 ,726,7583,726 ,0,0,0}, {16868,19245,16863 ,5489,7583,7797 ,0,0,0}, - {16871,19228,19247 ,726,7583,5488 ,0,0,0}, {19245,16868,16867 ,7583,5489,726 ,0,0,0}, - {19229,16871,19249 ,726,726,7583 ,0,0,0}, {19250,16871,16878 ,726,726,726 ,0,0,0}, - {16871,19250,19249 ,726,726,7583 ,0,0,0}, {19250,16878,16877 ,726,726,726 ,0,0,0}, - {17286,17388,19230 ,7798,7799,7800 ,0,0,0}, {19231,17284,17286 ,7801,7802,7798 ,0,0,0}, - {19231,19233,17284 ,7801,7802,7802 ,0,0,0}, {19230,19231,17286 ,7800,7801,7798 ,0,0,0}, - {17388,17597,19232 ,7799,7803,7804 ,0,0,0}, {17409,17395,19235 ,7805,7806,7807 ,0,0,0}, - {19234,19232,17597 ,7808,7804,7803 ,0,0,0}, {17597,17409,19234 ,7803,7805,7808 ,0,0,0}, - {19235,19234,17409 ,7807,7808,7805 ,0,0,0}, {17388,19232,19230 ,7799,7804,7800 ,0,0,0}, - {19235,17395,19236 ,7807,7806,7809 ,0,0,0}, {17390,19239,19236 ,7810,7811,7809 ,0,0,0}, - {19236,17395,17390 ,7809,7806,7810 ,0,0,0}, {19239,17390,17389 ,7811,7810,7812 ,0,0,0}, - {17294,19241,17389 ,7813,7814,7812 ,0,0,0}, {17294,17373,19243 ,7813,7815,7816 ,0,0,0}, - {17294,19243,19241 ,7813,7816,7814 ,0,0,0}, {19242,17375,19245 ,7817,7818,7819 ,0,0,0}, - {19243,17373,19242 ,7816,7815,7817 ,0,0,0}, {19242,17373,17375 ,7817,7815,7818 ,0,0,0}, - {17375,17404,19245 ,7818,7819,7819 ,0,0,0}, {19239,17389,19241 ,7811,7812,7814 ,0,0,0}, - {17418,19233,19237 ,7820,7802,7821 ,0,0,0}, {19233,17418,17284 ,7802,7820,7802 ,0,0,0}, - {19238,17422,19237 ,7822,7823,7821 ,0,0,0}, {17418,19237,17422 ,7820,7821,7823 ,0,0,0}, - {19238,19240,17383 ,7822,7824,7825 ,0,0,0}, {17383,17422,19238 ,7825,7823,7822 ,0,0,0}, - {17384,19240,19244 ,7826,7824,7827 ,0,0,0}, {19240,17384,17383 ,7824,7826,7825 ,0,0,0}, - {19246,17459,19244 ,7828,7829,7827 ,0,0,0}, {17384,19244,17459 ,7826,7827,7829 ,0,0,0}, - {19246,19248,17287 ,7828,7830,7831 ,0,0,0}, {17287,17459,19246 ,7831,7829,7828 ,0,0,0}, - {17288,19248,19247 ,7832,7830,7833 ,0,0,0}, {19248,17288,17287 ,7830,7832,7831 ,0,0,0}, - {19228,17446,19247 ,7834,7835,7833 ,0,0,0}, {17288,19247,17446 ,7832,7833,7835 ,0,0,0}, - {19228,19229,17449 ,7834,7836,7837 ,0,0,0}, {17449,17446,19228 ,7837,7835,7834 ,0,0,0}, - {17453,19229,19249 ,7838,7836,7839 ,0,0,0}, {19229,17453,17449 ,7836,7838,7837 ,0,0,0}, - {17453,19249,17454 ,7838,7839,7840 ,0,0,0}, {17454,19249,19250 ,7840,7839,7840 ,0,0,0}, - {18021,19250,16877 ,7841,7841,7841 ,0,0,0}, {19250,18027,18030 ,7841,7841,7841 ,0,0,0}, - {18021,18027,19250 ,7841,7841,7841 ,0,0,0}, {19250,18036,18041 ,7841,7841,7841 ,0,0,0}, - {18030,18036,19250 ,7841,7841,7841 ,0,0,0}, {19250,18045,18004 ,7841,7841,7841 ,0,0,0}, - {18041,18045,19250 ,7841,7841,7841 ,0,0,0}, {19250,18016,18015 ,7841,7841,7841 ,0,0,0}, - {18004,18016,19250 ,7841,7841,7841 ,0,0,0}, {19250,18015,17454 ,7841,7841,7841 ,0,0,0}, - {18082,19245,17404 ,7842,7842,7842 ,0,0,0}, {18082,18128,19245 ,7842,7842,7842 ,0,0,0}, - {19245,18128,18114 ,7842,7842,7842 ,0,0,0}, {18076,18069,19245 ,7842,7842,7842 ,0,0,0}, - {18076,19245,18114 ,7842,7842,7842 ,0,0,0}, {18069,18110,19245 ,7842,7842,7842 ,0,0,0}, - {19245,18102,18064 ,7842,7842,7842 ,0,0,0}, {18110,18102,19245 ,7842,7842,7842 ,0,0,0}, - {16863,19245,18065 ,7842,7842,7842 ,0,0,0}, {18064,18065,19245 ,7842,7842,7842 ,0,0,0}, - {16189,19251,17639 ,1790,7843,4204 ,0,0,0}, {19252,17636,19253 ,7844,4198,4199 ,0,0,0}, - {17625,17638,19254 ,7845,7846,7847 ,0,0,0}, {17616,19255,17434 ,7848,7849,7850 ,0,0,0}, - {19256,19257,17649 ,7851,7852,7853 ,0,0,0}, {19258,17413,19259 ,7854,7855,7856 ,0,0,0}, - {17415,17432,19260 ,7857,7858,7859 ,0,0,0}, {17281,17280,19261 ,7860,7861,7862 ,0,0,0}, - {17436,19262,17280 ,7863,7864,7861 ,0,0,0}, {17440,19263,19264 ,7865,7866,7867 ,0,0,0}, - {17281,19265,17439 ,7860,7868,7869 ,0,0,0}, {19266,17445,19264 ,7870,7871,7867 ,0,0,0}, - {17440,19264,17445 ,7865,7867,7871 ,0,0,0}, {19266,19267,17443 ,7870,7872,7873 ,0,0,0}, - {17443,17445,19266 ,7873,7871,7870 ,0,0,0}, {17428,19267,19268 ,7874,7872,7875 ,0,0,0}, - {19267,17428,17443 ,7872,7874,7873 ,0,0,0}, {19269,17426,19268 ,7876,7877,7875 ,0,0,0}, - {17428,19268,17426 ,7874,7875,7877 ,0,0,0}, {19269,16208,16209 ,7876,1711,1711 ,0,0,0}, - {16209,17426,19269 ,1711,7877,7876 ,0,0,0}, {19261,17280,19262 ,7862,7861,7864 ,0,0,0}, - {19263,17439,19265 ,7866,7869,7868 ,0,0,0}, {17439,19263,17440 ,7869,7866,7865 ,0,0,0}, - {19261,19265,17281 ,7862,7868,7860 ,0,0,0}, {19258,19262,17436 ,7854,7864,7863 ,0,0,0}, - {17415,19260,19259 ,7857,7859,7856 ,0,0,0}, {17415,19259,17413 ,7857,7856,7855 ,0,0,0}, - {17436,17413,19258 ,7863,7855,7854 ,0,0,0}, {17432,19270,19260 ,7858,7878,7859 ,0,0,0}, - {19270,17432,17434 ,7878,7858,7850 ,0,0,0}, {19257,19255,17616 ,7852,7849,7848 ,0,0,0}, - {19255,19270,17434 ,7849,7878,7850 ,0,0,0}, {17649,19257,17616 ,7853,7852,7848 ,0,0,0}, - {17637,19252,19256 ,7879,7844,7851 ,0,0,0}, {17637,19256,17649 ,7879,7851,7853 ,0,0,0}, - {17636,17625,19253 ,4198,7845,4199 ,0,0,0}, {17637,17636,19252 ,7879,4198,7844 ,0,0,0}, - {17638,19251,19254 ,7846,7843,7847 ,0,0,0}, {19253,17625,19254 ,4199,7845,7847 ,0,0,0}, - {16189,17639,16187 ,1790,4204,1790 ,0,0,0}, {19251,17638,17639 ,7843,7846,4204 ,0,0,0}, - {19261,19262,19256 ,726,7880,7881 ,0,0,0}, {19251,19266,19264 ,7882,7627,7625 ,0,0,0}, - {19257,19258,19255 ,7883,7758,726 ,0,0,0}, {19270,19255,19258 ,7884,726,7758 ,0,0,0}, - {19259,19260,19270 ,7880,7761,7884 ,0,0,0}, {19258,19257,19262 ,7758,7883,7880 ,0,0,0}, - {19259,19270,19258 ,7880,7884,7758 ,0,0,0}, {19261,19256,19252 ,726,7881,7885 ,0,0,0}, - {19262,19257,19256 ,7880,7883,7881 ,0,0,0}, {19252,19253,19265 ,7885,7886,7758 ,0,0,0}, - {19265,19261,19252 ,7758,726,7885 ,0,0,0}, {19263,19253,19254 ,726,7886,7887 ,0,0,0}, - {19253,19263,19265 ,7886,726,7758 ,0,0,0}, {19264,19263,19254 ,7625,726,7887 ,0,0,0}, - {16189,19266,19251 ,7758,7627,7882 ,0,0,0}, {19251,19264,19254 ,7882,7625,7887 ,0,0,0}, - {19267,16189,16186 ,7627,7758,7755 ,0,0,0}, {16189,19267,19266 ,7758,7627,7627 ,0,0,0}, - {16185,19268,16186 ,7625,726,7755 ,0,0,0}, {19267,16186,19268 ,7627,7755,726 ,0,0,0}, - {16185,16183,19269 ,7625,7761,726 ,0,0,0}, {19269,19268,16185 ,726,726,7625 ,0,0,0}, - {16208,16183,16177 ,7627,7761,7625 ,0,0,0}, {16183,16208,19269 ,7761,7627,726 ,0,0,0}, - {16174,16202,16180 ,726,7627,7625 ,0,0,0}, {16182,16206,16177 ,7880,726,7625 ,0,0,0}, - {16200,16173,16197 ,7625,726,726 ,0,0,0}, {16194,16170,16191 ,7627,7625,7625 ,0,0,0}, - {16196,16197,16171 ,726,726,7625 ,0,0,0}, {16191,16168,16190 ,7625,7625,726 ,0,0,0}, - {16170,16194,16196 ,7625,7627,726 ,0,0,0}, {16171,16170,16196 ,7625,7625,726 ,0,0,0}, - {16191,16170,16168 ,7625,7625,7625 ,0,0,0}, {16174,16173,16200 ,726,726,7625 ,0,0,0}, - {16171,16197,16173 ,7625,726,726 ,0,0,0}, {16203,16180,16202 ,726,7625,7627 ,0,0,0}, - {16202,16174,16200 ,7627,726,7625 ,0,0,0}, {16182,16203,16206 ,7880,726,726 ,0,0,0}, - {16203,16182,16180 ,726,7880,7625 ,0,0,0}, {16206,16208,16177 ,726,7627,7625 ,0,0,0}, - {16150,19271,17569 ,1790,7888,7889 ,0,0,0}, {17621,17610,19272 ,7890,7891,7892 ,0,0,0}, - {17623,17570,19273 ,7893,7894,7895 ,0,0,0}, {17611,19274,17612 ,7896,7897,4137 ,0,0,0}, - {19275,19276,17622 ,7898,7899,7900 ,0,0,0}, {19277,19278,17620 ,7901,7902,7903 ,0,0,0}, - {19277,17619,19279 ,7901,7904,7905 ,0,0,0}, {19280,19281,17455 ,7906,7907,7908 ,0,0,0}, - {17455,17456,19280 ,7908,7909,7906 ,0,0,0}, {17618,19281,19282 ,7910,7907,7911 ,0,0,0}, - {19281,17618,17455 ,7907,7910,7908 ,0,0,0}, {19283,17429,19282 ,7912,7913,7911 ,0,0,0}, - {17618,19282,17429 ,7910,7911,7913 ,0,0,0}, {19283,16164,16165 ,7912,1711,1711 ,0,0,0}, - {16165,17429,19283 ,1711,7913,7912 ,0,0,0}, {19274,17611,19276 ,7897,7896,7899 ,0,0,0}, - {19278,17456,17620 ,7902,7909,7903 ,0,0,0}, {19280,17456,19278 ,7906,7909,7902 ,0,0,0}, - {19272,17610,19284 ,7892,7891,7914 ,0,0,0}, {19279,17619,17612 ,7905,7904,4137 ,0,0,0}, - {19277,17620,17619 ,7901,7903,7904 ,0,0,0}, {19274,19279,17612 ,7897,7905,4137 ,0,0,0}, - {17622,19276,17611 ,7900,7899,7896 ,0,0,0}, {17621,19272,19275 ,7890,7892,7898 ,0,0,0}, - {19275,17622,17621 ,7898,7900,7890 ,0,0,0}, {17570,19271,19273 ,7894,7888,7895 ,0,0,0}, - {19284,17623,19273 ,7914,7893,7895 ,0,0,0}, {17610,17623,19284 ,7891,7893,7914 ,0,0,0}, - {16150,17569,16151 ,1790,7889,1790 ,0,0,0}, {19271,17570,17569 ,7888,7894,7889 ,0,0,0}, - {19277,16158,19278 ,726,7658,726 ,0,0,0}, {19282,19281,16162 ,726,726,7660 ,0,0,0}, - {16164,19283,19282 ,726,7660,726 ,0,0,0}, {19277,19279,16156 ,726,726,7658 ,0,0,0}, - {16159,16162,19280 ,7660,7660,7659 ,0,0,0}, {19276,19275,16136 ,7659,726,7661 ,0,0,0}, - {19276,16152,19274 ,7659,726,726 ,0,0,0}, {16139,16137,19272 ,7915,7916,726 ,0,0,0}, - {19271,16145,16143 ,7658,7917,5475 ,0,0,0}, {19273,16140,19284 ,7658,726,7659 ,0,0,0}, - {16150,16149,16145 ,7918,7918,7917 ,0,0,0}, {16147,16145,16149 ,7661,7917,7918 ,0,0,0}, - {19273,19271,16143 ,7658,7658,5475 ,0,0,0}, {19271,16150,16145 ,7658,7918,7917 ,0,0,0}, - {16140,19273,16143 ,726,7658,5475 ,0,0,0}, {19284,16140,16139 ,7659,726,7915 ,0,0,0}, - {19272,16137,19275 ,726,7916,726 ,0,0,0}, {19284,16139,19272 ,7659,7915,726 ,0,0,0}, - {19276,16136,16152 ,7659,7661,726 ,0,0,0}, {19275,16137,16136 ,726,7916,7661 ,0,0,0}, - {16153,19279,19274 ,7664,726,726 ,0,0,0}, {16152,16153,19274 ,726,7664,726 ,0,0,0}, - {16158,19277,16156 ,7658,726,7658 ,0,0,0}, {16156,19279,16153 ,7658,726,7664 ,0,0,0}, - {19278,16159,19280 ,726,7660,7659 ,0,0,0}, {19278,16158,16159 ,726,7658,7660 ,0,0,0}, - {19282,16162,16164 ,726,7660,726 ,0,0,0}, {19281,19280,16162 ,726,7659,7660 ,0,0,0}, - {16908,19285,19286 ,726,5469,7919 ,0,0,0}, {19287,16908,19288 ,7920,726,7921 ,0,0,0}, - {16908,19287,19285 ,726,7920,5469 ,0,0,0}, {16908,19289,19288 ,726,726,7921 ,0,0,0}, - {19290,16908,19286 ,7922,726,7919 ,0,0,0}, {19289,16908,19291 ,726,726,7920 ,0,0,0}, - {19290,19292,16908 ,7922,7923,726 ,0,0,0}, {16908,19293,19294 ,726,7924,7925 ,0,0,0}, - {19294,19295,16908 ,7925,7926,726 ,0,0,0}, {19292,19293,16908 ,7923,7924,726 ,0,0,0}, - {19296,19297,16908 ,5472,7927,726 ,0,0,0}, {19296,16908,19295 ,5472,726,7926 ,0,0,0}, - {19298,19299,16908 ,7928,7929,726 ,0,0,0}, {19298,16908,19297 ,7928,726,7927 ,0,0,0}, - {19300,19301,16908 ,726,5489,726 ,0,0,0}, {19300,16908,19299 ,726,726,7929 ,0,0,0}, - {16908,19302,16907 ,726,5488,7583 ,0,0,0}, {19302,16908,19301 ,5488,726,5489 ,0,0,0}, - {16907,19303,19304 ,7583,5470,5489 ,0,0,0}, {19302,19303,16907 ,5488,5470,7583 ,0,0,0}, - {16903,16904,19304 ,5489,5488,5489 ,0,0,0}, {16907,19304,16904 ,7583,5489,5488 ,0,0,0}, - {16898,16903,19304 ,5489,5489,5489 ,0,0,0}, {16908,18875,19291 ,726,5489,7920 ,0,0,0}, - {18875,19305,19306 ,5489,5470,5488 ,0,0,0}, {19291,18875,19306 ,7920,5489,5488 ,0,0,0}, - {19307,18875,18874 ,5489,5489,726 ,0,0,0}, {18875,19307,19305 ,5489,5489,5470 ,0,0,0}, - {17938,19307,18873 ,5489,5489,7583 ,0,0,0}, {18874,18873,19307 ,726,7583,5489 ,0,0,0}, - {17472,17433,19295 ,7930,7931,7932 ,0,0,0}, {19294,17474,17472 ,7933,7934,7930 ,0,0,0}, - {19294,19293,17474 ,7933,7935,7934 ,0,0,0}, {19295,19294,17472 ,7932,7933,7930 ,0,0,0}, - {17433,17617,19296 ,7931,7936,7937 ,0,0,0}, {17414,17435,19298 ,7938,7939,7940 ,0,0,0}, - {19297,19296,17617 ,7941,7937,7936 ,0,0,0}, {17617,17414,19297 ,7936,7938,7941 ,0,0,0}, - {19298,19297,17414 ,7940,7941,7938 ,0,0,0}, {17433,19296,19295 ,7931,7937,7932 ,0,0,0}, - {19298,17435,19299 ,7940,7939,7942 ,0,0,0}, {17437,19300,19299 ,7943,7944,7942 ,0,0,0}, - {19299,17435,17437 ,7942,7939,7943 ,0,0,0}, {19300,17437,17282 ,7944,7943,7945 ,0,0,0}, - {17425,19301,17282 ,7946,7947,7945 ,0,0,0}, {17425,17438,19302 ,7946,7948,7949 ,0,0,0}, - {17425,19302,19301 ,7946,7949,7947 ,0,0,0}, {19303,17430,19304 ,7950,7951,7952 ,0,0,0}, - {19302,17438,19303 ,7949,7948,7950 ,0,0,0}, {19303,17438,17430 ,7950,7948,7951 ,0,0,0}, - {17430,17431,19304 ,7951,7952,7952 ,0,0,0}, {19300,17282,19301 ,7944,7945,7947 ,0,0,0}, - {17594,19293,19292 ,7953,7935,7954 ,0,0,0}, {19293,17594,17474 ,7935,7953,7934 ,0,0,0}, - {19290,17473,19292 ,7955,7956,7954 ,0,0,0}, {17594,19292,17473 ,7953,7954,7956 ,0,0,0}, - {19290,19286,17457 ,7955,7957,7958 ,0,0,0}, {17457,17473,19290 ,7958,7956,7955 ,0,0,0}, - {17458,19286,19285 ,7959,7957,7960 ,0,0,0}, {19286,17458,17457 ,7957,7959,7958 ,0,0,0}, - {19287,17631,19285 ,7961,7962,7960 ,0,0,0}, {17458,19285,17631 ,7959,7960,7962 ,0,0,0}, - {19287,19288,17571 ,7961,7963,7964 ,0,0,0}, {17571,17631,19287 ,7964,7962,7961 ,0,0,0}, - {17572,19288,19289 ,7965,7963,7966 ,0,0,0}, {19288,17572,17571 ,7963,7965,7964 ,0,0,0}, - {19291,17465,19289 ,7967,7968,7966 ,0,0,0}, {17572,19289,17465 ,7965,7966,7968 ,0,0,0}, - {19291,19306,17493 ,7967,7969,7970 ,0,0,0}, {17493,17465,19291 ,7970,7968,7967 ,0,0,0}, - {17494,19306,19305 ,7971,7969,7972 ,0,0,0}, {19306,17494,17493 ,7969,7971,7970 ,0,0,0}, - {17494,19305,17496 ,7971,7972,7973 ,0,0,0}, {17496,19305,19307 ,7973,7972,7973 ,0,0,0}, - {17948,17954,19307 ,7974,7974,7974 ,0,0,0}, {19307,17938,17939 ,7974,7974,7974 ,0,0,0}, - {17939,17945,19307 ,7974,7974,7974 ,0,0,0}, {17959,19307,17954 ,7974,7974,7974 ,0,0,0}, - {17945,17948,19307 ,7974,7974,7974 ,0,0,0}, {17963,17916,19307 ,7974,7974,7974 ,0,0,0}, - {17963,19307,17959 ,7974,7974,7974 ,0,0,0}, {17916,17928,19307 ,7974,7974,7974 ,0,0,0}, - {17496,19307,17927 ,7974,7974,7974 ,0,0,0}, {17928,17927,19307 ,7974,7974,7974 ,0,0,0}, - {19304,17431,17996 ,7975,7975,7975 ,0,0,0}, {17996,18046,19304 ,7975,7975,7975 ,0,0,0}, - {19304,18032,17992 ,7975,7975,7975 ,0,0,0}, {18046,18032,19304 ,7975,7975,7975 ,0,0,0}, - {19304,17998,18028 ,7975,7975,7975 ,0,0,0}, {17992,17998,19304 ,7975,7975,7975 ,0,0,0}, - {19304,17984,17983 ,7975,7975,7975 ,0,0,0}, {18028,17984,19304 ,7975,7975,7975 ,0,0,0}, - {16898,19304,17988 ,7975,7975,7975 ,0,0,0}, {17983,17988,19304 ,7975,7975,7975 ,0,0,0}, - {16113,19308,17644 ,126,7976,7977 ,0,0,0}, {19309,17646,19310 ,7978,7979,7980 ,0,0,0}, - {17660,17647,19311 ,7981,7982,7983 ,0,0,0}, {17461,19312,17452 ,7984,7985,7986 ,0,0,0}, - {19313,19314,17628 ,7987,7988,7989 ,0,0,0}, {19315,17479,19316 ,7990,7991,7992 ,0,0,0}, - {17497,17464,19317 ,7993,7994,7995 ,0,0,0}, {17489,17490,19318 ,7996,7997,7998 ,0,0,0}, - {17480,19319,17490 ,7999,8000,7997 ,0,0,0}, {17481,19320,19321 ,8001,8002,8003 ,0,0,0}, - {17489,19322,17483 ,7996,8004,8005 ,0,0,0}, {19323,17484,19321 ,8006,8007,8003 ,0,0,0}, - {17481,19321,17484 ,8001,8003,8007 ,0,0,0}, {19323,19324,17487 ,8006,8008,8009 ,0,0,0}, - {17487,17484,19323 ,8009,8007,8006 ,0,0,0}, {17526,19324,19325 ,8010,8008,8011 ,0,0,0}, - {19324,17526,17487 ,8008,8010,8009 ,0,0,0}, {19326,17488,19325 ,8012,8013,8011 ,0,0,0}, - {17526,19325,17488 ,8010,8011,8013 ,0,0,0}, {19326,16132,16133 ,8012,8014,4346 ,0,0,0}, - {16133,17488,19326 ,4346,8013,8012 ,0,0,0}, {19318,17490,19319 ,7998,7997,8000 ,0,0,0}, - {19320,17483,19322 ,8002,8005,8004 ,0,0,0}, {17483,19320,17481 ,8005,8002,8001 ,0,0,0}, - {19318,19322,17489 ,7998,8004,7996 ,0,0,0}, {19315,19319,17480 ,7990,8000,7999 ,0,0,0}, - {17497,19317,19316 ,7993,7995,7992 ,0,0,0}, {17497,19316,17479 ,7993,7992,7991 ,0,0,0}, - {17480,17479,19315 ,7999,7991,7990 ,0,0,0}, {17464,19327,19317 ,7994,8015,7995 ,0,0,0}, - {19327,17464,17452 ,8015,7994,7986 ,0,0,0}, {19314,19312,17461 ,7988,7985,7984 ,0,0,0}, - {19312,19327,17452 ,7985,8015,7986 ,0,0,0}, {17628,19314,17461 ,7989,7988,7984 ,0,0,0}, - {17645,19309,19313 ,8016,7978,7987 ,0,0,0}, {17645,19313,17628 ,8016,7987,7989 ,0,0,0}, - {17646,17660,19310 ,7979,7981,7980 ,0,0,0}, {17645,17646,19309 ,8016,7979,7978 ,0,0,0}, - {17647,19308,19311 ,7982,7976,7983 ,0,0,0}, {19310,17660,19311 ,7980,7981,7983 ,0,0,0}, - {16113,17644,16111 ,126,7977,4289 ,0,0,0}, {19308,17647,17644 ,7976,7982,7977 ,0,0,0}, - {19326,19325,19324 ,7625,7880,7758 ,0,0,0}, {16118,19309,19310 ,7626,7880,726 ,0,0,0}, - {19324,19321,19318 ,7758,8017,8018 ,0,0,0}, {19324,19323,19321 ,7758,7758,8017 ,0,0,0}, - {19320,19318,19321 ,8017,8018,8017 ,0,0,0}, {19320,19322,19318 ,8017,7758,8018 ,0,0,0}, - {19319,19324,19318 ,8019,7758,8018 ,0,0,0}, {19319,19315,19326 ,8019,7884,7625 ,0,0,0}, - {19326,19324,19319 ,7625,7758,8019 ,0,0,0}, {19315,19316,16130 ,7884,8020,7625 ,0,0,0}, - {19315,16132,19326 ,7884,7625,7625 ,0,0,0}, {19327,16126,16127 ,8021,7625,726 ,0,0,0}, - {16127,16130,19317 ,726,7625,7257 ,0,0,0}, {16120,16121,19313 ,726,726,8017 ,0,0,0}, - {16124,19312,19314 ,7625,8022,7761 ,0,0,0}, {16115,19311,16114 ,7626,726,7626 ,0,0,0}, - {19310,16115,16118 ,726,7626,7626 ,0,0,0}, {16110,16095,16094 ,7625,726,726 ,0,0,0}, - {16113,16094,19308 ,7625,726,7625 ,0,0,0}, {16106,16097,16107 ,726,726,7625 ,0,0,0}, - {16097,16106,16104 ,726,726,726 ,0,0,0}, {16101,16106,16107 ,7625,726,7625 ,0,0,0}, - {16109,16107,16110 ,7625,7625,7625 ,0,0,0}, {16107,16097,16095 ,7625,726,726 ,0,0,0}, - {16098,16097,16104 ,726,726,726 ,0,0,0}, {16094,16113,16110 ,726,7625,7625 ,0,0,0}, - {16095,16110,16107 ,726,7625,7625 ,0,0,0}, {19308,16092,16114 ,7625,726,7626 ,0,0,0}, - {16092,19308,16094 ,726,7625,726 ,0,0,0}, {19311,16115,19310 ,726,7626,726 ,0,0,0}, - {19308,16114,19311 ,7625,7626,726 ,0,0,0}, {16118,16120,19309 ,7626,726,7880 ,0,0,0}, - {19313,16121,19314 ,8017,726,7761 ,0,0,0}, {19309,16120,19313 ,7880,726,8017 ,0,0,0}, - {19314,16121,16124 ,7761,726,7625 ,0,0,0}, {19312,16126,19327 ,8022,7625,8021 ,0,0,0}, - {19312,16124,16126 ,8022,7625,7625 ,0,0,0}, {16130,19316,19317 ,7625,8020,7257 ,0,0,0}, - {19317,19327,16127 ,7257,8021,726 ,0,0,0}, {16130,16132,19315 ,7625,7625,7884 ,0,0,0}, - {16074,19328,17643 ,8023,8024,8025 ,0,0,0}, {17385,17588,19329 ,8026,8027,8028 ,0,0,0}, - {17695,17641,19330 ,8029,8030,8031 ,0,0,0}, {17634,19331,17626 ,8032,8033,8034 ,0,0,0}, - {19332,19333,17593 ,8035,8036,8037 ,0,0,0}, {19334,19335,17633 ,8038,8039,8040 ,0,0,0}, - {19334,17635,19336 ,8038,8041,8042 ,0,0,0}, {19337,19338,17632 ,8043,8044,8045 ,0,0,0}, - {17632,17532,19337 ,8045,8046,8043 ,0,0,0}, {17529,19338,19339 ,8047,8044,8048 ,0,0,0}, - {19338,17529,17632 ,8044,8047,8045 ,0,0,0}, {19340,17530,19339 ,8049,8050,8048 ,0,0,0}, - {17529,19339,17530 ,8047,8048,8050 ,0,0,0}, {19340,16088,16089 ,8049,82,82 ,0,0,0}, - {16089,17530,19340 ,82,8050,8049 ,0,0,0}, {19331,17634,19333 ,8033,8032,8036 ,0,0,0}, - {19335,17532,17633 ,8039,8046,8040 ,0,0,0}, {19337,17532,19335 ,8043,8046,8039 ,0,0,0}, - {19329,17588,19341 ,8028,8027,8051 ,0,0,0}, {19336,17635,17626 ,8042,8041,8034 ,0,0,0}, - {19334,17633,17635 ,8038,8040,8041 ,0,0,0}, {19331,19336,17626 ,8033,8042,8034 ,0,0,0}, - {17593,19333,17634 ,8037,8036,8032 ,0,0,0}, {17385,19329,19332 ,8026,8028,8035 ,0,0,0}, - {19332,17593,17385 ,8035,8037,8026 ,0,0,0}, {17641,19328,19330 ,8030,8024,8031 ,0,0,0}, - {19341,17695,19330 ,8051,8029,8031 ,0,0,0}, {17588,17695,19341 ,8027,8029,8051 ,0,0,0}, - {16074,17643,16075 ,8023,8025,8052 ,0,0,0}, {19328,17641,17643 ,8024,8030,8025 ,0,0,0}, - {19334,16071,19335 ,726,726,726 ,0,0,0}, {19338,16067,16064 ,726,7661,726 ,0,0,0}, - {19331,19333,19328 ,726,7660,726 ,0,0,0}, {19336,16074,16073 ,726,726,726 ,0,0,0}, - {19330,19328,19329 ,7661,726,726 ,0,0,0}, {19329,19341,19330 ,726,7658,7661 ,0,0,0}, - {19329,19333,19332 ,726,7660,726 ,0,0,0}, {19328,16074,19331 ,726,726,726 ,0,0,0}, - {19333,19329,19328 ,7660,726,726 ,0,0,0}, {19336,16073,19334 ,726,726,726 ,0,0,0}, - {19331,16074,19336 ,726,726,726 ,0,0,0}, {19334,16073,16071 ,726,726,726 ,0,0,0}, - {19335,16069,19337 ,726,7658,726 ,0,0,0}, {19335,16071,16069 ,726,726,7658 ,0,0,0}, - {19338,19337,16067 ,726,726,7661 ,0,0,0}, {16069,16067,19337 ,7658,7661,726 ,0,0,0}, - {19338,16064,19339 ,726,726,726 ,0,0,0}, {16063,19340,19339 ,726,726,726 ,0,0,0}, - {19339,16064,16063 ,726,726,726 ,0,0,0}, {19340,16061,16088 ,726,726,726 ,0,0,0}, - {16061,19340,16063 ,726,726,726 ,0,0,0}, {16061,16060,16088 ,726,726,726 ,0,0,0}, - {16080,16076,16077 ,7659,726,726 ,0,0,0}, {16080,16086,16076 ,7659,726,726 ,0,0,0}, - {16083,16080,16082 ,726,7659,726 ,0,0,0}, {16083,16086,16080 ,726,726,7659 ,0,0,0}, - {16088,16060,16086 ,726,726,726 ,0,0,0}, {16076,16086,16060 ,726,726,726 ,0,0,0}, - {19342,19343,18870 ,726,8053,7583 ,0,0,0}, {18872,19344,18871 ,726,726,726 ,0,0,0}, - {19343,19345,18870 ,8053,7922,7583 ,0,0,0}, {19342,18870,19346 ,726,7583,5472 ,0,0,0}, - {18870,19347,19348 ,7583,7664,5488 ,0,0,0}, {19345,19347,18870 ,7922,7664,7583 ,0,0,0}, - {19349,19350,18870 ,7920,726,7583 ,0,0,0}, {19348,19351,18870 ,5488,5471,7583 ,0,0,0}, - {19352,19353,18872 ,7664,7583,726 ,0,0,0}, {18872,19354,19355 ,726,5488,7664 ,0,0,0}, - {19356,18872,19357 ,726,726,726 ,0,0,0}, {19358,19359,18872 ,7664,7664,726 ,0,0,0}, - {19360,19357,18872 ,726,726,726 ,0,0,0}, {18872,19356,19344 ,726,726,726 ,0,0,0}, - {19358,18872,19361 ,7664,726,7664 ,0,0,0}, {18872,19359,19360 ,726,7664,726 ,0,0,0}, - {18872,19353,19361 ,726,7583,7664 ,0,0,0}, {18872,19355,19362 ,726,7664,726 ,0,0,0}, - {18872,19362,19352 ,726,726,7664 ,0,0,0}, {19350,18872,18870 ,726,726,7583 ,0,0,0}, - {19350,19354,18872 ,726,5488,726 ,0,0,0}, {18870,19351,19349 ,7583,5471,7920 ,0,0,0}, - {17899,18871,19344 ,726,726,726 ,0,0,0}, {19346,18870,19363 ,5472,7583,7793 ,0,0,0}, - {19364,18870,18869 ,5471,7583,7664 ,0,0,0}, {18870,19364,19363 ,7583,5471,7793 ,0,0,0}, - {19364,18869,17844 ,5471,7664,7920 ,0,0,0}, {17451,17450,19362 ,8054,8055,8056 ,0,0,0}, - {19355,17460,17451 ,8057,8058,8054 ,0,0,0}, {19355,19354,17460 ,8057,8058,8058 ,0,0,0}, - {19362,19355,17451 ,8056,8057,8054 ,0,0,0}, {17450,17629,19352 ,8055,8059,8060 ,0,0,0}, - {17527,17471,19361 ,8061,8062,8063 ,0,0,0}, {19353,19352,17629 ,8064,8060,8059 ,0,0,0}, - {17629,17527,19353 ,8059,8061,8064 ,0,0,0}, {19361,19353,17527 ,8063,8064,8061 ,0,0,0}, - {17450,19352,19362 ,8055,8060,8056 ,0,0,0}, {19361,17471,19358 ,8063,8062,8065 ,0,0,0}, - {17470,19359,19358 ,8066,8067,8065 ,0,0,0}, {19358,17471,17470 ,8065,8062,8066 ,0,0,0}, - {19359,17470,17630 ,8067,8066,8068 ,0,0,0}, {17478,19360,17630 ,8069,8070,8068 ,0,0,0}, - {17478,17477,19357 ,8069,8071,8072 ,0,0,0}, {17478,19357,19360 ,8069,8072,8070 ,0,0,0}, - {19356,17492,19344 ,8073,8074,8075 ,0,0,0}, {19357,17477,19356 ,8072,8071,8073 ,0,0,0}, - {19356,17477,17492 ,8073,8071,8074 ,0,0,0}, {17492,17495,19344 ,8074,8075,8075 ,0,0,0}, - {19359,17630,19360 ,8067,8068,8070 ,0,0,0}, {17283,19354,19350 ,8076,8058,8077 ,0,0,0}, - {19354,17283,17460 ,8058,8076,8058 ,0,0,0}, {19349,17531,19350 ,8078,8079,8077 ,0,0,0}, - {17283,19350,17531 ,8076,8077,8079 ,0,0,0}, {19349,19351,17475 ,8078,8080,8081 ,0,0,0}, - {17475,17531,19349 ,8081,8079,8078 ,0,0,0}, {17476,19351,19348 ,8082,8080,8083 ,0,0,0}, - {19351,17476,17475 ,8080,8082,8081 ,0,0,0}, {19347,17653,19348 ,8084,8085,8083 ,0,0,0}, - {17476,19348,17653 ,8082,8083,8085 ,0,0,0}, {19347,19345,17421 ,8084,8086,8087 ,0,0,0}, - {17421,17653,19347 ,8087,8085,8084 ,0,0,0}, {17420,19345,19343 ,8088,8086,8089 ,0,0,0}, - {19345,17420,17421 ,8086,8088,8087 ,0,0,0}, {19342,17504,19343 ,8090,8091,8089 ,0,0,0}, - {17420,19343,17504 ,8088,8089,8091 ,0,0,0}, {19342,19346,17544 ,8090,8092,8093 ,0,0,0}, - {17544,17504,19342 ,8093,8091,8090 ,0,0,0}, {17545,19346,19363 ,8094,8092,8095 ,0,0,0}, - {19346,17545,17544 ,8092,8094,8093 ,0,0,0}, {17545,19363,17546 ,8094,8095,8096 ,0,0,0}, - {17546,19363,19364 ,8096,8095,8096 ,0,0,0}, {17851,19364,17844 ,8097,8098,8097 ,0,0,0}, - {19364,17852,17855 ,8098,8097,8098 ,0,0,0}, {17851,17852,19364 ,8097,8097,8098 ,0,0,0}, - {19364,17861,17866 ,8098,8098,8097 ,0,0,0}, {17855,17861,19364 ,8098,8098,8098 ,0,0,0}, - {19364,17870,17829 ,8098,8098,8097 ,0,0,0}, {17866,17870,19364 ,8097,8098,8098 ,0,0,0}, - {19364,17833,17832 ,8098,8097,8097 ,0,0,0}, {17829,17833,19364 ,8097,8097,8098 ,0,0,0}, - {19364,17832,17546 ,8098,8097,8098 ,0,0,0}, {17908,19344,17495 ,8099,8099,8099 ,0,0,0}, - {17908,17964,19344 ,8099,8099,8099 ,0,0,0}, {19344,17964,17950 ,8099,8099,8099 ,0,0,0}, - {17904,17910,19344 ,8099,8099,8099 ,0,0,0}, {17904,19344,17950 ,8099,8099,8099 ,0,0,0}, - {17910,17946,19344 ,8099,8099,8099 ,0,0,0}, {19344,17893,17892 ,8099,8099,8099 ,0,0,0}, - {17946,17893,19344 ,8099,8099,8099 ,0,0,0}, {17899,19344,17897 ,8099,8099,8099 ,0,0,0}, - {17892,17897,19344 ,8099,8099,8099 ,0,0,0}, {16037,19365,17687 ,1359,8100,4482 ,0,0,0}, - {19366,17686,19367 ,4475,8101,8102 ,0,0,0}, {17688,17685,19368 ,8103,8104,4478 ,0,0,0}, - {17519,19369,17511 ,8105,8106,8107 ,0,0,0}, {19370,19371,17691 ,4472,8108,8109 ,0,0,0}, - {19372,17548,19373 ,8110,8111,8112 ,0,0,0}, {17547,17509,19374 ,8113,8114,8115 ,0,0,0}, - {17522,17515,19375 ,8116,8117,8118 ,0,0,0}, {17550,19376,17515 ,8119,8120,8117 ,0,0,0}, - {17540,19377,19378 ,8121,8122,8123 ,0,0,0}, {17522,19379,17542 ,8116,8124,8125 ,0,0,0}, - {19380,17539,19378 ,8126,8127,8123 ,0,0,0}, {17540,19378,17539 ,8121,8123,8127 ,0,0,0}, - {19380,19381,17537 ,8126,8128,8129 ,0,0,0}, {17537,17539,19380 ,8129,8127,8126 ,0,0,0}, - {17534,19381,19382 ,8130,8128,8131 ,0,0,0}, {19381,17534,17537 ,8128,8130,8129 ,0,0,0}, - {19383,17535,19382 ,8132,8133,8131 ,0,0,0}, {17534,19382,17535 ,8130,8131,8133 ,0,0,0}, - {19383,16056,16057 ,8132,1435,1435 ,0,0,0}, {16057,17535,19383 ,1435,8133,8132 ,0,0,0}, - {19375,17515,19376 ,8118,8117,8120 ,0,0,0}, {19377,17542,19379 ,8122,8125,8124 ,0,0,0}, - {17542,19377,17540 ,8125,8122,8121 ,0,0,0}, {19375,19379,17522 ,8118,8124,8116 ,0,0,0}, - {19372,19376,17550 ,8110,8120,8119 ,0,0,0}, {17547,19374,19373 ,8113,8115,8112 ,0,0,0}, - {17547,19373,17548 ,8113,8112,8111 ,0,0,0}, {17550,17548,19372 ,8119,8111,8110 ,0,0,0}, - {17509,19384,19374 ,8114,8134,8115 ,0,0,0}, {19384,17509,17511 ,8134,8114,8107 ,0,0,0}, - {19371,19369,17519 ,8108,8106,8105 ,0,0,0}, {19369,19384,17511 ,8106,8134,8107 ,0,0,0}, - {17691,19371,17519 ,8109,8108,8105 ,0,0,0}, {17667,19366,19370 ,4474,4475,4472 ,0,0,0}, - {17667,19370,17691 ,4474,4472,8109 ,0,0,0}, {17686,17688,19367 ,8101,8103,8102 ,0,0,0}, - {17667,17686,19366 ,4474,8101,4475 ,0,0,0}, {17685,19365,19368 ,8104,8100,4478 ,0,0,0}, - {19367,17688,19368 ,8102,8103,4478 ,0,0,0}, {16037,17687,16035 ,1359,4482,1359 ,0,0,0}, - {19365,17685,17687 ,8100,8104,4482 ,0,0,0}, {16031,19369,19371 ,726,726,726 ,0,0,0}, - {19377,16038,19378 ,726,7626,7758 ,0,0,0}, {19383,19382,19381 ,7625,7625,726 ,0,0,0}, - {19379,19375,16018 ,8135,7628,7626 ,0,0,0}, {16018,16016,19379 ,7626,7626,8135 ,0,0,0}, - {16028,19373,19374 ,726,7627,726 ,0,0,0}, {16021,19372,16022 ,726,7628,726 ,0,0,0}, - {16025,19369,16031 ,726,726,726 ,0,0,0}, {19374,19384,16030 ,726,726,726 ,0,0,0}, - {19366,19367,19368 ,7628,7628,726 ,0,0,0}, {16034,16031,19371 ,726,726,726 ,0,0,0}, - {16037,16034,19365 ,726,726,726 ,0,0,0}, {19365,19366,19368 ,726,7628,726 ,0,0,0}, - {19365,16034,19366 ,726,726,7628 ,0,0,0}, {19371,19370,16034 ,726,726,726 ,0,0,0}, - {16034,19370,19366 ,726,726,7628 ,0,0,0}, {19369,16025,16030 ,726,726,726 ,0,0,0}, - {16034,16033,16031 ,726,726,726 ,0,0,0}, {16030,16028,19374 ,726,726,726 ,0,0,0}, - {16030,19384,19369 ,726,726,726 ,0,0,0}, {19372,19373,16022 ,7628,7627,726 ,0,0,0}, - {16022,19373,16028 ,726,7627,726 ,0,0,0}, {16019,19376,16021 ,726,726,726 ,0,0,0}, - {16021,19376,19372 ,726,726,7628 ,0,0,0}, {16019,16018,19375 ,726,7626,7628 ,0,0,0}, - {19375,19376,16019 ,7628,726,726 ,0,0,0}, {16016,16038,19377 ,7626,7626,726 ,0,0,0}, - {16016,19377,19379 ,7626,726,8135 ,0,0,0}, {16039,19378,16038 ,7626,7758,7626 ,0,0,0}, - {19380,19378,16042 ,8135,7758,7628 ,0,0,0}, {16039,16042,19378 ,7626,7628,7758 ,0,0,0}, - {16042,16044,19381 ,7628,726,726 ,0,0,0}, {19381,19380,16042 ,726,8135,7628 ,0,0,0}, - {19383,16044,16045 ,7625,726,7626 ,0,0,0}, {16044,19383,19381 ,726,7625,726 ,0,0,0}, - {16048,16051,16054 ,7626,726,7626 ,0,0,0}, {16045,16048,19383 ,7626,7626,7625 ,0,0,0}, - {16054,19383,16048 ,7626,7625,7626 ,0,0,0}, {16048,16050,16051 ,7626,7627,726 ,0,0,0}, - {19383,16054,16056 ,7625,7626,8135 ,0,0,0}, {15998,19385,17673 ,1359,8136,8137 ,0,0,0}, - {17656,17658,19386 ,8138,8139,8140 ,0,0,0}, {17675,17677,19387 ,8141,8142,8143 ,0,0,0}, - {17463,19388,17462 ,8144,8145,8146 ,0,0,0}, {19389,19390,17657 ,8147,8148,8149 ,0,0,0}, - {19391,19392,17655 ,8150,8151,8152 ,0,0,0}, {19391,17654,19393 ,8150,8153,8154 ,0,0,0}, - {19394,19395,17587 ,8155,8156,8157 ,0,0,0}, {17587,17586,19394 ,8157,8158,8155 ,0,0,0}, - {17501,19395,19396 ,8159,8156,8160 ,0,0,0}, {19395,17501,17587 ,8156,8159,8157 ,0,0,0}, - {19397,17500,19396 ,8161,8162,8160 ,0,0,0}, {17501,19396,17500 ,8159,8160,8162 ,0,0,0}, - {19397,16012,16013 ,8161,1435,1435 ,0,0,0}, {16013,17500,19397 ,1435,8162,8161 ,0,0,0}, - {19388,17463,19390 ,8145,8144,8148 ,0,0,0}, {19392,17586,17655 ,8151,8158,8152 ,0,0,0}, - {19394,17586,19392 ,8155,8158,8151 ,0,0,0}, {19386,17658,19398 ,8140,8139,8163 ,0,0,0}, - {19393,17654,17462 ,8154,8153,8146 ,0,0,0}, {19391,17655,17654 ,8150,8152,8153 ,0,0,0}, - {19388,19393,17462 ,8145,8154,8146 ,0,0,0}, {17657,19390,17463 ,8149,8148,8144 ,0,0,0}, - {17656,19386,19389 ,8138,8140,8147 ,0,0,0}, {19389,17657,17656 ,8147,8149,8138 ,0,0,0}, - {17677,19385,19387 ,8142,8136,8143 ,0,0,0}, {19398,17675,19387 ,8163,8141,8143 ,0,0,0}, - {17658,17675,19398 ,8139,8141,8163 ,0,0,0}, {15998,17673,15999 ,1359,8137,1359 ,0,0,0}, - {19385,17677,17673 ,8136,8142,8137 ,0,0,0}, {19395,19390,19389 ,726,7661,7661 ,0,0,0}, - {19391,19393,19394 ,7661,7658,726 ,0,0,0}, {19394,19392,19391 ,726,726,7661 ,0,0,0}, - {19388,19390,19394 ,7658,7661,726 ,0,0,0}, {19388,19394,19393 ,7658,726,7658 ,0,0,0}, - {19389,19396,19395 ,7661,726,726 ,0,0,0}, {19390,19395,19394 ,7661,726,726 ,0,0,0}, - {19396,19389,19386 ,726,7661,7658 ,0,0,0}, {19386,19398,19397 ,7658,7661,726 ,0,0,0}, - {19397,19396,19386 ,726,726,7658 ,0,0,0}, {16012,19398,19387 ,726,7661,7658 ,0,0,0}, - {19398,16012,19397 ,7661,726,726 ,0,0,0}, {15997,16006,15998 ,7658,726,726 ,0,0,0}, - {19385,16010,19387 ,7658,7660,7658 ,0,0,0}, {16004,15997,15995 ,726,7658,726 ,0,0,0}, - {15985,15984,15991 ,726,726,726 ,0,0,0}, {16001,15993,16000 ,726,726,726 ,0,0,0}, - {15991,15988,15987 ,726,726,726 ,0,0,0}, {15991,15984,16000 ,726,726,726 ,0,0,0}, - {15985,15991,15987 ,726,726,726 ,0,0,0}, {15995,15993,16001 ,726,726,726 ,0,0,0}, - {15993,15991,16000 ,726,726,726 ,0,0,0}, {16006,15997,16004 ,726,7658,726 ,0,0,0}, - {16004,15995,16001 ,726,726,726 ,0,0,0}, {15998,16007,19385 ,726,726,7658 ,0,0,0}, - {15998,16006,16007 ,726,726,726 ,0,0,0}, {19387,16010,16012 ,7658,7660,726 ,0,0,0}, - {16007,16010,19385 ,726,7660,7658 ,0,0,0}, {19399,19400,18867 ,726,726,7664 ,0,0,0}, - {19401,19399,18867 ,726,726,7664 ,0,0,0}, {19401,18867,19402 ,726,7664,726 ,0,0,0}, - {19403,18867,19400 ,726,7664,726 ,0,0,0}, {19404,19405,18867 ,726,726,7664 ,0,0,0}, - {19404,18867,19403 ,726,7664,726 ,0,0,0}, {19406,18867,18865 ,726,7664,726 ,0,0,0}, - {19402,18867,19406 ,726,7664,726 ,0,0,0}, {19407,18867,19405 ,726,7664,726 ,0,0,0}, - {18867,19407,19408 ,7664,726,726 ,0,0,0}, {19406,18865,19409 ,726,726,726 ,0,0,0}, - {19410,18867,19408 ,726,7664,726 ,0,0,0}, {19411,19409,18865 ,7583,726,726 ,0,0,0}, - {18865,19412,19411 ,726,7664,7583 ,0,0,0}, {18867,19410,19413 ,7664,726,726 ,0,0,0}, - {18867,19413,19414 ,7664,726,726 ,0,0,0}, {19415,19412,18865 ,726,7664,726 ,0,0,0}, - {19416,19417,18865 ,726,726,726 ,0,0,0}, {19417,19415,18865 ,726,726,726 ,0,0,0}, - {19418,18865,19419 ,726,726,726 ,0,0,0}, {19418,19416,18865 ,726,726,726 ,0,0,0}, - {18868,19414,17805 ,7664,726,726 ,0,0,0}, {19414,18868,18867 ,726,7664,7664 ,0,0,0}, - {19419,18865,19420 ,726,726,726 ,0,0,0}, {19421,18865,18866 ,726,726,7664 ,0,0,0}, - {18865,19421,19420 ,726,726,726 ,0,0,0}, {19421,18866,17729 ,726,7664,5488 ,0,0,0}, - {17517,17510,19399 ,8164,8165,8166 ,0,0,0}, {19401,17518,17517 ,8167,8168,8164 ,0,0,0}, - {19401,19402,17518 ,8167,8168,8168 ,0,0,0}, {19399,19401,17517 ,8166,8167,8164 ,0,0,0}, - {17510,17651,19400 ,8165,8169,8170 ,0,0,0}, {17549,17551,19404 ,8171,8172,8173 ,0,0,0}, - {19403,19400,17651 ,8174,8170,8169 ,0,0,0}, {17651,17549,19403 ,8169,8171,8174 ,0,0,0}, - {19404,19403,17549 ,8173,8174,8171 ,0,0,0}, {17510,19400,19399 ,8165,8170,8166 ,0,0,0}, - {19404,17551,19405 ,8173,8172,8175 ,0,0,0}, {17514,19407,19405 ,8176,8177,8175 ,0,0,0}, - {19405,17551,17514 ,8175,8172,8176 ,0,0,0}, {19407,17514,17516 ,8177,8176,8178 ,0,0,0}, - {17521,19408,17516 ,8179,8180,8178 ,0,0,0}, {17521,17553,19410 ,8179,8181,8182 ,0,0,0}, - {17521,19410,19408 ,8179,8182,8180 ,0,0,0}, {19413,17555,19414 ,8183,8184,8185 ,0,0,0}, - {19410,17553,19413 ,8182,8181,8183 ,0,0,0}, {19413,17553,17555 ,8183,8181,8184 ,0,0,0}, - {17555,17554,19414 ,8184,8185,8185 ,0,0,0}, {19407,17516,19408 ,8177,8178,8180 ,0,0,0}, - {17513,19402,19406 ,8186,8168,8187 ,0,0,0}, {19402,17513,17518 ,8168,8186,8168 ,0,0,0}, - {19409,17512,19406 ,8188,8189,8187 ,0,0,0}, {17513,19406,17512 ,8186,8187,8189 ,0,0,0}, - {19409,19411,17679 ,8188,8190,8191 ,0,0,0}, {17679,17512,19409 ,8191,8189,8188 ,0,0,0}, - {17507,19411,19412 ,8192,8190,8193 ,0,0,0}, {19411,17507,17679 ,8190,8192,8191 ,0,0,0}, - {19415,17508,19412 ,8194,8195,8193 ,0,0,0}, {17507,19412,17508 ,8192,8193,8195 ,0,0,0}, - {19415,19417,17581 ,8194,8196,8197 ,0,0,0}, {17581,17508,19415 ,8197,8195,8194 ,0,0,0}, - {17582,19417,19416 ,8198,8196,8199 ,0,0,0}, {19417,17582,17581 ,8196,8198,8197 ,0,0,0}, - {19418,17325,19416 ,8200,8201,8199 ,0,0,0}, {17582,19416,17325 ,8198,8199,8201 ,0,0,0}, - {19418,19419,17328 ,8200,8202,8203 ,0,0,0}, {17328,17325,19418 ,8203,8201,8200 ,0,0,0}, - {17329,19419,19420 ,8204,8202,8205 ,0,0,0}, {19419,17329,17328 ,8202,8204,8203 ,0,0,0}, - {17329,19420,17330 ,8204,8205,8206 ,0,0,0}, {17330,19420,19421 ,8206,8205,8206 ,0,0,0}, - {17730,19421,17729 ,8207,8207,8207 ,0,0,0}, {19421,17760,17763 ,8207,8207,8207 ,0,0,0}, - {17730,17760,19421 ,8207,8207,8207 ,0,0,0}, {19421,17769,17774 ,8207,8207,8207 ,0,0,0}, - {17763,17769,19421 ,8207,8207,8207 ,0,0,0}, {19421,17778,17708 ,8207,8207,8207 ,0,0,0}, - {17774,17778,19421 ,8207,8207,8207 ,0,0,0}, {19421,17711,17710 ,8207,8207,8207 ,0,0,0}, - {17708,17711,19421 ,8207,8207,8207 ,0,0,0}, {19421,17710,17330 ,8207,8207,8207 ,0,0,0}, - {17820,19414,17554 ,8208,8208,8208 ,0,0,0}, {17820,17871,19414 ,8208,8208,8208 ,0,0,0}, - {19414,17871,17857 ,8208,8208,8208 ,0,0,0}, {17814,17807,19414 ,8208,8208,8208 ,0,0,0}, - {17814,19414,17857 ,8208,8208,8208 ,0,0,0}, {17807,17853,19414 ,8208,8208,8208 ,0,0,0}, - {19414,17845,17799 ,8208,8208,8208 ,0,0,0}, {17853,17845,19414 ,8208,8208,8208 ,0,0,0}, - {17805,19414,17801 ,8208,8208,8208 ,0,0,0}, {17799,17801,19414 ,8208,8208,8208 ,0,0,0}, - {15961,19422,17317 ,1711,8209,4414 ,0,0,0}, {19423,17580,19424 ,8210,8211,8212 ,0,0,0}, - {17565,17318,19425 ,8213,8214,4410 ,0,0,0}, {17579,19426,17309 ,4402,8215,8216 ,0,0,0}, - {19427,19428,17578 ,8217,8218,8219 ,0,0,0}, {19429,17339,19430 ,8220,8221,8222 ,0,0,0}, - {17338,17564,19431 ,8223,8224,8225 ,0,0,0}, {17312,17311,19432 ,8226,8227,8228 ,0,0,0}, - {17334,19433,17311 ,8229,8230,8227 ,0,0,0}, {17315,19434,19435 ,8231,8232,8233 ,0,0,0}, - {17312,19436,17314 ,8226,8234,8235 ,0,0,0}, {19437,17331,19435 ,8236,8237,8233 ,0,0,0}, - {17315,19435,17331 ,8231,8233,8237 ,0,0,0}, {19437,19438,17319 ,8236,8238,8239 ,0,0,0}, - {17319,17331,19437 ,8239,8237,8236 ,0,0,0}, {17567,19438,19439 ,8240,8238,8241 ,0,0,0}, - {19438,17567,17319 ,8238,8240,8239 ,0,0,0}, {19440,17327,19439 ,8242,8243,8241 ,0,0,0}, - {17567,19439,17327 ,8240,8241,8243 ,0,0,0}, {19440,15980,15981 ,8242,1790,1790 ,0,0,0}, - {15981,17327,19440 ,1790,8243,8242 ,0,0,0}, {19432,17311,19433 ,8228,8227,8230 ,0,0,0}, - {19434,17314,19436 ,8232,8235,8234 ,0,0,0}, {17314,19434,17315 ,8235,8232,8231 ,0,0,0}, - {19432,19436,17312 ,8228,8234,8226 ,0,0,0}, {19429,19433,17334 ,8220,8230,8229 ,0,0,0}, - {17338,19431,19430 ,8223,8225,8222 ,0,0,0}, {17338,19430,17339 ,8223,8222,8221 ,0,0,0}, - {17334,17339,19429 ,8229,8221,8220 ,0,0,0}, {17564,19441,19431 ,8224,8244,8225 ,0,0,0}, - {19441,17564,17309 ,8244,8224,8216 ,0,0,0}, {19428,19426,17579 ,8218,8215,4402 ,0,0,0}, - {19426,19441,17309 ,8215,8244,8216 ,0,0,0}, {17578,19428,17579 ,8219,8218,4402 ,0,0,0}, - {17279,19423,19427 ,8245,8210,8217 ,0,0,0}, {17279,19427,17578 ,8245,8217,8219 ,0,0,0}, - {17580,17565,19424 ,8211,8213,8212 ,0,0,0}, {17279,17580,19423 ,8245,8211,8210 ,0,0,0}, - {17318,19422,19425 ,8214,8209,4410 ,0,0,0}, {19424,17565,19425 ,8212,8213,4410 ,0,0,0}, - {15961,17317,15959 ,1711,4414,1711 ,0,0,0}, {19422,17318,17317 ,8209,8214,4414 ,0,0,0}, - {19427,19432,19433 ,726,726,7626 ,0,0,0}, {19441,19430,19431 ,726,726,726 ,0,0,0}, - {19429,19441,19426 ,726,726,726 ,0,0,0}, {19428,19429,19426 ,726,726,726 ,0,0,0}, - {19428,19433,19429 ,726,7626,726 ,0,0,0}, {19441,19429,19430 ,726,726,726 ,0,0,0}, - {19428,19427,19433 ,726,726,7626 ,0,0,0}, {19423,19436,19432 ,726,726,726 ,0,0,0}, - {19427,19423,19432 ,726,726,726 ,0,0,0}, {19436,19424,19434 ,726,726,7626 ,0,0,0}, - {19424,19436,19423 ,726,726,726 ,0,0,0}, {19435,19434,19425 ,7628,7626,726 ,0,0,0}, - {19424,19425,19434 ,726,726,7626 ,0,0,0}, {19422,19437,19435 ,726,726,7628 ,0,0,0}, - {19435,19425,19422 ,7628,726,726 ,0,0,0}, {19437,15961,19438 ,726,726,726 ,0,0,0}, - {15961,19437,19422 ,726,726,726 ,0,0,0}, {19439,19438,15958 ,7625,726,726 ,0,0,0}, - {15961,15958,19438 ,726,726,726 ,0,0,0}, {19439,15958,15957 ,7625,726,726 ,0,0,0}, - {19440,19439,15957 ,726,7625,726 ,0,0,0}, {15957,15955,19440 ,726,726,726 ,0,0,0}, - {15949,15980,15955 ,726,726,726 ,0,0,0}, {19440,15955,15980 ,726,726,726 ,0,0,0}, - {15952,15946,15974 ,726,726,7625 ,0,0,0}, {15949,15954,15978 ,726,726,726 ,0,0,0}, - {15943,15968,15969 ,7626,726,726 ,0,0,0}, {15969,15972,15945 ,726,726,726 ,0,0,0}, - {15968,15942,15966 ,726,7625,7625 ,0,0,0}, {15942,15963,15966 ,7625,726,7625 ,0,0,0}, - {15940,15963,15942 ,726,726,7625 ,0,0,0}, {15940,15962,15963 ,726,726,726 ,0,0,0}, - {15945,15943,15969 ,726,7626,726 ,0,0,0}, {15942,15968,15943 ,7625,726,7626 ,0,0,0}, - {15972,15974,15946 ,726,7625,726 ,0,0,0}, {15945,15972,15946 ,726,726,726 ,0,0,0}, - {15952,15975,15954 ,726,726,726 ,0,0,0}, {15952,15974,15975 ,726,7625,726 ,0,0,0}, - {15949,15978,15980 ,726,726,726 ,0,0,0}, {15975,15978,15954 ,726,726,726 ,0,0,0}, - {15922,19442,17591 ,1711,8246,8247 ,0,0,0}, {17650,17664,19443 ,8248,8249,8250 ,0,0,0}, - {17663,17592,19444 ,8251,8252,8253 ,0,0,0}, {17503,19445,17502 ,8254,8255,8256 ,0,0,0}, - {19446,19447,17684 ,8257,8258,8259 ,0,0,0}, {19448,19449,17682 ,8260,8261,8262 ,0,0,0}, - {19448,17681,19450 ,8260,8263,8264 ,0,0,0}, {19451,19452,17584 ,8265,8266,8267 ,0,0,0}, - {17584,17585,19451 ,8267,8268,8265 ,0,0,0}, {17680,19452,19453 ,8269,8266,8270 ,0,0,0}, - {19452,17680,17584 ,8266,8269,8267 ,0,0,0}, {19454,17583,19453 ,8271,8272,8270 ,0,0,0}, - {17680,19453,17583 ,8269,8270,8272 ,0,0,0}, {19454,15936,15937 ,8271,1790,1790 ,0,0,0}, - {15937,17583,19454 ,1790,8272,8271 ,0,0,0}, {19445,17503,19447 ,8255,8254,8258 ,0,0,0}, - {19449,17585,17682 ,8261,8268,8262 ,0,0,0}, {19451,17585,19449 ,8265,8268,8261 ,0,0,0}, - {19443,17664,19455 ,8250,8249,8273 ,0,0,0}, {19450,17681,17502 ,8264,8263,8256 ,0,0,0}, - {19448,17682,17681 ,8260,8262,8263 ,0,0,0}, {19445,19450,17502 ,8255,8264,8256 ,0,0,0}, - {17684,19447,17503 ,8259,8258,8254 ,0,0,0}, {17650,19443,19446 ,8248,8250,8257 ,0,0,0}, - {19446,17684,17650 ,8257,8259,8248 ,0,0,0}, {17592,19442,19444 ,8252,8246,8253 ,0,0,0}, - {19455,17663,19444 ,8273,8251,8253 ,0,0,0}, {17664,17663,19455 ,8249,8251,8273 ,0,0,0}, - {15922,17591,15923 ,1711,8247,1711 ,0,0,0}, {19442,17592,17591 ,8246,8252,8247 ,0,0,0}, - {15936,19454,19453 ,726,7658,726 ,0,0,0}, {19455,15911,19443 ,726,726,726 ,0,0,0}, - {15934,19453,19452 ,7660,726,7660 ,0,0,0}, {19448,15930,19449 ,7660,726,7660 ,0,0,0}, - {15931,15934,19451 ,7660,7660,7583 ,0,0,0}, {15924,19445,19447 ,7660,7661,7661 ,0,0,0}, - {15928,19448,19450 ,726,7660,7658 ,0,0,0}, {15909,19443,15911 ,726,726,726 ,0,0,0}, - {19447,19446,15908 ,7661,726,726 ,0,0,0}, {19442,15917,15915 ,726,726,726 ,0,0,0}, - {19444,15912,19455 ,726,726,726 ,0,0,0}, {15922,15921,15917 ,726,726,726 ,0,0,0}, - {15919,15917,15921 ,726,726,726 ,0,0,0}, {15917,19442,15922 ,726,726,726 ,0,0,0}, - {19444,15915,15912 ,726,726,726 ,0,0,0}, {19444,19442,15915 ,726,726,726 ,0,0,0}, - {19446,19443,15909 ,726,726,726 ,0,0,0}, {15911,19455,15912 ,726,726,726 ,0,0,0}, - {15908,15924,19447 ,726,7660,7661 ,0,0,0}, {15909,15908,19446 ,726,726,726 ,0,0,0}, - {19450,19445,15925 ,7658,7661,7659 ,0,0,0}, {15925,19445,15924 ,7659,7661,7660 ,0,0,0}, - {15928,19450,15925 ,726,7658,7659 ,0,0,0}, {15931,19449,15930 ,7660,7660,726 ,0,0,0}, - {19448,15928,15930 ,7660,726,726 ,0,0,0}, {15934,19452,19451 ,7660,7660,7583 ,0,0,0}, - {15931,19451,19449 ,7660,7583,7660 ,0,0,0}, {15934,15936,19453 ,7660,726,726 ,0,0,0}, - {17689,15881,19456 ,8274,8275,8276 ,0,0,0}, {17690,17666,19457 ,8277,8278,8279 ,0,0,0}, - {19458,17666,17683 ,8280,8278,8281 ,0,0,0}, {19459,19460,17590 ,8282,8283,8284 ,0,0,0}, - {19461,17662,17661 ,8285,8286,8287 ,0,0,0}, {17671,17659,19462 ,8288,8289,8290 ,0,0,0}, - {17670,19463,19464 ,8291,8292,8293 ,0,0,0}, {17693,19465,17676 ,8294,8295,8296 ,0,0,0}, - {19466,19467,17672 ,1631,8297,1631 ,0,0,0}, {19468,19469,17674 ,8298,8299,8300 ,0,0,0}, - {19468,17694,19470 ,8298,8301,8302 ,0,0,0}, {19471,19472,17669 ,8303,8304,8305 ,0,0,0}, - {19471,17668,19469 ,8303,8306,8299 ,0,0,0}, {17607,19472,19473 ,8307,8304,8308 ,0,0,0}, - {19472,17607,17669 ,8304,8307,8305 ,0,0,0}, {19474,17648,19473 ,8309,8310,8308 ,0,0,0}, - {17607,19473,17648 ,8307,8308,8310 ,0,0,0}, {17589,19474,17642 ,8311,8309,8312 ,0,0,0}, - {17589,17648,19474 ,8311,8310,8309 ,0,0,0}, {17640,17642,19475 ,8313,8312,8314 ,0,0,0}, - {19474,19475,17642 ,8309,8314,8312 ,0,0,0}, {19476,15905,17640 ,8315,126,8313 ,0,0,0}, - {17640,19475,19476 ,8313,8314,8315 ,0,0,0}, {15903,15905,19476 ,126,126,8315 ,0,0,0}, - {17668,17674,19469 ,8306,8300,8299 ,0,0,0}, {19471,17669,17668 ,8303,8305,8306 ,0,0,0}, - {17694,17676,19470 ,8301,8296,8302 ,0,0,0}, {19468,17674,17694 ,8298,8300,8301 ,0,0,0}, - {19467,19465,17693 ,8297,8295,8294 ,0,0,0}, {19465,19470,17676 ,8295,8302,8296 ,0,0,0}, - {17671,19466,17672 ,8288,1631,1631 ,0,0,0}, {17672,19467,17693 ,1631,8297,8294 ,0,0,0}, - {17659,19464,19462 ,8289,8293,8290 ,0,0,0}, {17671,19462,19466 ,8288,8290,1631 ,0,0,0}, - {17670,17692,19463 ,8291,8316,8292 ,0,0,0}, {17659,17670,19464 ,8289,8291,8293 ,0,0,0}, - {17590,19460,17692 ,8284,8283,8316 ,0,0,0}, {19463,17692,19460 ,8292,8316,8283 ,0,0,0}, - {19461,19459,17662 ,8285,8282,8286 ,0,0,0}, {19459,17590,17662 ,8282,8284,8286 ,0,0,0}, - {17690,19477,17661 ,8277,8317,8287 ,0,0,0}, {19477,19461,17661 ,8317,8285,8287 ,0,0,0}, - {17666,19478,19457 ,8278,8318,8279 ,0,0,0}, {17690,19457,19477 ,8277,8279,8317 ,0,0,0}, - {19458,17683,19456 ,8280,8281,8276 ,0,0,0}, {19478,17666,19458 ,8318,8278,8280 ,0,0,0}, - {15881,17689,15880 ,8275,8274,4114 ,0,0,0}, {19456,17683,17689 ,8276,8281,8274 ,0,0,0}, - {19468,19479,19469 ,726,726,726 ,0,0,0}, {19480,15854,19476 ,726,726,726 ,0,0,0}, - {19481,19472,19482 ,726,726,726 ,0,0,0}, {15885,15839,15838 ,726,726,7661 ,0,0,0}, - {15894,15896,15848 ,726,726,726 ,0,0,0}, {19483,19475,19474 ,726,726,726 ,0,0,0}, - {15899,15902,15853 ,726,726,726 ,0,0,0}, {15903,15854,15902 ,726,726,726 ,0,0,0}, - {15851,15849,15900 ,7658,726,726 ,0,0,0}, {15899,15853,15851 ,726,726,7658 ,0,0,0}, - {19483,19480,19475 ,726,726,726 ,0,0,0}, {15896,15897,15849 ,726,726,726 ,0,0,0}, - {15894,15848,15845 ,726,726,726 ,0,0,0}, {15890,15843,15888 ,726,726,726 ,0,0,0}, - {15891,15845,15843 ,726,726,726 ,0,0,0}, {15839,15885,15888 ,726,726,726 ,0,0,0}, - {19481,19474,19473 ,726,726,726 ,0,0,0}, {19469,19484,19471 ,726,7661,726 ,0,0,0}, - {19471,19484,19482 ,726,7661,726 ,0,0,0}, {15818,15858,15857 ,7658,726,7658 ,0,0,0}, - {15884,15838,15818 ,726,7661,7658 ,0,0,0}, {19485,19479,19470 ,726,726,726 ,0,0,0}, - {15858,15822,15859 ,726,7658,726 ,0,0,0}, {15861,15823,15824 ,7661,7658,726 ,0,0,0}, - {19465,19467,19486 ,726,7661,726 ,0,0,0}, {19465,19486,19485 ,726,726,726 ,0,0,0}, - {19467,19466,19487 ,7661,7658,7658 ,0,0,0}, {15865,15864,15824 ,726,726,726 ,0,0,0}, - {15828,15867,15825 ,726,7583,726 ,0,0,0}, {19488,19489,19464 ,726,726,726 ,0,0,0}, - {19489,19487,19462 ,726,7658,726 ,0,0,0}, {15877,15831,15834 ,7664,726,7664 ,0,0,0}, - {19488,19464,19463 ,726,726,7661 ,0,0,0}, {19490,19463,19460 ,726,7661,7664 ,0,0,0}, - {15837,15881,15879 ,726,726,7664 ,0,0,0}, {19491,19456,15837 ,7664,726,726 ,0,0,0}, - {19490,19459,19492 ,726,7583,726 ,0,0,0}, {19458,19493,19478 ,7664,7664,726 ,0,0,0}, - {15859,15822,15823 ,726,7658,7658 ,0,0,0}, {19457,19478,19494 ,7664,726,7664 ,0,0,0}, - {19493,19494,19478 ,7664,7664,726 ,0,0,0}, {19458,19456,19491 ,7664,726,7664 ,0,0,0}, - {19458,19491,19493 ,7664,7664,7664 ,0,0,0}, {19495,19492,19461 ,7664,726,7583 ,0,0,0}, - {19495,19461,19477 ,7664,7583,7664 ,0,0,0}, {15881,15837,19456 ,726,726,726 ,0,0,0}, - {15830,15831,15873 ,726,726,726 ,0,0,0}, {15828,15830,15870 ,726,726,7664 ,0,0,0}, - {19495,19477,19494 ,7664,7664,7664 ,0,0,0}, {19477,19457,19494 ,7664,7664,7664 ,0,0,0}, - {19459,19461,19492 ,7583,7583,726 ,0,0,0}, {19460,19459,19490 ,7664,7583,726 ,0,0,0}, - {19488,19463,19490 ,726,7661,726 ,0,0,0}, {19462,19464,19489 ,726,726,726 ,0,0,0}, - {19466,19462,19487 ,7658,726,7658 ,0,0,0}, {19486,19467,19487 ,726,7661,7658 ,0,0,0}, - {19470,19465,19485 ,726,726,726 ,0,0,0}, {19468,19470,19479 ,726,726,726 ,0,0,0}, - {19484,19469,19479 ,7661,726,726 ,0,0,0}, {19472,19471,19482 ,726,726,726 ,0,0,0}, - {19473,19472,19481 ,726,726,726 ,0,0,0}, {19483,19474,19481 ,726,726,726 ,0,0,0}, - {19476,19475,19480 ,726,726,726 ,0,0,0}, {15903,19476,15854 ,726,726,726 ,0,0,0}, - {15853,15902,15854 ,726,726,726 ,0,0,0}, {15900,15899,15851 ,726,726,7658 ,0,0,0}, - {15897,15900,15849 ,726,726,726 ,0,0,0}, {15848,15896,15849 ,726,726,726 ,0,0,0}, - {15891,15894,15845 ,726,726,726 ,0,0,0}, {15890,15891,15843 ,726,726,726 ,0,0,0}, - {15839,15888,15843 ,726,726,726 ,0,0,0}, {15884,15885,15838 ,726,726,7661 ,0,0,0}, - {15857,15884,15818 ,7658,726,7658 ,0,0,0}, {15822,15858,15818 ,7658,726,7658 ,0,0,0}, - {15864,15861,15824 ,726,7661,726 ,0,0,0}, {15861,15859,15823 ,7661,726,7658 ,0,0,0}, - {15825,15865,15824 ,726,726,726 ,0,0,0}, {15828,15870,15867 ,726,7664,7583 ,0,0,0}, - {15825,15867,15865 ,726,7583,726 ,0,0,0}, {15830,15871,15870 ,726,7664,7664 ,0,0,0}, - {15873,15831,15877 ,726,726,7664 ,0,0,0}, {15871,15830,15873 ,7664,726,726 ,0,0,0}, - {15877,15834,15879 ,7664,7664,7664 ,0,0,0}, {15837,15879,15834 ,726,7664,7664 ,0,0,0}, - {19496,19497,15821 ,726,726,726 ,0,0,0}, {15840,15842,15850 ,726,726,726 ,0,0,0}, - {15819,15840,15855 ,726,726,726 ,0,0,0}, {15821,15820,19496 ,726,726,726 ,0,0,0}, - {15846,15847,15850 ,726,726,726 ,0,0,0}, {15841,15844,15842 ,726,726,726 ,0,0,0}, - {15846,15850,15844 ,726,726,726 ,0,0,0}, {15842,15844,15850 ,726,726,726 ,0,0,0}, - {15850,15852,15840 ,726,726,726 ,0,0,0}, {19496,15819,15855 ,726,726,726 ,0,0,0}, - {15855,15840,15852 ,726,726,726 ,0,0,0}, {15821,19497,19498 ,726,726,726 ,0,0,0}, - {19496,15820,15819 ,726,726,726 ,0,0,0}, {15826,19498,19499 ,726,726,726 ,0,0,0}, - {19498,15826,15821 ,726,726,726 ,0,0,0}, {19499,15829,15827 ,726,726,7658 ,0,0,0}, - {15826,19499,15827 ,726,726,7658 ,0,0,0}, {19500,15829,19499 ,726,726,726 ,0,0,0}, - {15829,19501,15832 ,726,726,7661 ,0,0,0}, {19501,15829,19500 ,726,726,726 ,0,0,0}, - {19501,19502,15832 ,726,726,7661 ,0,0,0}, {15833,19502,15835 ,726,726,7661 ,0,0,0}, - {15833,15832,19502 ,726,7661,726 ,0,0,0}, {15835,19503,19504 ,7661,726,726 ,0,0,0}, - {19502,19503,15835 ,726,726,7661 ,0,0,0}, {19505,15836,19504 ,726,7658,726 ,0,0,0}, - {15835,19504,15836 ,7661,726,7658 ,0,0,0}, {19506,19507,19508 ,726,726,7660 ,0,0,0}, - {19508,19509,19506 ,7660,726,726 ,0,0,0}, {19507,19510,19511 ,726,726,7658 ,0,0,0}, - {19507,19505,19508 ,726,726,7660 ,0,0,0}, {19507,19512,19505 ,726,7661,726 ,0,0,0}, - {19507,19506,19510 ,726,726,726 ,0,0,0}, {19505,19512,15836 ,726,7661,7658 ,0,0,0}, - {19512,15837,15836 ,8319,81,8320 ,0,0,0}, {19510,19495,19511 ,8321,8322,8323 ,0,0,0}, - {19507,19494,19493 ,8324,8325,8326 ,0,0,0}, {19508,19505,19488 ,8327,8328,8329 ,0,0,0}, - {19506,19509,19490 ,8330,8331,8332 ,0,0,0}, {19502,19486,19503 ,8333,8334,8335 ,0,0,0}, - {19487,19504,19503 ,8336,8337,8335 ,0,0,0}, {19500,19484,19501 ,7530,8338,8339 ,0,0,0}, - {19479,19502,19501 ,8340,8333,8339 ,0,0,0}, {19499,19481,19482 ,8341,8342,8343 ,0,0,0}, - {19482,19500,19499 ,8343,7530,8341 ,0,0,0}, {19481,19498,19483 ,8342,8344,8345 ,0,0,0}, - {19498,19481,19499 ,8344,8342,8341 ,0,0,0}, {19480,19483,19497 ,8346,8345,8347 ,0,0,0}, - {19498,19497,19483 ,8344,8347,8345 ,0,0,0}, {15855,19480,19496 ,96,8346,8348 ,0,0,0}, - {19480,19497,19496 ,8346,8347,8348 ,0,0,0}, {15854,19480,15855 ,96,8346,96 ,0,0,0}, - {19479,19501,19484 ,8340,8339,8338 ,0,0,0}, {19482,19484,19500 ,8343,8338,7530 ,0,0,0}, - {19485,19486,19502 ,8349,8334,8333 ,0,0,0}, {19479,19485,19502 ,8340,8349,8333 ,0,0,0}, - {19489,19504,19487 ,8350,8337,8336 ,0,0,0}, {19486,19487,19503 ,8334,8336,8335 ,0,0,0}, - {19488,19505,19489 ,8329,8328,8350 ,0,0,0}, {19504,19489,19505 ,8337,8350,8328 ,0,0,0}, - {19490,19509,19488 ,8332,8331,8329 ,0,0,0}, {19509,19508,19488 ,8331,8327,8329 ,0,0,0}, - {19492,19510,19506 ,7516,8321,8330 ,0,0,0}, {19492,19506,19490 ,7516,8330,8332 ,0,0,0}, - {19495,19494,19511 ,8322,8325,8323 ,0,0,0}, {19492,19495,19510 ,7516,8322,8321 ,0,0,0}, - {19507,19493,19512 ,8324,8326,8319 ,0,0,0}, {19511,19494,19507 ,8323,8325,8324 ,0,0,0}, - {15837,19512,19491 ,81,8319,8351 ,0,0,0}, {19512,19493,19491 ,8319,8326,8351 ,0,0,0} -// X-Ufo 8ZollPropeller.prt - , {19513,19514,19515 ,8352,8353,8354 ,0,0,0}, {19513,19516,19517 ,8352,8355,8356 ,0,0,0}, - {19517,19514,19513 ,8356,8353,8352 ,0,0,0}, {19518,19516,19519 ,8357,8355,8358 ,0,0,0}, - {19516,19518,19517 ,8355,8357,8356 ,0,0,0}, {19520,19521,19522 ,8359,8360,8361 ,0,0,0}, - {19518,19519,19521 ,8357,8358,8360 ,0,0,0}, {19523,19524,19520 ,8362,3877,8359 ,0,0,0}, - {19523,19525,19524 ,8362,4346,3877 ,0,0,0}, {19523,19520,19522 ,8362,8359,8361 ,0,0,0}, - {19521,19519,19522 ,8360,8358,8361 ,0,0,0}, {19526,19515,19514 ,8363,8354,8353 ,0,0,0}, - {19527,19526,19528 ,8364,8363,8365 ,0,0,0}, {19526,19527,19515 ,8363,8364,8354 ,0,0,0}, - {19529,19530,19528 ,8366,8367,8365 ,0,0,0}, {19527,19528,19530 ,8364,8365,8367 ,0,0,0}, - {19529,19531,19532 ,8366,8368,8369 ,0,0,0}, {19532,19530,19529 ,8369,8367,8366 ,0,0,0}, - {19533,19531,19534 ,8370,8368,8371 ,0,0,0}, {19531,19533,19532 ,8368,8370,8369 ,0,0,0}, - {19533,19534,19535 ,8370,8371,8372 ,0,0,0}, {19536,19537,19538 ,8357,8373,8374 ,0,0,0}, - {19536,19539,19537 ,8357,8356,8373 ,0,0,0}, {19536,19538,19540 ,8357,8374,8360 ,0,0,0}, - {19540,19541,19542 ,8360,8375,8359 ,0,0,0}, {19541,19540,19538 ,8375,8360,8374 ,0,0,0}, - {19543,19542,19541 ,8376,8359,8375 ,0,0,0}, {19544,19537,19539 ,8377,8373,8356 ,0,0,0}, - {19543,19545,19546 ,8376,81,5000 ,0,0,0}, {19546,19542,19543 ,5000,8359,8376 ,0,0,0}, - {19544,19539,19547 ,8377,8356,8378 ,0,0,0}, {19547,19548,19544 ,8378,8379,8377 ,0,0,0}, - {19549,19548,19550 ,8380,8379,8363 ,0,0,0}, {19547,19550,19548 ,8378,8363,8379 ,0,0,0}, - {19551,19552,19549 ,8365,8381,8380 ,0,0,0}, {19549,19550,19551 ,8380,8363,8365 ,0,0,0}, - {19553,19554,19552 ,8366,8368,8381 ,0,0,0}, {19553,19552,19551 ,8366,8381,8365 ,0,0,0}, - {19555,19554,19556 ,8382,8368,8383 ,0,0,0}, {19554,19555,19552 ,8368,8382,8381 ,0,0,0}, - {19555,19556,19557 ,8382,8383,8384 ,0,0,0}, {19558,19559,8402 ,8385,8386,8387 ,0,0,0}, - {19560,19561,19562 ,8388,8389,8390 ,0,0,0}, {19563,19558,8402 ,8391,8385,8387 ,0,0,0}, - {19560,19562,19564 ,8388,8390,8392 ,0,0,0}, {19561,19560,19563 ,8389,8388,8391 ,0,0,0}, - {19561,19563,8402 ,8389,8391,8387 ,0,0,0}, {19565,19566,19567 ,8393,878,8394 ,0,0,0}, - {19567,19564,19568 ,8394,8392,8395 ,0,0,0}, {19565,19567,19568 ,8393,8394,8395 ,0,0,0}, - {19566,19565,19569 ,878,8393,8396 ,0,0,0}, {19568,19564,19562 ,8395,8392,8390 ,0,0,0}, - {19558,19570,19559 ,8385,8363,8386 ,0,0,0}, {19571,19570,19572 ,8397,8363,8398 ,0,0,0}, - {19570,19571,19559 ,8363,8397,8386 ,0,0,0}, {19573,19574,19572 ,8399,8400,8398 ,0,0,0}, - {19571,19572,19574 ,8397,8398,8400 ,0,0,0}, {19573,19575,19576 ,8399,8401,8402 ,0,0,0}, - {19576,19574,19573 ,8402,8400,8399 ,0,0,0}, {19577,19575,19578 ,8403,8401,126 ,0,0,0}, - {19575,19577,19576 ,8401,8403,8402 ,0,0,0}, {19579,19580,19581 ,8404,8405,8406 ,0,0,0}, - {19581,19580,19582 ,8406,8405,8407 ,0,0,0}, {19583,19580,19579 ,8408,8405,8404 ,0,0,0}, - {19584,19581,19582 ,8409,8406,8407 ,0,0,0}, {19583,19579,19585 ,8408,8404,8410 ,0,0,0}, - {19585,19586,19587 ,8410,8411,8412 ,0,0,0}, {19586,19585,19579 ,8411,8410,8404 ,0,0,0}, - {19584,19582,19588 ,8409,8407,8413 ,0,0,0}, {19589,19590,19587 ,8414,8415,8412 ,0,0,0}, - {19587,19586,19589 ,8412,8411,8414 ,0,0,0}, {19590,19591,19592 ,8415,5000,4114 ,0,0,0}, - {19593,19590,19589 ,8416,8415,8414 ,0,0,0}, {19593,19591,19590 ,8416,5000,8415 ,0,0,0}, - {19582,19594,19588 ,8407,8417,8413 ,0,0,0}, {19594,19595,19596 ,8417,8418,8419 ,0,0,0}, - {19596,19588,19594 ,8419,8413,8417 ,0,0,0}, {19597,19595,19598 ,8420,8418,8421 ,0,0,0}, - {19595,19597,19596 ,8418,8420,8419 ,0,0,0}, {19599,19600,19598 ,8422,8423,8421 ,0,0,0}, - {19597,19598,19600 ,8420,8421,8423 ,0,0,0}, {19599,19601,19602 ,8422,8424,8425 ,0,0,0}, - {19602,19600,19599 ,8425,8423,8422 ,0,0,0}, {19603,19601,19604 ,8426,8424,8427 ,0,0,0}, - {19601,19603,19602 ,8424,8426,8425 ,0,0,0}, {19603,19604,19605 ,8426,8427,8428 ,0,0,0}, - {19605,19604,4818 ,8428,8427,8429 ,0,0,0}, {19606,19607,19608 ,8430,8431,8432 ,0,0,0}, - {19609,19610,19611 ,8433,8434,8435 ,0,0,0}, {19612,19613,19614 ,8436,8437,8438 ,0,0,0}, - {19615,19616,19617 ,8439,8440,8441 ,0,0,0}, {19618,19619,19620 ,8442,8443,8444 ,0,0,0}, - {19620,19535,19618 ,8444,8445,8442 ,0,0,0}, {19621,19622,19623 ,8446,8447,8448 ,0,0,0}, - {19600,19624,19597 ,8449,8450,8451 ,0,0,0}, {19625,19623,19626 ,8452,8448,8453 ,0,0,0}, - {19627,19628,19629 ,8454,8455,8456 ,0,0,0}, {19630,19631,19632 ,8457,8458,8459 ,0,0,0}, - {19633,19634,19635 ,8460,8461,8462 ,0,0,0}, {19636,19624,19629 ,8463,8450,8456 ,0,0,0}, - {19637,19549,19552 ,8464,8465,8466 ,0,0,0}, {19638,19639,19635 ,8467,8468,8462 ,0,0,0}, - {19640,19641,19642 ,8469,8470,8471 ,0,0,0}, {19643,19644,19640 ,8472,8473,8469 ,0,0,0}, - {19645,19646,19643 ,8474,8475,8472 ,0,0,0}, {19647,19643,19646 ,8476,8472,8475 ,0,0,0}, - {19648,19646,19645 ,8477,8475,8474 ,0,0,0}, {19649,19650,19651 ,8478,8479,8480 ,0,0,0}, - {19652,19637,19641 ,8481,8464,8470 ,0,0,0}, {19653,19654,19649 ,8482,8483,8478 ,0,0,0}, - {19603,19605,19629 ,8484,8485,8456 ,0,0,0}, {19631,19655,19632 ,8458,8486,8459 ,0,0,0}, - {19622,19656,19623 ,8447,8487,8448 ,0,0,0}, {19657,19658,19659 ,8488,8489,8490 ,0,0,0}, - {19581,19660,19579 ,8491,8492,8493 ,0,0,0}, {19617,19656,19661 ,8441,8487,8494 ,0,0,0}, - {19662,19532,19663 ,8495,8496,8497 ,0,0,0}, {19664,19665,19615 ,8498,8499,8439 ,0,0,0}, - {19610,19666,19667 ,8434,8500,8501 ,0,0,0}, {19668,19669,19670 ,8502,8503,8504 ,0,0,0}, - {19609,19611,19671 ,8433,8435,8505 ,0,0,0}, {19607,19606,19672 ,8431,8430,8506 ,0,0,0}, - {19673,19611,19668 ,8507,8435,8502 ,0,0,0}, {19674,19675,19676 ,8508,8509,8510 ,0,0,0}, - {19675,19672,19606 ,8509,8506,8430 ,0,0,0}, {19515,19677,19513 ,8511,8512,8513 ,0,0,0}, - {19678,19608,19679 ,8514,8432,8515 ,0,0,0}, {19609,19680,19681 ,8433,8516,8517 ,0,0,0}, - {19665,19591,19682 ,8499,8518,8519 ,0,0,0}, {19668,19611,19610 ,8502,8435,8434 ,0,0,0}, - {19668,19667,19683 ,8502,8501,8520 ,0,0,0}, {19610,19667,19668 ,8434,8501,8502 ,0,0,0}, - {19684,19685,19613 ,8521,8522,8437 ,0,0,0}, {19673,19612,19686 ,8507,8436,8523 ,0,0,0}, - {19608,19523,19522 ,8432,8524,8525 ,0,0,0}, {19687,19685,19684 ,8526,8522,8521 ,0,0,0}, - {19607,19687,19684 ,8431,8526,8521 ,0,0,0}, {19675,19606,19676 ,8509,8430,8510 ,0,0,0}, - {19672,19687,19607 ,8506,8526,8431 ,0,0,0}, {19679,19608,19522 ,8515,8432,8525 ,0,0,0}, - {19608,19678,19688 ,8432,8514,8527 ,0,0,0}, {19677,19679,19513 ,8512,8515,8513 ,0,0,0}, - {19679,19677,19678 ,8515,8512,8514 ,0,0,0}, {19527,19662,19515 ,8528,8495,8511 ,0,0,0}, - {19532,19662,19530 ,8496,8495,8529 ,0,0,0}, {19662,19677,19515 ,8495,8512,8511 ,0,0,0}, - {19663,19689,19662 ,8497,8530,8495 ,0,0,0}, {19533,19663,19532 ,8531,8497,8496 ,0,0,0}, - {19663,19535,19620 ,8497,8445,8444 ,0,0,0}, {19584,19690,19660 ,8532,8533,8492 ,0,0,0}, - {19691,19626,19623 ,8534,8453,8448 ,0,0,0}, {19631,19692,19693 ,8458,8535,8536 ,0,0,0}, - {19543,19692,19545 ,8537,8535,8538 ,0,0,0}, {19691,19694,19695 ,8534,8539,8540 ,0,0,0}, - {19625,19621,19623 ,8452,8446,8448 ,0,0,0}, {19581,19584,19660 ,8491,8532,8492 ,0,0,0}, - {19622,19696,19656 ,8447,8541,8487 ,0,0,0}, {19623,19656,19697 ,8448,8487,8542 ,0,0,0}, - {19656,19617,19616 ,8487,8441,8440 ,0,0,0}, {19665,19616,19615 ,8499,8440,8439 ,0,0,0}, - {19656,19616,19698 ,8487,8440,8543 ,0,0,0}, {19699,19682,19657 ,8544,8519,8488 ,0,0,0}, - {19665,19700,19616 ,8499,8545,8440 ,0,0,0}, {19610,19681,19620 ,8434,8517,8444 ,0,0,0}, - {19680,19700,19699 ,8516,8545,8544 ,0,0,0}, {19659,19663,19620 ,8490,8497,8444 ,0,0,0}, - {19620,19619,19610 ,8444,8443,8434 ,0,0,0}, {19659,19701,19663 ,8490,8546,8497 ,0,0,0}, - {19702,19659,19658 ,8547,8490,8489 ,0,0,0}, {19660,19703,19658 ,8492,8548,8489 ,0,0,0}, - {19660,19690,19704 ,8492,8533,8549 ,0,0,0}, {19584,19588,19690 ,8532,8550,8533 ,0,0,0}, - {19588,19596,19690 ,8550,8551,8533 ,0,0,0}, {19690,19624,19705 ,8533,8450,8552 ,0,0,0}, - {19600,19629,19624 ,8449,8456,8450 ,0,0,0}, {19602,19629,19600 ,8553,8456,8449 ,0,0,0}, - {19629,19602,19603 ,8456,8553,8484 ,0,0,0}, {19690,19597,19624 ,8533,8451,8450 ,0,0,0}, - {19605,19627,19629 ,8485,8454,8456 ,0,0,0}, {19706,19692,19707 ,8554,8535,8555 ,0,0,0}, - {19654,19653,19708 ,8483,8482,8556 ,0,0,0}, {19709,19640,19649 ,8557,8469,8478 ,0,0,0}, - {19649,19640,19710 ,8478,8469,8558 ,0,0,0}, {19710,19650,19649 ,8558,8479,8478 ,0,0,0}, - {19649,19654,19709 ,8478,8483,8557 ,0,0,0}, {19711,19636,19628 ,8559,8463,8455 ,0,0,0}, - {19655,19654,19708 ,8486,8483,8556 ,0,0,0}, {19655,19708,19712 ,8486,8556,8560 ,0,0,0}, - {19632,19655,19713 ,8459,8486,8561 ,0,0,0}, {19630,19545,19631 ,8457,8538,8458 ,0,0,0}, - {19714,19691,19693 ,8562,8534,8536 ,0,0,0}, {19692,19631,19545 ,8535,8458,8538 ,0,0,0}, - {19627,19605,19715 ,8454,8485,8563 ,0,0,0}, {19626,19627,19716 ,8453,8454,8564 ,0,0,0}, - {19706,19628,19714 ,8554,8455,8562 ,0,0,0}, {19706,19717,19711 ,8554,8565,8559 ,0,0,0}, - {19718,19548,19549 ,8566,8567,8465 ,0,0,0}, {19718,19544,19548 ,8566,8568,8567 ,0,0,0}, - {19719,19718,19639 ,8569,8566,8468 ,0,0,0}, {19717,19707,19719 ,8565,8555,8569 ,0,0,0}, - {19549,19637,19718 ,8465,8464,8566 ,0,0,0}, {19557,19642,19641 ,8570,8471,8470 ,0,0,0}, - {19684,19720,19607 ,8521,8571,8431 ,0,0,0}, {19614,19613,19685 ,8438,8437,8522 ,0,0,0}, - {19673,19721,19613 ,8507,8572,8437 ,0,0,0}, {19525,19523,19720 ,8573,8524,8571 ,0,0,0}, - {19721,19720,19684 ,8572,8571,8521 ,0,0,0}, {19720,19523,19608 ,8571,8524,8432 ,0,0,0}, - {19607,19720,19608 ,8431,8571,8432 ,0,0,0}, {19688,19676,19606 ,8527,8510,8430 ,0,0,0}, - {19612,19673,19613 ,8436,8507,8437 ,0,0,0}, {19686,19671,19611 ,8523,8505,8435 ,0,0,0}, - {19720,19722,19723 ,8571,8574,8575 ,0,0,0}, {19613,19721,19684 ,8437,8572,8521 ,0,0,0}, - {19670,19721,19668 ,8504,8572,8502 ,0,0,0}, {19525,19720,19723 ,8573,8571,8575 ,0,0,0}, - {19522,19519,19679 ,8525,8576,8515 ,0,0,0}, {19688,19606,19608 ,8527,8430,8432 ,0,0,0}, - {19686,19611,19673 ,8523,8435,8507 ,0,0,0}, {19671,19724,19609 ,8505,8577,8433 ,0,0,0}, - {19669,19668,19683 ,8503,8502,8520 ,0,0,0}, {19673,19668,19721 ,8507,8502,8572 ,0,0,0}, - {19722,19721,19670 ,8574,8572,8504 ,0,0,0}, {19721,19722,19720 ,8572,8574,8571 ,0,0,0}, - {19519,19516,19679 ,8576,8578,8515 ,0,0,0}, {19679,19516,19513 ,8515,8578,8513 ,0,0,0}, - {19725,19680,19724 ,8579,8516,8577 ,0,0,0}, {19725,19726,19700 ,8579,8580,8545 ,0,0,0}, - {19666,19610,19727 ,8500,8434,8581 ,0,0,0}, {19619,19727,19610 ,8443,8581,8434 ,0,0,0}, - {19677,19662,19689 ,8512,8495,8530 ,0,0,0}, {19527,19530,19662 ,8528,8529,8495 ,0,0,0}, - {19680,19609,19724 ,8516,8433,8577 ,0,0,0}, {19728,19591,19665 ,8582,8518,8499 ,0,0,0}, - {19620,19681,19657 ,8444,8517,8488 ,0,0,0}, {19609,19681,19610 ,8433,8517,8434 ,0,0,0}, - {19657,19681,19699 ,8488,8517,8544 ,0,0,0}, {19535,19663,19533 ,8445,8497,8531 ,0,0,0}, - {19620,19657,19659 ,8444,8488,8490 ,0,0,0}, {19663,19701,19689 ,8497,8546,8530 ,0,0,0}, - {19725,19700,19680 ,8579,8545,8516 ,0,0,0}, {19729,19700,19726 ,8583,8545,8580 ,0,0,0}, - {19591,19593,19682 ,8518,8584,8519 ,0,0,0}, {19680,19699,19681 ,8516,8544,8517 ,0,0,0}, - {19665,19682,19699 ,8499,8519,8544 ,0,0,0}, {19579,19660,19586 ,8493,8492,8585 ,0,0,0}, - {19658,19657,19682 ,8489,8488,8519 ,0,0,0}, {19701,19659,19702 ,8546,8490,8547 ,0,0,0}, - {19700,19729,19616 ,8545,8583,8440 ,0,0,0}, {19698,19616,19729 ,8543,8440,8583 ,0,0,0}, - {19728,19665,19664 ,8582,8499,8498 ,0,0,0}, {19700,19665,19699 ,8545,8499,8544 ,0,0,0}, - {19593,19589,19682 ,8584,8586,8519 ,0,0,0}, {19682,19589,19586 ,8519,8586,8585 ,0,0,0}, - {19586,19658,19682 ,8585,8489,8519 ,0,0,0}, {19702,19658,19703 ,8547,8489,8548 ,0,0,0}, - {19656,19698,19697 ,8487,8543,8542 ,0,0,0}, {19696,19661,19656 ,8541,8494,8487 ,0,0,0}, - {19703,19660,19704 ,8548,8492,8549 ,0,0,0}, {19586,19660,19658 ,8585,8492,8489 ,0,0,0}, - {19697,19694,19623 ,8542,8539,8448 ,0,0,0}, {19623,19694,19691 ,8448,8539,8534 ,0,0,0}, - {19597,19690,19596 ,8451,8533,8551 ,0,0,0}, {19690,19705,19704 ,8533,8552,8549 ,0,0,0}, - {19691,19627,19626 ,8534,8454,8453 ,0,0,0}, {19695,19730,19693 ,8540,8587,8536 ,0,0,0}, - {19541,19692,19543 ,8588,8535,8537 ,0,0,0}, {19716,19627,19715 ,8564,8454,8563 ,0,0,0}, - {19714,19627,19691 ,8562,8454,8534 ,0,0,0}, {19731,19624,19636 ,8589,8450,8463 ,0,0,0}, - {19629,19628,19636 ,8456,8455,8463 ,0,0,0}, {19705,19624,19731 ,8552,8450,8589 ,0,0,0}, - {19695,19693,19691 ,8540,8536,8534 ,0,0,0}, {19730,19732,19631 ,8587,8590,8458 ,0,0,0}, - {19537,19707,19538 ,8591,8555,8592 ,0,0,0}, {19627,19714,19628 ,8454,8562,8455 ,0,0,0}, - {19714,19693,19692 ,8562,8536,8535 ,0,0,0}, {19636,19733,19734 ,8463,8593,8594 ,0,0,0}, - {19628,19706,19711 ,8455,8554,8559 ,0,0,0}, {19731,19636,19734 ,8589,8463,8594 ,0,0,0}, - {19730,19631,19693 ,8587,8458,8536 ,0,0,0}, {19732,19655,19631 ,8590,8486,8458 ,0,0,0}, - {19707,19541,19538 ,8555,8588,8592 ,0,0,0}, {19714,19692,19706 ,8562,8535,8554 ,0,0,0}, - {19692,19541,19707 ,8535,8588,8555 ,0,0,0}, {19711,19735,19733 ,8559,8595,8593 ,0,0,0}, - {19706,19707,19717 ,8554,8555,8565 ,0,0,0}, {19733,19636,19711 ,8593,8463,8559 ,0,0,0}, - {19654,19655,19732 ,8483,8486,8590 ,0,0,0}, {19712,19713,19655 ,8560,8561,8486 ,0,0,0}, - {19718,19537,19544 ,8566,8591,8568 ,0,0,0}, {19717,19736,19735 ,8565,8596,8595 ,0,0,0}, - {19707,19718,19719 ,8555,8566,8569 ,0,0,0}, {19735,19711,19717 ,8595,8559,8565 ,0,0,0}, - {19649,19651,19653 ,8478,8480,8482 ,0,0,0}, {19709,19737,19640 ,8557,8597,8469 ,0,0,0}, - {19552,19555,19641 ,8466,8598,8470 ,0,0,0}, {19552,19641,19637 ,8466,8470,8464 ,0,0,0}, - {19719,19638,19736 ,8569,8467,8596 ,0,0,0}, {19718,19707,19537 ,8566,8555,8591 ,0,0,0}, - {19718,19637,19639 ,8566,8464,8468 ,0,0,0}, {19736,19717,19719 ,8596,8565,8569 ,0,0,0}, - {19640,19642,19710 ,8469,8471,8558 ,0,0,0}, {19737,19645,19643 ,8597,8474,8472 ,0,0,0}, - {19738,19634,19633 ,8599,8461,8460 ,0,0,0}, {19557,19641,19555 ,8570,8470,8598 ,0,0,0}, - {19641,19644,19652 ,8470,8473,8481 ,0,0,0}, {19633,19639,19637 ,8460,8468,8464 ,0,0,0}, - {19652,19633,19637 ,8481,8460,8464 ,0,0,0}, {19638,19719,19639 ,8467,8569,8468 ,0,0,0}, - {19737,19643,19640 ,8597,8472,8469 ,0,0,0}, {19640,19644,19641 ,8469,8473,8470 ,0,0,0}, - {19647,19739,19644 ,8476,8600,8473 ,0,0,0}, {19643,19647,19644 ,8472,8476,8473 ,0,0,0}, - {19739,19738,19652 ,8600,8599,8481 ,0,0,0}, {19644,19739,19652 ,8473,8600,8481 ,0,0,0}, - {19738,19633,19652 ,8599,8460,8481 ,0,0,0}, {19635,19639,19633 ,8462,8468,8460 ,0,0,0}, - {19740,19741,19742 ,8601,8602,8603 ,0,0,0}, {19743,19744,19741 ,8604,8605,8602 ,0,0,0}, - {19745,19746,19747 ,8606,8607,8608 ,0,0,0}, {19748,19749,19750 ,8609,8610,8611 ,0,0,0}, - {19751,19752,19753 ,8612,8613,8614 ,0,0,0}, {19754,19755,19756 ,8615,8616,8617 ,0,0,0}, - {19757,19758,19759 ,8618,8619,8620 ,0,0,0}, {19760,19761,19762 ,8621,8622,8623 ,0,0,0}, - {19763,19764,19765 ,8624,8625,8626 ,0,0,0}, {19766,19767,19768 ,8627,8628,8629 ,0,0,0}, - {19769,19770,19763 ,8630,8631,8624 ,0,0,0}, {19763,19765,19769 ,8624,8626,8630 ,0,0,0}, - {19770,19771,19772 ,8631,8632,8633 ,0,0,0}, {19771,19770,19769 ,8632,8631,8630 ,0,0,0}, - {19773,19772,19774 ,8634,8633,8635 ,0,0,0}, {19771,19774,19772 ,8632,8635,8633 ,0,0,0}, - {19775,19776,19773 ,8636,8637,8634 ,0,0,0}, {19773,19774,19775 ,8634,8635,8636 ,0,0,0}, - {19777,19776,19775 ,8638,8637,8636 ,0,0,0}, {19764,19768,19765 ,8625,8629,8626 ,0,0,0}, - {19766,19758,19767 ,8627,8619,8628 ,0,0,0}, {19764,19766,19768 ,8625,8627,8629 ,0,0,0}, - {19757,19759,19760 ,8618,8620,8621 ,0,0,0}, {19767,19758,19757 ,8628,8619,8618 ,0,0,0}, - {19762,19761,19753 ,8623,8622,8614 ,0,0,0}, {19760,19759,19761 ,8621,8620,8622 ,0,0,0}, - {19755,19752,19751 ,8616,8613,8612 ,0,0,0}, {19752,19762,19753 ,8613,8623,8614 ,0,0,0}, - {19778,19754,19756 ,8639,8615,8617 ,0,0,0}, {19756,19755,19751 ,8617,8616,8612 ,0,0,0}, - {19745,19778,19746 ,8606,8639,8607 ,0,0,0}, {19778,19745,19754 ,8639,8606,8615 ,0,0,0}, - {19747,19748,19750 ,8608,8609,8611 ,0,0,0}, {19746,19748,19747 ,8607,8609,8608 ,0,0,0}, - {19743,19749,19744 ,8604,8610,8605 ,0,0,0}, {19750,19749,19743 ,8611,8610,8604 ,0,0,0}, - {19742,19779,19740 ,8603,8640,8601 ,0,0,0}, {19741,19744,19742 ,8602,8605,8603 ,0,0,0}, - {19780,19781,19741 ,8641,8642,8643 ,0,0,0}, {19782,19743,19781 ,8644,8645,8642 ,0,0,0}, - {19754,19745,19783 ,8646,8647,8648 ,0,0,0}, {19747,19750,19784 ,8649,8650,8651 ,0,0,0}, - {19752,19785,19762 ,8652,8653,8654 ,0,0,0}, {19786,19787,19755 ,8655,8656,8657 ,0,0,0}, - {19788,19767,19757 ,8658,8659,8660 ,0,0,0}, {19789,19760,19790 ,8661,8662,8663 ,0,0,0}, - {19769,19765,19791 ,8664,8665,8666 ,0,0,0}, {19768,19792,19793 ,8667,8668,8669 ,0,0,0}, - {19794,19771,19769 ,8670,8671,8664 ,0,0,0}, {19769,19791,19794 ,8664,8666,8670 ,0,0,0}, - {19771,19795,19774 ,8671,8672,8673 ,0,0,0}, {19795,19771,19794 ,8672,8671,8670 ,0,0,0}, - {19775,19774,19796 ,8674,8673,8675 ,0,0,0}, {19795,19796,19774 ,8672,8675,8673 ,0,0,0}, - {19797,19777,19775 ,8676,8638,8674 ,0,0,0}, {19775,19796,19797 ,8674,8675,8676 ,0,0,0}, - {19798,19777,19797 ,8677,8638,8676 ,0,0,0}, {19765,19793,19791 ,8665,8669,8666 ,0,0,0}, - {19768,19767,19792 ,8667,8659,8668 ,0,0,0}, {19765,19768,19793 ,8665,8667,8669 ,0,0,0}, - {19788,19757,19789 ,8658,8660,8661 ,0,0,0}, {19792,19767,19788 ,8668,8659,8658 ,0,0,0}, - {19790,19760,19762 ,8663,8662,8654 ,0,0,0}, {19789,19757,19760 ,8661,8660,8662 ,0,0,0}, - {19787,19785,19752 ,8656,8653,8652 ,0,0,0}, {19785,19790,19762 ,8653,8663,8654 ,0,0,0}, - {19754,19786,19755 ,8646,8655,8657 ,0,0,0}, {19755,19787,19752 ,8657,8656,8652 ,0,0,0}, - {19745,19799,19783 ,8647,8678,8648 ,0,0,0}, {19754,19783,19786 ,8646,8648,8655 ,0,0,0}, - {19784,19799,19747 ,8651,8678,8649 ,0,0,0}, {19745,19747,19799 ,8647,8649,8678 ,0,0,0}, - {19782,19750,19743 ,8644,8650,8645 ,0,0,0}, {19784,19750,19782 ,8651,8650,8644 ,0,0,0}, - {19741,19740,19780 ,8643,8601,8641 ,0,0,0}, {19781,19743,19741 ,8642,8645,8643 ,0,0,0}, - {19800,19801,19781 ,8679,8680,8681 ,0,0,0}, {19784,19782,19802 ,8651,8644,8682 ,0,0,0}, - {19786,19783,19803 ,8683,8684,8685 ,0,0,0}, {19799,19804,19805 ,8678,8686,8687 ,0,0,0}, - {19785,19806,19790 ,8688,8689,8690 ,0,0,0}, {19807,19808,19787 ,8691,8692,8693 ,0,0,0}, - {19809,19792,19810 ,8694,8695,8696 ,0,0,0}, {19788,19789,19811 ,8697,8698,8699 ,0,0,0}, - {19794,19791,19812 ,8700,8701,8702 ,0,0,0}, {19793,19813,19791 ,8703,8704,8701 ,0,0,0}, - {19814,19795,19794 ,8705,8706,8700 ,0,0,0}, {19794,19812,19814 ,8700,8702,8705 ,0,0,0}, - {19795,19815,19796 ,8706,8707,8675 ,0,0,0}, {19815,19795,19814 ,8707,8706,8705 ,0,0,0}, - {19797,19796,19816 ,8708,8675,8709 ,0,0,0}, {19815,19816,19796 ,8707,8709,8675 ,0,0,0}, - {19816,19817,19798 ,8709,8710,8677 ,0,0,0}, {19798,19797,19816 ,8677,8708,8709 ,0,0,0}, - {19812,19791,19813 ,8702,8701,8704 ,0,0,0}, {19793,19792,19809 ,8703,8695,8694 ,0,0,0}, - {19793,19809,19813 ,8703,8694,8704 ,0,0,0}, {19810,19788,19811 ,8696,8697,8699 ,0,0,0}, - {19792,19788,19810 ,8695,8697,8696 ,0,0,0}, {19818,19789,19790 ,8711,8698,8690 ,0,0,0}, - {19811,19789,19818 ,8699,8698,8711 ,0,0,0}, {19808,19806,19785 ,8692,8689,8688 ,0,0,0}, - {19806,19818,19790 ,8689,8711,8690 ,0,0,0}, {19786,19807,19787 ,8683,8691,8693 ,0,0,0}, - {19787,19808,19785 ,8693,8692,8688 ,0,0,0}, {19783,19805,19803 ,8684,8687,8685 ,0,0,0}, - {19786,19803,19807 ,8683,8685,8691 ,0,0,0}, {19799,19784,19804 ,8678,8651,8686 ,0,0,0}, - {19783,19799,19805 ,8684,8678,8687 ,0,0,0}, {19802,19782,19801 ,8682,8644,8680 ,0,0,0}, - {19804,19784,19802 ,8686,8651,8682 ,0,0,0}, {19800,19781,19780 ,8679,8681,8641 ,0,0,0}, - {19801,19782,19781 ,8680,8644,8681 ,0,0,0}, {19819,19820,19801 ,8712,8713,8714 ,0,0,0}, - {19804,19802,19821 ,8715,8716,8717 ,0,0,0}, {19807,19803,19822 ,8718,8719,8720 ,0,0,0}, - {19805,19804,19823 ,8721,8715,8722 ,0,0,0}, {19806,19824,19818 ,8723,8724,8725 ,0,0,0}, - {19825,19826,19808 ,8726,8727,8728 ,0,0,0}, {19827,19809,19810 ,8729,8730,8731 ,0,0,0}, - {19828,19811,19829 ,8732,8733,8734 ,0,0,0}, {19830,19812,19831 ,8735,8736,8737 ,0,0,0}, - {19813,19832,19831 ,8738,8739,8737 ,0,0,0}, {19830,19833,19814 ,8735,8740,8741 ,0,0,0}, - {19814,19812,19830 ,8741,8736,8735 ,0,0,0}, {19815,19833,19834 ,8742,8740,8743 ,0,0,0}, - {19833,19815,19814 ,8740,8742,8741 ,0,0,0}, {19835,19816,19834 ,8744,8745,8743 ,0,0,0}, - {19815,19834,19816 ,8742,8743,8745 ,0,0,0}, {19835,19836,19817 ,8744,8746,8710 ,0,0,0}, - {19817,19816,19835 ,8710,8745,8744 ,0,0,0}, {19831,19812,19813 ,8737,8736,8738 ,0,0,0}, - {19832,19809,19827 ,8739,8730,8729 ,0,0,0}, {19813,19809,19832 ,8738,8730,8739 ,0,0,0}, - {19828,19810,19811 ,8732,8731,8733 ,0,0,0}, {19827,19810,19828 ,8729,8731,8732 ,0,0,0}, - {19824,19829,19818 ,8724,8734,8725 ,0,0,0}, {19829,19811,19818 ,8734,8733,8725 ,0,0,0}, - {19808,19826,19806 ,8728,8727,8723 ,0,0,0}, {19826,19824,19806 ,8727,8724,8723 ,0,0,0}, - {19807,19822,19825 ,8718,8720,8726 ,0,0,0}, {19807,19825,19808 ,8718,8726,8728 ,0,0,0}, - {19803,19805,19837 ,8719,8721,8747 ,0,0,0}, {19803,19837,19822 ,8719,8747,8720 ,0,0,0}, - {19823,19804,19821 ,8722,8715,8717 ,0,0,0}, {19837,19805,19823 ,8747,8721,8722 ,0,0,0}, - {19820,19802,19801 ,8713,8716,8714 ,0,0,0}, {19821,19802,19820 ,8717,8716,8713 ,0,0,0}, - {19819,19801,19800 ,8712,8714,8679 ,0,0,0}, {19834,19838,19839 ,8748,8749,8750 ,0,0,0}, - {19836,19835,19840 ,8746,8751,8752 ,0,0,0}, {19841,19831,19842 ,8753,8754,8755 ,0,0,0}, - {19830,19843,19833 ,8756,8757,8758 ,0,0,0}, {19829,19844,19828 ,8759,8760,8761 ,0,0,0}, - {19827,19845,19832 ,8762,8763,8764 ,0,0,0}, {19846,19826,19825 ,8765,8766,8767 ,0,0,0}, - {19847,19824,19848 ,8768,8769,8770 ,0,0,0}, {19849,19837,19850 ,8771,8772,8773 ,0,0,0}, - {19822,19849,19851 ,8774,8771,8775 ,0,0,0}, {19852,19850,19823 ,8776,8773,8777 ,0,0,0}, - {19837,19823,19850 ,8772,8777,8773 ,0,0,0}, {19821,19853,19852 ,8778,8779,8776 ,0,0,0}, - {19852,19823,19821 ,8776,8777,8778 ,0,0,0}, {19853,19820,19854 ,8779,8780,8781 ,0,0,0}, - {19820,19853,19821 ,8780,8779,8778 ,0,0,0}, {19851,19825,19822 ,8775,8767,8774 ,0,0,0}, - {19854,19820,19819 ,8781,8780,8782 ,0,0,0}, {19849,19822,19837 ,8771,8774,8772 ,0,0,0}, - {19846,19848,19826 ,8765,8770,8766 ,0,0,0}, {19851,19846,19825 ,8775,8765,8767 ,0,0,0}, - {19824,19847,19829 ,8769,8768,8759 ,0,0,0}, {19826,19848,19824 ,8766,8770,8769 ,0,0,0}, - {19828,19844,19855 ,8761,8760,8783 ,0,0,0}, {19829,19847,19844 ,8759,8768,8760 ,0,0,0}, - {19855,19845,19827 ,8783,8763,8762 ,0,0,0}, {19827,19828,19855 ,8762,8761,8783 ,0,0,0}, - {19842,19831,19832 ,8755,8754,8764 ,0,0,0}, {19842,19832,19845 ,8755,8764,8763 ,0,0,0}, - {19841,19843,19830 ,8753,8757,8756 ,0,0,0}, {19841,19830,19831 ,8753,8756,8754 ,0,0,0}, - {19833,19838,19834 ,8758,8749,8748 ,0,0,0}, {19843,19838,19833 ,8757,8749,8758 ,0,0,0}, - {19835,19839,19840 ,8751,8750,8752 ,0,0,0}, {19834,19839,19835 ,8748,8750,8751 ,0,0,0}, - {19836,19840,19856 ,8746,8752,8784 ,0,0,0}, {19857,19858,19859 ,8785,8786,8787 ,0,0,0}, - {19860,19861,19862 ,8788,8789,8790 ,0,0,0}, {19861,19863,19864 ,8789,8791,8792 ,0,0,0}, - {19864,19862,19861 ,8792,8790,8789 ,0,0,0}, {19861,19859,19865 ,8789,8787,8793 ,0,0,0}, - {19863,19866,19864 ,8791,8794,8792 ,0,0,0}, {19867,19868,19869 ,8795,8796,8797 ,0,0,0}, - {19819,19858,19854 ,8782,8786,8798 ,0,0,0}, {19870,19871,19872 ,8799,8800,8801 ,0,0,0}, - {19850,19852,19873 ,8802,8803,8804 ,0,0,0}, {19874,19875,19876 ,8805,8806,8807 ,0,0,0}, - {19851,19877,19846 ,8808,8809,8810 ,0,0,0}, {19878,19879,19845 ,8811,8812,8813 ,0,0,0}, - {19880,19881,19876 ,8814,8815,8807 ,0,0,0}, {19882,19883,19884 ,8816,8817,8818 ,0,0,0}, - {19885,19879,19886 ,8819,8812,8820 ,0,0,0}, {19839,19883,19840 ,8821,8817,8822 ,0,0,0}, - {19840,19887,19856 ,8822,8823,8824 ,0,0,0}, {19888,19889,19884 ,8825,8826,8818 ,0,0,0}, - {19840,19883,19887 ,8822,8817,8823 ,0,0,0}, {19890,19882,19891 ,8827,8816,8828 ,0,0,0}, - {19888,19884,19838 ,8825,8818,8829 ,0,0,0}, {19888,19892,19893 ,8825,8830,8831 ,0,0,0}, - {19843,19892,19888 ,8832,8830,8825 ,0,0,0}, {19842,19879,19885 ,8833,8812,8819 ,0,0,0}, - {19892,19885,19894 ,8830,8819,8834 ,0,0,0}, {19892,19841,19885 ,8830,8835,8819 ,0,0,0}, - {19895,19878,19881 ,8836,8811,8815 ,0,0,0}, {19896,19879,19878 ,8837,8812,8811 ,0,0,0}, - {19881,19844,19847 ,8815,8838,8839 ,0,0,0}, {19881,19878,19855 ,8815,8811,8840 ,0,0,0}, - {19846,19874,19848 ,8810,8805,8841 ,0,0,0}, {19848,19876,19847 ,8841,8807,8839 ,0,0,0}, - {19870,19897,19877 ,8799,8842,8809 ,0,0,0}, {19877,19898,19874 ,8809,8843,8805 ,0,0,0}, - {19849,19850,19871 ,8844,8802,8800 ,0,0,0}, {19851,19849,19870 ,8808,8844,8799 ,0,0,0}, - {19868,19899,19873 ,8796,8845,8804 ,0,0,0}, {19872,19871,19899 ,8801,8800,8845 ,0,0,0}, - {19900,19853,19854 ,8846,8847,8798 ,0,0,0}, {19869,19852,19853 ,8797,8803,8847 ,0,0,0}, - {19901,19865,19859 ,8848,8793,8787 ,0,0,0}, {19900,19857,19867 ,8846,8785,8795 ,0,0,0}, - {19859,19858,19901 ,8787,8786,8848 ,0,0,0}, {19863,19861,19865 ,8791,8789,8793 ,0,0,0}, - {19902,19860,19862 ,8849,8788,8790 ,0,0,0}, {19903,19860,19902 ,8850,8788,8849 ,0,0,0}, - {19858,19819,19901 ,8786,8782,8848 ,0,0,0}, {19859,19860,19857 ,8787,8788,8785 ,0,0,0}, - {19854,19858,19900 ,8798,8786,8846 ,0,0,0}, {19861,19860,19859 ,8789,8788,8787 ,0,0,0}, - {19904,19903,19902 ,8851,8850,8849 ,0,0,0}, {19905,19903,19904 ,8852,8850,8851 ,0,0,0}, - {19858,19857,19900 ,8786,8785,8846 ,0,0,0}, {19857,19903,19867 ,8785,8850,8795 ,0,0,0}, - {19853,19900,19869 ,8847,8846,8797 ,0,0,0}, {19860,19903,19857 ,8788,8850,8785 ,0,0,0}, - {19906,19905,19904 ,8853,8852,8851 ,0,0,0}, {19907,19905,19906 ,8854,8852,8853 ,0,0,0}, - {19900,19867,19869 ,8846,8795,8797 ,0,0,0}, {19867,19905,19868 ,8795,8852,8796 ,0,0,0}, - {19852,19869,19873 ,8803,8797,8804 ,0,0,0}, {19903,19905,19867 ,8850,8852,8795 ,0,0,0}, - {19908,19907,19906 ,8855,8854,8853 ,0,0,0}, {19909,19907,19908 ,8856,8854,8855 ,0,0,0}, - {19869,19868,19873 ,8797,8796,8804 ,0,0,0}, {19868,19907,19899 ,8796,8854,8845 ,0,0,0}, - {19850,19873,19871 ,8802,8804,8800 ,0,0,0}, {19905,19907,19868 ,8852,8854,8796 ,0,0,0}, - {19910,19909,19908 ,8857,8856,8855 ,0,0,0}, {19911,19909,19910 ,8858,8856,8857 ,0,0,0}, - {19873,19899,19871 ,8804,8845,8800 ,0,0,0}, {19899,19909,19872 ,8845,8856,8801 ,0,0,0}, - {19849,19871,19870 ,8844,8800,8799 ,0,0,0}, {19907,19909,19899 ,8854,8856,8845 ,0,0,0}, - {19912,19911,19910 ,8859,8858,8857 ,0,0,0}, {19913,19914,19891 ,8860,8861,8828 ,0,0,0}, - {19915,19911,19912 ,8862,8858,8859 ,0,0,0}, {19872,19911,19897 ,8801,8858,8842 ,0,0,0}, - {19851,19870,19877 ,8808,8799,8809 ,0,0,0}, {19909,19911,19872 ,8856,8858,8801 ,0,0,0}, - {19916,19915,19912 ,8863,8862,8859 ,0,0,0}, {19917,19918,19915 ,8864,8865,8862 ,0,0,0}, - {19872,19897,19870 ,8801,8842,8799 ,0,0,0}, {19897,19915,19898 ,8842,8862,8843 ,0,0,0}, - {19846,19877,19874 ,8810,8809,8805 ,0,0,0}, {19911,19915,19897 ,8858,8862,8842 ,0,0,0}, - {19916,19917,19915 ,8863,8864,8862 ,0,0,0}, {19919,19920,19918 ,8866,8867,8865 ,0,0,0}, - {19897,19898,19877 ,8842,8843,8809 ,0,0,0}, {19898,19918,19875 ,8843,8865,8806 ,0,0,0}, - {19848,19874,19876 ,8841,8805,8807 ,0,0,0}, {19915,19918,19898 ,8862,8865,8843 ,0,0,0}, - {19917,19919,19918 ,8864,8866,8865 ,0,0,0}, {19921,19922,19920 ,8868,8869,8867 ,0,0,0}, - {19898,19875,19874 ,8843,8806,8805 ,0,0,0}, {19920,19880,19875 ,8867,8814,8806 ,0,0,0}, - {19847,19876,19881 ,8839,8807,8815 ,0,0,0}, {19918,19920,19875 ,8865,8867,8806 ,0,0,0}, - {19919,19921,19920 ,8866,8868,8867 ,0,0,0}, {19922,19923,19924 ,8869,8870,8871 ,0,0,0}, - {19875,19880,19876 ,8806,8814,8807 ,0,0,0}, {19922,19895,19880 ,8869,8836,8814 ,0,0,0}, - {19855,19844,19881 ,8840,8838,8815 ,0,0,0}, {19920,19922,19880 ,8867,8869,8814 ,0,0,0}, - {19921,19923,19922 ,8868,8870,8869 ,0,0,0}, {19924,19925,19926 ,8871,8872,8873 ,0,0,0}, - {19880,19895,19881 ,8814,8836,8815 ,0,0,0}, {19924,19896,19895 ,8871,8837,8836 ,0,0,0}, - {19845,19855,19878 ,8813,8840,8811 ,0,0,0}, {19922,19924,19895 ,8869,8871,8836 ,0,0,0}, - {19923,19925,19924 ,8870,8872,8871 ,0,0,0}, {19926,19927,19928 ,8873,8874,8875 ,0,0,0}, - {19895,19896,19878 ,8836,8837,8811 ,0,0,0}, {19926,19886,19896 ,8873,8820,8837 ,0,0,0}, - {19842,19845,19879 ,8833,8813,8812 ,0,0,0}, {19924,19926,19896 ,8871,8873,8837 ,0,0,0}, - {19925,19927,19926 ,8872,8874,8873 ,0,0,0}, {19928,19929,19930 ,8875,8876,8877 ,0,0,0}, - {19896,19886,19879 ,8837,8820,8812 ,0,0,0}, {19928,19894,19886 ,8875,8834,8820 ,0,0,0}, - {19841,19842,19885 ,8835,8833,8819 ,0,0,0}, {19926,19928,19886 ,8873,8875,8820 ,0,0,0}, - {19927,19929,19928 ,8874,8876,8875 ,0,0,0}, {19930,19931,19932 ,8877,8878,8879 ,0,0,0}, - {19886,19894,19885 ,8820,8834,8819 ,0,0,0}, {19930,19893,19894 ,8877,8831,8834 ,0,0,0}, - {19843,19841,19892 ,8832,8835,8830 ,0,0,0}, {19928,19930,19894 ,8875,8877,8834 ,0,0,0}, - {19929,19931,19930 ,8876,8878,8877 ,0,0,0}, {19891,19932,19913 ,8828,8879,8860 ,0,0,0}, - {19894,19893,19892 ,8834,8831,8830 ,0,0,0}, {19893,19932,19889 ,8831,8879,8826 ,0,0,0}, - {19838,19843,19888 ,8829,8832,8825 ,0,0,0}, {19930,19932,19893 ,8877,8879,8831 ,0,0,0}, - {19931,19913,19932 ,8878,8860,8879 ,0,0,0}, {19839,19884,19883 ,8821,8818,8817 ,0,0,0}, - {19893,19889,19888 ,8831,8826,8825 ,0,0,0}, {19891,19882,19889 ,8828,8816,8826 ,0,0,0}, - {19839,19838,19884 ,8821,8829,8818 ,0,0,0}, {19891,19889,19932 ,8828,8826,8879 ,0,0,0}, - {19914,19890,19891 ,8861,8827,8828 ,0,0,0}, {19933,19882,19890 ,8880,8816,8827 ,0,0,0}, - {19889,19882,19884 ,8826,8816,8818 ,0,0,0}, {19882,19933,19883 ,8816,8880,8817 ,0,0,0}, - {19887,19883,19933 ,8823,8817,8880 ,0,0,0}, {19934,19935,19864 ,8881,8882,8883 ,0,0,0}, - {19902,19862,19936 ,8884,8885,8886 ,0,0,0}, {19908,19906,19937 ,8887,8888,8889 ,0,0,0}, - {19904,19938,19939 ,8890,8891,8892 ,0,0,0}, {19940,19941,19916 ,8893,8894,8895 ,0,0,0}, - {19942,19943,19910 ,8896,8897,8898 ,0,0,0}, {19944,19921,19945 ,8899,8900,8901 ,0,0,0}, - {19919,19917,19946 ,8902,8903,8904 ,0,0,0}, {19927,19925,19947 ,8905,8906,8907 ,0,0,0}, - {19923,19948,19925 ,8908,8909,8906 ,0,0,0}, {19949,19929,19927 ,8910,8911,8905 ,0,0,0}, - {19927,19947,19949 ,8905,8907,8910 ,0,0,0}, {19929,19950,19931 ,8911,8912,8913 ,0,0,0}, - {19950,19929,19949 ,8912,8911,8910 ,0,0,0}, {19913,19931,19951 ,8914,8913,8915 ,0,0,0}, - {19950,19951,19931 ,8912,8915,8913 ,0,0,0}, {19951,19952,19914 ,8915,8916,8861 ,0,0,0}, - {19914,19913,19951 ,8861,8914,8915 ,0,0,0}, {19947,19925,19948 ,8907,8906,8909 ,0,0,0}, - {19923,19921,19944 ,8908,8900,8899 ,0,0,0}, {19923,19944,19948 ,8908,8899,8909 ,0,0,0}, - {19945,19919,19946 ,8901,8902,8904 ,0,0,0}, {19921,19919,19945 ,8900,8902,8901 ,0,0,0}, - {19941,19917,19916 ,8894,8903,8895 ,0,0,0}, {19946,19917,19941 ,8904,8903,8894 ,0,0,0}, - {19943,19940,19912 ,8897,8893,8917 ,0,0,0}, {19940,19916,19912 ,8893,8895,8917 ,0,0,0}, - {19908,19942,19910 ,8887,8896,8898 ,0,0,0}, {19910,19943,19912 ,8898,8897,8917 ,0,0,0}, - {19906,19939,19937 ,8888,8892,8889 ,0,0,0}, {19908,19937,19942 ,8887,8889,8896 ,0,0,0}, - {19904,19902,19938 ,8890,8884,8891 ,0,0,0}, {19906,19904,19939 ,8888,8890,8892 ,0,0,0}, - {19936,19862,19935 ,8886,8885,8882 ,0,0,0}, {19938,19902,19936 ,8891,8884,8886 ,0,0,0}, - {19934,19864,19866 ,8881,8883,8918 ,0,0,0}, {19935,19862,19864 ,8882,8885,8883 ,0,0,0}, - {19953,19954,19935 ,8919,8920,8921 ,0,0,0}, {19936,19935,19955 ,8922,8921,8923 ,0,0,0}, - {19937,19939,19956 ,8924,8925,8926 ,0,0,0}, {19938,19957,19958 ,8927,8928,8929 ,0,0,0}, - {19943,19959,19940 ,8930,8931,8932 ,0,0,0}, {19960,19961,19942 ,8933,8934,8935 ,0,0,0}, - {19962,19945,19946 ,8936,8937,8938 ,0,0,0}, {19963,19941,19964 ,8939,8940,8941 ,0,0,0}, - {19947,19948,19965 ,8942,8943,8944 ,0,0,0}, {19944,19966,19967 ,8945,8946,8947 ,0,0,0}, - {19968,19949,19947 ,8948,8949,8942 ,0,0,0}, {19947,19965,19968 ,8942,8944,8948 ,0,0,0}, - {19949,19969,19950 ,8949,8950,8951 ,0,0,0}, {19969,19949,19968 ,8950,8949,8948 ,0,0,0}, - {19951,19950,19970 ,8952,8951,8953 ,0,0,0}, {19969,19970,19950 ,8950,8953,8951 ,0,0,0}, - {19971,19952,19951 ,8954,8916,8952 ,0,0,0}, {19951,19970,19971 ,8952,8953,8954 ,0,0,0}, - {19972,19952,19971 ,8955,8916,8954 ,0,0,0}, {19948,19967,19965 ,8943,8947,8944 ,0,0,0}, - {19944,19945,19966 ,8945,8937,8946 ,0,0,0}, {19948,19944,19967 ,8943,8945,8947 ,0,0,0}, - {19962,19946,19963 ,8936,8938,8939 ,0,0,0}, {19966,19945,19962 ,8946,8937,8936 ,0,0,0}, - {19964,19941,19940 ,8941,8940,8932 ,0,0,0}, {19963,19946,19941 ,8939,8938,8940 ,0,0,0}, - {19961,19959,19943 ,8934,8931,8930 ,0,0,0}, {19959,19964,19940 ,8931,8941,8932 ,0,0,0}, - {19937,19960,19942 ,8924,8933,8935 ,0,0,0}, {19942,19961,19943 ,8935,8934,8930 ,0,0,0}, - {19939,19958,19956 ,8925,8929,8926 ,0,0,0}, {19937,19956,19960 ,8924,8926,8933 ,0,0,0}, - {19938,19936,19957 ,8927,8922,8928 ,0,0,0}, {19939,19938,19958 ,8925,8927,8929 ,0,0,0}, - {19955,19935,19954 ,8923,8921,8920 ,0,0,0}, {19957,19936,19955 ,8928,8922,8923 ,0,0,0}, - {19953,19935,19934 ,8919,8921,8881 ,0,0,0}, {19973,19974,19954 ,8956,8957,8958 ,0,0,0}, - {19975,19955,19974 ,8959,8923,8957 ,0,0,0}, {19960,19956,19976 ,8960,8961,8962 ,0,0,0}, - {19958,19957,19977 ,8929,8928,8963 ,0,0,0}, {19959,19978,19964 ,8964,8965,8966 ,0,0,0}, - {19979,19980,19961 ,8967,8968,8969 ,0,0,0}, {19981,19966,19962 ,8970,8971,8972 ,0,0,0}, - {19982,19963,19983 ,8973,8974,8975 ,0,0,0}, {19968,19965,19984 ,8948,8944,8976 ,0,0,0}, - {19967,19985,19986 ,8977,8978,8979 ,0,0,0}, {19987,19969,19968 ,8980,8950,8948 ,0,0,0}, - {19968,19984,19987 ,8948,8976,8980 ,0,0,0}, {19969,19988,19970 ,8950,8981,8953 ,0,0,0}, - {19988,19969,19987 ,8981,8950,8980 ,0,0,0}, {19971,19970,19989 ,8982,8953,8983 ,0,0,0}, - {19988,19989,19970 ,8981,8983,8953 ,0,0,0}, {19990,19972,19971 ,8984,8955,8982 ,0,0,0}, - {19971,19989,19990 ,8982,8983,8984 ,0,0,0}, {19991,19972,19990 ,8985,8955,8984 ,0,0,0}, - {19965,19986,19984 ,8944,8979,8976 ,0,0,0}, {19967,19966,19985 ,8977,8971,8978 ,0,0,0}, - {19965,19967,19986 ,8944,8977,8979 ,0,0,0}, {19981,19962,19982 ,8970,8972,8973 ,0,0,0}, - {19985,19966,19981 ,8978,8971,8970 ,0,0,0}, {19983,19963,19964 ,8975,8974,8966 ,0,0,0}, - {19982,19962,19963 ,8973,8972,8974 ,0,0,0}, {19980,19978,19959 ,8968,8965,8964 ,0,0,0}, - {19978,19983,19964 ,8965,8975,8966 ,0,0,0}, {19960,19979,19961 ,8960,8967,8969 ,0,0,0}, - {19961,19980,19959 ,8969,8968,8964 ,0,0,0}, {19956,19992,19976 ,8961,8986,8962 ,0,0,0}, - {19960,19976,19979 ,8960,8962,8967 ,0,0,0}, {19977,19992,19958 ,8963,8986,8929 ,0,0,0}, - {19956,19958,19992 ,8961,8929,8986 ,0,0,0}, {19975,19957,19955 ,8959,8928,8923 ,0,0,0}, - {19977,19957,19975 ,8963,8928,8959 ,0,0,0}, {19954,19953,19973 ,8958,8919,8956 ,0,0,0}, - {19974,19955,19954 ,8957,8923,8958 ,0,0,0}, {19993,19994,19974 ,8987,8988,8989 ,0,0,0}, - {19995,19975,19994 ,8990,8991,8988 ,0,0,0}, {19979,19976,19996 ,8992,8993,8994 ,0,0,0}, - {19992,19977,19997 ,8995,8996,8997 ,0,0,0}, {19978,19998,19983 ,8998,8999,9000 ,0,0,0}, - {19999,20000,19980 ,9001,9002,9003 ,0,0,0}, {20001,19985,19981 ,9004,9005,9006 ,0,0,0}, - {20002,19982,20003 ,9007,9008,9009 ,0,0,0}, {20004,19984,20005 ,9010,9011,9012 ,0,0,0}, - {19986,19985,20006 ,9013,9005,9014 ,0,0,0}, {20007,19988,19987 ,9015,9016,9017 ,0,0,0}, - {19987,20004,20007 ,9017,9010,9015 ,0,0,0}, {19988,20008,19989 ,9016,9018,9019 ,0,0,0}, - {20008,19988,20007 ,9018,9016,9015 ,0,0,0}, {19990,19989,20009 ,9020,9019,9021 ,0,0,0}, - {20008,20009,19989 ,9018,9021,9019 ,0,0,0}, {20010,19991,19990 ,9022,8985,9020 ,0,0,0}, - {19990,20009,20010 ,9020,9021,9022 ,0,0,0}, {20011,19991,20010 ,9023,8985,9022 ,0,0,0}, - {20004,19987,19984 ,9010,9017,9011 ,0,0,0}, {20005,19986,20006 ,9012,9013,9014 ,0,0,0}, - {19984,19986,20005 ,9011,9013,9012 ,0,0,0}, {19981,20002,20001 ,9006,9007,9004 ,0,0,0}, - {20006,19985,20001 ,9014,9005,9004 ,0,0,0}, {20003,19982,19983 ,9009,9008,9000 ,0,0,0}, - {20002,19981,19982 ,9007,9006,9008 ,0,0,0}, {20000,19998,19978 ,9002,8999,8998 ,0,0,0}, - {19998,20003,19983 ,8999,9009,9000 ,0,0,0}, {19979,19999,19980 ,8992,9001,9003 ,0,0,0}, - {19980,20000,19978 ,9003,9002,8998 ,0,0,0}, {19976,20012,19996 ,8993,9024,8994 ,0,0,0}, - {19979,19996,19999 ,8992,8994,9001 ,0,0,0}, {19997,20012,19992 ,8997,9024,8995 ,0,0,0}, - {19976,19992,20012 ,8993,8995,9024 ,0,0,0}, {19995,19977,19975 ,8990,8996,8991 ,0,0,0}, - {19997,19977,19995 ,8997,8996,8990 ,0,0,0}, {19974,19973,19993 ,8989,8956,8987 ,0,0,0}, - {19994,19975,19974 ,8988,8991,8989 ,0,0,0}, {20013,19993,20014 ,9025,8987,9026 ,0,0,0}, - {20015,19997,20016 ,9027,9028,9029 ,0,0,0}, {20017,19995,19994 ,9030,9031,9032 ,0,0,0}, - {19999,20018,20000 ,9033,9034,9035 ,0,0,0}, {20012,20019,19996 ,9036,9037,9038 ,0,0,0}, - {20020,20002,20003 ,9039,9040,9041 ,0,0,0}, {20021,19998,20022 ,9042,9043,9044 ,0,0,0}, - {20023,20006,20024 ,9045,9046,9047 ,0,0,0}, {20001,20025,20024 ,9048,9049,9047 ,0,0,0}, - {20007,20004,20026 ,9050,9051,9052 ,0,0,0}, {20005,20027,20004 ,9053,9054,9051 ,0,0,0}, - {20028,20008,20007 ,9055,9056,9050 ,0,0,0}, {20007,20026,20028 ,9050,9052,9055 ,0,0,0}, - {20008,20029,20009 ,9056,9057,9058 ,0,0,0}, {20029,20008,20028 ,9057,9056,9055 ,0,0,0}, - {20010,20009,20030 ,9059,9058,9060 ,0,0,0}, {20029,20030,20009 ,9057,9060,9058 ,0,0,0}, - {20031,20011,20010 ,9061,9023,9059 ,0,0,0}, {20010,20030,20031 ,9059,9060,9061 ,0,0,0}, - {20023,20027,20005 ,9045,9054,9053 ,0,0,0}, {20004,20027,20026 ,9051,9054,9052 ,0,0,0}, - {20006,20001,20024 ,9046,9048,9047 ,0,0,0}, {20005,20006,20023 ,9053,9046,9045 ,0,0,0}, - {20025,20002,20020 ,9049,9040,9039 ,0,0,0}, {20001,20002,20025 ,9048,9040,9049 ,0,0,0}, - {20021,20003,19998 ,9042,9041,9043 ,0,0,0}, {20020,20003,20021 ,9039,9041,9042 ,0,0,0}, - {20018,20022,20000 ,9034,9044,9035 ,0,0,0}, {20022,19998,20000 ,9044,9043,9035 ,0,0,0}, - {19996,20032,19999 ,9038,9062,9033 ,0,0,0}, {20032,20018,19999 ,9062,9034,9033 ,0,0,0}, - {20012,20015,20019 ,9036,9027,9037 ,0,0,0}, {19996,20019,20032 ,9038,9037,9062 ,0,0,0}, - {19997,19995,20016 ,9028,9031,9029 ,0,0,0}, {20012,19997,20015 ,9036,9028,9027 ,0,0,0}, - {20017,19994,20013 ,9030,9032,9025 ,0,0,0}, {20016,19995,20017 ,9029,9031,9030 ,0,0,0}, - {19993,20013,19994 ,8987,9025,9032 ,0,0,0}, {20020,20021,20033 ,9063,9064,9065 ,0,0,0}, - {20034,20021,20022 ,9066,9064,9067 ,0,0,0}, {20021,20034,20033 ,9064,9066,9065 ,0,0,0}, - {20018,20035,20022 ,9068,9069,9067 ,0,0,0}, {20034,20022,20035 ,9066,9067,9069 ,0,0,0}, - {20018,20032,20036 ,9068,9070,9071 ,0,0,0}, {20036,20035,20018 ,9071,9069,9068 ,0,0,0}, - {20037,20032,20019 ,9072,9070,9073 ,0,0,0}, {20032,20037,20036 ,9070,9072,9071 ,0,0,0}, - {20015,20038,20019 ,9074,9075,9073 ,0,0,0}, {20037,20019,20038 ,9072,9073,9075 ,0,0,0}, - {20015,20016,20039 ,9074,9076,9077 ,0,0,0}, {20039,20038,20015 ,9077,9075,9074 ,0,0,0}, - {20040,20016,20017 ,9078,9076,9079 ,0,0,0}, {20016,20040,20039 ,9076,9078,9077 ,0,0,0}, - {20013,20041,20017 ,9080,9081,9079 ,0,0,0}, {20040,20017,20041 ,9078,9079,9081 ,0,0,0}, - {20014,20042,20041 ,9082,9083,9081 ,0,0,0}, {20041,20013,20014 ,9081,9080,9082 ,0,0,0}, - {20020,20033,20043 ,9063,9065,9084 ,0,0,0}, {20043,20044,20025 ,9084,9085,9086 ,0,0,0}, - {20025,20020,20043 ,9086,9063,9084 ,0,0,0}, {20024,20044,20045 ,9087,9085,9088 ,0,0,0}, - {20044,20024,20025 ,9085,9087,9086 ,0,0,0}, {20046,20023,20045 ,9089,9090,9088 ,0,0,0}, - {20024,20045,20023 ,9087,9088,9090 ,0,0,0}, {20046,20047,20027 ,9089,9091,9092 ,0,0,0}, - {20027,20023,20046 ,9092,9090,9089 ,0,0,0}, {20026,20047,20048 ,9093,9091,9094 ,0,0,0}, - {20047,20026,20027 ,9091,9093,9092 ,0,0,0}, {20049,20028,20048 ,9095,9096,9094 ,0,0,0}, - {20026,20048,20028 ,9093,9094,9096 ,0,0,0}, {20049,20050,20029 ,9095,9097,9098 ,0,0,0}, - {20029,20028,20049 ,9098,9096,9095 ,0,0,0}, {20030,20050,20051 ,9099,9097,9100 ,0,0,0}, - {20050,20030,20029 ,9097,9099,9098 ,0,0,0}, {20030,20051,20031 ,9099,9100,9101 ,0,0,0}, - {20052,20042,20053 ,9102,9103,9104 ,0,0,0}, {20054,20038,20055 ,9105,9106,9107 ,0,0,0}, - {20052,20056,20040 ,9102,9108,9109 ,0,0,0}, {20035,20057,20058 ,9110,9111,9112 ,0,0,0}, - {20037,20059,20036 ,9113,9114,9115 ,0,0,0}, {20060,20061,20043 ,9116,9117,9118 ,0,0,0}, - {20062,20033,20034 ,9119,9120,9121 ,0,0,0}, {20063,20046,20064 ,9122,9123,9124 ,0,0,0}, - {20045,20044,20065 ,9125,9126,9127 ,0,0,0}, {20066,20048,20047 ,9128,9129,9130 ,0,0,0}, - {20047,20063,20066 ,9130,9122,9128 ,0,0,0}, {20048,20067,20049 ,9129,9131,9132 ,0,0,0}, - {20067,20048,20066 ,9131,9129,9128 ,0,0,0}, {20050,20049,20068 ,9133,9132,9134 ,0,0,0}, - {20067,20068,20049 ,9131,9134,9132 ,0,0,0}, {20069,20051,20050 ,9135,9100,9133 ,0,0,0}, - {20050,20068,20069 ,9133,9134,9135 ,0,0,0}, {20046,20045,20064 ,9123,9125,9124 ,0,0,0}, - {20047,20046,20063 ,9130,9123,9122 ,0,0,0}, {20065,20044,20061 ,9127,9126,9117 ,0,0,0}, - {20064,20045,20065 ,9124,9125,9127 ,0,0,0}, {20060,20043,20033 ,9116,9118,9120 ,0,0,0}, - {20061,20044,20043 ,9117,9126,9118 ,0,0,0}, {20058,20062,20034 ,9112,9119,9121 ,0,0,0}, - {20062,20060,20033 ,9119,9116,9120 ,0,0,0}, {20036,20057,20035 ,9115,9111,9110 ,0,0,0}, - {20035,20058,20034 ,9110,9112,9121 ,0,0,0}, {20037,20054,20059 ,9113,9105,9114 ,0,0,0}, - {20036,20059,20057 ,9115,9114,9111 ,0,0,0}, {20038,20039,20055 ,9106,9136,9107 ,0,0,0}, - {20037,20038,20054 ,9113,9106,9105 ,0,0,0}, {20040,20056,20039 ,9109,9108,9136 ,0,0,0}, - {20055,20039,20056 ,9107,9136,9108 ,0,0,0}, {20052,20041,20042 ,9102,9137,9103 ,0,0,0}, - {20052,20040,20041 ,9102,9109,9137 ,0,0,0}, {20070,20053,20071 ,9138,9139,9140 ,0,0,0}, - {20072,20055,20073 ,9141,9142,9143 ,0,0,0}, {20074,20056,20052 ,9144,9145,9146 ,0,0,0}, - {20057,20075,20058 ,9147,9148,9149 ,0,0,0}, {20054,20076,20059 ,9150,9151,9152 ,0,0,0}, - {20077,20078,20060 ,9153,9154,9155 ,0,0,0}, {20077,20062,20079 ,9153,9156,9157 ,0,0,0}, - {20080,20064,20081 ,9158,9159,9160 ,0,0,0}, {20065,20061,20082 ,9161,9162,9163 ,0,0,0}, - {20083,20066,20063 ,9164,9165,9166 ,0,0,0}, {20063,20080,20083 ,9166,9158,9164 ,0,0,0}, - {20066,20084,20067 ,9165,9167,9168 ,0,0,0}, {20084,20066,20083 ,9167,9165,9164 ,0,0,0}, - {20068,20067,20085 ,9169,9168,9170 ,0,0,0}, {20084,20085,20067 ,9167,9170,9168 ,0,0,0}, - {20086,20069,20068 ,9171,9172,9169 ,0,0,0}, {20068,20085,20086 ,9169,9170,9171 ,0,0,0}, - {20064,20065,20081 ,9159,9161,9160 ,0,0,0}, {20063,20064,20080 ,9166,9159,9158 ,0,0,0}, - {20082,20061,20078 ,9163,9162,9154 ,0,0,0}, {20081,20065,20082 ,9160,9161,9163 ,0,0,0}, - {20077,20060,20062 ,9153,9155,9156 ,0,0,0}, {20078,20061,20060 ,9154,9162,9155 ,0,0,0}, - {20075,20079,20058 ,9148,9157,9149 ,0,0,0}, {20079,20062,20058 ,9157,9156,9149 ,0,0,0}, - {20059,20087,20057 ,9152,9173,9147 ,0,0,0}, {20087,20075,20057 ,9173,9148,9147 ,0,0,0}, - {20054,20072,20076 ,9150,9141,9151 ,0,0,0}, {20059,20076,20087 ,9152,9151,9173 ,0,0,0}, - {20055,20056,20073 ,9142,9145,9143 ,0,0,0}, {20054,20055,20072 ,9150,9142,9141 ,0,0,0}, - {20074,20052,20070 ,9144,9146,9138 ,0,0,0}, {20073,20056,20074 ,9143,9145,9144 ,0,0,0}, - {20053,20070,20052 ,9139,9138,9146 ,0,0,0}, {20088,20071,20089 ,9174,9175,9176 ,0,0,0}, - {20090,20073,20091 ,9177,9178,9179 ,0,0,0}, {20092,20074,20070 ,9180,9181,9182 ,0,0,0}, - {20087,20093,20094 ,9183,9184,9185 ,0,0,0}, {20072,20095,20076 ,9186,9187,9188 ,0,0,0}, - {20096,20097,20077 ,9189,9190,9191 ,0,0,0}, {20096,20079,20098 ,9189,9192,9193 ,0,0,0}, - {20099,20081,20100 ,9194,9195,9196 ,0,0,0}, {20082,20078,20101 ,9197,9198,9199 ,0,0,0}, - {20102,20083,20080 ,9200,9201,9202 ,0,0,0}, {20080,20099,20102 ,9202,9194,9200 ,0,0,0}, - {20083,20103,20084 ,9201,9203,9204 ,0,0,0}, {20103,20083,20102 ,9203,9201,9200 ,0,0,0}, - {20085,20084,20104 ,9205,9204,9206 ,0,0,0}, {20103,20104,20084 ,9203,9206,9204 ,0,0,0}, - {20105,20086,20085 ,9207,9208,9205 ,0,0,0}, {20085,20104,20105 ,9205,9206,9207 ,0,0,0}, - {20081,20082,20100 ,9195,9197,9196 ,0,0,0}, {20080,20081,20099 ,9202,9195,9194 ,0,0,0}, - {20101,20078,20097 ,9199,9198,9190 ,0,0,0}, {20100,20082,20101 ,9196,9197,9199 ,0,0,0}, - {20096,20077,20079 ,9189,9191,9192 ,0,0,0}, {20097,20078,20077 ,9190,9198,9191 ,0,0,0}, - {20094,20098,20075 ,9185,9193,9209 ,0,0,0}, {20098,20079,20075 ,9193,9192,9209 ,0,0,0}, - {20076,20093,20087 ,9188,9184,9183 ,0,0,0}, {20087,20094,20075 ,9183,9185,9209 ,0,0,0}, - {20072,20090,20095 ,9186,9177,9187 ,0,0,0}, {20076,20095,20093 ,9188,9187,9184 ,0,0,0}, - {20073,20074,20091 ,9178,9181,9179 ,0,0,0}, {20072,20073,20090 ,9186,9178,9177 ,0,0,0}, - {20092,20070,20088 ,9180,9182,9174 ,0,0,0}, {20091,20074,20092 ,9179,9181,9180 ,0,0,0}, - {20071,20088,20070 ,9175,9174,9182 ,0,0,0}, {19676,20089,19674 ,9210,9211,9212 ,0,0,0}, - {19677,20091,19678 ,9213,9214,9215 ,0,0,0}, {19688,20092,20088 ,9216,9217,9218 ,0,0,0}, - {20093,19701,19702 ,9219,9220,9221 ,0,0,0}, {20090,19689,20095 ,9222,9223,9224 ,0,0,0}, - {19704,19705,20096 ,9225,9226,9227 ,0,0,0}, {19703,20098,20094 ,9228,9229,9230 ,0,0,0}, - {19734,20100,20101 ,9231,9232,9233 ,0,0,0}, {19731,20097,19705 ,9234,9235,9226 ,0,0,0}, - {19735,20102,20099 ,9236,9237,9238 ,0,0,0}, {20099,19733,19735 ,9238,9239,9236 ,0,0,0}, - {20102,19736,20103 ,9237,9240,9241 ,0,0,0}, {19736,20102,19735 ,9240,9237,9236 ,0,0,0}, - {20103,19638,19635 ,9241,9242,9243 ,0,0,0}, {19736,19638,20103 ,9240,9242,9241 ,0,0,0}, - {19634,20104,19635 ,8461,9244,9243 ,0,0,0}, {20103,19635,20104 ,9241,9243,9244 ,0,0,0}, - {20105,20104,19634 ,9207,9244,8461 ,0,0,0}, {19733,20100,19734 ,9239,9232,9231 ,0,0,0}, - {20099,20100,19733 ,9238,9232,9239 ,0,0,0}, {19731,20101,20097 ,9234,9233,9235 ,0,0,0}, - {19734,20101,19731 ,9231,9233,9234 ,0,0,0}, {20096,20098,19704 ,9227,9229,9225 ,0,0,0}, - {19705,20097,20096 ,9226,9235,9227 ,0,0,0}, {19702,19703,20094 ,9221,9228,9230 ,0,0,0}, - {19703,19704,20098 ,9228,9225,9229 ,0,0,0}, {20095,19701,20093 ,9224,9220,9219 ,0,0,0}, - {20093,19702,20094 ,9219,9221,9230 ,0,0,0}, {20090,19677,19689 ,9222,9213,9223 ,0,0,0}, - {20095,19689,19701 ,9224,9223,9220 ,0,0,0}, {20091,20092,19678 ,9214,9217,9215 ,0,0,0}, - {20090,20091,19677 ,9222,9214,9213 ,0,0,0}, {19688,20088,19676 ,9216,9218,9210 ,0,0,0}, - {19678,20092,19688 ,9215,9217,9216 ,0,0,0}, {20089,19676,20088 ,9211,9210,9218 ,0,0,0}, - {20106,19614,20107 ,9245,8438,9246 ,0,0,0}, {20108,19724,19671 ,9247,9248,9249 ,0,0,0}, - {20109,19686,19612 ,9250,9251,9252 ,0,0,0}, {19729,20110,20111 ,9253,9254,9255 ,0,0,0}, - {19725,20112,19726 ,9256,9257,9258 ,0,0,0}, {20113,20114,19694 ,9259,9260,9261 ,0,0,0}, - {20115,19697,19698 ,9262,9263,9264 ,0,0,0}, {20116,19732,20117 ,9265,9266,9267 ,0,0,0}, - {19730,19695,20118 ,9268,9269,9270 ,0,0,0}, {20119,19709,19654 ,9271,9272,9273 ,0,0,0}, - {19654,20116,20119 ,9273,9265,9271 ,0,0,0}, {19709,20120,19737 ,9272,9274,9275 ,0,0,0}, - {20120,19709,20119 ,9274,9272,9271 ,0,0,0}, {19645,19737,20121 ,9276,9275,9277 ,0,0,0}, - {20120,20121,19737 ,9274,9277,9275 ,0,0,0}, {20122,19648,19645 ,9278,9279,9276 ,0,0,0}, - {19645,20121,20122 ,9276,9277,9278 ,0,0,0}, {19732,19730,20117 ,9266,9268,9267 ,0,0,0}, - {19654,19732,20116 ,9273,9266,9265 ,0,0,0}, {20118,19695,20114 ,9270,9269,9260 ,0,0,0}, - {20117,19730,20118 ,9267,9268,9270 ,0,0,0}, {20113,19694,19697 ,9259,9261,9263 ,0,0,0}, - {20114,19695,19694 ,9260,9269,9261 ,0,0,0}, {20111,20115,19698 ,9255,9262,9264 ,0,0,0}, - {20115,20113,19697 ,9262,9259,9263 ,0,0,0}, {19726,20110,19729 ,9258,9254,9253 ,0,0,0}, - {19729,20111,19698 ,9253,9255,9264 ,0,0,0}, {19725,20123,20112 ,9256,9280,9257 ,0,0,0}, - {19726,20112,20110 ,9258,9257,9254 ,0,0,0}, {20108,20123,19724 ,9247,9280,9248 ,0,0,0}, - {19725,19724,20123 ,9256,9248,9280 ,0,0,0}, {20109,19671,19686 ,9250,9249,9251 ,0,0,0}, - {20108,19671,20109 ,9247,9249,9250 ,0,0,0}, {20106,19612,19614 ,9245,9252,8438 ,0,0,0}, - {20109,19612,20106 ,9250,9252,9245 ,0,0,0}, {20124,20107,20125 ,9281,9246,9282 ,0,0,0}, - {20126,20108,20127 ,9283,9284,9285 ,0,0,0}, {20128,20109,20106 ,9286,9287,9288 ,0,0,0}, - {20110,20129,20130 ,9289,9290,9291 ,0,0,0}, {20123,20131,20112 ,9292,9293,9294 ,0,0,0}, - {20132,20114,20113 ,9295,9296,9297 ,0,0,0}, {20133,20115,20134 ,9298,9299,9300 ,0,0,0}, - {20135,20117,20136 ,9301,9302,9303 ,0,0,0}, {20118,20114,20137 ,9304,9296,9305 ,0,0,0}, - {20138,20119,20116 ,9306,9307,9308 ,0,0,0}, {20116,20135,20138 ,9308,9301,9306 ,0,0,0}, - {20119,20139,20120 ,9307,9309,9310 ,0,0,0}, {20139,20119,20138 ,9309,9307,9306 ,0,0,0}, - {20121,20120,20140 ,9311,9310,9312 ,0,0,0}, {20139,20140,20120 ,9309,9312,9310 ,0,0,0}, - {20141,20122,20121 ,9313,9314,9311 ,0,0,0}, {20121,20140,20141 ,9311,9312,9313 ,0,0,0}, - {20117,20118,20136 ,9302,9304,9303 ,0,0,0}, {20116,20117,20135 ,9308,9302,9301 ,0,0,0}, - {20137,20114,20132 ,9305,9296,9295 ,0,0,0}, {20136,20118,20137 ,9303,9304,9305 ,0,0,0}, - {20133,20113,20115 ,9298,9297,9299 ,0,0,0}, {20132,20113,20133 ,9295,9297,9298 ,0,0,0}, - {20130,20134,20111 ,9291,9300,9315 ,0,0,0}, {20134,20115,20111 ,9300,9299,9315 ,0,0,0}, - {20112,20129,20110 ,9294,9290,9289 ,0,0,0}, {20110,20130,20111 ,9289,9291,9315 ,0,0,0}, - {20123,20126,20131 ,9292,9283,9293 ,0,0,0}, {20112,20131,20129 ,9294,9293,9290 ,0,0,0}, - {20108,20109,20127 ,9284,9287,9285 ,0,0,0}, {20123,20108,20126 ,9292,9284,9283 ,0,0,0}, - {20128,20106,20124 ,9286,9288,9281 ,0,0,0}, {20127,20109,20128 ,9285,9287,9286 ,0,0,0}, - {20107,20124,20106 ,9246,9281,9288 ,0,0,0}, {20142,20125,20143 ,9316,9282,9317 ,0,0,0}, - {20144,20127,20145 ,9318,9319,9320 ,0,0,0}, {20146,20128,20124 ,9321,9322,9323 ,0,0,0}, - {20129,20147,20130 ,9324,9325,9326 ,0,0,0}, {20126,20148,20131 ,9327,9328,9329 ,0,0,0}, - {20149,20132,20133 ,9330,9331,9332 ,0,0,0}, {20150,20134,20151 ,9333,9334,9335 ,0,0,0}, - {20152,20136,20153 ,9336,9337,9338 ,0,0,0}, {20137,20132,20154 ,9339,9331,9340 ,0,0,0}, - {20155,20138,20135 ,9341,9342,9343 ,0,0,0}, {20135,20152,20155 ,9343,9336,9341 ,0,0,0}, - {20138,20156,20139 ,9342,9344,9345 ,0,0,0}, {20156,20138,20155 ,9344,9342,9341 ,0,0,0}, - {20140,20139,20157 ,9346,9345,9347 ,0,0,0}, {20156,20157,20139 ,9344,9347,9345 ,0,0,0}, - {20158,20141,20140 ,9348,9349,9346 ,0,0,0}, {20140,20157,20158 ,9346,9347,9348 ,0,0,0}, - {20136,20137,20153 ,9337,9339,9338 ,0,0,0}, {20135,20136,20152 ,9343,9337,9336 ,0,0,0}, - {20154,20132,20149 ,9340,9331,9330 ,0,0,0}, {20153,20137,20154 ,9338,9339,9340 ,0,0,0}, - {20150,20133,20134 ,9333,9332,9334 ,0,0,0}, {20149,20133,20150 ,9330,9332,9333 ,0,0,0}, - {20147,20151,20130 ,9325,9335,9326 ,0,0,0}, {20151,20134,20130 ,9335,9334,9326 ,0,0,0}, - {20131,20159,20129 ,9329,9350,9324 ,0,0,0}, {20159,20147,20129 ,9350,9325,9324 ,0,0,0}, - {20126,20144,20148 ,9327,9318,9328 ,0,0,0}, {20131,20148,20159 ,9329,9328,9350 ,0,0,0}, - {20127,20128,20145 ,9319,9322,9320 ,0,0,0}, {20126,20127,20144 ,9327,9319,9318 ,0,0,0}, - {20146,20124,20142 ,9321,9323,9316 ,0,0,0}, {20145,20128,20146 ,9320,9322,9321 ,0,0,0}, - {20125,20142,20124 ,9282,9316,9323 ,0,0,0}, {19742,20160,19779 ,9351,9352,8640 ,0,0,0}, - {19748,20161,19749 ,9353,9354,9355 ,0,0,0}, {19744,20162,20163 ,9356,9357,9358 ,0,0,0}, - {20164,19756,20165 ,9359,9360,9361 ,0,0,0}, {20166,19746,20167 ,9362,9363,9364 ,0,0,0}, - {19761,20168,20169 ,9365,9366,9367 ,0,0,0}, {19753,20170,19751 ,9368,9369,9370 ,0,0,0}, - {20171,20172,19766 ,9371,9372,9373 ,0,0,0}, {20173,19759,19758 ,9374,9375,9376 ,0,0,0}, - {20174,20175,19763 ,9377,9378,9379 ,0,0,0}, {19764,19763,20175 ,9380,9379,9378 ,0,0,0}, - {19770,20176,20174 ,9381,9382,9377 ,0,0,0}, {20174,19763,19770 ,9377,9379,9381 ,0,0,0}, - {20176,19772,20177 ,9382,9383,9384 ,0,0,0}, {19772,20176,19770 ,9383,9382,9381 ,0,0,0}, - {20178,20177,19773 ,9385,9384,9386 ,0,0,0}, {19772,19773,20177 ,9383,9386,9384 ,0,0,0}, - {19776,20179,20178 ,8637,9387,9385 ,0,0,0}, {20178,19773,19776 ,9385,9386,8637 ,0,0,0}, - {19766,19764,20171 ,9373,9380,9371 ,0,0,0}, {20171,19764,20175 ,9371,9380,9378 ,0,0,0}, - {20172,20173,19758 ,9372,9374,9376 ,0,0,0}, {20172,19758,19766 ,9372,9376,9373 ,0,0,0}, - {19759,20168,19761 ,9375,9366,9365 ,0,0,0}, {20173,20168,19759 ,9374,9366,9375 ,0,0,0}, - {19753,20169,20170 ,9368,9367,9369 ,0,0,0}, {19761,20169,19753 ,9365,9367,9368 ,0,0,0}, - {19756,19751,20165 ,9360,9370,9361 ,0,0,0}, {19751,20170,20165 ,9370,9369,9361 ,0,0,0}, - {20167,19778,20164 ,9364,9388,9359 ,0,0,0}, {19778,19756,20164 ,9388,9360,9359 ,0,0,0}, - {20166,19748,19746 ,9362,9353,9363 ,0,0,0}, {20167,19746,19778 ,9364,9363,9388 ,0,0,0}, - {20161,20162,19749 ,9354,9357,9355 ,0,0,0}, {20166,20161,19748 ,9362,9354,9353 ,0,0,0}, - {19744,20163,19742 ,9356,9358,9351 ,0,0,0}, {19749,20162,19744 ,9355,9357,9356 ,0,0,0}, - {20160,19742,20163 ,9352,9351,9358 ,0,0,0}, {20180,20143,20181 ,9389,9317,9390 ,0,0,0}, - {20182,20145,20183 ,9391,9392,9393 ,0,0,0}, {20184,20146,20142 ,9394,9395,9396 ,0,0,0}, - {20159,20185,20186 ,9397,9398,9399 ,0,0,0}, {20144,20187,20148 ,9400,9401,9402 ,0,0,0}, - {20188,20189,20150 ,9403,9404,9405 ,0,0,0}, {20190,20151,20147 ,9406,9407,9408 ,0,0,0}, - {20191,20153,20154 ,9409,9410,9411 ,0,0,0}, {20154,20149,20192 ,9411,9412,9413 ,0,0,0}, - {20193,20155,20152 ,9414,9415,9416 ,0,0,0}, {20152,20194,20193 ,9416,9417,9414 ,0,0,0}, - {20155,20195,20156 ,9415,9418,9419 ,0,0,0}, {20195,20155,20193 ,9418,9415,9414 ,0,0,0}, - {20157,20156,20196 ,9420,9419,9421 ,0,0,0}, {20195,20196,20156 ,9418,9421,9419 ,0,0,0}, - {20197,20157,20198 ,9422,9420,9423 ,0,0,0}, {20157,20196,20198 ,9420,9421,9423 ,0,0,0}, - {20158,20157,20197 ,9424,9420,9422 ,0,0,0}, {20194,20153,20191 ,9417,9410,9409 ,0,0,0}, - {20152,20153,20194 ,9416,9410,9417 ,0,0,0}, {20149,20189,20192 ,9412,9404,9413 ,0,0,0}, - {20191,20154,20192 ,9409,9411,9413 ,0,0,0}, {20188,20150,20151 ,9403,9405,9407 ,0,0,0}, - {20189,20149,20150 ,9404,9412,9405 ,0,0,0}, {20186,20190,20147 ,9399,9406,9408 ,0,0,0}, - {20190,20188,20151 ,9406,9403,9407 ,0,0,0}, {20148,20185,20159 ,9402,9398,9397 ,0,0,0}, - {20159,20186,20147 ,9397,9399,9408 ,0,0,0}, {20144,20182,20187 ,9400,9391,9401 ,0,0,0}, - {20148,20187,20185 ,9402,9401,9398 ,0,0,0}, {20145,20146,20183 ,9392,9395,9393 ,0,0,0}, - {20144,20145,20182 ,9400,9392,9391 ,0,0,0}, {20184,20142,20180 ,9394,9396,9389 ,0,0,0}, - {20183,20146,20184 ,9393,9395,9394 ,0,0,0}, {20143,20180,20142 ,9317,9389,9396 ,0,0,0}, - {20163,20181,20160 ,9425,9390,9426 ,0,0,0}, {20166,20183,20161 ,9427,9428,9429 ,0,0,0}, - {20162,20184,20180 ,9430,9431,9432 ,0,0,0}, {20185,20164,20165 ,9433,9434,9435 ,0,0,0}, - {20182,20167,20187 ,9436,9437,9438 ,0,0,0}, {20169,20168,20188 ,9439,9440,9441 ,0,0,0}, - {20170,20190,20186 ,9442,9443,9444 ,0,0,0}, {20171,20191,20172 ,9445,9446,9447 ,0,0,0}, - {20192,20189,20173 ,9448,9449,9450 ,0,0,0}, {20174,20193,20175 ,9451,9452,9453 ,0,0,0}, - {20194,20171,20175 ,9454,9445,9453 ,0,0,0}, {20174,20176,20195 ,9451,9455,9456 ,0,0,0}, - {20195,20193,20174 ,9456,9452,9451 ,0,0,0}, {20196,20176,20177 ,9457,9455,9458 ,0,0,0}, - {20176,20196,20195 ,9455,9457,9456 ,0,0,0}, {20178,20198,20177 ,9459,9460,9458 ,0,0,0}, - {20196,20177,20198 ,9457,9458,9460 ,0,0,0}, {20179,20197,20198 ,9461,9422,9460 ,0,0,0}, - {20198,20178,20179 ,9460,9459,9461 ,0,0,0}, {20191,20171,20194 ,9446,9445,9454 ,0,0,0}, - {20193,20194,20175 ,9452,9454,9453 ,0,0,0}, {20172,20192,20173 ,9447,9448,9450 ,0,0,0}, - {20191,20192,20172 ,9446,9448,9447 ,0,0,0}, {20168,20189,20188 ,9440,9449,9441 ,0,0,0}, - {20173,20189,20168 ,9450,9449,9440 ,0,0,0}, {20170,20169,20190 ,9442,9439,9443 ,0,0,0}, - {20169,20188,20190 ,9439,9441,9443 ,0,0,0}, {20185,20165,20186 ,9433,9435,9444 ,0,0,0}, - {20165,20170,20186 ,9435,9442,9444 ,0,0,0}, {20187,20167,20164 ,9438,9437,9434 ,0,0,0}, - {20187,20164,20185 ,9438,9434,9433 ,0,0,0}, {20182,20183,20166 ,9436,9428,9427 ,0,0,0}, - {20182,20166,20167 ,9436,9427,9437 ,0,0,0}, {20161,20184,20162 ,9429,9431,9430 ,0,0,0}, - {20183,20184,20161 ,9428,9431,9429 ,0,0,0}, {20163,20180,20181 ,9425,9432,9390 ,0,0,0}, - {20162,20180,20163 ,9430,9432,9425 ,0,0,0}, {19866,20199,20200 ,9462,9463,9464 ,0,0,0}, - {19865,20201,19863 ,9465,9466,9467 ,0,0,0}, {20199,19866,20202 ,9463,9462,9468 ,0,0,0}, - {20200,20203,19866 ,9464,9462,9462 ,0,0,0}, {20202,19866,19863 ,9468,9462,9467 ,0,0,0}, - {20204,20202,19863 ,9469,9468,9467 ,0,0,0}, {20204,19863,20201 ,9469,9467,9466 ,0,0,0}, - {19901,19819,20205 ,9470,9471,9472 ,0,0,0}, {19901,20206,20207 ,9470,9473,9474 ,0,0,0}, - {20205,20206,19901 ,9472,9473,9470 ,0,0,0}, {19865,20207,20208 ,9465,9474,9475 ,0,0,0}, - {19865,19901,20207 ,9465,9470,9474 ,0,0,0}, {19865,20209,20210 ,9465,9476,9477 ,0,0,0}, - {20208,20209,19865 ,9475,9476,9465 ,0,0,0}, {19865,20211,20212 ,9465,9478,9479 ,0,0,0}, - {20210,20211,19865 ,9477,9478,9465 ,0,0,0}, {20201,19865,20213 ,9466,9465,9480 ,0,0,0}, - {20212,20213,19865 ,9479,9480,9465 ,0,0,0}, {20214,19687,20215 ,9481,9482,9483 ,0,0,0}, - {19687,20216,20217 ,9482,9484,9485 ,0,0,0}, {20217,19685,19687 ,9485,9486,9482 ,0,0,0}, - {19687,20214,20216 ,9482,9481,9484 ,0,0,0}, {19685,20218,20219 ,9486,9487,9488 ,0,0,0}, - {19685,20217,20218 ,9486,9485,9487 ,0,0,0}, {19687,20220,20215 ,9482,9489,9483 ,0,0,0}, - {19685,20219,19614 ,9486,9488,9490 ,0,0,0}, {20221,19687,19672 ,9491,9482,9492 ,0,0,0}, - {19687,20221,20220 ,9482,9491,9489 ,0,0,0}, {19674,20222,20223 ,9493,9493,9494 ,0,0,0}, - {20224,20225,19675 ,9495,9496,9497 ,0,0,0}, {20226,20227,19674 ,9498,9499,9493 ,0,0,0}, - {20226,19674,20223 ,9498,9493,9494 ,0,0,0}, {19674,20228,19675 ,9493,9500,9497 ,0,0,0}, - {20228,19674,20227 ,9500,9493,9499 ,0,0,0}, {20229,19675,20225 ,9501,9497,9496 ,0,0,0}, - {20228,20224,19675 ,9500,9495,9497 ,0,0,0}, {20221,19672,20229 ,9491,9492,9501 ,0,0,0}, - {20229,19672,19675 ,9501,9492,9497 ,0,0,0}, {20222,19674,20230 ,9502,9503,9504 ,0,0,0}, - {20071,20230,20089 ,9505,9504,9506 ,0,0,0}, {20071,20053,20230 ,9505,9507,9504 ,0,0,0}, - {20230,20053,20042 ,9504,9507,9508 ,0,0,0}, {20042,20014,20230 ,9508,9509,9504 ,0,0,0}, - {20230,19674,20089 ,9504,9503,9506 ,0,0,0}, {20231,20229,20232 ,9510,9511,4303 ,0,0,0}, - {20231,20233,20221 ,9510,82,9512 ,0,0,0}, {20221,20229,20231 ,9512,9511,9510 ,0,0,0}, - {20234,20235,20236 ,9513,9514,9515 ,0,0,0}, {20235,20237,20236 ,9514,9516,9515 ,0,0,0}, - {20235,20234,20238 ,9514,9513,9517 ,0,0,0}, {20216,20239,20238 ,9518,9519,9517 ,0,0,0}, - {20234,20216,20238 ,9513,9518,9517 ,0,0,0}, {20214,20239,20216 ,9520,9519,9518 ,0,0,0}, - {20239,20214,20240 ,9519,9520,9521 ,0,0,0}, {20215,20241,20240 ,9522,9523,9521 ,0,0,0}, - {20240,20214,20215 ,9521,9520,9522 ,0,0,0}, {20241,20220,20242 ,9523,9524,9525 ,0,0,0}, - {20220,20241,20215 ,9524,9523,9522 ,0,0,0}, {20233,20242,20221 ,9526,9525,9527 ,0,0,0}, - {20220,20221,20242 ,9524,9527,9525 ,0,0,0}, {20227,20243,20244 ,9528,9529,9530 ,0,0,0}, - {20232,20229,20225 ,9531,9532,9533 ,0,0,0}, {20225,20224,20245 ,9533,9534,9535 ,0,0,0}, - {20246,20228,20244 ,9536,9537,9530 ,0,0,0}, {20245,20224,20246 ,9535,9534,9536 ,0,0,0}, - {20225,20245,20232 ,9533,9535,9531 ,0,0,0}, {20224,20228,20246 ,9534,9537,9536 ,0,0,0}, - {20228,20227,20244 ,9537,9528,9530 ,0,0,0}, {20243,20227,20226 ,9529,9528,9538 ,0,0,0}, - {20226,20223,20247 ,9538,9539,9540 ,0,0,0}, {20247,20243,20226 ,9540,9529,9538 ,0,0,0}, - {20248,20223,20222 ,9541,9539,9542 ,0,0,0}, {20223,20248,20247 ,9539,9541,9540 ,0,0,0}, - {20248,20222,20230 ,9541,9542,9542 ,0,0,0}, {20203,20249,20250 ,9543,9543,9544 ,0,0,0}, - {20203,20250,20251 ,9543,9544,9543 ,0,0,0}, {20252,20203,20251 ,9543,9543,9543 ,0,0,0}, - {20243,20247,20203 ,9543,9543,9543 ,0,0,0}, {20243,20203,20252 ,9543,9543,9543 ,0,0,0}, - {20203,20248,20230 ,9543,9543,9544 ,0,0,0}, {20247,20248,20203 ,9543,9543,9543 ,0,0,0}, - {20203,20230,19866 ,9543,9544,9543 ,0,0,0}, {20230,19993,19973 ,9544,9543,9543 ,0,0,0}, - {20230,20014,19993 ,9544,9544,9543 ,0,0,0}, {19973,19953,20230 ,9543,9544,9544 ,0,0,0}, - {19866,20230,19934 ,9543,9544,9543 ,0,0,0}, {20230,19953,19934 ,9544,9544,9543 ,0,0,0}, - {19779,20160,20253 ,9545,9546,9547 ,0,0,0}, {20205,20254,20206 ,9548,9549,9550 ,0,0,0}, - {20255,20254,19780 ,9551,9549,9552 ,0,0,0}, {20256,20237,20257 ,9553,9554,9555 ,0,0,0}, - {20258,20256,20257 ,9556,9553,9555 ,0,0,0}, {20259,20260,20261 ,9557,9558,9559 ,0,0,0}, - {20260,20258,20261 ,9558,9556,9559 ,0,0,0}, {20254,19800,19780 ,9549,9560,9552 ,0,0,0}, - {20255,19780,19740 ,9551,9552,9561 ,0,0,0}, {20259,20207,20206 ,9557,9562,9550 ,0,0,0}, - {19819,19800,20205 ,9563,9560,9548 ,0,0,0}, {19779,20255,19740 ,9545,9551,9561 ,0,0,0}, - {20253,20262,20255 ,9547,9564,9551 ,0,0,0}, {20255,19779,20253 ,9551,9545,9547 ,0,0,0}, - {20262,20256,20258 ,9564,9553,9556 ,0,0,0}, {20260,20259,20206 ,9558,9557,9550 ,0,0,0}, - {20258,20260,20255 ,9556,9558,9551 ,0,0,0}, {20205,19800,20254 ,9548,9560,9549 ,0,0,0}, - {20258,20255,20262 ,9556,9551,9564 ,0,0,0}, {20257,20261,20258 ,9555,9559,9556 ,0,0,0}, - {20206,20254,20260 ,9550,9549,9558 ,0,0,0}, {20255,20260,20254 ,9551,9558,9549 ,0,0,0}, - {20263,20264,20265 ,9565,9566,9567 ,0,0,0}, {20266,20267,20268 ,9568,9569,9570 ,0,0,0}, - {20269,20270,20271 ,9571,9572,9573 ,0,0,0}, {20237,20235,20272 ,9574,9575,9576 ,0,0,0}, - {20273,20274,20211 ,9577,9578,9579 ,0,0,0}, {20275,20276,20277 ,9580,9581,9582 ,0,0,0}, - {20278,20279,20264 ,9583,9584,9566 ,0,0,0}, {20201,20213,20279 ,9585,9586,9584 ,0,0,0}, - {20280,20242,20233 ,9587,9588,9589 ,0,0,0}, {20263,20265,20280 ,9565,9567,9587 ,0,0,0}, - {20201,20279,20278 ,9585,9584,9583 ,0,0,0}, {20268,20265,20264 ,9570,9567,9566 ,0,0,0}, - {20213,20281,20279 ,9586,9590,9584 ,0,0,0}, {20274,20281,20212 ,9578,9590,9591 ,0,0,0}, - {20282,20273,20277 ,9592,9577,9582 ,0,0,0}, {20283,20271,20267 ,9593,9573,9569 ,0,0,0}, - {20208,20259,20275 ,9594,9595,9580 ,0,0,0}, {20270,20282,20272 ,9572,9592,9576 ,0,0,0}, - {20207,20259,20208 ,9596,9595,9594 ,0,0,0}, {20275,20259,20261 ,9580,9595,9597 ,0,0,0}, - {20212,20281,20213 ,9591,9590,9586 ,0,0,0}, {20212,20211,20274 ,9591,9579,9578 ,0,0,0}, - {20280,20265,20242 ,9587,9567,9588 ,0,0,0}, {20278,20264,20263 ,9583,9566,9565 ,0,0,0}, - {20268,20264,20266 ,9570,9566,9568 ,0,0,0}, {20241,20242,20265 ,9598,9588,9567 ,0,0,0}, - {20266,20279,20281 ,9568,9584,9590 ,0,0,0}, {20257,20237,20272 ,9599,9574,9576 ,0,0,0}, - {20265,20268,20241 ,9567,9570,9598 ,0,0,0}, {20279,20266,20264 ,9584,9568,9566 ,0,0,0}, - {20267,20266,20283 ,9569,9568,9593 ,0,0,0}, {20240,20241,20268 ,9600,9598,9570 ,0,0,0}, - {20274,20283,20281 ,9578,9593,9590 ,0,0,0}, {20210,20273,20211 ,9601,9577,9579 ,0,0,0}, - {20268,20267,20240 ,9570,9569,9600 ,0,0,0}, {20281,20283,20266 ,9590,9593,9568 ,0,0,0}, - {20271,20283,20269 ,9573,9593,9571 ,0,0,0}, {20239,20240,20267 ,9602,9600,9569 ,0,0,0}, - {20273,20269,20274 ,9577,9571,9578 ,0,0,0}, {20209,20277,20210 ,9603,9582,9601 ,0,0,0}, - {20271,20238,20239 ,9573,9604,9602 ,0,0,0}, {20274,20269,20283 ,9578,9571,9593 ,0,0,0}, - {20269,20282,20270 ,9571,9592,9572 ,0,0,0}, {20239,20267,20271 ,9602,9569,9573 ,0,0,0}, - {20210,20277,20273 ,9601,9582,9577 ,0,0,0}, {20275,20209,20208 ,9580,9603,9594 ,0,0,0}, - {20270,20235,20238 ,9572,9575,9604 ,0,0,0}, {20273,20282,20269 ,9577,9592,9571 ,0,0,0}, - {20276,20272,20282 ,9581,9576,9592 ,0,0,0}, {20238,20271,20270 ,9604,9573,9572 ,0,0,0}, - {20209,20275,20277 ,9603,9580,9582 ,0,0,0}, {20277,20276,20282 ,9582,9581,9592 ,0,0,0}, - {20261,20257,20276 ,9597,9599,9581 ,0,0,0}, {20275,20261,20276 ,9580,9597,9581 ,0,0,0}, - {20257,20272,20276 ,9599,9576,9581 ,0,0,0}, {20235,20270,20272 ,9575,9572,9576 ,0,0,0}, - {20280,20231,20284 ,9605,9606,9607 ,0,0,0}, {20204,20285,20202 ,9608,9609,9468 ,0,0,0}, - {20284,20231,20286 ,9607,9606,9610 ,0,0,0}, {20231,20232,20286 ,9606,82,9610 ,0,0,0}, - {20284,20287,20285 ,9607,9611,9609 ,0,0,0}, {20280,20233,20231 ,9605,82,9606 ,0,0,0}, - {20285,20287,20202 ,9609,9611,9468 ,0,0,0}, {20278,20285,20204 ,9612,9609,9608 ,0,0,0}, - {20201,20278,20204 ,9613,9612,9608 ,0,0,0}, {20278,20263,20285 ,9612,9614,9609 ,0,0,0}, - {20263,20280,20284 ,9614,9605,9607 ,0,0,0}, {20263,20284,20285 ,9614,9607,9609 ,0,0,0}, - {20287,20284,20286 ,9611,9607,9610 ,0,0,0}, {20252,20251,20244 ,9615,9616,9617 ,0,0,0}, - {20286,20232,20245 ,9618,82,9619 ,0,0,0}, {20245,20246,20288 ,9619,9620,9621 ,0,0,0}, - {20245,20288,20286 ,9619,9621,9618 ,0,0,0}, {20243,20252,20244 ,9622,9615,9617 ,0,0,0}, - {20250,20249,20289 ,9623,9624,9625 ,0,0,0}, {20289,20290,20250 ,9625,9626,9623 ,0,0,0}, - {20287,20288,20291 ,9627,9621,9628 ,0,0,0}, {20291,20288,20290 ,9628,9621,9626 ,0,0,0}, - {20249,20203,20200 ,9624,9629,9630 ,0,0,0}, {20287,20291,20202 ,9627,9628,9631 ,0,0,0}, - {20200,20291,20289 ,9630,9628,9625 ,0,0,0}, {20286,20288,20287 ,9618,9621,9627 ,0,0,0}, - {20200,20199,20291 ,9630,9632,9628 ,0,0,0}, {20291,20199,20202 ,9628,9632,9631 ,0,0,0}, - {20288,20246,20290 ,9621,9620,9626 ,0,0,0}, {20244,20290,20246 ,9617,9626,9620 ,0,0,0}, - {20200,20289,20249 ,9630,9625,9624 ,0,0,0}, {20291,20290,20289 ,9628,9626,9625 ,0,0,0}, - {20251,20290,20244 ,9616,9626,9617 ,0,0,0}, {20251,20250,20290 ,9616,9623,9626 ,0,0,0}, - {20125,20292,20293 ,9633,9634,9635 ,0,0,0}, {20237,20256,20294 ,9636,9637,9638 ,0,0,0}, - {20295,20294,20256 ,9639,9638,9637 ,0,0,0}, {20125,20293,20143 ,9633,9635,9640 ,0,0,0}, - {20293,20292,20295 ,9635,9634,9639 ,0,0,0}, {20253,20160,20181 ,9641,9642,9643 ,0,0,0}, - {20143,20293,20181 ,9640,9635,9643 ,0,0,0}, {20219,20292,20107 ,9644,9634,9645 ,0,0,0}, - {20296,20219,20218 ,9646,9644,9647 ,0,0,0}, {20292,20125,20107 ,9634,9633,9645 ,0,0,0}, - {20294,20234,20236 ,9638,9648,9649 ,0,0,0}, {20294,20296,20297 ,9638,9646,9650 ,0,0,0}, - {20107,19614,20219 ,9645,9651,9644 ,0,0,0}, {20234,20297,20216 ,9648,9650,9652 ,0,0,0}, - {20297,20234,20294 ,9650,9648,9638 ,0,0,0}, {20293,20253,20181 ,9635,9641,9643 ,0,0,0}, - {20292,20296,20295 ,9634,9646,9639 ,0,0,0}, {20262,20253,20293 ,9653,9641,9635 ,0,0,0}, - {20219,20296,20292 ,9644,9646,9634 ,0,0,0}, {20297,20218,20217 ,9650,9647,9654 ,0,0,0}, - {20256,20262,20295 ,9637,9653,9639 ,0,0,0}, {20293,20295,20262 ,9635,9639,9653 ,0,0,0}, - {20218,20297,20296 ,9647,9650,9646 ,0,0,0}, {20216,20297,20217 ,9652,9650,9654 ,0,0,0}, - {20294,20236,20237 ,9638,9649,9636 ,0,0,0}, {20296,20294,20295 ,9646,9638,9639 ,0,0,0}, - {20298,19739,20299 ,9655,9656,9657 ,0,0,0}, {19739,20300,20301 ,9656,9658,9659 ,0,0,0}, - {20301,19738,19739 ,9659,9660,9656 ,0,0,0}, {19739,20298,20300 ,9656,9655,9658 ,0,0,0}, - {19738,20302,20303 ,9660,9661,9662 ,0,0,0}, {19738,20301,20302 ,9660,9659,9661 ,0,0,0}, - {19739,20304,20299 ,9656,9663,9657 ,0,0,0}, {19738,20303,19634 ,9660,9662,9664 ,0,0,0}, - {20305,19739,19647 ,9665,9656,9666 ,0,0,0}, {19739,20305,20304 ,9656,9665,9663 ,0,0,0}, - {19648,20306,20307 ,9667,9667,9668 ,0,0,0}, {20308,20309,19646 ,9669,9670,9671 ,0,0,0}, - {20310,20311,19648 ,9672,9673,9667 ,0,0,0}, {20310,19648,20307 ,9672,9667,9668 ,0,0,0}, - {19648,20312,19646 ,9667,9674,9671 ,0,0,0}, {20312,19648,20311 ,9674,9667,9673 ,0,0,0}, - {20313,19646,20309 ,9675,9671,9670 ,0,0,0}, {20312,20308,19646 ,9674,9669,9671 ,0,0,0}, - {20305,19647,20313 ,9665,9666,9675 ,0,0,0}, {20313,19647,19646 ,9675,9666,9671 ,0,0,0}, - {19856,20314,20315 ,9676,9677,9678 ,0,0,0}, {19933,20316,19887 ,9679,9680,9681 ,0,0,0}, - {20314,19856,20317 ,9677,9676,9682 ,0,0,0}, {20315,20318,19856 ,9678,9676,9676 ,0,0,0}, - {20317,19856,19887 ,9682,9676,9681 ,0,0,0}, {20319,20317,19887 ,9683,9682,9681 ,0,0,0}, - {20319,19887,20316 ,9683,9681,9680 ,0,0,0}, {19890,19914,20320 ,9684,9685,9686 ,0,0,0}, - {19890,20321,20322 ,9684,9687,9688 ,0,0,0}, {20320,20321,19890 ,9686,9687,9684 ,0,0,0}, - {19933,20322,20323 ,9679,9688,9689 ,0,0,0}, {19933,19890,20322 ,9679,9684,9688 ,0,0,0}, - {19933,20324,20325 ,9679,9690,9691 ,0,0,0}, {20323,20324,19933 ,9689,9690,9679 ,0,0,0}, - {19933,20326,20327 ,9679,9692,9693 ,0,0,0}, {20325,20326,19933 ,9691,9692,9679 ,0,0,0}, - {20316,19933,20328 ,9680,9679,9694 ,0,0,0}, {20327,20328,19933 ,9693,9694,9679 ,0,0,0}, - {20197,20306,20158 ,9695,9696,9695 ,0,0,0}, {19648,20122,20306 ,9695,9695,9696 ,0,0,0}, - {20179,20329,20306 ,9695,9696,9696 ,0,0,0}, {20306,20197,20179 ,9696,9695,9695 ,0,0,0}, - {20141,20158,20306 ,9695,9695,9696 ,0,0,0}, {20141,20306,20122 ,9695,9696,9695 ,0,0,0}, - {20330,20331,20305 ,126,126,126 ,0,0,0}, {20313,20332,20330 ,9697,126,126 ,0,0,0}, - {20330,20305,20313 ,126,126,9697 ,0,0,0}, {20333,20334,20335 ,9698,9699,9700 ,0,0,0}, - {20334,20336,20335 ,9699,9701,9700 ,0,0,0}, {20334,20333,20337 ,9699,9698,9702 ,0,0,0}, - {20300,20338,20337 ,9703,9704,9702 ,0,0,0}, {20333,20300,20337 ,9698,9703,9702 ,0,0,0}, - {20298,20338,20300 ,9705,9704,9703 ,0,0,0}, {20338,20298,20339 ,9704,9705,9706 ,0,0,0}, - {20299,20340,20339 ,9707,9708,9706 ,0,0,0}, {20339,20298,20299 ,9706,9705,9707 ,0,0,0}, - {20340,20304,20341 ,9708,9709,9710 ,0,0,0}, {20304,20340,20299 ,9709,9708,9707 ,0,0,0}, - {20331,20341,20305 ,9711,9710,9712 ,0,0,0}, {20304,20305,20341 ,9709,9712,9710 ,0,0,0}, - {20342,20343,20311 ,9713,9714,9715 ,0,0,0}, {20344,20312,20343 ,9716,9717,9714 ,0,0,0}, - {20313,20309,20332 ,126,9718,126 ,0,0,0}, {20308,20345,20309 ,9719,9720,9718 ,0,0,0}, - {20308,20344,20345 ,9719,9716,9720 ,0,0,0}, {20345,20332,20309 ,9720,126,9718 ,0,0,0}, - {20312,20344,20308 ,9717,9716,9719 ,0,0,0}, {20312,20311,20343 ,9717,9715,9714 ,0,0,0}, - {20342,20311,20310 ,9713,9715,9721 ,0,0,0}, {20310,20307,20346 ,9721,9722,9723 ,0,0,0}, - {20346,20342,20310 ,9723,9713,9721 ,0,0,0}, {20347,20307,20306 ,9724,9722,9725 ,0,0,0}, - {20307,20347,20346 ,9722,9724,9723 ,0,0,0}, {20347,20306,20329 ,9724,9725,9725 ,0,0,0}, - {19817,20329,19798 ,9726,9727,9728 ,0,0,0}, {20348,20318,20349 ,9729,9730,9731 ,0,0,0}, - {20318,20342,20346 ,9730,9732,9733 ,0,0,0}, {20346,20347,20318 ,9733,9734,9730 ,0,0,0}, - {20348,20350,20318 ,9729,9735,9730 ,0,0,0}, {20318,20351,20342 ,9730,9736,9732 ,0,0,0}, - {20350,20351,20318 ,9735,9736,9730 ,0,0,0}, {20329,19856,20318 ,9727,9737,9730 ,0,0,0}, - {20347,20329,20318 ,9734,9727,9730 ,0,0,0}, {20329,19836,19856 ,9727,9738,9737 ,0,0,0}, - {19836,20329,19817 ,9738,9727,9726 ,0,0,0}, {20329,19776,19777 ,9727,9739,9740 ,0,0,0}, - {20329,20179,19776 ,9727,9727,9739 ,0,0,0}, {19777,19798,20329 ,9740,9728,9727 ,0,0,0}, - {20011,20031,20352 ,9741,9742,9743 ,0,0,0}, {20320,20353,20321 ,9744,9745,9746 ,0,0,0}, - {20354,20353,19972 ,9747,9745,9748 ,0,0,0}, {20355,20336,20356 ,9749,9750,9751 ,0,0,0}, - {20357,20355,20356 ,9752,9749,9751 ,0,0,0}, {20358,20359,20360 ,9753,9754,9755 ,0,0,0}, - {20359,20357,20360 ,9754,9752,9755 ,0,0,0}, {20353,19952,19972 ,9745,9756,9748 ,0,0,0}, - {20354,19972,19991 ,9747,9748,9757 ,0,0,0}, {20358,20322,20321 ,9753,9758,9746 ,0,0,0}, - {19914,19952,20320 ,9759,9756,9744 ,0,0,0}, {20011,20354,19991 ,9741,9747,9757 ,0,0,0}, - {20352,20361,20354 ,9743,9760,9747 ,0,0,0}, {20354,20011,20352 ,9747,9741,9743 ,0,0,0}, - {20361,20355,20357 ,9760,9749,9752 ,0,0,0}, {20359,20358,20321 ,9754,9753,9746 ,0,0,0}, - {20357,20359,20354 ,9752,9754,9747 ,0,0,0}, {20320,19952,20353 ,9744,9756,9745 ,0,0,0}, - {20357,20354,20361 ,9752,9747,9760 ,0,0,0}, {20356,20360,20357 ,9751,9755,9752 ,0,0,0}, - {20321,20353,20359 ,9746,9745,9754 ,0,0,0}, {20354,20359,20353 ,9747,9754,9745 ,0,0,0}, - {20362,20363,20364 ,9761,9762,9763 ,0,0,0}, {20338,20365,20366 ,9764,9765,9766 ,0,0,0}, - {20338,20339,20365 ,9764,9767,9765 ,0,0,0}, {20356,20334,20367 ,9768,9769,9770 ,0,0,0}, - {20368,20326,20369 ,9771,9772,9773 ,0,0,0}, {20356,20336,20334 ,9768,9774,9769 ,0,0,0}, - {20370,20371,20372 ,9775,9776,9777 ,0,0,0}, {20340,20373,20374 ,9778,9779,9780 ,0,0,0}, - {20331,20371,20375 ,126,9776,9781 ,0,0,0}, {20370,20376,20375 ,9775,9782,9781 ,0,0,0}, - {20328,20327,20377 ,9783,9784,9785 ,0,0,0}, {20327,20368,20377 ,9784,9771,9785 ,0,0,0}, - {20378,20379,20362 ,9786,9787,9761 ,0,0,0}, {20368,20369,20376 ,9771,9773,9782 ,0,0,0}, - {20380,20316,20328 ,9788,9789,9783 ,0,0,0}, {20337,20366,20367 ,9790,9766,9770 ,0,0,0}, - {20340,20374,20339 ,9778,9780,9767 ,0,0,0}, {20367,20364,20360 ,9770,9763,9791 ,0,0,0}, - {20360,20364,20358 ,9791,9763,9792 ,0,0,0}, {20358,20363,20322 ,9792,9762,9793 ,0,0,0}, - {20356,20367,20360 ,9768,9770,9791 ,0,0,0}, {20334,20337,20367 ,9769,9790,9770 ,0,0,0}, - {20363,20358,20364 ,9762,9792,9763 ,0,0,0}, {20363,20379,20323 ,9762,9787,9794 ,0,0,0}, - {20364,20366,20362 ,9763,9766,9761 ,0,0,0}, {20322,20363,20323 ,9793,9762,9794 ,0,0,0}, - {20367,20366,20364 ,9770,9766,9763 ,0,0,0}, {20337,20338,20366 ,9790,9764,9766 ,0,0,0}, - {20379,20363,20362 ,9787,9762,9761 ,0,0,0}, {20379,20381,20324 ,9787,9795,9796 ,0,0,0}, - {20362,20365,20378 ,9761,9765,9786 ,0,0,0}, {20323,20379,20324 ,9794,9787,9796 ,0,0,0}, - {20366,20365,20362 ,9766,9765,9761 ,0,0,0}, {20374,20365,20339 ,9780,9765,9767 ,0,0,0}, - {20381,20379,20378 ,9795,9787,9786 ,0,0,0}, {20381,20369,20325 ,9795,9773,9797 ,0,0,0}, - {20374,20382,20378 ,9780,9798,9786 ,0,0,0}, {20324,20381,20325 ,9796,9795,9797 ,0,0,0}, - {20374,20378,20365 ,9780,9786,9765 ,0,0,0}, {20341,20373,20340 ,9799,9779,9778 ,0,0,0}, - {20369,20381,20382 ,9773,9795,9798 ,0,0,0}, {20378,20382,20381 ,9786,9798,9795 ,0,0,0}, - {20373,20376,20382 ,9779,9782,9798 ,0,0,0}, {20325,20369,20326 ,9797,9773,9772 ,0,0,0}, - {20374,20373,20382 ,9780,9779,9798 ,0,0,0}, {20331,20375,20341 ,126,9781,9799 ,0,0,0}, - {20377,20368,20370 ,9785,9771,9775 ,0,0,0}, {20382,20376,20369 ,9798,9782,9773 ,0,0,0}, - {20376,20370,20368 ,9782,9775,9771 ,0,0,0}, {20326,20368,20327 ,9772,9771,9784 ,0,0,0}, - {20373,20341,20375 ,9779,9799,9781 ,0,0,0}, {20376,20373,20375 ,9782,9779,9781 ,0,0,0}, - {20377,20372,20380 ,9785,9777,9788 ,0,0,0}, {20371,20370,20375 ,9776,9775,9781 ,0,0,0}, - {20380,20328,20377 ,9788,9783,9785 ,0,0,0}, {20372,20377,20370 ,9777,9785,9775 ,0,0,0}, - {20371,20330,20383 ,9800,9801,9802 ,0,0,0}, {20319,20384,20317 ,9803,9804,9682 ,0,0,0}, - {20383,20330,20385 ,9802,9801,9805 ,0,0,0}, {20330,20332,20385 ,9801,126,9805 ,0,0,0}, - {20383,20386,20384 ,9802,9806,9804 ,0,0,0}, {20371,20331,20330 ,9800,126,9801 ,0,0,0}, - {20384,20386,20317 ,9804,9806,9682 ,0,0,0}, {20380,20384,20319 ,9807,9804,9803 ,0,0,0}, - {20316,20380,20319 ,9808,9807,9803 ,0,0,0}, {20380,20372,20384 ,9807,9809,9804 ,0,0,0}, - {20372,20371,20383 ,9809,9800,9802 ,0,0,0}, {20372,20383,20384 ,9809,9802,9804 ,0,0,0}, - {20386,20383,20385 ,9806,9802,9805 ,0,0,0}, {20351,20350,20343 ,9810,9811,9812 ,0,0,0}, - {20385,20332,20345 ,9813,126,9814 ,0,0,0}, {20345,20344,20387 ,9814,9815,9816 ,0,0,0}, - {20345,20387,20385 ,9814,9816,9813 ,0,0,0}, {20342,20351,20343 ,9817,9810,9812 ,0,0,0}, - {20348,20349,20388 ,9818,9819,9820 ,0,0,0}, {20388,20389,20348 ,9820,9821,9818 ,0,0,0}, - {20386,20387,20390 ,9822,9816,9823 ,0,0,0}, {20390,20387,20389 ,9823,9816,9821 ,0,0,0}, - {20349,20318,20315 ,9819,9824,9825 ,0,0,0}, {20386,20390,20317 ,9822,9823,9826 ,0,0,0}, - {20315,20390,20388 ,9825,9823,9820 ,0,0,0}, {20385,20387,20386 ,9813,9816,9822 ,0,0,0}, - {20315,20314,20390 ,9825,9827,9823 ,0,0,0}, {20390,20314,20317 ,9823,9827,9826 ,0,0,0}, - {20387,20344,20389 ,9816,9815,9821 ,0,0,0}, {20343,20389,20344 ,9812,9821,9815 ,0,0,0}, - {20315,20388,20349 ,9825,9820,9819 ,0,0,0}, {20390,20389,20388 ,9823,9821,9820 ,0,0,0}, - {20350,20389,20343 ,9811,9821,9812 ,0,0,0}, {20350,20348,20389 ,9811,9818,9821 ,0,0,0}, - {20391,20086,20392 ,9828,9829,9830 ,0,0,0}, {20105,19634,20303 ,9831,9832,9833 ,0,0,0}, - {20333,20393,20300 ,9834,9835,9836 ,0,0,0}, {20394,20355,20395 ,9837,9838,9839 ,0,0,0}, - {20355,20394,20335 ,9838,9837,9840 ,0,0,0}, {20335,20336,20355 ,9840,9841,9838 ,0,0,0}, - {20361,20395,20355 ,9842,9839,9838 ,0,0,0}, {20391,20069,20086 ,9828,9843,9829 ,0,0,0}, - {20335,20394,20333 ,9840,9837,9834 ,0,0,0}, {20393,20395,20396 ,9835,9839,9844 ,0,0,0}, - {20352,20031,20051 ,9845,9846,9847 ,0,0,0}, {20069,20391,20051 ,9843,9828,9847 ,0,0,0}, - {20396,20302,20301 ,9844,9848,9849 ,0,0,0}, {20392,20105,20303 ,9830,9831,9833 ,0,0,0}, - {20394,20395,20393 ,9837,9839,9835 ,0,0,0}, {20396,20301,20393 ,9844,9849,9835 ,0,0,0}, - {20300,20393,20301 ,9836,9835,9849 ,0,0,0}, {20333,20394,20393 ,9834,9837,9835 ,0,0,0}, - {20391,20361,20352 ,9828,9842,9845 ,0,0,0}, {20396,20391,20392 ,9844,9828,9830 ,0,0,0}, - {20396,20395,20391 ,9844,9839,9828 ,0,0,0}, {20302,20396,20392 ,9848,9844,9830 ,0,0,0}, - {20361,20391,20395 ,9842,9828,9839 ,0,0,0}, {20051,20391,20352 ,9847,9828,9845 ,0,0,0}, - {20105,20392,20086 ,9831,9830,9829 ,0,0,0}, {20392,20303,20302 ,9830,9833,9848 ,0,0,0}, - {19728,19592,19591 ,9850,9851,8275 ,0,0,0}, {20397,20398,19617 ,9852,9853,9854 ,0,0,0}, - {19664,20399,20400 ,9855,9856,9857 ,0,0,0}, {19622,19621,20401 ,9858,9859,9860 ,0,0,0}, - {19661,19696,20402 ,9861,9862,9863 ,0,0,0}, {19625,19626,20403 ,9864,9865,9866 ,0,0,0}, - {19625,20404,19621 ,9864,9867,9859 ,0,0,0}, {20405,19716,20406 ,9868,9869,9870 ,0,0,0}, - {19716,20405,19626 ,9869,9868,9865 ,0,0,0}, {20407,20406,19715 ,9871,9870,9872 ,0,0,0}, - {19716,19715,20406 ,9869,9872,9870 ,0,0,0}, {19605,4818,20407 ,126,126,9871 ,0,0,0}, - {20407,19715,19605 ,9871,9872,126 ,0,0,0}, {20403,20404,19625 ,9866,9867,9864 ,0,0,0}, - {19626,20405,20403 ,9865,9868,9866 ,0,0,0}, {20401,20402,19622 ,9860,9863,9858 ,0,0,0}, - {19621,20404,20401 ,9859,9867,9860 ,0,0,0}, {20397,19661,20402 ,9852,9861,9863 ,0,0,0}, - {19696,19622,20402 ,9862,9858,9863 ,0,0,0}, {20398,19615,19617 ,9853,9873,9854 ,0,0,0}, - {20397,19617,19661 ,9852,9854,9861 ,0,0,0}, {19664,19615,20399 ,9855,9873,9856 ,0,0,0}, - {20398,20399,19615 ,9853,9856,9873 ,0,0,0}, {19728,20400,20408 ,9850,9857,9874 ,0,0,0}, - {19664,20400,19728 ,9855,9857,9850 ,0,0,0}, {19592,19728,20408 ,9851,9850,9874 ,0,0,0}, - {20399,19571,19574 ,730,730,730 ,0,0,0}, {19587,20409,19585 ,730,730,730 ,0,0,0}, - {19587,19590,20410 ,730,730,730 ,0,0,0}, {19583,19585,20411 ,730,730,730 ,0,0,0}, - {19590,19577,20410 ,730,730,730 ,0,0,0}, {20409,19587,20410 ,730,730,730 ,0,0,0}, - {19577,19590,19592 ,730,730,730 ,0,0,0}, {19583,20412,19580 ,730,730,730 ,0,0,0}, - {20408,19577,19592 ,730,730,730 ,0,0,0}, {19559,19571,20397 ,730,730,730 ,0,0,0}, - {19594,19582,20413 ,730,730,730 ,0,0,0}, {20414,19595,19594 ,730,730,730 ,0,0,0}, - {8402,19559,20402 ,730,730,730 ,0,0,0}, {19561,20401,20404 ,730,730,730 ,0,0,0}, - {20415,19598,19595 ,730,730,730 ,0,0,0}, {19598,20416,19599 ,730,730,730 ,0,0,0}, - {19601,19599,20417 ,730,730,730 ,0,0,0}, {20404,19562,19561 ,730,730,730 ,0,0,0}, - {19562,20403,20405 ,730,730,730 ,0,0,0}, {19569,20407,4818 ,730,730,730 ,0,0,0}, - {4818,19604,19569 ,730,730,730 ,0,0,0}, {19601,20418,19604 ,730,730,730 ,0,0,0}, - {20406,19568,20405 ,730,730,730 ,0,0,0}, {19582,19580,20413 ,730,730,730 ,0,0,0}, - {19574,19576,20400 ,730,730,730 ,0,0,0}, {20402,20401,8402 ,730,730,730 ,0,0,0}, - {20409,20411,19585 ,730,730,730 ,0,0,0}, {20411,20412,19583 ,730,730,730 ,0,0,0}, - {20412,20413,19580 ,730,730,730 ,0,0,0}, {20413,20414,19594 ,730,730,730 ,0,0,0}, - {20414,20415,19595 ,730,730,730 ,0,0,0}, {20415,20416,19598 ,730,730,730 ,0,0,0}, - {20416,20417,19599 ,730,730,730 ,0,0,0}, {20417,20418,19601 ,730,730,730 ,0,0,0}, - {20418,19569,19604 ,730,730,730 ,0,0,0}, {19569,19565,20407 ,730,730,730 ,0,0,0}, - {19565,19568,20406 ,730,730,730 ,0,0,0}, {19565,20406,20407 ,730,730,730 ,0,0,0}, - {19568,19562,20405 ,730,730,730 ,0,0,0}, {20403,19562,20404 ,730,730,730 ,0,0,0}, - {19561,8402,20401 ,730,730,730 ,0,0,0}, {19559,20397,20402 ,730,730,730 ,0,0,0}, - {19571,20398,20397 ,730,730,730 ,0,0,0}, {20399,19574,20400 ,730,730,730 ,0,0,0}, - {20398,19571,20399 ,730,730,730 ,0,0,0}, {20400,19576,20408 ,730,730,730 ,0,0,0}, - {19577,20408,19576 ,730,730,730 ,0,0,0}, {19575,20419,20420 ,730,730,9875 ,0,0,0}, - {20421,20420,20422 ,730,9875,730 ,0,0,0}, {20421,20422,20423 ,730,730,9875 ,0,0,0}, - {20424,20420,20421 ,730,9875,730 ,0,0,0}, {20424,19578,20420 ,730,730,9875 ,0,0,0}, - {20423,20422,20425 ,9875,730,9876 ,0,0,0}, {19575,20420,19578 ,730,9875,730 ,0,0,0}, - {20419,19573,20426 ,730,730,9876 ,0,0,0}, {20419,19575,19573 ,730,730,730 ,0,0,0}, - {20426,19573,20427 ,9876,730,730 ,0,0,0}, {20427,19573,19572 ,730,730,9876 ,0,0,0}, - {20427,19572,19570 ,730,9876,730 ,0,0,0}, {20428,19570,19558 ,9877,730,9876 ,0,0,0}, - {19570,20428,20427 ,730,9877,730 ,0,0,0}, {19566,20428,19563 ,730,9877,730 ,0,0,0}, - {19558,19563,20428 ,9876,730,9877 ,0,0,0}, {19567,19560,19564 ,9876,730,9878 ,0,0,0}, - {19563,19560,19567 ,730,730,9876 ,0,0,0}, {19567,19566,19563 ,9876,730,730 ,0,0,0}, - {19569,20418,20428 ,9879,9880,9881 ,0,0,0}, {20420,20419,20415 ,9882,9883,9884 ,0,0,0}, - {20426,20427,20417 ,9885,9886,9887 ,0,0,0}, {20425,20413,20412 ,9888,9889,9890 ,0,0,0}, - {20414,20413,20422 ,9891,9889,9892 ,0,0,0}, {20421,20411,20409 ,9893,9894,9895 ,0,0,0}, - {20411,20421,20423 ,9894,9893,9896 ,0,0,0}, {20410,20424,20409 ,9897,9898,9895 ,0,0,0}, - {20421,20409,20424 ,9893,9895,9898 ,0,0,0}, {20410,19577,19578 ,9897,96,96 ,0,0,0}, - {19578,20424,20410 ,96,9898,9897 ,0,0,0}, {20425,20412,20423 ,9888,9890,9896 ,0,0,0}, - {20412,20411,20423 ,9890,9894,9896 ,0,0,0}, {20415,20414,20420 ,9884,9891,9882 ,0,0,0}, - {20414,20422,20420 ,9891,9892,9882 ,0,0,0}, {20422,20413,20425 ,9892,9889,9888 ,0,0,0}, - {20427,20428,20418 ,9886,9881,9880 ,0,0,0}, {20416,20415,20419 ,9899,9884,9883 ,0,0,0}, - {20418,20417,20427 ,9880,9887,9886 ,0,0,0}, {20416,20426,20417 ,9899,9885,9887 ,0,0,0}, - {20419,20426,20416 ,9883,9885,9899 ,0,0,0}, {20428,19566,19569 ,9881,761,9879 ,0,0,0}, - {19630,19546,19545 ,9900,82,9901 ,0,0,0}, {20429,20430,19712 ,9902,9903,9904 ,0,0,0}, - {19713,20431,19632 ,9905,9906,9907 ,0,0,0}, {20432,19651,20433 ,9908,9909,9910 ,0,0,0}, - {19708,19653,20434 ,9911,9912,9913 ,0,0,0}, {20435,19650,19710 ,9914,9915,9916 ,0,0,0}, - {19650,20435,20433 ,9915,9914,9910 ,0,0,0}, {19642,20436,19710 ,9917,9918,9916 ,0,0,0}, - {20435,19710,20436 ,9914,9916,9918 ,0,0,0}, {19642,19557,19556 ,9917,2619,3135 ,0,0,0}, - {19556,20436,19642 ,3135,9918,9917 ,0,0,0}, {19651,20432,19653 ,9909,9908,9912 ,0,0,0}, - {19651,19650,20433 ,9909,9915,9910 ,0,0,0}, {20429,19708,20434 ,9902,9911,9913 ,0,0,0}, - {20434,19653,20432 ,9913,9912,9908 ,0,0,0}, {20430,19713,19712 ,9903,9905,9904 ,0,0,0}, - {20429,19712,19708 ,9902,9904,9911 ,0,0,0}, {20431,20437,19632 ,9906,9919,9907 ,0,0,0}, - {20430,20431,19713 ,9903,9906,9905 ,0,0,0}, {19546,19630,20437 ,82,9900,9919 ,0,0,0}, - {19632,20437,19630 ,9907,9919,9900 ,0,0,0}, {19553,20429,19554 ,730,730,730 ,0,0,0}, - {19550,20431,19551 ,730,730,730 ,0,0,0}, {19556,20434,20432 ,730,730,730 ,0,0,0}, - {20436,20432,20433 ,730,730,730 ,0,0,0}, {20435,20436,20433 ,730,730,730 ,0,0,0}, - {19554,20434,19556 ,730,730,730 ,0,0,0}, {19556,20432,20436 ,730,730,730 ,0,0,0}, - {19554,20429,20434 ,730,730,730 ,0,0,0}, {19553,20430,20429 ,730,730,730 ,0,0,0}, - {19553,19551,20431 ,730,730,730 ,0,0,0}, {20431,20430,19553 ,730,730,730 ,0,0,0}, - {20437,20431,19550 ,730,730,730 ,0,0,0}, {20437,19547,19546 ,730,730,730 ,0,0,0}, - {19547,20437,19550 ,730,730,730 ,0,0,0}, {19546,19547,19539 ,730,730,730 ,0,0,0}, - {19542,19536,19540 ,730,730,730 ,0,0,0}, {19539,19536,19542 ,730,730,730 ,0,0,0}, - {19542,19546,19539 ,730,730,730 ,0,0,0}, {19723,19524,19525 ,9920,9921,9922 ,0,0,0}, - {20438,20439,19669 ,9902,9903,9923 ,0,0,0}, {19670,20440,19722 ,9924,9906,9925 ,0,0,0}, - {20441,19667,19666 ,9908,9926,9927 ,0,0,0}, {19683,19667,20442 ,9928,9926,8336 ,0,0,0}, - {20443,19727,19619 ,9914,9929,9930 ,0,0,0}, {19666,19727,20444 ,9927,9929,9910 ,0,0,0}, - {19618,20445,19619 ,9931,9918,9930 ,0,0,0}, {20443,19619,20445 ,9914,9930,9918 ,0,0,0}, - {19618,19535,19534 ,9931,96,9932 ,0,0,0}, {19534,20445,19618 ,9932,9918,9931 ,0,0,0}, - {20441,19666,20444 ,9908,9927,9910 ,0,0,0}, {20444,19727,20443 ,9910,9929,9914 ,0,0,0}, - {19683,20442,20438 ,9928,8336,9902 ,0,0,0}, {20442,19667,20441 ,8336,9926,9908 ,0,0,0}, - {20439,19670,19669 ,9903,9924,9923 ,0,0,0}, {20438,19669,19683 ,9902,9923,9928 ,0,0,0}, - {20440,20446,19722 ,9906,9919,9925 ,0,0,0}, {20439,20440,19670 ,9903,9906,9924 ,0,0,0}, - {19524,19723,20446 ,9921,9920,9919 ,0,0,0}, {19722,20446,19723 ,9925,9919,9920 ,0,0,0}, - {19529,20438,19531 ,730,730,730 ,0,0,0}, {19526,20440,19528 ,730,730,730 ,0,0,0}, - {19534,20442,20441 ,730,730,730 ,0,0,0}, {20445,20441,20444 ,730,730,730 ,0,0,0}, - {20443,20445,20444 ,730,730,730 ,0,0,0}, {19531,20442,19534 ,730,730,730 ,0,0,0}, - {19534,20441,20445 ,730,730,730 ,0,0,0}, {19531,20438,20442 ,730,730,730 ,0,0,0}, - {19529,20439,20438 ,730,730,730 ,0,0,0}, {19529,19528,20440 ,730,730,730 ,0,0,0}, - {20440,20439,19529 ,730,730,730 ,0,0,0}, {20446,20440,19526 ,730,730,730 ,0,0,0}, - {20446,19514,19524 ,730,730,730 ,0,0,0}, {19514,20446,19526 ,730,730,730 ,0,0,0}, - {19524,19514,19517 ,730,730,730 ,0,0,0}, {19520,19518,19521 ,730,730,730 ,0,0,0}, - {19517,19518,19520 ,730,730,730 ,0,0,0}, {19520,19524,19517 ,730,730,730 ,0,0,0} -// X-Ufo 8ZollPropeller.prt - , {20447,20448,20449 ,9933,9934,9935 ,0,0,0}, {20447,20450,20451 ,9933,9936,9937 ,0,0,0}, - {20451,20448,20447 ,9937,9934,9933 ,0,0,0}, {20452,20450,20453 ,9938,9936,9939 ,0,0,0}, - {20450,20452,20451 ,9936,9938,9937 ,0,0,0}, {20454,20455,20456 ,9940,9941,9942 ,0,0,0}, - {20452,20453,20455 ,9938,9939,9941 ,0,0,0}, {20457,20458,20454 ,9943,2394,9940 ,0,0,0}, - {20457,20459,20458 ,9943,9944,2394 ,0,0,0}, {20457,20454,20456 ,9943,9940,9942 ,0,0,0}, - {20455,20453,20456 ,9941,9939,9942 ,0,0,0}, {20460,20449,20448 ,9945,9935,9934 ,0,0,0}, - {20461,20460,20462 ,9946,9945,9947 ,0,0,0}, {20460,20461,20449 ,9945,9946,9935 ,0,0,0}, - {20463,20464,20462 ,9948,9949,9947 ,0,0,0}, {20461,20462,20464 ,9946,9947,9949 ,0,0,0}, - {20463,20465,20466 ,9948,9950,9951 ,0,0,0}, {20466,20464,20463 ,9951,9949,9948 ,0,0,0}, - {20467,20465,20468 ,9952,9950,9953 ,0,0,0}, {20465,20467,20466 ,9950,9952,9951 ,0,0,0}, - {20467,20468,20469 ,9952,9953,9954 ,0,0,0}, {20470,20471,20472 ,9938,9955,9956 ,0,0,0}, - {20470,20473,20471 ,9938,9937,9955 ,0,0,0}, {20470,20472,20474 ,9938,9956,9941 ,0,0,0}, - {20474,20475,20476 ,9941,9957,9940 ,0,0,0}, {20475,20474,20472 ,9957,9941,9956 ,0,0,0}, - {20477,20476,20475 ,9958,9940,9957 ,0,0,0}, {20478,20471,20473 ,9959,9955,9937 ,0,0,0}, - {20477,20479,20480 ,9958,9960,9961 ,0,0,0}, {20480,20476,20477 ,9961,9940,9958 ,0,0,0}, - {20478,20473,20481 ,9959,9937,9962 ,0,0,0}, {20481,20482,20478 ,9962,9963,9959 ,0,0,0}, - {20483,20482,20484 ,9964,9963,9945 ,0,0,0}, {20481,20484,20482 ,9962,9945,9963 ,0,0,0}, - {20485,20486,20483 ,9947,9965,9964 ,0,0,0}, {20483,20484,20485 ,9964,9945,9947 ,0,0,0}, - {20487,20488,20486 ,9948,9950,9965 ,0,0,0}, {20487,20486,20485 ,9948,9965,9947 ,0,0,0}, - {20489,20488,20490 ,9966,9950,9967 ,0,0,0}, {20488,20489,20486 ,9950,9966,9965 ,0,0,0}, - {20489,20490,20491 ,9966,9967,9968 ,0,0,0}, {20492,20493,8447 ,9969,9970,9971 ,0,0,0}, - {20494,20495,20496 ,9972,9973,9974 ,0,0,0}, {20497,20492,8447 ,9975,9969,9971 ,0,0,0}, - {20494,20496,20498 ,9972,9974,9976 ,0,0,0}, {20495,20494,20497 ,9973,9972,9975 ,0,0,0}, - {20495,20497,8447 ,9973,9975,9971 ,0,0,0}, {20499,20500,20501 ,9977,9978,9979 ,0,0,0}, - {20501,20498,20502 ,9979,9976,9980 ,0,0,0}, {20499,20501,20502 ,9977,9979,9980 ,0,0,0}, - {20500,20499,20503 ,9978,9977,9981 ,0,0,0}, {20502,20498,20496 ,9980,9976,9974 ,0,0,0}, - {20492,20504,20493 ,9969,9945,9970 ,0,0,0}, {20505,20504,20506 ,9982,9945,9983 ,0,0,0}, - {20504,20505,20493 ,9945,9982,9970 ,0,0,0}, {20507,20508,20506 ,9984,9985,9983 ,0,0,0}, - {20505,20506,20508 ,9982,9983,9985 ,0,0,0}, {20507,20509,20510 ,9984,9986,9987 ,0,0,0}, - {20510,20508,20507 ,9987,9985,9984 ,0,0,0}, {20511,20509,20512 ,9988,9986,21 ,0,0,0}, - {20509,20511,20510 ,9986,9988,9987 ,0,0,0}, {20513,20514,20515 ,9989,9990,9991 ,0,0,0}, - {20515,20514,20516 ,9991,9990,9992 ,0,0,0}, {20517,20514,20513 ,9993,9990,9989 ,0,0,0}, - {20518,20515,20516 ,9994,9991,9992 ,0,0,0}, {20517,20513,20519 ,9993,9989,9995 ,0,0,0}, - {20519,20520,20521 ,9995,9996,9997 ,0,0,0}, {20520,20519,20513 ,9996,9995,9989 ,0,0,0}, - {20518,20516,20522 ,9994,9992,9998 ,0,0,0}, {20523,20524,20521 ,9999,10000,9997 ,0,0,0}, - {20521,20520,20523 ,9997,9996,9999 ,0,0,0}, {20524,20525,20526 ,10000,9961,10001 ,0,0,0}, - {20527,20524,20523 ,10002,10000,9999 ,0,0,0}, {20527,20525,20524 ,10002,9961,10000 ,0,0,0}, - {20516,20528,20522 ,9992,10003,9998 ,0,0,0}, {20528,20529,20530 ,10003,10004,10005 ,0,0,0}, - {20530,20522,20528 ,10005,9998,10003 ,0,0,0}, {20531,20529,20532 ,10006,10004,10007 ,0,0,0}, - {20529,20531,20530 ,10004,10006,10005 ,0,0,0}, {20533,20534,20532 ,10008,10009,10007 ,0,0,0}, - {20531,20532,20534 ,10006,10007,10009 ,0,0,0}, {20533,20535,20536 ,10008,10010,10011 ,0,0,0}, - {20536,20534,20533 ,10011,10009,10008 ,0,0,0}, {20537,20535,20538 ,10012,10010,10013 ,0,0,0}, - {20535,20537,20536 ,10010,10012,10011 ,0,0,0}, {20537,20538,20539 ,10012,10013,10014 ,0,0,0}, - {20539,20538,20540 ,10014,10013,10015 ,0,0,0}, {20541,20542,20543 ,10016,10017,10018 ,0,0,0}, - {20544,20545,20546 ,10019,10020,10021 ,0,0,0}, {20547,20548,20549 ,10022,10023,10024 ,0,0,0}, - {20550,20551,20552 ,10025,10026,10027 ,0,0,0}, {20553,20554,20555 ,10028,10029,10030 ,0,0,0}, - {20555,20469,20553 ,10030,10031,10028 ,0,0,0}, {20556,20557,20558 ,10032,10033,10034 ,0,0,0}, - {20534,20559,20531 ,10035,10036,10037 ,0,0,0}, {20560,20558,20561 ,10038,10034,10039 ,0,0,0}, - {20562,20563,20564 ,10040,10041,10042 ,0,0,0}, {20565,20566,20567 ,10043,10044,10045 ,0,0,0}, - {20568,20569,20570 ,10046,10047,10048 ,0,0,0}, {20571,20559,20564 ,10049,10036,10042 ,0,0,0}, - {20572,20483,20486 ,10050,10051,10052 ,0,0,0}, {20573,20574,20570 ,10053,10054,10048 ,0,0,0}, - {20575,20576,20577 ,10055,10056,10057 ,0,0,0}, {20578,20579,20575 ,10058,10059,10055 ,0,0,0}, - {20580,20581,20578 ,10060,10061,10058 ,0,0,0}, {20582,20578,20581 ,10062,10058,10061 ,0,0,0}, - {20583,20581,20580 ,10063,10061,10060 ,0,0,0}, {20584,20585,20586 ,10064,10065,10066 ,0,0,0}, - {20587,20572,20576 ,10067,10050,10056 ,0,0,0}, {20588,20589,20584 ,10068,10069,10064 ,0,0,0}, - {20537,20539,20564 ,10070,10071,10042 ,0,0,0}, {20566,20590,20567 ,10044,10072,10045 ,0,0,0}, - {20557,20591,20558 ,10033,10073,10034 ,0,0,0}, {20592,20593,20594 ,10074,10075,10076 ,0,0,0}, - {20515,20595,20513 ,10077,10078,10079 ,0,0,0}, {20552,20591,20596 ,10027,10073,10080 ,0,0,0}, - {20597,20466,20598 ,10081,10082,10083 ,0,0,0}, {20599,20600,20550 ,10084,10085,10025 ,0,0,0}, - {20545,20601,20602 ,10020,10086,10087 ,0,0,0}, {20603,20604,20605 ,10088,10089,10090 ,0,0,0}, - {20544,20546,20606 ,10019,10021,10091 ,0,0,0}, {20542,20541,20607 ,10017,10016,10092 ,0,0,0}, - {20608,20546,20603 ,10093,10021,10088 ,0,0,0}, {20609,20610,20611 ,10094,10095,10096 ,0,0,0}, - {20610,20607,20541 ,10095,10092,10016 ,0,0,0}, {20449,20612,20447 ,10097,10098,10099 ,0,0,0}, - {20613,20543,20614 ,10100,10018,10101 ,0,0,0}, {20544,20615,20616 ,10019,10102,10103 ,0,0,0}, - {20600,20525,20617 ,10085,10104,10105 ,0,0,0}, {20603,20546,20545 ,10088,10021,10020 ,0,0,0}, - {20603,20602,20618 ,10088,10087,10106 ,0,0,0}, {20545,20602,20603 ,10020,10087,10088 ,0,0,0}, - {20619,20620,20548 ,10107,10108,10023 ,0,0,0}, {20608,20547,20621 ,10093,10022,10109 ,0,0,0}, - {20543,20457,20456 ,10018,10110,10111 ,0,0,0}, {20622,20620,20619 ,10112,10108,10107 ,0,0,0}, - {20542,20622,20619 ,10017,10112,10107 ,0,0,0}, {20610,20541,20611 ,10095,10016,10096 ,0,0,0}, - {20607,20622,20542 ,10092,10112,10017 ,0,0,0}, {20614,20543,20456 ,10101,10018,10111 ,0,0,0}, - {20543,20613,20623 ,10018,10100,10113 ,0,0,0}, {20612,20614,20447 ,10098,10101,10099 ,0,0,0}, - {20614,20612,20613 ,10101,10098,10100 ,0,0,0}, {20461,20597,20449 ,10114,10081,10097 ,0,0,0}, - {20466,20597,20464 ,10082,10081,10115 ,0,0,0}, {20597,20612,20449 ,10081,10098,10097 ,0,0,0}, - {20598,20624,20597 ,10083,10116,10081 ,0,0,0}, {20467,20598,20466 ,10117,10083,10082 ,0,0,0}, - {20598,20469,20555 ,10083,10031,10030 ,0,0,0}, {20518,20625,20595 ,10118,10119,10078 ,0,0,0}, - {20626,20561,20558 ,10120,10039,10034 ,0,0,0}, {20566,20627,20628 ,10044,10121,10122 ,0,0,0}, - {20477,20627,20479 ,10123,10121,10124 ,0,0,0}, {20626,20629,20630 ,10120,10125,10126 ,0,0,0}, - {20560,20556,20558 ,10038,10032,10034 ,0,0,0}, {20515,20518,20595 ,10077,10118,10078 ,0,0,0}, - {20557,20631,20591 ,10033,10127,10073 ,0,0,0}, {20558,20591,20632 ,10034,10073,10128 ,0,0,0}, - {20591,20552,20551 ,10073,10027,10026 ,0,0,0}, {20600,20551,20550 ,10085,10026,10025 ,0,0,0}, - {20591,20551,20633 ,10073,10026,10129 ,0,0,0}, {20634,20617,20592 ,10130,10105,10074 ,0,0,0}, - {20600,20635,20551 ,10085,10131,10026 ,0,0,0}, {20545,20616,20555 ,10020,10103,10030 ,0,0,0}, - {20615,20635,20634 ,10102,10131,10130 ,0,0,0}, {20594,20598,20555 ,10076,10083,10030 ,0,0,0}, - {20555,20554,20545 ,10030,10029,10020 ,0,0,0}, {20594,20636,20598 ,10076,10132,10083 ,0,0,0}, - {20637,20594,20593 ,10133,10076,10075 ,0,0,0}, {20595,20638,20593 ,10078,10134,10075 ,0,0,0}, - {20595,20625,20639 ,10078,10119,10135 ,0,0,0}, {20518,20522,20625 ,10118,10136,10119 ,0,0,0}, - {20522,20530,20625 ,10136,10137,10119 ,0,0,0}, {20625,20559,20640 ,10119,10036,10138 ,0,0,0}, - {20534,20564,20559 ,10035,10042,10036 ,0,0,0}, {20536,20564,20534 ,10139,10042,10035 ,0,0,0}, - {20564,20536,20537 ,10042,10139,10070 ,0,0,0}, {20625,20531,20559 ,10119,10037,10036 ,0,0,0}, - {20539,20562,20564 ,10071,10040,10042 ,0,0,0}, {20641,20627,20642 ,10140,10121,10141 ,0,0,0}, - {20589,20588,20643 ,10069,10068,10142 ,0,0,0}, {20644,20575,20584 ,10143,10055,10064 ,0,0,0}, - {20584,20575,20645 ,10064,10055,10144 ,0,0,0}, {20645,20585,20584 ,10144,10065,10064 ,0,0,0}, - {20584,20589,20644 ,10064,10069,10143 ,0,0,0}, {20646,20571,20563 ,10145,10049,10041 ,0,0,0}, - {20590,20589,20643 ,10072,10069,10142 ,0,0,0}, {20590,20643,20647 ,10072,10142,10146 ,0,0,0}, - {20567,20590,20648 ,10045,10072,10147 ,0,0,0}, {20565,20479,20566 ,10043,10124,10044 ,0,0,0}, - {20649,20626,20628 ,10148,10120,10122 ,0,0,0}, {20627,20566,20479 ,10121,10044,10124 ,0,0,0}, - {20562,20539,20650 ,10040,10071,10149 ,0,0,0}, {20561,20562,20651 ,10039,10040,10150 ,0,0,0}, - {20641,20563,20649 ,10140,10041,10148 ,0,0,0}, {20641,20652,20646 ,10140,10151,10145 ,0,0,0}, - {20653,20482,20483 ,10152,10153,10051 ,0,0,0}, {20653,20478,20482 ,10152,10154,10153 ,0,0,0}, - {20654,20653,20574 ,10155,10152,10054 ,0,0,0}, {20652,20642,20654 ,10151,10141,10155 ,0,0,0}, - {20483,20572,20653 ,10051,10050,10152 ,0,0,0}, {20491,20577,20576 ,10156,10057,10056 ,0,0,0}, - {20619,20655,20542 ,10107,10157,10017 ,0,0,0}, {20549,20548,20620 ,10024,10023,10108 ,0,0,0}, - {20608,20656,20548 ,10093,10158,10023 ,0,0,0}, {20459,20457,20655 ,10159,10110,10157 ,0,0,0}, - {20656,20655,20619 ,10158,10157,10107 ,0,0,0}, {20655,20457,20543 ,10157,10110,10018 ,0,0,0}, - {20542,20655,20543 ,10017,10157,10018 ,0,0,0}, {20623,20611,20541 ,10113,10096,10016 ,0,0,0}, - {20547,20608,20548 ,10022,10093,10023 ,0,0,0}, {20621,20606,20546 ,10109,10091,10021 ,0,0,0}, - {20655,20657,20658 ,10157,10160,10161 ,0,0,0}, {20548,20656,20619 ,10023,10158,10107 ,0,0,0}, - {20605,20656,20603 ,10090,10158,10088 ,0,0,0}, {20459,20655,20658 ,10159,10157,10161 ,0,0,0}, - {20456,20453,20614 ,10111,10162,10101 ,0,0,0}, {20623,20541,20543 ,10113,10016,10018 ,0,0,0}, - {20621,20546,20608 ,10109,10021,10093 ,0,0,0}, {20606,20659,20544 ,10091,10163,10019 ,0,0,0}, - {20604,20603,20618 ,10089,10088,10106 ,0,0,0}, {20608,20603,20656 ,10093,10088,10158 ,0,0,0}, - {20657,20656,20605 ,10160,10158,10090 ,0,0,0}, {20656,20657,20655 ,10158,10160,10157 ,0,0,0}, - {20453,20450,20614 ,10162,10164,10101 ,0,0,0}, {20614,20450,20447 ,10101,10164,10099 ,0,0,0}, - {20660,20615,20659 ,10165,10102,10163 ,0,0,0}, {20660,20661,20635 ,10165,10166,10131 ,0,0,0}, - {20601,20545,20662 ,10086,10020,10167 ,0,0,0}, {20554,20662,20545 ,10029,10167,10020 ,0,0,0}, - {20612,20597,20624 ,10098,10081,10116 ,0,0,0}, {20461,20464,20597 ,10114,10115,10081 ,0,0,0}, - {20615,20544,20659 ,10102,10019,10163 ,0,0,0}, {20663,20525,20600 ,10168,10104,10085 ,0,0,0}, - {20555,20616,20592 ,10030,10103,10074 ,0,0,0}, {20544,20616,20545 ,10019,10103,10020 ,0,0,0}, - {20592,20616,20634 ,10074,10103,10130 ,0,0,0}, {20469,20598,20467 ,10031,10083,10117 ,0,0,0}, - {20555,20592,20594 ,10030,10074,10076 ,0,0,0}, {20598,20636,20624 ,10083,10132,10116 ,0,0,0}, - {20660,20635,20615 ,10165,10131,10102 ,0,0,0}, {20664,20635,20661 ,10169,10131,10166 ,0,0,0}, - {20525,20527,20617 ,10104,10170,10105 ,0,0,0}, {20615,20634,20616 ,10102,10130,10103 ,0,0,0}, - {20600,20617,20634 ,10085,10105,10130 ,0,0,0}, {20513,20595,20520 ,10079,10078,10171 ,0,0,0}, - {20593,20592,20617 ,10075,10074,10105 ,0,0,0}, {20636,20594,20637 ,10132,10076,10133 ,0,0,0}, - {20635,20664,20551 ,10131,10169,10026 ,0,0,0}, {20633,20551,20664 ,10129,10026,10169 ,0,0,0}, - {20663,20600,20599 ,10168,10085,10084 ,0,0,0}, {20635,20600,20634 ,10131,10085,10130 ,0,0,0}, - {20527,20523,20617 ,10170,10172,10105 ,0,0,0}, {20617,20523,20520 ,10105,10172,10171 ,0,0,0}, - {20520,20593,20617 ,10171,10075,10105 ,0,0,0}, {20637,20593,20638 ,10133,10075,10134 ,0,0,0}, - {20591,20633,20632 ,10073,10129,10128 ,0,0,0}, {20631,20596,20591 ,10127,10080,10073 ,0,0,0}, - {20638,20595,20639 ,10134,10078,10135 ,0,0,0}, {20520,20595,20593 ,10171,10078,10075 ,0,0,0}, - {20632,20629,20558 ,10128,10125,10034 ,0,0,0}, {20558,20629,20626 ,10034,10125,10120 ,0,0,0}, - {20531,20625,20530 ,10037,10119,10137 ,0,0,0}, {20625,20640,20639 ,10119,10138,10135 ,0,0,0}, - {20626,20562,20561 ,10120,10040,10039 ,0,0,0}, {20630,20665,20628 ,10126,10173,10122 ,0,0,0}, - {20475,20627,20477 ,10174,10121,10123 ,0,0,0}, {20651,20562,20650 ,10150,10040,10149 ,0,0,0}, - {20649,20562,20626 ,10148,10040,10120 ,0,0,0}, {20666,20559,20571 ,10175,10036,10049 ,0,0,0}, - {20564,20563,20571 ,10042,10041,10049 ,0,0,0}, {20640,20559,20666 ,10138,10036,10175 ,0,0,0}, - {20630,20628,20626 ,10126,10122,10120 ,0,0,0}, {20665,20667,20566 ,10173,10176,10044 ,0,0,0}, - {20471,20642,20472 ,10177,10141,10178 ,0,0,0}, {20562,20649,20563 ,10040,10148,10041 ,0,0,0}, - {20649,20628,20627 ,10148,10122,10121 ,0,0,0}, {20571,20668,20669 ,10049,10179,10180 ,0,0,0}, - {20563,20641,20646 ,10041,10140,10145 ,0,0,0}, {20666,20571,20669 ,10175,10049,10180 ,0,0,0}, - {20665,20566,20628 ,10173,10044,10122 ,0,0,0}, {20667,20590,20566 ,10176,10072,10044 ,0,0,0}, - {20642,20475,20472 ,10141,10174,10178 ,0,0,0}, {20649,20627,20641 ,10148,10121,10140 ,0,0,0}, - {20627,20475,20642 ,10121,10174,10141 ,0,0,0}, {20646,20670,20668 ,10145,10181,10179 ,0,0,0}, - {20641,20642,20652 ,10140,10141,10151 ,0,0,0}, {20668,20571,20646 ,10179,10049,10145 ,0,0,0}, - {20589,20590,20667 ,10069,10072,10176 ,0,0,0}, {20647,20648,20590 ,10146,10147,10072 ,0,0,0}, - {20653,20471,20478 ,10152,10177,10154 ,0,0,0}, {20652,20671,20670 ,10151,10182,10181 ,0,0,0}, - {20642,20653,20654 ,10141,10152,10155 ,0,0,0}, {20670,20646,20652 ,10181,10145,10151 ,0,0,0}, - {20584,20586,20588 ,10064,10066,10068 ,0,0,0}, {20644,20672,20575 ,10143,10183,10055 ,0,0,0}, - {20486,20489,20576 ,10052,10184,10056 ,0,0,0}, {20486,20576,20572 ,10052,10056,10050 ,0,0,0}, - {20654,20573,20671 ,10155,10053,10182 ,0,0,0}, {20653,20642,20471 ,10152,10141,10177 ,0,0,0}, - {20653,20572,20574 ,10152,10050,10054 ,0,0,0}, {20671,20652,20654 ,10182,10151,10155 ,0,0,0}, - {20575,20577,20645 ,10055,10057,10144 ,0,0,0}, {20672,20580,20578 ,10183,10060,10058 ,0,0,0}, - {20673,20569,20568 ,10185,10047,10046 ,0,0,0}, {20491,20576,20489 ,10156,10056,10184 ,0,0,0}, - {20576,20579,20587 ,10056,10059,10067 ,0,0,0}, {20568,20574,20572 ,10046,10054,10050 ,0,0,0}, - {20587,20568,20572 ,10067,10046,10050 ,0,0,0}, {20573,20654,20574 ,10053,10155,10054 ,0,0,0}, - {20672,20578,20575 ,10183,10058,10055 ,0,0,0}, {20575,20579,20576 ,10055,10059,10056 ,0,0,0}, - {20582,20674,20579 ,10062,10186,10059 ,0,0,0}, {20578,20582,20579 ,10058,10062,10059 ,0,0,0}, - {20674,20673,20587 ,10186,10185,10067 ,0,0,0}, {20579,20674,20587 ,10059,10186,10067 ,0,0,0}, - {20673,20568,20587 ,10185,10046,10067 ,0,0,0}, {20570,20574,20568 ,10048,10054,10046 ,0,0,0}, - {20675,20676,20677 ,10187,10188,10189 ,0,0,0}, {20678,20679,20676 ,10190,10191,10188 ,0,0,0}, - {20680,20681,20682 ,10192,10193,10194 ,0,0,0}, {20683,20684,20685 ,10195,10196,10197 ,0,0,0}, - {20686,20687,20688 ,10198,10199,10200 ,0,0,0}, {20689,20690,20691 ,10201,10202,10203 ,0,0,0}, - {20692,20693,20694 ,10204,10205,10206 ,0,0,0}, {20695,20696,20697 ,10207,10208,10209 ,0,0,0}, - {20698,20699,20700 ,10210,10211,10212 ,0,0,0}, {20701,20702,20703 ,10213,10214,10215 ,0,0,0}, - {20704,20705,20698 ,10216,10217,10210 ,0,0,0}, {20698,20700,20704 ,10210,10212,10216 ,0,0,0}, - {20705,20706,20707 ,10217,10218,10219 ,0,0,0}, {20706,20705,20704 ,10218,10217,10216 ,0,0,0}, - {20708,20707,20709 ,10220,10219,10221 ,0,0,0}, {20706,20709,20707 ,10218,10221,10219 ,0,0,0}, - {20710,20711,20708 ,10222,10223,10220 ,0,0,0}, {20708,20709,20710 ,10220,10221,10222 ,0,0,0}, - {20712,20711,20710 ,10224,10223,10222 ,0,0,0}, {20699,20703,20700 ,10211,10215,10212 ,0,0,0}, - {20701,20693,20702 ,10213,10205,10214 ,0,0,0}, {20699,20701,20703 ,10211,10213,10215 ,0,0,0}, - {20692,20694,20695 ,10204,10206,10207 ,0,0,0}, {20702,20693,20692 ,10214,10205,10204 ,0,0,0}, - {20697,20696,20688 ,10209,10208,10200 ,0,0,0}, {20695,20694,20696 ,10207,10206,10208 ,0,0,0}, - {20690,20687,20686 ,10202,10199,10198 ,0,0,0}, {20687,20697,20688 ,10199,10209,10200 ,0,0,0}, - {20713,20689,20691 ,10225,10201,10203 ,0,0,0}, {20691,20690,20686 ,10203,10202,10198 ,0,0,0}, - {20680,20713,20681 ,10192,10225,10193 ,0,0,0}, {20713,20680,20689 ,10225,10192,10201 ,0,0,0}, - {20682,20683,20685 ,10194,10195,10197 ,0,0,0}, {20681,20683,20682 ,10193,10195,10194 ,0,0,0}, - {20678,20684,20679 ,10190,10196,10191 ,0,0,0}, {20685,20684,20678 ,10197,10196,10190 ,0,0,0}, - {20677,20714,20675 ,10189,10226,10187 ,0,0,0}, {20676,20679,20677 ,10188,10191,10189 ,0,0,0}, - {20715,20716,20676 ,10227,10228,10229 ,0,0,0}, {20717,20678,20716 ,10230,10231,10228 ,0,0,0}, - {20689,20680,20718 ,10232,10233,10234 ,0,0,0}, {20682,20685,20719 ,10235,10236,10237 ,0,0,0}, - {20687,20720,20697 ,10238,10239,10240 ,0,0,0}, {20721,20722,20690 ,10241,10242,10243 ,0,0,0}, - {20723,20702,20692 ,10244,10245,10246 ,0,0,0}, {20724,20695,20725 ,10247,10248,10249 ,0,0,0}, - {20704,20700,20726 ,10250,10251,10252 ,0,0,0}, {20703,20727,20728 ,10253,10254,10255 ,0,0,0}, - {20729,20706,20704 ,10256,10257,10250 ,0,0,0}, {20704,20726,20729 ,10250,10252,10256 ,0,0,0}, - {20706,20730,20709 ,10257,10258,10259 ,0,0,0}, {20730,20706,20729 ,10258,10257,10256 ,0,0,0}, - {20710,20709,20731 ,10260,10259,10261 ,0,0,0}, {20730,20731,20709 ,10258,10261,10259 ,0,0,0}, - {20732,20712,20710 ,10262,10224,10260 ,0,0,0}, {20710,20731,20732 ,10260,10261,10262 ,0,0,0}, - {20733,20712,20732 ,10263,10224,10262 ,0,0,0}, {20700,20728,20726 ,10251,10255,10252 ,0,0,0}, - {20703,20702,20727 ,10253,10245,10254 ,0,0,0}, {20700,20703,20728 ,10251,10253,10255 ,0,0,0}, - {20723,20692,20724 ,10244,10246,10247 ,0,0,0}, {20727,20702,20723 ,10254,10245,10244 ,0,0,0}, - {20725,20695,20697 ,10249,10248,10240 ,0,0,0}, {20724,20692,20695 ,10247,10246,10248 ,0,0,0}, - {20722,20720,20687 ,10242,10239,10238 ,0,0,0}, {20720,20725,20697 ,10239,10249,10240 ,0,0,0}, - {20689,20721,20690 ,10232,10241,10243 ,0,0,0}, {20690,20722,20687 ,10243,10242,10238 ,0,0,0}, - {20680,20734,20718 ,10233,10264,10234 ,0,0,0}, {20689,20718,20721 ,10232,10234,10241 ,0,0,0}, - {20719,20734,20682 ,10237,10264,10235 ,0,0,0}, {20680,20682,20734 ,10233,10235,10264 ,0,0,0}, - {20717,20685,20678 ,10230,10236,10231 ,0,0,0}, {20719,20685,20717 ,10237,10236,10230 ,0,0,0}, - {20676,20675,20715 ,10229,10187,10227 ,0,0,0}, {20716,20678,20676 ,10228,10231,10229 ,0,0,0}, - {20735,20736,20716 ,10265,10266,10267 ,0,0,0}, {20719,20717,20737 ,10237,10230,10268 ,0,0,0}, - {20721,20718,20738 ,10269,10270,10271 ,0,0,0}, {20734,20739,20740 ,10264,10272,10273 ,0,0,0}, - {20720,20741,20725 ,10274,10275,10276 ,0,0,0}, {20742,20743,20722 ,10277,10278,10279 ,0,0,0}, - {20744,20727,20745 ,10280,10281,10282 ,0,0,0}, {20723,20724,20746 ,10283,10284,10285 ,0,0,0}, - {20729,20726,20747 ,10286,10287,10288 ,0,0,0}, {20728,20748,20726 ,10289,10290,10287 ,0,0,0}, - {20749,20730,20729 ,10291,10292,10286 ,0,0,0}, {20729,20747,20749 ,10286,10288,10291 ,0,0,0}, - {20730,20750,20731 ,10292,10293,10261 ,0,0,0}, {20750,20730,20749 ,10293,10292,10291 ,0,0,0}, - {20732,20731,20751 ,10294,10261,10295 ,0,0,0}, {20750,20751,20731 ,10293,10295,10261 ,0,0,0}, - {20751,20752,20733 ,10295,10296,10263 ,0,0,0}, {20733,20732,20751 ,10263,10294,10295 ,0,0,0}, - {20747,20726,20748 ,10288,10287,10290 ,0,0,0}, {20728,20727,20744 ,10289,10281,10280 ,0,0,0}, - {20728,20744,20748 ,10289,10280,10290 ,0,0,0}, {20745,20723,20746 ,10282,10283,10285 ,0,0,0}, - {20727,20723,20745 ,10281,10283,10282 ,0,0,0}, {20753,20724,20725 ,10297,10284,10276 ,0,0,0}, - {20746,20724,20753 ,10285,10284,10297 ,0,0,0}, {20743,20741,20720 ,10278,10275,10274 ,0,0,0}, - {20741,20753,20725 ,10275,10297,10276 ,0,0,0}, {20721,20742,20722 ,10269,10277,10279 ,0,0,0}, - {20722,20743,20720 ,10279,10278,10274 ,0,0,0}, {20718,20740,20738 ,10270,10273,10271 ,0,0,0}, - {20721,20738,20742 ,10269,10271,10277 ,0,0,0}, {20734,20719,20739 ,10264,10237,10272 ,0,0,0}, - {20718,20734,20740 ,10270,10264,10273 ,0,0,0}, {20737,20717,20736 ,10268,10230,10266 ,0,0,0}, - {20739,20719,20737 ,10272,10237,10268 ,0,0,0}, {20735,20716,20715 ,10265,10267,10227 ,0,0,0}, - {20736,20717,20716 ,10266,10230,10267 ,0,0,0}, {20754,20755,20736 ,10298,10299,10300 ,0,0,0}, - {20739,20737,20756 ,10301,10302,10303 ,0,0,0}, {20742,20738,20757 ,10304,10305,10306 ,0,0,0}, - {20740,20739,20758 ,10307,10301,10308 ,0,0,0}, {20741,20759,20753 ,10309,10310,10311 ,0,0,0}, - {20760,20761,20743 ,10312,10313,10314 ,0,0,0}, {20762,20744,20745 ,10315,10316,10317 ,0,0,0}, - {20763,20746,20764 ,10318,10319,10320 ,0,0,0}, {20765,20747,20766 ,10321,10322,10323 ,0,0,0}, - {20748,20767,20766 ,10324,10325,10323 ,0,0,0}, {20765,20768,20749 ,10321,10326,10327 ,0,0,0}, - {20749,20747,20765 ,10327,10322,10321 ,0,0,0}, {20750,20768,20769 ,10328,10326,10329 ,0,0,0}, - {20768,20750,20749 ,10326,10328,10327 ,0,0,0}, {20770,20751,20769 ,10330,10331,10329 ,0,0,0}, - {20750,20769,20751 ,10328,10329,10331 ,0,0,0}, {20770,20771,20752 ,10330,10332,10296 ,0,0,0}, - {20752,20751,20770 ,10296,10331,10330 ,0,0,0}, {20766,20747,20748 ,10323,10322,10324 ,0,0,0}, - {20767,20744,20762 ,10325,10316,10315 ,0,0,0}, {20748,20744,20767 ,10324,10316,10325 ,0,0,0}, - {20763,20745,20746 ,10318,10317,10319 ,0,0,0}, {20762,20745,20763 ,10315,10317,10318 ,0,0,0}, - {20759,20764,20753 ,10310,10320,10311 ,0,0,0}, {20764,20746,20753 ,10320,10319,10311 ,0,0,0}, - {20743,20761,20741 ,10314,10313,10309 ,0,0,0}, {20761,20759,20741 ,10313,10310,10309 ,0,0,0}, - {20742,20757,20760 ,10304,10306,10312 ,0,0,0}, {20742,20760,20743 ,10304,10312,10314 ,0,0,0}, - {20738,20740,20772 ,10305,10307,10333 ,0,0,0}, {20738,20772,20757 ,10305,10333,10306 ,0,0,0}, - {20758,20739,20756 ,10308,10301,10303 ,0,0,0}, {20772,20740,20758 ,10333,10307,10308 ,0,0,0}, - {20755,20737,20736 ,10299,10302,10300 ,0,0,0}, {20756,20737,20755 ,10303,10302,10299 ,0,0,0}, - {20754,20736,20735 ,10298,10300,10265 ,0,0,0}, {20769,20773,20774 ,10334,10335,10336 ,0,0,0}, - {20771,20770,20775 ,10332,10337,10338 ,0,0,0}, {20776,20766,20777 ,10339,10340,10341 ,0,0,0}, - {20765,20778,20768 ,10342,10343,10344 ,0,0,0}, {20764,20779,20763 ,10345,10346,10347 ,0,0,0}, - {20762,20780,20767 ,10348,10349,10350 ,0,0,0}, {20781,20761,20760 ,10351,10352,10353 ,0,0,0}, - {20782,20759,20783 ,10354,10355,10356 ,0,0,0}, {20784,20772,20785 ,10357,10358,10359 ,0,0,0}, - {20757,20784,20786 ,10360,10357,10361 ,0,0,0}, {20787,20785,20758 ,10362,10359,10363 ,0,0,0}, - {20772,20758,20785 ,10358,10363,10359 ,0,0,0}, {20756,20788,20787 ,10364,10365,10362 ,0,0,0}, - {20787,20758,20756 ,10362,10363,10364 ,0,0,0}, {20788,20755,20789 ,10365,10366,10367 ,0,0,0}, - {20755,20788,20756 ,10366,10365,10364 ,0,0,0}, {20786,20760,20757 ,10361,10353,10360 ,0,0,0}, - {20789,20755,20754 ,10367,10366,10368 ,0,0,0}, {20784,20757,20772 ,10357,10360,10358 ,0,0,0}, - {20781,20783,20761 ,10351,10356,10352 ,0,0,0}, {20786,20781,20760 ,10361,10351,10353 ,0,0,0}, - {20759,20782,20764 ,10355,10354,10345 ,0,0,0}, {20761,20783,20759 ,10352,10356,10355 ,0,0,0}, - {20763,20779,20790 ,10347,10346,10369 ,0,0,0}, {20764,20782,20779 ,10345,10354,10346 ,0,0,0}, - {20790,20780,20762 ,10369,10349,10348 ,0,0,0}, {20762,20763,20790 ,10348,10347,10369 ,0,0,0}, - {20777,20766,20767 ,10341,10340,10350 ,0,0,0}, {20777,20767,20780 ,10341,10350,10349 ,0,0,0}, - {20776,20778,20765 ,10339,10343,10342 ,0,0,0}, {20776,20765,20766 ,10339,10342,10340 ,0,0,0}, - {20768,20773,20769 ,10344,10335,10334 ,0,0,0}, {20778,20773,20768 ,10343,10335,10344 ,0,0,0}, - {20770,20774,20775 ,10337,10336,10338 ,0,0,0}, {20769,20774,20770 ,10334,10336,10337 ,0,0,0}, - {20771,20775,20791 ,10332,10338,10370 ,0,0,0}, {20792,20793,20794 ,10371,10372,10373 ,0,0,0}, - {20795,20796,20797 ,10374,10375,10376 ,0,0,0}, {20796,20798,20799 ,10375,10377,10378 ,0,0,0}, - {20799,20797,20796 ,10378,10376,10375 ,0,0,0}, {20796,20794,20800 ,10375,10373,10379 ,0,0,0}, - {20798,20801,20799 ,10377,10380,10378 ,0,0,0}, {20802,20803,20804 ,10381,10382,10383 ,0,0,0}, - {20754,20793,20789 ,10368,10372,10384 ,0,0,0}, {20805,20806,20807 ,10385,10386,10387 ,0,0,0}, - {20785,20787,20808 ,10388,10389,10390 ,0,0,0}, {20809,20810,20811 ,10391,10392,10393 ,0,0,0}, - {20786,20812,20781 ,10394,10395,10396 ,0,0,0}, {20813,20814,20780 ,10397,10398,10399 ,0,0,0}, - {20815,20816,20811 ,10400,10401,10393 ,0,0,0}, {20817,20818,20819 ,10402,10403,10404 ,0,0,0}, - {20820,20814,20821 ,10405,10398,10406 ,0,0,0}, {20774,20818,20775 ,10407,10403,10408 ,0,0,0}, - {20775,20822,20791 ,10408,10409,10410 ,0,0,0}, {20823,20824,20819 ,10411,10412,10404 ,0,0,0}, - {20775,20818,20822 ,10408,10403,10409 ,0,0,0}, {20825,20817,20826 ,10413,10402,10414 ,0,0,0}, - {20823,20819,20773 ,10411,10404,10415 ,0,0,0}, {20823,20827,20828 ,10411,10416,10417 ,0,0,0}, - {20778,20827,20823 ,10418,10416,10411 ,0,0,0}, {20777,20814,20820 ,10419,10398,10405 ,0,0,0}, - {20827,20820,20829 ,10416,10405,10420 ,0,0,0}, {20827,20776,20820 ,10416,10421,10405 ,0,0,0}, - {20830,20813,20816 ,10422,10397,10401 ,0,0,0}, {20831,20814,20813 ,10423,10398,10397 ,0,0,0}, - {20816,20779,20782 ,10401,10424,10425 ,0,0,0}, {20816,20813,20790 ,10401,10397,10426 ,0,0,0}, - {20781,20809,20783 ,10396,10391,10427 ,0,0,0}, {20783,20811,20782 ,10427,10393,10425 ,0,0,0}, - {20805,20832,20812 ,10385,10428,10395 ,0,0,0}, {20812,20833,20809 ,10395,10429,10391 ,0,0,0}, - {20784,20785,20806 ,10430,10388,10386 ,0,0,0}, {20786,20784,20805 ,10394,10430,10385 ,0,0,0}, - {20803,20834,20808 ,10382,10431,10390 ,0,0,0}, {20807,20806,20834 ,10387,10386,10431 ,0,0,0}, - {20835,20788,20789 ,10432,10433,10384 ,0,0,0}, {20804,20787,20788 ,10383,10389,10433 ,0,0,0}, - {20836,20800,20794 ,10434,10379,10373 ,0,0,0}, {20835,20792,20802 ,10432,10371,10381 ,0,0,0}, - {20794,20793,20836 ,10373,10372,10434 ,0,0,0}, {20798,20796,20800 ,10377,10375,10379 ,0,0,0}, - {20837,20795,20797 ,10435,10374,10376 ,0,0,0}, {20838,20795,20837 ,10436,10374,10435 ,0,0,0}, - {20793,20754,20836 ,10372,10368,10434 ,0,0,0}, {20794,20795,20792 ,10373,10374,10371 ,0,0,0}, - {20789,20793,20835 ,10384,10372,10432 ,0,0,0}, {20796,20795,20794 ,10375,10374,10373 ,0,0,0}, - {20839,20838,20837 ,10437,10436,10435 ,0,0,0}, {20840,20838,20839 ,10438,10436,10437 ,0,0,0}, - {20793,20792,20835 ,10372,10371,10432 ,0,0,0}, {20792,20838,20802 ,10371,10436,10381 ,0,0,0}, - {20788,20835,20804 ,10433,10432,10383 ,0,0,0}, {20795,20838,20792 ,10374,10436,10371 ,0,0,0}, - {20841,20840,20839 ,10439,10438,10437 ,0,0,0}, {20842,20840,20841 ,10440,10438,10439 ,0,0,0}, - {20835,20802,20804 ,10432,10381,10383 ,0,0,0}, {20802,20840,20803 ,10381,10438,10382 ,0,0,0}, - {20787,20804,20808 ,10389,10383,10390 ,0,0,0}, {20838,20840,20802 ,10436,10438,10381 ,0,0,0}, - {20843,20842,20841 ,10441,10440,10439 ,0,0,0}, {20844,20842,20843 ,10442,10440,10441 ,0,0,0}, - {20804,20803,20808 ,10383,10382,10390 ,0,0,0}, {20803,20842,20834 ,10382,10440,10431 ,0,0,0}, - {20785,20808,20806 ,10388,10390,10386 ,0,0,0}, {20840,20842,20803 ,10438,10440,10382 ,0,0,0}, - {20845,20844,20843 ,10443,10442,10441 ,0,0,0}, {20846,20844,20845 ,10444,10442,10443 ,0,0,0}, - {20808,20834,20806 ,10390,10431,10386 ,0,0,0}, {20834,20844,20807 ,10431,10442,10387 ,0,0,0}, - {20784,20806,20805 ,10430,10386,10385 ,0,0,0}, {20842,20844,20834 ,10440,10442,10431 ,0,0,0}, - {20847,20846,20845 ,10445,10444,10443 ,0,0,0}, {20848,20849,20826 ,10446,10447,10414 ,0,0,0}, - {20850,20846,20847 ,10448,10444,10445 ,0,0,0}, {20807,20846,20832 ,10387,10444,10428 ,0,0,0}, - {20786,20805,20812 ,10394,10385,10395 ,0,0,0}, {20844,20846,20807 ,10442,10444,10387 ,0,0,0}, - {20851,20850,20847 ,10449,10448,10445 ,0,0,0}, {20852,20853,20850 ,10450,10451,10448 ,0,0,0}, - {20807,20832,20805 ,10387,10428,10385 ,0,0,0}, {20832,20850,20833 ,10428,10448,10429 ,0,0,0}, - {20781,20812,20809 ,10396,10395,10391 ,0,0,0}, {20846,20850,20832 ,10444,10448,10428 ,0,0,0}, - {20851,20852,20850 ,10449,10450,10448 ,0,0,0}, {20854,20855,20853 ,10452,10453,10451 ,0,0,0}, - {20832,20833,20812 ,10428,10429,10395 ,0,0,0}, {20833,20853,20810 ,10429,10451,10392 ,0,0,0}, - {20783,20809,20811 ,10427,10391,10393 ,0,0,0}, {20850,20853,20833 ,10448,10451,10429 ,0,0,0}, - {20852,20854,20853 ,10450,10452,10451 ,0,0,0}, {20856,20857,20855 ,10454,10455,10453 ,0,0,0}, - {20833,20810,20809 ,10429,10392,10391 ,0,0,0}, {20855,20815,20810 ,10453,10400,10392 ,0,0,0}, - {20782,20811,20816 ,10425,10393,10401 ,0,0,0}, {20853,20855,20810 ,10451,10453,10392 ,0,0,0}, - {20854,20856,20855 ,10452,10454,10453 ,0,0,0}, {20857,20858,20859 ,10455,10456,10457 ,0,0,0}, - {20810,20815,20811 ,10392,10400,10393 ,0,0,0}, {20857,20830,20815 ,10455,10422,10400 ,0,0,0}, - {20790,20779,20816 ,10426,10424,10401 ,0,0,0}, {20855,20857,20815 ,10453,10455,10400 ,0,0,0}, - {20856,20858,20857 ,10454,10456,10455 ,0,0,0}, {20859,20860,20861 ,10457,10458,10459 ,0,0,0}, - {20815,20830,20816 ,10400,10422,10401 ,0,0,0}, {20859,20831,20830 ,10457,10423,10422 ,0,0,0}, - {20780,20790,20813 ,10399,10426,10397 ,0,0,0}, {20857,20859,20830 ,10455,10457,10422 ,0,0,0}, - {20858,20860,20859 ,10456,10458,10457 ,0,0,0}, {20861,20862,20863 ,10459,10460,10461 ,0,0,0}, - {20830,20831,20813 ,10422,10423,10397 ,0,0,0}, {20861,20821,20831 ,10459,10406,10423 ,0,0,0}, - {20777,20780,20814 ,10419,10399,10398 ,0,0,0}, {20859,20861,20831 ,10457,10459,10423 ,0,0,0}, - {20860,20862,20861 ,10458,10460,10459 ,0,0,0}, {20863,20864,20865 ,10461,10462,10463 ,0,0,0}, - {20831,20821,20814 ,10423,10406,10398 ,0,0,0}, {20863,20829,20821 ,10461,10420,10406 ,0,0,0}, - {20776,20777,20820 ,10421,10419,10405 ,0,0,0}, {20861,20863,20821 ,10459,10461,10406 ,0,0,0}, - {20862,20864,20863 ,10460,10462,10461 ,0,0,0}, {20865,20866,20867 ,10463,10464,10465 ,0,0,0}, - {20821,20829,20820 ,10406,10420,10405 ,0,0,0}, {20865,20828,20829 ,10463,10417,10420 ,0,0,0}, - {20778,20776,20827 ,10418,10421,10416 ,0,0,0}, {20863,20865,20829 ,10461,10463,10420 ,0,0,0}, - {20864,20866,20865 ,10462,10464,10463 ,0,0,0}, {20826,20867,20848 ,10414,10465,10446 ,0,0,0}, - {20829,20828,20827 ,10420,10417,10416 ,0,0,0}, {20828,20867,20824 ,10417,10465,10412 ,0,0,0}, - {20773,20778,20823 ,10415,10418,10411 ,0,0,0}, {20865,20867,20828 ,10463,10465,10417 ,0,0,0}, - {20866,20848,20867 ,10464,10446,10465 ,0,0,0}, {20774,20819,20818 ,10407,10404,10403 ,0,0,0}, - {20828,20824,20823 ,10417,10412,10411 ,0,0,0}, {20826,20817,20824 ,10414,10402,10412 ,0,0,0}, - {20774,20773,20819 ,10407,10415,10404 ,0,0,0}, {20826,20824,20867 ,10414,10412,10465 ,0,0,0}, - {20849,20825,20826 ,10447,10413,10414 ,0,0,0}, {20868,20817,20825 ,10466,10402,10413 ,0,0,0}, - {20824,20817,20819 ,10412,10402,10404 ,0,0,0}, {20817,20868,20818 ,10402,10466,10403 ,0,0,0}, - {20822,20818,20868 ,10409,10403,10466 ,0,0,0}, {20869,20870,20799 ,10467,10468,10469 ,0,0,0}, - {20837,20797,20871 ,10470,10471,10472 ,0,0,0}, {20843,20841,20872 ,10473,10474,10475 ,0,0,0}, - {20839,20873,20874 ,10476,10477,10478 ,0,0,0}, {20875,20876,20851 ,10479,10480,10481 ,0,0,0}, - {20877,20878,20845 ,10482,10483,10484 ,0,0,0}, {20879,20856,20880 ,10485,10486,10487 ,0,0,0}, - {20854,20852,20881 ,10488,10489,10490 ,0,0,0}, {20862,20860,20882 ,10491,10492,10493 ,0,0,0}, - {20858,20883,20860 ,10494,10495,10492 ,0,0,0}, {20884,20864,20862 ,10496,10497,10491 ,0,0,0}, - {20862,20882,20884 ,10491,10493,10496 ,0,0,0}, {20864,20885,20866 ,10497,10498,10499 ,0,0,0}, - {20885,20864,20884 ,10498,10497,10496 ,0,0,0}, {20848,20866,20886 ,10500,10499,10501 ,0,0,0}, - {20885,20886,20866 ,10498,10501,10499 ,0,0,0}, {20886,20887,20849 ,10501,10502,10447 ,0,0,0}, - {20849,20848,20886 ,10447,10500,10501 ,0,0,0}, {20882,20860,20883 ,10493,10492,10495 ,0,0,0}, - {20858,20856,20879 ,10494,10486,10485 ,0,0,0}, {20858,20879,20883 ,10494,10485,10495 ,0,0,0}, - {20880,20854,20881 ,10487,10488,10490 ,0,0,0}, {20856,20854,20880 ,10486,10488,10487 ,0,0,0}, - {20876,20852,20851 ,10480,10489,10481 ,0,0,0}, {20881,20852,20876 ,10490,10489,10480 ,0,0,0}, - {20878,20875,20847 ,10483,10479,10503 ,0,0,0}, {20875,20851,20847 ,10479,10481,10503 ,0,0,0}, - {20843,20877,20845 ,10473,10482,10484 ,0,0,0}, {20845,20878,20847 ,10484,10483,10503 ,0,0,0}, - {20841,20874,20872 ,10474,10478,10475 ,0,0,0}, {20843,20872,20877 ,10473,10475,10482 ,0,0,0}, - {20839,20837,20873 ,10476,10470,10477 ,0,0,0}, {20841,20839,20874 ,10474,10476,10478 ,0,0,0}, - {20871,20797,20870 ,10472,10471,10468 ,0,0,0}, {20873,20837,20871 ,10477,10470,10472 ,0,0,0}, - {20869,20799,20801 ,10467,10469,10504 ,0,0,0}, {20870,20797,20799 ,10468,10471,10469 ,0,0,0}, - {20888,20889,20870 ,10505,10506,10507 ,0,0,0}, {20871,20870,20890 ,10508,10507,10509 ,0,0,0}, - {20872,20874,20891 ,10510,10511,10512 ,0,0,0}, {20873,20892,20893 ,10513,10514,10515 ,0,0,0}, - {20878,20894,20875 ,10516,10517,10518 ,0,0,0}, {20895,20896,20877 ,10519,10520,10521 ,0,0,0}, - {20897,20880,20881 ,10522,10523,10524 ,0,0,0}, {20898,20876,20899 ,10525,10526,10527 ,0,0,0}, - {20882,20883,20900 ,10528,10529,10530 ,0,0,0}, {20879,20901,20902 ,10531,10532,10533 ,0,0,0}, - {20903,20884,20882 ,10534,10535,10528 ,0,0,0}, {20882,20900,20903 ,10528,10530,10534 ,0,0,0}, - {20884,20904,20885 ,10535,10536,10537 ,0,0,0}, {20904,20884,20903 ,10536,10535,10534 ,0,0,0}, - {20886,20885,20905 ,10538,10537,10539 ,0,0,0}, {20904,20905,20885 ,10536,10539,10537 ,0,0,0}, - {20906,20887,20886 ,10540,10502,10538 ,0,0,0}, {20886,20905,20906 ,10538,10539,10540 ,0,0,0}, - {20907,20887,20906 ,10541,10502,10540 ,0,0,0}, {20883,20902,20900 ,10529,10533,10530 ,0,0,0}, - {20879,20880,20901 ,10531,10523,10532 ,0,0,0}, {20883,20879,20902 ,10529,10531,10533 ,0,0,0}, - {20897,20881,20898 ,10522,10524,10525 ,0,0,0}, {20901,20880,20897 ,10532,10523,10522 ,0,0,0}, - {20899,20876,20875 ,10527,10526,10518 ,0,0,0}, {20898,20881,20876 ,10525,10524,10526 ,0,0,0}, - {20896,20894,20878 ,10520,10517,10516 ,0,0,0}, {20894,20899,20875 ,10517,10527,10518 ,0,0,0}, - {20872,20895,20877 ,10510,10519,10521 ,0,0,0}, {20877,20896,20878 ,10521,10520,10516 ,0,0,0}, - {20874,20893,20891 ,10511,10515,10512 ,0,0,0}, {20872,20891,20895 ,10510,10512,10519 ,0,0,0}, - {20873,20871,20892 ,10513,10508,10514 ,0,0,0}, {20874,20873,20893 ,10511,10513,10515 ,0,0,0}, - {20890,20870,20889 ,10509,10507,10506 ,0,0,0}, {20892,20871,20890 ,10514,10508,10509 ,0,0,0}, - {20888,20870,20869 ,10505,10507,10467 ,0,0,0}, {20908,20909,20889 ,10542,10543,10544 ,0,0,0}, - {20910,20890,20909 ,10545,10509,10543 ,0,0,0}, {20895,20891,20911 ,10546,10547,10548 ,0,0,0}, - {20893,20892,20912 ,10515,10514,10549 ,0,0,0}, {20894,20913,20899 ,10550,10551,10552 ,0,0,0}, - {20914,20915,20896 ,10553,10554,10555 ,0,0,0}, {20916,20901,20897 ,10556,10557,10558 ,0,0,0}, - {20917,20898,20918 ,10559,10560,10561 ,0,0,0}, {20903,20900,20919 ,10534,10530,10562 ,0,0,0}, - {20902,20920,20921 ,10563,10564,10565 ,0,0,0}, {20922,20904,20903 ,10566,10536,10534 ,0,0,0}, - {20903,20919,20922 ,10534,10562,10566 ,0,0,0}, {20904,20923,20905 ,10536,10567,10539 ,0,0,0}, - {20923,20904,20922 ,10567,10536,10566 ,0,0,0}, {20906,20905,20924 ,10568,10539,10569 ,0,0,0}, - {20923,20924,20905 ,10567,10569,10539 ,0,0,0}, {20925,20907,20906 ,10570,10541,10568 ,0,0,0}, - {20906,20924,20925 ,10568,10569,10570 ,0,0,0}, {20926,20907,20925 ,10571,10541,10570 ,0,0,0}, - {20900,20921,20919 ,10530,10565,10562 ,0,0,0}, {20902,20901,20920 ,10563,10557,10564 ,0,0,0}, - {20900,20902,20921 ,10530,10563,10565 ,0,0,0}, {20916,20897,20917 ,10556,10558,10559 ,0,0,0}, - {20920,20901,20916 ,10564,10557,10556 ,0,0,0}, {20918,20898,20899 ,10561,10560,10552 ,0,0,0}, - {20917,20897,20898 ,10559,10558,10560 ,0,0,0}, {20915,20913,20894 ,10554,10551,10550 ,0,0,0}, - {20913,20918,20899 ,10551,10561,10552 ,0,0,0}, {20895,20914,20896 ,10546,10553,10555 ,0,0,0}, - {20896,20915,20894 ,10555,10554,10550 ,0,0,0}, {20891,20927,20911 ,10547,10572,10548 ,0,0,0}, - {20895,20911,20914 ,10546,10548,10553 ,0,0,0}, {20912,20927,20893 ,10549,10572,10515 ,0,0,0}, - {20891,20893,20927 ,10547,10515,10572 ,0,0,0}, {20910,20892,20890 ,10545,10514,10509 ,0,0,0}, - {20912,20892,20910 ,10549,10514,10545 ,0,0,0}, {20889,20888,20908 ,10544,10505,10542 ,0,0,0}, - {20909,20890,20889 ,10543,10509,10544 ,0,0,0}, {20928,20929,20909 ,10573,10574,10575 ,0,0,0}, - {20930,20910,20929 ,10576,10577,10574 ,0,0,0}, {20914,20911,20931 ,10578,10579,10580 ,0,0,0}, - {20927,20912,20932 ,10581,10582,10583 ,0,0,0}, {20913,20933,20918 ,10584,10585,10586 ,0,0,0}, - {20934,20935,20915 ,10587,10588,10589 ,0,0,0}, {20936,20920,20916 ,10590,10591,10592 ,0,0,0}, - {20937,20917,20938 ,10593,10594,10595 ,0,0,0}, {20939,20919,20940 ,10596,10597,10598 ,0,0,0}, - {20921,20920,20941 ,10599,10591,10600 ,0,0,0}, {20942,20923,20922 ,10601,10602,10603 ,0,0,0}, - {20922,20939,20942 ,10603,10596,10601 ,0,0,0}, {20923,20943,20924 ,10602,10604,10605 ,0,0,0}, - {20943,20923,20942 ,10604,10602,10601 ,0,0,0}, {20925,20924,20944 ,10606,10605,10607 ,0,0,0}, - {20943,20944,20924 ,10604,10607,10605 ,0,0,0}, {20945,20926,20925 ,10608,10571,10606 ,0,0,0}, - {20925,20944,20945 ,10606,10607,10608 ,0,0,0}, {20946,20926,20945 ,10609,10571,10608 ,0,0,0}, - {20939,20922,20919 ,10596,10603,10597 ,0,0,0}, {20940,20921,20941 ,10598,10599,10600 ,0,0,0}, - {20919,20921,20940 ,10597,10599,10598 ,0,0,0}, {20916,20937,20936 ,10592,10593,10590 ,0,0,0}, - {20941,20920,20936 ,10600,10591,10590 ,0,0,0}, {20938,20917,20918 ,10595,10594,10586 ,0,0,0}, - {20937,20916,20917 ,10593,10592,10594 ,0,0,0}, {20935,20933,20913 ,10588,10585,10584 ,0,0,0}, - {20933,20938,20918 ,10585,10595,10586 ,0,0,0}, {20914,20934,20915 ,10578,10587,10589 ,0,0,0}, - {20915,20935,20913 ,10589,10588,10584 ,0,0,0}, {20911,20947,20931 ,10579,10610,10580 ,0,0,0}, - {20914,20931,20934 ,10578,10580,10587 ,0,0,0}, {20932,20947,20927 ,10583,10610,10581 ,0,0,0}, - {20911,20927,20947 ,10579,10581,10610 ,0,0,0}, {20930,20912,20910 ,10576,10582,10577 ,0,0,0}, - {20932,20912,20930 ,10583,10582,10576 ,0,0,0}, {20909,20908,20928 ,10575,10542,10573 ,0,0,0}, - {20929,20910,20909 ,10574,10577,10575 ,0,0,0}, {20948,20928,20949 ,10611,10573,10612 ,0,0,0}, - {20950,20932,20951 ,10613,10614,10615 ,0,0,0}, {20952,20930,20929 ,10616,10617,10618 ,0,0,0}, - {20934,20953,20935 ,10619,10620,10621 ,0,0,0}, {20947,20954,20931 ,10622,10623,10624 ,0,0,0}, - {20955,20937,20938 ,10625,10626,10627 ,0,0,0}, {20956,20933,20957 ,10628,10629,10630 ,0,0,0}, - {20958,20941,20959 ,10631,10632,10633 ,0,0,0}, {20936,20960,20959 ,10634,10635,10633 ,0,0,0}, - {20942,20939,20961 ,10636,10637,10638 ,0,0,0}, {20940,20962,20939 ,10639,10640,10637 ,0,0,0}, - {20963,20943,20942 ,10641,10642,10636 ,0,0,0}, {20942,20961,20963 ,10636,10638,10641 ,0,0,0}, - {20943,20964,20944 ,10642,10643,10644 ,0,0,0}, {20964,20943,20963 ,10643,10642,10641 ,0,0,0}, - {20945,20944,20965 ,10645,10644,10646 ,0,0,0}, {20964,20965,20944 ,10643,10646,10644 ,0,0,0}, - {20966,20946,20945 ,10647,10609,10645 ,0,0,0}, {20945,20965,20966 ,10645,10646,10647 ,0,0,0}, - {20958,20962,20940 ,10631,10640,10639 ,0,0,0}, {20939,20962,20961 ,10637,10640,10638 ,0,0,0}, - {20941,20936,20959 ,10632,10634,10633 ,0,0,0}, {20940,20941,20958 ,10639,10632,10631 ,0,0,0}, - {20960,20937,20955 ,10635,10626,10625 ,0,0,0}, {20936,20937,20960 ,10634,10626,10635 ,0,0,0}, - {20956,20938,20933 ,10628,10627,10629 ,0,0,0}, {20955,20938,20956 ,10625,10627,10628 ,0,0,0}, - {20953,20957,20935 ,10620,10630,10621 ,0,0,0}, {20957,20933,20935 ,10630,10629,10621 ,0,0,0}, - {20931,20967,20934 ,10624,10648,10619 ,0,0,0}, {20967,20953,20934 ,10648,10620,10619 ,0,0,0}, - {20947,20950,20954 ,10622,10613,10623 ,0,0,0}, {20931,20954,20967 ,10624,10623,10648 ,0,0,0}, - {20932,20930,20951 ,10614,10617,10615 ,0,0,0}, {20947,20932,20950 ,10622,10614,10613 ,0,0,0}, - {20952,20929,20948 ,10616,10618,10611 ,0,0,0}, {20951,20930,20952 ,10615,10617,10616 ,0,0,0}, - {20928,20948,20929 ,10573,10611,10618 ,0,0,0}, {20955,20956,20968 ,10649,10650,10651 ,0,0,0}, - {20969,20956,20957 ,10652,10650,10653 ,0,0,0}, {20956,20969,20968 ,10650,10652,10651 ,0,0,0}, - {20953,20970,20957 ,10654,10655,10653 ,0,0,0}, {20969,20957,20970 ,10652,10653,10655 ,0,0,0}, - {20953,20967,20971 ,10654,10656,10657 ,0,0,0}, {20971,20970,20953 ,10657,10655,10654 ,0,0,0}, - {20972,20967,20954 ,10658,10656,10659 ,0,0,0}, {20967,20972,20971 ,10656,10658,10657 ,0,0,0}, - {20950,20973,20954 ,10660,10661,10659 ,0,0,0}, {20972,20954,20973 ,10658,10659,10661 ,0,0,0}, - {20950,20951,20974 ,10660,10662,10663 ,0,0,0}, {20974,20973,20950 ,10663,10661,10660 ,0,0,0}, - {20975,20951,20952 ,10664,10662,10665 ,0,0,0}, {20951,20975,20974 ,10662,10664,10663 ,0,0,0}, - {20948,20976,20952 ,10666,10667,10665 ,0,0,0}, {20975,20952,20976 ,10664,10665,10667 ,0,0,0}, - {20949,20977,20976 ,10668,10669,10667 ,0,0,0}, {20976,20948,20949 ,10667,10666,10668 ,0,0,0}, - {20955,20968,20978 ,10649,10651,10670 ,0,0,0}, {20978,20979,20960 ,10670,10671,10672 ,0,0,0}, - {20960,20955,20978 ,10672,10649,10670 ,0,0,0}, {20959,20979,20980 ,10673,10671,10674 ,0,0,0}, - {20979,20959,20960 ,10671,10673,10672 ,0,0,0}, {20981,20958,20980 ,10675,10676,10674 ,0,0,0}, - {20959,20980,20958 ,10673,10674,10676 ,0,0,0}, {20981,20982,20962 ,10675,10677,10678 ,0,0,0}, - {20962,20958,20981 ,10678,10676,10675 ,0,0,0}, {20961,20982,20983 ,10679,10677,10680 ,0,0,0}, - {20982,20961,20962 ,10677,10679,10678 ,0,0,0}, {20984,20963,20983 ,10681,10682,10680 ,0,0,0}, - {20961,20983,20963 ,10679,10680,10682 ,0,0,0}, {20984,20985,20964 ,10681,10683,10684 ,0,0,0}, - {20964,20963,20984 ,10684,10682,10681 ,0,0,0}, {20965,20985,20986 ,10685,10683,10686 ,0,0,0}, - {20985,20965,20964 ,10683,10685,10684 ,0,0,0}, {20965,20986,20966 ,10685,10686,10687 ,0,0,0}, - {20987,20977,20988 ,10688,10689,10690 ,0,0,0}, {20989,20973,20990 ,10691,10692,10693 ,0,0,0}, - {20987,20991,20975 ,10688,10694,10695 ,0,0,0}, {20970,20992,20993 ,10696,10697,10698 ,0,0,0}, - {20972,20994,20971 ,10699,10700,10701 ,0,0,0}, {20995,20996,20978 ,10702,10703,10704 ,0,0,0}, - {20997,20968,20969 ,10705,10706,10707 ,0,0,0}, {20998,20981,20999 ,10708,10709,10710 ,0,0,0}, - {20980,20979,21000 ,10711,10712,10713 ,0,0,0}, {21001,20983,20982 ,10714,10715,10716 ,0,0,0}, - {20982,20998,21001 ,10716,10708,10714 ,0,0,0}, {20983,21002,20984 ,10715,10717,10718 ,0,0,0}, - {21002,20983,21001 ,10717,10715,10714 ,0,0,0}, {20985,20984,21003 ,10719,10718,10720 ,0,0,0}, - {21002,21003,20984 ,10717,10720,10718 ,0,0,0}, {21004,20986,20985 ,10721,10686,10719 ,0,0,0}, - {20985,21003,21004 ,10719,10720,10721 ,0,0,0}, {20981,20980,20999 ,10709,10711,10710 ,0,0,0}, - {20982,20981,20998 ,10716,10709,10708 ,0,0,0}, {21000,20979,20996 ,10713,10712,10703 ,0,0,0}, - {20999,20980,21000 ,10710,10711,10713 ,0,0,0}, {20995,20978,20968 ,10702,10704,10706 ,0,0,0}, - {20996,20979,20978 ,10703,10712,10704 ,0,0,0}, {20993,20997,20969 ,10698,10705,10707 ,0,0,0}, - {20997,20995,20968 ,10705,10702,10706 ,0,0,0}, {20971,20992,20970 ,10701,10697,10696 ,0,0,0}, - {20970,20993,20969 ,10696,10698,10707 ,0,0,0}, {20972,20989,20994 ,10699,10691,10700 ,0,0,0}, - {20971,20994,20992 ,10701,10700,10697 ,0,0,0}, {20973,20974,20990 ,10692,10722,10693 ,0,0,0}, - {20972,20973,20989 ,10699,10692,10691 ,0,0,0}, {20975,20991,20974 ,10695,10694,10722 ,0,0,0}, - {20990,20974,20991 ,10693,10722,10694 ,0,0,0}, {20987,20976,20977 ,10688,10723,10689 ,0,0,0}, - {20987,20975,20976 ,10688,10695,10723 ,0,0,0}, {21005,20988,21006 ,10724,10725,10726 ,0,0,0}, - {21007,20990,21008 ,10727,10728,10729 ,0,0,0}, {21009,20991,20987 ,10730,10731,10732 ,0,0,0}, - {20992,21010,20993 ,10733,10734,10735 ,0,0,0}, {20989,21011,20994 ,10736,10737,10738 ,0,0,0}, - {21012,21013,20995 ,10739,10740,10741 ,0,0,0}, {21012,20997,21014 ,10739,10742,10743 ,0,0,0}, - {21015,20999,21016 ,10744,10745,10746 ,0,0,0}, {21000,20996,21017 ,10747,10748,10749 ,0,0,0}, - {21018,21001,20998 ,10750,10751,10752 ,0,0,0}, {20998,21015,21018 ,10752,10744,10750 ,0,0,0}, - {21001,21019,21002 ,10751,10753,10754 ,0,0,0}, {21019,21001,21018 ,10753,10751,10750 ,0,0,0}, - {21003,21002,21020 ,10755,10754,10756 ,0,0,0}, {21019,21020,21002 ,10753,10756,10754 ,0,0,0}, - {21021,21004,21003 ,10757,10758,10755 ,0,0,0}, {21003,21020,21021 ,10755,10756,10757 ,0,0,0}, - {20999,21000,21016 ,10745,10747,10746 ,0,0,0}, {20998,20999,21015 ,10752,10745,10744 ,0,0,0}, - {21017,20996,21013 ,10749,10748,10740 ,0,0,0}, {21016,21000,21017 ,10746,10747,10749 ,0,0,0}, - {21012,20995,20997 ,10739,10741,10742 ,0,0,0}, {21013,20996,20995 ,10740,10748,10741 ,0,0,0}, - {21010,21014,20993 ,10734,10743,10735 ,0,0,0}, {21014,20997,20993 ,10743,10742,10735 ,0,0,0}, - {20994,21022,20992 ,10738,10759,10733 ,0,0,0}, {21022,21010,20992 ,10759,10734,10733 ,0,0,0}, - {20989,21007,21011 ,10736,10727,10737 ,0,0,0}, {20994,21011,21022 ,10738,10737,10759 ,0,0,0}, - {20990,20991,21008 ,10728,10731,10729 ,0,0,0}, {20989,20990,21007 ,10736,10728,10727 ,0,0,0}, - {21009,20987,21005 ,10730,10732,10724 ,0,0,0}, {21008,20991,21009 ,10729,10731,10730 ,0,0,0}, - {20988,21005,20987 ,10725,10724,10732 ,0,0,0}, {21023,21006,21024 ,10760,10761,10762 ,0,0,0}, - {21025,21008,21026 ,10763,10764,10765 ,0,0,0}, {21027,21009,21005 ,10766,10767,10768 ,0,0,0}, - {21022,21028,21029 ,10769,10770,10771 ,0,0,0}, {21007,21030,21011 ,10772,10773,10774 ,0,0,0}, - {21031,21032,21012 ,10775,10776,10777 ,0,0,0}, {21031,21014,21033 ,10775,10778,10779 ,0,0,0}, - {21034,21016,21035 ,10780,10781,10782 ,0,0,0}, {21017,21013,21036 ,10783,10784,10785 ,0,0,0}, - {21037,21018,21015 ,10786,10787,10788 ,0,0,0}, {21015,21034,21037 ,10788,10780,10786 ,0,0,0}, - {21018,21038,21019 ,10787,10789,10790 ,0,0,0}, {21038,21018,21037 ,10789,10787,10786 ,0,0,0}, - {21020,21019,21039 ,10791,10790,10792 ,0,0,0}, {21038,21039,21019 ,10789,10792,10790 ,0,0,0}, - {21040,21021,21020 ,10793,10794,10791 ,0,0,0}, {21020,21039,21040 ,10791,10792,10793 ,0,0,0}, - {21016,21017,21035 ,10781,10783,10782 ,0,0,0}, {21015,21016,21034 ,10788,10781,10780 ,0,0,0}, - {21036,21013,21032 ,10785,10784,10776 ,0,0,0}, {21035,21017,21036 ,10782,10783,10785 ,0,0,0}, - {21031,21012,21014 ,10775,10777,10778 ,0,0,0}, {21032,21013,21012 ,10776,10784,10777 ,0,0,0}, - {21029,21033,21010 ,10771,10779,10795 ,0,0,0}, {21033,21014,21010 ,10779,10778,10795 ,0,0,0}, - {21011,21028,21022 ,10774,10770,10769 ,0,0,0}, {21022,21029,21010 ,10769,10771,10795 ,0,0,0}, - {21007,21025,21030 ,10772,10763,10773 ,0,0,0}, {21011,21030,21028 ,10774,10773,10770 ,0,0,0}, - {21008,21009,21026 ,10764,10767,10765 ,0,0,0}, {21007,21008,21025 ,10772,10764,10763 ,0,0,0}, - {21027,21005,21023 ,10766,10768,10760 ,0,0,0}, {21026,21009,21027 ,10765,10767,10766 ,0,0,0}, - {21006,21023,21005 ,10761,10760,10768 ,0,0,0}, {20611,21024,20609 ,10796,10797,10798 ,0,0,0}, - {20612,21026,20613 ,10799,10800,10801 ,0,0,0}, {20623,21027,21023 ,10802,10803,10804 ,0,0,0}, - {21028,20636,20637 ,10805,10806,10807 ,0,0,0}, {21025,20624,21030 ,10808,10809,10810 ,0,0,0}, - {20639,20640,21031 ,10811,10812,10813 ,0,0,0}, {20638,21033,21029 ,10814,10815,10816 ,0,0,0}, - {20669,21035,21036 ,10817,10818,10819 ,0,0,0}, {20666,21032,20640 ,10820,10821,10812 ,0,0,0}, - {20670,21037,21034 ,10822,10823,10824 ,0,0,0}, {21034,20668,20670 ,10824,10825,10822 ,0,0,0}, - {21037,20671,21038 ,10823,10826,10827 ,0,0,0}, {20671,21037,20670 ,10826,10823,10822 ,0,0,0}, - {21038,20573,20570 ,10827,10828,10829 ,0,0,0}, {20671,20573,21038 ,10826,10828,10827 ,0,0,0}, - {20569,21039,20570 ,10047,10830,10829 ,0,0,0}, {21038,20570,21039 ,10827,10829,10830 ,0,0,0}, - {21040,21039,20569 ,10793,10830,10047 ,0,0,0}, {20668,21035,20669 ,10825,10818,10817 ,0,0,0}, - {21034,21035,20668 ,10824,10818,10825 ,0,0,0}, {20666,21036,21032 ,10820,10819,10821 ,0,0,0}, - {20669,21036,20666 ,10817,10819,10820 ,0,0,0}, {21031,21033,20639 ,10813,10815,10811 ,0,0,0}, - {20640,21032,21031 ,10812,10821,10813 ,0,0,0}, {20637,20638,21029 ,10807,10814,10816 ,0,0,0}, - {20638,20639,21033 ,10814,10811,10815 ,0,0,0}, {21030,20636,21028 ,10810,10806,10805 ,0,0,0}, - {21028,20637,21029 ,10805,10807,10816 ,0,0,0}, {21025,20612,20624 ,10808,10799,10809 ,0,0,0}, - {21030,20624,20636 ,10810,10809,10806 ,0,0,0}, {21026,21027,20613 ,10800,10803,10801 ,0,0,0}, - {21025,21026,20612 ,10808,10800,10799 ,0,0,0}, {20623,21023,20611 ,10802,10804,10796 ,0,0,0}, - {20613,21027,20623 ,10801,10803,10802 ,0,0,0}, {21024,20611,21023 ,10797,10796,10804 ,0,0,0}, - {21041,20549,21042 ,10831,10024,10832 ,0,0,0}, {21043,20659,20606 ,10833,10834,10835 ,0,0,0}, - {21044,20621,20547 ,10836,10837,10838 ,0,0,0}, {20664,21045,21046 ,10839,10840,10841 ,0,0,0}, - {20660,21047,20661 ,10842,10843,10844 ,0,0,0}, {21048,21049,20629 ,10845,10846,10847 ,0,0,0}, - {21050,20632,20633 ,10848,10849,10850 ,0,0,0}, {21051,20667,21052 ,10851,10852,10853 ,0,0,0}, - {20665,20630,21053 ,10854,10855,10856 ,0,0,0}, {21054,20644,20589 ,10857,10858,10859 ,0,0,0}, - {20589,21051,21054 ,10859,10851,10857 ,0,0,0}, {20644,21055,20672 ,10858,10860,10861 ,0,0,0}, - {21055,20644,21054 ,10860,10858,10857 ,0,0,0}, {20580,20672,21056 ,10862,10861,10863 ,0,0,0}, - {21055,21056,20672 ,10860,10863,10861 ,0,0,0}, {21057,20583,20580 ,10864,10865,10862 ,0,0,0}, - {20580,21056,21057 ,10862,10863,10864 ,0,0,0}, {20667,20665,21052 ,10852,10854,10853 ,0,0,0}, - {20589,20667,21051 ,10859,10852,10851 ,0,0,0}, {21053,20630,21049 ,10856,10855,10846 ,0,0,0}, - {21052,20665,21053 ,10853,10854,10856 ,0,0,0}, {21048,20629,20632 ,10845,10847,10849 ,0,0,0}, - {21049,20630,20629 ,10846,10855,10847 ,0,0,0}, {21046,21050,20633 ,10841,10848,10850 ,0,0,0}, - {21050,21048,20632 ,10848,10845,10849 ,0,0,0}, {20661,21045,20664 ,10844,10840,10839 ,0,0,0}, - {20664,21046,20633 ,10839,10841,10850 ,0,0,0}, {20660,21058,21047 ,10842,10866,10843 ,0,0,0}, - {20661,21047,21045 ,10844,10843,10840 ,0,0,0}, {21043,21058,20659 ,10833,10866,10834 ,0,0,0}, - {20660,20659,21058 ,10842,10834,10866 ,0,0,0}, {21044,20606,20621 ,10836,10835,10837 ,0,0,0}, - {21043,20606,21044 ,10833,10835,10836 ,0,0,0}, {21041,20547,20549 ,10831,10838,10024 ,0,0,0}, - {21044,20547,21041 ,10836,10838,10831 ,0,0,0}, {21059,21042,21060 ,10867,10832,10868 ,0,0,0}, - {21061,21043,21062 ,10869,10870,10871 ,0,0,0}, {21063,21044,21041 ,10872,10873,10874 ,0,0,0}, - {21045,21064,21065 ,10875,10876,10877 ,0,0,0}, {21058,21066,21047 ,10878,10879,10880 ,0,0,0}, - {21067,21049,21048 ,10881,10882,10883 ,0,0,0}, {21068,21050,21069 ,10884,10885,10886 ,0,0,0}, - {21070,21052,21071 ,10887,10888,10889 ,0,0,0}, {21053,21049,21072 ,10890,10882,10891 ,0,0,0}, - {21073,21054,21051 ,10892,10893,10894 ,0,0,0}, {21051,21070,21073 ,10894,10887,10892 ,0,0,0}, - {21054,21074,21055 ,10893,10895,10896 ,0,0,0}, {21074,21054,21073 ,10895,10893,10892 ,0,0,0}, - {21056,21055,21075 ,10897,10896,10898 ,0,0,0}, {21074,21075,21055 ,10895,10898,10896 ,0,0,0}, - {21076,21057,21056 ,10899,10900,10897 ,0,0,0}, {21056,21075,21076 ,10897,10898,10899 ,0,0,0}, - {21052,21053,21071 ,10888,10890,10889 ,0,0,0}, {21051,21052,21070 ,10894,10888,10887 ,0,0,0}, - {21072,21049,21067 ,10891,10882,10881 ,0,0,0}, {21071,21053,21072 ,10889,10890,10891 ,0,0,0}, - {21068,21048,21050 ,10884,10883,10885 ,0,0,0}, {21067,21048,21068 ,10881,10883,10884 ,0,0,0}, - {21065,21069,21046 ,10877,10886,10901 ,0,0,0}, {21069,21050,21046 ,10886,10885,10901 ,0,0,0}, - {21047,21064,21045 ,10880,10876,10875 ,0,0,0}, {21045,21065,21046 ,10875,10877,10901 ,0,0,0}, - {21058,21061,21066 ,10878,10869,10879 ,0,0,0}, {21047,21066,21064 ,10880,10879,10876 ,0,0,0}, - {21043,21044,21062 ,10870,10873,10871 ,0,0,0}, {21058,21043,21061 ,10878,10870,10869 ,0,0,0}, - {21063,21041,21059 ,10872,10874,10867 ,0,0,0}, {21062,21044,21063 ,10871,10873,10872 ,0,0,0}, - {21042,21059,21041 ,10832,10867,10874 ,0,0,0}, {21077,21060,21078 ,10902,10868,10903 ,0,0,0}, - {21079,21062,21080 ,10904,10905,10906 ,0,0,0}, {21081,21063,21059 ,10907,10908,10909 ,0,0,0}, - {21064,21082,21065 ,10910,10911,10912 ,0,0,0}, {21061,21083,21066 ,10913,10914,10915 ,0,0,0}, - {21084,21067,21068 ,10916,10917,10918 ,0,0,0}, {21085,21069,21086 ,10919,10920,10921 ,0,0,0}, - {21087,21071,21088 ,10922,10923,10924 ,0,0,0}, {21072,21067,21089 ,10925,10917,10926 ,0,0,0}, - {21090,21073,21070 ,10927,10928,10929 ,0,0,0}, {21070,21087,21090 ,10929,10922,10927 ,0,0,0}, - {21073,21091,21074 ,10928,10930,10931 ,0,0,0}, {21091,21073,21090 ,10930,10928,10927 ,0,0,0}, - {21075,21074,21092 ,10932,10931,10933 ,0,0,0}, {21091,21092,21074 ,10930,10933,10931 ,0,0,0}, - {21093,21076,21075 ,10934,10935,10932 ,0,0,0}, {21075,21092,21093 ,10932,10933,10934 ,0,0,0}, - {21071,21072,21088 ,10923,10925,10924 ,0,0,0}, {21070,21071,21087 ,10929,10923,10922 ,0,0,0}, - {21089,21067,21084 ,10926,10917,10916 ,0,0,0}, {21088,21072,21089 ,10924,10925,10926 ,0,0,0}, - {21085,21068,21069 ,10919,10918,10920 ,0,0,0}, {21084,21068,21085 ,10916,10918,10919 ,0,0,0}, - {21082,21086,21065 ,10911,10921,10912 ,0,0,0}, {21086,21069,21065 ,10921,10920,10912 ,0,0,0}, - {21066,21094,21064 ,10915,10936,10910 ,0,0,0}, {21094,21082,21064 ,10936,10911,10910 ,0,0,0}, - {21061,21079,21083 ,10913,10904,10914 ,0,0,0}, {21066,21083,21094 ,10915,10914,10936 ,0,0,0}, - {21062,21063,21080 ,10905,10908,10906 ,0,0,0}, {21061,21062,21079 ,10913,10905,10904 ,0,0,0}, - {21081,21059,21077 ,10907,10909,10902 ,0,0,0}, {21080,21063,21081 ,10906,10908,10907 ,0,0,0}, - {21060,21077,21059 ,10868,10902,10909 ,0,0,0}, {20677,21095,20714 ,10937,10938,10226 ,0,0,0}, - {20683,21096,20684 ,10939,10940,10941 ,0,0,0}, {20679,21097,21098 ,10942,10943,10944 ,0,0,0}, - {21099,20691,21100 ,10945,10946,10947 ,0,0,0}, {21101,20681,21102 ,10948,10949,10950 ,0,0,0}, - {20696,21103,21104 ,10951,10952,10953 ,0,0,0}, {20688,21105,20686 ,10954,10955,10956 ,0,0,0}, - {21106,21107,20701 ,10957,10958,10959 ,0,0,0}, {21108,20694,20693 ,10960,10961,10962 ,0,0,0}, - {21109,21110,20698 ,10963,10964,10965 ,0,0,0}, {20699,20698,21110 ,10966,10965,10964 ,0,0,0}, - {20705,21111,21109 ,10967,10968,10963 ,0,0,0}, {21109,20698,20705 ,10963,10965,10967 ,0,0,0}, - {21111,20707,21112 ,10968,10969,10970 ,0,0,0}, {20707,21111,20705 ,10969,10968,10967 ,0,0,0}, - {21113,21112,20708 ,10971,10970,10972 ,0,0,0}, {20707,20708,21112 ,10969,10972,10970 ,0,0,0}, - {20711,21114,21113 ,10223,10973,10971 ,0,0,0}, {21113,20708,20711 ,10971,10972,10223 ,0,0,0}, - {20701,20699,21106 ,10959,10966,10957 ,0,0,0}, {21106,20699,21110 ,10957,10966,10964 ,0,0,0}, - {21107,21108,20693 ,10958,10960,10962 ,0,0,0}, {21107,20693,20701 ,10958,10962,10959 ,0,0,0}, - {20694,21103,20696 ,10961,10952,10951 ,0,0,0}, {21108,21103,20694 ,10960,10952,10961 ,0,0,0}, - {20688,21104,21105 ,10954,10953,10955 ,0,0,0}, {20696,21104,20688 ,10951,10953,10954 ,0,0,0}, - {20691,20686,21100 ,10946,10956,10947 ,0,0,0}, {20686,21105,21100 ,10956,10955,10947 ,0,0,0}, - {21102,20713,21099 ,10950,10974,10945 ,0,0,0}, {20713,20691,21099 ,10974,10946,10945 ,0,0,0}, - {21101,20683,20681 ,10948,10939,10949 ,0,0,0}, {21102,20681,20713 ,10950,10949,10974 ,0,0,0}, - {21096,21097,20684 ,10940,10943,10941 ,0,0,0}, {21101,21096,20683 ,10948,10940,10939 ,0,0,0}, - {20679,21098,20677 ,10942,10944,10937 ,0,0,0}, {20684,21097,20679 ,10941,10943,10942 ,0,0,0}, - {21095,20677,21098 ,10938,10937,10944 ,0,0,0}, {21115,21078,21116 ,10975,10903,10976 ,0,0,0}, - {21117,21080,21118 ,10977,10978,10979 ,0,0,0}, {21119,21081,21077 ,10980,10981,10982 ,0,0,0}, - {21094,21120,21121 ,10983,10984,10985 ,0,0,0}, {21079,21122,21083 ,10986,10987,10988 ,0,0,0}, - {21123,21124,21085 ,10989,10990,10991 ,0,0,0}, {21125,21086,21082 ,10992,10993,10994 ,0,0,0}, - {21126,21088,21089 ,10995,10996,10997 ,0,0,0}, {21089,21084,21127 ,10997,10998,10999 ,0,0,0}, - {21128,21090,21087 ,11000,11001,11002 ,0,0,0}, {21087,21129,21128 ,11002,11003,11000 ,0,0,0}, - {21090,21130,21091 ,11001,11004,11005 ,0,0,0}, {21130,21090,21128 ,11004,11001,11000 ,0,0,0}, - {21092,21091,21131 ,11006,11005,11007 ,0,0,0}, {21130,21131,21091 ,11004,11007,11005 ,0,0,0}, - {21132,21092,21133 ,11008,11006,11009 ,0,0,0}, {21092,21131,21133 ,11006,11007,11009 ,0,0,0}, - {21093,21092,21132 ,11010,11006,11008 ,0,0,0}, {21129,21088,21126 ,11003,10996,10995 ,0,0,0}, - {21087,21088,21129 ,11002,10996,11003 ,0,0,0}, {21084,21124,21127 ,10998,10990,10999 ,0,0,0}, - {21126,21089,21127 ,10995,10997,10999 ,0,0,0}, {21123,21085,21086 ,10989,10991,10993 ,0,0,0}, - {21124,21084,21085 ,10990,10998,10991 ,0,0,0}, {21121,21125,21082 ,10985,10992,10994 ,0,0,0}, - {21125,21123,21086 ,10992,10989,10993 ,0,0,0}, {21083,21120,21094 ,10988,10984,10983 ,0,0,0}, - {21094,21121,21082 ,10983,10985,10994 ,0,0,0}, {21079,21117,21122 ,10986,10977,10987 ,0,0,0}, - {21083,21122,21120 ,10988,10987,10984 ,0,0,0}, {21080,21081,21118 ,10978,10981,10979 ,0,0,0}, - {21079,21080,21117 ,10986,10978,10977 ,0,0,0}, {21119,21077,21115 ,10980,10982,10975 ,0,0,0}, - {21118,21081,21119 ,10979,10981,10980 ,0,0,0}, {21078,21115,21077 ,10903,10975,10982 ,0,0,0}, - {21098,21116,21095 ,11011,10976,11012 ,0,0,0}, {21101,21118,21096 ,11013,11014,11015 ,0,0,0}, - {21097,21119,21115 ,11016,11017,11018 ,0,0,0}, {21120,21099,21100 ,11019,11020,11021 ,0,0,0}, - {21117,21102,21122 ,11022,11023,11024 ,0,0,0}, {21104,21103,21123 ,11025,11026,11027 ,0,0,0}, - {21105,21125,21121 ,11028,11029,11030 ,0,0,0}, {21106,21126,21107 ,11031,11032,11033 ,0,0,0}, - {21127,21124,21108 ,11034,11035,11036 ,0,0,0}, {21109,21128,21110 ,11037,11038,11039 ,0,0,0}, - {21129,21106,21110 ,11040,11031,11039 ,0,0,0}, {21109,21111,21130 ,11037,11041,11042 ,0,0,0}, - {21130,21128,21109 ,11042,11038,11037 ,0,0,0}, {21131,21111,21112 ,11043,11041,11044 ,0,0,0}, - {21111,21131,21130 ,11041,11043,11042 ,0,0,0}, {21113,21133,21112 ,11045,11046,11044 ,0,0,0}, - {21131,21112,21133 ,11043,11044,11046 ,0,0,0}, {21114,21132,21133 ,11047,11008,11046 ,0,0,0}, - {21133,21113,21114 ,11046,11045,11047 ,0,0,0}, {21126,21106,21129 ,11032,11031,11040 ,0,0,0}, - {21128,21129,21110 ,11038,11040,11039 ,0,0,0}, {21107,21127,21108 ,11033,11034,11036 ,0,0,0}, - {21126,21127,21107 ,11032,11034,11033 ,0,0,0}, {21103,21124,21123 ,11026,11035,11027 ,0,0,0}, - {21108,21124,21103 ,11036,11035,11026 ,0,0,0}, {21105,21104,21125 ,11028,11025,11029 ,0,0,0}, - {21104,21123,21125 ,11025,11027,11029 ,0,0,0}, {21120,21100,21121 ,11019,11021,11030 ,0,0,0}, - {21100,21105,21121 ,11021,11028,11030 ,0,0,0}, {21122,21102,21099 ,11024,11023,11020 ,0,0,0}, - {21122,21099,21120 ,11024,11020,11019 ,0,0,0}, {21117,21118,21101 ,11022,11014,11013 ,0,0,0}, - {21117,21101,21102 ,11022,11013,11023 ,0,0,0}, {21096,21119,21097 ,11015,11017,11016 ,0,0,0}, - {21118,21119,21096 ,11014,11017,11015 ,0,0,0}, {21098,21115,21116 ,11011,11018,10976 ,0,0,0}, - {21097,21115,21098 ,11016,11018,11011 ,0,0,0}, {20801,21134,21135 ,11048,11049,11050 ,0,0,0}, - {20800,21136,20798 ,11051,11052,11053 ,0,0,0}, {21134,20801,21137 ,11049,11048,11054 ,0,0,0}, - {21135,21138,20801 ,11050,11048,11048 ,0,0,0}, {21137,20801,20798 ,11054,11048,11053 ,0,0,0}, - {21139,21137,20798 ,11055,11054,11053 ,0,0,0}, {21139,20798,21136 ,11055,11053,11052 ,0,0,0}, - {20836,20754,21140 ,11056,11057,11058 ,0,0,0}, {20836,21141,21142 ,11056,11059,11060 ,0,0,0}, - {21140,21141,20836 ,11058,11059,11056 ,0,0,0}, {20800,21142,21143 ,11051,11060,11061 ,0,0,0}, - {20800,20836,21142 ,11051,11056,11060 ,0,0,0}, {20800,21144,21145 ,11051,11062,11063 ,0,0,0}, - {21143,21144,20800 ,11061,11062,11051 ,0,0,0}, {20800,21146,21147 ,11051,11064,11065 ,0,0,0}, - {21145,21146,20800 ,11063,11064,11051 ,0,0,0}, {21136,20800,21148 ,11052,11051,11066 ,0,0,0}, - {21147,21148,20800 ,11065,11066,11051 ,0,0,0}, {21149,20622,21150 ,11067,11068,11069 ,0,0,0}, - {20622,21151,21152 ,11068,11070,11071 ,0,0,0}, {21152,20620,20622 ,11071,11072,11068 ,0,0,0}, - {20622,21149,21151 ,11068,11067,11070 ,0,0,0}, {20620,21153,21154 ,11072,11073,11074 ,0,0,0}, - {20620,21152,21153 ,11072,11071,11073 ,0,0,0}, {20622,21155,21150 ,11068,11075,11069 ,0,0,0}, - {20620,21154,20549 ,11072,11074,11076 ,0,0,0}, {21156,20622,20607 ,11077,11068,11078 ,0,0,0}, - {20622,21156,21155 ,11068,11077,11075 ,0,0,0}, {20609,21157,21158 ,11079,11079,11080 ,0,0,0}, - {21159,21160,20610 ,11081,11082,11083 ,0,0,0}, {21161,21162,20609 ,11084,11085,11079 ,0,0,0}, - {21161,20609,21158 ,11084,11079,11080 ,0,0,0}, {20609,21163,20610 ,11079,11086,11083 ,0,0,0}, - {21163,20609,21162 ,11086,11079,11085 ,0,0,0}, {21164,20610,21160 ,11087,11083,11082 ,0,0,0}, - {21163,21159,20610 ,11086,11081,11083 ,0,0,0}, {21156,20607,21164 ,11077,11078,11087 ,0,0,0}, - {21164,20607,20610 ,11087,11078,11083 ,0,0,0}, {21157,20609,21165 ,11088,11089,11090 ,0,0,0}, - {21006,21165,21024 ,11091,11090,11092 ,0,0,0}, {21006,20988,21165 ,11091,11093,11090 ,0,0,0}, - {21165,20988,20977 ,11090,11093,11094 ,0,0,0}, {20977,20949,21165 ,11094,11095,11090 ,0,0,0}, - {21165,20609,21024 ,11090,11089,11092 ,0,0,0}, {21166,21164,21167 ,11096,11097,11098 ,0,0,0}, - {21166,21168,21156 ,11096,324,11099 ,0,0,0}, {21156,21164,21166 ,11099,11097,11096 ,0,0,0}, - {21169,21170,21171 ,11100,11101,11102 ,0,0,0}, {21170,21172,21171 ,11101,11103,11102 ,0,0,0}, - {21170,21169,21173 ,11101,11100,11104 ,0,0,0}, {21151,21174,21173 ,11105,11106,11104 ,0,0,0}, - {21169,21151,21173 ,11100,11105,11104 ,0,0,0}, {21149,21174,21151 ,11107,11106,11105 ,0,0,0}, - {21174,21149,21175 ,11106,11107,11108 ,0,0,0}, {21150,21176,21175 ,11109,11110,11108 ,0,0,0}, - {21175,21149,21150 ,11108,11107,11109 ,0,0,0}, {21176,21155,21177 ,11110,11111,11112 ,0,0,0}, - {21155,21176,21150 ,11111,11110,11109 ,0,0,0}, {21168,21177,21156 ,11113,11112,11114 ,0,0,0}, - {21155,21156,21177 ,11111,11114,11112 ,0,0,0}, {21162,21178,21179 ,11115,11116,11117 ,0,0,0}, - {21167,21164,21160 ,11118,11119,11120 ,0,0,0}, {21160,21159,21180 ,11120,11121,11122 ,0,0,0}, - {21181,21163,21179 ,11123,11124,11117 ,0,0,0}, {21180,21159,21181 ,11122,11121,11123 ,0,0,0}, - {21160,21180,21167 ,11120,11122,11118 ,0,0,0}, {21159,21163,21181 ,11121,11124,11123 ,0,0,0}, - {21163,21162,21179 ,11124,11115,11117 ,0,0,0}, {21178,21162,21161 ,11116,11115,11125 ,0,0,0}, - {21161,21158,21182 ,11125,11126,11127 ,0,0,0}, {21182,21178,21161 ,11127,11116,11125 ,0,0,0}, - {21183,21158,21157 ,11128,11126,11129 ,0,0,0}, {21158,21183,21182 ,11126,11128,11127 ,0,0,0}, - {21183,21157,21165 ,11128,11129,11129 ,0,0,0}, {21138,21184,21185 ,11130,11130,11131 ,0,0,0}, - {21138,21185,21186 ,11130,11131,11130 ,0,0,0}, {21187,21138,21186 ,11130,11130,11130 ,0,0,0}, - {21178,21182,21138 ,11130,11130,11130 ,0,0,0}, {21178,21138,21187 ,11130,11130,11130 ,0,0,0}, - {21138,21183,21165 ,11130,11130,11131 ,0,0,0}, {21182,21183,21138 ,11130,11130,11130 ,0,0,0}, - {21138,21165,20801 ,11130,11131,11130 ,0,0,0}, {21165,20928,20908 ,11131,11130,11130 ,0,0,0}, - {21165,20949,20928 ,11131,11131,11130 ,0,0,0}, {20908,20888,21165 ,11130,11131,11131 ,0,0,0}, - {20801,21165,20869 ,11130,11131,11130 ,0,0,0}, {21165,20888,20869 ,11131,11131,11130 ,0,0,0}, - {20714,21095,21188 ,11132,11133,11134 ,0,0,0}, {21140,21189,21141 ,11135,11136,11137 ,0,0,0}, - {21190,21189,20715 ,11138,11136,11139 ,0,0,0}, {21191,21172,21192 ,11140,11141,11142 ,0,0,0}, - {21193,21191,21192 ,11143,11140,11142 ,0,0,0}, {21194,21195,21196 ,11144,11145,11146 ,0,0,0}, - {21195,21193,21196 ,11145,11143,11146 ,0,0,0}, {21189,20735,20715 ,11136,11147,11139 ,0,0,0}, - {21190,20715,20675 ,11138,11139,11148 ,0,0,0}, {21194,21142,21141 ,11144,11149,11137 ,0,0,0}, - {20754,20735,21140 ,11150,11147,11135 ,0,0,0}, {20714,21190,20675 ,11132,11138,11148 ,0,0,0}, - {21188,21197,21190 ,11134,11151,11138 ,0,0,0}, {21190,20714,21188 ,11138,11132,11134 ,0,0,0}, - {21197,21191,21193 ,11151,11140,11143 ,0,0,0}, {21195,21194,21141 ,11145,11144,11137 ,0,0,0}, - {21193,21195,21190 ,11143,11145,11138 ,0,0,0}, {21140,20735,21189 ,11135,11147,11136 ,0,0,0}, - {21193,21190,21197 ,11143,11138,11151 ,0,0,0}, {21192,21196,21193 ,11142,11146,11143 ,0,0,0}, - {21141,21189,21195 ,11137,11136,11145 ,0,0,0}, {21190,21195,21189 ,11138,11145,11136 ,0,0,0}, - {21198,21199,21200 ,11152,11153,11154 ,0,0,0}, {21201,21202,21203 ,11155,11156,11157 ,0,0,0}, - {21204,21205,21206 ,11158,11159,11160 ,0,0,0}, {21172,21170,21207 ,11161,11162,11163 ,0,0,0}, - {21208,21209,21146 ,11164,11165,11166 ,0,0,0}, {21210,21211,21212 ,11167,11168,11169 ,0,0,0}, - {21213,21214,21199 ,11170,11171,11153 ,0,0,0}, {21136,21148,21214 ,11172,11173,11171 ,0,0,0}, - {21215,21177,21168 ,11174,11175,11176 ,0,0,0}, {21198,21200,21215 ,11152,11154,11174 ,0,0,0}, - {21136,21214,21213 ,11172,11171,11170 ,0,0,0}, {21203,21200,21199 ,11157,11154,11153 ,0,0,0}, - {21148,21216,21214 ,11173,11177,11171 ,0,0,0}, {21209,21216,21147 ,11165,11177,11178 ,0,0,0}, - {21217,21208,21212 ,11179,11164,11169 ,0,0,0}, {21218,21206,21202 ,11180,11160,11156 ,0,0,0}, - {21143,21194,21210 ,11181,11182,11167 ,0,0,0}, {21205,21217,21207 ,11159,11179,11163 ,0,0,0}, - {21142,21194,21143 ,11183,11182,11181 ,0,0,0}, {21210,21194,21196 ,11167,11182,11184 ,0,0,0}, - {21147,21216,21148 ,11178,11177,11173 ,0,0,0}, {21147,21146,21209 ,11178,11166,11165 ,0,0,0}, - {21215,21200,21177 ,11174,11154,11175 ,0,0,0}, {21213,21199,21198 ,11170,11153,11152 ,0,0,0}, - {21203,21199,21201 ,11157,11153,11155 ,0,0,0}, {21176,21177,21200 ,11185,11175,11154 ,0,0,0}, - {21201,21214,21216 ,11155,11171,11177 ,0,0,0}, {21192,21172,21207 ,11186,11161,11163 ,0,0,0}, - {21200,21203,21176 ,11154,11157,11185 ,0,0,0}, {21214,21201,21199 ,11171,11155,11153 ,0,0,0}, - {21202,21201,21218 ,11156,11155,11180 ,0,0,0}, {21175,21176,21203 ,11187,11185,11157 ,0,0,0}, - {21209,21218,21216 ,11165,11180,11177 ,0,0,0}, {21145,21208,21146 ,11188,11164,11166 ,0,0,0}, - {21203,21202,21175 ,11157,11156,11187 ,0,0,0}, {21216,21218,21201 ,11177,11180,11155 ,0,0,0}, - {21206,21218,21204 ,11160,11180,11158 ,0,0,0}, {21174,21175,21202 ,11189,11187,11156 ,0,0,0}, - {21208,21204,21209 ,11164,11158,11165 ,0,0,0}, {21144,21212,21145 ,11190,11169,11188 ,0,0,0}, - {21206,21173,21174 ,11160,11191,11189 ,0,0,0}, {21209,21204,21218 ,11165,11158,11180 ,0,0,0}, - {21204,21217,21205 ,11158,11179,11159 ,0,0,0}, {21174,21202,21206 ,11189,11156,11160 ,0,0,0}, - {21145,21212,21208 ,11188,11169,11164 ,0,0,0}, {21210,21144,21143 ,11167,11190,11181 ,0,0,0}, - {21205,21170,21173 ,11159,11162,11191 ,0,0,0}, {21208,21217,21204 ,11164,11179,11158 ,0,0,0}, - {21211,21207,21217 ,11168,11163,11179 ,0,0,0}, {21173,21206,21205 ,11191,11160,11159 ,0,0,0}, - {21144,21210,21212 ,11190,11167,11169 ,0,0,0}, {21212,21211,21217 ,11169,11168,11179 ,0,0,0}, - {21196,21192,21211 ,11184,11186,11168 ,0,0,0}, {21210,21196,21211 ,11167,11184,11168 ,0,0,0}, - {21192,21207,21211 ,11186,11163,11168 ,0,0,0}, {21170,21205,21207 ,11162,11159,11163 ,0,0,0}, - {21215,21166,21219 ,11192,11193,11194 ,0,0,0}, {21139,21220,21137 ,11195,11196,11054 ,0,0,0}, - {21219,21166,21221 ,11194,11193,11197 ,0,0,0}, {21166,21167,21221 ,11193,324,11197 ,0,0,0}, - {21219,21222,21220 ,11194,11198,11196 ,0,0,0}, {21215,21168,21166 ,11192,324,11193 ,0,0,0}, - {21220,21222,21137 ,11196,11198,11054 ,0,0,0}, {21213,21220,21139 ,11199,11196,11195 ,0,0,0}, - {21136,21213,21139 ,11200,11199,11195 ,0,0,0}, {21213,21198,21220 ,11199,11201,11196 ,0,0,0}, - {21198,21215,21219 ,11201,11192,11194 ,0,0,0}, {21198,21219,21220 ,11201,11194,11196 ,0,0,0}, - {21222,21219,21221 ,11198,11194,11197 ,0,0,0}, {21187,21186,21179 ,11202,11203,11204 ,0,0,0}, - {21221,21167,21180 ,11205,324,11206 ,0,0,0}, {21180,21181,21223 ,11206,11207,11208 ,0,0,0}, - {21180,21223,21221 ,11206,11208,11205 ,0,0,0}, {21178,21187,21179 ,11209,11202,11204 ,0,0,0}, - {21185,21184,21224 ,11210,11211,11212 ,0,0,0}, {21224,21225,21185 ,11212,11213,11210 ,0,0,0}, - {21222,21223,21226 ,11214,11208,11215 ,0,0,0}, {21226,21223,21225 ,11215,11208,11213 ,0,0,0}, - {21184,21138,21135 ,11211,11216,11217 ,0,0,0}, {21222,21226,21137 ,11214,11215,11218 ,0,0,0}, - {21135,21226,21224 ,11217,11215,11212 ,0,0,0}, {21221,21223,21222 ,11205,11208,11214 ,0,0,0}, - {21135,21134,21226 ,11217,11219,11215 ,0,0,0}, {21226,21134,21137 ,11215,11219,11218 ,0,0,0}, - {21223,21181,21225 ,11208,11207,11213 ,0,0,0}, {21179,21225,21181 ,11204,11213,11207 ,0,0,0}, - {21135,21224,21184 ,11217,11212,11211 ,0,0,0}, {21226,21225,21224 ,11215,11213,11212 ,0,0,0}, - {21186,21225,21179 ,11203,11213,11204 ,0,0,0}, {21186,21185,21225 ,11203,11210,11213 ,0,0,0}, - {21060,21227,21228 ,11220,11221,11222 ,0,0,0}, {21172,21191,21229 ,11223,11224,11225 ,0,0,0}, - {21230,21229,21191 ,11226,11225,11224 ,0,0,0}, {21060,21228,21078 ,11220,11222,11227 ,0,0,0}, - {21228,21227,21230 ,11222,11221,11226 ,0,0,0}, {21188,21095,21116 ,11228,11229,11230 ,0,0,0}, - {21078,21228,21116 ,11227,11222,11230 ,0,0,0}, {21154,21227,21042 ,11231,11221,11232 ,0,0,0}, - {21231,21154,21153 ,11233,11231,11234 ,0,0,0}, {21227,21060,21042 ,11221,11220,11232 ,0,0,0}, - {21229,21169,21171 ,11225,11235,11236 ,0,0,0}, {21229,21231,21232 ,11225,11233,11237 ,0,0,0}, - {21042,20549,21154 ,11232,11238,11231 ,0,0,0}, {21169,21232,21151 ,11235,11237,11239 ,0,0,0}, - {21232,21169,21229 ,11237,11235,11225 ,0,0,0}, {21228,21188,21116 ,11222,11228,11230 ,0,0,0}, - {21227,21231,21230 ,11221,11233,11226 ,0,0,0}, {21197,21188,21228 ,11240,11228,11222 ,0,0,0}, - {21154,21231,21227 ,11231,11233,11221 ,0,0,0}, {21232,21153,21152 ,11237,11234,11241 ,0,0,0}, - {21191,21197,21230 ,11224,11240,11226 ,0,0,0}, {21228,21230,21197 ,11222,11226,11240 ,0,0,0}, - {21153,21232,21231 ,11234,11237,11233 ,0,0,0}, {21151,21232,21152 ,11239,11237,11241 ,0,0,0}, - {21229,21171,21172 ,11225,11236,11223 ,0,0,0}, {21231,21229,21230 ,11233,11225,11226 ,0,0,0}, - {21233,20674,21234 ,11242,11243,11244 ,0,0,0}, {20674,21235,21236 ,11243,11245,11246 ,0,0,0}, - {21236,20673,20674 ,11246,11247,11243 ,0,0,0}, {20674,21233,21235 ,11243,11242,11245 ,0,0,0}, - {20673,21237,21238 ,11247,11248,11249 ,0,0,0}, {20673,21236,21237 ,11247,11246,11248 ,0,0,0}, - {20674,21239,21234 ,11243,11250,11244 ,0,0,0}, {20673,21238,20569 ,11247,11249,11251 ,0,0,0}, - {21240,20674,20582 ,11252,11243,11253 ,0,0,0}, {20674,21240,21239 ,11243,11252,11250 ,0,0,0}, - {20583,21241,21242 ,11254,11254,11255 ,0,0,0}, {21243,21244,20581 ,11256,11257,11258 ,0,0,0}, - {21245,21246,20583 ,11259,11260,11254 ,0,0,0}, {21245,20583,21242 ,11259,11254,11255 ,0,0,0}, - {20583,21247,20581 ,11254,11261,11258 ,0,0,0}, {21247,20583,21246 ,11261,11254,11260 ,0,0,0}, - {21248,20581,21244 ,11262,11258,11257 ,0,0,0}, {21247,21243,20581 ,11261,11256,11258 ,0,0,0}, - {21240,20582,21248 ,11252,11253,11262 ,0,0,0}, {21248,20582,20581 ,11262,11253,11258 ,0,0,0}, - {20791,21249,21250 ,11263,11264,11265 ,0,0,0}, {20868,21251,20822 ,11266,11267,11268 ,0,0,0}, - {21249,20791,21252 ,11264,11263,11269 ,0,0,0}, {21250,21253,20791 ,11265,11263,11263 ,0,0,0}, - {21252,20791,20822 ,11269,11263,11268 ,0,0,0}, {21254,21252,20822 ,11270,11269,11268 ,0,0,0}, - {21254,20822,21251 ,11270,11268,11267 ,0,0,0}, {20825,20849,21255 ,11271,11272,11273 ,0,0,0}, - {20825,21256,21257 ,11271,11274,11275 ,0,0,0}, {21255,21256,20825 ,11273,11274,11271 ,0,0,0}, - {20868,21257,21258 ,11266,11275,11276 ,0,0,0}, {20868,20825,21257 ,11266,11271,11275 ,0,0,0}, - {20868,21259,21260 ,11266,11277,11278 ,0,0,0}, {21258,21259,20868 ,11276,11277,11266 ,0,0,0}, - {20868,21261,21262 ,11266,11279,11280 ,0,0,0}, {21260,21261,20868 ,11278,11279,11266 ,0,0,0}, - {21251,20868,21263 ,11267,11266,11281 ,0,0,0}, {21262,21263,20868 ,11280,11281,11266 ,0,0,0}, - {21132,21241,21093 ,11282,11283,11282 ,0,0,0}, {20583,21057,21241 ,11282,11282,11283 ,0,0,0}, - {21114,21264,21241 ,11282,11283,11283 ,0,0,0}, {21241,21132,21114 ,11283,11282,11282 ,0,0,0}, - {21076,21093,21241 ,11282,11282,11283 ,0,0,0}, {21076,21241,21057 ,11282,11283,11282 ,0,0,0}, - {21265,21266,21240 ,21,21,21 ,0,0,0}, {21248,21267,21265 ,11284,21,21 ,0,0,0}, - {21265,21240,21248 ,21,21,11284 ,0,0,0}, {21268,21269,21270 ,11285,11286,11287 ,0,0,0}, - {21269,21271,21270 ,11286,11288,11287 ,0,0,0}, {21269,21268,21272 ,11286,11285,11289 ,0,0,0}, - {21235,21273,21272 ,11290,11291,11289 ,0,0,0}, {21268,21235,21272 ,11285,11290,11289 ,0,0,0}, - {21233,21273,21235 ,11292,11291,11290 ,0,0,0}, {21273,21233,21274 ,11291,11292,11293 ,0,0,0}, - {21234,21275,21274 ,11294,11295,11293 ,0,0,0}, {21274,21233,21234 ,11293,11292,11294 ,0,0,0}, - {21275,21239,21276 ,11295,11296,11297 ,0,0,0}, {21239,21275,21234 ,11296,11295,11294 ,0,0,0}, - {21266,21276,21240 ,11298,11297,11299 ,0,0,0}, {21239,21240,21276 ,11296,11299,11297 ,0,0,0}, - {21277,21278,21246 ,11300,11301,11302 ,0,0,0}, {21279,21247,21278 ,11303,11304,11301 ,0,0,0}, - {21248,21244,21267 ,21,11305,21 ,0,0,0}, {21243,21280,21244 ,11306,11307,11305 ,0,0,0}, - {21243,21279,21280 ,11306,11303,11307 ,0,0,0}, {21280,21267,21244 ,11307,21,11305 ,0,0,0}, - {21247,21279,21243 ,11304,11303,11306 ,0,0,0}, {21247,21246,21278 ,11304,11302,11301 ,0,0,0}, - {21277,21246,21245 ,11300,11302,11308 ,0,0,0}, {21245,21242,21281 ,11308,11309,11310 ,0,0,0}, - {21281,21277,21245 ,11310,11300,11308 ,0,0,0}, {21282,21242,21241 ,11311,11309,11312 ,0,0,0}, - {21242,21282,21281 ,11309,11311,11310 ,0,0,0}, {21282,21241,21264 ,11311,11312,11312 ,0,0,0}, - {20752,21264,20733 ,11313,11314,11315 ,0,0,0}, {21283,21253,21284 ,11316,11317,11318 ,0,0,0}, - {21253,21277,21281 ,11317,11319,11320 ,0,0,0}, {21281,21282,21253 ,11320,11321,11317 ,0,0,0}, - {21283,21285,21253 ,11316,11322,11317 ,0,0,0}, {21253,21286,21277 ,11317,11323,11319 ,0,0,0}, - {21285,21286,21253 ,11322,11323,11317 ,0,0,0}, {21264,20791,21253 ,11314,11324,11317 ,0,0,0}, - {21282,21264,21253 ,11321,11314,11317 ,0,0,0}, {21264,20771,20791 ,11314,11325,11324 ,0,0,0}, - {20771,21264,20752 ,11325,11314,11313 ,0,0,0}, {21264,20711,20712 ,11314,11326,11327 ,0,0,0}, - {21264,21114,20711 ,11314,11314,11326 ,0,0,0}, {20712,20733,21264 ,11327,11315,11314 ,0,0,0}, - {20946,20966,21287 ,11328,11329,11330 ,0,0,0}, {21255,21288,21256 ,11331,11332,11333 ,0,0,0}, - {21289,21288,20907 ,11334,11332,11335 ,0,0,0}, {21290,21271,21291 ,11336,11337,11338 ,0,0,0}, - {21292,21290,21291 ,11339,11336,11338 ,0,0,0}, {21293,21294,21295 ,11340,11341,11342 ,0,0,0}, - {21294,21292,21295 ,11341,11339,11342 ,0,0,0}, {21288,20887,20907 ,11332,11343,11335 ,0,0,0}, - {21289,20907,20926 ,11334,11335,11344 ,0,0,0}, {21293,21257,21256 ,11340,11345,11333 ,0,0,0}, - {20849,20887,21255 ,11346,11343,11331 ,0,0,0}, {20946,21289,20926 ,11328,11334,11344 ,0,0,0}, - {21287,21296,21289 ,11330,11347,11334 ,0,0,0}, {21289,20946,21287 ,11334,11328,11330 ,0,0,0}, - {21296,21290,21292 ,11347,11336,11339 ,0,0,0}, {21294,21293,21256 ,11341,11340,11333 ,0,0,0}, - {21292,21294,21289 ,11339,11341,11334 ,0,0,0}, {21255,20887,21288 ,11331,11343,11332 ,0,0,0}, - {21292,21289,21296 ,11339,11334,11347 ,0,0,0}, {21291,21295,21292 ,11338,11342,11339 ,0,0,0}, - {21256,21288,21294 ,11333,11332,11341 ,0,0,0}, {21289,21294,21288 ,11334,11341,11332 ,0,0,0}, - {21297,21298,21299 ,11348,11349,11350 ,0,0,0}, {21273,21300,21301 ,11351,11352,11353 ,0,0,0}, - {21273,21274,21300 ,11351,11354,11352 ,0,0,0}, {21291,21269,21302 ,11355,11356,11357 ,0,0,0}, - {21303,21261,21304 ,11358,11359,11360 ,0,0,0}, {21291,21271,21269 ,11355,11361,11356 ,0,0,0}, - {21305,21306,21307 ,11362,11363,11364 ,0,0,0}, {21275,21308,21309 ,11365,11366,11367 ,0,0,0}, - {21266,21306,21310 ,21,11363,11368 ,0,0,0}, {21305,21311,21310 ,11362,11369,11368 ,0,0,0}, - {21263,21262,21312 ,11370,11371,11372 ,0,0,0}, {21262,21303,21312 ,11371,11358,11372 ,0,0,0}, - {21313,21314,21297 ,11373,11374,11348 ,0,0,0}, {21303,21304,21311 ,11358,11360,11369 ,0,0,0}, - {21315,21251,21263 ,11375,11376,11370 ,0,0,0}, {21272,21301,21302 ,11377,11353,11357 ,0,0,0}, - {21275,21309,21274 ,11365,11367,11354 ,0,0,0}, {21302,21299,21295 ,11357,11350,11378 ,0,0,0}, - {21295,21299,21293 ,11378,11350,11379 ,0,0,0}, {21293,21298,21257 ,11379,11349,11380 ,0,0,0}, - {21291,21302,21295 ,11355,11357,11378 ,0,0,0}, {21269,21272,21302 ,11356,11377,11357 ,0,0,0}, - {21298,21293,21299 ,11349,11379,11350 ,0,0,0}, {21298,21314,21258 ,11349,11374,11381 ,0,0,0}, - {21299,21301,21297 ,11350,11353,11348 ,0,0,0}, {21257,21298,21258 ,11380,11349,11381 ,0,0,0}, - {21302,21301,21299 ,11357,11353,11350 ,0,0,0}, {21272,21273,21301 ,11377,11351,11353 ,0,0,0}, - {21314,21298,21297 ,11374,11349,11348 ,0,0,0}, {21314,21316,21259 ,11374,11382,11383 ,0,0,0}, - {21297,21300,21313 ,11348,11352,11373 ,0,0,0}, {21258,21314,21259 ,11381,11374,11383 ,0,0,0}, - {21301,21300,21297 ,11353,11352,11348 ,0,0,0}, {21309,21300,21274 ,11367,11352,11354 ,0,0,0}, - {21316,21314,21313 ,11382,11374,11373 ,0,0,0}, {21316,21304,21260 ,11382,11360,11384 ,0,0,0}, - {21309,21317,21313 ,11367,11385,11373 ,0,0,0}, {21259,21316,21260 ,11383,11382,11384 ,0,0,0}, - {21309,21313,21300 ,11367,11373,11352 ,0,0,0}, {21276,21308,21275 ,11386,11366,11365 ,0,0,0}, - {21304,21316,21317 ,11360,11382,11385 ,0,0,0}, {21313,21317,21316 ,11373,11385,11382 ,0,0,0}, - {21308,21311,21317 ,11366,11369,11385 ,0,0,0}, {21260,21304,21261 ,11384,11360,11359 ,0,0,0}, - {21309,21308,21317 ,11367,11366,11385 ,0,0,0}, {21266,21310,21276 ,21,11368,11386 ,0,0,0}, - {21312,21303,21305 ,11372,11358,11362 ,0,0,0}, {21317,21311,21304 ,11385,11369,11360 ,0,0,0}, - {21311,21305,21303 ,11369,11362,11358 ,0,0,0}, {21261,21303,21262 ,11359,11358,11371 ,0,0,0}, - {21308,21276,21310 ,11366,11386,11368 ,0,0,0}, {21311,21308,21310 ,11369,11366,11368 ,0,0,0}, - {21312,21307,21315 ,11372,11364,11375 ,0,0,0}, {21306,21305,21310 ,11363,11362,11368 ,0,0,0}, - {21315,21263,21312 ,11375,11370,11372 ,0,0,0}, {21307,21312,21305 ,11364,11372,11362 ,0,0,0}, - {21306,21265,21318 ,11387,11388,11389 ,0,0,0}, {21254,21319,21252 ,11390,11391,11269 ,0,0,0}, - {21318,21265,21320 ,11389,11388,11392 ,0,0,0}, {21265,21267,21320 ,11388,21,11392 ,0,0,0}, - {21318,21321,21319 ,11389,11393,11391 ,0,0,0}, {21306,21266,21265 ,11387,21,11388 ,0,0,0}, - {21319,21321,21252 ,11391,11393,11269 ,0,0,0}, {21315,21319,21254 ,11394,11391,11390 ,0,0,0}, - {21251,21315,21254 ,11395,11394,11390 ,0,0,0}, {21315,21307,21319 ,11394,11396,11391 ,0,0,0}, - {21307,21306,21318 ,11396,11387,11389 ,0,0,0}, {21307,21318,21319 ,11396,11389,11391 ,0,0,0}, - {21321,21318,21320 ,11393,11389,11392 ,0,0,0}, {21286,21285,21278 ,11397,11398,11399 ,0,0,0}, - {21320,21267,21280 ,11400,21,11401 ,0,0,0}, {21280,21279,21322 ,11401,11402,11403 ,0,0,0}, - {21280,21322,21320 ,11401,11403,11400 ,0,0,0}, {21277,21286,21278 ,11404,11397,11399 ,0,0,0}, - {21283,21284,21323 ,11405,11406,11407 ,0,0,0}, {21323,21324,21283 ,11407,11408,11405 ,0,0,0}, - {21321,21322,21325 ,11409,11403,11410 ,0,0,0}, {21325,21322,21324 ,11410,11403,11408 ,0,0,0}, - {21284,21253,21250 ,11406,11411,11412 ,0,0,0}, {21321,21325,21252 ,11409,11410,11413 ,0,0,0}, - {21250,21325,21323 ,11412,11410,11407 ,0,0,0}, {21320,21322,21321 ,11400,11403,11409 ,0,0,0}, - {21250,21249,21325 ,11412,11414,11410 ,0,0,0}, {21325,21249,21252 ,11410,11414,11413 ,0,0,0}, - {21322,21279,21324 ,11403,11402,11408 ,0,0,0}, {21278,21324,21279 ,11399,11408,11402 ,0,0,0}, - {21250,21323,21284 ,11412,11407,11406 ,0,0,0}, {21325,21324,21323 ,11410,11408,11407 ,0,0,0}, - {21285,21324,21278 ,11398,11408,11399 ,0,0,0}, {21285,21283,21324 ,11398,11405,11408 ,0,0,0}, - {21326,21021,21327 ,11415,11416,11417 ,0,0,0}, {21040,20569,21238 ,11418,11419,11420 ,0,0,0}, - {21268,21328,21235 ,11421,11422,11423 ,0,0,0}, {21329,21290,21330 ,11424,11425,11426 ,0,0,0}, - {21290,21329,21270 ,11425,11424,11427 ,0,0,0}, {21270,21271,21290 ,11427,11428,11425 ,0,0,0}, - {21296,21330,21290 ,11429,11426,11425 ,0,0,0}, {21326,21004,21021 ,11415,11430,11416 ,0,0,0}, - {21270,21329,21268 ,11427,11424,11421 ,0,0,0}, {21328,21330,21331 ,11422,11426,11431 ,0,0,0}, - {21287,20966,20986 ,11432,11433,11434 ,0,0,0}, {21004,21326,20986 ,11430,11415,11434 ,0,0,0}, - {21331,21237,21236 ,11431,11435,11436 ,0,0,0}, {21327,21040,21238 ,11417,11418,11420 ,0,0,0}, - {21329,21330,21328 ,11424,11426,11422 ,0,0,0}, {21331,21236,21328 ,11431,11436,11422 ,0,0,0}, - {21235,21328,21236 ,11423,11422,11436 ,0,0,0}, {21268,21329,21328 ,11421,11424,11422 ,0,0,0}, - {21326,21296,21287 ,11415,11429,11432 ,0,0,0}, {21331,21326,21327 ,11431,11415,11417 ,0,0,0}, - {21331,21330,21326 ,11431,11426,11415 ,0,0,0}, {21237,21331,21327 ,11435,11431,11417 ,0,0,0}, - {21296,21326,21330 ,11429,11415,11426 ,0,0,0}, {20986,21326,21287 ,11434,11415,11432 ,0,0,0}, - {21040,21327,21021 ,11418,11417,11416 ,0,0,0}, {21327,21238,21237 ,11417,11420,11435 ,0,0,0}, - {20663,20526,20525 ,11437,11438,11439 ,0,0,0}, {21332,21333,20552 ,11440,11441,11442 ,0,0,0}, - {20599,21334,21335 ,11443,11444,11445 ,0,0,0}, {20557,20556,21336 ,11446,11447,11448 ,0,0,0}, - {20596,20631,21337 ,11449,11450,11451 ,0,0,0}, {20560,20561,21338 ,11452,11453,11454 ,0,0,0}, - {20560,21339,20556 ,11452,11455,11447 ,0,0,0}, {21340,20651,21341 ,11456,11457,11458 ,0,0,0}, - {20651,21340,20561 ,11457,11456,11453 ,0,0,0}, {21342,21341,20650 ,11459,11458,11460 ,0,0,0}, - {20651,20650,21341 ,11457,11460,11458 ,0,0,0}, {20539,20540,21342 ,21,21,11459 ,0,0,0}, - {21342,20650,20539 ,11459,11460,21 ,0,0,0}, {21338,21339,20560 ,11454,11455,11452 ,0,0,0}, - {20561,21340,21338 ,11453,11456,11454 ,0,0,0}, {21336,21337,20557 ,11448,11451,11446 ,0,0,0}, - {20556,21339,21336 ,11447,11455,11448 ,0,0,0}, {21332,20596,21337 ,11440,11449,11451 ,0,0,0}, - {20631,20557,21337 ,11450,11446,11451 ,0,0,0}, {21333,20550,20552 ,11441,11461,11442 ,0,0,0}, - {21332,20552,20596 ,11440,11442,11449 ,0,0,0}, {20599,20550,21334 ,11443,11461,11444 ,0,0,0}, - {21333,21334,20550 ,11441,11444,11461 ,0,0,0}, {20663,21335,21343 ,11437,11445,11462 ,0,0,0}, - {20599,21335,20663 ,11443,11445,11437 ,0,0,0}, {20526,20663,21343 ,11438,11437,11462 ,0,0,0}, - {21334,20505,20508 ,730,730,730 ,0,0,0}, {20521,21344,20519 ,730,730,730 ,0,0,0}, - {20521,20524,21345 ,730,730,730 ,0,0,0}, {20517,20519,21346 ,730,730,730 ,0,0,0}, - {20524,20511,21345 ,730,730,730 ,0,0,0}, {21344,20521,21345 ,730,730,730 ,0,0,0}, - {20511,20524,20526 ,730,730,730 ,0,0,0}, {20517,21347,20514 ,730,730,730 ,0,0,0}, - {21343,20511,20526 ,730,730,730 ,0,0,0}, {20493,20505,21332 ,730,730,730 ,0,0,0}, - {20528,20516,21348 ,730,730,730 ,0,0,0}, {21349,20529,20528 ,730,730,730 ,0,0,0}, - {8447,20493,21337 ,730,730,730 ,0,0,0}, {20495,21336,21339 ,730,730,730 ,0,0,0}, - {21350,20532,20529 ,730,730,730 ,0,0,0}, {20532,21351,20533 ,730,730,730 ,0,0,0}, - {20535,20533,21352 ,730,730,730 ,0,0,0}, {21339,20496,20495 ,730,730,730 ,0,0,0}, - {20496,21338,21340 ,730,730,730 ,0,0,0}, {20503,21342,20540 ,730,730,730 ,0,0,0}, - {20540,20538,20503 ,730,730,730 ,0,0,0}, {20535,21353,20538 ,730,730,730 ,0,0,0}, - {21341,20502,21340 ,730,730,730 ,0,0,0}, {20516,20514,21348 ,730,730,730 ,0,0,0}, - {20508,20510,21335 ,730,730,730 ,0,0,0}, {21337,21336,8447 ,730,730,730 ,0,0,0}, - {21344,21346,20519 ,730,730,730 ,0,0,0}, {21346,21347,20517 ,730,730,730 ,0,0,0}, - {21347,21348,20514 ,730,730,730 ,0,0,0}, {21348,21349,20528 ,730,730,730 ,0,0,0}, - {21349,21350,20529 ,730,730,730 ,0,0,0}, {21350,21351,20532 ,730,730,730 ,0,0,0}, - {21351,21352,20533 ,730,730,730 ,0,0,0}, {21352,21353,20535 ,730,730,730 ,0,0,0}, - {21353,20503,20538 ,730,730,730 ,0,0,0}, {20503,20499,21342 ,730,730,730 ,0,0,0}, - {20499,20502,21341 ,730,730,730 ,0,0,0}, {20499,21341,21342 ,730,730,730 ,0,0,0}, - {20502,20496,21340 ,730,730,730 ,0,0,0}, {21338,20496,21339 ,730,730,730 ,0,0,0}, - {20495,8447,21336 ,730,730,730 ,0,0,0}, {20493,21332,21337 ,730,730,730 ,0,0,0}, - {20505,21333,21332 ,730,730,730 ,0,0,0}, {21334,20508,21335 ,730,730,730 ,0,0,0}, - {21333,20505,21334 ,730,730,730 ,0,0,0}, {21335,20510,21343 ,730,730,730 ,0,0,0}, - {20511,21343,20510 ,730,730,730 ,0,0,0}, {20509,21354,21355 ,730,730,11463 ,0,0,0}, - {21356,21355,21357 ,730,11463,730 ,0,0,0}, {21356,21357,21358 ,730,730,11463 ,0,0,0}, - {21359,21355,21356 ,730,11463,730 ,0,0,0}, {21359,20512,21355 ,730,730,11463 ,0,0,0}, - {21358,21357,21360 ,11463,730,11464 ,0,0,0}, {20509,21355,20512 ,730,11463,730 ,0,0,0}, - {21354,20507,21361 ,730,730,11464 ,0,0,0}, {21354,20509,20507 ,730,730,730 ,0,0,0}, - {21361,20507,21362 ,11464,730,730 ,0,0,0}, {21362,20507,20506 ,730,730,11464 ,0,0,0}, - {21362,20506,20504 ,730,11464,730 ,0,0,0}, {21363,20504,20492 ,11465,730,11464 ,0,0,0}, - {20504,21363,21362 ,730,11465,730 ,0,0,0}, {20500,21363,20497 ,730,11465,730 ,0,0,0}, - {20492,20497,21363 ,11464,730,11465 ,0,0,0}, {20501,20494,20498 ,11464,730,11466 ,0,0,0}, - {20497,20494,20501 ,730,730,11464 ,0,0,0}, {20501,20500,20497 ,11464,730,730 ,0,0,0}, - {20503,21353,21363 ,11467,11468,11469 ,0,0,0}, {21355,21354,21350 ,11470,11471,11472 ,0,0,0}, - {21361,21362,21352 ,11473,11474,11475 ,0,0,0}, {21360,21348,21347 ,11476,11477,11478 ,0,0,0}, - {21349,21348,21357 ,11479,11477,11480 ,0,0,0}, {21356,21346,21344 ,11481,11482,11483 ,0,0,0}, - {21346,21356,21358 ,11482,11481,11484 ,0,0,0}, {21345,21359,21344 ,11485,11486,11483 ,0,0,0}, - {21356,21344,21359 ,11481,11483,11486 ,0,0,0}, {21345,20511,20512 ,11485,11487,11487 ,0,0,0}, - {20512,21359,21345 ,11487,11486,11485 ,0,0,0}, {21360,21347,21358 ,11476,11478,11484 ,0,0,0}, - {21347,21346,21358 ,11478,11482,11484 ,0,0,0}, {21350,21349,21355 ,11472,11479,11470 ,0,0,0}, - {21349,21357,21355 ,11479,11480,11470 ,0,0,0}, {21357,21348,21360 ,11480,11477,11476 ,0,0,0}, - {21362,21363,21353 ,11474,11469,11468 ,0,0,0}, {21351,21350,21354 ,11488,11472,11471 ,0,0,0}, - {21353,21352,21362 ,11468,11475,11474 ,0,0,0}, {21351,21361,21352 ,11488,11473,11475 ,0,0,0}, - {21354,21361,21351 ,11471,11473,11488 ,0,0,0}, {21363,20500,20503 ,11469,11489,11467 ,0,0,0}, - {20565,20480,20479 ,11490,324,11491 ,0,0,0}, {21364,21365,20647 ,11492,11493,11494 ,0,0,0}, - {20648,21366,20567 ,11495,11496,11497 ,0,0,0}, {21367,20586,21368 ,11498,11499,11500 ,0,0,0}, - {20643,20588,21369 ,11501,11502,11503 ,0,0,0}, {21370,20585,20645 ,11504,11505,11506 ,0,0,0}, - {20585,21370,21368 ,11505,11504,11500 ,0,0,0}, {20577,21371,20645 ,11507,11508,11506 ,0,0,0}, - {21370,20645,21371 ,11504,11506,11508 ,0,0,0}, {20577,20491,20490 ,11507,1095,1631 ,0,0,0}, - {20490,21371,20577 ,1631,11508,11507 ,0,0,0}, {20586,21367,20588 ,11499,11498,11502 ,0,0,0}, - {20586,20585,21368 ,11499,11505,11500 ,0,0,0}, {21364,20643,21369 ,11492,11501,11503 ,0,0,0}, - {21369,20588,21367 ,11503,11502,11498 ,0,0,0}, {21365,20648,20647 ,11493,11495,11494 ,0,0,0}, - {21364,20647,20643 ,11492,11494,11501 ,0,0,0}, {21366,21372,20567 ,11496,11509,11497 ,0,0,0}, - {21365,21366,20648 ,11493,11496,11495 ,0,0,0}, {20480,20565,21372 ,324,11490,11509 ,0,0,0}, - {20567,21372,20565 ,11497,11509,11490 ,0,0,0}, {20487,21364,20488 ,730,730,730 ,0,0,0}, - {20484,21366,20485 ,730,730,730 ,0,0,0}, {20490,21369,21367 ,730,730,730 ,0,0,0}, - {21371,21367,21368 ,730,730,730 ,0,0,0}, {21370,21371,21368 ,730,730,730 ,0,0,0}, - {20488,21369,20490 ,730,730,730 ,0,0,0}, {20490,21367,21371 ,730,730,730 ,0,0,0}, - {20488,21364,21369 ,730,730,730 ,0,0,0}, {20487,21365,21364 ,730,730,730 ,0,0,0}, - {20487,20485,21366 ,730,730,730 ,0,0,0}, {21366,21365,20487 ,730,730,730 ,0,0,0}, - {21372,21366,20484 ,730,730,730 ,0,0,0}, {21372,20481,20480 ,730,730,730 ,0,0,0}, - {20481,21372,20484 ,730,730,730 ,0,0,0}, {20480,20481,20473 ,730,730,730 ,0,0,0}, - {20476,20470,20474 ,730,730,730 ,0,0,0}, {20473,20470,20476 ,730,730,730 ,0,0,0}, - {20476,20480,20473 ,730,730,730 ,0,0,0}, {20658,20458,20459 ,11510,11511,11512 ,0,0,0}, - {21373,21374,20604 ,11492,11493,11513 ,0,0,0}, {20605,21375,20657 ,11514,11496,11515 ,0,0,0}, - {21376,20602,20601 ,11498,11516,11517 ,0,0,0}, {20618,20602,21377 ,11518,11516,11519 ,0,0,0}, - {21378,20662,20554 ,11504,11520,11521 ,0,0,0}, {20601,20662,21379 ,11517,11520,11500 ,0,0,0}, - {20553,21380,20554 ,11522,11508,11521 ,0,0,0}, {21378,20554,21380 ,11504,11521,11508 ,0,0,0}, - {20553,20469,20468 ,11522,11487,11523 ,0,0,0}, {20468,21380,20553 ,11523,11508,11522 ,0,0,0}, - {21376,20601,21379 ,11498,11517,11500 ,0,0,0}, {21379,20662,21378 ,11500,11520,11504 ,0,0,0}, - {20618,21377,21373 ,11518,11519,11492 ,0,0,0}, {21377,20602,21376 ,11519,11516,11498 ,0,0,0}, - {21374,20605,20604 ,11493,11514,11513 ,0,0,0}, {21373,20604,20618 ,11492,11513,11518 ,0,0,0}, - {21375,21381,20657 ,11496,11509,11515 ,0,0,0}, {21374,21375,20605 ,11493,11496,11514 ,0,0,0}, - {20458,20658,21381 ,11511,11510,11509 ,0,0,0}, {20657,21381,20658 ,11515,11509,11510 ,0,0,0}, - {20463,21373,20465 ,730,730,730 ,0,0,0}, {20460,21375,20462 ,730,730,730 ,0,0,0}, - {20468,21377,21376 ,730,730,730 ,0,0,0}, {21380,21376,21379 ,730,730,730 ,0,0,0}, - {21378,21380,21379 ,730,730,730 ,0,0,0}, {20465,21377,20468 ,730,730,730 ,0,0,0}, - {20468,21376,21380 ,730,730,730 ,0,0,0}, {20465,21373,21377 ,730,730,730 ,0,0,0}, - {20463,21374,21373 ,730,730,730 ,0,0,0}, {20463,20462,21375 ,730,730,730 ,0,0,0}, - {21375,21374,20463 ,730,730,730 ,0,0,0}, {21381,21375,20460 ,730,730,730 ,0,0,0}, - {21381,20448,20458 ,730,730,730 ,0,0,0}, {20448,21381,20460 ,730,730,730 ,0,0,0}, - {20458,20448,20451 ,730,730,730 ,0,0,0}, {20454,20452,20455 ,730,730,730 ,0,0,0}, - {20451,20452,20454 ,730,730,730 ,0,0,0}, {20454,20458,20451 ,730,730,730 ,0,0,0} -// X-Ufo 8ZollPropeller.prt - , {21382,21383,21384 ,8352,8353,8354 ,0,0,0}, {21382,21385,21386 ,8352,8355,8356 ,0,0,0}, - {21386,21383,21382 ,8356,8353,8352 ,0,0,0}, {21387,21385,21388 ,8357,8355,8358 ,0,0,0}, - {21385,21387,21386 ,8355,8357,8356 ,0,0,0}, {21389,21390,21391 ,8359,8360,8361 ,0,0,0}, - {21387,21388,21390 ,8357,8358,8360 ,0,0,0}, {21392,21393,21389 ,8362,3877,8359 ,0,0,0}, - {21392,21394,21393 ,8362,4346,3877 ,0,0,0}, {21392,21389,21391 ,8362,8359,8361 ,0,0,0}, - {21390,21388,21391 ,8360,8358,8361 ,0,0,0}, {21395,21384,21383 ,8363,8354,8353 ,0,0,0}, - {21396,21395,21397 ,8364,8363,8365 ,0,0,0}, {21395,21396,21384 ,8363,8364,8354 ,0,0,0}, - {21398,21399,21397 ,8366,8367,8365 ,0,0,0}, {21396,21397,21399 ,8364,8365,8367 ,0,0,0}, - {21398,21400,21401 ,8366,8368,8369 ,0,0,0}, {21401,21399,21398 ,8369,8367,8366 ,0,0,0}, - {21402,21400,21403 ,8370,8368,8371 ,0,0,0}, {21400,21402,21401 ,8368,8370,8369 ,0,0,0}, - {21402,21403,21404 ,8370,8371,8372 ,0,0,0}, {21405,21406,21407 ,8357,8373,8374 ,0,0,0}, - {21405,21408,21406 ,8357,8356,8373 ,0,0,0}, {21405,21407,21409 ,8357,8374,8360 ,0,0,0}, - {21409,21410,21411 ,8360,8375,8359 ,0,0,0}, {21410,21409,21407 ,8375,8360,8374 ,0,0,0}, - {21412,21411,21410 ,8376,8359,8375 ,0,0,0}, {21413,21406,21408 ,8377,8373,8356 ,0,0,0}, - {21412,21414,21415 ,8376,81,5000 ,0,0,0}, {21415,21411,21412 ,5000,8359,8376 ,0,0,0}, - {21413,21408,21416 ,8377,8356,8378 ,0,0,0}, {21416,21417,21413 ,8378,8379,8377 ,0,0,0}, - {21418,21417,21419 ,8380,8379,8363 ,0,0,0}, {21416,21419,21417 ,8378,8363,8379 ,0,0,0}, - {21420,21421,21418 ,8365,8381,8380 ,0,0,0}, {21418,21419,21420 ,8380,8363,8365 ,0,0,0}, - {21422,21423,21421 ,8366,8368,8381 ,0,0,0}, {21422,21421,21420 ,8366,8381,8365 ,0,0,0}, - {21424,21423,21425 ,8382,8368,8383 ,0,0,0}, {21423,21424,21421 ,8368,8382,8381 ,0,0,0}, - {21424,21425,21426 ,8382,8383,8384 ,0,0,0}, {21427,21428,15792 ,8385,8386,8387 ,0,0,0}, - {21429,21430,21431 ,8388,8389,8390 ,0,0,0}, {21432,21427,15792 ,8391,8385,8387 ,0,0,0}, - {21429,21431,21433 ,8388,8390,8392 ,0,0,0}, {21430,21429,21432 ,8389,8388,8391 ,0,0,0}, - {21430,21432,15792 ,8389,8391,8387 ,0,0,0}, {21434,21435,21436 ,8393,878,8394 ,0,0,0}, - {21436,21433,21437 ,8394,8392,8395 ,0,0,0}, {21434,21436,21437 ,8393,8394,8395 ,0,0,0}, - {21435,21434,21438 ,878,8393,8396 ,0,0,0}, {21437,21433,21431 ,8395,8392,8390 ,0,0,0}, - {21427,21439,21428 ,8385,8363,8386 ,0,0,0}, {21440,21439,21441 ,8397,8363,8398 ,0,0,0}, - {21439,21440,21428 ,8363,8397,8386 ,0,0,0}, {21442,21443,21441 ,8399,8400,8398 ,0,0,0}, - {21440,21441,21443 ,8397,8398,8400 ,0,0,0}, {21442,21444,21445 ,8399,8401,8402 ,0,0,0}, - {21445,21443,21442 ,8402,8400,8399 ,0,0,0}, {21446,21444,21447 ,8403,8401,126 ,0,0,0}, - {21444,21446,21445 ,8401,8403,8402 ,0,0,0}, {21448,21449,21450 ,8404,8405,8406 ,0,0,0}, - {21450,21449,21451 ,8406,8405,8407 ,0,0,0}, {21452,21449,21448 ,8408,8405,8404 ,0,0,0}, - {21453,21450,21451 ,8409,8406,8407 ,0,0,0}, {21452,21448,21454 ,8408,8404,8410 ,0,0,0}, - {21454,21455,21456 ,8410,8411,8412 ,0,0,0}, {21455,21454,21448 ,8411,8410,8404 ,0,0,0}, - {21453,21451,21457 ,8409,8407,8413 ,0,0,0}, {21458,21459,21456 ,8414,8415,8412 ,0,0,0}, - {21456,21455,21458 ,8412,8411,8414 ,0,0,0}, {21459,21460,21461 ,8415,5000,4114 ,0,0,0}, - {21462,21459,21458 ,8416,8415,8414 ,0,0,0}, {21462,21460,21459 ,8416,5000,8415 ,0,0,0}, - {21451,21463,21457 ,8407,8417,8413 ,0,0,0}, {21463,21464,21465 ,8417,8418,8419 ,0,0,0}, - {21465,21457,21463 ,8419,8413,8417 ,0,0,0}, {21466,21464,21467 ,8420,8418,8421 ,0,0,0}, - {21464,21466,21465 ,8418,8420,8419 ,0,0,0}, {21468,21469,21467 ,8422,8423,8421 ,0,0,0}, - {21466,21467,21469 ,8420,8421,8423 ,0,0,0}, {21468,21470,21471 ,8422,8424,8425 ,0,0,0}, - {21471,21469,21468 ,8425,8423,8422 ,0,0,0}, {21472,21470,21473 ,8426,8424,8427 ,0,0,0}, - {21470,21472,21471 ,8424,8426,8425 ,0,0,0}, {21472,21473,21474 ,8426,8427,8428 ,0,0,0}, - {21474,21473,21475 ,8428,8427,8429 ,0,0,0}, {21476,21477,21478 ,8430,8431,8432 ,0,0,0}, - {21479,21480,21481 ,8433,8434,8435 ,0,0,0}, {21482,21483,21484 ,8436,8437,8438 ,0,0,0}, - {21485,21486,21487 ,8439,8440,8441 ,0,0,0}, {21488,21489,21490 ,8442,8443,8444 ,0,0,0}, - {21490,21404,21488 ,8444,8445,8442 ,0,0,0}, {21491,21492,21493 ,8446,8447,8448 ,0,0,0}, - {21469,21494,21466 ,8449,8450,8451 ,0,0,0}, {21495,21493,21496 ,8452,8448,8453 ,0,0,0}, - {21497,21498,21499 ,8454,8455,8456 ,0,0,0}, {21500,21501,21502 ,8457,8458,8459 ,0,0,0}, - {21503,21504,21505 ,8460,8461,8462 ,0,0,0}, {21506,21494,21499 ,8463,8450,8456 ,0,0,0}, - {21507,21418,21421 ,8464,8465,8466 ,0,0,0}, {21508,21509,21505 ,8467,8468,8462 ,0,0,0}, - {21510,21511,21512 ,8469,8470,8471 ,0,0,0}, {21513,21514,21510 ,8472,8473,8469 ,0,0,0}, - {21515,21516,21513 ,8474,8475,8472 ,0,0,0}, {21517,21513,21516 ,8476,8472,8475 ,0,0,0}, - {21518,21516,21515 ,8477,8475,8474 ,0,0,0}, {21519,21520,21521 ,8478,8479,8480 ,0,0,0}, - {21522,21507,21511 ,8481,8464,8470 ,0,0,0}, {21523,21524,21519 ,8482,8483,8478 ,0,0,0}, - {21472,21474,21499 ,8484,8485,8456 ,0,0,0}, {21501,21525,21502 ,8458,8486,8459 ,0,0,0}, - {21492,21526,21493 ,8447,8487,8448 ,0,0,0}, {21527,21528,21529 ,8488,8489,8490 ,0,0,0}, - {21450,21530,21448 ,8491,8492,8493 ,0,0,0}, {21487,21526,21531 ,8441,8487,8494 ,0,0,0}, - {21532,21401,21533 ,8495,8496,8497 ,0,0,0}, {21534,21535,21485 ,8498,8499,8439 ,0,0,0}, - {21480,21536,21537 ,8434,8500,8501 ,0,0,0}, {21538,21539,21540 ,8502,8503,8504 ,0,0,0}, - {21479,21481,21541 ,8433,8435,8505 ,0,0,0}, {21477,21476,21542 ,8431,8430,8506 ,0,0,0}, - {21543,21481,21538 ,8507,8435,8502 ,0,0,0}, {21544,21545,21546 ,8508,8509,8510 ,0,0,0}, - {21545,21542,21476 ,8509,8506,8430 ,0,0,0}, {21384,21547,21382 ,8511,8512,8513 ,0,0,0}, - {21548,21478,21549 ,8514,8432,8515 ,0,0,0}, {21479,21550,21551 ,8433,8516,8517 ,0,0,0}, - {21535,21460,21552 ,8499,8518,8519 ,0,0,0}, {21538,21481,21480 ,8502,8435,8434 ,0,0,0}, - {21538,21537,21553 ,8502,8501,8520 ,0,0,0}, {21480,21537,21538 ,8434,8501,8502 ,0,0,0}, - {21554,21555,21483 ,8521,8522,8437 ,0,0,0}, {21543,21482,21556 ,8507,8436,8523 ,0,0,0}, - {21478,21392,21391 ,8432,8524,8525 ,0,0,0}, {21557,21555,21554 ,8526,8522,8521 ,0,0,0}, - {21477,21557,21554 ,8431,8526,8521 ,0,0,0}, {21545,21476,21546 ,8509,8430,8510 ,0,0,0}, - {21542,21557,21477 ,8506,8526,8431 ,0,0,0}, {21549,21478,21391 ,8515,8432,8525 ,0,0,0}, - {21478,21548,21558 ,8432,8514,8527 ,0,0,0}, {21547,21549,21382 ,8512,8515,8513 ,0,0,0}, - {21549,21547,21548 ,8515,8512,8514 ,0,0,0}, {21396,21532,21384 ,8528,8495,8511 ,0,0,0}, - {21401,21532,21399 ,8496,8495,8529 ,0,0,0}, {21532,21547,21384 ,8495,8512,8511 ,0,0,0}, - {21533,21559,21532 ,8497,8530,8495 ,0,0,0}, {21402,21533,21401 ,8531,8497,8496 ,0,0,0}, - {21533,21404,21490 ,8497,8445,8444 ,0,0,0}, {21453,21560,21530 ,8532,8533,8492 ,0,0,0}, - {21561,21496,21493 ,8534,8453,8448 ,0,0,0}, {21501,21562,21563 ,8458,8535,8536 ,0,0,0}, - {21412,21562,21414 ,8537,8535,8538 ,0,0,0}, {21561,21564,21565 ,8534,8539,8540 ,0,0,0}, - {21495,21491,21493 ,8452,8446,8448 ,0,0,0}, {21450,21453,21530 ,8491,8532,8492 ,0,0,0}, - {21492,21566,21526 ,8447,8541,8487 ,0,0,0}, {21493,21526,21567 ,8448,8487,8542 ,0,0,0}, - {21526,21487,21486 ,8487,8441,8440 ,0,0,0}, {21535,21486,21485 ,8499,8440,8439 ,0,0,0}, - {21526,21486,21568 ,8487,8440,8543 ,0,0,0}, {21569,21552,21527 ,8544,8519,8488 ,0,0,0}, - {21535,21570,21486 ,8499,8545,8440 ,0,0,0}, {21480,21551,21490 ,8434,8517,8444 ,0,0,0}, - {21550,21570,21569 ,8516,8545,8544 ,0,0,0}, {21529,21533,21490 ,8490,8497,8444 ,0,0,0}, - {21490,21489,21480 ,8444,8443,8434 ,0,0,0}, {21529,21571,21533 ,8490,8546,8497 ,0,0,0}, - {21572,21529,21528 ,8547,8490,8489 ,0,0,0}, {21530,21573,21528 ,8492,8548,8489 ,0,0,0}, - {21530,21560,21574 ,8492,8533,8549 ,0,0,0}, {21453,21457,21560 ,8532,8550,8533 ,0,0,0}, - {21457,21465,21560 ,8550,8551,8533 ,0,0,0}, {21560,21494,21575 ,8533,8450,8552 ,0,0,0}, - {21469,21499,21494 ,8449,8456,8450 ,0,0,0}, {21471,21499,21469 ,8553,8456,8449 ,0,0,0}, - {21499,21471,21472 ,8456,8553,8484 ,0,0,0}, {21560,21466,21494 ,8533,8451,8450 ,0,0,0}, - {21474,21497,21499 ,8485,8454,8456 ,0,0,0}, {21576,21562,21577 ,8554,8535,8555 ,0,0,0}, - {21524,21523,21578 ,8483,8482,8556 ,0,0,0}, {21579,21510,21519 ,8557,8469,8478 ,0,0,0}, - {21519,21510,21580 ,8478,8469,8558 ,0,0,0}, {21580,21520,21519 ,8558,8479,8478 ,0,0,0}, - {21519,21524,21579 ,8478,8483,8557 ,0,0,0}, {21581,21506,21498 ,8559,8463,8455 ,0,0,0}, - {21525,21524,21578 ,8486,8483,8556 ,0,0,0}, {21525,21578,21582 ,8486,8556,8560 ,0,0,0}, - {21502,21525,21583 ,8459,8486,8561 ,0,0,0}, {21500,21414,21501 ,8457,8538,8458 ,0,0,0}, - {21584,21561,21563 ,8562,8534,8536 ,0,0,0}, {21562,21501,21414 ,8535,8458,8538 ,0,0,0}, - {21497,21474,21585 ,8454,8485,8563 ,0,0,0}, {21496,21497,21586 ,8453,8454,8564 ,0,0,0}, - {21576,21498,21584 ,8554,8455,8562 ,0,0,0}, {21576,21587,21581 ,8554,8565,8559 ,0,0,0}, - {21588,21417,21418 ,8566,8567,8465 ,0,0,0}, {21588,21413,21417 ,8566,8568,8567 ,0,0,0}, - {21589,21588,21509 ,8569,8566,8468 ,0,0,0}, {21587,21577,21589 ,8565,8555,8569 ,0,0,0}, - {21418,21507,21588 ,8465,8464,8566 ,0,0,0}, {21426,21512,21511 ,8570,8471,8470 ,0,0,0}, - {21554,21590,21477 ,8521,8571,8431 ,0,0,0}, {21484,21483,21555 ,8438,8437,8522 ,0,0,0}, - {21543,21591,21483 ,8507,8572,8437 ,0,0,0}, {21394,21392,21590 ,8573,8524,8571 ,0,0,0}, - {21591,21590,21554 ,8572,8571,8521 ,0,0,0}, {21590,21392,21478 ,8571,8524,8432 ,0,0,0}, - {21477,21590,21478 ,8431,8571,8432 ,0,0,0}, {21558,21546,21476 ,8527,8510,8430 ,0,0,0}, - {21482,21543,21483 ,8436,8507,8437 ,0,0,0}, {21556,21541,21481 ,8523,8505,8435 ,0,0,0}, - {21590,21592,21593 ,8571,8574,8575 ,0,0,0}, {21483,21591,21554 ,8437,8572,8521 ,0,0,0}, - {21540,21591,21538 ,8504,8572,8502 ,0,0,0}, {21394,21590,21593 ,8573,8571,8575 ,0,0,0}, - {21391,21388,21549 ,8525,8576,8515 ,0,0,0}, {21558,21476,21478 ,8527,8430,8432 ,0,0,0}, - {21556,21481,21543 ,8523,8435,8507 ,0,0,0}, {21541,21594,21479 ,8505,8577,8433 ,0,0,0}, - {21539,21538,21553 ,8503,8502,8520 ,0,0,0}, {21543,21538,21591 ,8507,8502,8572 ,0,0,0}, - {21592,21591,21540 ,8574,8572,8504 ,0,0,0}, {21591,21592,21590 ,8572,8574,8571 ,0,0,0}, - {21388,21385,21549 ,8576,8578,8515 ,0,0,0}, {21549,21385,21382 ,8515,8578,8513 ,0,0,0}, - {21595,21550,21594 ,8579,8516,8577 ,0,0,0}, {21595,21596,21570 ,8579,8580,8545 ,0,0,0}, - {21536,21480,21597 ,8500,8434,8581 ,0,0,0}, {21489,21597,21480 ,8443,8581,8434 ,0,0,0}, - {21547,21532,21559 ,8512,8495,8530 ,0,0,0}, {21396,21399,21532 ,8528,8529,8495 ,0,0,0}, - {21550,21479,21594 ,8516,8433,8577 ,0,0,0}, {21598,21460,21535 ,8582,8518,8499 ,0,0,0}, - {21490,21551,21527 ,8444,8517,8488 ,0,0,0}, {21479,21551,21480 ,8433,8517,8434 ,0,0,0}, - {21527,21551,21569 ,8488,8517,8544 ,0,0,0}, {21404,21533,21402 ,8445,8497,8531 ,0,0,0}, - {21490,21527,21529 ,8444,8488,8490 ,0,0,0}, {21533,21571,21559 ,8497,8546,8530 ,0,0,0}, - {21595,21570,21550 ,8579,8545,8516 ,0,0,0}, {21599,21570,21596 ,8583,8545,8580 ,0,0,0}, - {21460,21462,21552 ,8518,8584,8519 ,0,0,0}, {21550,21569,21551 ,8516,8544,8517 ,0,0,0}, - {21535,21552,21569 ,8499,8519,8544 ,0,0,0}, {21448,21530,21455 ,8493,8492,8585 ,0,0,0}, - {21528,21527,21552 ,8489,8488,8519 ,0,0,0}, {21571,21529,21572 ,8546,8490,8547 ,0,0,0}, - {21570,21599,21486 ,8545,8583,8440 ,0,0,0}, {21568,21486,21599 ,8543,8440,8583 ,0,0,0}, - {21598,21535,21534 ,8582,8499,8498 ,0,0,0}, {21570,21535,21569 ,8545,8499,8544 ,0,0,0}, - {21462,21458,21552 ,8584,8586,8519 ,0,0,0}, {21552,21458,21455 ,8519,8586,8585 ,0,0,0}, - {21455,21528,21552 ,8585,8489,8519 ,0,0,0}, {21572,21528,21573 ,8547,8489,8548 ,0,0,0}, - {21526,21568,21567 ,8487,8543,8542 ,0,0,0}, {21566,21531,21526 ,8541,8494,8487 ,0,0,0}, - {21573,21530,21574 ,8548,8492,8549 ,0,0,0}, {21455,21530,21528 ,8585,8492,8489 ,0,0,0}, - {21567,21564,21493 ,8542,8539,8448 ,0,0,0}, {21493,21564,21561 ,8448,8539,8534 ,0,0,0}, - {21466,21560,21465 ,8451,8533,8551 ,0,0,0}, {21560,21575,21574 ,8533,8552,8549 ,0,0,0}, - {21561,21497,21496 ,8534,8454,8453 ,0,0,0}, {21565,21600,21563 ,8540,8587,8536 ,0,0,0}, - {21410,21562,21412 ,8588,8535,8537 ,0,0,0}, {21586,21497,21585 ,8564,8454,8563 ,0,0,0}, - {21584,21497,21561 ,8562,8454,8534 ,0,0,0}, {21601,21494,21506 ,8589,8450,8463 ,0,0,0}, - {21499,21498,21506 ,8456,8455,8463 ,0,0,0}, {21575,21494,21601 ,8552,8450,8589 ,0,0,0}, - {21565,21563,21561 ,8540,8536,8534 ,0,0,0}, {21600,21602,21501 ,8587,8590,8458 ,0,0,0}, - {21406,21577,21407 ,8591,8555,8592 ,0,0,0}, {21497,21584,21498 ,8454,8562,8455 ,0,0,0}, - {21584,21563,21562 ,8562,8536,8535 ,0,0,0}, {21506,21603,21604 ,8463,8593,8594 ,0,0,0}, - {21498,21576,21581 ,8455,8554,8559 ,0,0,0}, {21601,21506,21604 ,8589,8463,8594 ,0,0,0}, - {21600,21501,21563 ,8587,8458,8536 ,0,0,0}, {21602,21525,21501 ,8590,8486,8458 ,0,0,0}, - {21577,21410,21407 ,8555,8588,8592 ,0,0,0}, {21584,21562,21576 ,8562,8535,8554 ,0,0,0}, - {21562,21410,21577 ,8535,8588,8555 ,0,0,0}, {21581,21605,21603 ,8559,8595,8593 ,0,0,0}, - {21576,21577,21587 ,8554,8555,8565 ,0,0,0}, {21603,21506,21581 ,8593,8463,8559 ,0,0,0}, - {21524,21525,21602 ,8483,8486,8590 ,0,0,0}, {21582,21583,21525 ,8560,8561,8486 ,0,0,0}, - {21588,21406,21413 ,8566,8591,8568 ,0,0,0}, {21587,21606,21605 ,8565,8596,8595 ,0,0,0}, - {21577,21588,21589 ,8555,8566,8569 ,0,0,0}, {21605,21581,21587 ,8595,8559,8565 ,0,0,0}, - {21519,21521,21523 ,8478,8480,8482 ,0,0,0}, {21579,21607,21510 ,8557,8597,8469 ,0,0,0}, - {21421,21424,21511 ,8466,8598,8470 ,0,0,0}, {21421,21511,21507 ,8466,8470,8464 ,0,0,0}, - {21589,21508,21606 ,8569,8467,8596 ,0,0,0}, {21588,21577,21406 ,8566,8555,8591 ,0,0,0}, - {21588,21507,21509 ,8566,8464,8468 ,0,0,0}, {21606,21587,21589 ,8596,8565,8569 ,0,0,0}, - {21510,21512,21580 ,8469,8471,8558 ,0,0,0}, {21607,21515,21513 ,8597,8474,8472 ,0,0,0}, - {21608,21504,21503 ,8599,8461,8460 ,0,0,0}, {21426,21511,21424 ,8570,8470,8598 ,0,0,0}, - {21511,21514,21522 ,8470,8473,8481 ,0,0,0}, {21503,21509,21507 ,8460,8468,8464 ,0,0,0}, - {21522,21503,21507 ,8481,8460,8464 ,0,0,0}, {21508,21589,21509 ,8467,8569,8468 ,0,0,0}, - {21607,21513,21510 ,8597,8472,8469 ,0,0,0}, {21510,21514,21511 ,8469,8473,8470 ,0,0,0}, - {21517,21609,21514 ,8476,8600,8473 ,0,0,0}, {21513,21517,21514 ,8472,8476,8473 ,0,0,0}, - {21609,21608,21522 ,8600,8599,8481 ,0,0,0}, {21514,21609,21522 ,8473,8600,8481 ,0,0,0}, - {21608,21503,21522 ,8599,8460,8481 ,0,0,0}, {21505,21509,21503 ,8462,8468,8460 ,0,0,0}, - {21610,21611,21612 ,8601,8602,8603 ,0,0,0}, {21613,21614,21611 ,8604,8605,8602 ,0,0,0}, - {21615,21616,21617 ,8606,8607,8608 ,0,0,0}, {21618,21619,21620 ,8609,8610,8611 ,0,0,0}, - {21621,21622,21623 ,8612,8613,8614 ,0,0,0}, {21624,21625,21626 ,8615,8616,8617 ,0,0,0}, - {21627,21628,21629 ,8618,8619,8620 ,0,0,0}, {21630,21631,21632 ,8621,8622,8623 ,0,0,0}, - {21633,21634,21635 ,8624,8625,8626 ,0,0,0}, {21636,21637,21638 ,8627,8628,8629 ,0,0,0}, - {21639,21640,21633 ,8630,8631,8624 ,0,0,0}, {21633,21635,21639 ,8624,8626,8630 ,0,0,0}, - {21640,21641,21642 ,8631,8632,8633 ,0,0,0}, {21641,21640,21639 ,8632,8631,8630 ,0,0,0}, - {21643,21642,21644 ,8634,8633,8635 ,0,0,0}, {21641,21644,21642 ,8632,8635,8633 ,0,0,0}, - {21645,21646,21643 ,8636,8637,8634 ,0,0,0}, {21643,21644,21645 ,8634,8635,8636 ,0,0,0}, - {21647,21646,21645 ,8638,8637,8636 ,0,0,0}, {21634,21638,21635 ,8625,8629,8626 ,0,0,0}, - {21636,21628,21637 ,8627,8619,8628 ,0,0,0}, {21634,21636,21638 ,8625,8627,8629 ,0,0,0}, - {21627,21629,21630 ,8618,8620,8621 ,0,0,0}, {21637,21628,21627 ,8628,8619,8618 ,0,0,0}, - {21632,21631,21623 ,8623,8622,8614 ,0,0,0}, {21630,21629,21631 ,8621,8620,8622 ,0,0,0}, - {21625,21622,21621 ,8616,8613,8612 ,0,0,0}, {21622,21632,21623 ,8613,8623,8614 ,0,0,0}, - {21648,21624,21626 ,8639,8615,8617 ,0,0,0}, {21626,21625,21621 ,8617,8616,8612 ,0,0,0}, - {21615,21648,21616 ,8606,8639,8607 ,0,0,0}, {21648,21615,21624 ,8639,8606,8615 ,0,0,0}, - {21617,21618,21620 ,8608,8609,8611 ,0,0,0}, {21616,21618,21617 ,8607,8609,8608 ,0,0,0}, - {21613,21619,21614 ,8604,8610,8605 ,0,0,0}, {21620,21619,21613 ,8611,8610,8604 ,0,0,0}, - {21612,21649,21610 ,8603,8640,8601 ,0,0,0}, {21611,21614,21612 ,8602,8605,8603 ,0,0,0}, - {21650,21651,21611 ,8641,8642,8643 ,0,0,0}, {21652,21613,21651 ,8644,8645,8642 ,0,0,0}, - {21624,21615,21653 ,8646,8647,8648 ,0,0,0}, {21617,21620,21654 ,8649,8650,8651 ,0,0,0}, - {21622,21655,21632 ,8652,8653,8654 ,0,0,0}, {21656,21657,21625 ,8655,8656,8657 ,0,0,0}, - {21658,21637,21627 ,8658,8659,8660 ,0,0,0}, {21659,21630,21660 ,8661,8662,8663 ,0,0,0}, - {21639,21635,21661 ,8664,8665,8666 ,0,0,0}, {21638,21662,21663 ,8667,8668,8669 ,0,0,0}, - {21664,21641,21639 ,8670,8671,8664 ,0,0,0}, {21639,21661,21664 ,8664,8666,8670 ,0,0,0}, - {21641,21665,21644 ,8671,8672,8673 ,0,0,0}, {21665,21641,21664 ,8672,8671,8670 ,0,0,0}, - {21645,21644,21666 ,8674,8673,8675 ,0,0,0}, {21665,21666,21644 ,8672,8675,8673 ,0,0,0}, - {21667,21647,21645 ,8676,8638,8674 ,0,0,0}, {21645,21666,21667 ,8674,8675,8676 ,0,0,0}, - {21668,21647,21667 ,8677,8638,8676 ,0,0,0}, {21635,21663,21661 ,8665,8669,8666 ,0,0,0}, - {21638,21637,21662 ,8667,8659,8668 ,0,0,0}, {21635,21638,21663 ,8665,8667,8669 ,0,0,0}, - {21658,21627,21659 ,8658,8660,8661 ,0,0,0}, {21662,21637,21658 ,8668,8659,8658 ,0,0,0}, - {21660,21630,21632 ,8663,8662,8654 ,0,0,0}, {21659,21627,21630 ,8661,8660,8662 ,0,0,0}, - {21657,21655,21622 ,8656,8653,8652 ,0,0,0}, {21655,21660,21632 ,8653,8663,8654 ,0,0,0}, - {21624,21656,21625 ,8646,8655,8657 ,0,0,0}, {21625,21657,21622 ,8657,8656,8652 ,0,0,0}, - {21615,21669,21653 ,8647,8678,8648 ,0,0,0}, {21624,21653,21656 ,8646,8648,8655 ,0,0,0}, - {21654,21669,21617 ,8651,8678,8649 ,0,0,0}, {21615,21617,21669 ,8647,8649,8678 ,0,0,0}, - {21652,21620,21613 ,8644,8650,8645 ,0,0,0}, {21654,21620,21652 ,8651,8650,8644 ,0,0,0}, - {21611,21610,21650 ,8643,8601,8641 ,0,0,0}, {21651,21613,21611 ,8642,8645,8643 ,0,0,0}, - {21670,21671,21651 ,8679,8680,8681 ,0,0,0}, {21654,21652,21672 ,8651,8644,8682 ,0,0,0}, - {21656,21653,21673 ,8683,8684,8685 ,0,0,0}, {21669,21674,21675 ,8678,8686,8687 ,0,0,0}, - {21655,21676,21660 ,8688,8689,8690 ,0,0,0}, {21677,21678,21657 ,8691,8692,8693 ,0,0,0}, - {21679,21662,21680 ,8694,8695,8696 ,0,0,0}, {21658,21659,21681 ,8697,8698,8699 ,0,0,0}, - {21664,21661,21682 ,8700,8701,8702 ,0,0,0}, {21663,21683,21661 ,8703,8704,8701 ,0,0,0}, - {21684,21665,21664 ,8705,8706,8700 ,0,0,0}, {21664,21682,21684 ,8700,8702,8705 ,0,0,0}, - {21665,21685,21666 ,8706,8707,8675 ,0,0,0}, {21685,21665,21684 ,8707,8706,8705 ,0,0,0}, - {21667,21666,21686 ,8708,8675,8709 ,0,0,0}, {21685,21686,21666 ,8707,8709,8675 ,0,0,0}, - {21686,21687,21668 ,8709,8710,8677 ,0,0,0}, {21668,21667,21686 ,8677,8708,8709 ,0,0,0}, - {21682,21661,21683 ,8702,8701,8704 ,0,0,0}, {21663,21662,21679 ,8703,8695,8694 ,0,0,0}, - {21663,21679,21683 ,8703,8694,8704 ,0,0,0}, {21680,21658,21681 ,8696,8697,8699 ,0,0,0}, - {21662,21658,21680 ,8695,8697,8696 ,0,0,0}, {21688,21659,21660 ,8711,8698,8690 ,0,0,0}, - {21681,21659,21688 ,8699,8698,8711 ,0,0,0}, {21678,21676,21655 ,8692,8689,8688 ,0,0,0}, - {21676,21688,21660 ,8689,8711,8690 ,0,0,0}, {21656,21677,21657 ,8683,8691,8693 ,0,0,0}, - {21657,21678,21655 ,8693,8692,8688 ,0,0,0}, {21653,21675,21673 ,8684,8687,8685 ,0,0,0}, - {21656,21673,21677 ,8683,8685,8691 ,0,0,0}, {21669,21654,21674 ,8678,8651,8686 ,0,0,0}, - {21653,21669,21675 ,8684,8678,8687 ,0,0,0}, {21672,21652,21671 ,8682,8644,8680 ,0,0,0}, - {21674,21654,21672 ,8686,8651,8682 ,0,0,0}, {21670,21651,21650 ,8679,8681,8641 ,0,0,0}, - {21671,21652,21651 ,8680,8644,8681 ,0,0,0}, {21689,21690,21671 ,8712,8713,8714 ,0,0,0}, - {21674,21672,21691 ,8715,8716,8717 ,0,0,0}, {21677,21673,21692 ,8718,8719,8720 ,0,0,0}, - {21675,21674,21693 ,8721,8715,8722 ,0,0,0}, {21676,21694,21688 ,8723,8724,8725 ,0,0,0}, - {21695,21696,21678 ,8726,8727,8728 ,0,0,0}, {21697,21679,21680 ,8729,8730,8731 ,0,0,0}, - {21698,21681,21699 ,8732,8733,8734 ,0,0,0}, {21700,21682,21701 ,8735,8736,8737 ,0,0,0}, - {21683,21702,21701 ,8738,8739,8737 ,0,0,0}, {21700,21703,21684 ,8735,8740,8741 ,0,0,0}, - {21684,21682,21700 ,8741,8736,8735 ,0,0,0}, {21685,21703,21704 ,8742,8740,8743 ,0,0,0}, - {21703,21685,21684 ,8740,8742,8741 ,0,0,0}, {21705,21686,21704 ,8744,8745,8743 ,0,0,0}, - {21685,21704,21686 ,8742,8743,8745 ,0,0,0}, {21705,21706,21687 ,8744,8746,8710 ,0,0,0}, - {21687,21686,21705 ,8710,8745,8744 ,0,0,0}, {21701,21682,21683 ,8737,8736,8738 ,0,0,0}, - {21702,21679,21697 ,8739,8730,8729 ,0,0,0}, {21683,21679,21702 ,8738,8730,8739 ,0,0,0}, - {21698,21680,21681 ,8732,8731,8733 ,0,0,0}, {21697,21680,21698 ,8729,8731,8732 ,0,0,0}, - {21694,21699,21688 ,8724,8734,8725 ,0,0,0}, {21699,21681,21688 ,8734,8733,8725 ,0,0,0}, - {21678,21696,21676 ,8728,8727,8723 ,0,0,0}, {21696,21694,21676 ,8727,8724,8723 ,0,0,0}, - {21677,21692,21695 ,8718,8720,8726 ,0,0,0}, {21677,21695,21678 ,8718,8726,8728 ,0,0,0}, - {21673,21675,21707 ,8719,8721,8747 ,0,0,0}, {21673,21707,21692 ,8719,8747,8720 ,0,0,0}, - {21693,21674,21691 ,8722,8715,8717 ,0,0,0}, {21707,21675,21693 ,8747,8721,8722 ,0,0,0}, - {21690,21672,21671 ,8713,8716,8714 ,0,0,0}, {21691,21672,21690 ,8717,8716,8713 ,0,0,0}, - {21689,21671,21670 ,8712,8714,8679 ,0,0,0}, {21704,21708,21709 ,8748,8749,8750 ,0,0,0}, - {21706,21705,21710 ,8746,8751,8752 ,0,0,0}, {21711,21701,21712 ,8753,8754,8755 ,0,0,0}, - {21700,21713,21703 ,8756,8757,8758 ,0,0,0}, {21699,21714,21698 ,8759,8760,8761 ,0,0,0}, - {21697,21715,21702 ,8762,8763,8764 ,0,0,0}, {21716,21696,21695 ,8765,8766,8767 ,0,0,0}, - {21717,21694,21718 ,8768,8769,8770 ,0,0,0}, {21719,21707,21720 ,8771,8772,8773 ,0,0,0}, - {21692,21719,21721 ,8774,8771,8775 ,0,0,0}, {21722,21720,21693 ,8776,8773,8777 ,0,0,0}, - {21707,21693,21720 ,8772,8777,8773 ,0,0,0}, {21691,21723,21722 ,8778,8779,8776 ,0,0,0}, - {21722,21693,21691 ,8776,8777,8778 ,0,0,0}, {21723,21690,21724 ,8779,8780,8781 ,0,0,0}, - {21690,21723,21691 ,8780,8779,8778 ,0,0,0}, {21721,21695,21692 ,8775,8767,8774 ,0,0,0}, - {21724,21690,21689 ,8781,8780,8782 ,0,0,0}, {21719,21692,21707 ,8771,8774,8772 ,0,0,0}, - {21716,21718,21696 ,8765,8770,8766 ,0,0,0}, {21721,21716,21695 ,8775,8765,8767 ,0,0,0}, - {21694,21717,21699 ,8769,8768,8759 ,0,0,0}, {21696,21718,21694 ,8766,8770,8769 ,0,0,0}, - {21698,21714,21725 ,8761,8760,8783 ,0,0,0}, {21699,21717,21714 ,8759,8768,8760 ,0,0,0}, - {21725,21715,21697 ,8783,8763,8762 ,0,0,0}, {21697,21698,21725 ,8762,8761,8783 ,0,0,0}, - {21712,21701,21702 ,8755,8754,8764 ,0,0,0}, {21712,21702,21715 ,8755,8764,8763 ,0,0,0}, - {21711,21713,21700 ,8753,8757,8756 ,0,0,0}, {21711,21700,21701 ,8753,8756,8754 ,0,0,0}, - {21703,21708,21704 ,8758,8749,8748 ,0,0,0}, {21713,21708,21703 ,8757,8749,8758 ,0,0,0}, - {21705,21709,21710 ,8751,8750,8752 ,0,0,0}, {21704,21709,21705 ,8748,8750,8751 ,0,0,0}, - {21706,21710,21726 ,8746,8752,8784 ,0,0,0}, {21727,21728,21729 ,8785,8786,8787 ,0,0,0}, - {21730,21731,21732 ,8788,8789,8790 ,0,0,0}, {21731,21733,21734 ,8789,8791,8792 ,0,0,0}, - {21734,21732,21731 ,8792,8790,8789 ,0,0,0}, {21731,21729,21735 ,8789,8787,8793 ,0,0,0}, - {21733,21736,21734 ,8791,8794,8792 ,0,0,0}, {21737,21738,21739 ,8795,8796,8797 ,0,0,0}, - {21689,21728,21724 ,8782,8786,8798 ,0,0,0}, {21740,21741,21742 ,8799,8800,8801 ,0,0,0}, - {21720,21722,21743 ,8802,8803,8804 ,0,0,0}, {21744,21745,21746 ,8805,8806,8807 ,0,0,0}, - {21721,21747,21716 ,8808,8809,8810 ,0,0,0}, {21748,21749,21715 ,8811,8812,8813 ,0,0,0}, - {21750,21751,21746 ,8814,8815,8807 ,0,0,0}, {21752,21753,21754 ,8816,8817,8818 ,0,0,0}, - {21755,21749,21756 ,8819,8812,8820 ,0,0,0}, {21709,21753,21710 ,8821,8817,8822 ,0,0,0}, - {21710,21757,21726 ,8822,8823,8824 ,0,0,0}, {21758,21759,21754 ,8825,8826,8818 ,0,0,0}, - {21710,21753,21757 ,8822,8817,8823 ,0,0,0}, {21760,21752,21761 ,8827,8816,8828 ,0,0,0}, - {21758,21754,21708 ,8825,8818,8829 ,0,0,0}, {21758,21762,21763 ,8825,8830,8831 ,0,0,0}, - {21713,21762,21758 ,8832,8830,8825 ,0,0,0}, {21712,21749,21755 ,8833,8812,8819 ,0,0,0}, - {21762,21755,21764 ,8830,8819,8834 ,0,0,0}, {21762,21711,21755 ,8830,8835,8819 ,0,0,0}, - {21765,21748,21751 ,8836,8811,8815 ,0,0,0}, {21766,21749,21748 ,8837,8812,8811 ,0,0,0}, - {21751,21714,21717 ,8815,8838,8839 ,0,0,0}, {21751,21748,21725 ,8815,8811,8840 ,0,0,0}, - {21716,21744,21718 ,8810,8805,8841 ,0,0,0}, {21718,21746,21717 ,8841,8807,8839 ,0,0,0}, - {21740,21767,21747 ,8799,8842,8809 ,0,0,0}, {21747,21768,21744 ,8809,8843,8805 ,0,0,0}, - {21719,21720,21741 ,8844,8802,8800 ,0,0,0}, {21721,21719,21740 ,8808,8844,8799 ,0,0,0}, - {21738,21769,21743 ,8796,8845,8804 ,0,0,0}, {21742,21741,21769 ,8801,8800,8845 ,0,0,0}, - {21770,21723,21724 ,8846,8847,8798 ,0,0,0}, {21739,21722,21723 ,8797,8803,8847 ,0,0,0}, - {21771,21735,21729 ,8848,8793,8787 ,0,0,0}, {21770,21727,21737 ,8846,8785,8795 ,0,0,0}, - {21729,21728,21771 ,8787,8786,8848 ,0,0,0}, {21733,21731,21735 ,8791,8789,8793 ,0,0,0}, - {21772,21730,21732 ,8849,8788,8790 ,0,0,0}, {21773,21730,21772 ,8850,8788,8849 ,0,0,0}, - {21728,21689,21771 ,8786,8782,8848 ,0,0,0}, {21729,21730,21727 ,8787,8788,8785 ,0,0,0}, - {21724,21728,21770 ,8798,8786,8846 ,0,0,0}, {21731,21730,21729 ,8789,8788,8787 ,0,0,0}, - {21774,21773,21772 ,8851,8850,8849 ,0,0,0}, {21775,21773,21774 ,8852,8850,8851 ,0,0,0}, - {21728,21727,21770 ,8786,8785,8846 ,0,0,0}, {21727,21773,21737 ,8785,8850,8795 ,0,0,0}, - {21723,21770,21739 ,8847,8846,8797 ,0,0,0}, {21730,21773,21727 ,8788,8850,8785 ,0,0,0}, - {21776,21775,21774 ,8853,8852,8851 ,0,0,0}, {21777,21775,21776 ,8854,8852,8853 ,0,0,0}, - {21770,21737,21739 ,8846,8795,8797 ,0,0,0}, {21737,21775,21738 ,8795,8852,8796 ,0,0,0}, - {21722,21739,21743 ,8803,8797,8804 ,0,0,0}, {21773,21775,21737 ,8850,8852,8795 ,0,0,0}, - {21778,21777,21776 ,8855,8854,8853 ,0,0,0}, {21779,21777,21778 ,8856,8854,8855 ,0,0,0}, - {21739,21738,21743 ,8797,8796,8804 ,0,0,0}, {21738,21777,21769 ,8796,8854,8845 ,0,0,0}, - {21720,21743,21741 ,8802,8804,8800 ,0,0,0}, {21775,21777,21738 ,8852,8854,8796 ,0,0,0}, - {21780,21779,21778 ,8857,8856,8855 ,0,0,0}, {21781,21779,21780 ,8858,8856,8857 ,0,0,0}, - {21743,21769,21741 ,8804,8845,8800 ,0,0,0}, {21769,21779,21742 ,8845,8856,8801 ,0,0,0}, - {21719,21741,21740 ,8844,8800,8799 ,0,0,0}, {21777,21779,21769 ,8854,8856,8845 ,0,0,0}, - {21782,21781,21780 ,8859,8858,8857 ,0,0,0}, {21783,21784,21761 ,8860,8861,8828 ,0,0,0}, - {21785,21781,21782 ,8862,8858,8859 ,0,0,0}, {21742,21781,21767 ,8801,8858,8842 ,0,0,0}, - {21721,21740,21747 ,8808,8799,8809 ,0,0,0}, {21779,21781,21742 ,8856,8858,8801 ,0,0,0}, - {21786,21785,21782 ,8863,8862,8859 ,0,0,0}, {21787,21788,21785 ,8864,8865,8862 ,0,0,0}, - {21742,21767,21740 ,8801,8842,8799 ,0,0,0}, {21767,21785,21768 ,8842,8862,8843 ,0,0,0}, - {21716,21747,21744 ,8810,8809,8805 ,0,0,0}, {21781,21785,21767 ,8858,8862,8842 ,0,0,0}, - {21786,21787,21785 ,8863,8864,8862 ,0,0,0}, {21789,21790,21788 ,8866,8867,8865 ,0,0,0}, - {21767,21768,21747 ,8842,8843,8809 ,0,0,0}, {21768,21788,21745 ,8843,8865,8806 ,0,0,0}, - {21718,21744,21746 ,8841,8805,8807 ,0,0,0}, {21785,21788,21768 ,8862,8865,8843 ,0,0,0}, - {21787,21789,21788 ,8864,8866,8865 ,0,0,0}, {21791,21792,21790 ,8868,8869,8867 ,0,0,0}, - {21768,21745,21744 ,8843,8806,8805 ,0,0,0}, {21790,21750,21745 ,8867,8814,8806 ,0,0,0}, - {21717,21746,21751 ,8839,8807,8815 ,0,0,0}, {21788,21790,21745 ,8865,8867,8806 ,0,0,0}, - {21789,21791,21790 ,8866,8868,8867 ,0,0,0}, {21792,21793,21794 ,8869,8870,8871 ,0,0,0}, - {21745,21750,21746 ,8806,8814,8807 ,0,0,0}, {21792,21765,21750 ,8869,8836,8814 ,0,0,0}, - {21725,21714,21751 ,8840,8838,8815 ,0,0,0}, {21790,21792,21750 ,8867,8869,8814 ,0,0,0}, - {21791,21793,21792 ,8868,8870,8869 ,0,0,0}, {21794,21795,21796 ,8871,8872,8873 ,0,0,0}, - {21750,21765,21751 ,8814,8836,8815 ,0,0,0}, {21794,21766,21765 ,8871,8837,8836 ,0,0,0}, - {21715,21725,21748 ,8813,8840,8811 ,0,0,0}, {21792,21794,21765 ,8869,8871,8836 ,0,0,0}, - {21793,21795,21794 ,8870,8872,8871 ,0,0,0}, {21796,21797,21798 ,8873,8874,8875 ,0,0,0}, - {21765,21766,21748 ,8836,8837,8811 ,0,0,0}, {21796,21756,21766 ,8873,8820,8837 ,0,0,0}, - {21712,21715,21749 ,8833,8813,8812 ,0,0,0}, {21794,21796,21766 ,8871,8873,8837 ,0,0,0}, - {21795,21797,21796 ,8872,8874,8873 ,0,0,0}, {21798,21799,21800 ,8875,8876,8877 ,0,0,0}, - {21766,21756,21749 ,8837,8820,8812 ,0,0,0}, {21798,21764,21756 ,8875,8834,8820 ,0,0,0}, - {21711,21712,21755 ,8835,8833,8819 ,0,0,0}, {21796,21798,21756 ,8873,8875,8820 ,0,0,0}, - {21797,21799,21798 ,8874,8876,8875 ,0,0,0}, {21800,21801,21802 ,8877,8878,8879 ,0,0,0}, - {21756,21764,21755 ,8820,8834,8819 ,0,0,0}, {21800,21763,21764 ,8877,8831,8834 ,0,0,0}, - {21713,21711,21762 ,8832,8835,8830 ,0,0,0}, {21798,21800,21764 ,8875,8877,8834 ,0,0,0}, - {21799,21801,21800 ,8876,8878,8877 ,0,0,0}, {21761,21802,21783 ,8828,8879,8860 ,0,0,0}, - {21764,21763,21762 ,8834,8831,8830 ,0,0,0}, {21763,21802,21759 ,8831,8879,8826 ,0,0,0}, - {21708,21713,21758 ,8829,8832,8825 ,0,0,0}, {21800,21802,21763 ,8877,8879,8831 ,0,0,0}, - {21801,21783,21802 ,8878,8860,8879 ,0,0,0}, {21709,21754,21753 ,8821,8818,8817 ,0,0,0}, - {21763,21759,21758 ,8831,8826,8825 ,0,0,0}, {21761,21752,21759 ,8828,8816,8826 ,0,0,0}, - {21709,21708,21754 ,8821,8829,8818 ,0,0,0}, {21761,21759,21802 ,8828,8826,8879 ,0,0,0}, - {21784,21760,21761 ,8861,8827,8828 ,0,0,0}, {21803,21752,21760 ,8880,8816,8827 ,0,0,0}, - {21759,21752,21754 ,8826,8816,8818 ,0,0,0}, {21752,21803,21753 ,8816,8880,8817 ,0,0,0}, - {21757,21753,21803 ,8823,8817,8880 ,0,0,0}, {21804,21805,21734 ,8881,8882,8883 ,0,0,0}, - {21772,21732,21806 ,8884,8885,8886 ,0,0,0}, {21778,21776,21807 ,8887,8888,8889 ,0,0,0}, - {21774,21808,21809 ,8890,8891,8892 ,0,0,0}, {21810,21811,21786 ,8893,8894,8895 ,0,0,0}, - {21812,21813,21780 ,8896,8897,8898 ,0,0,0}, {21814,21791,21815 ,8899,8900,8901 ,0,0,0}, - {21789,21787,21816 ,8902,8903,8904 ,0,0,0}, {21797,21795,21817 ,8905,8906,8907 ,0,0,0}, - {21793,21818,21795 ,8908,8909,8906 ,0,0,0}, {21819,21799,21797 ,8910,8911,8905 ,0,0,0}, - {21797,21817,21819 ,8905,8907,8910 ,0,0,0}, {21799,21820,21801 ,8911,8912,8913 ,0,0,0}, - {21820,21799,21819 ,8912,8911,8910 ,0,0,0}, {21783,21801,21821 ,8914,8913,8915 ,0,0,0}, - {21820,21821,21801 ,8912,8915,8913 ,0,0,0}, {21821,21822,21784 ,8915,8916,8861 ,0,0,0}, - {21784,21783,21821 ,8861,8914,8915 ,0,0,0}, {21817,21795,21818 ,8907,8906,8909 ,0,0,0}, - {21793,21791,21814 ,8908,8900,8899 ,0,0,0}, {21793,21814,21818 ,8908,8899,8909 ,0,0,0}, - {21815,21789,21816 ,8901,8902,8904 ,0,0,0}, {21791,21789,21815 ,8900,8902,8901 ,0,0,0}, - {21811,21787,21786 ,8894,8903,8895 ,0,0,0}, {21816,21787,21811 ,8904,8903,8894 ,0,0,0}, - {21813,21810,21782 ,8897,8893,8917 ,0,0,0}, {21810,21786,21782 ,8893,8895,8917 ,0,0,0}, - {21778,21812,21780 ,8887,8896,8898 ,0,0,0}, {21780,21813,21782 ,8898,8897,8917 ,0,0,0}, - {21776,21809,21807 ,8888,8892,8889 ,0,0,0}, {21778,21807,21812 ,8887,8889,8896 ,0,0,0}, - {21774,21772,21808 ,8890,8884,8891 ,0,0,0}, {21776,21774,21809 ,8888,8890,8892 ,0,0,0}, - {21806,21732,21805 ,8886,8885,8882 ,0,0,0}, {21808,21772,21806 ,8891,8884,8886 ,0,0,0}, - {21804,21734,21736 ,8881,8883,8918 ,0,0,0}, {21805,21732,21734 ,8882,8885,8883 ,0,0,0}, - {21823,21824,21805 ,8919,8920,8921 ,0,0,0}, {21806,21805,21825 ,8922,8921,8923 ,0,0,0}, - {21807,21809,21826 ,8924,8925,8926 ,0,0,0}, {21808,21827,21828 ,8927,8928,8929 ,0,0,0}, - {21813,21829,21810 ,8930,8931,8932 ,0,0,0}, {21830,21831,21812 ,8933,8934,8935 ,0,0,0}, - {21832,21815,21816 ,8936,8937,8938 ,0,0,0}, {21833,21811,21834 ,8939,8940,8941 ,0,0,0}, - {21817,21818,21835 ,8942,8943,8944 ,0,0,0}, {21814,21836,21837 ,8945,8946,8947 ,0,0,0}, - {21838,21819,21817 ,8948,8949,8942 ,0,0,0}, {21817,21835,21838 ,8942,8944,8948 ,0,0,0}, - {21819,21839,21820 ,8949,8950,8951 ,0,0,0}, {21839,21819,21838 ,8950,8949,8948 ,0,0,0}, - {21821,21820,21840 ,8952,8951,8953 ,0,0,0}, {21839,21840,21820 ,8950,8953,8951 ,0,0,0}, - {21841,21822,21821 ,8954,8916,8952 ,0,0,0}, {21821,21840,21841 ,8952,8953,8954 ,0,0,0}, - {21842,21822,21841 ,8955,8916,8954 ,0,0,0}, {21818,21837,21835 ,8943,8947,8944 ,0,0,0}, - {21814,21815,21836 ,8945,8937,8946 ,0,0,0}, {21818,21814,21837 ,8943,8945,8947 ,0,0,0}, - {21832,21816,21833 ,8936,8938,8939 ,0,0,0}, {21836,21815,21832 ,8946,8937,8936 ,0,0,0}, - {21834,21811,21810 ,8941,8940,8932 ,0,0,0}, {21833,21816,21811 ,8939,8938,8940 ,0,0,0}, - {21831,21829,21813 ,8934,8931,8930 ,0,0,0}, {21829,21834,21810 ,8931,8941,8932 ,0,0,0}, - {21807,21830,21812 ,8924,8933,8935 ,0,0,0}, {21812,21831,21813 ,8935,8934,8930 ,0,0,0}, - {21809,21828,21826 ,8925,8929,8926 ,0,0,0}, {21807,21826,21830 ,8924,8926,8933 ,0,0,0}, - {21808,21806,21827 ,8927,8922,8928 ,0,0,0}, {21809,21808,21828 ,8925,8927,8929 ,0,0,0}, - {21825,21805,21824 ,8923,8921,8920 ,0,0,0}, {21827,21806,21825 ,8928,8922,8923 ,0,0,0}, - {21823,21805,21804 ,8919,8921,8881 ,0,0,0}, {21843,21844,21824 ,8956,8957,8958 ,0,0,0}, - {21845,21825,21844 ,8959,8923,8957 ,0,0,0}, {21830,21826,21846 ,8960,8961,8962 ,0,0,0}, - {21828,21827,21847 ,8929,8928,8963 ,0,0,0}, {21829,21848,21834 ,8964,8965,8966 ,0,0,0}, - {21849,21850,21831 ,8967,8968,8969 ,0,0,0}, {21851,21836,21832 ,8970,8971,8972 ,0,0,0}, - {21852,21833,21853 ,8973,8974,8975 ,0,0,0}, {21838,21835,21854 ,8948,8944,8976 ,0,0,0}, - {21837,21855,21856 ,8977,8978,8979 ,0,0,0}, {21857,21839,21838 ,8980,8950,8948 ,0,0,0}, - {21838,21854,21857 ,8948,8976,8980 ,0,0,0}, {21839,21858,21840 ,8950,8981,8953 ,0,0,0}, - {21858,21839,21857 ,8981,8950,8980 ,0,0,0}, {21841,21840,21859 ,8982,8953,8983 ,0,0,0}, - {21858,21859,21840 ,8981,8983,8953 ,0,0,0}, {21860,21842,21841 ,8984,8955,8982 ,0,0,0}, - {21841,21859,21860 ,8982,8983,8984 ,0,0,0}, {21861,21842,21860 ,8985,8955,8984 ,0,0,0}, - {21835,21856,21854 ,8944,8979,8976 ,0,0,0}, {21837,21836,21855 ,8977,8971,8978 ,0,0,0}, - {21835,21837,21856 ,8944,8977,8979 ,0,0,0}, {21851,21832,21852 ,8970,8972,8973 ,0,0,0}, - {21855,21836,21851 ,8978,8971,8970 ,0,0,0}, {21853,21833,21834 ,8975,8974,8966 ,0,0,0}, - {21852,21832,21833 ,8973,8972,8974 ,0,0,0}, {21850,21848,21829 ,8968,8965,8964 ,0,0,0}, - {21848,21853,21834 ,8965,8975,8966 ,0,0,0}, {21830,21849,21831 ,8960,8967,8969 ,0,0,0}, - {21831,21850,21829 ,8969,8968,8964 ,0,0,0}, {21826,21862,21846 ,8961,8986,8962 ,0,0,0}, - {21830,21846,21849 ,8960,8962,8967 ,0,0,0}, {21847,21862,21828 ,8963,8986,8929 ,0,0,0}, - {21826,21828,21862 ,8961,8929,8986 ,0,0,0}, {21845,21827,21825 ,8959,8928,8923 ,0,0,0}, - {21847,21827,21845 ,8963,8928,8959 ,0,0,0}, {21824,21823,21843 ,8958,8919,8956 ,0,0,0}, - {21844,21825,21824 ,8957,8923,8958 ,0,0,0}, {21863,21864,21844 ,8987,8988,8989 ,0,0,0}, - {21865,21845,21864 ,8990,8991,8988 ,0,0,0}, {21849,21846,21866 ,8992,8993,8994 ,0,0,0}, - {21862,21847,21867 ,8995,8996,8997 ,0,0,0}, {21848,21868,21853 ,8998,8999,9000 ,0,0,0}, - {21869,21870,21850 ,9001,9002,9003 ,0,0,0}, {21871,21855,21851 ,9004,9005,9006 ,0,0,0}, - {21872,21852,21873 ,9007,9008,9009 ,0,0,0}, {21874,21854,21875 ,9010,9011,9012 ,0,0,0}, - {21856,21855,21876 ,9013,9005,9014 ,0,0,0}, {21877,21858,21857 ,9015,9016,9017 ,0,0,0}, - {21857,21874,21877 ,9017,9010,9015 ,0,0,0}, {21858,21878,21859 ,9016,9018,9019 ,0,0,0}, - {21878,21858,21877 ,9018,9016,9015 ,0,0,0}, {21860,21859,21879 ,9020,9019,9021 ,0,0,0}, - {21878,21879,21859 ,9018,9021,9019 ,0,0,0}, {21880,21861,21860 ,9022,8985,9020 ,0,0,0}, - {21860,21879,21880 ,9020,9021,9022 ,0,0,0}, {21881,21861,21880 ,9023,8985,9022 ,0,0,0}, - {21874,21857,21854 ,9010,9017,9011 ,0,0,0}, {21875,21856,21876 ,9012,9013,9014 ,0,0,0}, - {21854,21856,21875 ,9011,9013,9012 ,0,0,0}, {21851,21872,21871 ,9006,9007,9004 ,0,0,0}, - {21876,21855,21871 ,9014,9005,9004 ,0,0,0}, {21873,21852,21853 ,9009,9008,9000 ,0,0,0}, - {21872,21851,21852 ,9007,9006,9008 ,0,0,0}, {21870,21868,21848 ,9002,8999,8998 ,0,0,0}, - {21868,21873,21853 ,8999,9009,9000 ,0,0,0}, {21849,21869,21850 ,8992,9001,9003 ,0,0,0}, - {21850,21870,21848 ,9003,9002,8998 ,0,0,0}, {21846,21882,21866 ,8993,9024,8994 ,0,0,0}, - {21849,21866,21869 ,8992,8994,9001 ,0,0,0}, {21867,21882,21862 ,8997,9024,8995 ,0,0,0}, - {21846,21862,21882 ,8993,8995,9024 ,0,0,0}, {21865,21847,21845 ,8990,8996,8991 ,0,0,0}, - {21867,21847,21865 ,8997,8996,8990 ,0,0,0}, {21844,21843,21863 ,8989,8956,8987 ,0,0,0}, - {21864,21845,21844 ,8988,8991,8989 ,0,0,0}, {21883,21863,21884 ,9025,8987,9026 ,0,0,0}, - {21885,21867,21886 ,9027,9028,9029 ,0,0,0}, {21887,21865,21864 ,9030,9031,9032 ,0,0,0}, - {21869,21888,21870 ,9033,9034,9035 ,0,0,0}, {21882,21889,21866 ,9036,9037,9038 ,0,0,0}, - {21890,21872,21873 ,9039,9040,9041 ,0,0,0}, {21891,21868,21892 ,9042,9043,9044 ,0,0,0}, - {21893,21876,21894 ,9045,9046,9047 ,0,0,0}, {21871,21895,21894 ,9048,9049,9047 ,0,0,0}, - {21877,21874,21896 ,9050,9051,9052 ,0,0,0}, {21875,21897,21874 ,9053,9054,9051 ,0,0,0}, - {21898,21878,21877 ,9055,9056,9050 ,0,0,0}, {21877,21896,21898 ,9050,9052,9055 ,0,0,0}, - {21878,21899,21879 ,9056,9057,9058 ,0,0,0}, {21899,21878,21898 ,9057,9056,9055 ,0,0,0}, - {21880,21879,21900 ,9059,9058,9060 ,0,0,0}, {21899,21900,21879 ,9057,9060,9058 ,0,0,0}, - {21901,21881,21880 ,9061,9023,9059 ,0,0,0}, {21880,21900,21901 ,9059,9060,9061 ,0,0,0}, - {21893,21897,21875 ,9045,9054,9053 ,0,0,0}, {21874,21897,21896 ,9051,9054,9052 ,0,0,0}, - {21876,21871,21894 ,9046,9048,9047 ,0,0,0}, {21875,21876,21893 ,9053,9046,9045 ,0,0,0}, - {21895,21872,21890 ,9049,9040,9039 ,0,0,0}, {21871,21872,21895 ,9048,9040,9049 ,0,0,0}, - {21891,21873,21868 ,9042,9041,9043 ,0,0,0}, {21890,21873,21891 ,9039,9041,9042 ,0,0,0}, - {21888,21892,21870 ,9034,9044,9035 ,0,0,0}, {21892,21868,21870 ,9044,9043,9035 ,0,0,0}, - {21866,21902,21869 ,9038,9062,9033 ,0,0,0}, {21902,21888,21869 ,9062,9034,9033 ,0,0,0}, - {21882,21885,21889 ,9036,9027,9037 ,0,0,0}, {21866,21889,21902 ,9038,9037,9062 ,0,0,0}, - {21867,21865,21886 ,9028,9031,9029 ,0,0,0}, {21882,21867,21885 ,9036,9028,9027 ,0,0,0}, - {21887,21864,21883 ,9030,9032,9025 ,0,0,0}, {21886,21865,21887 ,9029,9031,9030 ,0,0,0}, - {21863,21883,21864 ,8987,9025,9032 ,0,0,0}, {21890,21891,21903 ,9063,9064,9065 ,0,0,0}, - {21904,21891,21892 ,9066,9064,9067 ,0,0,0}, {21891,21904,21903 ,9064,9066,9065 ,0,0,0}, - {21888,21905,21892 ,9068,9069,9067 ,0,0,0}, {21904,21892,21905 ,9066,9067,9069 ,0,0,0}, - {21888,21902,21906 ,9068,9070,9071 ,0,0,0}, {21906,21905,21888 ,9071,9069,9068 ,0,0,0}, - {21907,21902,21889 ,9072,9070,9073 ,0,0,0}, {21902,21907,21906 ,9070,9072,9071 ,0,0,0}, - {21885,21908,21889 ,9074,9075,9073 ,0,0,0}, {21907,21889,21908 ,9072,9073,9075 ,0,0,0}, - {21885,21886,21909 ,9074,9076,9077 ,0,0,0}, {21909,21908,21885 ,9077,9075,9074 ,0,0,0}, - {21910,21886,21887 ,9078,9076,9079 ,0,0,0}, {21886,21910,21909 ,9076,9078,9077 ,0,0,0}, - {21883,21911,21887 ,9080,9081,9079 ,0,0,0}, {21910,21887,21911 ,9078,9079,9081 ,0,0,0}, - {21884,21912,21911 ,9082,9083,9081 ,0,0,0}, {21911,21883,21884 ,9081,9080,9082 ,0,0,0}, - {21890,21903,21913 ,9063,9065,9084 ,0,0,0}, {21913,21914,21895 ,9084,9085,9086 ,0,0,0}, - {21895,21890,21913 ,9086,9063,9084 ,0,0,0}, {21894,21914,21915 ,9087,9085,9088 ,0,0,0}, - {21914,21894,21895 ,9085,9087,9086 ,0,0,0}, {21916,21893,21915 ,9089,9090,9088 ,0,0,0}, - {21894,21915,21893 ,9087,9088,9090 ,0,0,0}, {21916,21917,21897 ,9089,9091,9092 ,0,0,0}, - {21897,21893,21916 ,9092,9090,9089 ,0,0,0}, {21896,21917,21918 ,9093,9091,9094 ,0,0,0}, - {21917,21896,21897 ,9091,9093,9092 ,0,0,0}, {21919,21898,21918 ,9095,9096,9094 ,0,0,0}, - {21896,21918,21898 ,9093,9094,9096 ,0,0,0}, {21919,21920,21899 ,9095,9097,9098 ,0,0,0}, - {21899,21898,21919 ,9098,9096,9095 ,0,0,0}, {21900,21920,21921 ,9099,9097,9100 ,0,0,0}, - {21920,21900,21899 ,9097,9099,9098 ,0,0,0}, {21900,21921,21901 ,9099,9100,9101 ,0,0,0}, - {21922,21912,21923 ,9102,9103,9104 ,0,0,0}, {21924,21908,21925 ,9105,9106,9107 ,0,0,0}, - {21922,21926,21910 ,9102,9108,9109 ,0,0,0}, {21905,21927,21928 ,9110,9111,9112 ,0,0,0}, - {21907,21929,21906 ,9113,9114,9115 ,0,0,0}, {21930,21931,21913 ,9116,9117,9118 ,0,0,0}, - {21932,21903,21904 ,9119,9120,9121 ,0,0,0}, {21933,21916,21934 ,9122,9123,9124 ,0,0,0}, - {21915,21914,21935 ,9125,9126,9127 ,0,0,0}, {21936,21918,21917 ,9128,9129,9130 ,0,0,0}, - {21917,21933,21936 ,9130,9122,9128 ,0,0,0}, {21918,21937,21919 ,9129,9131,9132 ,0,0,0}, - {21937,21918,21936 ,9131,9129,9128 ,0,0,0}, {21920,21919,21938 ,9133,9132,9134 ,0,0,0}, - {21937,21938,21919 ,9131,9134,9132 ,0,0,0}, {21939,21921,21920 ,9135,9100,9133 ,0,0,0}, - {21920,21938,21939 ,9133,9134,9135 ,0,0,0}, {21916,21915,21934 ,9123,9125,9124 ,0,0,0}, - {21917,21916,21933 ,9130,9123,9122 ,0,0,0}, {21935,21914,21931 ,9127,9126,9117 ,0,0,0}, - {21934,21915,21935 ,9124,9125,9127 ,0,0,0}, {21930,21913,21903 ,9116,9118,9120 ,0,0,0}, - {21931,21914,21913 ,9117,9126,9118 ,0,0,0}, {21928,21932,21904 ,9112,9119,9121 ,0,0,0}, - {21932,21930,21903 ,9119,9116,9120 ,0,0,0}, {21906,21927,21905 ,9115,9111,9110 ,0,0,0}, - {21905,21928,21904 ,9110,9112,9121 ,0,0,0}, {21907,21924,21929 ,9113,9105,9114 ,0,0,0}, - {21906,21929,21927 ,9115,9114,9111 ,0,0,0}, {21908,21909,21925 ,9106,9136,9107 ,0,0,0}, - {21907,21908,21924 ,9113,9106,9105 ,0,0,0}, {21910,21926,21909 ,9109,9108,9136 ,0,0,0}, - {21925,21909,21926 ,9107,9136,9108 ,0,0,0}, {21922,21911,21912 ,9102,9137,9103 ,0,0,0}, - {21922,21910,21911 ,9102,9109,9137 ,0,0,0}, {21940,21923,21941 ,9138,9139,9140 ,0,0,0}, - {21942,21925,21943 ,9141,9142,9143 ,0,0,0}, {21944,21926,21922 ,9144,9145,9146 ,0,0,0}, - {21927,21945,21928 ,9147,9148,9149 ,0,0,0}, {21924,21946,21929 ,9150,9151,9152 ,0,0,0}, - {21947,21948,21930 ,9153,9154,9155 ,0,0,0}, {21947,21932,21949 ,9153,9156,9157 ,0,0,0}, - {21950,21934,21951 ,9158,9159,9160 ,0,0,0}, {21935,21931,21952 ,9161,9162,9163 ,0,0,0}, - {21953,21936,21933 ,9164,9165,9166 ,0,0,0}, {21933,21950,21953 ,9166,9158,9164 ,0,0,0}, - {21936,21954,21937 ,9165,9167,9168 ,0,0,0}, {21954,21936,21953 ,9167,9165,9164 ,0,0,0}, - {21938,21937,21955 ,9169,9168,9170 ,0,0,0}, {21954,21955,21937 ,9167,9170,9168 ,0,0,0}, - {21956,21939,21938 ,9171,9172,9169 ,0,0,0}, {21938,21955,21956 ,9169,9170,9171 ,0,0,0}, - {21934,21935,21951 ,9159,9161,9160 ,0,0,0}, {21933,21934,21950 ,9166,9159,9158 ,0,0,0}, - {21952,21931,21948 ,9163,9162,9154 ,0,0,0}, {21951,21935,21952 ,9160,9161,9163 ,0,0,0}, - {21947,21930,21932 ,9153,9155,9156 ,0,0,0}, {21948,21931,21930 ,9154,9162,9155 ,0,0,0}, - {21945,21949,21928 ,9148,9157,9149 ,0,0,0}, {21949,21932,21928 ,9157,9156,9149 ,0,0,0}, - {21929,21957,21927 ,9152,9173,9147 ,0,0,0}, {21957,21945,21927 ,9173,9148,9147 ,0,0,0}, - {21924,21942,21946 ,9150,9141,9151 ,0,0,0}, {21929,21946,21957 ,9152,9151,9173 ,0,0,0}, - {21925,21926,21943 ,9142,9145,9143 ,0,0,0}, {21924,21925,21942 ,9150,9142,9141 ,0,0,0}, - {21944,21922,21940 ,9144,9146,9138 ,0,0,0}, {21943,21926,21944 ,9143,9145,9144 ,0,0,0}, - {21923,21940,21922 ,9139,9138,9146 ,0,0,0}, {21958,21941,21959 ,9174,9175,9176 ,0,0,0}, - {21960,21943,21961 ,9177,9178,9179 ,0,0,0}, {21962,21944,21940 ,9180,9181,9182 ,0,0,0}, - {21957,21963,21964 ,9183,9184,9185 ,0,0,0}, {21942,21965,21946 ,9186,9187,9188 ,0,0,0}, - {21966,21967,21947 ,9189,9190,9191 ,0,0,0}, {21966,21949,21968 ,9189,9192,9193 ,0,0,0}, - {21969,21951,21970 ,9194,9195,9196 ,0,0,0}, {21952,21948,21971 ,9197,9198,9199 ,0,0,0}, - {21972,21953,21950 ,9200,9201,9202 ,0,0,0}, {21950,21969,21972 ,9202,9194,9200 ,0,0,0}, - {21953,21973,21954 ,9201,9203,9204 ,0,0,0}, {21973,21953,21972 ,9203,9201,9200 ,0,0,0}, - {21955,21954,21974 ,9205,9204,9206 ,0,0,0}, {21973,21974,21954 ,9203,9206,9204 ,0,0,0}, - {21975,21956,21955 ,9207,9208,9205 ,0,0,0}, {21955,21974,21975 ,9205,9206,9207 ,0,0,0}, - {21951,21952,21970 ,9195,9197,9196 ,0,0,0}, {21950,21951,21969 ,9202,9195,9194 ,0,0,0}, - {21971,21948,21967 ,9199,9198,9190 ,0,0,0}, {21970,21952,21971 ,9196,9197,9199 ,0,0,0}, - {21966,21947,21949 ,9189,9191,9192 ,0,0,0}, {21967,21948,21947 ,9190,9198,9191 ,0,0,0}, - {21964,21968,21945 ,9185,9193,9209 ,0,0,0}, {21968,21949,21945 ,9193,9192,9209 ,0,0,0}, - {21946,21963,21957 ,9188,9184,9183 ,0,0,0}, {21957,21964,21945 ,9183,9185,9209 ,0,0,0}, - {21942,21960,21965 ,9186,9177,9187 ,0,0,0}, {21946,21965,21963 ,9188,9187,9184 ,0,0,0}, - {21943,21944,21961 ,9178,9181,9179 ,0,0,0}, {21942,21943,21960 ,9186,9178,9177 ,0,0,0}, - {21962,21940,21958 ,9180,9182,9174 ,0,0,0}, {21961,21944,21962 ,9179,9181,9180 ,0,0,0}, - {21941,21958,21940 ,9175,9174,9182 ,0,0,0}, {21546,21959,21544 ,9210,9211,9212 ,0,0,0}, - {21547,21961,21548 ,9213,9214,9215 ,0,0,0}, {21558,21962,21958 ,9216,9217,9218 ,0,0,0}, - {21963,21571,21572 ,9219,9220,9221 ,0,0,0}, {21960,21559,21965 ,9222,9223,9224 ,0,0,0}, - {21574,21575,21966 ,9225,9226,9227 ,0,0,0}, {21573,21968,21964 ,9228,9229,9230 ,0,0,0}, - {21604,21970,21971 ,9231,9232,9233 ,0,0,0}, {21601,21967,21575 ,9234,9235,9226 ,0,0,0}, - {21605,21972,21969 ,9236,9237,9238 ,0,0,0}, {21969,21603,21605 ,9238,9239,9236 ,0,0,0}, - {21972,21606,21973 ,9237,9240,9241 ,0,0,0}, {21606,21972,21605 ,9240,9237,9236 ,0,0,0}, - {21973,21508,21505 ,9241,9242,9243 ,0,0,0}, {21606,21508,21973 ,9240,9242,9241 ,0,0,0}, - {21504,21974,21505 ,8461,9244,9243 ,0,0,0}, {21973,21505,21974 ,9241,9243,9244 ,0,0,0}, - {21975,21974,21504 ,9207,9244,8461 ,0,0,0}, {21603,21970,21604 ,9239,9232,9231 ,0,0,0}, - {21969,21970,21603 ,9238,9232,9239 ,0,0,0}, {21601,21971,21967 ,9234,9233,9235 ,0,0,0}, - {21604,21971,21601 ,9231,9233,9234 ,0,0,0}, {21966,21968,21574 ,9227,9229,9225 ,0,0,0}, - {21575,21967,21966 ,9226,9235,9227 ,0,0,0}, {21572,21573,21964 ,9221,9228,9230 ,0,0,0}, - {21573,21574,21968 ,9228,9225,9229 ,0,0,0}, {21965,21571,21963 ,9224,9220,9219 ,0,0,0}, - {21963,21572,21964 ,9219,9221,9230 ,0,0,0}, {21960,21547,21559 ,9222,9213,9223 ,0,0,0}, - {21965,21559,21571 ,9224,9223,9220 ,0,0,0}, {21961,21962,21548 ,9214,9217,9215 ,0,0,0}, - {21960,21961,21547 ,9222,9214,9213 ,0,0,0}, {21558,21958,21546 ,9216,9218,9210 ,0,0,0}, - {21548,21962,21558 ,9215,9217,9216 ,0,0,0}, {21959,21546,21958 ,9211,9210,9218 ,0,0,0}, - {21976,21484,21977 ,9245,8438,9246 ,0,0,0}, {21978,21594,21541 ,9247,9248,9249 ,0,0,0}, - {21979,21556,21482 ,9250,9251,9252 ,0,0,0}, {21599,21980,21981 ,9253,9254,9255 ,0,0,0}, - {21595,21982,21596 ,9256,9257,9258 ,0,0,0}, {21983,21984,21564 ,9259,9260,9261 ,0,0,0}, - {21985,21567,21568 ,9262,9263,9264 ,0,0,0}, {21986,21602,21987 ,9265,9266,9267 ,0,0,0}, - {21600,21565,21988 ,9268,9269,9270 ,0,0,0}, {21989,21579,21524 ,9271,9272,9273 ,0,0,0}, - {21524,21986,21989 ,9273,9265,9271 ,0,0,0}, {21579,21990,21607 ,9272,9274,9275 ,0,0,0}, - {21990,21579,21989 ,9274,9272,9271 ,0,0,0}, {21515,21607,21991 ,9276,9275,9277 ,0,0,0}, - {21990,21991,21607 ,9274,9277,9275 ,0,0,0}, {21992,21518,21515 ,9278,9279,9276 ,0,0,0}, - {21515,21991,21992 ,9276,9277,9278 ,0,0,0}, {21602,21600,21987 ,9266,9268,9267 ,0,0,0}, - {21524,21602,21986 ,9273,9266,9265 ,0,0,0}, {21988,21565,21984 ,9270,9269,9260 ,0,0,0}, - {21987,21600,21988 ,9267,9268,9270 ,0,0,0}, {21983,21564,21567 ,9259,9261,9263 ,0,0,0}, - {21984,21565,21564 ,9260,9269,9261 ,0,0,0}, {21981,21985,21568 ,9255,9262,9264 ,0,0,0}, - {21985,21983,21567 ,9262,9259,9263 ,0,0,0}, {21596,21980,21599 ,9258,9254,9253 ,0,0,0}, - {21599,21981,21568 ,9253,9255,9264 ,0,0,0}, {21595,21993,21982 ,9256,9280,9257 ,0,0,0}, - {21596,21982,21980 ,9258,9257,9254 ,0,0,0}, {21978,21993,21594 ,9247,9280,9248 ,0,0,0}, - {21595,21594,21993 ,9256,9248,9280 ,0,0,0}, {21979,21541,21556 ,9250,9249,9251 ,0,0,0}, - {21978,21541,21979 ,9247,9249,9250 ,0,0,0}, {21976,21482,21484 ,9245,9252,8438 ,0,0,0}, - {21979,21482,21976 ,9250,9252,9245 ,0,0,0}, {21994,21977,21995 ,9281,9246,9282 ,0,0,0}, - {21996,21978,21997 ,9283,9284,9285 ,0,0,0}, {21998,21979,21976 ,9286,9287,9288 ,0,0,0}, - {21980,21999,22000 ,9289,9290,9291 ,0,0,0}, {21993,22001,21982 ,9292,9293,9294 ,0,0,0}, - {22002,21984,21983 ,9295,9296,9297 ,0,0,0}, {22003,21985,22004 ,9298,9299,9300 ,0,0,0}, - {22005,21987,22006 ,9301,9302,9303 ,0,0,0}, {21988,21984,22007 ,9304,9296,9305 ,0,0,0}, - {22008,21989,21986 ,9306,9307,9308 ,0,0,0}, {21986,22005,22008 ,9308,9301,9306 ,0,0,0}, - {21989,22009,21990 ,9307,9309,9310 ,0,0,0}, {22009,21989,22008 ,9309,9307,9306 ,0,0,0}, - {21991,21990,22010 ,9311,9310,9312 ,0,0,0}, {22009,22010,21990 ,9309,9312,9310 ,0,0,0}, - {22011,21992,21991 ,9313,9314,9311 ,0,0,0}, {21991,22010,22011 ,9311,9312,9313 ,0,0,0}, - {21987,21988,22006 ,9302,9304,9303 ,0,0,0}, {21986,21987,22005 ,9308,9302,9301 ,0,0,0}, - {22007,21984,22002 ,9305,9296,9295 ,0,0,0}, {22006,21988,22007 ,9303,9304,9305 ,0,0,0}, - {22003,21983,21985 ,9298,9297,9299 ,0,0,0}, {22002,21983,22003 ,9295,9297,9298 ,0,0,0}, - {22000,22004,21981 ,9291,9300,9315 ,0,0,0}, {22004,21985,21981 ,9300,9299,9315 ,0,0,0}, - {21982,21999,21980 ,9294,9290,9289 ,0,0,0}, {21980,22000,21981 ,9289,9291,9315 ,0,0,0}, - {21993,21996,22001 ,9292,9283,9293 ,0,0,0}, {21982,22001,21999 ,9294,9293,9290 ,0,0,0}, - {21978,21979,21997 ,9284,9287,9285 ,0,0,0}, {21993,21978,21996 ,9292,9284,9283 ,0,0,0}, - {21998,21976,21994 ,9286,9288,9281 ,0,0,0}, {21997,21979,21998 ,9285,9287,9286 ,0,0,0}, - {21977,21994,21976 ,9246,9281,9288 ,0,0,0}, {22012,21995,22013 ,9316,9282,9317 ,0,0,0}, - {22014,21997,22015 ,9318,9319,9320 ,0,0,0}, {22016,21998,21994 ,9321,9322,9323 ,0,0,0}, - {21999,22017,22000 ,9324,9325,9326 ,0,0,0}, {21996,22018,22001 ,9327,9328,9329 ,0,0,0}, - {22019,22002,22003 ,9330,9331,9332 ,0,0,0}, {22020,22004,22021 ,9333,9334,9335 ,0,0,0}, - {22022,22006,22023 ,9336,9337,9338 ,0,0,0}, {22007,22002,22024 ,9339,9331,9340 ,0,0,0}, - {22025,22008,22005 ,9341,9342,9343 ,0,0,0}, {22005,22022,22025 ,9343,9336,9341 ,0,0,0}, - {22008,22026,22009 ,9342,9344,9345 ,0,0,0}, {22026,22008,22025 ,9344,9342,9341 ,0,0,0}, - {22010,22009,22027 ,9346,9345,9347 ,0,0,0}, {22026,22027,22009 ,9344,9347,9345 ,0,0,0}, - {22028,22011,22010 ,9348,9349,9346 ,0,0,0}, {22010,22027,22028 ,9346,9347,9348 ,0,0,0}, - {22006,22007,22023 ,9337,9339,9338 ,0,0,0}, {22005,22006,22022 ,9343,9337,9336 ,0,0,0}, - {22024,22002,22019 ,9340,9331,9330 ,0,0,0}, {22023,22007,22024 ,9338,9339,9340 ,0,0,0}, - {22020,22003,22004 ,9333,9332,9334 ,0,0,0}, {22019,22003,22020 ,9330,9332,9333 ,0,0,0}, - {22017,22021,22000 ,9325,9335,9326 ,0,0,0}, {22021,22004,22000 ,9335,9334,9326 ,0,0,0}, - {22001,22029,21999 ,9329,9350,9324 ,0,0,0}, {22029,22017,21999 ,9350,9325,9324 ,0,0,0}, - {21996,22014,22018 ,9327,9318,9328 ,0,0,0}, {22001,22018,22029 ,9329,9328,9350 ,0,0,0}, - {21997,21998,22015 ,9319,9322,9320 ,0,0,0}, {21996,21997,22014 ,9327,9319,9318 ,0,0,0}, - {22016,21994,22012 ,9321,9323,9316 ,0,0,0}, {22015,21998,22016 ,9320,9322,9321 ,0,0,0}, - {21995,22012,21994 ,9282,9316,9323 ,0,0,0}, {21612,22030,21649 ,9351,9352,8640 ,0,0,0}, - {21618,22031,21619 ,9353,9354,9355 ,0,0,0}, {21614,22032,22033 ,9356,9357,9358 ,0,0,0}, - {22034,21626,22035 ,9359,9360,9361 ,0,0,0}, {22036,21616,22037 ,9362,9363,9364 ,0,0,0}, - {21631,22038,22039 ,9365,9366,9367 ,0,0,0}, {21623,22040,21621 ,9368,9369,9370 ,0,0,0}, - {22041,22042,21636 ,9371,9372,9373 ,0,0,0}, {22043,21629,21628 ,9374,9375,9376 ,0,0,0}, - {22044,22045,21633 ,9377,9378,9379 ,0,0,0}, {21634,21633,22045 ,9380,9379,9378 ,0,0,0}, - {21640,22046,22044 ,9381,9382,9377 ,0,0,0}, {22044,21633,21640 ,9377,9379,9381 ,0,0,0}, - {22046,21642,22047 ,9382,9383,9384 ,0,0,0}, {21642,22046,21640 ,9383,9382,9381 ,0,0,0}, - {22048,22047,21643 ,9385,9384,9386 ,0,0,0}, {21642,21643,22047 ,9383,9386,9384 ,0,0,0}, - {21646,22049,22048 ,8637,9387,9385 ,0,0,0}, {22048,21643,21646 ,9385,9386,8637 ,0,0,0}, - {21636,21634,22041 ,9373,9380,9371 ,0,0,0}, {22041,21634,22045 ,9371,9380,9378 ,0,0,0}, - {22042,22043,21628 ,9372,9374,9376 ,0,0,0}, {22042,21628,21636 ,9372,9376,9373 ,0,0,0}, - {21629,22038,21631 ,9375,9366,9365 ,0,0,0}, {22043,22038,21629 ,9374,9366,9375 ,0,0,0}, - {21623,22039,22040 ,9368,9367,9369 ,0,0,0}, {21631,22039,21623 ,9365,9367,9368 ,0,0,0}, - {21626,21621,22035 ,9360,9370,9361 ,0,0,0}, {21621,22040,22035 ,9370,9369,9361 ,0,0,0}, - {22037,21648,22034 ,9364,9388,9359 ,0,0,0}, {21648,21626,22034 ,9388,9360,9359 ,0,0,0}, - {22036,21618,21616 ,9362,9353,9363 ,0,0,0}, {22037,21616,21648 ,9364,9363,9388 ,0,0,0}, - {22031,22032,21619 ,9354,9357,9355 ,0,0,0}, {22036,22031,21618 ,9362,9354,9353 ,0,0,0}, - {21614,22033,21612 ,9356,9358,9351 ,0,0,0}, {21619,22032,21614 ,9355,9357,9356 ,0,0,0}, - {22030,21612,22033 ,9352,9351,9358 ,0,0,0}, {22050,22013,22051 ,9389,9317,9390 ,0,0,0}, - {22052,22015,22053 ,9391,9392,9393 ,0,0,0}, {22054,22016,22012 ,9394,9395,9396 ,0,0,0}, - {22029,22055,22056 ,9397,9398,9399 ,0,0,0}, {22014,22057,22018 ,9400,9401,9402 ,0,0,0}, - {22058,22059,22020 ,9403,9404,9405 ,0,0,0}, {22060,22021,22017 ,9406,9407,9408 ,0,0,0}, - {22061,22023,22024 ,9409,9410,9411 ,0,0,0}, {22024,22019,22062 ,9411,9412,9413 ,0,0,0}, - {22063,22025,22022 ,9414,9415,9416 ,0,0,0}, {22022,22064,22063 ,9416,9417,9414 ,0,0,0}, - {22025,22065,22026 ,9415,9418,9419 ,0,0,0}, {22065,22025,22063 ,9418,9415,9414 ,0,0,0}, - {22027,22026,22066 ,9420,9419,9421 ,0,0,0}, {22065,22066,22026 ,9418,9421,9419 ,0,0,0}, - {22067,22027,22068 ,9422,9420,9423 ,0,0,0}, {22027,22066,22068 ,9420,9421,9423 ,0,0,0}, - {22028,22027,22067 ,9424,9420,9422 ,0,0,0}, {22064,22023,22061 ,9417,9410,9409 ,0,0,0}, - {22022,22023,22064 ,9416,9410,9417 ,0,0,0}, {22019,22059,22062 ,9412,9404,9413 ,0,0,0}, - {22061,22024,22062 ,9409,9411,9413 ,0,0,0}, {22058,22020,22021 ,9403,9405,9407 ,0,0,0}, - {22059,22019,22020 ,9404,9412,9405 ,0,0,0}, {22056,22060,22017 ,9399,9406,9408 ,0,0,0}, - {22060,22058,22021 ,9406,9403,9407 ,0,0,0}, {22018,22055,22029 ,9402,9398,9397 ,0,0,0}, - {22029,22056,22017 ,9397,9399,9408 ,0,0,0}, {22014,22052,22057 ,9400,9391,9401 ,0,0,0}, - {22018,22057,22055 ,9402,9401,9398 ,0,0,0}, {22015,22016,22053 ,9392,9395,9393 ,0,0,0}, - {22014,22015,22052 ,9400,9392,9391 ,0,0,0}, {22054,22012,22050 ,9394,9396,9389 ,0,0,0}, - {22053,22016,22054 ,9393,9395,9394 ,0,0,0}, {22013,22050,22012 ,9317,9389,9396 ,0,0,0}, - {22033,22051,22030 ,9425,9390,9426 ,0,0,0}, {22036,22053,22031 ,9427,9428,9429 ,0,0,0}, - {22032,22054,22050 ,9430,9431,9432 ,0,0,0}, {22055,22034,22035 ,9433,9434,9435 ,0,0,0}, - {22052,22037,22057 ,9436,9437,9438 ,0,0,0}, {22039,22038,22058 ,9439,9440,9441 ,0,0,0}, - {22040,22060,22056 ,9442,9443,9444 ,0,0,0}, {22041,22061,22042 ,9445,9446,9447 ,0,0,0}, - {22062,22059,22043 ,9448,9449,9450 ,0,0,0}, {22044,22063,22045 ,9451,9452,9453 ,0,0,0}, - {22064,22041,22045 ,9454,9445,9453 ,0,0,0}, {22044,22046,22065 ,9451,9455,9456 ,0,0,0}, - {22065,22063,22044 ,9456,9452,9451 ,0,0,0}, {22066,22046,22047 ,9457,9455,9458 ,0,0,0}, - {22046,22066,22065 ,9455,9457,9456 ,0,0,0}, {22048,22068,22047 ,9459,9460,9458 ,0,0,0}, - {22066,22047,22068 ,9457,9458,9460 ,0,0,0}, {22049,22067,22068 ,9461,9422,9460 ,0,0,0}, - {22068,22048,22049 ,9460,9459,9461 ,0,0,0}, {22061,22041,22064 ,9446,9445,9454 ,0,0,0}, - {22063,22064,22045 ,9452,9454,9453 ,0,0,0}, {22042,22062,22043 ,9447,9448,9450 ,0,0,0}, - {22061,22062,22042 ,9446,9448,9447 ,0,0,0}, {22038,22059,22058 ,9440,9449,9441 ,0,0,0}, - {22043,22059,22038 ,9450,9449,9440 ,0,0,0}, {22040,22039,22060 ,9442,9439,9443 ,0,0,0}, - {22039,22058,22060 ,9439,9441,9443 ,0,0,0}, {22055,22035,22056 ,9433,9435,9444 ,0,0,0}, - {22035,22040,22056 ,9435,9442,9444 ,0,0,0}, {22057,22037,22034 ,9438,9437,9434 ,0,0,0}, - {22057,22034,22055 ,9438,9434,9433 ,0,0,0}, {22052,22053,22036 ,9436,9428,9427 ,0,0,0}, - {22052,22036,22037 ,9436,9427,9437 ,0,0,0}, {22031,22054,22032 ,9429,9431,9430 ,0,0,0}, - {22053,22054,22031 ,9428,9431,9429 ,0,0,0}, {22033,22050,22051 ,9425,9432,9390 ,0,0,0}, - {22032,22050,22033 ,9430,9432,9425 ,0,0,0}, {21736,22069,22070 ,9462,9463,9464 ,0,0,0}, - {21735,22071,21733 ,9465,9466,9467 ,0,0,0}, {22069,21736,22072 ,9463,9462,9468 ,0,0,0}, - {22070,22073,21736 ,9464,9462,9462 ,0,0,0}, {22072,21736,21733 ,9468,9462,9467 ,0,0,0}, - {22074,22072,21733 ,9469,9468,9467 ,0,0,0}, {22074,21733,22071 ,9469,9467,9466 ,0,0,0}, - {21771,21689,22075 ,9470,9471,9472 ,0,0,0}, {21771,22076,22077 ,9470,9473,9474 ,0,0,0}, - {22075,22076,21771 ,9472,9473,9470 ,0,0,0}, {21735,22077,22078 ,9465,9474,9475 ,0,0,0}, - {21735,21771,22077 ,9465,9470,9474 ,0,0,0}, {21735,22079,22080 ,9465,9476,9477 ,0,0,0}, - {22078,22079,21735 ,9475,9476,9465 ,0,0,0}, {21735,22081,22082 ,9465,9478,9479 ,0,0,0}, - {22080,22081,21735 ,9477,9478,9465 ,0,0,0}, {22071,21735,22083 ,9466,9465,9480 ,0,0,0}, - {22082,22083,21735 ,9479,9480,9465 ,0,0,0}, {22084,21557,22085 ,9481,9482,9483 ,0,0,0}, - {21557,22086,22087 ,9482,9484,9485 ,0,0,0}, {22087,21555,21557 ,9485,9486,9482 ,0,0,0}, - {21557,22084,22086 ,9482,9481,9484 ,0,0,0}, {21555,22088,22089 ,9486,9487,9488 ,0,0,0}, - {21555,22087,22088 ,9486,9485,9487 ,0,0,0}, {21557,22090,22085 ,9482,9489,9483 ,0,0,0}, - {21555,22089,21484 ,9486,9488,9490 ,0,0,0}, {22091,21557,21542 ,9491,9482,9492 ,0,0,0}, - {21557,22091,22090 ,9482,9491,9489 ,0,0,0}, {21544,22092,22093 ,9493,9493,9494 ,0,0,0}, - {22094,22095,21545 ,9495,9496,9497 ,0,0,0}, {22096,22097,21544 ,9498,9499,9493 ,0,0,0}, - {22096,21544,22093 ,9498,9493,9494 ,0,0,0}, {21544,22098,21545 ,9493,9500,9497 ,0,0,0}, - {22098,21544,22097 ,9500,9493,9499 ,0,0,0}, {22099,21545,22095 ,9501,9497,9496 ,0,0,0}, - {22098,22094,21545 ,9500,9495,9497 ,0,0,0}, {22091,21542,22099 ,9491,9492,9501 ,0,0,0}, - {22099,21542,21545 ,9501,9492,9497 ,0,0,0}, {22092,21544,22100 ,9502,9503,9504 ,0,0,0}, - {21941,22100,21959 ,9505,9504,9506 ,0,0,0}, {21941,21923,22100 ,9505,9507,9504 ,0,0,0}, - {22100,21923,21912 ,9504,9507,9508 ,0,0,0}, {21912,21884,22100 ,9508,9509,9504 ,0,0,0}, - {22100,21544,21959 ,9504,9503,9506 ,0,0,0}, {22101,22099,22102 ,9510,9511,4303 ,0,0,0}, - {22101,22103,22091 ,9510,82,9512 ,0,0,0}, {22091,22099,22101 ,9512,9511,9510 ,0,0,0}, - {22104,22105,22106 ,9513,9514,9515 ,0,0,0}, {22105,22107,22106 ,9514,9516,9515 ,0,0,0}, - {22105,22104,22108 ,9514,9513,9517 ,0,0,0}, {22086,22109,22108 ,9518,9519,9517 ,0,0,0}, - {22104,22086,22108 ,9513,9518,9517 ,0,0,0}, {22084,22109,22086 ,9520,9519,9518 ,0,0,0}, - {22109,22084,22110 ,9519,9520,9521 ,0,0,0}, {22085,22111,22110 ,9522,9523,9521 ,0,0,0}, - {22110,22084,22085 ,9521,9520,9522 ,0,0,0}, {22111,22090,22112 ,9523,9524,9525 ,0,0,0}, - {22090,22111,22085 ,9524,9523,9522 ,0,0,0}, {22103,22112,22091 ,9526,9525,9527 ,0,0,0}, - {22090,22091,22112 ,9524,9527,9525 ,0,0,0}, {22097,22113,22114 ,9528,9529,9530 ,0,0,0}, - {22102,22099,22095 ,9531,9532,9533 ,0,0,0}, {22095,22094,22115 ,9533,9534,9535 ,0,0,0}, - {22116,22098,22114 ,9536,9537,9530 ,0,0,0}, {22115,22094,22116 ,9535,9534,9536 ,0,0,0}, - {22095,22115,22102 ,9533,9535,9531 ,0,0,0}, {22094,22098,22116 ,9534,9537,9536 ,0,0,0}, - {22098,22097,22114 ,9537,9528,9530 ,0,0,0}, {22113,22097,22096 ,9529,9528,9538 ,0,0,0}, - {22096,22093,22117 ,9538,9539,9540 ,0,0,0}, {22117,22113,22096 ,9540,9529,9538 ,0,0,0}, - {22118,22093,22092 ,9541,9539,9542 ,0,0,0}, {22093,22118,22117 ,9539,9541,9540 ,0,0,0}, - {22118,22092,22100 ,9541,9542,9542 ,0,0,0}, {22073,22119,22120 ,9543,9543,9544 ,0,0,0}, - {22073,22120,22121 ,9543,9544,9543 ,0,0,0}, {22122,22073,22121 ,9543,9543,9543 ,0,0,0}, - {22113,22117,22073 ,9543,9543,9543 ,0,0,0}, {22113,22073,22122 ,9543,9543,9543 ,0,0,0}, - {22073,22118,22100 ,9543,9543,9544 ,0,0,0}, {22117,22118,22073 ,9543,9543,9543 ,0,0,0}, - {22073,22100,21736 ,9543,9544,9543 ,0,0,0}, {22100,21863,21843 ,9544,9543,9543 ,0,0,0}, - {22100,21884,21863 ,9544,9544,9543 ,0,0,0}, {21843,21823,22100 ,9543,9544,9544 ,0,0,0}, - {21736,22100,21804 ,9543,9544,9543 ,0,0,0}, {22100,21823,21804 ,9544,9544,9543 ,0,0,0}, - {21649,22030,22123 ,9545,9546,9547 ,0,0,0}, {22075,22124,22076 ,9548,9549,9550 ,0,0,0}, - {22125,22124,21650 ,9551,9549,9552 ,0,0,0}, {22126,22107,22127 ,9553,9554,9555 ,0,0,0}, - {22128,22126,22127 ,9556,9553,9555 ,0,0,0}, {22129,22130,22131 ,9557,9558,9559 ,0,0,0}, - {22130,22128,22131 ,9558,9556,9559 ,0,0,0}, {22124,21670,21650 ,9549,9560,9552 ,0,0,0}, - {22125,21650,21610 ,9551,9552,9561 ,0,0,0}, {22129,22077,22076 ,9557,9562,9550 ,0,0,0}, - {21689,21670,22075 ,9563,9560,9548 ,0,0,0}, {21649,22125,21610 ,9545,9551,9561 ,0,0,0}, - {22123,22132,22125 ,9547,9564,9551 ,0,0,0}, {22125,21649,22123 ,9551,9545,9547 ,0,0,0}, - {22132,22126,22128 ,9564,9553,9556 ,0,0,0}, {22130,22129,22076 ,9558,9557,9550 ,0,0,0}, - {22128,22130,22125 ,9556,9558,9551 ,0,0,0}, {22075,21670,22124 ,9548,9560,9549 ,0,0,0}, - {22128,22125,22132 ,9556,9551,9564 ,0,0,0}, {22127,22131,22128 ,9555,9559,9556 ,0,0,0}, - {22076,22124,22130 ,9550,9549,9558 ,0,0,0}, {22125,22130,22124 ,9551,9558,9549 ,0,0,0}, - {22133,22134,22135 ,9565,9566,9567 ,0,0,0}, {22136,22137,22138 ,9568,9569,9570 ,0,0,0}, - {22139,22140,22141 ,9571,9572,9573 ,0,0,0}, {22107,22105,22142 ,9574,9575,9576 ,0,0,0}, - {22143,22144,22081 ,9577,9578,9579 ,0,0,0}, {22145,22146,22147 ,9580,9581,9582 ,0,0,0}, - {22148,22149,22134 ,9583,9584,9566 ,0,0,0}, {22071,22083,22149 ,9585,9586,9584 ,0,0,0}, - {22150,22112,22103 ,9587,9588,9589 ,0,0,0}, {22133,22135,22150 ,9565,9567,9587 ,0,0,0}, - {22071,22149,22148 ,9585,9584,9583 ,0,0,0}, {22138,22135,22134 ,9570,9567,9566 ,0,0,0}, - {22083,22151,22149 ,9586,9590,9584 ,0,0,0}, {22144,22151,22082 ,9578,9590,9591 ,0,0,0}, - {22152,22143,22147 ,9592,9577,9582 ,0,0,0}, {22153,22141,22137 ,9593,9573,9569 ,0,0,0}, - {22078,22129,22145 ,9594,9595,9580 ,0,0,0}, {22140,22152,22142 ,9572,9592,9576 ,0,0,0}, - {22077,22129,22078 ,9596,9595,9594 ,0,0,0}, {22145,22129,22131 ,9580,9595,9597 ,0,0,0}, - {22082,22151,22083 ,9591,9590,9586 ,0,0,0}, {22082,22081,22144 ,9591,9579,9578 ,0,0,0}, - {22150,22135,22112 ,9587,9567,9588 ,0,0,0}, {22148,22134,22133 ,9583,9566,9565 ,0,0,0}, - {22138,22134,22136 ,9570,9566,9568 ,0,0,0}, {22111,22112,22135 ,9598,9588,9567 ,0,0,0}, - {22136,22149,22151 ,9568,9584,9590 ,0,0,0}, {22127,22107,22142 ,9599,9574,9576 ,0,0,0}, - {22135,22138,22111 ,9567,9570,9598 ,0,0,0}, {22149,22136,22134 ,9584,9568,9566 ,0,0,0}, - {22137,22136,22153 ,9569,9568,9593 ,0,0,0}, {22110,22111,22138 ,9600,9598,9570 ,0,0,0}, - {22144,22153,22151 ,9578,9593,9590 ,0,0,0}, {22080,22143,22081 ,9601,9577,9579 ,0,0,0}, - {22138,22137,22110 ,9570,9569,9600 ,0,0,0}, {22151,22153,22136 ,9590,9593,9568 ,0,0,0}, - {22141,22153,22139 ,9573,9593,9571 ,0,0,0}, {22109,22110,22137 ,9602,9600,9569 ,0,0,0}, - {22143,22139,22144 ,9577,9571,9578 ,0,0,0}, {22079,22147,22080 ,9603,9582,9601 ,0,0,0}, - {22141,22108,22109 ,9573,9604,9602 ,0,0,0}, {22144,22139,22153 ,9578,9571,9593 ,0,0,0}, - {22139,22152,22140 ,9571,9592,9572 ,0,0,0}, {22109,22137,22141 ,9602,9569,9573 ,0,0,0}, - {22080,22147,22143 ,9601,9582,9577 ,0,0,0}, {22145,22079,22078 ,9580,9603,9594 ,0,0,0}, - {22140,22105,22108 ,9572,9575,9604 ,0,0,0}, {22143,22152,22139 ,9577,9592,9571 ,0,0,0}, - {22146,22142,22152 ,9581,9576,9592 ,0,0,0}, {22108,22141,22140 ,9604,9573,9572 ,0,0,0}, - {22079,22145,22147 ,9603,9580,9582 ,0,0,0}, {22147,22146,22152 ,9582,9581,9592 ,0,0,0}, - {22131,22127,22146 ,9597,9599,9581 ,0,0,0}, {22145,22131,22146 ,9580,9597,9581 ,0,0,0}, - {22127,22142,22146 ,9599,9576,9581 ,0,0,0}, {22105,22140,22142 ,9575,9572,9576 ,0,0,0}, - {22150,22101,22154 ,9605,9606,9607 ,0,0,0}, {22074,22155,22072 ,9608,9609,9468 ,0,0,0}, - {22154,22101,22156 ,9607,9606,9610 ,0,0,0}, {22101,22102,22156 ,9606,82,9610 ,0,0,0}, - {22154,22157,22155 ,9607,9611,9609 ,0,0,0}, {22150,22103,22101 ,9605,82,9606 ,0,0,0}, - {22155,22157,22072 ,9609,9611,9468 ,0,0,0}, {22148,22155,22074 ,9612,9609,9608 ,0,0,0}, - {22071,22148,22074 ,9613,9612,9608 ,0,0,0}, {22148,22133,22155 ,9612,9614,9609 ,0,0,0}, - {22133,22150,22154 ,9614,9605,9607 ,0,0,0}, {22133,22154,22155 ,9614,9607,9609 ,0,0,0}, - {22157,22154,22156 ,9611,9607,9610 ,0,0,0}, {22122,22121,22114 ,9615,9616,9617 ,0,0,0}, - {22156,22102,22115 ,9618,82,9619 ,0,0,0}, {22115,22116,22158 ,9619,9620,9621 ,0,0,0}, - {22115,22158,22156 ,9619,9621,9618 ,0,0,0}, {22113,22122,22114 ,9622,9615,9617 ,0,0,0}, - {22120,22119,22159 ,9623,9624,9625 ,0,0,0}, {22159,22160,22120 ,9625,9626,9623 ,0,0,0}, - {22157,22158,22161 ,9627,9621,9628 ,0,0,0}, {22161,22158,22160 ,9628,9621,9626 ,0,0,0}, - {22119,22073,22070 ,9624,9629,9630 ,0,0,0}, {22157,22161,22072 ,9627,9628,9631 ,0,0,0}, - {22070,22161,22159 ,9630,9628,9625 ,0,0,0}, {22156,22158,22157 ,9618,9621,9627 ,0,0,0}, - {22070,22069,22161 ,9630,9632,9628 ,0,0,0}, {22161,22069,22072 ,9628,9632,9631 ,0,0,0}, - {22158,22116,22160 ,9621,9620,9626 ,0,0,0}, {22114,22160,22116 ,9617,9626,9620 ,0,0,0}, - {22070,22159,22119 ,9630,9625,9624 ,0,0,0}, {22161,22160,22159 ,9628,9626,9625 ,0,0,0}, - {22121,22160,22114 ,9616,9626,9617 ,0,0,0}, {22121,22120,22160 ,9616,9623,9626 ,0,0,0}, - {21995,22162,22163 ,9633,9634,9635 ,0,0,0}, {22107,22126,22164 ,9636,9637,9638 ,0,0,0}, - {22165,22164,22126 ,9639,9638,9637 ,0,0,0}, {21995,22163,22013 ,9633,9635,9640 ,0,0,0}, - {22163,22162,22165 ,9635,9634,9639 ,0,0,0}, {22123,22030,22051 ,9641,9642,9643 ,0,0,0}, - {22013,22163,22051 ,9640,9635,9643 ,0,0,0}, {22089,22162,21977 ,9644,9634,9645 ,0,0,0}, - {22166,22089,22088 ,9646,9644,9647 ,0,0,0}, {22162,21995,21977 ,9634,9633,9645 ,0,0,0}, - {22164,22104,22106 ,9638,9648,9649 ,0,0,0}, {22164,22166,22167 ,9638,9646,9650 ,0,0,0}, - {21977,21484,22089 ,9645,9651,9644 ,0,0,0}, {22104,22167,22086 ,9648,9650,9652 ,0,0,0}, - {22167,22104,22164 ,9650,9648,9638 ,0,0,0}, {22163,22123,22051 ,9635,9641,9643 ,0,0,0}, - {22162,22166,22165 ,9634,9646,9639 ,0,0,0}, {22132,22123,22163 ,9653,9641,9635 ,0,0,0}, - {22089,22166,22162 ,9644,9646,9634 ,0,0,0}, {22167,22088,22087 ,9650,9647,9654 ,0,0,0}, - {22126,22132,22165 ,9637,9653,9639 ,0,0,0}, {22163,22165,22132 ,9635,9639,9653 ,0,0,0}, - {22088,22167,22166 ,9647,9650,9646 ,0,0,0}, {22086,22167,22087 ,9652,9650,9654 ,0,0,0}, - {22164,22106,22107 ,9638,9649,9636 ,0,0,0}, {22166,22164,22165 ,9646,9638,9639 ,0,0,0}, - {22168,21609,22169 ,9655,9656,9657 ,0,0,0}, {21609,22170,22171 ,9656,9658,9659 ,0,0,0}, - {22171,21608,21609 ,9659,9660,9656 ,0,0,0}, {21609,22168,22170 ,9656,9655,9658 ,0,0,0}, - {21608,22172,22173 ,9660,9661,9662 ,0,0,0}, {21608,22171,22172 ,9660,9659,9661 ,0,0,0}, - {21609,22174,22169 ,9656,9663,9657 ,0,0,0}, {21608,22173,21504 ,9660,9662,9664 ,0,0,0}, - {22175,21609,21517 ,9665,9656,9666 ,0,0,0}, {21609,22175,22174 ,9656,9665,9663 ,0,0,0}, - {21518,22176,22177 ,9667,9667,9668 ,0,0,0}, {22178,22179,21516 ,9669,9670,9671 ,0,0,0}, - {22180,22181,21518 ,9672,9673,9667 ,0,0,0}, {22180,21518,22177 ,9672,9667,9668 ,0,0,0}, - {21518,22182,21516 ,9667,9674,9671 ,0,0,0}, {22182,21518,22181 ,9674,9667,9673 ,0,0,0}, - {22183,21516,22179 ,9675,9671,9670 ,0,0,0}, {22182,22178,21516 ,9674,9669,9671 ,0,0,0}, - {22175,21517,22183 ,9665,9666,9675 ,0,0,0}, {22183,21517,21516 ,9675,9666,9671 ,0,0,0}, - {21726,22184,22185 ,9676,9677,9678 ,0,0,0}, {21803,22186,21757 ,9679,9680,9681 ,0,0,0}, - {22184,21726,22187 ,9677,9676,9682 ,0,0,0}, {22185,22188,21726 ,9678,9676,9676 ,0,0,0}, - {22187,21726,21757 ,9682,9676,9681 ,0,0,0}, {22189,22187,21757 ,9683,9682,9681 ,0,0,0}, - {22189,21757,22186 ,9683,9681,9680 ,0,0,0}, {21760,21784,22190 ,9684,9685,9686 ,0,0,0}, - {21760,22191,22192 ,9684,9687,9688 ,0,0,0}, {22190,22191,21760 ,9686,9687,9684 ,0,0,0}, - {21803,22192,22193 ,9679,9688,9689 ,0,0,0}, {21803,21760,22192 ,9679,9684,9688 ,0,0,0}, - {21803,22194,22195 ,9679,9690,9691 ,0,0,0}, {22193,22194,21803 ,9689,9690,9679 ,0,0,0}, - {21803,22196,22197 ,9679,9692,9693 ,0,0,0}, {22195,22196,21803 ,9691,9692,9679 ,0,0,0}, - {22186,21803,22198 ,9680,9679,9694 ,0,0,0}, {22197,22198,21803 ,9693,9694,9679 ,0,0,0}, - {22067,22176,22028 ,9695,9696,9695 ,0,0,0}, {21518,21992,22176 ,9695,9695,9696 ,0,0,0}, - {22049,22199,22176 ,9695,9696,9696 ,0,0,0}, {22176,22067,22049 ,9696,9695,9695 ,0,0,0}, - {22011,22028,22176 ,9695,9695,9696 ,0,0,0}, {22011,22176,21992 ,9695,9696,9695 ,0,0,0}, - {22200,22201,22175 ,126,126,126 ,0,0,0}, {22183,22202,22200 ,9697,126,126 ,0,0,0}, - {22200,22175,22183 ,126,126,9697 ,0,0,0}, {22203,22204,22205 ,9698,9699,9700 ,0,0,0}, - {22204,22206,22205 ,9699,9701,9700 ,0,0,0}, {22204,22203,22207 ,9699,9698,9702 ,0,0,0}, - {22170,22208,22207 ,9703,9704,9702 ,0,0,0}, {22203,22170,22207 ,9698,9703,9702 ,0,0,0}, - {22168,22208,22170 ,9705,9704,9703 ,0,0,0}, {22208,22168,22209 ,9704,9705,9706 ,0,0,0}, - {22169,22210,22209 ,9707,9708,9706 ,0,0,0}, {22209,22168,22169 ,9706,9705,9707 ,0,0,0}, - {22210,22174,22211 ,9708,9709,9710 ,0,0,0}, {22174,22210,22169 ,9709,9708,9707 ,0,0,0}, - {22201,22211,22175 ,9711,9710,9712 ,0,0,0}, {22174,22175,22211 ,9709,9712,9710 ,0,0,0}, - {22212,22213,22181 ,9713,9714,9715 ,0,0,0}, {22214,22182,22213 ,9716,9717,9714 ,0,0,0}, - {22183,22179,22202 ,126,9718,126 ,0,0,0}, {22178,22215,22179 ,9719,9720,9718 ,0,0,0}, - {22178,22214,22215 ,9719,9716,9720 ,0,0,0}, {22215,22202,22179 ,9720,126,9718 ,0,0,0}, - {22182,22214,22178 ,9717,9716,9719 ,0,0,0}, {22182,22181,22213 ,9717,9715,9714 ,0,0,0}, - {22212,22181,22180 ,9713,9715,9721 ,0,0,0}, {22180,22177,22216 ,9721,9722,9723 ,0,0,0}, - {22216,22212,22180 ,9723,9713,9721 ,0,0,0}, {22217,22177,22176 ,9724,9722,9725 ,0,0,0}, - {22177,22217,22216 ,9722,9724,9723 ,0,0,0}, {22217,22176,22199 ,9724,9725,9725 ,0,0,0}, - {21687,22199,21668 ,9726,9727,9728 ,0,0,0}, {22218,22188,22219 ,9729,9730,9731 ,0,0,0}, - {22188,22212,22216 ,9730,9732,9733 ,0,0,0}, {22216,22217,22188 ,9733,9734,9730 ,0,0,0}, - {22218,22220,22188 ,9729,9735,9730 ,0,0,0}, {22188,22221,22212 ,9730,9736,9732 ,0,0,0}, - {22220,22221,22188 ,9735,9736,9730 ,0,0,0}, {22199,21726,22188 ,9727,9737,9730 ,0,0,0}, - {22217,22199,22188 ,9734,9727,9730 ,0,0,0}, {22199,21706,21726 ,9727,9738,9737 ,0,0,0}, - {21706,22199,21687 ,9738,9727,9726 ,0,0,0}, {22199,21646,21647 ,9727,9739,9740 ,0,0,0}, - {22199,22049,21646 ,9727,9727,9739 ,0,0,0}, {21647,21668,22199 ,9740,9728,9727 ,0,0,0}, - {21881,21901,22222 ,9741,9742,9743 ,0,0,0}, {22190,22223,22191 ,9744,9745,9746 ,0,0,0}, - {22224,22223,21842 ,9747,9745,9748 ,0,0,0}, {22225,22206,22226 ,9749,9750,9751 ,0,0,0}, - {22227,22225,22226 ,9752,9749,9751 ,0,0,0}, {22228,22229,22230 ,9753,9754,9755 ,0,0,0}, - {22229,22227,22230 ,9754,9752,9755 ,0,0,0}, {22223,21822,21842 ,9745,9756,9748 ,0,0,0}, - {22224,21842,21861 ,9747,9748,9757 ,0,0,0}, {22228,22192,22191 ,9753,9758,9746 ,0,0,0}, - {21784,21822,22190 ,9759,9756,9744 ,0,0,0}, {21881,22224,21861 ,9741,9747,9757 ,0,0,0}, - {22222,22231,22224 ,9743,9760,9747 ,0,0,0}, {22224,21881,22222 ,9747,9741,9743 ,0,0,0}, - {22231,22225,22227 ,9760,9749,9752 ,0,0,0}, {22229,22228,22191 ,9754,9753,9746 ,0,0,0}, - {22227,22229,22224 ,9752,9754,9747 ,0,0,0}, {22190,21822,22223 ,9744,9756,9745 ,0,0,0}, - {22227,22224,22231 ,9752,9747,9760 ,0,0,0}, {22226,22230,22227 ,9751,9755,9752 ,0,0,0}, - {22191,22223,22229 ,9746,9745,9754 ,0,0,0}, {22224,22229,22223 ,9747,9754,9745 ,0,0,0}, - {22232,22233,22234 ,9761,9762,9763 ,0,0,0}, {22208,22235,22236 ,9764,9765,9766 ,0,0,0}, - {22208,22209,22235 ,9764,9767,9765 ,0,0,0}, {22226,22204,22237 ,9768,9769,9770 ,0,0,0}, - {22238,22196,22239 ,9771,9772,9773 ,0,0,0}, {22226,22206,22204 ,9768,9774,9769 ,0,0,0}, - {22240,22241,22242 ,9775,9776,9777 ,0,0,0}, {22210,22243,22244 ,9778,9779,9780 ,0,0,0}, - {22201,22241,22245 ,126,9776,9781 ,0,0,0}, {22240,22246,22245 ,9775,9782,9781 ,0,0,0}, - {22198,22197,22247 ,9783,9784,9785 ,0,0,0}, {22197,22238,22247 ,9784,9771,9785 ,0,0,0}, - {22248,22249,22232 ,9786,9787,9761 ,0,0,0}, {22238,22239,22246 ,9771,9773,9782 ,0,0,0}, - {22250,22186,22198 ,9788,9789,9783 ,0,0,0}, {22207,22236,22237 ,9790,9766,9770 ,0,0,0}, - {22210,22244,22209 ,9778,9780,9767 ,0,0,0}, {22237,22234,22230 ,9770,9763,9791 ,0,0,0}, - {22230,22234,22228 ,9791,9763,9792 ,0,0,0}, {22228,22233,22192 ,9792,9762,9793 ,0,0,0}, - {22226,22237,22230 ,9768,9770,9791 ,0,0,0}, {22204,22207,22237 ,9769,9790,9770 ,0,0,0}, - {22233,22228,22234 ,9762,9792,9763 ,0,0,0}, {22233,22249,22193 ,9762,9787,9794 ,0,0,0}, - {22234,22236,22232 ,9763,9766,9761 ,0,0,0}, {22192,22233,22193 ,9793,9762,9794 ,0,0,0}, - {22237,22236,22234 ,9770,9766,9763 ,0,0,0}, {22207,22208,22236 ,9790,9764,9766 ,0,0,0}, - {22249,22233,22232 ,9787,9762,9761 ,0,0,0}, {22249,22251,22194 ,9787,9795,9796 ,0,0,0}, - {22232,22235,22248 ,9761,9765,9786 ,0,0,0}, {22193,22249,22194 ,9794,9787,9796 ,0,0,0}, - {22236,22235,22232 ,9766,9765,9761 ,0,0,0}, {22244,22235,22209 ,9780,9765,9767 ,0,0,0}, - {22251,22249,22248 ,9795,9787,9786 ,0,0,0}, {22251,22239,22195 ,9795,9773,9797 ,0,0,0}, - {22244,22252,22248 ,9780,9798,9786 ,0,0,0}, {22194,22251,22195 ,9796,9795,9797 ,0,0,0}, - {22244,22248,22235 ,9780,9786,9765 ,0,0,0}, {22211,22243,22210 ,9799,9779,9778 ,0,0,0}, - {22239,22251,22252 ,9773,9795,9798 ,0,0,0}, {22248,22252,22251 ,9786,9798,9795 ,0,0,0}, - {22243,22246,22252 ,9779,9782,9798 ,0,0,0}, {22195,22239,22196 ,9797,9773,9772 ,0,0,0}, - {22244,22243,22252 ,9780,9779,9798 ,0,0,0}, {22201,22245,22211 ,126,9781,9799 ,0,0,0}, - {22247,22238,22240 ,9785,9771,9775 ,0,0,0}, {22252,22246,22239 ,9798,9782,9773 ,0,0,0}, - {22246,22240,22238 ,9782,9775,9771 ,0,0,0}, {22196,22238,22197 ,9772,9771,9784 ,0,0,0}, - {22243,22211,22245 ,9779,9799,9781 ,0,0,0}, {22246,22243,22245 ,9782,9779,9781 ,0,0,0}, - {22247,22242,22250 ,9785,9777,9788 ,0,0,0}, {22241,22240,22245 ,9776,9775,9781 ,0,0,0}, - {22250,22198,22247 ,9788,9783,9785 ,0,0,0}, {22242,22247,22240 ,9777,9785,9775 ,0,0,0}, - {22241,22200,22253 ,9800,9801,9802 ,0,0,0}, {22189,22254,22187 ,9803,9804,9682 ,0,0,0}, - {22253,22200,22255 ,9802,9801,9805 ,0,0,0}, {22200,22202,22255 ,9801,126,9805 ,0,0,0}, - {22253,22256,22254 ,9802,9806,9804 ,0,0,0}, {22241,22201,22200 ,9800,126,9801 ,0,0,0}, - {22254,22256,22187 ,9804,9806,9682 ,0,0,0}, {22250,22254,22189 ,9807,9804,9803 ,0,0,0}, - {22186,22250,22189 ,9808,9807,9803 ,0,0,0}, {22250,22242,22254 ,9807,9809,9804 ,0,0,0}, - {22242,22241,22253 ,9809,9800,9802 ,0,0,0}, {22242,22253,22254 ,9809,9802,9804 ,0,0,0}, - {22256,22253,22255 ,9806,9802,9805 ,0,0,0}, {22221,22220,22213 ,9810,9811,9812 ,0,0,0}, - {22255,22202,22215 ,9813,126,9814 ,0,0,0}, {22215,22214,22257 ,9814,9815,9816 ,0,0,0}, - {22215,22257,22255 ,9814,9816,9813 ,0,0,0}, {22212,22221,22213 ,9817,9810,9812 ,0,0,0}, - {22218,22219,22258 ,9818,9819,9820 ,0,0,0}, {22258,22259,22218 ,9820,9821,9818 ,0,0,0}, - {22256,22257,22260 ,9822,9816,9823 ,0,0,0}, {22260,22257,22259 ,9823,9816,9821 ,0,0,0}, - {22219,22188,22185 ,9819,9824,9825 ,0,0,0}, {22256,22260,22187 ,9822,9823,9826 ,0,0,0}, - {22185,22260,22258 ,9825,9823,9820 ,0,0,0}, {22255,22257,22256 ,9813,9816,9822 ,0,0,0}, - {22185,22184,22260 ,9825,9827,9823 ,0,0,0}, {22260,22184,22187 ,9823,9827,9826 ,0,0,0}, - {22257,22214,22259 ,9816,9815,9821 ,0,0,0}, {22213,22259,22214 ,9812,9821,9815 ,0,0,0}, - {22185,22258,22219 ,9825,9820,9819 ,0,0,0}, {22260,22259,22258 ,9823,9821,9820 ,0,0,0}, - {22220,22259,22213 ,9811,9821,9812 ,0,0,0}, {22220,22218,22259 ,9811,9818,9821 ,0,0,0}, - {22261,21956,22262 ,9828,9829,9830 ,0,0,0}, {21975,21504,22173 ,9831,9832,9833 ,0,0,0}, - {22203,22263,22170 ,9834,9835,9836 ,0,0,0}, {22264,22225,22265 ,9837,9838,9839 ,0,0,0}, - {22225,22264,22205 ,9838,9837,9840 ,0,0,0}, {22205,22206,22225 ,9840,9841,9838 ,0,0,0}, - {22231,22265,22225 ,9842,9839,9838 ,0,0,0}, {22261,21939,21956 ,9828,9843,9829 ,0,0,0}, - {22205,22264,22203 ,9840,9837,9834 ,0,0,0}, {22263,22265,22266 ,9835,9839,9844 ,0,0,0}, - {22222,21901,21921 ,9845,9846,9847 ,0,0,0}, {21939,22261,21921 ,9843,9828,9847 ,0,0,0}, - {22266,22172,22171 ,9844,9848,9849 ,0,0,0}, {22262,21975,22173 ,9830,9831,9833 ,0,0,0}, - {22264,22265,22263 ,9837,9839,9835 ,0,0,0}, {22266,22171,22263 ,9844,9849,9835 ,0,0,0}, - {22170,22263,22171 ,9836,9835,9849 ,0,0,0}, {22203,22264,22263 ,9834,9837,9835 ,0,0,0}, - {22261,22231,22222 ,9828,9842,9845 ,0,0,0}, {22266,22261,22262 ,9844,9828,9830 ,0,0,0}, - {22266,22265,22261 ,9844,9839,9828 ,0,0,0}, {22172,22266,22262 ,9848,9844,9830 ,0,0,0}, - {22231,22261,22265 ,9842,9828,9839 ,0,0,0}, {21921,22261,22222 ,9847,9828,9845 ,0,0,0}, - {21975,22262,21956 ,9831,9830,9829 ,0,0,0}, {22262,22173,22172 ,9830,9833,9848 ,0,0,0}, - {21598,21461,21460 ,9850,9851,8275 ,0,0,0}, {22267,22268,21487 ,9852,9853,9854 ,0,0,0}, - {21534,22269,22270 ,9855,9856,9857 ,0,0,0}, {21492,21491,22271 ,9858,9859,9860 ,0,0,0}, - {21531,21566,22272 ,9861,9862,9863 ,0,0,0}, {21495,21496,22273 ,9864,9865,9866 ,0,0,0}, - {21495,22274,21491 ,9864,9867,9859 ,0,0,0}, {22275,21586,22276 ,9868,9869,9870 ,0,0,0}, - {21586,22275,21496 ,9869,9868,9865 ,0,0,0}, {22277,22276,21585 ,9871,9870,9872 ,0,0,0}, - {21586,21585,22276 ,9869,9872,9870 ,0,0,0}, {21474,21475,22277 ,126,126,9871 ,0,0,0}, - {22277,21585,21474 ,9871,9872,126 ,0,0,0}, {22273,22274,21495 ,9866,9867,9864 ,0,0,0}, - {21496,22275,22273 ,9865,9868,9866 ,0,0,0}, {22271,22272,21492 ,9860,9863,9858 ,0,0,0}, - {21491,22274,22271 ,9859,9867,9860 ,0,0,0}, {22267,21531,22272 ,9852,9861,9863 ,0,0,0}, - {21566,21492,22272 ,9862,9858,9863 ,0,0,0}, {22268,21485,21487 ,9853,9873,9854 ,0,0,0}, - {22267,21487,21531 ,9852,9854,9861 ,0,0,0}, {21534,21485,22269 ,9855,9873,9856 ,0,0,0}, - {22268,22269,21485 ,9853,9856,9873 ,0,0,0}, {21598,22270,22278 ,9850,9857,9874 ,0,0,0}, - {21534,22270,21598 ,9855,9857,9850 ,0,0,0}, {21461,21598,22278 ,9851,9850,9874 ,0,0,0}, - {22269,21440,21443 ,730,730,730 ,0,0,0}, {21456,22279,21454 ,730,730,730 ,0,0,0}, - {21456,21459,22280 ,730,730,730 ,0,0,0}, {21452,21454,22281 ,730,730,730 ,0,0,0}, - {21459,21446,22280 ,730,730,730 ,0,0,0}, {22279,21456,22280 ,730,730,730 ,0,0,0}, - {21446,21459,21461 ,730,730,730 ,0,0,0}, {21452,22282,21449 ,730,730,730 ,0,0,0}, - {22278,21446,21461 ,730,730,730 ,0,0,0}, {21428,21440,22267 ,730,730,730 ,0,0,0}, - {21463,21451,22283 ,730,730,730 ,0,0,0}, {22284,21464,21463 ,730,730,730 ,0,0,0}, - {15792,21428,22272 ,730,730,730 ,0,0,0}, {21430,22271,22274 ,730,730,730 ,0,0,0}, - {22285,21467,21464 ,730,730,730 ,0,0,0}, {21467,22286,21468 ,730,730,730 ,0,0,0}, - {21470,21468,22287 ,730,730,730 ,0,0,0}, {22274,21431,21430 ,730,730,730 ,0,0,0}, - {21431,22273,22275 ,730,730,730 ,0,0,0}, {21438,22277,21475 ,730,730,730 ,0,0,0}, - {21475,21473,21438 ,730,730,730 ,0,0,0}, {21470,22288,21473 ,730,730,730 ,0,0,0}, - {22276,21437,22275 ,730,730,730 ,0,0,0}, {21451,21449,22283 ,730,730,730 ,0,0,0}, - {21443,21445,22270 ,730,730,730 ,0,0,0}, {22272,22271,15792 ,730,730,730 ,0,0,0}, - {22279,22281,21454 ,730,730,730 ,0,0,0}, {22281,22282,21452 ,730,730,730 ,0,0,0}, - {22282,22283,21449 ,730,730,730 ,0,0,0}, {22283,22284,21463 ,730,730,730 ,0,0,0}, - {22284,22285,21464 ,730,730,730 ,0,0,0}, {22285,22286,21467 ,730,730,730 ,0,0,0}, - {22286,22287,21468 ,730,730,730 ,0,0,0}, {22287,22288,21470 ,730,730,730 ,0,0,0}, - {22288,21438,21473 ,730,730,730 ,0,0,0}, {21438,21434,22277 ,730,730,730 ,0,0,0}, - {21434,21437,22276 ,730,730,730 ,0,0,0}, {21434,22276,22277 ,730,730,730 ,0,0,0}, - {21437,21431,22275 ,730,730,730 ,0,0,0}, {22273,21431,22274 ,730,730,730 ,0,0,0}, - {21430,15792,22271 ,730,730,730 ,0,0,0}, {21428,22267,22272 ,730,730,730 ,0,0,0}, - {21440,22268,22267 ,730,730,730 ,0,0,0}, {22269,21443,22270 ,730,730,730 ,0,0,0}, - {22268,21440,22269 ,730,730,730 ,0,0,0}, {22270,21445,22278 ,730,730,730 ,0,0,0}, - {21446,22278,21445 ,730,730,730 ,0,0,0}, {21444,22289,22290 ,730,730,9875 ,0,0,0}, - {22291,22290,22292 ,730,9875,730 ,0,0,0}, {22291,22292,22293 ,730,730,9875 ,0,0,0}, - {22294,22290,22291 ,730,9875,730 ,0,0,0}, {22294,21447,22290 ,730,730,9875 ,0,0,0}, - {22293,22292,22295 ,9875,730,9876 ,0,0,0}, {21444,22290,21447 ,730,9875,730 ,0,0,0}, - {22289,21442,22296 ,730,730,9876 ,0,0,0}, {22289,21444,21442 ,730,730,730 ,0,0,0}, - {22296,21442,22297 ,9876,730,730 ,0,0,0}, {22297,21442,21441 ,730,730,9876 ,0,0,0}, - {22297,21441,21439 ,730,9876,730 ,0,0,0}, {22298,21439,21427 ,9877,730,9876 ,0,0,0}, - {21439,22298,22297 ,730,9877,730 ,0,0,0}, {21435,22298,21432 ,730,9877,730 ,0,0,0}, - {21427,21432,22298 ,9876,730,9877 ,0,0,0}, {21436,21429,21433 ,9876,730,9878 ,0,0,0}, - {21432,21429,21436 ,730,730,9876 ,0,0,0}, {21436,21435,21432 ,9876,730,730 ,0,0,0}, - {21438,22288,22298 ,9879,9880,9881 ,0,0,0}, {22290,22289,22285 ,9882,9883,9884 ,0,0,0}, - {22296,22297,22287 ,9885,9886,9887 ,0,0,0}, {22295,22283,22282 ,9888,9889,9890 ,0,0,0}, - {22284,22283,22292 ,9891,9889,9892 ,0,0,0}, {22291,22281,22279 ,9893,9894,9895 ,0,0,0}, - {22281,22291,22293 ,9894,9893,9896 ,0,0,0}, {22280,22294,22279 ,9897,9898,9895 ,0,0,0}, - {22291,22279,22294 ,9893,9895,9898 ,0,0,0}, {22280,21446,21447 ,9897,96,96 ,0,0,0}, - {21447,22294,22280 ,96,9898,9897 ,0,0,0}, {22295,22282,22293 ,9888,9890,9896 ,0,0,0}, - {22282,22281,22293 ,9890,9894,9896 ,0,0,0}, {22285,22284,22290 ,9884,9891,9882 ,0,0,0}, - {22284,22292,22290 ,9891,9892,9882 ,0,0,0}, {22292,22283,22295 ,9892,9889,9888 ,0,0,0}, - {22297,22298,22288 ,9886,9881,9880 ,0,0,0}, {22286,22285,22289 ,9899,9884,9883 ,0,0,0}, - {22288,22287,22297 ,9880,9887,9886 ,0,0,0}, {22286,22296,22287 ,9899,9885,9887 ,0,0,0}, - {22289,22296,22286 ,9883,9885,9899 ,0,0,0}, {22298,21435,21438 ,9881,761,9879 ,0,0,0}, - {21500,21415,21414 ,9900,82,9901 ,0,0,0}, {22299,22300,21582 ,9902,9903,9904 ,0,0,0}, - {21583,22301,21502 ,9905,9906,9907 ,0,0,0}, {22302,21521,22303 ,9908,9909,9910 ,0,0,0}, - {21578,21523,22304 ,9911,9912,9913 ,0,0,0}, {22305,21520,21580 ,9914,9915,9916 ,0,0,0}, - {21520,22305,22303 ,9915,9914,9910 ,0,0,0}, {21512,22306,21580 ,9917,9918,9916 ,0,0,0}, - {22305,21580,22306 ,9914,9916,9918 ,0,0,0}, {21512,21426,21425 ,9917,2619,3135 ,0,0,0}, - {21425,22306,21512 ,3135,9918,9917 ,0,0,0}, {21521,22302,21523 ,9909,9908,9912 ,0,0,0}, - {21521,21520,22303 ,9909,9915,9910 ,0,0,0}, {22299,21578,22304 ,9902,9911,9913 ,0,0,0}, - {22304,21523,22302 ,9913,9912,9908 ,0,0,0}, {22300,21583,21582 ,9903,9905,9904 ,0,0,0}, - {22299,21582,21578 ,9902,9904,9911 ,0,0,0}, {22301,22307,21502 ,9906,9919,9907 ,0,0,0}, - {22300,22301,21583 ,9903,9906,9905 ,0,0,0}, {21415,21500,22307 ,82,9900,9919 ,0,0,0}, - {21502,22307,21500 ,9907,9919,9900 ,0,0,0}, {21422,22299,21423 ,730,730,730 ,0,0,0}, - {21419,22301,21420 ,730,730,730 ,0,0,0}, {21425,22304,22302 ,730,730,730 ,0,0,0}, - {22306,22302,22303 ,730,730,730 ,0,0,0}, {22305,22306,22303 ,730,730,730 ,0,0,0}, - {21423,22304,21425 ,730,730,730 ,0,0,0}, {21425,22302,22306 ,730,730,730 ,0,0,0}, - {21423,22299,22304 ,730,730,730 ,0,0,0}, {21422,22300,22299 ,730,730,730 ,0,0,0}, - {21422,21420,22301 ,730,730,730 ,0,0,0}, {22301,22300,21422 ,730,730,730 ,0,0,0}, - {22307,22301,21419 ,730,730,730 ,0,0,0}, {22307,21416,21415 ,730,730,730 ,0,0,0}, - {21416,22307,21419 ,730,730,730 ,0,0,0}, {21415,21416,21408 ,730,730,730 ,0,0,0}, - {21411,21405,21409 ,730,730,730 ,0,0,0}, {21408,21405,21411 ,730,730,730 ,0,0,0}, - {21411,21415,21408 ,730,730,730 ,0,0,0}, {21593,21393,21394 ,9920,9921,9922 ,0,0,0}, - {22308,22309,21539 ,9902,9903,9923 ,0,0,0}, {21540,22310,21592 ,9924,9906,9925 ,0,0,0}, - {22311,21537,21536 ,9908,9926,9927 ,0,0,0}, {21553,21537,22312 ,9928,9926,8336 ,0,0,0}, - {22313,21597,21489 ,9914,9929,9930 ,0,0,0}, {21536,21597,22314 ,9927,9929,9910 ,0,0,0}, - {21488,22315,21489 ,9931,9918,9930 ,0,0,0}, {22313,21489,22315 ,9914,9930,9918 ,0,0,0}, - {21488,21404,21403 ,9931,96,9932 ,0,0,0}, {21403,22315,21488 ,9932,9918,9931 ,0,0,0}, - {22311,21536,22314 ,9908,9927,9910 ,0,0,0}, {22314,21597,22313 ,9910,9929,9914 ,0,0,0}, - {21553,22312,22308 ,9928,8336,9902 ,0,0,0}, {22312,21537,22311 ,8336,9926,9908 ,0,0,0}, - {22309,21540,21539 ,9903,9924,9923 ,0,0,0}, {22308,21539,21553 ,9902,9923,9928 ,0,0,0}, - {22310,22316,21592 ,9906,9919,9925 ,0,0,0}, {22309,22310,21540 ,9903,9906,9924 ,0,0,0}, - {21393,21593,22316 ,9921,9920,9919 ,0,0,0}, {21592,22316,21593 ,9925,9919,9920 ,0,0,0}, - {21398,22308,21400 ,730,730,730 ,0,0,0}, {21395,22310,21397 ,730,730,730 ,0,0,0}, - {21403,22312,22311 ,730,730,730 ,0,0,0}, {22315,22311,22314 ,730,730,730 ,0,0,0}, - {22313,22315,22314 ,730,730,730 ,0,0,0}, {21400,22312,21403 ,730,730,730 ,0,0,0}, - {21403,22311,22315 ,730,730,730 ,0,0,0}, {21400,22308,22312 ,730,730,730 ,0,0,0}, - {21398,22309,22308 ,730,730,730 ,0,0,0}, {21398,21397,22310 ,730,730,730 ,0,0,0}, - {22310,22309,21398 ,730,730,730 ,0,0,0}, {22316,22310,21395 ,730,730,730 ,0,0,0}, - {22316,21383,21393 ,730,730,730 ,0,0,0}, {21383,22316,21395 ,730,730,730 ,0,0,0}, - {21393,21383,21386 ,730,730,730 ,0,0,0}, {21389,21387,21390 ,730,730,730 ,0,0,0}, - {21386,21387,21389 ,730,730,730 ,0,0,0}, {21389,21393,21386 ,730,730,730 ,0,0,0} -// X-Ufo 8ZollPropeller.prt - , {22317,22318,22319 ,9933,9934,9935 ,0,0,0}, {22317,22320,22321 ,9933,9936,9937 ,0,0,0}, - {22321,22318,22317 ,9937,9934,9933 ,0,0,0}, {22322,22320,22323 ,9938,9936,9939 ,0,0,0}, - {22320,22322,22321 ,9936,9938,9937 ,0,0,0}, {22324,22325,22326 ,9940,9941,9942 ,0,0,0}, - {22322,22323,22325 ,9938,9939,9941 ,0,0,0}, {22327,22328,22324 ,9943,2394,9940 ,0,0,0}, - {22327,22329,22328 ,9943,9944,2394 ,0,0,0}, {22327,22324,22326 ,9943,9940,9942 ,0,0,0}, - {22325,22323,22326 ,9941,9939,9942 ,0,0,0}, {22330,22319,22318 ,9945,9935,9934 ,0,0,0}, - {22331,22330,22332 ,9946,9945,9947 ,0,0,0}, {22330,22331,22319 ,9945,9946,9935 ,0,0,0}, - {22333,22334,22332 ,9948,9949,9947 ,0,0,0}, {22331,22332,22334 ,9946,9947,9949 ,0,0,0}, - {22333,22335,22336 ,9948,9950,9951 ,0,0,0}, {22336,22334,22333 ,9951,9949,9948 ,0,0,0}, - {22337,22335,22338 ,9952,9950,9953 ,0,0,0}, {22335,22337,22336 ,9950,9952,9951 ,0,0,0}, - {22337,22338,22339 ,9952,9953,9954 ,0,0,0}, {22340,22341,22342 ,9938,9955,9956 ,0,0,0}, - {22340,22343,22341 ,9938,9937,9955 ,0,0,0}, {22340,22342,22344 ,9938,9956,9941 ,0,0,0}, - {22344,22345,22346 ,9941,9957,9940 ,0,0,0}, {22345,22344,22342 ,9957,9941,9956 ,0,0,0}, - {22347,22346,22345 ,9958,9940,9957 ,0,0,0}, {22348,22341,22343 ,9959,9955,9937 ,0,0,0}, - {22347,22349,22350 ,9958,9960,9961 ,0,0,0}, {22350,22346,22347 ,9961,9940,9958 ,0,0,0}, - {22348,22343,22351 ,9959,9937,9962 ,0,0,0}, {22351,22352,22348 ,9962,9963,9959 ,0,0,0}, - {22353,22352,22354 ,9964,9963,9945 ,0,0,0}, {22351,22354,22352 ,9962,9945,9963 ,0,0,0}, - {22355,22356,22353 ,9947,9965,9964 ,0,0,0}, {22353,22354,22355 ,9964,9945,9947 ,0,0,0}, - {22357,22358,22356 ,9948,9950,9965 ,0,0,0}, {22357,22356,22355 ,9948,9965,9947 ,0,0,0}, - {22359,22358,22360 ,9966,9950,9967 ,0,0,0}, {22358,22359,22356 ,9950,9966,9965 ,0,0,0}, - {22359,22360,22361 ,9966,9967,9968 ,0,0,0}, {22362,22363,15837 ,9969,9970,9971 ,0,0,0}, - {22364,22365,22366 ,9972,9973,9974 ,0,0,0}, {22367,22362,15837 ,9975,9969,9971 ,0,0,0}, - {22364,22366,22368 ,9972,9974,9976 ,0,0,0}, {22365,22364,22367 ,9973,9972,9975 ,0,0,0}, - {22365,22367,15837 ,9973,9975,9971 ,0,0,0}, {22369,22370,22371 ,9977,9978,9979 ,0,0,0}, - {22371,22368,22372 ,9979,9976,9980 ,0,0,0}, {22369,22371,22372 ,9977,9979,9980 ,0,0,0}, - {22370,22369,22373 ,9978,9977,9981 ,0,0,0}, {22372,22368,22366 ,9980,9976,9974 ,0,0,0}, - {22362,22374,22363 ,9969,9945,9970 ,0,0,0}, {22375,22374,22376 ,9982,9945,9983 ,0,0,0}, - {22374,22375,22363 ,9945,9982,9970 ,0,0,0}, {22377,22378,22376 ,9984,9985,9983 ,0,0,0}, - {22375,22376,22378 ,9982,9983,9985 ,0,0,0}, {22377,22379,22380 ,9984,9986,9987 ,0,0,0}, - {22380,22378,22377 ,9987,9985,9984 ,0,0,0}, {22381,22379,22382 ,9988,9986,21 ,0,0,0}, - {22379,22381,22380 ,9986,9988,9987 ,0,0,0}, {22383,22384,22385 ,9989,9990,9991 ,0,0,0}, - {22385,22384,22386 ,9991,9990,9992 ,0,0,0}, {22387,22384,22383 ,9993,9990,9989 ,0,0,0}, - {22388,22385,22386 ,9994,9991,9992 ,0,0,0}, {22387,22383,22389 ,9993,9989,9995 ,0,0,0}, - {22389,22390,22391 ,9995,9996,9997 ,0,0,0}, {22390,22389,22383 ,9996,9995,9989 ,0,0,0}, - {22388,22386,22392 ,9994,9992,9998 ,0,0,0}, {22393,22394,22391 ,9999,10000,9997 ,0,0,0}, - {22391,22390,22393 ,9997,9996,9999 ,0,0,0}, {22394,22395,22396 ,10000,9961,10001 ,0,0,0}, - {22397,22394,22393 ,10002,10000,9999 ,0,0,0}, {22397,22395,22394 ,10002,9961,10000 ,0,0,0}, - {22386,22398,22392 ,9992,10003,9998 ,0,0,0}, {22398,22399,22400 ,10003,10004,10005 ,0,0,0}, - {22400,22392,22398 ,10005,9998,10003 ,0,0,0}, {22401,22399,22402 ,10006,10004,10007 ,0,0,0}, - {22399,22401,22400 ,10004,10006,10005 ,0,0,0}, {22403,22404,22402 ,10008,10009,10007 ,0,0,0}, - {22401,22402,22404 ,10006,10007,10009 ,0,0,0}, {22403,22405,22406 ,10008,10010,10011 ,0,0,0}, - {22406,22404,22403 ,10011,10009,10008 ,0,0,0}, {22407,22405,22408 ,10012,10010,10013 ,0,0,0}, - {22405,22407,22406 ,10010,10012,10011 ,0,0,0}, {22407,22408,22409 ,10012,10013,10014 ,0,0,0}, - {22409,22408,22410 ,10014,10013,10015 ,0,0,0}, {22411,22412,22413 ,10016,10017,10018 ,0,0,0}, - {22414,22415,22416 ,10019,10020,10021 ,0,0,0}, {22417,22418,22419 ,10022,10023,10024 ,0,0,0}, - {22420,22421,22422 ,10025,10026,10027 ,0,0,0}, {22423,22424,22425 ,10028,10029,10030 ,0,0,0}, - {22425,22339,22423 ,10030,10031,10028 ,0,0,0}, {22426,22427,22428 ,10032,10033,10034 ,0,0,0}, - {22404,22429,22401 ,10035,10036,10037 ,0,0,0}, {22430,22428,22431 ,10038,10034,10039 ,0,0,0}, - {22432,22433,22434 ,10040,10041,10042 ,0,0,0}, {22435,22436,22437 ,10043,10044,10045 ,0,0,0}, - {22438,22439,22440 ,10046,10047,10048 ,0,0,0}, {22441,22429,22434 ,10049,10036,10042 ,0,0,0}, - {22442,22353,22356 ,10050,10051,10052 ,0,0,0}, {22443,22444,22440 ,10053,10054,10048 ,0,0,0}, - {22445,22446,22447 ,10055,10056,10057 ,0,0,0}, {22448,22449,22445 ,10058,10059,10055 ,0,0,0}, - {22450,22451,22448 ,10060,10061,10058 ,0,0,0}, {22452,22448,22451 ,10062,10058,10061 ,0,0,0}, - {22453,22451,22450 ,10063,10061,10060 ,0,0,0}, {22454,22455,22456 ,10064,10065,10066 ,0,0,0}, - {22457,22442,22446 ,10067,10050,10056 ,0,0,0}, {22458,22459,22454 ,10068,10069,10064 ,0,0,0}, - {22407,22409,22434 ,10070,10071,10042 ,0,0,0}, {22436,22460,22437 ,10044,10072,10045 ,0,0,0}, - {22427,22461,22428 ,10033,10073,10034 ,0,0,0}, {22462,22463,22464 ,10074,10075,10076 ,0,0,0}, - {22385,22465,22383 ,10077,10078,10079 ,0,0,0}, {22422,22461,22466 ,10027,10073,10080 ,0,0,0}, - {22467,22336,22468 ,10081,10082,10083 ,0,0,0}, {22469,22470,22420 ,10084,10085,10025 ,0,0,0}, - {22415,22471,22472 ,10020,10086,10087 ,0,0,0}, {22473,22474,22475 ,10088,10089,10090 ,0,0,0}, - {22414,22416,22476 ,10019,10021,10091 ,0,0,0}, {22412,22411,22477 ,10017,10016,10092 ,0,0,0}, - {22478,22416,22473 ,10093,10021,10088 ,0,0,0}, {22479,22480,22481 ,10094,10095,10096 ,0,0,0}, - {22480,22477,22411 ,10095,10092,10016 ,0,0,0}, {22319,22482,22317 ,10097,10098,10099 ,0,0,0}, - {22483,22413,22484 ,10100,10018,10101 ,0,0,0}, {22414,22485,22486 ,10019,10102,10103 ,0,0,0}, - {22470,22395,22487 ,10085,10104,10105 ,0,0,0}, {22473,22416,22415 ,10088,10021,10020 ,0,0,0}, - {22473,22472,22488 ,10088,10087,10106 ,0,0,0}, {22415,22472,22473 ,10020,10087,10088 ,0,0,0}, - {22489,22490,22418 ,10107,10108,10023 ,0,0,0}, {22478,22417,22491 ,10093,10022,10109 ,0,0,0}, - {22413,22327,22326 ,10018,10110,10111 ,0,0,0}, {22492,22490,22489 ,10112,10108,10107 ,0,0,0}, - {22412,22492,22489 ,10017,10112,10107 ,0,0,0}, {22480,22411,22481 ,10095,10016,10096 ,0,0,0}, - {22477,22492,22412 ,10092,10112,10017 ,0,0,0}, {22484,22413,22326 ,10101,10018,10111 ,0,0,0}, - {22413,22483,22493 ,10018,10100,10113 ,0,0,0}, {22482,22484,22317 ,10098,10101,10099 ,0,0,0}, - {22484,22482,22483 ,10101,10098,10100 ,0,0,0}, {22331,22467,22319 ,10114,10081,10097 ,0,0,0}, - {22336,22467,22334 ,10082,10081,10115 ,0,0,0}, {22467,22482,22319 ,10081,10098,10097 ,0,0,0}, - {22468,22494,22467 ,10083,10116,10081 ,0,0,0}, {22337,22468,22336 ,10117,10083,10082 ,0,0,0}, - {22468,22339,22425 ,10083,10031,10030 ,0,0,0}, {22388,22495,22465 ,10118,10119,10078 ,0,0,0}, - {22496,22431,22428 ,10120,10039,10034 ,0,0,0}, {22436,22497,22498 ,10044,10121,10122 ,0,0,0}, - {22347,22497,22349 ,10123,10121,10124 ,0,0,0}, {22496,22499,22500 ,10120,10125,10126 ,0,0,0}, - {22430,22426,22428 ,10038,10032,10034 ,0,0,0}, {22385,22388,22465 ,10077,10118,10078 ,0,0,0}, - {22427,22501,22461 ,10033,10127,10073 ,0,0,0}, {22428,22461,22502 ,10034,10073,10128 ,0,0,0}, - {22461,22422,22421 ,10073,10027,10026 ,0,0,0}, {22470,22421,22420 ,10085,10026,10025 ,0,0,0}, - {22461,22421,22503 ,10073,10026,10129 ,0,0,0}, {22504,22487,22462 ,10130,10105,10074 ,0,0,0}, - {22470,22505,22421 ,10085,10131,10026 ,0,0,0}, {22415,22486,22425 ,10020,10103,10030 ,0,0,0}, - {22485,22505,22504 ,10102,10131,10130 ,0,0,0}, {22464,22468,22425 ,10076,10083,10030 ,0,0,0}, - {22425,22424,22415 ,10030,10029,10020 ,0,0,0}, {22464,22506,22468 ,10076,10132,10083 ,0,0,0}, - {22507,22464,22463 ,10133,10076,10075 ,0,0,0}, {22465,22508,22463 ,10078,10134,10075 ,0,0,0}, - {22465,22495,22509 ,10078,10119,10135 ,0,0,0}, {22388,22392,22495 ,10118,10136,10119 ,0,0,0}, - {22392,22400,22495 ,10136,10137,10119 ,0,0,0}, {22495,22429,22510 ,10119,10036,10138 ,0,0,0}, - {22404,22434,22429 ,10035,10042,10036 ,0,0,0}, {22406,22434,22404 ,10139,10042,10035 ,0,0,0}, - {22434,22406,22407 ,10042,10139,10070 ,0,0,0}, {22495,22401,22429 ,10119,10037,10036 ,0,0,0}, - {22409,22432,22434 ,10071,10040,10042 ,0,0,0}, {22511,22497,22512 ,10140,10121,10141 ,0,0,0}, - {22459,22458,22513 ,10069,10068,10142 ,0,0,0}, {22514,22445,22454 ,10143,10055,10064 ,0,0,0}, - {22454,22445,22515 ,10064,10055,10144 ,0,0,0}, {22515,22455,22454 ,10144,10065,10064 ,0,0,0}, - {22454,22459,22514 ,10064,10069,10143 ,0,0,0}, {22516,22441,22433 ,10145,10049,10041 ,0,0,0}, - {22460,22459,22513 ,10072,10069,10142 ,0,0,0}, {22460,22513,22517 ,10072,10142,10146 ,0,0,0}, - {22437,22460,22518 ,10045,10072,10147 ,0,0,0}, {22435,22349,22436 ,10043,10124,10044 ,0,0,0}, - {22519,22496,22498 ,10148,10120,10122 ,0,0,0}, {22497,22436,22349 ,10121,10044,10124 ,0,0,0}, - {22432,22409,22520 ,10040,10071,10149 ,0,0,0}, {22431,22432,22521 ,10039,10040,10150 ,0,0,0}, - {22511,22433,22519 ,10140,10041,10148 ,0,0,0}, {22511,22522,22516 ,10140,10151,10145 ,0,0,0}, - {22523,22352,22353 ,10152,10153,10051 ,0,0,0}, {22523,22348,22352 ,10152,10154,10153 ,0,0,0}, - {22524,22523,22444 ,10155,10152,10054 ,0,0,0}, {22522,22512,22524 ,10151,10141,10155 ,0,0,0}, - {22353,22442,22523 ,10051,10050,10152 ,0,0,0}, {22361,22447,22446 ,10156,10057,10056 ,0,0,0}, - {22489,22525,22412 ,10107,10157,10017 ,0,0,0}, {22419,22418,22490 ,10024,10023,10108 ,0,0,0}, - {22478,22526,22418 ,10093,10158,10023 ,0,0,0}, {22329,22327,22525 ,10159,10110,10157 ,0,0,0}, - {22526,22525,22489 ,10158,10157,10107 ,0,0,0}, {22525,22327,22413 ,10157,10110,10018 ,0,0,0}, - {22412,22525,22413 ,10017,10157,10018 ,0,0,0}, {22493,22481,22411 ,10113,10096,10016 ,0,0,0}, - {22417,22478,22418 ,10022,10093,10023 ,0,0,0}, {22491,22476,22416 ,10109,10091,10021 ,0,0,0}, - {22525,22527,22528 ,10157,10160,10161 ,0,0,0}, {22418,22526,22489 ,10023,10158,10107 ,0,0,0}, - {22475,22526,22473 ,10090,10158,10088 ,0,0,0}, {22329,22525,22528 ,10159,10157,10161 ,0,0,0}, - {22326,22323,22484 ,10111,10162,10101 ,0,0,0}, {22493,22411,22413 ,10113,10016,10018 ,0,0,0}, - {22491,22416,22478 ,10109,10021,10093 ,0,0,0}, {22476,22529,22414 ,10091,10163,10019 ,0,0,0}, - {22474,22473,22488 ,10089,10088,10106 ,0,0,0}, {22478,22473,22526 ,10093,10088,10158 ,0,0,0}, - {22527,22526,22475 ,10160,10158,10090 ,0,0,0}, {22526,22527,22525 ,10158,10160,10157 ,0,0,0}, - {22323,22320,22484 ,10162,10164,10101 ,0,0,0}, {22484,22320,22317 ,10101,10164,10099 ,0,0,0}, - {22530,22485,22529 ,10165,10102,10163 ,0,0,0}, {22530,22531,22505 ,10165,10166,10131 ,0,0,0}, - {22471,22415,22532 ,10086,10020,10167 ,0,0,0}, {22424,22532,22415 ,10029,10167,10020 ,0,0,0}, - {22482,22467,22494 ,10098,10081,10116 ,0,0,0}, {22331,22334,22467 ,10114,10115,10081 ,0,0,0}, - {22485,22414,22529 ,10102,10019,10163 ,0,0,0}, {22533,22395,22470 ,10168,10104,10085 ,0,0,0}, - {22425,22486,22462 ,10030,10103,10074 ,0,0,0}, {22414,22486,22415 ,10019,10103,10020 ,0,0,0}, - {22462,22486,22504 ,10074,10103,10130 ,0,0,0}, {22339,22468,22337 ,10031,10083,10117 ,0,0,0}, - {22425,22462,22464 ,10030,10074,10076 ,0,0,0}, {22468,22506,22494 ,10083,10132,10116 ,0,0,0}, - {22530,22505,22485 ,10165,10131,10102 ,0,0,0}, {22534,22505,22531 ,10169,10131,10166 ,0,0,0}, - {22395,22397,22487 ,10104,10170,10105 ,0,0,0}, {22485,22504,22486 ,10102,10130,10103 ,0,0,0}, - {22470,22487,22504 ,10085,10105,10130 ,0,0,0}, {22383,22465,22390 ,10079,10078,10171 ,0,0,0}, - {22463,22462,22487 ,10075,10074,10105 ,0,0,0}, {22506,22464,22507 ,10132,10076,10133 ,0,0,0}, - {22505,22534,22421 ,10131,10169,10026 ,0,0,0}, {22503,22421,22534 ,10129,10026,10169 ,0,0,0}, - {22533,22470,22469 ,10168,10085,10084 ,0,0,0}, {22505,22470,22504 ,10131,10085,10130 ,0,0,0}, - {22397,22393,22487 ,10170,10172,10105 ,0,0,0}, {22487,22393,22390 ,10105,10172,10171 ,0,0,0}, - {22390,22463,22487 ,10171,10075,10105 ,0,0,0}, {22507,22463,22508 ,10133,10075,10134 ,0,0,0}, - {22461,22503,22502 ,10073,10129,10128 ,0,0,0}, {22501,22466,22461 ,10127,10080,10073 ,0,0,0}, - {22508,22465,22509 ,10134,10078,10135 ,0,0,0}, {22390,22465,22463 ,10171,10078,10075 ,0,0,0}, - {22502,22499,22428 ,10128,10125,10034 ,0,0,0}, {22428,22499,22496 ,10034,10125,10120 ,0,0,0}, - {22401,22495,22400 ,10037,10119,10137 ,0,0,0}, {22495,22510,22509 ,10119,10138,10135 ,0,0,0}, - {22496,22432,22431 ,10120,10040,10039 ,0,0,0}, {22500,22535,22498 ,10126,10173,10122 ,0,0,0}, - {22345,22497,22347 ,10174,10121,10123 ,0,0,0}, {22521,22432,22520 ,10150,10040,10149 ,0,0,0}, - {22519,22432,22496 ,10148,10040,10120 ,0,0,0}, {22536,22429,22441 ,10175,10036,10049 ,0,0,0}, - {22434,22433,22441 ,10042,10041,10049 ,0,0,0}, {22510,22429,22536 ,10138,10036,10175 ,0,0,0}, - {22500,22498,22496 ,10126,10122,10120 ,0,0,0}, {22535,22537,22436 ,10173,10176,10044 ,0,0,0}, - {22341,22512,22342 ,10177,10141,10178 ,0,0,0}, {22432,22519,22433 ,10040,10148,10041 ,0,0,0}, - {22519,22498,22497 ,10148,10122,10121 ,0,0,0}, {22441,22538,22539 ,10049,10179,10180 ,0,0,0}, - {22433,22511,22516 ,10041,10140,10145 ,0,0,0}, {22536,22441,22539 ,10175,10049,10180 ,0,0,0}, - {22535,22436,22498 ,10173,10044,10122 ,0,0,0}, {22537,22460,22436 ,10176,10072,10044 ,0,0,0}, - {22512,22345,22342 ,10141,10174,10178 ,0,0,0}, {22519,22497,22511 ,10148,10121,10140 ,0,0,0}, - {22497,22345,22512 ,10121,10174,10141 ,0,0,0}, {22516,22540,22538 ,10145,10181,10179 ,0,0,0}, - {22511,22512,22522 ,10140,10141,10151 ,0,0,0}, {22538,22441,22516 ,10179,10049,10145 ,0,0,0}, - {22459,22460,22537 ,10069,10072,10176 ,0,0,0}, {22517,22518,22460 ,10146,10147,10072 ,0,0,0}, - {22523,22341,22348 ,10152,10177,10154 ,0,0,0}, {22522,22541,22540 ,10151,10182,10181 ,0,0,0}, - {22512,22523,22524 ,10141,10152,10155 ,0,0,0}, {22540,22516,22522 ,10181,10145,10151 ,0,0,0}, - {22454,22456,22458 ,10064,10066,10068 ,0,0,0}, {22514,22542,22445 ,10143,10183,10055 ,0,0,0}, - {22356,22359,22446 ,10052,10184,10056 ,0,0,0}, {22356,22446,22442 ,10052,10056,10050 ,0,0,0}, - {22524,22443,22541 ,10155,10053,10182 ,0,0,0}, {22523,22512,22341 ,10152,10141,10177 ,0,0,0}, - {22523,22442,22444 ,10152,10050,10054 ,0,0,0}, {22541,22522,22524 ,10182,10151,10155 ,0,0,0}, - {22445,22447,22515 ,10055,10057,10144 ,0,0,0}, {22542,22450,22448 ,10183,10060,10058 ,0,0,0}, - {22543,22439,22438 ,10185,10047,10046 ,0,0,0}, {22361,22446,22359 ,10156,10056,10184 ,0,0,0}, - {22446,22449,22457 ,10056,10059,10067 ,0,0,0}, {22438,22444,22442 ,10046,10054,10050 ,0,0,0}, - {22457,22438,22442 ,10067,10046,10050 ,0,0,0}, {22443,22524,22444 ,10053,10155,10054 ,0,0,0}, - {22542,22448,22445 ,10183,10058,10055 ,0,0,0}, {22445,22449,22446 ,10055,10059,10056 ,0,0,0}, - {22452,22544,22449 ,10062,10186,10059 ,0,0,0}, {22448,22452,22449 ,10058,10062,10059 ,0,0,0}, - {22544,22543,22457 ,10186,10185,10067 ,0,0,0}, {22449,22544,22457 ,10059,10186,10067 ,0,0,0}, - {22543,22438,22457 ,10185,10046,10067 ,0,0,0}, {22440,22444,22438 ,10048,10054,10046 ,0,0,0}, - {22545,22546,22547 ,10187,10188,10189 ,0,0,0}, {22548,22549,22546 ,10190,10191,10188 ,0,0,0}, - {22550,22551,22552 ,10192,10193,10194 ,0,0,0}, {22553,22554,22555 ,10195,10196,10197 ,0,0,0}, - {22556,22557,22558 ,10198,10199,10200 ,0,0,0}, {22559,22560,22561 ,10201,10202,10203 ,0,0,0}, - {22562,22563,22564 ,10204,10205,10206 ,0,0,0}, {22565,22566,22567 ,10207,10208,10209 ,0,0,0}, - {22568,22569,22570 ,10210,10211,10212 ,0,0,0}, {22571,22572,22573 ,10213,10214,10215 ,0,0,0}, - {22574,22575,22568 ,10216,10217,10210 ,0,0,0}, {22568,22570,22574 ,10210,10212,10216 ,0,0,0}, - {22575,22576,22577 ,10217,10218,10219 ,0,0,0}, {22576,22575,22574 ,10218,10217,10216 ,0,0,0}, - {22578,22577,22579 ,10220,10219,10221 ,0,0,0}, {22576,22579,22577 ,10218,10221,10219 ,0,0,0}, - {22580,22581,22578 ,10222,10223,10220 ,0,0,0}, {22578,22579,22580 ,10220,10221,10222 ,0,0,0}, - {22582,22581,22580 ,10224,10223,10222 ,0,0,0}, {22569,22573,22570 ,10211,10215,10212 ,0,0,0}, - {22571,22563,22572 ,10213,10205,10214 ,0,0,0}, {22569,22571,22573 ,10211,10213,10215 ,0,0,0}, - {22562,22564,22565 ,10204,10206,10207 ,0,0,0}, {22572,22563,22562 ,10214,10205,10204 ,0,0,0}, - {22567,22566,22558 ,10209,10208,10200 ,0,0,0}, {22565,22564,22566 ,10207,10206,10208 ,0,0,0}, - {22560,22557,22556 ,10202,10199,10198 ,0,0,0}, {22557,22567,22558 ,10199,10209,10200 ,0,0,0}, - {22583,22559,22561 ,10225,10201,10203 ,0,0,0}, {22561,22560,22556 ,10203,10202,10198 ,0,0,0}, - {22550,22583,22551 ,10192,10225,10193 ,0,0,0}, {22583,22550,22559 ,10225,10192,10201 ,0,0,0}, - {22552,22553,22555 ,10194,10195,10197 ,0,0,0}, {22551,22553,22552 ,10193,10195,10194 ,0,0,0}, - {22548,22554,22549 ,10190,10196,10191 ,0,0,0}, {22555,22554,22548 ,10197,10196,10190 ,0,0,0}, - {22547,22584,22545 ,10189,10226,10187 ,0,0,0}, {22546,22549,22547 ,10188,10191,10189 ,0,0,0}, - {22585,22586,22546 ,10227,10228,10229 ,0,0,0}, {22587,22548,22586 ,10230,10231,10228 ,0,0,0}, - {22559,22550,22588 ,10232,10233,10234 ,0,0,0}, {22552,22555,22589 ,10235,10236,10237 ,0,0,0}, - {22557,22590,22567 ,10238,10239,10240 ,0,0,0}, {22591,22592,22560 ,10241,10242,10243 ,0,0,0}, - {22593,22572,22562 ,10244,10245,10246 ,0,0,0}, {22594,22565,22595 ,10247,10248,10249 ,0,0,0}, - {22574,22570,22596 ,10250,10251,10252 ,0,0,0}, {22573,22597,22598 ,10253,10254,10255 ,0,0,0}, - {22599,22576,22574 ,10256,10257,10250 ,0,0,0}, {22574,22596,22599 ,10250,10252,10256 ,0,0,0}, - {22576,22600,22579 ,10257,10258,10259 ,0,0,0}, {22600,22576,22599 ,10258,10257,10256 ,0,0,0}, - {22580,22579,22601 ,10260,10259,10261 ,0,0,0}, {22600,22601,22579 ,10258,10261,10259 ,0,0,0}, - {22602,22582,22580 ,10262,10224,10260 ,0,0,0}, {22580,22601,22602 ,10260,10261,10262 ,0,0,0}, - {22603,22582,22602 ,10263,10224,10262 ,0,0,0}, {22570,22598,22596 ,10251,10255,10252 ,0,0,0}, - {22573,22572,22597 ,10253,10245,10254 ,0,0,0}, {22570,22573,22598 ,10251,10253,10255 ,0,0,0}, - {22593,22562,22594 ,10244,10246,10247 ,0,0,0}, {22597,22572,22593 ,10254,10245,10244 ,0,0,0}, - {22595,22565,22567 ,10249,10248,10240 ,0,0,0}, {22594,22562,22565 ,10247,10246,10248 ,0,0,0}, - {22592,22590,22557 ,10242,10239,10238 ,0,0,0}, {22590,22595,22567 ,10239,10249,10240 ,0,0,0}, - {22559,22591,22560 ,10232,10241,10243 ,0,0,0}, {22560,22592,22557 ,10243,10242,10238 ,0,0,0}, - {22550,22604,22588 ,10233,10264,10234 ,0,0,0}, {22559,22588,22591 ,10232,10234,10241 ,0,0,0}, - {22589,22604,22552 ,10237,10264,10235 ,0,0,0}, {22550,22552,22604 ,10233,10235,10264 ,0,0,0}, - {22587,22555,22548 ,10230,10236,10231 ,0,0,0}, {22589,22555,22587 ,10237,10236,10230 ,0,0,0}, - {22546,22545,22585 ,10229,10187,10227 ,0,0,0}, {22586,22548,22546 ,10228,10231,10229 ,0,0,0}, - {22605,22606,22586 ,10265,10266,10267 ,0,0,0}, {22589,22587,22607 ,10237,10230,10268 ,0,0,0}, - {22591,22588,22608 ,10269,10270,10271 ,0,0,0}, {22604,22609,22610 ,10264,10272,10273 ,0,0,0}, - {22590,22611,22595 ,10274,10275,10276 ,0,0,0}, {22612,22613,22592 ,10277,10278,10279 ,0,0,0}, - {22614,22597,22615 ,10280,10281,10282 ,0,0,0}, {22593,22594,22616 ,10283,10284,10285 ,0,0,0}, - {22599,22596,22617 ,10286,10287,10288 ,0,0,0}, {22598,22618,22596 ,10289,10290,10287 ,0,0,0}, - {22619,22600,22599 ,10291,10292,10286 ,0,0,0}, {22599,22617,22619 ,10286,10288,10291 ,0,0,0}, - {22600,22620,22601 ,10292,10293,10261 ,0,0,0}, {22620,22600,22619 ,10293,10292,10291 ,0,0,0}, - {22602,22601,22621 ,10294,10261,10295 ,0,0,0}, {22620,22621,22601 ,10293,10295,10261 ,0,0,0}, - {22621,22622,22603 ,10295,10296,10263 ,0,0,0}, {22603,22602,22621 ,10263,10294,10295 ,0,0,0}, - {22617,22596,22618 ,10288,10287,10290 ,0,0,0}, {22598,22597,22614 ,10289,10281,10280 ,0,0,0}, - {22598,22614,22618 ,10289,10280,10290 ,0,0,0}, {22615,22593,22616 ,10282,10283,10285 ,0,0,0}, - {22597,22593,22615 ,10281,10283,10282 ,0,0,0}, {22623,22594,22595 ,10297,10284,10276 ,0,0,0}, - {22616,22594,22623 ,10285,10284,10297 ,0,0,0}, {22613,22611,22590 ,10278,10275,10274 ,0,0,0}, - {22611,22623,22595 ,10275,10297,10276 ,0,0,0}, {22591,22612,22592 ,10269,10277,10279 ,0,0,0}, - {22592,22613,22590 ,10279,10278,10274 ,0,0,0}, {22588,22610,22608 ,10270,10273,10271 ,0,0,0}, - {22591,22608,22612 ,10269,10271,10277 ,0,0,0}, {22604,22589,22609 ,10264,10237,10272 ,0,0,0}, - {22588,22604,22610 ,10270,10264,10273 ,0,0,0}, {22607,22587,22606 ,10268,10230,10266 ,0,0,0}, - {22609,22589,22607 ,10272,10237,10268 ,0,0,0}, {22605,22586,22585 ,10265,10267,10227 ,0,0,0}, - {22606,22587,22586 ,10266,10230,10267 ,0,0,0}, {22624,22625,22606 ,10298,10299,10300 ,0,0,0}, - {22609,22607,22626 ,10301,10302,10303 ,0,0,0}, {22612,22608,22627 ,10304,10305,10306 ,0,0,0}, - {22610,22609,22628 ,10307,10301,10308 ,0,0,0}, {22611,22629,22623 ,10309,10310,10311 ,0,0,0}, - {22630,22631,22613 ,10312,10313,10314 ,0,0,0}, {22632,22614,22615 ,10315,10316,10317 ,0,0,0}, - {22633,22616,22634 ,10318,10319,10320 ,0,0,0}, {22635,22617,22636 ,10321,10322,10323 ,0,0,0}, - {22618,22637,22636 ,10324,10325,10323 ,0,0,0}, {22635,22638,22619 ,10321,10326,10327 ,0,0,0}, - {22619,22617,22635 ,10327,10322,10321 ,0,0,0}, {22620,22638,22639 ,10328,10326,10329 ,0,0,0}, - {22638,22620,22619 ,10326,10328,10327 ,0,0,0}, {22640,22621,22639 ,10330,10331,10329 ,0,0,0}, - {22620,22639,22621 ,10328,10329,10331 ,0,0,0}, {22640,22641,22622 ,10330,10332,10296 ,0,0,0}, - {22622,22621,22640 ,10296,10331,10330 ,0,0,0}, {22636,22617,22618 ,10323,10322,10324 ,0,0,0}, - {22637,22614,22632 ,10325,10316,10315 ,0,0,0}, {22618,22614,22637 ,10324,10316,10325 ,0,0,0}, - {22633,22615,22616 ,10318,10317,10319 ,0,0,0}, {22632,22615,22633 ,10315,10317,10318 ,0,0,0}, - {22629,22634,22623 ,10310,10320,10311 ,0,0,0}, {22634,22616,22623 ,10320,10319,10311 ,0,0,0}, - {22613,22631,22611 ,10314,10313,10309 ,0,0,0}, {22631,22629,22611 ,10313,10310,10309 ,0,0,0}, - {22612,22627,22630 ,10304,10306,10312 ,0,0,0}, {22612,22630,22613 ,10304,10312,10314 ,0,0,0}, - {22608,22610,22642 ,10305,10307,10333 ,0,0,0}, {22608,22642,22627 ,10305,10333,10306 ,0,0,0}, - {22628,22609,22626 ,10308,10301,10303 ,0,0,0}, {22642,22610,22628 ,10333,10307,10308 ,0,0,0}, - {22625,22607,22606 ,10299,10302,10300 ,0,0,0}, {22626,22607,22625 ,10303,10302,10299 ,0,0,0}, - {22624,22606,22605 ,10298,10300,10265 ,0,0,0}, {22639,22643,22644 ,10334,10335,10336 ,0,0,0}, - {22641,22640,22645 ,10332,10337,10338 ,0,0,0}, {22646,22636,22647 ,10339,10340,10341 ,0,0,0}, - {22635,22648,22638 ,10342,10343,10344 ,0,0,0}, {22634,22649,22633 ,10345,10346,10347 ,0,0,0}, - {22632,22650,22637 ,10348,10349,10350 ,0,0,0}, {22651,22631,22630 ,10351,10352,10353 ,0,0,0}, - {22652,22629,22653 ,10354,10355,10356 ,0,0,0}, {22654,22642,22655 ,10357,10358,10359 ,0,0,0}, - {22627,22654,22656 ,10360,10357,10361 ,0,0,0}, {22657,22655,22628 ,10362,10359,10363 ,0,0,0}, - {22642,22628,22655 ,10358,10363,10359 ,0,0,0}, {22626,22658,22657 ,10364,10365,10362 ,0,0,0}, - {22657,22628,22626 ,10362,10363,10364 ,0,0,0}, {22658,22625,22659 ,10365,10366,10367 ,0,0,0}, - {22625,22658,22626 ,10366,10365,10364 ,0,0,0}, {22656,22630,22627 ,10361,10353,10360 ,0,0,0}, - {22659,22625,22624 ,10367,10366,10368 ,0,0,0}, {22654,22627,22642 ,10357,10360,10358 ,0,0,0}, - {22651,22653,22631 ,10351,10356,10352 ,0,0,0}, {22656,22651,22630 ,10361,10351,10353 ,0,0,0}, - {22629,22652,22634 ,10355,10354,10345 ,0,0,0}, {22631,22653,22629 ,10352,10356,10355 ,0,0,0}, - {22633,22649,22660 ,10347,10346,10369 ,0,0,0}, {22634,22652,22649 ,10345,10354,10346 ,0,0,0}, - {22660,22650,22632 ,10369,10349,10348 ,0,0,0}, {22632,22633,22660 ,10348,10347,10369 ,0,0,0}, - {22647,22636,22637 ,10341,10340,10350 ,0,0,0}, {22647,22637,22650 ,10341,10350,10349 ,0,0,0}, - {22646,22648,22635 ,10339,10343,10342 ,0,0,0}, {22646,22635,22636 ,10339,10342,10340 ,0,0,0}, - {22638,22643,22639 ,10344,10335,10334 ,0,0,0}, {22648,22643,22638 ,10343,10335,10344 ,0,0,0}, - {22640,22644,22645 ,10337,10336,10338 ,0,0,0}, {22639,22644,22640 ,10334,10336,10337 ,0,0,0}, - {22641,22645,22661 ,10332,10338,10370 ,0,0,0}, {22662,22663,22664 ,10371,10372,10373 ,0,0,0}, - {22665,22666,22667 ,10374,10375,10376 ,0,0,0}, {22666,22668,22669 ,10375,10377,10378 ,0,0,0}, - {22669,22667,22666 ,10378,10376,10375 ,0,0,0}, {22666,22664,22670 ,10375,10373,10379 ,0,0,0}, - {22668,22671,22669 ,10377,10380,10378 ,0,0,0}, {22672,22673,22674 ,10381,10382,10383 ,0,0,0}, - {22624,22663,22659 ,10368,10372,10384 ,0,0,0}, {22675,22676,22677 ,10385,10386,10387 ,0,0,0}, - {22655,22657,22678 ,10388,10389,10390 ,0,0,0}, {22679,22680,22681 ,10391,10392,10393 ,0,0,0}, - {22656,22682,22651 ,10394,10395,10396 ,0,0,0}, {22683,22684,22650 ,10397,10398,10399 ,0,0,0}, - {22685,22686,22681 ,10400,10401,10393 ,0,0,0}, {22687,22688,22689 ,10402,10403,10404 ,0,0,0}, - {22690,22684,22691 ,10405,10398,10406 ,0,0,0}, {22644,22688,22645 ,10407,10403,10408 ,0,0,0}, - {22645,22692,22661 ,10408,10409,10410 ,0,0,0}, {22693,22694,22689 ,10411,10412,10404 ,0,0,0}, - {22645,22688,22692 ,10408,10403,10409 ,0,0,0}, {22695,22687,22696 ,10413,10402,10414 ,0,0,0}, - {22693,22689,22643 ,10411,10404,10415 ,0,0,0}, {22693,22697,22698 ,10411,10416,10417 ,0,0,0}, - {22648,22697,22693 ,10418,10416,10411 ,0,0,0}, {22647,22684,22690 ,10419,10398,10405 ,0,0,0}, - {22697,22690,22699 ,10416,10405,10420 ,0,0,0}, {22697,22646,22690 ,10416,10421,10405 ,0,0,0}, - {22700,22683,22686 ,10422,10397,10401 ,0,0,0}, {22701,22684,22683 ,10423,10398,10397 ,0,0,0}, - {22686,22649,22652 ,10401,10424,10425 ,0,0,0}, {22686,22683,22660 ,10401,10397,10426 ,0,0,0}, - {22651,22679,22653 ,10396,10391,10427 ,0,0,0}, {22653,22681,22652 ,10427,10393,10425 ,0,0,0}, - {22675,22702,22682 ,10385,10428,10395 ,0,0,0}, {22682,22703,22679 ,10395,10429,10391 ,0,0,0}, - {22654,22655,22676 ,10430,10388,10386 ,0,0,0}, {22656,22654,22675 ,10394,10430,10385 ,0,0,0}, - {22673,22704,22678 ,10382,10431,10390 ,0,0,0}, {22677,22676,22704 ,10387,10386,10431 ,0,0,0}, - {22705,22658,22659 ,10432,10433,10384 ,0,0,0}, {22674,22657,22658 ,10383,10389,10433 ,0,0,0}, - {22706,22670,22664 ,10434,10379,10373 ,0,0,0}, {22705,22662,22672 ,10432,10371,10381 ,0,0,0}, - {22664,22663,22706 ,10373,10372,10434 ,0,0,0}, {22668,22666,22670 ,10377,10375,10379 ,0,0,0}, - {22707,22665,22667 ,10435,10374,10376 ,0,0,0}, {22708,22665,22707 ,10436,10374,10435 ,0,0,0}, - {22663,22624,22706 ,10372,10368,10434 ,0,0,0}, {22664,22665,22662 ,10373,10374,10371 ,0,0,0}, - {22659,22663,22705 ,10384,10372,10432 ,0,0,0}, {22666,22665,22664 ,10375,10374,10373 ,0,0,0}, - {22709,22708,22707 ,10437,10436,10435 ,0,0,0}, {22710,22708,22709 ,10438,10436,10437 ,0,0,0}, - {22663,22662,22705 ,10372,10371,10432 ,0,0,0}, {22662,22708,22672 ,10371,10436,10381 ,0,0,0}, - {22658,22705,22674 ,10433,10432,10383 ,0,0,0}, {22665,22708,22662 ,10374,10436,10371 ,0,0,0}, - {22711,22710,22709 ,10439,10438,10437 ,0,0,0}, {22712,22710,22711 ,10440,10438,10439 ,0,0,0}, - {22705,22672,22674 ,10432,10381,10383 ,0,0,0}, {22672,22710,22673 ,10381,10438,10382 ,0,0,0}, - {22657,22674,22678 ,10389,10383,10390 ,0,0,0}, {22708,22710,22672 ,10436,10438,10381 ,0,0,0}, - {22713,22712,22711 ,10441,10440,10439 ,0,0,0}, {22714,22712,22713 ,10442,10440,10441 ,0,0,0}, - {22674,22673,22678 ,10383,10382,10390 ,0,0,0}, {22673,22712,22704 ,10382,10440,10431 ,0,0,0}, - {22655,22678,22676 ,10388,10390,10386 ,0,0,0}, {22710,22712,22673 ,10438,10440,10382 ,0,0,0}, - {22715,22714,22713 ,10443,10442,10441 ,0,0,0}, {22716,22714,22715 ,10444,10442,10443 ,0,0,0}, - {22678,22704,22676 ,10390,10431,10386 ,0,0,0}, {22704,22714,22677 ,10431,10442,10387 ,0,0,0}, - {22654,22676,22675 ,10430,10386,10385 ,0,0,0}, {22712,22714,22704 ,10440,10442,10431 ,0,0,0}, - {22717,22716,22715 ,10445,10444,10443 ,0,0,0}, {22718,22719,22696 ,10446,10447,10414 ,0,0,0}, - {22720,22716,22717 ,10448,10444,10445 ,0,0,0}, {22677,22716,22702 ,10387,10444,10428 ,0,0,0}, - {22656,22675,22682 ,10394,10385,10395 ,0,0,0}, {22714,22716,22677 ,10442,10444,10387 ,0,0,0}, - {22721,22720,22717 ,10449,10448,10445 ,0,0,0}, {22722,22723,22720 ,10450,10451,10448 ,0,0,0}, - {22677,22702,22675 ,10387,10428,10385 ,0,0,0}, {22702,22720,22703 ,10428,10448,10429 ,0,0,0}, - {22651,22682,22679 ,10396,10395,10391 ,0,0,0}, {22716,22720,22702 ,10444,10448,10428 ,0,0,0}, - {22721,22722,22720 ,10449,10450,10448 ,0,0,0}, {22724,22725,22723 ,10452,10453,10451 ,0,0,0}, - {22702,22703,22682 ,10428,10429,10395 ,0,0,0}, {22703,22723,22680 ,10429,10451,10392 ,0,0,0}, - {22653,22679,22681 ,10427,10391,10393 ,0,0,0}, {22720,22723,22703 ,10448,10451,10429 ,0,0,0}, - {22722,22724,22723 ,10450,10452,10451 ,0,0,0}, {22726,22727,22725 ,10454,10455,10453 ,0,0,0}, - {22703,22680,22679 ,10429,10392,10391 ,0,0,0}, {22725,22685,22680 ,10453,10400,10392 ,0,0,0}, - {22652,22681,22686 ,10425,10393,10401 ,0,0,0}, {22723,22725,22680 ,10451,10453,10392 ,0,0,0}, - {22724,22726,22725 ,10452,10454,10453 ,0,0,0}, {22727,22728,22729 ,10455,10456,10457 ,0,0,0}, - {22680,22685,22681 ,10392,10400,10393 ,0,0,0}, {22727,22700,22685 ,10455,10422,10400 ,0,0,0}, - {22660,22649,22686 ,10426,10424,10401 ,0,0,0}, {22725,22727,22685 ,10453,10455,10400 ,0,0,0}, - {22726,22728,22727 ,10454,10456,10455 ,0,0,0}, {22729,22730,22731 ,10457,10458,10459 ,0,0,0}, - {22685,22700,22686 ,10400,10422,10401 ,0,0,0}, {22729,22701,22700 ,10457,10423,10422 ,0,0,0}, - {22650,22660,22683 ,10399,10426,10397 ,0,0,0}, {22727,22729,22700 ,10455,10457,10422 ,0,0,0}, - {22728,22730,22729 ,10456,10458,10457 ,0,0,0}, {22731,22732,22733 ,10459,10460,10461 ,0,0,0}, - {22700,22701,22683 ,10422,10423,10397 ,0,0,0}, {22731,22691,22701 ,10459,10406,10423 ,0,0,0}, - {22647,22650,22684 ,10419,10399,10398 ,0,0,0}, {22729,22731,22701 ,10457,10459,10423 ,0,0,0}, - {22730,22732,22731 ,10458,10460,10459 ,0,0,0}, {22733,22734,22735 ,10461,10462,10463 ,0,0,0}, - {22701,22691,22684 ,10423,10406,10398 ,0,0,0}, {22733,22699,22691 ,10461,10420,10406 ,0,0,0}, - {22646,22647,22690 ,10421,10419,10405 ,0,0,0}, {22731,22733,22691 ,10459,10461,10406 ,0,0,0}, - {22732,22734,22733 ,10460,10462,10461 ,0,0,0}, {22735,22736,22737 ,10463,10464,10465 ,0,0,0}, - {22691,22699,22690 ,10406,10420,10405 ,0,0,0}, {22735,22698,22699 ,10463,10417,10420 ,0,0,0}, - {22648,22646,22697 ,10418,10421,10416 ,0,0,0}, {22733,22735,22699 ,10461,10463,10420 ,0,0,0}, - {22734,22736,22735 ,10462,10464,10463 ,0,0,0}, {22696,22737,22718 ,10414,10465,10446 ,0,0,0}, - {22699,22698,22697 ,10420,10417,10416 ,0,0,0}, {22698,22737,22694 ,10417,10465,10412 ,0,0,0}, - {22643,22648,22693 ,10415,10418,10411 ,0,0,0}, {22735,22737,22698 ,10463,10465,10417 ,0,0,0}, - {22736,22718,22737 ,10464,10446,10465 ,0,0,0}, {22644,22689,22688 ,10407,10404,10403 ,0,0,0}, - {22698,22694,22693 ,10417,10412,10411 ,0,0,0}, {22696,22687,22694 ,10414,10402,10412 ,0,0,0}, - {22644,22643,22689 ,10407,10415,10404 ,0,0,0}, {22696,22694,22737 ,10414,10412,10465 ,0,0,0}, - {22719,22695,22696 ,10447,10413,10414 ,0,0,0}, {22738,22687,22695 ,10466,10402,10413 ,0,0,0}, - {22694,22687,22689 ,10412,10402,10404 ,0,0,0}, {22687,22738,22688 ,10402,10466,10403 ,0,0,0}, - {22692,22688,22738 ,10409,10403,10466 ,0,0,0}, {22739,22740,22669 ,10467,10468,10469 ,0,0,0}, - {22707,22667,22741 ,10470,10471,10472 ,0,0,0}, {22713,22711,22742 ,10473,10474,10475 ,0,0,0}, - {22709,22743,22744 ,10476,10477,10478 ,0,0,0}, {22745,22746,22721 ,10479,10480,10481 ,0,0,0}, - {22747,22748,22715 ,10482,10483,10484 ,0,0,0}, {22749,22726,22750 ,10485,10486,10487 ,0,0,0}, - {22724,22722,22751 ,10488,10489,10490 ,0,0,0}, {22732,22730,22752 ,10491,10492,10493 ,0,0,0}, - {22728,22753,22730 ,10494,10495,10492 ,0,0,0}, {22754,22734,22732 ,10496,10497,10491 ,0,0,0}, - {22732,22752,22754 ,10491,10493,10496 ,0,0,0}, {22734,22755,22736 ,10497,10498,10499 ,0,0,0}, - {22755,22734,22754 ,10498,10497,10496 ,0,0,0}, {22718,22736,22756 ,10500,10499,10501 ,0,0,0}, - {22755,22756,22736 ,10498,10501,10499 ,0,0,0}, {22756,22757,22719 ,10501,10502,10447 ,0,0,0}, - {22719,22718,22756 ,10447,10500,10501 ,0,0,0}, {22752,22730,22753 ,10493,10492,10495 ,0,0,0}, - {22728,22726,22749 ,10494,10486,10485 ,0,0,0}, {22728,22749,22753 ,10494,10485,10495 ,0,0,0}, - {22750,22724,22751 ,10487,10488,10490 ,0,0,0}, {22726,22724,22750 ,10486,10488,10487 ,0,0,0}, - {22746,22722,22721 ,10480,10489,10481 ,0,0,0}, {22751,22722,22746 ,10490,10489,10480 ,0,0,0}, - {22748,22745,22717 ,10483,10479,10503 ,0,0,0}, {22745,22721,22717 ,10479,10481,10503 ,0,0,0}, - {22713,22747,22715 ,10473,10482,10484 ,0,0,0}, {22715,22748,22717 ,10484,10483,10503 ,0,0,0}, - {22711,22744,22742 ,10474,10478,10475 ,0,0,0}, {22713,22742,22747 ,10473,10475,10482 ,0,0,0}, - {22709,22707,22743 ,10476,10470,10477 ,0,0,0}, {22711,22709,22744 ,10474,10476,10478 ,0,0,0}, - {22741,22667,22740 ,10472,10471,10468 ,0,0,0}, {22743,22707,22741 ,10477,10470,10472 ,0,0,0}, - {22739,22669,22671 ,10467,10469,10504 ,0,0,0}, {22740,22667,22669 ,10468,10471,10469 ,0,0,0}, - {22758,22759,22740 ,10505,10506,10507 ,0,0,0}, {22741,22740,22760 ,10508,10507,10509 ,0,0,0}, - {22742,22744,22761 ,10510,10511,10512 ,0,0,0}, {22743,22762,22763 ,10513,10514,10515 ,0,0,0}, - {22748,22764,22745 ,10516,10517,10518 ,0,0,0}, {22765,22766,22747 ,10519,10520,10521 ,0,0,0}, - {22767,22750,22751 ,10522,10523,10524 ,0,0,0}, {22768,22746,22769 ,10525,10526,10527 ,0,0,0}, - {22752,22753,22770 ,10528,10529,10530 ,0,0,0}, {22749,22771,22772 ,10531,10532,10533 ,0,0,0}, - {22773,22754,22752 ,10534,10535,10528 ,0,0,0}, {22752,22770,22773 ,10528,10530,10534 ,0,0,0}, - {22754,22774,22755 ,10535,10536,10537 ,0,0,0}, {22774,22754,22773 ,10536,10535,10534 ,0,0,0}, - {22756,22755,22775 ,10538,10537,10539 ,0,0,0}, {22774,22775,22755 ,10536,10539,10537 ,0,0,0}, - {22776,22757,22756 ,10540,10502,10538 ,0,0,0}, {22756,22775,22776 ,10538,10539,10540 ,0,0,0}, - {22777,22757,22776 ,10541,10502,10540 ,0,0,0}, {22753,22772,22770 ,10529,10533,10530 ,0,0,0}, - {22749,22750,22771 ,10531,10523,10532 ,0,0,0}, {22753,22749,22772 ,10529,10531,10533 ,0,0,0}, - {22767,22751,22768 ,10522,10524,10525 ,0,0,0}, {22771,22750,22767 ,10532,10523,10522 ,0,0,0}, - {22769,22746,22745 ,10527,10526,10518 ,0,0,0}, {22768,22751,22746 ,10525,10524,10526 ,0,0,0}, - {22766,22764,22748 ,10520,10517,10516 ,0,0,0}, {22764,22769,22745 ,10517,10527,10518 ,0,0,0}, - {22742,22765,22747 ,10510,10519,10521 ,0,0,0}, {22747,22766,22748 ,10521,10520,10516 ,0,0,0}, - {22744,22763,22761 ,10511,10515,10512 ,0,0,0}, {22742,22761,22765 ,10510,10512,10519 ,0,0,0}, - {22743,22741,22762 ,10513,10508,10514 ,0,0,0}, {22744,22743,22763 ,10511,10513,10515 ,0,0,0}, - {22760,22740,22759 ,10509,10507,10506 ,0,0,0}, {22762,22741,22760 ,10514,10508,10509 ,0,0,0}, - {22758,22740,22739 ,10505,10507,10467 ,0,0,0}, {22778,22779,22759 ,10542,10543,10544 ,0,0,0}, - {22780,22760,22779 ,10545,10509,10543 ,0,0,0}, {22765,22761,22781 ,10546,10547,10548 ,0,0,0}, - {22763,22762,22782 ,10515,10514,10549 ,0,0,0}, {22764,22783,22769 ,10550,10551,10552 ,0,0,0}, - {22784,22785,22766 ,10553,10554,10555 ,0,0,0}, {22786,22771,22767 ,10556,10557,10558 ,0,0,0}, - {22787,22768,22788 ,10559,10560,10561 ,0,0,0}, {22773,22770,22789 ,10534,10530,10562 ,0,0,0}, - {22772,22790,22791 ,10563,10564,10565 ,0,0,0}, {22792,22774,22773 ,10566,10536,10534 ,0,0,0}, - {22773,22789,22792 ,10534,10562,10566 ,0,0,0}, {22774,22793,22775 ,10536,10567,10539 ,0,0,0}, - {22793,22774,22792 ,10567,10536,10566 ,0,0,0}, {22776,22775,22794 ,10568,10539,10569 ,0,0,0}, - {22793,22794,22775 ,10567,10569,10539 ,0,0,0}, {22795,22777,22776 ,10570,10541,10568 ,0,0,0}, - {22776,22794,22795 ,10568,10569,10570 ,0,0,0}, {22796,22777,22795 ,10571,10541,10570 ,0,0,0}, - {22770,22791,22789 ,10530,10565,10562 ,0,0,0}, {22772,22771,22790 ,10563,10557,10564 ,0,0,0}, - {22770,22772,22791 ,10530,10563,10565 ,0,0,0}, {22786,22767,22787 ,10556,10558,10559 ,0,0,0}, - {22790,22771,22786 ,10564,10557,10556 ,0,0,0}, {22788,22768,22769 ,10561,10560,10552 ,0,0,0}, - {22787,22767,22768 ,10559,10558,10560 ,0,0,0}, {22785,22783,22764 ,10554,10551,10550 ,0,0,0}, - {22783,22788,22769 ,10551,10561,10552 ,0,0,0}, {22765,22784,22766 ,10546,10553,10555 ,0,0,0}, - {22766,22785,22764 ,10555,10554,10550 ,0,0,0}, {22761,22797,22781 ,10547,10572,10548 ,0,0,0}, - {22765,22781,22784 ,10546,10548,10553 ,0,0,0}, {22782,22797,22763 ,10549,10572,10515 ,0,0,0}, - {22761,22763,22797 ,10547,10515,10572 ,0,0,0}, {22780,22762,22760 ,10545,10514,10509 ,0,0,0}, - {22782,22762,22780 ,10549,10514,10545 ,0,0,0}, {22759,22758,22778 ,10544,10505,10542 ,0,0,0}, - {22779,22760,22759 ,10543,10509,10544 ,0,0,0}, {22798,22799,22779 ,10573,10574,10575 ,0,0,0}, - {22800,22780,22799 ,10576,10577,10574 ,0,0,0}, {22784,22781,22801 ,10578,10579,10580 ,0,0,0}, - {22797,22782,22802 ,10581,10582,10583 ,0,0,0}, {22783,22803,22788 ,10584,10585,10586 ,0,0,0}, - {22804,22805,22785 ,10587,10588,10589 ,0,0,0}, {22806,22790,22786 ,10590,10591,10592 ,0,0,0}, - {22807,22787,22808 ,10593,10594,10595 ,0,0,0}, {22809,22789,22810 ,10596,10597,10598 ,0,0,0}, - {22791,22790,22811 ,10599,10591,10600 ,0,0,0}, {22812,22793,22792 ,10601,10602,10603 ,0,0,0}, - {22792,22809,22812 ,10603,10596,10601 ,0,0,0}, {22793,22813,22794 ,10602,10604,10605 ,0,0,0}, - {22813,22793,22812 ,10604,10602,10601 ,0,0,0}, {22795,22794,22814 ,10606,10605,10607 ,0,0,0}, - {22813,22814,22794 ,10604,10607,10605 ,0,0,0}, {22815,22796,22795 ,10608,10571,10606 ,0,0,0}, - {22795,22814,22815 ,10606,10607,10608 ,0,0,0}, {22816,22796,22815 ,10609,10571,10608 ,0,0,0}, - {22809,22792,22789 ,10596,10603,10597 ,0,0,0}, {22810,22791,22811 ,10598,10599,10600 ,0,0,0}, - {22789,22791,22810 ,10597,10599,10598 ,0,0,0}, {22786,22807,22806 ,10592,10593,10590 ,0,0,0}, - {22811,22790,22806 ,10600,10591,10590 ,0,0,0}, {22808,22787,22788 ,10595,10594,10586 ,0,0,0}, - {22807,22786,22787 ,10593,10592,10594 ,0,0,0}, {22805,22803,22783 ,10588,10585,10584 ,0,0,0}, - {22803,22808,22788 ,10585,10595,10586 ,0,0,0}, {22784,22804,22785 ,10578,10587,10589 ,0,0,0}, - {22785,22805,22783 ,10589,10588,10584 ,0,0,0}, {22781,22817,22801 ,10579,10610,10580 ,0,0,0}, - {22784,22801,22804 ,10578,10580,10587 ,0,0,0}, {22802,22817,22797 ,10583,10610,10581 ,0,0,0}, - {22781,22797,22817 ,10579,10581,10610 ,0,0,0}, {22800,22782,22780 ,10576,10582,10577 ,0,0,0}, - {22802,22782,22800 ,10583,10582,10576 ,0,0,0}, {22779,22778,22798 ,10575,10542,10573 ,0,0,0}, - {22799,22780,22779 ,10574,10577,10575 ,0,0,0}, {22818,22798,22819 ,10611,10573,10612 ,0,0,0}, - {22820,22802,22821 ,10613,10614,10615 ,0,0,0}, {22822,22800,22799 ,10616,10617,10618 ,0,0,0}, - {22804,22823,22805 ,10619,10620,10621 ,0,0,0}, {22817,22824,22801 ,10622,10623,10624 ,0,0,0}, - {22825,22807,22808 ,10625,10626,10627 ,0,0,0}, {22826,22803,22827 ,10628,10629,10630 ,0,0,0}, - {22828,22811,22829 ,10631,10632,10633 ,0,0,0}, {22806,22830,22829 ,10634,10635,10633 ,0,0,0}, - {22812,22809,22831 ,10636,10637,10638 ,0,0,0}, {22810,22832,22809 ,10639,10640,10637 ,0,0,0}, - {22833,22813,22812 ,10641,10642,10636 ,0,0,0}, {22812,22831,22833 ,10636,10638,10641 ,0,0,0}, - {22813,22834,22814 ,10642,10643,10644 ,0,0,0}, {22834,22813,22833 ,10643,10642,10641 ,0,0,0}, - {22815,22814,22835 ,10645,10644,10646 ,0,0,0}, {22834,22835,22814 ,10643,10646,10644 ,0,0,0}, - {22836,22816,22815 ,10647,10609,10645 ,0,0,0}, {22815,22835,22836 ,10645,10646,10647 ,0,0,0}, - {22828,22832,22810 ,10631,10640,10639 ,0,0,0}, {22809,22832,22831 ,10637,10640,10638 ,0,0,0}, - {22811,22806,22829 ,10632,10634,10633 ,0,0,0}, {22810,22811,22828 ,10639,10632,10631 ,0,0,0}, - {22830,22807,22825 ,10635,10626,10625 ,0,0,0}, {22806,22807,22830 ,10634,10626,10635 ,0,0,0}, - {22826,22808,22803 ,10628,10627,10629 ,0,0,0}, {22825,22808,22826 ,10625,10627,10628 ,0,0,0}, - {22823,22827,22805 ,10620,10630,10621 ,0,0,0}, {22827,22803,22805 ,10630,10629,10621 ,0,0,0}, - {22801,22837,22804 ,10624,10648,10619 ,0,0,0}, {22837,22823,22804 ,10648,10620,10619 ,0,0,0}, - {22817,22820,22824 ,10622,10613,10623 ,0,0,0}, {22801,22824,22837 ,10624,10623,10648 ,0,0,0}, - {22802,22800,22821 ,10614,10617,10615 ,0,0,0}, {22817,22802,22820 ,10622,10614,10613 ,0,0,0}, - {22822,22799,22818 ,10616,10618,10611 ,0,0,0}, {22821,22800,22822 ,10615,10617,10616 ,0,0,0}, - {22798,22818,22799 ,10573,10611,10618 ,0,0,0}, {22825,22826,22838 ,10649,10650,10651 ,0,0,0}, - {22839,22826,22827 ,10652,10650,10653 ,0,0,0}, {22826,22839,22838 ,10650,10652,10651 ,0,0,0}, - {22823,22840,22827 ,10654,10655,10653 ,0,0,0}, {22839,22827,22840 ,10652,10653,10655 ,0,0,0}, - {22823,22837,22841 ,10654,10656,10657 ,0,0,0}, {22841,22840,22823 ,10657,10655,10654 ,0,0,0}, - {22842,22837,22824 ,10658,10656,10659 ,0,0,0}, {22837,22842,22841 ,10656,10658,10657 ,0,0,0}, - {22820,22843,22824 ,10660,10661,10659 ,0,0,0}, {22842,22824,22843 ,10658,10659,10661 ,0,0,0}, - {22820,22821,22844 ,10660,10662,10663 ,0,0,0}, {22844,22843,22820 ,10663,10661,10660 ,0,0,0}, - {22845,22821,22822 ,10664,10662,10665 ,0,0,0}, {22821,22845,22844 ,10662,10664,10663 ,0,0,0}, - {22818,22846,22822 ,10666,10667,10665 ,0,0,0}, {22845,22822,22846 ,10664,10665,10667 ,0,0,0}, - {22819,22847,22846 ,10668,10669,10667 ,0,0,0}, {22846,22818,22819 ,10667,10666,10668 ,0,0,0}, - {22825,22838,22848 ,10649,10651,10670 ,0,0,0}, {22848,22849,22830 ,10670,10671,10672 ,0,0,0}, - {22830,22825,22848 ,10672,10649,10670 ,0,0,0}, {22829,22849,22850 ,10673,10671,10674 ,0,0,0}, - {22849,22829,22830 ,10671,10673,10672 ,0,0,0}, {22851,22828,22850 ,10675,10676,10674 ,0,0,0}, - {22829,22850,22828 ,10673,10674,10676 ,0,0,0}, {22851,22852,22832 ,10675,10677,10678 ,0,0,0}, - {22832,22828,22851 ,10678,10676,10675 ,0,0,0}, {22831,22852,22853 ,10679,10677,10680 ,0,0,0}, - {22852,22831,22832 ,10677,10679,10678 ,0,0,0}, {22854,22833,22853 ,10681,10682,10680 ,0,0,0}, - {22831,22853,22833 ,10679,10680,10682 ,0,0,0}, {22854,22855,22834 ,10681,10683,10684 ,0,0,0}, - {22834,22833,22854 ,10684,10682,10681 ,0,0,0}, {22835,22855,22856 ,10685,10683,10686 ,0,0,0}, - {22855,22835,22834 ,10683,10685,10684 ,0,0,0}, {22835,22856,22836 ,10685,10686,10687 ,0,0,0}, - {22857,22847,22858 ,10688,10689,10690 ,0,0,0}, {22859,22843,22860 ,10691,10692,10693 ,0,0,0}, - {22857,22861,22845 ,10688,10694,10695 ,0,0,0}, {22840,22862,22863 ,10696,10697,10698 ,0,0,0}, - {22842,22864,22841 ,10699,10700,10701 ,0,0,0}, {22865,22866,22848 ,10702,10703,10704 ,0,0,0}, - {22867,22838,22839 ,10705,10706,10707 ,0,0,0}, {22868,22851,22869 ,10708,10709,10710 ,0,0,0}, - {22850,22849,22870 ,10711,10712,10713 ,0,0,0}, {22871,22853,22852 ,10714,10715,10716 ,0,0,0}, - {22852,22868,22871 ,10716,10708,10714 ,0,0,0}, {22853,22872,22854 ,10715,10717,10718 ,0,0,0}, - {22872,22853,22871 ,10717,10715,10714 ,0,0,0}, {22855,22854,22873 ,10719,10718,10720 ,0,0,0}, - {22872,22873,22854 ,10717,10720,10718 ,0,0,0}, {22874,22856,22855 ,10721,10686,10719 ,0,0,0}, - {22855,22873,22874 ,10719,10720,10721 ,0,0,0}, {22851,22850,22869 ,10709,10711,10710 ,0,0,0}, - {22852,22851,22868 ,10716,10709,10708 ,0,0,0}, {22870,22849,22866 ,10713,10712,10703 ,0,0,0}, - {22869,22850,22870 ,10710,10711,10713 ,0,0,0}, {22865,22848,22838 ,10702,10704,10706 ,0,0,0}, - {22866,22849,22848 ,10703,10712,10704 ,0,0,0}, {22863,22867,22839 ,10698,10705,10707 ,0,0,0}, - {22867,22865,22838 ,10705,10702,10706 ,0,0,0}, {22841,22862,22840 ,10701,10697,10696 ,0,0,0}, - {22840,22863,22839 ,10696,10698,10707 ,0,0,0}, {22842,22859,22864 ,10699,10691,10700 ,0,0,0}, - {22841,22864,22862 ,10701,10700,10697 ,0,0,0}, {22843,22844,22860 ,10692,10722,10693 ,0,0,0}, - {22842,22843,22859 ,10699,10692,10691 ,0,0,0}, {22845,22861,22844 ,10695,10694,10722 ,0,0,0}, - {22860,22844,22861 ,10693,10722,10694 ,0,0,0}, {22857,22846,22847 ,10688,10723,10689 ,0,0,0}, - {22857,22845,22846 ,10688,10695,10723 ,0,0,0}, {22875,22858,22876 ,10724,10725,10726 ,0,0,0}, - {22877,22860,22878 ,10727,10728,10729 ,0,0,0}, {22879,22861,22857 ,10730,10731,10732 ,0,0,0}, - {22862,22880,22863 ,10733,10734,10735 ,0,0,0}, {22859,22881,22864 ,10736,10737,10738 ,0,0,0}, - {22882,22883,22865 ,10739,10740,10741 ,0,0,0}, {22882,22867,22884 ,10739,10742,10743 ,0,0,0}, - {22885,22869,22886 ,10744,10745,10746 ,0,0,0}, {22870,22866,22887 ,10747,10748,10749 ,0,0,0}, - {22888,22871,22868 ,10750,10751,10752 ,0,0,0}, {22868,22885,22888 ,10752,10744,10750 ,0,0,0}, - {22871,22889,22872 ,10751,10753,10754 ,0,0,0}, {22889,22871,22888 ,10753,10751,10750 ,0,0,0}, - {22873,22872,22890 ,10755,10754,10756 ,0,0,0}, {22889,22890,22872 ,10753,10756,10754 ,0,0,0}, - {22891,22874,22873 ,10757,10758,10755 ,0,0,0}, {22873,22890,22891 ,10755,10756,10757 ,0,0,0}, - {22869,22870,22886 ,10745,10747,10746 ,0,0,0}, {22868,22869,22885 ,10752,10745,10744 ,0,0,0}, - {22887,22866,22883 ,10749,10748,10740 ,0,0,0}, {22886,22870,22887 ,10746,10747,10749 ,0,0,0}, - {22882,22865,22867 ,10739,10741,10742 ,0,0,0}, {22883,22866,22865 ,10740,10748,10741 ,0,0,0}, - {22880,22884,22863 ,10734,10743,10735 ,0,0,0}, {22884,22867,22863 ,10743,10742,10735 ,0,0,0}, - {22864,22892,22862 ,10738,10759,10733 ,0,0,0}, {22892,22880,22862 ,10759,10734,10733 ,0,0,0}, - {22859,22877,22881 ,10736,10727,10737 ,0,0,0}, {22864,22881,22892 ,10738,10737,10759 ,0,0,0}, - {22860,22861,22878 ,10728,10731,10729 ,0,0,0}, {22859,22860,22877 ,10736,10728,10727 ,0,0,0}, - {22879,22857,22875 ,10730,10732,10724 ,0,0,0}, {22878,22861,22879 ,10729,10731,10730 ,0,0,0}, - {22858,22875,22857 ,10725,10724,10732 ,0,0,0}, {22893,22876,22894 ,10760,10761,10762 ,0,0,0}, - {22895,22878,22896 ,10763,10764,10765 ,0,0,0}, {22897,22879,22875 ,10766,10767,10768 ,0,0,0}, - {22892,22898,22899 ,10769,10770,10771 ,0,0,0}, {22877,22900,22881 ,10772,10773,10774 ,0,0,0}, - {22901,22902,22882 ,10775,10776,10777 ,0,0,0}, {22901,22884,22903 ,10775,10778,10779 ,0,0,0}, - {22904,22886,22905 ,10780,10781,10782 ,0,0,0}, {22887,22883,22906 ,10783,10784,10785 ,0,0,0}, - {22907,22888,22885 ,10786,10787,10788 ,0,0,0}, {22885,22904,22907 ,10788,10780,10786 ,0,0,0}, - {22888,22908,22889 ,10787,10789,10790 ,0,0,0}, {22908,22888,22907 ,10789,10787,10786 ,0,0,0}, - {22890,22889,22909 ,10791,10790,10792 ,0,0,0}, {22908,22909,22889 ,10789,10792,10790 ,0,0,0}, - {22910,22891,22890 ,10793,10794,10791 ,0,0,0}, {22890,22909,22910 ,10791,10792,10793 ,0,0,0}, - {22886,22887,22905 ,10781,10783,10782 ,0,0,0}, {22885,22886,22904 ,10788,10781,10780 ,0,0,0}, - {22906,22883,22902 ,10785,10784,10776 ,0,0,0}, {22905,22887,22906 ,10782,10783,10785 ,0,0,0}, - {22901,22882,22884 ,10775,10777,10778 ,0,0,0}, {22902,22883,22882 ,10776,10784,10777 ,0,0,0}, - {22899,22903,22880 ,10771,10779,10795 ,0,0,0}, {22903,22884,22880 ,10779,10778,10795 ,0,0,0}, - {22881,22898,22892 ,10774,10770,10769 ,0,0,0}, {22892,22899,22880 ,10769,10771,10795 ,0,0,0}, - {22877,22895,22900 ,10772,10763,10773 ,0,0,0}, {22881,22900,22898 ,10774,10773,10770 ,0,0,0}, - {22878,22879,22896 ,10764,10767,10765 ,0,0,0}, {22877,22878,22895 ,10772,10764,10763 ,0,0,0}, - {22897,22875,22893 ,10766,10768,10760 ,0,0,0}, {22896,22879,22897 ,10765,10767,10766 ,0,0,0}, - {22876,22893,22875 ,10761,10760,10768 ,0,0,0}, {22481,22894,22479 ,10796,10797,10798 ,0,0,0}, - {22482,22896,22483 ,10799,10800,10801 ,0,0,0}, {22493,22897,22893 ,10802,10803,10804 ,0,0,0}, - {22898,22506,22507 ,10805,10806,10807 ,0,0,0}, {22895,22494,22900 ,10808,10809,10810 ,0,0,0}, - {22509,22510,22901 ,10811,10812,10813 ,0,0,0}, {22508,22903,22899 ,10814,10815,10816 ,0,0,0}, - {22539,22905,22906 ,10817,10818,10819 ,0,0,0}, {22536,22902,22510 ,10820,10821,10812 ,0,0,0}, - {22540,22907,22904 ,10822,10823,10824 ,0,0,0}, {22904,22538,22540 ,10824,10825,10822 ,0,0,0}, - {22907,22541,22908 ,10823,10826,10827 ,0,0,0}, {22541,22907,22540 ,10826,10823,10822 ,0,0,0}, - {22908,22443,22440 ,10827,10828,10829 ,0,0,0}, {22541,22443,22908 ,10826,10828,10827 ,0,0,0}, - {22439,22909,22440 ,10047,10830,10829 ,0,0,0}, {22908,22440,22909 ,10827,10829,10830 ,0,0,0}, - {22910,22909,22439 ,10793,10830,10047 ,0,0,0}, {22538,22905,22539 ,10825,10818,10817 ,0,0,0}, - {22904,22905,22538 ,10824,10818,10825 ,0,0,0}, {22536,22906,22902 ,10820,10819,10821 ,0,0,0}, - {22539,22906,22536 ,10817,10819,10820 ,0,0,0}, {22901,22903,22509 ,10813,10815,10811 ,0,0,0}, - {22510,22902,22901 ,10812,10821,10813 ,0,0,0}, {22507,22508,22899 ,10807,10814,10816 ,0,0,0}, - {22508,22509,22903 ,10814,10811,10815 ,0,0,0}, {22900,22506,22898 ,10810,10806,10805 ,0,0,0}, - {22898,22507,22899 ,10805,10807,10816 ,0,0,0}, {22895,22482,22494 ,10808,10799,10809 ,0,0,0}, - {22900,22494,22506 ,10810,10809,10806 ,0,0,0}, {22896,22897,22483 ,10800,10803,10801 ,0,0,0}, - {22895,22896,22482 ,10808,10800,10799 ,0,0,0}, {22493,22893,22481 ,10802,10804,10796 ,0,0,0}, - {22483,22897,22493 ,10801,10803,10802 ,0,0,0}, {22894,22481,22893 ,10797,10796,10804 ,0,0,0}, - {22911,22419,22912 ,10831,10024,10832 ,0,0,0}, {22913,22529,22476 ,10833,10834,10835 ,0,0,0}, - {22914,22491,22417 ,10836,10837,10838 ,0,0,0}, {22534,22915,22916 ,10839,10840,10841 ,0,0,0}, - {22530,22917,22531 ,10842,10843,10844 ,0,0,0}, {22918,22919,22499 ,10845,10846,10847 ,0,0,0}, - {22920,22502,22503 ,10848,10849,10850 ,0,0,0}, {22921,22537,22922 ,10851,10852,10853 ,0,0,0}, - {22535,22500,22923 ,10854,10855,10856 ,0,0,0}, {22924,22514,22459 ,10857,10858,10859 ,0,0,0}, - {22459,22921,22924 ,10859,10851,10857 ,0,0,0}, {22514,22925,22542 ,10858,10860,10861 ,0,0,0}, - {22925,22514,22924 ,10860,10858,10857 ,0,0,0}, {22450,22542,22926 ,10862,10861,10863 ,0,0,0}, - {22925,22926,22542 ,10860,10863,10861 ,0,0,0}, {22927,22453,22450 ,10864,10865,10862 ,0,0,0}, - {22450,22926,22927 ,10862,10863,10864 ,0,0,0}, {22537,22535,22922 ,10852,10854,10853 ,0,0,0}, - {22459,22537,22921 ,10859,10852,10851 ,0,0,0}, {22923,22500,22919 ,10856,10855,10846 ,0,0,0}, - {22922,22535,22923 ,10853,10854,10856 ,0,0,0}, {22918,22499,22502 ,10845,10847,10849 ,0,0,0}, - {22919,22500,22499 ,10846,10855,10847 ,0,0,0}, {22916,22920,22503 ,10841,10848,10850 ,0,0,0}, - {22920,22918,22502 ,10848,10845,10849 ,0,0,0}, {22531,22915,22534 ,10844,10840,10839 ,0,0,0}, - {22534,22916,22503 ,10839,10841,10850 ,0,0,0}, {22530,22928,22917 ,10842,10866,10843 ,0,0,0}, - {22531,22917,22915 ,10844,10843,10840 ,0,0,0}, {22913,22928,22529 ,10833,10866,10834 ,0,0,0}, - {22530,22529,22928 ,10842,10834,10866 ,0,0,0}, {22914,22476,22491 ,10836,10835,10837 ,0,0,0}, - {22913,22476,22914 ,10833,10835,10836 ,0,0,0}, {22911,22417,22419 ,10831,10838,10024 ,0,0,0}, - {22914,22417,22911 ,10836,10838,10831 ,0,0,0}, {22929,22912,22930 ,10867,10832,10868 ,0,0,0}, - {22931,22913,22932 ,10869,10870,10871 ,0,0,0}, {22933,22914,22911 ,10872,10873,10874 ,0,0,0}, - {22915,22934,22935 ,10875,10876,10877 ,0,0,0}, {22928,22936,22917 ,10878,10879,10880 ,0,0,0}, - {22937,22919,22918 ,10881,10882,10883 ,0,0,0}, {22938,22920,22939 ,10884,10885,10886 ,0,0,0}, - {22940,22922,22941 ,10887,10888,10889 ,0,0,0}, {22923,22919,22942 ,10890,10882,10891 ,0,0,0}, - {22943,22924,22921 ,10892,10893,10894 ,0,0,0}, {22921,22940,22943 ,10894,10887,10892 ,0,0,0}, - {22924,22944,22925 ,10893,10895,10896 ,0,0,0}, {22944,22924,22943 ,10895,10893,10892 ,0,0,0}, - {22926,22925,22945 ,10897,10896,10898 ,0,0,0}, {22944,22945,22925 ,10895,10898,10896 ,0,0,0}, - {22946,22927,22926 ,10899,10900,10897 ,0,0,0}, {22926,22945,22946 ,10897,10898,10899 ,0,0,0}, - {22922,22923,22941 ,10888,10890,10889 ,0,0,0}, {22921,22922,22940 ,10894,10888,10887 ,0,0,0}, - {22942,22919,22937 ,10891,10882,10881 ,0,0,0}, {22941,22923,22942 ,10889,10890,10891 ,0,0,0}, - {22938,22918,22920 ,10884,10883,10885 ,0,0,0}, {22937,22918,22938 ,10881,10883,10884 ,0,0,0}, - {22935,22939,22916 ,10877,10886,10901 ,0,0,0}, {22939,22920,22916 ,10886,10885,10901 ,0,0,0}, - {22917,22934,22915 ,10880,10876,10875 ,0,0,0}, {22915,22935,22916 ,10875,10877,10901 ,0,0,0}, - {22928,22931,22936 ,10878,10869,10879 ,0,0,0}, {22917,22936,22934 ,10880,10879,10876 ,0,0,0}, - {22913,22914,22932 ,10870,10873,10871 ,0,0,0}, {22928,22913,22931 ,10878,10870,10869 ,0,0,0}, - {22933,22911,22929 ,10872,10874,10867 ,0,0,0}, {22932,22914,22933 ,10871,10873,10872 ,0,0,0}, - {22912,22929,22911 ,10832,10867,10874 ,0,0,0}, {22947,22930,22948 ,10902,10868,10903 ,0,0,0}, - {22949,22932,22950 ,10904,10905,10906 ,0,0,0}, {22951,22933,22929 ,10907,10908,10909 ,0,0,0}, - {22934,22952,22935 ,10910,10911,10912 ,0,0,0}, {22931,22953,22936 ,10913,10914,10915 ,0,0,0}, - {22954,22937,22938 ,10916,10917,10918 ,0,0,0}, {22955,22939,22956 ,10919,10920,10921 ,0,0,0}, - {22957,22941,22958 ,10922,10923,10924 ,0,0,0}, {22942,22937,22959 ,10925,10917,10926 ,0,0,0}, - {22960,22943,22940 ,10927,10928,10929 ,0,0,0}, {22940,22957,22960 ,10929,10922,10927 ,0,0,0}, - {22943,22961,22944 ,10928,10930,10931 ,0,0,0}, {22961,22943,22960 ,10930,10928,10927 ,0,0,0}, - {22945,22944,22962 ,10932,10931,10933 ,0,0,0}, {22961,22962,22944 ,10930,10933,10931 ,0,0,0}, - {22963,22946,22945 ,10934,10935,10932 ,0,0,0}, {22945,22962,22963 ,10932,10933,10934 ,0,0,0}, - {22941,22942,22958 ,10923,10925,10924 ,0,0,0}, {22940,22941,22957 ,10929,10923,10922 ,0,0,0}, - {22959,22937,22954 ,10926,10917,10916 ,0,0,0}, {22958,22942,22959 ,10924,10925,10926 ,0,0,0}, - {22955,22938,22939 ,10919,10918,10920 ,0,0,0}, {22954,22938,22955 ,10916,10918,10919 ,0,0,0}, - {22952,22956,22935 ,10911,10921,10912 ,0,0,0}, {22956,22939,22935 ,10921,10920,10912 ,0,0,0}, - {22936,22964,22934 ,10915,10936,10910 ,0,0,0}, {22964,22952,22934 ,10936,10911,10910 ,0,0,0}, - {22931,22949,22953 ,10913,10904,10914 ,0,0,0}, {22936,22953,22964 ,10915,10914,10936 ,0,0,0}, - {22932,22933,22950 ,10905,10908,10906 ,0,0,0}, {22931,22932,22949 ,10913,10905,10904 ,0,0,0}, - {22951,22929,22947 ,10907,10909,10902 ,0,0,0}, {22950,22933,22951 ,10906,10908,10907 ,0,0,0}, - {22930,22947,22929 ,10868,10902,10909 ,0,0,0}, {22547,22965,22584 ,10937,10938,10226 ,0,0,0}, - {22553,22966,22554 ,10939,10940,10941 ,0,0,0}, {22549,22967,22968 ,10942,10943,10944 ,0,0,0}, - {22969,22561,22970 ,10945,10946,10947 ,0,0,0}, {22971,22551,22972 ,10948,10949,10950 ,0,0,0}, - {22566,22973,22974 ,10951,10952,10953 ,0,0,0}, {22558,22975,22556 ,10954,10955,10956 ,0,0,0}, - {22976,22977,22571 ,10957,10958,10959 ,0,0,0}, {22978,22564,22563 ,10960,10961,10962 ,0,0,0}, - {22979,22980,22568 ,10963,10964,10965 ,0,0,0}, {22569,22568,22980 ,10966,10965,10964 ,0,0,0}, - {22575,22981,22979 ,10967,10968,10963 ,0,0,0}, {22979,22568,22575 ,10963,10965,10967 ,0,0,0}, - {22981,22577,22982 ,10968,10969,10970 ,0,0,0}, {22577,22981,22575 ,10969,10968,10967 ,0,0,0}, - {22983,22982,22578 ,10971,10970,10972 ,0,0,0}, {22577,22578,22982 ,10969,10972,10970 ,0,0,0}, - {22581,22984,22983 ,10223,10973,10971 ,0,0,0}, {22983,22578,22581 ,10971,10972,10223 ,0,0,0}, - {22571,22569,22976 ,10959,10966,10957 ,0,0,0}, {22976,22569,22980 ,10957,10966,10964 ,0,0,0}, - {22977,22978,22563 ,10958,10960,10962 ,0,0,0}, {22977,22563,22571 ,10958,10962,10959 ,0,0,0}, - {22564,22973,22566 ,10961,10952,10951 ,0,0,0}, {22978,22973,22564 ,10960,10952,10961 ,0,0,0}, - {22558,22974,22975 ,10954,10953,10955 ,0,0,0}, {22566,22974,22558 ,10951,10953,10954 ,0,0,0}, - {22561,22556,22970 ,10946,10956,10947 ,0,0,0}, {22556,22975,22970 ,10956,10955,10947 ,0,0,0}, - {22972,22583,22969 ,10950,10974,10945 ,0,0,0}, {22583,22561,22969 ,10974,10946,10945 ,0,0,0}, - {22971,22553,22551 ,10948,10939,10949 ,0,0,0}, {22972,22551,22583 ,10950,10949,10974 ,0,0,0}, - {22966,22967,22554 ,10940,10943,10941 ,0,0,0}, {22971,22966,22553 ,10948,10940,10939 ,0,0,0}, - {22549,22968,22547 ,10942,10944,10937 ,0,0,0}, {22554,22967,22549 ,10941,10943,10942 ,0,0,0}, - {22965,22547,22968 ,10938,10937,10944 ,0,0,0}, {22985,22948,22986 ,10975,10903,10976 ,0,0,0}, - {22987,22950,22988 ,10977,10978,10979 ,0,0,0}, {22989,22951,22947 ,10980,10981,10982 ,0,0,0}, - {22964,22990,22991 ,10983,10984,10985 ,0,0,0}, {22949,22992,22953 ,10986,10987,10988 ,0,0,0}, - {22993,22994,22955 ,10989,10990,10991 ,0,0,0}, {22995,22956,22952 ,10992,10993,10994 ,0,0,0}, - {22996,22958,22959 ,10995,10996,10997 ,0,0,0}, {22959,22954,22997 ,10997,10998,10999 ,0,0,0}, - {22998,22960,22957 ,11000,11001,11002 ,0,0,0}, {22957,22999,22998 ,11002,11003,11000 ,0,0,0}, - {22960,23000,22961 ,11001,11004,11005 ,0,0,0}, {23000,22960,22998 ,11004,11001,11000 ,0,0,0}, - {22962,22961,23001 ,11006,11005,11007 ,0,0,0}, {23000,23001,22961 ,11004,11007,11005 ,0,0,0}, - {23002,22962,23003 ,11008,11006,11009 ,0,0,0}, {22962,23001,23003 ,11006,11007,11009 ,0,0,0}, - {22963,22962,23002 ,11010,11006,11008 ,0,0,0}, {22999,22958,22996 ,11003,10996,10995 ,0,0,0}, - {22957,22958,22999 ,11002,10996,11003 ,0,0,0}, {22954,22994,22997 ,10998,10990,10999 ,0,0,0}, - {22996,22959,22997 ,10995,10997,10999 ,0,0,0}, {22993,22955,22956 ,10989,10991,10993 ,0,0,0}, - {22994,22954,22955 ,10990,10998,10991 ,0,0,0}, {22991,22995,22952 ,10985,10992,10994 ,0,0,0}, - {22995,22993,22956 ,10992,10989,10993 ,0,0,0}, {22953,22990,22964 ,10988,10984,10983 ,0,0,0}, - {22964,22991,22952 ,10983,10985,10994 ,0,0,0}, {22949,22987,22992 ,10986,10977,10987 ,0,0,0}, - {22953,22992,22990 ,10988,10987,10984 ,0,0,0}, {22950,22951,22988 ,10978,10981,10979 ,0,0,0}, - {22949,22950,22987 ,10986,10978,10977 ,0,0,0}, {22989,22947,22985 ,10980,10982,10975 ,0,0,0}, - {22988,22951,22989 ,10979,10981,10980 ,0,0,0}, {22948,22985,22947 ,10903,10975,10982 ,0,0,0}, - {22968,22986,22965 ,11011,10976,11012 ,0,0,0}, {22971,22988,22966 ,11013,11014,11015 ,0,0,0}, - {22967,22989,22985 ,11016,11017,11018 ,0,0,0}, {22990,22969,22970 ,11019,11020,11021 ,0,0,0}, - {22987,22972,22992 ,11022,11023,11024 ,0,0,0}, {22974,22973,22993 ,11025,11026,11027 ,0,0,0}, - {22975,22995,22991 ,11028,11029,11030 ,0,0,0}, {22976,22996,22977 ,11031,11032,11033 ,0,0,0}, - {22997,22994,22978 ,11034,11035,11036 ,0,0,0}, {22979,22998,22980 ,11037,11038,11039 ,0,0,0}, - {22999,22976,22980 ,11040,11031,11039 ,0,0,0}, {22979,22981,23000 ,11037,11041,11042 ,0,0,0}, - {23000,22998,22979 ,11042,11038,11037 ,0,0,0}, {23001,22981,22982 ,11043,11041,11044 ,0,0,0}, - {22981,23001,23000 ,11041,11043,11042 ,0,0,0}, {22983,23003,22982 ,11045,11046,11044 ,0,0,0}, - {23001,22982,23003 ,11043,11044,11046 ,0,0,0}, {22984,23002,23003 ,11047,11008,11046 ,0,0,0}, - {23003,22983,22984 ,11046,11045,11047 ,0,0,0}, {22996,22976,22999 ,11032,11031,11040 ,0,0,0}, - {22998,22999,22980 ,11038,11040,11039 ,0,0,0}, {22977,22997,22978 ,11033,11034,11036 ,0,0,0}, - {22996,22997,22977 ,11032,11034,11033 ,0,0,0}, {22973,22994,22993 ,11026,11035,11027 ,0,0,0}, - {22978,22994,22973 ,11036,11035,11026 ,0,0,0}, {22975,22974,22995 ,11028,11025,11029 ,0,0,0}, - {22974,22993,22995 ,11025,11027,11029 ,0,0,0}, {22990,22970,22991 ,11019,11021,11030 ,0,0,0}, - {22970,22975,22991 ,11021,11028,11030 ,0,0,0}, {22992,22972,22969 ,11024,11023,11020 ,0,0,0}, - {22992,22969,22990 ,11024,11020,11019 ,0,0,0}, {22987,22988,22971 ,11022,11014,11013 ,0,0,0}, - {22987,22971,22972 ,11022,11013,11023 ,0,0,0}, {22966,22989,22967 ,11015,11017,11016 ,0,0,0}, - {22988,22989,22966 ,11014,11017,11015 ,0,0,0}, {22968,22985,22986 ,11011,11018,10976 ,0,0,0}, - {22967,22985,22968 ,11016,11018,11011 ,0,0,0}, {22671,23004,23005 ,11048,11049,11050 ,0,0,0}, - {22670,23006,22668 ,11051,11052,11053 ,0,0,0}, {23004,22671,23007 ,11049,11048,11054 ,0,0,0}, - {23005,23008,22671 ,11050,11048,11048 ,0,0,0}, {23007,22671,22668 ,11054,11048,11053 ,0,0,0}, - {23009,23007,22668 ,11055,11054,11053 ,0,0,0}, {23009,22668,23006 ,11055,11053,11052 ,0,0,0}, - {22706,22624,23010 ,11056,11057,11058 ,0,0,0}, {22706,23011,23012 ,11056,11059,11060 ,0,0,0}, - {23010,23011,22706 ,11058,11059,11056 ,0,0,0}, {22670,23012,23013 ,11051,11060,11061 ,0,0,0}, - {22670,22706,23012 ,11051,11056,11060 ,0,0,0}, {22670,23014,23015 ,11051,11062,11063 ,0,0,0}, - {23013,23014,22670 ,11061,11062,11051 ,0,0,0}, {22670,23016,23017 ,11051,11064,11065 ,0,0,0}, - {23015,23016,22670 ,11063,11064,11051 ,0,0,0}, {23006,22670,23018 ,11052,11051,11066 ,0,0,0}, - {23017,23018,22670 ,11065,11066,11051 ,0,0,0}, {23019,22492,23020 ,11067,11068,11069 ,0,0,0}, - {22492,23021,23022 ,11068,11070,11071 ,0,0,0}, {23022,22490,22492 ,11071,11072,11068 ,0,0,0}, - {22492,23019,23021 ,11068,11067,11070 ,0,0,0}, {22490,23023,23024 ,11072,11073,11074 ,0,0,0}, - {22490,23022,23023 ,11072,11071,11073 ,0,0,0}, {22492,23025,23020 ,11068,11075,11069 ,0,0,0}, - {22490,23024,22419 ,11072,11074,11076 ,0,0,0}, {23026,22492,22477 ,11077,11068,11078 ,0,0,0}, - {22492,23026,23025 ,11068,11077,11075 ,0,0,0}, {22479,23027,23028 ,11079,11079,11080 ,0,0,0}, - {23029,23030,22480 ,11081,11082,11083 ,0,0,0}, {23031,23032,22479 ,11084,11085,11079 ,0,0,0}, - {23031,22479,23028 ,11084,11079,11080 ,0,0,0}, {22479,23033,22480 ,11079,11086,11083 ,0,0,0}, - {23033,22479,23032 ,11086,11079,11085 ,0,0,0}, {23034,22480,23030 ,11087,11083,11082 ,0,0,0}, - {23033,23029,22480 ,11086,11081,11083 ,0,0,0}, {23026,22477,23034 ,11077,11078,11087 ,0,0,0}, - {23034,22477,22480 ,11087,11078,11083 ,0,0,0}, {23027,22479,23035 ,11088,11089,11090 ,0,0,0}, - {22876,23035,22894 ,11091,11090,11092 ,0,0,0}, {22876,22858,23035 ,11091,11093,11090 ,0,0,0}, - {23035,22858,22847 ,11090,11093,11094 ,0,0,0}, {22847,22819,23035 ,11094,11095,11090 ,0,0,0}, - {23035,22479,22894 ,11090,11089,11092 ,0,0,0}, {23036,23034,23037 ,11096,11097,11098 ,0,0,0}, - {23036,23038,23026 ,11096,324,11099 ,0,0,0}, {23026,23034,23036 ,11099,11097,11096 ,0,0,0}, - {23039,23040,23041 ,11100,11101,11102 ,0,0,0}, {23040,23042,23041 ,11101,11103,11102 ,0,0,0}, - {23040,23039,23043 ,11101,11100,11104 ,0,0,0}, {23021,23044,23043 ,11105,11106,11104 ,0,0,0}, - {23039,23021,23043 ,11100,11105,11104 ,0,0,0}, {23019,23044,23021 ,11107,11106,11105 ,0,0,0}, - {23044,23019,23045 ,11106,11107,11108 ,0,0,0}, {23020,23046,23045 ,11109,11110,11108 ,0,0,0}, - {23045,23019,23020 ,11108,11107,11109 ,0,0,0}, {23046,23025,23047 ,11110,11111,11112 ,0,0,0}, - {23025,23046,23020 ,11111,11110,11109 ,0,0,0}, {23038,23047,23026 ,11113,11112,11114 ,0,0,0}, - {23025,23026,23047 ,11111,11114,11112 ,0,0,0}, {23032,23048,23049 ,11115,11116,11117 ,0,0,0}, - {23037,23034,23030 ,11118,11119,11120 ,0,0,0}, {23030,23029,23050 ,11120,11121,11122 ,0,0,0}, - {23051,23033,23049 ,11123,11124,11117 ,0,0,0}, {23050,23029,23051 ,11122,11121,11123 ,0,0,0}, - {23030,23050,23037 ,11120,11122,11118 ,0,0,0}, {23029,23033,23051 ,11121,11124,11123 ,0,0,0}, - {23033,23032,23049 ,11124,11115,11117 ,0,0,0}, {23048,23032,23031 ,11116,11115,11125 ,0,0,0}, - {23031,23028,23052 ,11125,11126,11127 ,0,0,0}, {23052,23048,23031 ,11127,11116,11125 ,0,0,0}, - {23053,23028,23027 ,11128,11126,11129 ,0,0,0}, {23028,23053,23052 ,11126,11128,11127 ,0,0,0}, - {23053,23027,23035 ,11128,11129,11129 ,0,0,0}, {23008,23054,23055 ,11130,11130,11131 ,0,0,0}, - {23008,23055,23056 ,11130,11131,11130 ,0,0,0}, {23057,23008,23056 ,11130,11130,11130 ,0,0,0}, - {23048,23052,23008 ,11130,11130,11130 ,0,0,0}, {23048,23008,23057 ,11130,11130,11130 ,0,0,0}, - {23008,23053,23035 ,11130,11130,11131 ,0,0,0}, {23052,23053,23008 ,11130,11130,11130 ,0,0,0}, - {23008,23035,22671 ,11130,11131,11130 ,0,0,0}, {23035,22798,22778 ,11131,11130,11130 ,0,0,0}, - {23035,22819,22798 ,11131,11131,11130 ,0,0,0}, {22778,22758,23035 ,11130,11131,11131 ,0,0,0}, - {22671,23035,22739 ,11130,11131,11130 ,0,0,0}, {23035,22758,22739 ,11131,11131,11130 ,0,0,0}, - {22584,22965,23058 ,11132,11133,11134 ,0,0,0}, {23010,23059,23011 ,11135,11136,11137 ,0,0,0}, - {23060,23059,22585 ,11138,11136,11139 ,0,0,0}, {23061,23042,23062 ,11140,11141,11142 ,0,0,0}, - {23063,23061,23062 ,11143,11140,11142 ,0,0,0}, {23064,23065,23066 ,11144,11145,11146 ,0,0,0}, - {23065,23063,23066 ,11145,11143,11146 ,0,0,0}, {23059,22605,22585 ,11136,11147,11139 ,0,0,0}, - {23060,22585,22545 ,11138,11139,11148 ,0,0,0}, {23064,23012,23011 ,11144,11149,11137 ,0,0,0}, - {22624,22605,23010 ,11150,11147,11135 ,0,0,0}, {22584,23060,22545 ,11132,11138,11148 ,0,0,0}, - {23058,23067,23060 ,11134,11151,11138 ,0,0,0}, {23060,22584,23058 ,11138,11132,11134 ,0,0,0}, - {23067,23061,23063 ,11151,11140,11143 ,0,0,0}, {23065,23064,23011 ,11145,11144,11137 ,0,0,0}, - {23063,23065,23060 ,11143,11145,11138 ,0,0,0}, {23010,22605,23059 ,11135,11147,11136 ,0,0,0}, - {23063,23060,23067 ,11143,11138,11151 ,0,0,0}, {23062,23066,23063 ,11142,11146,11143 ,0,0,0}, - {23011,23059,23065 ,11137,11136,11145 ,0,0,0}, {23060,23065,23059 ,11138,11145,11136 ,0,0,0}, - {23068,23069,23070 ,11152,11153,11154 ,0,0,0}, {23071,23072,23073 ,11155,11156,11157 ,0,0,0}, - {23074,23075,23076 ,11158,11159,11160 ,0,0,0}, {23042,23040,23077 ,11161,11162,11163 ,0,0,0}, - {23078,23079,23016 ,11164,11165,11166 ,0,0,0}, {23080,23081,23082 ,11167,11168,11169 ,0,0,0}, - {23083,23084,23069 ,11170,11171,11153 ,0,0,0}, {23006,23018,23084 ,11172,11173,11171 ,0,0,0}, - {23085,23047,23038 ,11174,11175,11176 ,0,0,0}, {23068,23070,23085 ,11152,11154,11174 ,0,0,0}, - {23006,23084,23083 ,11172,11171,11170 ,0,0,0}, {23073,23070,23069 ,11157,11154,11153 ,0,0,0}, - {23018,23086,23084 ,11173,11177,11171 ,0,0,0}, {23079,23086,23017 ,11165,11177,11178 ,0,0,0}, - {23087,23078,23082 ,11179,11164,11169 ,0,0,0}, {23088,23076,23072 ,11180,11160,11156 ,0,0,0}, - {23013,23064,23080 ,11181,11182,11167 ,0,0,0}, {23075,23087,23077 ,11159,11179,11163 ,0,0,0}, - {23012,23064,23013 ,11183,11182,11181 ,0,0,0}, {23080,23064,23066 ,11167,11182,11184 ,0,0,0}, - {23017,23086,23018 ,11178,11177,11173 ,0,0,0}, {23017,23016,23079 ,11178,11166,11165 ,0,0,0}, - {23085,23070,23047 ,11174,11154,11175 ,0,0,0}, {23083,23069,23068 ,11170,11153,11152 ,0,0,0}, - {23073,23069,23071 ,11157,11153,11155 ,0,0,0}, {23046,23047,23070 ,11185,11175,11154 ,0,0,0}, - {23071,23084,23086 ,11155,11171,11177 ,0,0,0}, {23062,23042,23077 ,11186,11161,11163 ,0,0,0}, - {23070,23073,23046 ,11154,11157,11185 ,0,0,0}, {23084,23071,23069 ,11171,11155,11153 ,0,0,0}, - {23072,23071,23088 ,11156,11155,11180 ,0,0,0}, {23045,23046,23073 ,11187,11185,11157 ,0,0,0}, - {23079,23088,23086 ,11165,11180,11177 ,0,0,0}, {23015,23078,23016 ,11188,11164,11166 ,0,0,0}, - {23073,23072,23045 ,11157,11156,11187 ,0,0,0}, {23086,23088,23071 ,11177,11180,11155 ,0,0,0}, - {23076,23088,23074 ,11160,11180,11158 ,0,0,0}, {23044,23045,23072 ,11189,11187,11156 ,0,0,0}, - {23078,23074,23079 ,11164,11158,11165 ,0,0,0}, {23014,23082,23015 ,11190,11169,11188 ,0,0,0}, - {23076,23043,23044 ,11160,11191,11189 ,0,0,0}, {23079,23074,23088 ,11165,11158,11180 ,0,0,0}, - {23074,23087,23075 ,11158,11179,11159 ,0,0,0}, {23044,23072,23076 ,11189,11156,11160 ,0,0,0}, - {23015,23082,23078 ,11188,11169,11164 ,0,0,0}, {23080,23014,23013 ,11167,11190,11181 ,0,0,0}, - {23075,23040,23043 ,11159,11162,11191 ,0,0,0}, {23078,23087,23074 ,11164,11179,11158 ,0,0,0}, - {23081,23077,23087 ,11168,11163,11179 ,0,0,0}, {23043,23076,23075 ,11191,11160,11159 ,0,0,0}, - {23014,23080,23082 ,11190,11167,11169 ,0,0,0}, {23082,23081,23087 ,11169,11168,11179 ,0,0,0}, - {23066,23062,23081 ,11184,11186,11168 ,0,0,0}, {23080,23066,23081 ,11167,11184,11168 ,0,0,0}, - {23062,23077,23081 ,11186,11163,11168 ,0,0,0}, {23040,23075,23077 ,11162,11159,11163 ,0,0,0}, - {23085,23036,23089 ,11192,11193,11194 ,0,0,0}, {23009,23090,23007 ,11195,11196,11054 ,0,0,0}, - {23089,23036,23091 ,11194,11193,11197 ,0,0,0}, {23036,23037,23091 ,11193,324,11197 ,0,0,0}, - {23089,23092,23090 ,11194,11198,11196 ,0,0,0}, {23085,23038,23036 ,11192,324,11193 ,0,0,0}, - {23090,23092,23007 ,11196,11198,11054 ,0,0,0}, {23083,23090,23009 ,11199,11196,11195 ,0,0,0}, - {23006,23083,23009 ,11200,11199,11195 ,0,0,0}, {23083,23068,23090 ,11199,11201,11196 ,0,0,0}, - {23068,23085,23089 ,11201,11192,11194 ,0,0,0}, {23068,23089,23090 ,11201,11194,11196 ,0,0,0}, - {23092,23089,23091 ,11198,11194,11197 ,0,0,0}, {23057,23056,23049 ,11202,11203,11204 ,0,0,0}, - {23091,23037,23050 ,11205,324,11206 ,0,0,0}, {23050,23051,23093 ,11206,11207,11208 ,0,0,0}, - {23050,23093,23091 ,11206,11208,11205 ,0,0,0}, {23048,23057,23049 ,11209,11202,11204 ,0,0,0}, - {23055,23054,23094 ,11210,11211,11212 ,0,0,0}, {23094,23095,23055 ,11212,11213,11210 ,0,0,0}, - {23092,23093,23096 ,11214,11208,11215 ,0,0,0}, {23096,23093,23095 ,11215,11208,11213 ,0,0,0}, - {23054,23008,23005 ,11211,11216,11217 ,0,0,0}, {23092,23096,23007 ,11214,11215,11218 ,0,0,0}, - {23005,23096,23094 ,11217,11215,11212 ,0,0,0}, {23091,23093,23092 ,11205,11208,11214 ,0,0,0}, - {23005,23004,23096 ,11217,11219,11215 ,0,0,0}, {23096,23004,23007 ,11215,11219,11218 ,0,0,0}, - {23093,23051,23095 ,11208,11207,11213 ,0,0,0}, {23049,23095,23051 ,11204,11213,11207 ,0,0,0}, - {23005,23094,23054 ,11217,11212,11211 ,0,0,0}, {23096,23095,23094 ,11215,11213,11212 ,0,0,0}, - {23056,23095,23049 ,11203,11213,11204 ,0,0,0}, {23056,23055,23095 ,11203,11210,11213 ,0,0,0}, - {22930,23097,23098 ,11220,11221,11222 ,0,0,0}, {23042,23061,23099 ,11223,11224,11225 ,0,0,0}, - {23100,23099,23061 ,11226,11225,11224 ,0,0,0}, {22930,23098,22948 ,11220,11222,11227 ,0,0,0}, - {23098,23097,23100 ,11222,11221,11226 ,0,0,0}, {23058,22965,22986 ,11228,11229,11230 ,0,0,0}, - {22948,23098,22986 ,11227,11222,11230 ,0,0,0}, {23024,23097,22912 ,11231,11221,11232 ,0,0,0}, - {23101,23024,23023 ,11233,11231,11234 ,0,0,0}, {23097,22930,22912 ,11221,11220,11232 ,0,0,0}, - {23099,23039,23041 ,11225,11235,11236 ,0,0,0}, {23099,23101,23102 ,11225,11233,11237 ,0,0,0}, - {22912,22419,23024 ,11232,11238,11231 ,0,0,0}, {23039,23102,23021 ,11235,11237,11239 ,0,0,0}, - {23102,23039,23099 ,11237,11235,11225 ,0,0,0}, {23098,23058,22986 ,11222,11228,11230 ,0,0,0}, - {23097,23101,23100 ,11221,11233,11226 ,0,0,0}, {23067,23058,23098 ,11240,11228,11222 ,0,0,0}, - {23024,23101,23097 ,11231,11233,11221 ,0,0,0}, {23102,23023,23022 ,11237,11234,11241 ,0,0,0}, - {23061,23067,23100 ,11224,11240,11226 ,0,0,0}, {23098,23100,23067 ,11222,11226,11240 ,0,0,0}, - {23023,23102,23101 ,11234,11237,11233 ,0,0,0}, {23021,23102,23022 ,11239,11237,11241 ,0,0,0}, - {23099,23041,23042 ,11225,11236,11223 ,0,0,0}, {23101,23099,23100 ,11233,11225,11226 ,0,0,0}, - {23103,22544,23104 ,11242,11243,11244 ,0,0,0}, {22544,23105,23106 ,11243,11245,11246 ,0,0,0}, - {23106,22543,22544 ,11246,11247,11243 ,0,0,0}, {22544,23103,23105 ,11243,11242,11245 ,0,0,0}, - {22543,23107,23108 ,11247,11248,11249 ,0,0,0}, {22543,23106,23107 ,11247,11246,11248 ,0,0,0}, - {22544,23109,23104 ,11243,11250,11244 ,0,0,0}, {22543,23108,22439 ,11247,11249,11251 ,0,0,0}, - {23110,22544,22452 ,11252,11243,11253 ,0,0,0}, {22544,23110,23109 ,11243,11252,11250 ,0,0,0}, - {22453,23111,23112 ,11254,11254,11255 ,0,0,0}, {23113,23114,22451 ,11256,11257,11258 ,0,0,0}, - {23115,23116,22453 ,11259,11260,11254 ,0,0,0}, {23115,22453,23112 ,11259,11254,11255 ,0,0,0}, - {22453,23117,22451 ,11254,11261,11258 ,0,0,0}, {23117,22453,23116 ,11261,11254,11260 ,0,0,0}, - {23118,22451,23114 ,11262,11258,11257 ,0,0,0}, {23117,23113,22451 ,11261,11256,11258 ,0,0,0}, - {23110,22452,23118 ,11252,11253,11262 ,0,0,0}, {23118,22452,22451 ,11262,11253,11258 ,0,0,0}, - {22661,23119,23120 ,11263,11264,11265 ,0,0,0}, {22738,23121,22692 ,11266,11267,11268 ,0,0,0}, - {23119,22661,23122 ,11264,11263,11269 ,0,0,0}, {23120,23123,22661 ,11265,11263,11263 ,0,0,0}, - {23122,22661,22692 ,11269,11263,11268 ,0,0,0}, {23124,23122,22692 ,11270,11269,11268 ,0,0,0}, - {23124,22692,23121 ,11270,11268,11267 ,0,0,0}, {22695,22719,23125 ,11271,11272,11273 ,0,0,0}, - {22695,23126,23127 ,11271,11274,11275 ,0,0,0}, {23125,23126,22695 ,11273,11274,11271 ,0,0,0}, - {22738,23127,23128 ,11266,11275,11276 ,0,0,0}, {22738,22695,23127 ,11266,11271,11275 ,0,0,0}, - {22738,23129,23130 ,11266,11277,11278 ,0,0,0}, {23128,23129,22738 ,11276,11277,11266 ,0,0,0}, - {22738,23131,23132 ,11266,11279,11280 ,0,0,0}, {23130,23131,22738 ,11278,11279,11266 ,0,0,0}, - {23121,22738,23133 ,11267,11266,11281 ,0,0,0}, {23132,23133,22738 ,11280,11281,11266 ,0,0,0}, - {23002,23111,22963 ,11282,11283,11282 ,0,0,0}, {22453,22927,23111 ,11282,11282,11283 ,0,0,0}, - {22984,23134,23111 ,11282,11283,11283 ,0,0,0}, {23111,23002,22984 ,11283,11282,11282 ,0,0,0}, - {22946,22963,23111 ,11282,11282,11283 ,0,0,0}, {22946,23111,22927 ,11282,11283,11282 ,0,0,0}, - {23135,23136,23110 ,21,21,21 ,0,0,0}, {23118,23137,23135 ,11284,21,21 ,0,0,0}, - {23135,23110,23118 ,21,21,11284 ,0,0,0}, {23138,23139,23140 ,11285,11286,11287 ,0,0,0}, - {23139,23141,23140 ,11286,11288,11287 ,0,0,0}, {23139,23138,23142 ,11286,11285,11289 ,0,0,0}, - {23105,23143,23142 ,11290,11291,11289 ,0,0,0}, {23138,23105,23142 ,11285,11290,11289 ,0,0,0}, - {23103,23143,23105 ,11292,11291,11290 ,0,0,0}, {23143,23103,23144 ,11291,11292,11293 ,0,0,0}, - {23104,23145,23144 ,11294,11295,11293 ,0,0,0}, {23144,23103,23104 ,11293,11292,11294 ,0,0,0}, - {23145,23109,23146 ,11295,11296,11297 ,0,0,0}, {23109,23145,23104 ,11296,11295,11294 ,0,0,0}, - {23136,23146,23110 ,11298,11297,11299 ,0,0,0}, {23109,23110,23146 ,11296,11299,11297 ,0,0,0}, - {23147,23148,23116 ,11300,11301,11302 ,0,0,0}, {23149,23117,23148 ,11303,11304,11301 ,0,0,0}, - {23118,23114,23137 ,21,11305,21 ,0,0,0}, {23113,23150,23114 ,11306,11307,11305 ,0,0,0}, - {23113,23149,23150 ,11306,11303,11307 ,0,0,0}, {23150,23137,23114 ,11307,21,11305 ,0,0,0}, - {23117,23149,23113 ,11304,11303,11306 ,0,0,0}, {23117,23116,23148 ,11304,11302,11301 ,0,0,0}, - {23147,23116,23115 ,11300,11302,11308 ,0,0,0}, {23115,23112,23151 ,11308,11309,11310 ,0,0,0}, - {23151,23147,23115 ,11310,11300,11308 ,0,0,0}, {23152,23112,23111 ,11311,11309,11312 ,0,0,0}, - {23112,23152,23151 ,11309,11311,11310 ,0,0,0}, {23152,23111,23134 ,11311,11312,11312 ,0,0,0}, - {22622,23134,22603 ,11313,11314,11315 ,0,0,0}, {23153,23123,23154 ,11316,11317,11318 ,0,0,0}, - {23123,23147,23151 ,11317,11319,11320 ,0,0,0}, {23151,23152,23123 ,11320,11321,11317 ,0,0,0}, - {23153,23155,23123 ,11316,11322,11317 ,0,0,0}, {23123,23156,23147 ,11317,11323,11319 ,0,0,0}, - {23155,23156,23123 ,11322,11323,11317 ,0,0,0}, {23134,22661,23123 ,11314,11324,11317 ,0,0,0}, - {23152,23134,23123 ,11321,11314,11317 ,0,0,0}, {23134,22641,22661 ,11314,11325,11324 ,0,0,0}, - {22641,23134,22622 ,11325,11314,11313 ,0,0,0}, {23134,22581,22582 ,11314,11326,11327 ,0,0,0}, - {23134,22984,22581 ,11314,11314,11326 ,0,0,0}, {22582,22603,23134 ,11327,11315,11314 ,0,0,0}, - {22816,22836,23157 ,11328,11329,11330 ,0,0,0}, {23125,23158,23126 ,11331,11332,11333 ,0,0,0}, - {23159,23158,22777 ,11334,11332,11335 ,0,0,0}, {23160,23141,23161 ,11336,11337,11338 ,0,0,0}, - {23162,23160,23161 ,11339,11336,11338 ,0,0,0}, {23163,23164,23165 ,11340,11341,11342 ,0,0,0}, - {23164,23162,23165 ,11341,11339,11342 ,0,0,0}, {23158,22757,22777 ,11332,11343,11335 ,0,0,0}, - {23159,22777,22796 ,11334,11335,11344 ,0,0,0}, {23163,23127,23126 ,11340,11345,11333 ,0,0,0}, - {22719,22757,23125 ,11346,11343,11331 ,0,0,0}, {22816,23159,22796 ,11328,11334,11344 ,0,0,0}, - {23157,23166,23159 ,11330,11347,11334 ,0,0,0}, {23159,22816,23157 ,11334,11328,11330 ,0,0,0}, - {23166,23160,23162 ,11347,11336,11339 ,0,0,0}, {23164,23163,23126 ,11341,11340,11333 ,0,0,0}, - {23162,23164,23159 ,11339,11341,11334 ,0,0,0}, {23125,22757,23158 ,11331,11343,11332 ,0,0,0}, - {23162,23159,23166 ,11339,11334,11347 ,0,0,0}, {23161,23165,23162 ,11338,11342,11339 ,0,0,0}, - {23126,23158,23164 ,11333,11332,11341 ,0,0,0}, {23159,23164,23158 ,11334,11341,11332 ,0,0,0}, - {23167,23168,23169 ,11348,11349,11350 ,0,0,0}, {23143,23170,23171 ,11351,11352,11353 ,0,0,0}, - {23143,23144,23170 ,11351,11354,11352 ,0,0,0}, {23161,23139,23172 ,11355,11356,11357 ,0,0,0}, - {23173,23131,23174 ,11358,11359,11360 ,0,0,0}, {23161,23141,23139 ,11355,11361,11356 ,0,0,0}, - {23175,23176,23177 ,11362,11363,11364 ,0,0,0}, {23145,23178,23179 ,11365,11366,11367 ,0,0,0}, - {23136,23176,23180 ,21,11363,11368 ,0,0,0}, {23175,23181,23180 ,11362,11369,11368 ,0,0,0}, - {23133,23132,23182 ,11370,11371,11372 ,0,0,0}, {23132,23173,23182 ,11371,11358,11372 ,0,0,0}, - {23183,23184,23167 ,11373,11374,11348 ,0,0,0}, {23173,23174,23181 ,11358,11360,11369 ,0,0,0}, - {23185,23121,23133 ,11375,11376,11370 ,0,0,0}, {23142,23171,23172 ,11377,11353,11357 ,0,0,0}, - {23145,23179,23144 ,11365,11367,11354 ,0,0,0}, {23172,23169,23165 ,11357,11350,11378 ,0,0,0}, - {23165,23169,23163 ,11378,11350,11379 ,0,0,0}, {23163,23168,23127 ,11379,11349,11380 ,0,0,0}, - {23161,23172,23165 ,11355,11357,11378 ,0,0,0}, {23139,23142,23172 ,11356,11377,11357 ,0,0,0}, - {23168,23163,23169 ,11349,11379,11350 ,0,0,0}, {23168,23184,23128 ,11349,11374,11381 ,0,0,0}, - {23169,23171,23167 ,11350,11353,11348 ,0,0,0}, {23127,23168,23128 ,11380,11349,11381 ,0,0,0}, - {23172,23171,23169 ,11357,11353,11350 ,0,0,0}, {23142,23143,23171 ,11377,11351,11353 ,0,0,0}, - {23184,23168,23167 ,11374,11349,11348 ,0,0,0}, {23184,23186,23129 ,11374,11382,11383 ,0,0,0}, - {23167,23170,23183 ,11348,11352,11373 ,0,0,0}, {23128,23184,23129 ,11381,11374,11383 ,0,0,0}, - {23171,23170,23167 ,11353,11352,11348 ,0,0,0}, {23179,23170,23144 ,11367,11352,11354 ,0,0,0}, - {23186,23184,23183 ,11382,11374,11373 ,0,0,0}, {23186,23174,23130 ,11382,11360,11384 ,0,0,0}, - {23179,23187,23183 ,11367,11385,11373 ,0,0,0}, {23129,23186,23130 ,11383,11382,11384 ,0,0,0}, - {23179,23183,23170 ,11367,11373,11352 ,0,0,0}, {23146,23178,23145 ,11386,11366,11365 ,0,0,0}, - {23174,23186,23187 ,11360,11382,11385 ,0,0,0}, {23183,23187,23186 ,11373,11385,11382 ,0,0,0}, - {23178,23181,23187 ,11366,11369,11385 ,0,0,0}, {23130,23174,23131 ,11384,11360,11359 ,0,0,0}, - {23179,23178,23187 ,11367,11366,11385 ,0,0,0}, {23136,23180,23146 ,21,11368,11386 ,0,0,0}, - {23182,23173,23175 ,11372,11358,11362 ,0,0,0}, {23187,23181,23174 ,11385,11369,11360 ,0,0,0}, - {23181,23175,23173 ,11369,11362,11358 ,0,0,0}, {23131,23173,23132 ,11359,11358,11371 ,0,0,0}, - {23178,23146,23180 ,11366,11386,11368 ,0,0,0}, {23181,23178,23180 ,11369,11366,11368 ,0,0,0}, - {23182,23177,23185 ,11372,11364,11375 ,0,0,0}, {23176,23175,23180 ,11363,11362,11368 ,0,0,0}, - {23185,23133,23182 ,11375,11370,11372 ,0,0,0}, {23177,23182,23175 ,11364,11372,11362 ,0,0,0}, - {23176,23135,23188 ,11387,11388,11389 ,0,0,0}, {23124,23189,23122 ,11390,11391,11269 ,0,0,0}, - {23188,23135,23190 ,11389,11388,11392 ,0,0,0}, {23135,23137,23190 ,11388,21,11392 ,0,0,0}, - {23188,23191,23189 ,11389,11393,11391 ,0,0,0}, {23176,23136,23135 ,11387,21,11388 ,0,0,0}, - {23189,23191,23122 ,11391,11393,11269 ,0,0,0}, {23185,23189,23124 ,11394,11391,11390 ,0,0,0}, - {23121,23185,23124 ,11395,11394,11390 ,0,0,0}, {23185,23177,23189 ,11394,11396,11391 ,0,0,0}, - {23177,23176,23188 ,11396,11387,11389 ,0,0,0}, {23177,23188,23189 ,11396,11389,11391 ,0,0,0}, - {23191,23188,23190 ,11393,11389,11392 ,0,0,0}, {23156,23155,23148 ,11397,11398,11399 ,0,0,0}, - {23190,23137,23150 ,11400,21,11401 ,0,0,0}, {23150,23149,23192 ,11401,11402,11403 ,0,0,0}, - {23150,23192,23190 ,11401,11403,11400 ,0,0,0}, {23147,23156,23148 ,11404,11397,11399 ,0,0,0}, - {23153,23154,23193 ,11405,11406,11407 ,0,0,0}, {23193,23194,23153 ,11407,11408,11405 ,0,0,0}, - {23191,23192,23195 ,11409,11403,11410 ,0,0,0}, {23195,23192,23194 ,11410,11403,11408 ,0,0,0}, - {23154,23123,23120 ,11406,11411,11412 ,0,0,0}, {23191,23195,23122 ,11409,11410,11413 ,0,0,0}, - {23120,23195,23193 ,11412,11410,11407 ,0,0,0}, {23190,23192,23191 ,11400,11403,11409 ,0,0,0}, - {23120,23119,23195 ,11412,11414,11410 ,0,0,0}, {23195,23119,23122 ,11410,11414,11413 ,0,0,0}, - {23192,23149,23194 ,11403,11402,11408 ,0,0,0}, {23148,23194,23149 ,11399,11408,11402 ,0,0,0}, - {23120,23193,23154 ,11412,11407,11406 ,0,0,0}, {23195,23194,23193 ,11410,11408,11407 ,0,0,0}, - {23155,23194,23148 ,11398,11408,11399 ,0,0,0}, {23155,23153,23194 ,11398,11405,11408 ,0,0,0}, - {23196,22891,23197 ,11415,11416,11417 ,0,0,0}, {22910,22439,23108 ,11418,11419,11420 ,0,0,0}, - {23138,23198,23105 ,11421,11422,11423 ,0,0,0}, {23199,23160,23200 ,11424,11425,11426 ,0,0,0}, - {23160,23199,23140 ,11425,11424,11427 ,0,0,0}, {23140,23141,23160 ,11427,11428,11425 ,0,0,0}, - {23166,23200,23160 ,11429,11426,11425 ,0,0,0}, {23196,22874,22891 ,11415,11430,11416 ,0,0,0}, - {23140,23199,23138 ,11427,11424,11421 ,0,0,0}, {23198,23200,23201 ,11422,11426,11431 ,0,0,0}, - {23157,22836,22856 ,11432,11433,11434 ,0,0,0}, {22874,23196,22856 ,11430,11415,11434 ,0,0,0}, - {23201,23107,23106 ,11431,11435,11436 ,0,0,0}, {23197,22910,23108 ,11417,11418,11420 ,0,0,0}, - {23199,23200,23198 ,11424,11426,11422 ,0,0,0}, {23201,23106,23198 ,11431,11436,11422 ,0,0,0}, - {23105,23198,23106 ,11423,11422,11436 ,0,0,0}, {23138,23199,23198 ,11421,11424,11422 ,0,0,0}, - {23196,23166,23157 ,11415,11429,11432 ,0,0,0}, {23201,23196,23197 ,11431,11415,11417 ,0,0,0}, - {23201,23200,23196 ,11431,11426,11415 ,0,0,0}, {23107,23201,23197 ,11435,11431,11417 ,0,0,0}, - {23166,23196,23200 ,11429,11415,11426 ,0,0,0}, {22856,23196,23157 ,11434,11415,11432 ,0,0,0}, - {22910,23197,22891 ,11418,11417,11416 ,0,0,0}, {23197,23108,23107 ,11417,11420,11435 ,0,0,0}, - {22533,22396,22395 ,11437,11438,11439 ,0,0,0}, {23202,23203,22422 ,11440,11441,11442 ,0,0,0}, - {22469,23204,23205 ,11443,11444,11445 ,0,0,0}, {22427,22426,23206 ,11446,11447,11448 ,0,0,0}, - {22466,22501,23207 ,11449,11450,11451 ,0,0,0}, {22430,22431,23208 ,11452,11453,11454 ,0,0,0}, - {22430,23209,22426 ,11452,11455,11447 ,0,0,0}, {23210,22521,23211 ,11456,11457,11458 ,0,0,0}, - {22521,23210,22431 ,11457,11456,11453 ,0,0,0}, {23212,23211,22520 ,11459,11458,11460 ,0,0,0}, - {22521,22520,23211 ,11457,11460,11458 ,0,0,0}, {22409,22410,23212 ,21,21,11459 ,0,0,0}, - {23212,22520,22409 ,11459,11460,21 ,0,0,0}, {23208,23209,22430 ,11454,11455,11452 ,0,0,0}, - {22431,23210,23208 ,11453,11456,11454 ,0,0,0}, {23206,23207,22427 ,11448,11451,11446 ,0,0,0}, - {22426,23209,23206 ,11447,11455,11448 ,0,0,0}, {23202,22466,23207 ,11440,11449,11451 ,0,0,0}, - {22501,22427,23207 ,11450,11446,11451 ,0,0,0}, {23203,22420,22422 ,11441,11461,11442 ,0,0,0}, - {23202,22422,22466 ,11440,11442,11449 ,0,0,0}, {22469,22420,23204 ,11443,11461,11444 ,0,0,0}, - {23203,23204,22420 ,11441,11444,11461 ,0,0,0}, {22533,23205,23213 ,11437,11445,11462 ,0,0,0}, - {22469,23205,22533 ,11443,11445,11437 ,0,0,0}, {22396,22533,23213 ,11438,11437,11462 ,0,0,0}, - {23204,22375,22378 ,730,730,730 ,0,0,0}, {22391,23214,22389 ,730,730,730 ,0,0,0}, - {22391,22394,23215 ,730,730,730 ,0,0,0}, {22387,22389,23216 ,730,730,730 ,0,0,0}, - {22394,22381,23215 ,730,730,730 ,0,0,0}, {23214,22391,23215 ,730,730,730 ,0,0,0}, - {22381,22394,22396 ,730,730,730 ,0,0,0}, {22387,23217,22384 ,730,730,730 ,0,0,0}, - {23213,22381,22396 ,730,730,730 ,0,0,0}, {22363,22375,23202 ,730,730,730 ,0,0,0}, - {22398,22386,23218 ,730,730,730 ,0,0,0}, {23219,22399,22398 ,730,730,730 ,0,0,0}, - {15837,22363,23207 ,730,730,730 ,0,0,0}, {22365,23206,23209 ,730,730,730 ,0,0,0}, - {23220,22402,22399 ,730,730,730 ,0,0,0}, {22402,23221,22403 ,730,730,730 ,0,0,0}, - {22405,22403,23222 ,730,730,730 ,0,0,0}, {23209,22366,22365 ,730,730,730 ,0,0,0}, - {22366,23208,23210 ,730,730,730 ,0,0,0}, {22373,23212,22410 ,730,730,730 ,0,0,0}, - {22410,22408,22373 ,730,730,730 ,0,0,0}, {22405,23223,22408 ,730,730,730 ,0,0,0}, - {23211,22372,23210 ,730,730,730 ,0,0,0}, {22386,22384,23218 ,730,730,730 ,0,0,0}, - {22378,22380,23205 ,730,730,730 ,0,0,0}, {23207,23206,15837 ,730,730,730 ,0,0,0}, - {23214,23216,22389 ,730,730,730 ,0,0,0}, {23216,23217,22387 ,730,730,730 ,0,0,0}, - {23217,23218,22384 ,730,730,730 ,0,0,0}, {23218,23219,22398 ,730,730,730 ,0,0,0}, - {23219,23220,22399 ,730,730,730 ,0,0,0}, {23220,23221,22402 ,730,730,730 ,0,0,0}, - {23221,23222,22403 ,730,730,730 ,0,0,0}, {23222,23223,22405 ,730,730,730 ,0,0,0}, - {23223,22373,22408 ,730,730,730 ,0,0,0}, {22373,22369,23212 ,730,730,730 ,0,0,0}, - {22369,22372,23211 ,730,730,730 ,0,0,0}, {22369,23211,23212 ,730,730,730 ,0,0,0}, - {22372,22366,23210 ,730,730,730 ,0,0,0}, {23208,22366,23209 ,730,730,730 ,0,0,0}, - {22365,15837,23206 ,730,730,730 ,0,0,0}, {22363,23202,23207 ,730,730,730 ,0,0,0}, - {22375,23203,23202 ,730,730,730 ,0,0,0}, {23204,22378,23205 ,730,730,730 ,0,0,0}, - {23203,22375,23204 ,730,730,730 ,0,0,0}, {23205,22380,23213 ,730,730,730 ,0,0,0}, - {22381,23213,22380 ,730,730,730 ,0,0,0}, {22379,23224,23225 ,730,730,11463 ,0,0,0}, - {23226,23225,23227 ,730,11463,730 ,0,0,0}, {23226,23227,23228 ,730,730,11463 ,0,0,0}, - {23229,23225,23226 ,730,11463,730 ,0,0,0}, {23229,22382,23225 ,730,730,11463 ,0,0,0}, - {23228,23227,23230 ,11463,730,11464 ,0,0,0}, {22379,23225,22382 ,730,11463,730 ,0,0,0}, - {23224,22377,23231 ,730,730,11464 ,0,0,0}, {23224,22379,22377 ,730,730,730 ,0,0,0}, - {23231,22377,23232 ,11464,730,730 ,0,0,0}, {23232,22377,22376 ,730,730,11464 ,0,0,0}, - {23232,22376,22374 ,730,11464,730 ,0,0,0}, {23233,22374,22362 ,11465,730,11464 ,0,0,0}, - {22374,23233,23232 ,730,11465,730 ,0,0,0}, {22370,23233,22367 ,730,11465,730 ,0,0,0}, - {22362,22367,23233 ,11464,730,11465 ,0,0,0}, {22371,22364,22368 ,11464,730,11466 ,0,0,0}, - {22367,22364,22371 ,730,730,11464 ,0,0,0}, {22371,22370,22367 ,11464,730,730 ,0,0,0}, - {22373,23223,23233 ,11467,11468,11469 ,0,0,0}, {23225,23224,23220 ,11470,11471,11472 ,0,0,0}, - {23231,23232,23222 ,11473,11474,11475 ,0,0,0}, {23230,23218,23217 ,11476,11477,11478 ,0,0,0}, - {23219,23218,23227 ,11479,11477,11480 ,0,0,0}, {23226,23216,23214 ,11481,11482,11483 ,0,0,0}, - {23216,23226,23228 ,11482,11481,11484 ,0,0,0}, {23215,23229,23214 ,11485,11486,11483 ,0,0,0}, - {23226,23214,23229 ,11481,11483,11486 ,0,0,0}, {23215,22381,22382 ,11485,11487,11487 ,0,0,0}, - {22382,23229,23215 ,11487,11486,11485 ,0,0,0}, {23230,23217,23228 ,11476,11478,11484 ,0,0,0}, - {23217,23216,23228 ,11478,11482,11484 ,0,0,0}, {23220,23219,23225 ,11472,11479,11470 ,0,0,0}, - {23219,23227,23225 ,11479,11480,11470 ,0,0,0}, {23227,23218,23230 ,11480,11477,11476 ,0,0,0}, - {23232,23233,23223 ,11474,11469,11468 ,0,0,0}, {23221,23220,23224 ,11488,11472,11471 ,0,0,0}, - {23223,23222,23232 ,11468,11475,11474 ,0,0,0}, {23221,23231,23222 ,11488,11473,11475 ,0,0,0}, - {23224,23231,23221 ,11471,11473,11488 ,0,0,0}, {23233,22370,22373 ,11469,11489,11467 ,0,0,0}, - {22435,22350,22349 ,11490,324,11491 ,0,0,0}, {23234,23235,22517 ,11492,11493,11494 ,0,0,0}, - {22518,23236,22437 ,11495,11496,11497 ,0,0,0}, {23237,22456,23238 ,11498,11499,11500 ,0,0,0}, - {22513,22458,23239 ,11501,11502,11503 ,0,0,0}, {23240,22455,22515 ,11504,11505,11506 ,0,0,0}, - {22455,23240,23238 ,11505,11504,11500 ,0,0,0}, {22447,23241,22515 ,11507,11508,11506 ,0,0,0}, - {23240,22515,23241 ,11504,11506,11508 ,0,0,0}, {22447,22361,22360 ,11507,1095,1631 ,0,0,0}, - {22360,23241,22447 ,1631,11508,11507 ,0,0,0}, {22456,23237,22458 ,11499,11498,11502 ,0,0,0}, - {22456,22455,23238 ,11499,11505,11500 ,0,0,0}, {23234,22513,23239 ,11492,11501,11503 ,0,0,0}, - {23239,22458,23237 ,11503,11502,11498 ,0,0,0}, {23235,22518,22517 ,11493,11495,11494 ,0,0,0}, - {23234,22517,22513 ,11492,11494,11501 ,0,0,0}, {23236,23242,22437 ,11496,11509,11497 ,0,0,0}, - {23235,23236,22518 ,11493,11496,11495 ,0,0,0}, {22350,22435,23242 ,324,11490,11509 ,0,0,0}, - {22437,23242,22435 ,11497,11509,11490 ,0,0,0}, {22357,23234,22358 ,730,730,730 ,0,0,0}, - {22354,23236,22355 ,730,730,730 ,0,0,0}, {22360,23239,23237 ,730,730,730 ,0,0,0}, - {23241,23237,23238 ,730,730,730 ,0,0,0}, {23240,23241,23238 ,730,730,730 ,0,0,0}, - {22358,23239,22360 ,730,730,730 ,0,0,0}, {22360,23237,23241 ,730,730,730 ,0,0,0}, - {22358,23234,23239 ,730,730,730 ,0,0,0}, {22357,23235,23234 ,730,730,730 ,0,0,0}, - {22357,22355,23236 ,730,730,730 ,0,0,0}, {23236,23235,22357 ,730,730,730 ,0,0,0}, - {23242,23236,22354 ,730,730,730 ,0,0,0}, {23242,22351,22350 ,730,730,730 ,0,0,0}, - {22351,23242,22354 ,730,730,730 ,0,0,0}, {22350,22351,22343 ,730,730,730 ,0,0,0}, - {22346,22340,22344 ,730,730,730 ,0,0,0}, {22343,22340,22346 ,730,730,730 ,0,0,0}, - {22346,22350,22343 ,730,730,730 ,0,0,0}, {22528,22328,22329 ,11510,11511,11512 ,0,0,0}, - {23243,23244,22474 ,11492,11493,11513 ,0,0,0}, {22475,23245,22527 ,11514,11496,11515 ,0,0,0}, - {23246,22472,22471 ,11498,11516,11517 ,0,0,0}, {22488,22472,23247 ,11518,11516,11519 ,0,0,0}, - {23248,22532,22424 ,11504,11520,11521 ,0,0,0}, {22471,22532,23249 ,11517,11520,11500 ,0,0,0}, - {22423,23250,22424 ,11522,11508,11521 ,0,0,0}, {23248,22424,23250 ,11504,11521,11508 ,0,0,0}, - {22423,22339,22338 ,11522,11487,11523 ,0,0,0}, {22338,23250,22423 ,11523,11508,11522 ,0,0,0}, - {23246,22471,23249 ,11498,11517,11500 ,0,0,0}, {23249,22532,23248 ,11500,11520,11504 ,0,0,0}, - {22488,23247,23243 ,11518,11519,11492 ,0,0,0}, {23247,22472,23246 ,11519,11516,11498 ,0,0,0}, - {23244,22475,22474 ,11493,11514,11513 ,0,0,0}, {23243,22474,22488 ,11492,11513,11518 ,0,0,0}, - {23245,23251,22527 ,11496,11509,11515 ,0,0,0}, {23244,23245,22475 ,11493,11496,11514 ,0,0,0}, - {22328,22528,23251 ,11511,11510,11509 ,0,0,0}, {22527,23251,22528 ,11515,11509,11510 ,0,0,0}, - {22333,23243,22335 ,730,730,730 ,0,0,0}, {22330,23245,22332 ,730,730,730 ,0,0,0}, - {22338,23247,23246 ,730,730,730 ,0,0,0}, {23250,23246,23249 ,730,730,730 ,0,0,0}, - {23248,23250,23249 ,730,730,730 ,0,0,0}, {22335,23247,22338 ,730,730,730 ,0,0,0}, - {22338,23246,23250 ,730,730,730 ,0,0,0}, {22335,23243,23247 ,730,730,730 ,0,0,0}, - {22333,23244,23243 ,730,730,730 ,0,0,0}, {22333,22332,23245 ,730,730,730 ,0,0,0}, - {23245,23244,22333 ,730,730,730 ,0,0,0}, {23251,23245,22330 ,730,730,730 ,0,0,0}, - {23251,22318,22328 ,730,730,730 ,0,0,0}, {22318,23251,22330 ,730,730,730 ,0,0,0}, - {22328,22318,22321 ,730,730,730 ,0,0,0}, {22324,22322,22325 ,730,730,730 ,0,0,0}, - {22321,22322,22324 ,730,730,730 ,0,0,0}, {22324,22328,22321 ,730,730,730 ,0,0,0} -// Landegestell.prt - , {23252,23253,23254 ,11524,11525,11526 ,0,0,0}, {23255,23256,23257 ,11527,11528,11529 ,0,0,0}, - {23258,23259,23260 ,11530,11531,11532 ,0,0,0}, {23261,23253,23262 ,11533,11525,11534 ,0,0,0}, - {23263,23260,23264 ,11535,11532,11536 ,0,0,0}, {23265,23266,23267 ,11537,11538,11539 ,0,0,0}, - {23268,23269,23270 ,11540,11541,11542 ,0,0,0}, {23271,23264,23259 ,11543,11536,11531 ,0,0,0}, - {23272,23273,23274 ,11544,11545,11546 ,0,0,0}, {23268,23275,23274 ,11540,11547,11546 ,0,0,0}, - {23276,23277,23278 ,11548,11549,11550 ,0,0,0}, {23278,23277,23273 ,11550,11549,11545 ,0,0,0}, - {23279,23278,23280 ,11551,11550,11552 ,0,0,0}, {23262,23253,23252 ,11534,11525,11524 ,0,0,0}, - {23280,23281,23279 ,11552,11553,11551 ,0,0,0}, {23282,23283,23284 ,11554,11555,11556 ,0,0,0}, - {23254,23285,23252 ,11526,11557,11524 ,0,0,0}, {23286,23287,23284 ,11558,11559,11556 ,0,0,0}, - {23288,23289,23286 ,11560,11561,11558 ,0,0,0}, {23289,23290,23286 ,11561,11562,11558 ,0,0,0}, - {23284,23287,23282 ,11556,11559,11554 ,0,0,0}, {23291,23292,23256 ,11563,11564,11528 ,0,0,0}, - {23293,23294,23295 ,11565,11566,11567 ,0,0,0}, {23291,23296,23292 ,11563,11568,11564 ,0,0,0}, - {23297,23298,23299 ,11569,11570,11571 ,0,0,0}, {23294,23300,23295 ,11566,11572,11567 ,0,0,0}, - {23301,23302,23303 ,11573,11574,11575 ,0,0,0}, {23297,23299,23304 ,11569,11571,11576 ,0,0,0}, - {23305,23306,23307 ,11577,11578,11579 ,0,0,0}, {23306,23305,23308 ,11578,11577,11580 ,0,0,0}, - {23309,23310,23311 ,11581,11582,11583 ,0,0,0}, {23312,23313,23310 ,11584,11585,11582 ,0,0,0}, - {23314,23315,23316 ,11586,11587,11588 ,0,0,0}, {23309,23311,23317 ,11581,11583,11589 ,0,0,0}, - {23318,23319,23320 ,11590,11591,11592 ,0,0,0}, {23314,23316,23321 ,11586,11588,11593 ,0,0,0}, - {23322,23323,23324 ,11594,11595,11596 ,0,0,0}, {23325,23319,23318 ,11597,11591,11590 ,0,0,0}, - {23326,23327,23328 ,11598,11599,11600 ,0,0,0}, {23328,23324,23326 ,11600,11596,11598 ,0,0,0}, - {23329,23330,23331 ,11601,11602,11603 ,0,0,0}, {23332,23327,23333 ,11604,11599,11605 ,0,0,0}, - {23334,23335,23336 ,11606,11607,11608 ,0,0,0}, {23337,23334,23338 ,11609,11606,11610 ,0,0,0}, - {23339,23340,23341 ,11611,11612,11613 ,0,0,0}, {23342,23339,23336 ,11614,11611,11608 ,0,0,0}, - {23343,23344,23345 ,11615,11616,11617 ,0,0,0}, {23346,23341,23347 ,11618,11613,11619 ,0,0,0}, - {23348,23349,23350 ,11620,11621,11622 ,0,0,0}, {23345,23351,23343 ,11617,11623,11615 ,0,0,0}, - {23352,23348,23353 ,11624,11620,11625 ,0,0,0}, {23343,23351,23354 ,11615,11623,11626 ,0,0,0}, - {23355,23352,23346 ,11627,11624,11618 ,0,0,0}, {23348,23352,23355 ,11620,11624,11627 ,0,0,0}, - {23356,23357,23358 ,11628,11629,11630 ,0,0,0}, {23359,23342,23360 ,11631,11614,11632 ,0,0,0}, - {23361,23362,23363 ,11633,11634,11635 ,0,0,0}, {23359,23360,23364 ,11631,11632,11636 ,0,0,0}, - {23365,23366,23367 ,11637,11638,11639 ,0,0,0}, {23363,23368,23369 ,11635,11640,11641 ,0,0,0}, - {23370,23371,23367 ,11642,11643,11639 ,0,0,0}, {23372,23373,23374 ,11644,11645,11646 ,0,0,0}, - {23375,23376,23377 ,11647,11648,11649 ,0,0,0}, {23377,23374,23375 ,11649,11646,11647 ,0,0,0}, - {23376,23375,23378 ,11648,11647,11650 ,0,0,0}, {23347,23341,23340 ,11619,11613,11612 ,0,0,0}, - {23348,23354,23353 ,11620,11626,11625 ,0,0,0}, {23342,23336,23335 ,11614,11608,11607 ,0,0,0}, - {23342,23340,23339 ,11614,11612,11611 ,0,0,0}, {23337,23338,23329 ,11609,11610,11601 ,0,0,0}, - {23334,23337,23335 ,11606,11609,11607 ,0,0,0}, {23331,23330,23332 ,11603,11602,11604 ,0,0,0}, - {23338,23330,23329 ,11610,11602,11601 ,0,0,0}, {23331,23332,23333 ,11603,11604,11605 ,0,0,0}, - {23379,23337,23329 ,11651,11609,11601 ,0,0,0}, {23328,23322,23324 ,11600,11594,11596 ,0,0,0}, - {23327,23326,23333 ,11599,11598,11605 ,0,0,0}, {23318,23320,23380 ,11590,11592,11652 ,0,0,0}, - {23381,23325,23382 ,11653,11597,11654 ,0,0,0}, {23324,23323,23382 ,11596,11595,11654 ,0,0,0}, - {23319,23325,23381 ,11591,11597,11653 ,0,0,0}, {23323,23381,23382 ,11595,11653,11654 ,0,0,0}, - {23380,23320,23321 ,11652,11592,11593 ,0,0,0}, {23383,23318,23380 ,11655,11590,11652 ,0,0,0}, - {23321,23316,23380 ,11593,11588,11652 ,0,0,0}, {23317,23315,23384 ,11589,11587,11656 ,0,0,0}, - {23314,23384,23315 ,11586,11656,11587 ,0,0,0}, {23385,23317,23384 ,11657,11589,11656 ,0,0,0}, - {23313,23311,23310 ,11585,11583,11582 ,0,0,0}, {23309,23317,23385 ,11581,11589,11657 ,0,0,0}, - {23312,23386,23313 ,11584,11658,11585 ,0,0,0}, {23307,23306,23386 ,11579,11578,11658 ,0,0,0}, - {23386,23312,23307 ,11658,11584,11579 ,0,0,0}, {23308,23387,23303 ,11580,11659,11575 ,0,0,0}, - {23388,23389,23390 ,11660,11661,11662 ,0,0,0}, {23303,23387,23391 ,11575,11659,11663 ,0,0,0}, - {23387,23308,23305 ,11659,11580,11577 ,0,0,0}, {23392,23304,23302 ,11664,11576,11574 ,0,0,0}, - {23301,23303,23391 ,11573,11575,11663 ,0,0,0}, {23304,23392,23297 ,11576,11664,11569 ,0,0,0}, - {23392,23302,23301 ,11664,11574,11573 ,0,0,0}, {23296,23393,23394 ,11568,11665,11666 ,0,0,0}, - {23298,23300,23395 ,11570,11572,11667 ,0,0,0}, {23299,23298,23395 ,11571,11570,11667 ,0,0,0}, - {23395,23300,23294 ,11667,11572,11566 ,0,0,0}, {23396,23397,23398 ,11668,11669,11670 ,0,0,0}, - {23393,23293,23295 ,11665,11565,11567 ,0,0,0}, {23285,23254,23283 ,11557,11526,11555 ,0,0,0}, - {23296,23293,23393 ,11568,11565,11665 ,0,0,0}, {23296,23394,23292 ,11568,11666,11564 ,0,0,0}, - {23256,23255,23291 ,11528,11527,11563 ,0,0,0}, {23290,23289,23257 ,11562,11561,11529 ,0,0,0}, - {23257,23289,23255 ,11529,11561,11527 ,0,0,0}, {23282,23285,23283 ,11554,11557,11555 ,0,0,0}, - {23290,23287,23286 ,11562,11559,11558 ,0,0,0}, {23267,23399,23400 ,11539,11671,11672 ,0,0,0}, - {23261,23262,23399 ,11533,11534,11671 ,0,0,0}, {23400,23265,23267 ,11672,11537,11539 ,0,0,0}, - {23261,23399,23267 ,11533,11671,11539 ,0,0,0}, {23400,23401,23265 ,11672,11673,11537 ,0,0,0}, - {23402,23403,23269 ,11674,11675,11541 ,0,0,0}, {23265,23401,23404 ,11537,11673,11676 ,0,0,0}, - {23404,23401,23405 ,11676,11673,11677 ,0,0,0}, {23406,23404,23407 ,11678,11676,11679 ,0,0,0}, - {23405,23407,23404 ,11677,11679,11676 ,0,0,0}, {23270,23408,23268 ,11542,11680,11540 ,0,0,0}, - {23409,23406,23407 ,11681,11678,11679 ,0,0,0}, {23410,23409,23407 ,11682,11681,11679 ,0,0,0}, - {23406,23409,23411 ,11678,11681,11683 ,0,0,0}, {23412,23413,23411 ,11684,11685,11683 ,0,0,0}, - {23403,23402,23414 ,11675,11674,11686 ,0,0,0}, {23411,23413,23406 ,11683,11685,11678 ,0,0,0}, - {23412,23402,23413 ,11684,11674,11685 ,0,0,0}, {23406,23415,23404 ,11678,11687,11676 ,0,0,0}, - {23416,23261,23267 ,11688,11533,11539 ,0,0,0}, {23404,23258,23265 ,11676,11530,11537 ,0,0,0}, - {23417,23253,23261 ,11689,11525,11533 ,0,0,0}, {23266,23265,23258 ,11538,11537,11530 ,0,0,0}, - {23418,23254,23253 ,11690,11526,11525 ,0,0,0}, {23416,23267,23266 ,11688,11539,11538 ,0,0,0}, - {23419,23283,23254 ,11691,11555,11526 ,0,0,0}, {23417,23261,23416 ,11689,11533,11688 ,0,0,0}, - {23420,23284,23283 ,11692,11556,11555 ,0,0,0}, {23418,23253,23417 ,11690,11525,11689 ,0,0,0}, - {23421,23286,23284 ,11693,11558,11556 ,0,0,0}, {23254,23418,23419 ,11526,11690,11691 ,0,0,0}, - {23422,23423,23424 ,11694,11695,11696 ,0,0,0}, {23283,23419,23420 ,11555,11691,11692 ,0,0,0}, - {23424,23255,23289 ,11696,11527,11561 ,0,0,0}, {23284,23420,23421 ,11556,11692,11693 ,0,0,0}, - {23425,23291,23255 ,11697,11563,11527 ,0,0,0}, {23286,23421,23288 ,11558,11693,11560 ,0,0,0}, - {23426,23296,23291 ,11698,11568,11563 ,0,0,0}, {23289,23288,23424 ,11561,11560,11696 ,0,0,0}, - {23427,23293,23296 ,11699,11565,11568 ,0,0,0}, {23255,23424,23425 ,11527,11696,11697 ,0,0,0}, - {23428,23294,23293 ,11700,11566,11565 ,0,0,0}, {23426,23291,23425 ,11698,11563,11697 ,0,0,0}, - {23429,23395,23294 ,11701,11667,11566 ,0,0,0}, {23427,23296,23426 ,11699,11568,11698 ,0,0,0}, - {23430,23299,23395 ,11702,11571,11667 ,0,0,0}, {23293,23427,23428 ,11565,11699,11700 ,0,0,0}, - {23397,23304,23299 ,11669,11576,11571 ,0,0,0}, {23294,23428,23429 ,11566,11700,11701 ,0,0,0}, - {23431,23302,23304 ,11703,11574,11576 ,0,0,0}, {23395,23429,23430 ,11667,11701,11702 ,0,0,0}, - {23432,23303,23302 ,11704,11575,11574 ,0,0,0}, {23299,23430,23397 ,11571,11702,11669 ,0,0,0}, - {23433,23308,23303 ,11705,11580,11575 ,0,0,0}, {23431,23304,23397 ,11703,11576,11669 ,0,0,0}, - {23434,23306,23308 ,11706,11578,11580 ,0,0,0}, {23432,23302,23431 ,11704,11574,11703 ,0,0,0}, - {23435,23386,23306 ,11707,11658,11578 ,0,0,0}, {23303,23432,23433 ,11575,11704,11705 ,0,0,0}, - {23313,23386,23388 ,11585,11658,11660 ,0,0,0}, {23308,23433,23434 ,11580,11705,11706 ,0,0,0}, - {23436,23311,23313 ,11708,11583,11585 ,0,0,0}, {23306,23434,23435 ,11578,11706,11707 ,0,0,0}, - {23437,23317,23311 ,11709,11589,11583 ,0,0,0}, {23386,23435,23388 ,11658,11707,11660 ,0,0,0}, - {23438,23315,23317 ,11710,11587,11589 ,0,0,0}, {23436,23313,23388 ,11708,11585,11660 ,0,0,0}, - {23439,23316,23315 ,11711,11588,11587 ,0,0,0}, {23437,23311,23436 ,11709,11583,11708 ,0,0,0}, - {23440,23380,23316 ,11712,11652,11588 ,0,0,0}, {23317,23437,23438 ,11589,11709,11710 ,0,0,0}, - {23441,23442,23443 ,11713,11714,11715 ,0,0,0}, {23315,23438,23439 ,11587,11710,11711 ,0,0,0}, - {23444,23325,23318 ,11716,11597,11590 ,0,0,0}, {23316,23439,23440 ,11588,11711,11712 ,0,0,0}, - {23445,23382,23325 ,11717,11654,11597 ,0,0,0}, {23380,23440,23383 ,11652,11712,11655 ,0,0,0}, - {23446,23324,23382 ,11718,11596,11654 ,0,0,0}, {23318,23383,23444 ,11590,11655,11716 ,0,0,0}, - {23447,23326,23324 ,11719,11598,11596 ,0,0,0}, {23445,23325,23444 ,11717,11597,11716 ,0,0,0}, - {23448,23333,23326 ,11720,11605,11598 ,0,0,0}, {23446,23382,23445 ,11718,11654,11717 ,0,0,0}, - {23449,23331,23333 ,11721,11603,11605 ,0,0,0}, {23447,23324,23446 ,11719,11596,11718 ,0,0,0}, - {23450,23329,23331 ,11722,11601,11603 ,0,0,0}, {23326,23447,23448 ,11598,11719,11720 ,0,0,0}, - {23337,23451,23335 ,11609,11723,11607 ,0,0,0}, {23333,23448,23449 ,11605,11720,11721 ,0,0,0}, - {23360,23452,23364 ,11632,11724,11636 ,0,0,0}, {23331,23449,23450 ,11603,11721,11722 ,0,0,0}, - {23360,23342,23335 ,11632,11614,11607 ,0,0,0}, {23329,23450,23379 ,11601,11722,11651 ,0,0,0}, - {23359,23340,23342 ,11631,11612,11614 ,0,0,0}, {23337,23379,23451 ,11609,11651,11723 ,0,0,0}, - {23347,23340,23453 ,11619,11612,11725 ,0,0,0}, {23451,23360,23335 ,11723,11632,11607 ,0,0,0}, - {23362,23349,23355 ,11634,11621,11627 ,0,0,0}, {23349,23362,23361 ,11621,11634,11633 ,0,0,0}, - {23347,23355,23346 ,11619,11627,11618 ,0,0,0}, {23340,23359,23453 ,11612,11631,11725 ,0,0,0}, - {23343,23354,23454 ,11615,11626,11726 ,0,0,0}, {23347,23362,23355 ,11619,11634,11627 ,0,0,0}, - {23348,23355,23349 ,11620,11627,11621 ,0,0,0}, {23455,23456,23343 ,11727,11728,11615 ,0,0,0}, - {23353,23354,23351 ,11625,11626,11623 ,0,0,0}, {23350,23454,23354 ,11622,11726,11626 ,0,0,0}, - {23344,23343,23456 ,11616,11615,11728 ,0,0,0}, {23413,23415,23406 ,11685,11687,11678 ,0,0,0}, - {23414,23402,23412 ,11686,11674,11684 ,0,0,0}, {23275,23457,23274 ,11547,11729,11546 ,0,0,0}, - {23415,23258,23404 ,11687,11530,11676 ,0,0,0}, {23413,23458,23415 ,11685,11730,11687 ,0,0,0}, - {23266,23260,23459 ,11538,11532,11731 ,0,0,0}, {23259,23258,23415 ,11531,11530,11687 ,0,0,0}, - {23416,23459,23460 ,11688,11731,11732 ,0,0,0}, {23260,23266,23258 ,11532,11538,11530 ,0,0,0}, - {23417,23460,23461 ,11689,11732,11733 ,0,0,0}, {23459,23416,23266 ,11731,11688,11538 ,0,0,0}, - {23418,23461,23462 ,11690,11733,11734 ,0,0,0}, {23460,23417,23416 ,11732,11689,11688 ,0,0,0}, - {23419,23462,23463 ,11691,11734,11735 ,0,0,0}, {23461,23418,23417 ,11733,11690,11689 ,0,0,0}, - {23420,23463,23464 ,11692,11735,11736 ,0,0,0}, {23462,23419,23418 ,11734,11691,11690 ,0,0,0}, - {23421,23464,23465 ,11693,11736,11737 ,0,0,0}, {23463,23420,23419 ,11735,11692,11691 ,0,0,0}, - {23288,23465,23422 ,11560,11737,11694 ,0,0,0}, {23421,23420,23464 ,11693,11692,11736 ,0,0,0}, - {23466,23467,23468 ,11738,11739,11740 ,0,0,0}, {23288,23421,23465 ,11560,11693,11737 ,0,0,0}, - {23425,23423,23466 ,11697,11695,11738 ,0,0,0}, {23424,23288,23422 ,11696,11560,11694 ,0,0,0}, - {23426,23466,23469 ,11698,11738,11741 ,0,0,0}, {23425,23424,23423 ,11697,11696,11695 ,0,0,0}, - {23427,23469,23470 ,11699,11741,11742 ,0,0,0}, {23466,23426,23425 ,11738,11698,11697 ,0,0,0}, - {23428,23470,23471 ,11700,11742,11743 ,0,0,0}, {23469,23427,23426 ,11741,11699,11698 ,0,0,0}, - {23429,23471,23472 ,11701,11743,11744 ,0,0,0}, {23470,23428,23427 ,11742,11700,11699 ,0,0,0}, - {23430,23472,23398 ,11702,11744,11670 ,0,0,0}, {23429,23428,23471 ,11701,11700,11743 ,0,0,0}, - {23473,23474,23475 ,11745,11746,11747 ,0,0,0}, {23430,23429,23472 ,11702,11701,11744 ,0,0,0}, - {23431,23396,23476 ,11703,11668,11748 ,0,0,0}, {23397,23430,23398 ,11669,11702,11670 ,0,0,0}, - {23432,23476,23477 ,11704,11748,11749 ,0,0,0}, {23396,23431,23397 ,11668,11703,11669 ,0,0,0}, - {23433,23477,23478 ,11705,11749,11750 ,0,0,0}, {23476,23432,23431 ,11748,11704,11703 ,0,0,0}, - {23434,23478,23479 ,11706,11750,11751 ,0,0,0}, {23477,23433,23432 ,11749,11705,11704 ,0,0,0}, - {23435,23479,23389 ,11707,11751,11661 ,0,0,0}, {23434,23433,23478 ,11706,11705,11750 ,0,0,0}, - {23480,23481,23482 ,11752,11753,11754 ,0,0,0}, {23435,23434,23479 ,11707,11706,11751 ,0,0,0}, - {23436,23390,23483 ,11708,11662,11755 ,0,0,0}, {23388,23435,23389 ,11660,11707,11661 ,0,0,0}, - {23437,23483,23484 ,11709,11755,11756 ,0,0,0}, {23436,23388,23390 ,11708,11660,11662 ,0,0,0}, - {23438,23484,23485 ,11710,11756,11757 ,0,0,0}, {23483,23437,23436 ,11755,11709,11708 ,0,0,0}, - {23439,23485,23486 ,11711,11757,11758 ,0,0,0}, {23484,23438,23437 ,11756,11710,11709 ,0,0,0}, - {23440,23486,23487 ,11712,11758,11759 ,0,0,0}, {23485,23439,23438 ,11757,11711,11710 ,0,0,0}, - {23383,23487,23488 ,11655,11759,11760 ,0,0,0}, {23440,23439,23486 ,11712,11711,11758 ,0,0,0}, - {23444,23488,23442 ,11716,11760,11714 ,0,0,0}, {23383,23440,23487 ,11655,11712,11759 ,0,0,0}, - {23445,23442,23489 ,11717,11714,11761 ,0,0,0}, {23444,23383,23488 ,11716,11655,11760 ,0,0,0}, - {23446,23489,23490 ,11718,11761,11762 ,0,0,0}, {23442,23445,23444 ,11714,11717,11716 ,0,0,0}, - {23447,23490,23491 ,11719,11762,11763 ,0,0,0}, {23489,23446,23445 ,11761,11718,11717 ,0,0,0}, - {23448,23491,23492 ,11720,11763,11764 ,0,0,0}, {23490,23447,23446 ,11762,11719,11718 ,0,0,0}, - {23449,23492,23493 ,11721,11764,11765 ,0,0,0}, {23491,23448,23447 ,11763,11720,11719 ,0,0,0}, - {23450,23493,23494 ,11722,11765,11766 ,0,0,0}, {23492,23449,23448 ,11764,11721,11720 ,0,0,0}, - {23379,23494,23495 ,11651,11766,11767 ,0,0,0}, {23493,23450,23449 ,11765,11722,11721 ,0,0,0}, - {23451,23495,23452 ,11723,11767,11724 ,0,0,0}, {23379,23450,23494 ,11651,11722,11766 ,0,0,0}, - {23496,23359,23364 ,11768,11631,11636 ,0,0,0}, {23451,23379,23495 ,11723,11651,11767 ,0,0,0}, - {23369,23365,23497 ,11641,11637,11769 ,0,0,0}, {23360,23451,23452 ,11632,11723,11724 ,0,0,0}, - {23496,23363,23453 ,11768,11635,11725 ,0,0,0}, {23356,23349,23361 ,11628,11621,11633 ,0,0,0}, - {23453,23362,23347 ,11725,11634,11619 ,0,0,0}, {23496,23453,23359 ,11768,11725,11631 ,0,0,0}, - {23369,23361,23363 ,11641,11633,11635 ,0,0,0}, {23453,23363,23362 ,11725,11635,11634 ,0,0,0}, - {23498,23454,23358 ,11770,11726,11630 ,0,0,0}, {23454,23455,23343 ,11726,11727,11615 ,0,0,0}, - {23348,23350,23354 ,11620,11622,11626 ,0,0,0}, {23350,23356,23358 ,11622,11628,11630 ,0,0,0}, - {23498,23455,23454 ,11770,11727,11726 ,0,0,0}, {23402,23458,23413 ,11674,11730,11685 ,0,0,0}, - {23270,23269,23403 ,11542,11541,11675 ,0,0,0}, {23273,23277,23499 ,11545,11549,11771 ,0,0,0}, - {23458,23259,23415 ,11730,11531,11687 ,0,0,0}, {23402,23500,23458 ,11674,11772,11730 ,0,0,0}, - {23501,23502,23503 ,11773,11774,11775 ,0,0,0}, {23271,23259,23458 ,11543,11531,11730 ,0,0,0}, - {23263,23501,23459 ,11535,11773,11731 ,0,0,0}, {23264,23260,23259 ,11536,11532,11531 ,0,0,0}, - {23501,23504,23460 ,11773,11776,11732 ,0,0,0}, {23263,23459,23260 ,11535,11731,11532 ,0,0,0}, - {23504,23505,23461 ,11776,11777,11733 ,0,0,0}, {23501,23460,23459 ,11773,11732,11731 ,0,0,0}, - {23505,23506,23462 ,11777,11778,11734 ,0,0,0}, {23504,23461,23460 ,11776,11733,11732 ,0,0,0}, - {23506,23507,23463 ,11778,11779,11735 ,0,0,0}, {23505,23462,23461 ,11777,11734,11733 ,0,0,0}, - {23507,23508,23464 ,11779,11780,11736 ,0,0,0}, {23506,23463,23462 ,11778,11735,11734 ,0,0,0}, - {23508,23509,23465 ,11780,11781,11737 ,0,0,0}, {23507,23464,23463 ,11779,11736,11735 ,0,0,0}, - {23509,23510,23422 ,11781,11782,11694 ,0,0,0}, {23508,23465,23464 ,11780,11737,11736 ,0,0,0}, - {23510,23467,23423 ,11782,11739,11695 ,0,0,0}, {23422,23465,23509 ,11694,11737,11781 ,0,0,0}, - {23511,23512,23513 ,11783,11784,11785 ,0,0,0}, {23423,23422,23510 ,11695,11694,11782 ,0,0,0}, - {23468,23511,23469 ,11740,11783,11741 ,0,0,0}, {23467,23466,23423 ,11739,11738,11695 ,0,0,0}, - {23511,23514,23470 ,11783,11786,11742 ,0,0,0}, {23468,23469,23466 ,11740,11741,11738 ,0,0,0}, - {23514,23515,23471 ,11786,11787,11743 ,0,0,0}, {23511,23470,23469 ,11783,11742,11741 ,0,0,0}, - {23515,23516,23472 ,11787,11788,11744 ,0,0,0}, {23514,23471,23470 ,11786,11743,11742 ,0,0,0}, - {23516,23517,23398 ,11788,11789,11670 ,0,0,0}, {23515,23472,23471 ,11787,11744,11743 ,0,0,0}, - {23396,23517,23518 ,11668,11789,11790 ,0,0,0}, {23398,23472,23516 ,11670,11744,11788 ,0,0,0}, - {23518,23473,23476 ,11790,11745,11748 ,0,0,0}, {23517,23396,23398 ,11789,11668,11670 ,0,0,0}, - {23473,23519,23477 ,11745,11791,11749 ,0,0,0}, {23518,23476,23396 ,11790,11748,11668 ,0,0,0}, - {23519,23520,23478 ,11791,11792,11750 ,0,0,0}, {23473,23477,23476 ,11745,11749,11748 ,0,0,0}, - {23520,23521,23479 ,11792,11793,11751 ,0,0,0}, {23519,23478,23477 ,11791,11750,11749 ,0,0,0}, - {23521,23522,23389 ,11793,11794,11661 ,0,0,0}, {23520,23479,23478 ,11792,11751,11750 ,0,0,0}, - {23522,23523,23390 ,11794,11795,11662 ,0,0,0}, {23389,23479,23521 ,11661,11751,11793 ,0,0,0}, - {23523,23480,23483 ,11795,11752,11755 ,0,0,0}, {23390,23389,23522 ,11662,11661,11794 ,0,0,0}, - {23480,23524,23484 ,11752,11796,11756 ,0,0,0}, {23523,23483,23390 ,11795,11755,11662 ,0,0,0}, - {23524,23525,23485 ,11796,11797,11757 ,0,0,0}, {23480,23484,23483 ,11752,11756,11755 ,0,0,0}, - {23525,23526,23486 ,11797,11798,11758 ,0,0,0}, {23524,23485,23484 ,11796,11757,11756 ,0,0,0}, - {23526,23527,23487 ,11798,11799,11759 ,0,0,0}, {23525,23486,23485 ,11797,11758,11757 ,0,0,0}, - {23527,23443,23488 ,11799,11715,11760 ,0,0,0}, {23487,23486,23526 ,11759,11758,11798 ,0,0,0}, - {23528,23529,23530 ,11800,11801,11802 ,0,0,0}, {23488,23487,23527 ,11760,11759,11799 ,0,0,0}, - {23441,23528,23489 ,11713,11800,11761 ,0,0,0}, {23443,23442,23488 ,11715,11714,11760 ,0,0,0}, - {23528,23531,23490 ,11800,11803,11762 ,0,0,0}, {23441,23489,23442 ,11713,11761,11714 ,0,0,0}, - {23531,23532,23491 ,11803,11804,11763 ,0,0,0}, {23528,23490,23489 ,11800,11762,11761 ,0,0,0}, - {23532,23533,23492 ,11804,11805,11764 ,0,0,0}, {23531,23491,23490 ,11803,11763,11762 ,0,0,0}, - {23533,23534,23493 ,11805,11806,11765 ,0,0,0}, {23532,23492,23491 ,11804,11764,11763 ,0,0,0}, - {23534,23535,23494 ,11806,11807,11766 ,0,0,0}, {23533,23493,23492 ,11805,11765,11764 ,0,0,0}, - {23535,23536,23495 ,11807,11808,11767 ,0,0,0}, {23534,23494,23493 ,11806,11766,11765 ,0,0,0}, - {23536,23537,23452 ,11808,11809,11724 ,0,0,0}, {23535,23495,23494 ,11807,11767,11766 ,0,0,0}, - {23537,23538,23364 ,11809,11810,11636 ,0,0,0}, {23536,23452,23495 ,11808,11724,11767 ,0,0,0}, - {23538,23368,23496 ,11810,11640,11768 ,0,0,0}, {23364,23452,23537 ,11636,11724,11809 ,0,0,0}, - {23539,23361,23369 ,11811,11633,11641 ,0,0,0}, {23364,23538,23496 ,11636,11810,11768 ,0,0,0}, - {23368,23365,23369 ,11640,11637,11641 ,0,0,0}, {23496,23368,23363 ,11768,11640,11635 ,0,0,0}, - {23540,23358,23357 ,11812,11630,11629 ,0,0,0}, {23350,23358,23454 ,11622,11630,11726 ,0,0,0}, - {23349,23356,23350 ,11621,11628,11622 ,0,0,0}, {23539,23357,23356 ,11811,11629,11628 ,0,0,0}, - {23498,23358,23540 ,11770,11630,11812 ,0,0,0}, {23500,23402,23269 ,11772,11674,11541 ,0,0,0}, - {23275,23268,23408 ,11547,11540,11680 ,0,0,0}, {23271,23541,23542 ,11543,11813,11814 ,0,0,0}, - {23500,23271,23458 ,11772,11543,11730 ,0,0,0}, {23543,23500,23269 ,11815,11772,11541 ,0,0,0}, - {23264,23542,23544 ,11536,11814,11816 ,0,0,0}, {23500,23541,23271 ,11772,11813,11543 ,0,0,0}, - {23263,23544,23502 ,11535,11816,11774 ,0,0,0}, {23542,23264,23271 ,11814,11536,11543 ,0,0,0}, - {23545,23504,23503 ,11817,11776,11775 ,0,0,0}, {23544,23263,23264 ,11816,11535,11536 ,0,0,0}, - {23546,23505,23545 ,11818,11777,11817 ,0,0,0}, {23502,23501,23263 ,11774,11773,11535 ,0,0,0}, - {23547,23548,23549 ,11819,11820,11821 ,0,0,0}, {23503,23504,23501 ,11775,11776,11773 ,0,0,0}, - {23546,23547,23506 ,11818,11819,11778 ,0,0,0}, {23545,23505,23504 ,11817,11777,11776 ,0,0,0}, - {23547,23550,23507 ,11819,11822,11779 ,0,0,0}, {23546,23506,23505 ,11818,11778,11777 ,0,0,0}, - {23550,23551,23508 ,11822,11823,11780 ,0,0,0}, {23547,23507,23506 ,11819,11779,11778 ,0,0,0}, - {23551,23552,23509 ,11823,11824,11781 ,0,0,0}, {23550,23508,23507 ,11822,11780,11779 ,0,0,0}, - {23552,23553,23510 ,11824,11825,11782 ,0,0,0}, {23551,23509,23508 ,11823,11781,11780 ,0,0,0}, - {23467,23553,23554 ,11739,11825,11826 ,0,0,0}, {23552,23510,23509 ,11824,11782,11781 ,0,0,0}, - {23468,23554,23512 ,11740,11826,11784 ,0,0,0}, {23553,23467,23510 ,11825,11739,11782 ,0,0,0}, - {23555,23556,23557 ,11827,11828,11829 ,0,0,0}, {23554,23468,23467 ,11826,11740,11739 ,0,0,0}, - {23513,23555,23514 ,11785,11827,11786 ,0,0,0}, {23512,23511,23468 ,11784,11783,11740 ,0,0,0}, - {23555,23558,23515 ,11827,11830,11787 ,0,0,0}, {23513,23514,23511 ,11785,11786,11783 ,0,0,0}, - {23558,23559,23516 ,11830,11831,11788 ,0,0,0}, {23555,23515,23514 ,11827,11787,11786 ,0,0,0}, - {23517,23559,23560 ,11789,11831,11832 ,0,0,0}, {23558,23516,23515 ,11830,11788,11787 ,0,0,0}, - {23518,23560,23474 ,11790,11832,11746 ,0,0,0}, {23517,23516,23559 ,11789,11788,11831 ,0,0,0}, - {23561,23562,23563 ,11833,11834,11835 ,0,0,0}, {23560,23518,23517 ,11832,11790,11789 ,0,0,0}, - {23475,23561,23519 ,11747,11833,11791 ,0,0,0}, {23474,23473,23518 ,11746,11745,11790 ,0,0,0}, - {23561,23564,23520 ,11833,11836,11792 ,0,0,0}, {23475,23519,23473 ,11747,11791,11745 ,0,0,0}, - {23564,23565,23521 ,11836,11837,11793 ,0,0,0}, {23561,23520,23519 ,11833,11792,11791 ,0,0,0}, - {23565,23566,23522 ,11837,11838,11794 ,0,0,0}, {23564,23521,23520 ,11836,11793,11792 ,0,0,0}, - {23523,23566,23481 ,11795,11838,11753 ,0,0,0}, {23522,23521,23565 ,11794,11793,11837 ,0,0,0}, - {23567,23568,23569 ,11839,11840,11841 ,0,0,0}, {23566,23523,23522 ,11838,11795,11794 ,0,0,0}, - {23482,23567,23524 ,11754,11839,11796 ,0,0,0}, {23481,23480,23523 ,11753,11752,11795 ,0,0,0}, - {23567,23570,23525 ,11839,11842,11797 ,0,0,0}, {23482,23524,23480 ,11754,11796,11752 ,0,0,0}, - {23570,23571,23526 ,11842,11843,11798 ,0,0,0}, {23567,23525,23524 ,11839,11797,11796 ,0,0,0}, - {23571,23572,23527 ,11843,11844,11799 ,0,0,0}, {23570,23526,23525 ,11842,11798,11797 ,0,0,0}, - {23443,23572,23573 ,11715,11844,11845 ,0,0,0}, {23571,23527,23526 ,11843,11799,11798 ,0,0,0}, - {23441,23573,23529 ,11713,11845,11801 ,0,0,0}, {23572,23443,23527 ,11844,11715,11799 ,0,0,0}, - {23574,23531,23530 ,11846,11803,11802 ,0,0,0}, {23573,23441,23443 ,11845,11713,11715 ,0,0,0}, - {23575,23576,23577 ,11847,11848,11849 ,0,0,0}, {23529,23528,23441 ,11801,11800,11713 ,0,0,0}, - {23574,23575,23532 ,11846,11847,11804 ,0,0,0}, {23530,23531,23528 ,11802,11803,11800 ,0,0,0}, - {23575,23578,23533 ,11847,11850,11805 ,0,0,0}, {23574,23532,23531 ,11846,11804,11803 ,0,0,0}, - {23578,23579,23534 ,11850,11851,11806 ,0,0,0}, {23575,23533,23532 ,11847,11805,11804 ,0,0,0}, - {23579,23580,23535 ,11851,11852,11807 ,0,0,0}, {23578,23534,23533 ,11850,11806,11805 ,0,0,0}, - {23580,23581,23536 ,11852,11853,11808 ,0,0,0}, {23579,23535,23534 ,11851,11807,11806 ,0,0,0}, - {23581,23582,23537 ,11853,11854,11809 ,0,0,0}, {23580,23536,23535 ,11852,11808,11807 ,0,0,0}, - {23582,23366,23538 ,11854,11638,11810 ,0,0,0}, {23581,23537,23536 ,11853,11809,11808 ,0,0,0}, - {23368,23366,23365 ,11640,11638,11637 ,0,0,0}, {23537,23582,23538 ,11809,11854,11810 ,0,0,0}, - {23583,23357,23539 ,11855,11629,11811 ,0,0,0}, {23368,23538,23366 ,11640,11810,11638 ,0,0,0}, - {23584,23357,23583 ,11856,11629,11855 ,0,0,0}, {23585,23540,23357 ,11857,11812,11629 ,0,0,0}, - {23361,23539,23356 ,11633,11811,11628 ,0,0,0}, {23497,23583,23539 ,11769,11855,11811 ,0,0,0}, - {23584,23585,23357 ,11856,11857,11629 ,0,0,0}, {23543,23269,23268 ,11815,11541,11540 ,0,0,0}, - {23272,23274,23457 ,11544,11546,11729 ,0,0,0}, {23541,23586,23587 ,11813,11858,11859 ,0,0,0}, - {23543,23541,23500 ,11815,11813,11772 ,0,0,0}, {23268,23588,23543 ,11540,11860,11815 ,0,0,0}, - {23542,23587,23589 ,11814,11859,11861 ,0,0,0}, {23543,23586,23541 ,11815,11858,11813 ,0,0,0}, - {23544,23589,23590 ,11816,11861,11862 ,0,0,0}, {23541,23587,23542 ,11813,11859,11814 ,0,0,0}, - {23502,23590,23591 ,11774,11862,11863 ,0,0,0}, {23542,23589,23544 ,11814,11861,11816 ,0,0,0}, - {23503,23591,23592 ,11775,11863,11864 ,0,0,0}, {23544,23590,23502 ,11816,11862,11774 ,0,0,0}, - {23545,23592,23593 ,11817,11864,11865 ,0,0,0}, {23502,23591,23503 ,11774,11863,11775 ,0,0,0}, - {23546,23593,23548 ,11818,11865,11820 ,0,0,0}, {23592,23545,23503 ,11864,11817,11775 ,0,0,0}, - {23594,23550,23549 ,11866,11822,11821 ,0,0,0}, {23593,23546,23545 ,11865,11818,11817 ,0,0,0}, - {23595,23596,23594 ,11867,11868,11866 ,0,0,0}, {23548,23547,23546 ,11820,11819,11818 ,0,0,0}, - {23594,23596,23551 ,11866,11868,11823 ,0,0,0}, {23549,23550,23547 ,11821,11822,11819 ,0,0,0}, - {23596,23597,23552 ,11868,11869,11824 ,0,0,0}, {23594,23551,23550 ,11866,11823,11822 ,0,0,0}, - {23553,23597,23598 ,11825,11869,11870 ,0,0,0}, {23596,23552,23551 ,11868,11824,11823 ,0,0,0}, - {23554,23598,23599 ,11826,11870,11871 ,0,0,0}, {23552,23597,23553 ,11824,11869,11825 ,0,0,0}, - {23512,23599,23600 ,11784,11871,11872 ,0,0,0}, {23553,23598,23554 ,11825,11870,11826 ,0,0,0}, - {23513,23600,23556 ,11785,11872,11828 ,0,0,0}, {23599,23512,23554 ,11871,11784,11826 ,0,0,0}, - {23601,23602,23557 ,11873,11874,11829 ,0,0,0}, {23600,23513,23512 ,11872,11785,11784 ,0,0,0}, - {23557,23602,23558 ,11829,11874,11830 ,0,0,0}, {23556,23555,23513 ,11828,11827,11785 ,0,0,0}, - {23602,23603,23559 ,11874,11875,11831 ,0,0,0}, {23557,23558,23555 ,11829,11830,11827 ,0,0,0}, - {23560,23603,23604 ,11832,11875,11876 ,0,0,0}, {23602,23559,23558 ,11874,11831,11830 ,0,0,0}, - {23474,23604,23605 ,11746,11876,11877 ,0,0,0}, {23559,23603,23560 ,11831,11875,11832 ,0,0,0}, - {23475,23605,23562 ,11747,11877,11834 ,0,0,0}, {23604,23474,23560 ,11876,11746,11832 ,0,0,0}, - {23606,23607,23563 ,11878,11879,11835 ,0,0,0}, {23605,23475,23474 ,11877,11747,11746 ,0,0,0}, - {23563,23607,23564 ,11835,11879,11836 ,0,0,0}, {23562,23561,23475 ,11834,11833,11747 ,0,0,0}, - {23607,23608,23565 ,11879,11880,11837 ,0,0,0}, {23563,23564,23561 ,11835,11836,11833 ,0,0,0}, - {23566,23608,23609 ,11838,11880,11881 ,0,0,0}, {23607,23565,23564 ,11879,11837,11836 ,0,0,0}, - {23481,23609,23610 ,11753,11881,11882 ,0,0,0}, {23565,23608,23566 ,11837,11880,11838 ,0,0,0}, - {23482,23610,23568 ,11754,11882,11840 ,0,0,0}, {23609,23481,23566 ,11881,11753,11838 ,0,0,0}, - {23611,23612,23569 ,11883,11884,11841 ,0,0,0}, {23610,23482,23481 ,11882,11754,11753 ,0,0,0}, - {23569,23612,23570 ,11841,11884,11842 ,0,0,0}, {23568,23567,23482 ,11840,11839,11754 ,0,0,0}, - {23612,23613,23571 ,11884,11885,11843 ,0,0,0}, {23569,23570,23567 ,11841,11842,11839 ,0,0,0}, - {23572,23613,23614 ,11844,11885,11886 ,0,0,0}, {23612,23571,23570 ,11884,11843,11842 ,0,0,0}, - {23573,23614,23615 ,11845,11886,11887 ,0,0,0}, {23571,23613,23572 ,11843,11885,11844 ,0,0,0}, - {23529,23615,23616 ,11801,11887,11888 ,0,0,0}, {23572,23614,23573 ,11844,11886,11845 ,0,0,0}, - {23530,23616,23617 ,11802,11888,11889 ,0,0,0}, {23573,23615,23529 ,11845,11887,11801 ,0,0,0}, - {23574,23617,23576 ,11846,11889,11848 ,0,0,0}, {23616,23530,23529 ,11888,11802,11801 ,0,0,0}, - {23618,23578,23577 ,11890,11850,11849 ,0,0,0}, {23617,23574,23530 ,11889,11846,11802 ,0,0,0}, - {23619,23620,23618 ,11891,11892,11890 ,0,0,0}, {23576,23575,23574 ,11848,11847,11846 ,0,0,0}, - {23618,23620,23579 ,11890,11892,11851 ,0,0,0}, {23577,23578,23575 ,11849,11850,11847 ,0,0,0}, - {23620,23621,23580 ,11892,11893,11852 ,0,0,0}, {23618,23579,23578 ,11890,11851,11850 ,0,0,0}, - {23621,23622,23581 ,11893,11894,11853 ,0,0,0}, {23620,23580,23579 ,11892,11852,11851 ,0,0,0}, - {23622,23623,23582 ,11894,11895,11854 ,0,0,0}, {23621,23581,23580 ,11893,11853,11852 ,0,0,0}, - {23366,23623,23367 ,11638,11895,11639 ,0,0,0}, {23622,23582,23581 ,11894,11854,11853 ,0,0,0}, - {23367,23624,23365 ,11639,11896,11637 ,0,0,0}, {23366,23582,23623 ,11638,11854,11895 ,0,0,0}, - {23625,23583,23373 ,11897,11855,11645 ,0,0,0}, {23625,23626,23583 ,11897,11898,11855 ,0,0,0}, - {23369,23497,23539 ,11641,11769,11811 ,0,0,0}, {23624,23373,23497 ,11896,11645,11769 ,0,0,0}, - {23584,23583,23626 ,11856,11855,11898 ,0,0,0}, {23274,23588,23268 ,11546,11860,11540 ,0,0,0}, - {23627,23273,23272 ,11899,11545,11544 ,0,0,0}, {23628,23586,23588 ,11900,11858,11860 ,0,0,0}, - {23588,23586,23543 ,11860,11858,11815 ,0,0,0}, {23588,23499,23628 ,11860,11771,11900 ,0,0,0}, - {23629,23587,23586 ,11901,11859,11858 ,0,0,0}, {23586,23628,23629 ,11858,11900,11901 ,0,0,0}, - {23630,23589,23587 ,11902,11861,11859 ,0,0,0}, {23587,23629,23630 ,11859,11901,11902 ,0,0,0}, - {23631,23590,23589 ,11903,11862,11861 ,0,0,0}, {23589,23630,23631 ,11861,11902,11903 ,0,0,0}, - {23632,23591,23590 ,11904,11863,11862 ,0,0,0}, {23590,23631,23632 ,11862,11903,11904 ,0,0,0}, - {23633,23592,23591 ,11905,11864,11863 ,0,0,0}, {23591,23632,23633 ,11863,11904,11905 ,0,0,0}, - {23634,23593,23592 ,11906,11865,11864 ,0,0,0}, {23592,23633,23634 ,11864,11905,11906 ,0,0,0}, - {23635,23548,23593 ,11907,11820,11865 ,0,0,0}, {23593,23634,23635 ,11865,11906,11907 ,0,0,0}, - {23636,23549,23548 ,11908,11821,11820 ,0,0,0}, {23548,23635,23636 ,11820,11907,11908 ,0,0,0}, - {23637,23594,23549 ,11909,11866,11821 ,0,0,0}, {23636,23637,23549 ,11908,11909,11821 ,0,0,0}, - {23638,23639,23640 ,11910,11911,11912 ,0,0,0}, {23637,23595,23594 ,11909,11867,11866 ,0,0,0}, - {23641,23597,23596 ,11913,11869,11868 ,0,0,0}, {23595,23641,23596 ,11867,11913,11868 ,0,0,0}, - {23642,23598,23597 ,11914,11870,11869 ,0,0,0}, {23597,23641,23642 ,11869,11913,11914 ,0,0,0}, - {23643,23599,23598 ,11915,11871,11870 ,0,0,0}, {23598,23642,23643 ,11870,11914,11915 ,0,0,0}, - {23644,23600,23599 ,11916,11872,11871 ,0,0,0}, {23599,23643,23644 ,11871,11915,11916 ,0,0,0}, - {23645,23556,23600 ,11917,11828,11872 ,0,0,0}, {23600,23644,23645 ,11872,11916,11917 ,0,0,0}, - {23646,23557,23556 ,11918,11829,11828 ,0,0,0}, {23645,23646,23556 ,11917,11918,11828 ,0,0,0}, - {23647,23601,23648 ,11919,11873,11920 ,0,0,0}, {23646,23601,23557 ,11918,11873,11829 ,0,0,0}, - {23647,23603,23602 ,11919,11875,11874 ,0,0,0}, {23601,23647,23602 ,11873,11919,11874 ,0,0,0}, - {23649,23604,23603 ,11921,11876,11875 ,0,0,0}, {23603,23647,23649 ,11875,11919,11921 ,0,0,0}, - {23650,23605,23604 ,11922,11877,11876 ,0,0,0}, {23604,23649,23650 ,11876,11921,11922 ,0,0,0}, - {23651,23562,23605 ,11923,11834,11877 ,0,0,0}, {23605,23650,23651 ,11877,11922,11923 ,0,0,0}, - {23652,23563,23562 ,11924,11835,11834 ,0,0,0}, {23651,23652,23562 ,11923,11924,11834 ,0,0,0}, - {23653,23654,23655 ,11925,11926,11927 ,0,0,0}, {23652,23606,23563 ,11924,11878,11835 ,0,0,0}, - {23656,23608,23607 ,11928,11880,11879 ,0,0,0}, {23606,23656,23607 ,11878,11928,11879 ,0,0,0}, - {23657,23609,23608 ,11929,11881,11880 ,0,0,0}, {23608,23656,23657 ,11880,11928,11929 ,0,0,0}, - {23658,23610,23609 ,11930,11882,11881 ,0,0,0}, {23609,23657,23658 ,11881,11929,11930 ,0,0,0}, - {23659,23568,23610 ,11931,11840,11882 ,0,0,0}, {23610,23658,23659 ,11882,11930,11931 ,0,0,0}, - {23660,23569,23568 ,11932,11841,11840 ,0,0,0}, {23659,23660,23568 ,11931,11932,11840 ,0,0,0}, - {23612,23661,23613 ,11884,11933,11885 ,0,0,0}, {23660,23611,23569 ,11932,11883,11841 ,0,0,0}, - {23662,23663,23661 ,11934,11935,11933 ,0,0,0}, {23611,23661,23612 ,11883,11933,11884 ,0,0,0}, - {23663,23614,23613 ,11935,11886,11885 ,0,0,0}, {23613,23661,23663 ,11885,11933,11935 ,0,0,0}, - {23664,23615,23614 ,11936,11887,11886 ,0,0,0}, {23614,23663,23664 ,11886,11935,11936 ,0,0,0}, - {23665,23616,23615 ,11937,11888,11887 ,0,0,0}, {23615,23664,23665 ,11887,11936,11937 ,0,0,0}, - {23666,23617,23616 ,11938,11889,11888 ,0,0,0}, {23616,23665,23666 ,11888,11937,11938 ,0,0,0}, - {23667,23576,23617 ,11939,11848,11889 ,0,0,0}, {23617,23666,23667 ,11889,11938,11939 ,0,0,0}, - {23668,23577,23576 ,11940,11849,11848 ,0,0,0}, {23576,23667,23668 ,11848,11939,11940 ,0,0,0}, - {23669,23618,23577 ,11941,11890,11849 ,0,0,0}, {23668,23669,23577 ,11940,11941,11849 ,0,0,0}, - {23620,23670,23621 ,11892,11942,11893 ,0,0,0}, {23669,23619,23618 ,11941,11891,11890 ,0,0,0}, - {23621,23671,23622 ,11893,11943,11894 ,0,0,0}, {23619,23670,23620 ,11891,11942,11892 ,0,0,0}, - {23622,23672,23623 ,11894,11944,11895 ,0,0,0}, {23670,23671,23621 ,11942,11943,11893 ,0,0,0}, - {23623,23370,23367 ,11895,11642,11639 ,0,0,0}, {23671,23672,23622 ,11943,11944,11894 ,0,0,0}, - {23375,23374,23371 ,11647,11646,11643 ,0,0,0}, {23672,23370,23623 ,11944,11642,11895 ,0,0,0}, - {23371,23624,23367 ,11643,11896,11639 ,0,0,0}, {23497,23373,23583 ,11769,11645,11855 ,0,0,0}, - {23365,23624,23497 ,11637,11896,11769 ,0,0,0}, {23624,23371,23374 ,11896,11643,11646 ,0,0,0}, - {23625,23373,23372 ,11897,11645,11644 ,0,0,0}, {23273,23499,23274 ,11545,11771,11546 ,0,0,0}, - {23627,23280,23278 ,11899,11552,11550 ,0,0,0}, {23628,23499,23673 ,11900,11771,11945 ,0,0,0}, - {23274,23499,23588 ,11546,11771,11860 ,0,0,0}, {23499,23277,23673 ,11771,11549,11945 ,0,0,0}, - {23629,23628,23674 ,11901,11900,11946 ,0,0,0}, {23628,23673,23674 ,11900,11945,11946 ,0,0,0}, - {23630,23629,23675 ,11902,11901,11947 ,0,0,0}, {23629,23674,23675 ,11901,11946,11947 ,0,0,0}, - {23631,23630,23676 ,11903,11902,11948 ,0,0,0}, {23630,23675,23676 ,11902,11947,11948 ,0,0,0}, - {23632,23631,23677 ,11904,11903,11949 ,0,0,0}, {23631,23676,23677 ,11903,11948,11949 ,0,0,0}, - {23633,23632,23678 ,11905,11904,11950 ,0,0,0}, {23632,23677,23678 ,11904,11949,11950 ,0,0,0}, - {23634,23633,23679 ,11906,11905,11951 ,0,0,0}, {23633,23678,23679 ,11905,11950,11951 ,0,0,0}, - {23635,23634,23680 ,11907,11906,11952 ,0,0,0}, {23634,23679,23680 ,11906,11951,11952 ,0,0,0}, - {23636,23635,23681 ,11908,11907,11953 ,0,0,0}, {23635,23680,23681 ,11907,11952,11953 ,0,0,0}, - {23637,23636,23682 ,11909,11908,11954 ,0,0,0}, {23636,23681,23682 ,11908,11953,11954 ,0,0,0}, - {23595,23637,23683 ,11867,11909,11955 ,0,0,0}, {23637,23682,23683 ,11909,11954,11955 ,0,0,0}, - {23641,23595,23638 ,11913,11867,11910 ,0,0,0}, {23683,23638,23595 ,11955,11910,11867 ,0,0,0}, - {23642,23641,23640 ,11914,11913,11912 ,0,0,0}, {23641,23638,23640 ,11913,11910,11912 ,0,0,0}, - {23643,23642,23684 ,11915,11914,11956 ,0,0,0}, {23642,23640,23684 ,11914,11912,11956 ,0,0,0}, - {23644,23643,23685 ,11916,11915,11957 ,0,0,0}, {23643,23684,23685 ,11915,11956,11957 ,0,0,0}, - {23645,23644,23686 ,11917,11916,11958 ,0,0,0}, {23644,23685,23686 ,11916,11957,11958 ,0,0,0}, - {23646,23645,23687 ,11918,11917,11959 ,0,0,0}, {23645,23686,23687 ,11917,11958,11959 ,0,0,0}, - {23601,23646,23688 ,11873,11918,11960 ,0,0,0}, {23646,23687,23688 ,11918,11959,11960 ,0,0,0}, - {23688,23689,23648 ,11960,11961,11920 ,0,0,0}, {23688,23648,23601 ,11960,11920,11873 ,0,0,0}, - {23649,23647,23690 ,11921,11919,11962 ,0,0,0}, {23647,23648,23690 ,11919,11920,11962 ,0,0,0}, - {23650,23649,23691 ,11922,11921,11963 ,0,0,0}, {23649,23690,23691 ,11921,11962,11963 ,0,0,0}, - {23651,23650,23692 ,11923,11922,11964 ,0,0,0}, {23650,23691,23692 ,11922,11963,11964 ,0,0,0}, - {23652,23651,23693 ,11924,11923,11965 ,0,0,0}, {23651,23692,23693 ,11923,11964,11965 ,0,0,0}, - {23606,23652,23694 ,11878,11924,11966 ,0,0,0}, {23652,23693,23694 ,11924,11965,11966 ,0,0,0}, - {23656,23606,23653 ,11928,11878,11925 ,0,0,0}, {23694,23653,23606 ,11966,11925,11878 ,0,0,0}, - {23657,23656,23655 ,11929,11928,11927 ,0,0,0}, {23656,23653,23655 ,11928,11925,11927 ,0,0,0}, - {23658,23657,23695 ,11930,11929,11967 ,0,0,0}, {23657,23655,23695 ,11929,11927,11967 ,0,0,0}, - {23659,23658,23696 ,11931,11930,11968 ,0,0,0}, {23658,23695,23696 ,11930,11967,11968 ,0,0,0}, - {23660,23659,23697 ,11932,11931,11969 ,0,0,0}, {23659,23696,23697 ,11931,11968,11969 ,0,0,0}, - {23611,23660,23698 ,11883,11932,11970 ,0,0,0}, {23660,23697,23698 ,11932,11969,11970 ,0,0,0}, - {23661,23611,23699 ,11933,11883,11971 ,0,0,0}, {23611,23698,23699 ,11883,11970,11971 ,0,0,0}, - {23662,23699,23700 ,11934,11971,11972 ,0,0,0}, {23699,23662,23661 ,11971,11934,11933 ,0,0,0}, - {23664,23663,23701 ,11936,11935,11973 ,0,0,0}, {23663,23662,23701 ,11935,11934,11973 ,0,0,0}, - {23665,23664,23702 ,11937,11936,11974 ,0,0,0}, {23664,23701,23702 ,11936,11973,11974 ,0,0,0}, - {23666,23665,23703 ,11938,11937,11975 ,0,0,0}, {23665,23702,23703 ,11937,11974,11975 ,0,0,0}, - {23667,23666,23704 ,11939,11938,11976 ,0,0,0}, {23666,23703,23704 ,11938,11975,11976 ,0,0,0}, - {23668,23667,23705 ,11940,11939,11977 ,0,0,0}, {23667,23704,23705 ,11939,11976,11977 ,0,0,0}, - {23669,23668,23706 ,11941,11940,11978 ,0,0,0}, {23668,23705,23706 ,11940,11977,11978 ,0,0,0}, - {23619,23669,23707 ,11891,11941,11979 ,0,0,0}, {23669,23706,23707 ,11941,11978,11979 ,0,0,0}, - {23670,23619,23708 ,11942,11891,11980 ,0,0,0}, {23619,23707,23708 ,11891,11979,11980 ,0,0,0}, - {23671,23670,23709 ,11943,11942,11981 ,0,0,0}, {23670,23708,23709 ,11942,11980,11981 ,0,0,0}, - {23672,23671,23710 ,11944,11943,11982 ,0,0,0}, {23671,23709,23710 ,11943,11981,11982 ,0,0,0}, - {23370,23672,23711 ,11642,11944,11983 ,0,0,0}, {23672,23710,23711 ,11944,11982,11983 ,0,0,0}, - {23712,23371,23370 ,11984,11643,11642 ,0,0,0}, {23712,23370,23711 ,11984,11642,11983 ,0,0,0}, - {23624,23374,23373 ,11896,11646,11645 ,0,0,0}, {23712,23375,23371 ,11984,11647,11643 ,0,0,0}, - {23372,23374,23377 ,11644,11646,11649 ,0,0,0}, {23278,23273,23627 ,11550,11545,11899 ,0,0,0}, - {23279,23276,23278 ,11551,11548,11550 ,0,0,0}, {23276,23713,23277 ,11548,11985,11549 ,0,0,0}, - {23277,23713,23673 ,11549,11985,11945 ,0,0,0}, {23713,23714,23673 ,11985,11986,11945 ,0,0,0}, - {23673,23714,23674 ,11945,11986,11946 ,0,0,0}, {23714,23715,23674 ,11986,11987,11946 ,0,0,0}, - {23674,23715,23675 ,11946,11987,11947 ,0,0,0}, {23715,23716,23675 ,11987,11988,11947 ,0,0,0}, - {23675,23716,23676 ,11947,11988,11948 ,0,0,0}, {23716,23717,23676 ,11988,11989,11948 ,0,0,0}, - {23676,23717,23677 ,11948,11989,11949 ,0,0,0}, {23717,23718,23677 ,11989,11990,11949 ,0,0,0}, - {23677,23718,23678 ,11949,11990,11950 ,0,0,0}, {23718,23719,23678 ,11990,11991,11950 ,0,0,0}, - {23678,23719,23679 ,11950,11991,11951 ,0,0,0}, {23719,23720,23679 ,11991,11992,11951 ,0,0,0}, - {23720,23721,23680 ,11992,11993,11952 ,0,0,0}, {23720,23680,23679 ,11992,11952,11951 ,0,0,0}, - {23721,23722,23681 ,11993,11994,11953 ,0,0,0}, {23721,23681,23680 ,11993,11953,11952 ,0,0,0}, - {23722,23723,23682 ,11994,11995,11954 ,0,0,0}, {23722,23682,23681 ,11994,11954,11953 ,0,0,0}, - {23723,23724,23683 ,11995,11996,11955 ,0,0,0}, {23723,23683,23682 ,11995,11955,11954 ,0,0,0}, - {23724,23725,23638 ,11996,11997,11910 ,0,0,0}, {23724,23638,23683 ,11996,11910,11955 ,0,0,0}, - {23639,23638,23725 ,11911,11910,11997 ,0,0,0}, {23639,23726,23640 ,11911,11998,11912 ,0,0,0}, - {23640,23726,23684 ,11912,11998,11956 ,0,0,0}, {23726,23727,23684 ,11998,11999,11956 ,0,0,0}, - {23684,23727,23685 ,11956,11999,11957 ,0,0,0}, {23727,23728,23685 ,11999,12000,11957 ,0,0,0}, - {23728,23729,23686 ,12000,12001,11958 ,0,0,0}, {23728,23686,23685 ,12000,11958,11957 ,0,0,0}, - {23729,23730,23687 ,12001,12002,11959 ,0,0,0}, {23729,23687,23686 ,12001,11959,11958 ,0,0,0}, - {23730,23689,23688 ,12002,11961,11960 ,0,0,0}, {23730,23688,23687 ,12002,11960,11959 ,0,0,0}, - {23689,23731,23648 ,11961,12003,11920 ,0,0,0}, {23731,23732,23648 ,12003,12004,11920 ,0,0,0}, - {23648,23732,23690 ,11920,12004,11962 ,0,0,0}, {23732,23733,23690 ,12004,12005,11962 ,0,0,0}, - {23690,23733,23691 ,11962,12005,11963 ,0,0,0}, {23733,23734,23691 ,12005,12006,11963 ,0,0,0}, - {23734,23735,23692 ,12006,12007,11964 ,0,0,0}, {23734,23692,23691 ,12006,11964,11963 ,0,0,0}, - {23735,23736,23693 ,12007,12008,11965 ,0,0,0}, {23735,23693,23692 ,12007,11965,11964 ,0,0,0}, - {23736,23737,23694 ,12008,12009,11966 ,0,0,0}, {23736,23694,23693 ,12008,11966,11965 ,0,0,0}, - {23737,23738,23653 ,12009,12010,11925 ,0,0,0}, {23737,23653,23694 ,12009,11925,11966 ,0,0,0}, - {23654,23653,23738 ,11926,11925,12010 ,0,0,0}, {23654,23739,23655 ,11926,12011,11927 ,0,0,0}, - {23655,23739,23695 ,11927,12011,11967 ,0,0,0}, {23739,23740,23695 ,12011,12012,11967 ,0,0,0}, - {23740,23741,23696 ,12012,12013,11968 ,0,0,0}, {23740,23696,23695 ,12012,11968,11967 ,0,0,0}, - {23741,23742,23697 ,12013,12014,11969 ,0,0,0}, {23741,23697,23696 ,12013,11969,11968 ,0,0,0}, - {23742,23743,23698 ,12014,12015,11970 ,0,0,0}, {23742,23698,23697 ,12014,11970,11969 ,0,0,0}, - {23743,23700,23699 ,12015,11972,11971 ,0,0,0}, {23743,23699,23698 ,12015,11971,11970 ,0,0,0}, - {23700,23744,23662 ,11972,12016,11934 ,0,0,0}, {23744,23745,23662 ,12016,12017,11934 ,0,0,0}, - {23662,23745,23701 ,11934,12017,11973 ,0,0,0}, {23745,23746,23701 ,12017,12018,11973 ,0,0,0}, - {23701,23746,23702 ,11973,12018,11974 ,0,0,0}, {23746,23747,23702 ,12018,12019,11974 ,0,0,0}, - {23702,23747,23703 ,11974,12019,11975 ,0,0,0}, {23747,23748,23703 ,12019,12020,11975 ,0,0,0}, - {23748,23749,23704 ,12020,12021,11976 ,0,0,0}, {23748,23704,23703 ,12020,11976,11975 ,0,0,0}, - {23749,23750,23705 ,12021,12022,11977 ,0,0,0}, {23749,23705,23704 ,12021,11977,11976 ,0,0,0}, - {23750,23751,23706 ,12022,12023,11978 ,0,0,0}, {23750,23706,23705 ,12022,11978,11977 ,0,0,0}, - {23751,23752,23707 ,12023,12024,11979 ,0,0,0}, {23751,23707,23706 ,12023,11979,11978 ,0,0,0}, - {23752,23753,23708 ,12024,12025,11980 ,0,0,0}, {23752,23708,23707 ,12024,11980,11979 ,0,0,0}, - {23753,23754,23709 ,12025,12026,11981 ,0,0,0}, {23753,23709,23708 ,12025,11981,11980 ,0,0,0}, - {23754,23755,23710 ,12026,12027,11982 ,0,0,0}, {23754,23710,23709 ,12026,11982,11981 ,0,0,0}, - {23755,23756,23711 ,12027,12028,11983 ,0,0,0}, {23755,23711,23710 ,12027,11983,11982 ,0,0,0}, - {23756,23757,23712 ,12028,12029,11984 ,0,0,0}, {23756,23712,23711 ,12028,11984,11983 ,0,0,0}, - {23758,23712,23757 ,12030,11984,12029 ,0,0,0}, {23712,23758,23375 ,11984,12030,11647 ,0,0,0}, - {23375,23758,23378 ,11647,12030,11650 ,0,0,0}, {23759,23760,23761 ,12031,12032,12033 ,0,0,0}, - {23762,23763,23764 ,12034,12035,12036 ,0,0,0}, {23765,23766,23767 ,12037,12038,12039 ,0,0,0}, - {23768,23769,23765 ,12040,12041,12037 ,0,0,0}, {23770,23771,23772 ,12042,12043,12044 ,0,0,0}, - {23773,23774,23775 ,12045,12046,12047 ,0,0,0}, {23776,23777,23778 ,12048,12049,12050 ,0,0,0}, - {23779,23780,23773 ,12051,12052,12045 ,0,0,0}, {23781,23782,23783 ,12053,12054,12055 ,0,0,0}, - {23783,23778,23784 ,12055,12050,12056 ,0,0,0}, {23785,23781,23786 ,12057,12053,12058 ,0,0,0}, - {23782,23781,23787 ,12054,12053,12059 ,0,0,0}, {23768,23788,23789 ,12040,12060,12061 ,0,0,0}, - {23785,23790,23781 ,12057,12062,12053 ,0,0,0}, {23791,23792,23793 ,12063,12064,12065 ,0,0,0}, - {23792,23794,23761 ,12064,12066,12033 ,0,0,0}, {23795,23796,23793 ,12067,12068,12065 ,0,0,0}, - {23794,23792,23791 ,12066,12064,12063 ,0,0,0}, {23797,23798,23795 ,12069,12070,12067 ,0,0,0}, - {23793,23796,23791 ,12065,12068,12063 ,0,0,0}, {23799,23800,23763 ,12071,12072,12035 ,0,0,0}, - {23801,23802,23803 ,12073,12074,12075 ,0,0,0}, {23799,23804,23800 ,12071,12076,12072 ,0,0,0}, - {23805,23806,23807 ,12077,12078,12079 ,0,0,0}, {23802,23808,23803 ,12074,12080,12075 ,0,0,0}, - {23809,23810,23811 ,12081,12082,12083 ,0,0,0}, {23805,23807,23812 ,12077,12079,12084 ,0,0,0}, - {23813,23814,23815 ,12085,12086,12087 ,0,0,0}, {23814,23813,23816 ,12086,12085,12088 ,0,0,0}, - {23817,23818,23819 ,12089,12090,12091 ,0,0,0}, {23820,23821,23818 ,12092,12093,12090 ,0,0,0}, - {23822,23823,23824 ,12094,12095,12096 ,0,0,0}, {23817,23819,23825 ,12089,12091,12097 ,0,0,0}, - {23826,23827,23828 ,12098,12099,12100 ,0,0,0}, {23822,23824,23829 ,12094,12096,12101 ,0,0,0}, - {23830,23831,23832 ,12102,12103,12104 ,0,0,0}, {23833,23827,23826 ,12105,12099,12098 ,0,0,0}, - {23834,23835,23836 ,12106,12107,12108 ,0,0,0}, {23836,23832,23834 ,12108,12104,12106 ,0,0,0}, - {23837,23838,23839 ,12109,12110,12111 ,0,0,0}, {23840,23835,23841 ,12112,12107,12113 ,0,0,0}, - {23842,23843,23844 ,12114,12115,12116 ,0,0,0}, {23843,23842,23845 ,12115,12114,12117 ,0,0,0}, - {23846,23847,23848 ,12118,12119,12120 ,0,0,0}, {23844,23847,23849 ,12116,12119,12121 ,0,0,0}, - {23850,23851,23852 ,12122,12123,12124 ,0,0,0}, {23853,23854,23855 ,12125,12126,12127 ,0,0,0}, - {23856,23857,23858 ,12128,12129,12130 ,0,0,0}, {23857,23856,23859 ,12129,12128,12131 ,0,0,0}, - {23860,23861,23862 ,12132,12133,12134 ,0,0,0}, {23863,23864,23860 ,12135,12136,12132 ,0,0,0}, - {23861,23860,23864 ,12133,12132,12136 ,0,0,0}, {23861,23864,23850 ,12133,12136,12122 ,0,0,0}, - {23865,23866,23867 ,12137,12138,12139 ,0,0,0}, {23848,23852,23851 ,12120,12124,12123 ,0,0,0}, - {23868,23853,23855 ,12140,12125,12127 ,0,0,0}, {23854,23869,23855 ,12126,12141,12127 ,0,0,0}, - {23870,23871,23853 ,12142,12143,12125 ,0,0,0}, {23853,23872,23854 ,12125,12144,12126 ,0,0,0}, - {23873,23874,23875 ,12145,12146,12147 ,0,0,0}, {23272,23876,23877 ,12148,12149,12150 ,0,0,0}, - {23877,23878,23627 ,12150,12151,12152 ,0,0,0}, {23878,23280,23627 ,12151,12153,12152 ,0,0,0}, - {23281,23280,23879 ,730,12153,12154 ,0,0,0}, {23867,23847,23865 ,12139,12119,12137 ,0,0,0}, - {23858,23863,23860 ,12130,12135,12132 ,0,0,0}, {23848,23851,23846 ,12120,12123,12118 ,0,0,0}, - {23410,23859,23409 ,12155,12131,12156 ,0,0,0}, {23842,23844,23849 ,12114,12116,12121 ,0,0,0}, - {23847,23846,23849 ,12119,12118,12121 ,0,0,0}, {23837,23845,23838 ,12109,12117,12110 ,0,0,0}, - {23843,23845,23837 ,12115,12117,12109 ,0,0,0}, {23837,23880,23843 ,12109,12157,12115 ,0,0,0}, - {23838,23840,23839 ,12110,12112,12111 ,0,0,0}, {23841,23835,23834 ,12113,12107,12106 ,0,0,0}, - {23840,23841,23839 ,12112,12113,12111 ,0,0,0}, {23830,23832,23836 ,12102,12104,12108 ,0,0,0}, - {23826,23828,23881 ,12098,12100,12158 ,0,0,0}, {23882,23833,23883 ,12159,12105,12160 ,0,0,0}, - {23832,23831,23883 ,12104,12103,12160 ,0,0,0}, {23827,23833,23882 ,12099,12105,12159 ,0,0,0}, - {23831,23882,23883 ,12103,12159,12160 ,0,0,0}, {23881,23828,23829 ,12158,12100,12101 ,0,0,0}, - {23884,23826,23881 ,12161,12098,12158 ,0,0,0}, {23829,23824,23881 ,12101,12096,12158 ,0,0,0}, - {23825,23823,23885 ,12097,12095,12162 ,0,0,0}, {23822,23885,23823 ,12094,12162,12095 ,0,0,0}, - {23886,23825,23885 ,12163,12097,12162 ,0,0,0}, {23821,23819,23818 ,12093,12091,12090 ,0,0,0}, - {23817,23825,23886 ,12089,12097,12163 ,0,0,0}, {23820,23887,23821 ,12092,12164,12093 ,0,0,0}, - {23815,23814,23887 ,12087,12086,12164 ,0,0,0}, {23887,23820,23815 ,12164,12092,12087 ,0,0,0}, - {23816,23888,23811 ,12088,12165,12083 ,0,0,0}, {23889,23890,23891 ,12166,12167,12168 ,0,0,0}, - {23811,23888,23892 ,12083,12165,12169 ,0,0,0}, {23888,23816,23813 ,12165,12088,12085 ,0,0,0}, - {23893,23812,23810 ,12170,12084,12082 ,0,0,0}, {23809,23811,23892 ,12081,12083,12169 ,0,0,0}, - {23812,23893,23805 ,12084,12170,12077 ,0,0,0}, {23893,23810,23809 ,12170,12082,12081 ,0,0,0}, - {23804,23894,23895 ,12076,12171,12172 ,0,0,0}, {23806,23808,23896 ,12078,12080,12173 ,0,0,0}, - {23807,23806,23896 ,12079,12078,12173 ,0,0,0}, {23896,23808,23802 ,12173,12080,12074 ,0,0,0}, - {23897,23898,23899 ,12174,12175,12176 ,0,0,0}, {23894,23801,23803 ,12171,12073,12075 ,0,0,0}, - {23761,23794,23759 ,12033,12066,12031 ,0,0,0}, {23804,23801,23894 ,12076,12073,12171 ,0,0,0}, - {23804,23895,23800 ,12076,12172,12072 ,0,0,0}, {23763,23762,23799 ,12035,12034,12071 ,0,0,0}, - {23798,23797,23764 ,12070,12069,12036 ,0,0,0}, {23764,23797,23762 ,12036,12069,12034 ,0,0,0}, - {23900,23797,23795 ,12177,12069,12067 ,0,0,0}, {23798,23796,23795 ,12070,12068,12067 ,0,0,0}, - {23760,23789,23788 ,12032,12061,12060 ,0,0,0}, {23759,23789,23760 ,12031,12061,12032 ,0,0,0}, - {23769,23766,23765 ,12041,12038,12037 ,0,0,0}, {23768,23765,23788 ,12040,12037,12060 ,0,0,0}, - {23769,23901,23766 ,12041,12178,12038 ,0,0,0}, {23772,23902,23776 ,12044,12179,12048 ,0,0,0}, - {23903,23904,23901 ,12180,12181,12178 ,0,0,0}, {23770,23905,23906 ,12042,12182,12183 ,0,0,0}, - {23904,23907,23908 ,12181,12184,12185 ,0,0,0}, {23903,23907,23904 ,12180,12184,12181 ,0,0,0}, - {23904,23766,23901 ,12181,12038,12178 ,0,0,0}, {23908,23909,23910 ,12185,12186,12187 ,0,0,0}, - {23909,23908,23911 ,12186,12185,12188 ,0,0,0}, {23907,23911,23908 ,12184,12188,12185 ,0,0,0}, - {23906,23905,23910 ,12183,12182,12187 ,0,0,0}, {23912,23772,23771 ,12189,12044,12043 ,0,0,0}, - {23908,23910,23905 ,12185,12187,12182 ,0,0,0}, {23777,23776,23913 ,12049,12048,12190 ,0,0,0}, - {23908,23914,23904 ,12185,12191,12181 ,0,0,0}, {23915,23788,23765 ,12192,12060,12037 ,0,0,0}, - {23904,23775,23766 ,12181,12047,12038 ,0,0,0}, {23916,23760,23788 ,12193,12032,12060 ,0,0,0}, - {23767,23766,23775 ,12039,12038,12047 ,0,0,0}, {23917,23761,23760 ,12194,12033,12032 ,0,0,0}, - {23915,23765,23767 ,12192,12037,12039 ,0,0,0}, {23918,23792,23761 ,12195,12064,12033 ,0,0,0}, - {23916,23788,23915 ,12193,12060,12192 ,0,0,0}, {23919,23793,23792 ,12196,12065,12064 ,0,0,0}, - {23917,23760,23916 ,12194,12032,12193 ,0,0,0}, {23920,23795,23793 ,12197,12067,12065 ,0,0,0}, - {23761,23917,23918 ,12033,12194,12195 ,0,0,0}, {23921,23922,23923 ,12198,12199,12200 ,0,0,0}, - {23792,23918,23919 ,12064,12195,12196 ,0,0,0}, {23923,23762,23797 ,12200,12034,12069 ,0,0,0}, - {23793,23919,23920 ,12065,12196,12197 ,0,0,0}, {23924,23799,23762 ,12201,12071,12034 ,0,0,0}, - {23795,23920,23900 ,12067,12197,12177 ,0,0,0}, {23925,23804,23799 ,12202,12076,12071 ,0,0,0}, - {23797,23900,23923 ,12069,12177,12200 ,0,0,0}, {23926,23801,23804 ,12203,12073,12076 ,0,0,0}, - {23762,23923,23924 ,12034,12200,12201 ,0,0,0}, {23927,23802,23801 ,12204,12074,12073 ,0,0,0}, - {23925,23799,23924 ,12202,12071,12201 ,0,0,0}, {23928,23896,23802 ,12205,12173,12074 ,0,0,0}, - {23926,23804,23925 ,12203,12076,12202 ,0,0,0}, {23929,23807,23896 ,12206,12079,12173 ,0,0,0}, - {23801,23926,23927 ,12073,12203,12204 ,0,0,0}, {23898,23812,23807 ,12175,12084,12079 ,0,0,0}, - {23802,23927,23928 ,12074,12204,12205 ,0,0,0}, {23930,23810,23812 ,12207,12082,12084 ,0,0,0}, - {23896,23928,23929 ,12173,12205,12206 ,0,0,0}, {23931,23811,23810 ,12208,12083,12082 ,0,0,0}, - {23807,23929,23898 ,12079,12206,12175 ,0,0,0}, {23932,23816,23811 ,12209,12088,12083 ,0,0,0}, - {23930,23812,23898 ,12207,12084,12175 ,0,0,0}, {23933,23814,23816 ,12210,12086,12088 ,0,0,0}, - {23931,23810,23930 ,12208,12082,12207 ,0,0,0}, {23934,23887,23814 ,12211,12164,12086 ,0,0,0}, - {23811,23931,23932 ,12083,12208,12209 ,0,0,0}, {23821,23887,23889 ,12093,12164,12166 ,0,0,0}, - {23816,23932,23933 ,12088,12209,12210 ,0,0,0}, {23935,23819,23821 ,12212,12091,12093 ,0,0,0}, - {23814,23933,23934 ,12086,12210,12211 ,0,0,0}, {23936,23825,23819 ,12213,12097,12091 ,0,0,0}, - {23887,23934,23889 ,12164,12211,12166 ,0,0,0}, {23937,23823,23825 ,12214,12095,12097 ,0,0,0}, - {23935,23821,23889 ,12212,12093,12166 ,0,0,0}, {23938,23824,23823 ,12215,12096,12095 ,0,0,0}, - {23936,23819,23935 ,12213,12091,12212 ,0,0,0}, {23939,23881,23824 ,12216,12158,12096 ,0,0,0}, - {23825,23936,23937 ,12097,12213,12214 ,0,0,0}, {23940,23941,23942 ,12217,12218,12219 ,0,0,0}, - {23823,23937,23938 ,12095,12214,12215 ,0,0,0}, {23943,23833,23826 ,12220,12105,12098 ,0,0,0}, - {23824,23938,23939 ,12096,12215,12216 ,0,0,0}, {23944,23883,23833 ,12221,12160,12105 ,0,0,0}, - {23881,23939,23884 ,12158,12216,12161 ,0,0,0}, {23945,23832,23883 ,12222,12104,12160 ,0,0,0}, - {23826,23884,23943 ,12098,12161,12220 ,0,0,0}, {23946,23834,23832 ,12223,12106,12104 ,0,0,0}, - {23944,23833,23943 ,12221,12105,12220 ,0,0,0}, {23947,23841,23834 ,12224,12113,12106 ,0,0,0}, - {23945,23883,23944 ,12222,12160,12221 ,0,0,0}, {23948,23839,23841 ,12225,12111,12113 ,0,0,0}, - {23946,23832,23945 ,12223,12104,12222 ,0,0,0}, {23949,23837,23839 ,12226,12109,12111 ,0,0,0}, - {23834,23946,23947 ,12106,12223,12224 ,0,0,0}, {23843,23950,23844 ,12115,12227,12116 ,0,0,0}, - {23841,23947,23948 ,12113,12224,12225 ,0,0,0}, {23865,23951,23866 ,12137,12228,12138 ,0,0,0}, - {23839,23948,23949 ,12111,12225,12226 ,0,0,0}, {23865,23847,23844 ,12137,12119,12116 ,0,0,0}, - {23837,23949,23880 ,12109,12226,12157 ,0,0,0}, {23867,23848,23847 ,12139,12120,12119 ,0,0,0}, - {23843,23880,23950 ,12115,12157,12227 ,0,0,0}, {23852,23848,23952 ,12124,12120,12229 ,0,0,0}, - {23865,23844,23950 ,12137,12116,12227 ,0,0,0}, {23869,23862,23861 ,12141,12134,12133 ,0,0,0}, - {23953,23860,23862 ,12230,12132,12134 ,0,0,0}, {23852,23861,23850 ,12124,12133,12122 ,0,0,0}, - {23952,23848,23867 ,12229,12120,12139 ,0,0,0}, {23869,23854,23862 ,12141,12126,12134 ,0,0,0}, - {23861,23852,23869 ,12133,12124,12141 ,0,0,0}, {23858,23954,23856 ,12130,12231,12128 ,0,0,0}, - {23856,23409,23859 ,12128,12156,12131 ,0,0,0}, {23863,23858,23857 ,12135,12130,12129 ,0,0,0}, - {23858,23953,23954 ,12130,12230,12231 ,0,0,0}, {23411,23409,23856 ,12232,12156,12128 ,0,0,0}, - {23905,23914,23908 ,12182,12191,12185 ,0,0,0}, {23771,23770,23906 ,12043,12042,12183 ,0,0,0}, - {23955,23783,23782 ,12233,12055,12054 ,0,0,0}, {23914,23775,23904 ,12191,12047,12181 ,0,0,0}, - {23914,23905,23956 ,12191,12182,12234 ,0,0,0}, {23767,23774,23957 ,12039,12046,12235 ,0,0,0}, - {23773,23775,23914 ,12045,12047,12191 ,0,0,0}, {23915,23957,23958 ,12192,12235,12236 ,0,0,0}, - {23774,23767,23775 ,12046,12039,12047 ,0,0,0}, {23916,23958,23959 ,12193,12236,12237 ,0,0,0}, - {23957,23915,23767 ,12235,12192,12039 ,0,0,0}, {23917,23959,23960 ,12194,12237,12238 ,0,0,0}, - {23958,23916,23915 ,12236,12193,12192 ,0,0,0}, {23918,23960,23961 ,12195,12238,12239 ,0,0,0}, - {23959,23917,23916 ,12237,12194,12193 ,0,0,0}, {23919,23961,23962 ,12196,12239,12240 ,0,0,0}, - {23960,23918,23917 ,12238,12195,12194 ,0,0,0}, {23920,23962,23963 ,12197,12240,12241 ,0,0,0}, - {23961,23919,23918 ,12239,12196,12195 ,0,0,0}, {23900,23963,23921 ,12177,12241,12198 ,0,0,0}, - {23920,23919,23962 ,12197,12196,12240 ,0,0,0}, {23964,23965,23966 ,12242,12243,12244 ,0,0,0}, - {23900,23920,23963 ,12177,12197,12241 ,0,0,0}, {23924,23922,23964 ,12201,12199,12242 ,0,0,0}, - {23923,23900,23921 ,12200,12177,12198 ,0,0,0}, {23925,23964,23967 ,12202,12242,12245 ,0,0,0}, - {23924,23923,23922 ,12201,12200,12199 ,0,0,0}, {23926,23967,23968 ,12203,12245,12246 ,0,0,0}, - {23964,23925,23924 ,12242,12202,12201 ,0,0,0}, {23927,23968,23969 ,12204,12246,12247 ,0,0,0}, - {23967,23926,23925 ,12245,12203,12202 ,0,0,0}, {23928,23969,23970 ,12205,12247,12248 ,0,0,0}, - {23968,23927,23926 ,12246,12204,12203 ,0,0,0}, {23929,23970,23899 ,12206,12248,12176 ,0,0,0}, - {23928,23927,23969 ,12205,12204,12247 ,0,0,0}, {23971,23972,23973 ,12249,12250,12251 ,0,0,0}, - {23929,23928,23970 ,12206,12205,12248 ,0,0,0}, {23930,23897,23974 ,12207,12174,12252 ,0,0,0}, - {23898,23929,23899 ,12175,12206,12176 ,0,0,0}, {23931,23974,23975 ,12208,12252,12253 ,0,0,0}, - {23897,23930,23898 ,12174,12207,12175 ,0,0,0}, {23932,23975,23976 ,12209,12253,12254 ,0,0,0}, - {23974,23931,23930 ,12252,12208,12207 ,0,0,0}, {23933,23976,23977 ,12210,12254,12255 ,0,0,0}, - {23975,23932,23931 ,12253,12209,12208 ,0,0,0}, {23934,23977,23890 ,12211,12255,12167 ,0,0,0}, - {23933,23932,23976 ,12210,12209,12254 ,0,0,0}, {23978,23979,23980 ,12256,12257,12258 ,0,0,0}, - {23934,23933,23977 ,12211,12210,12255 ,0,0,0}, {23935,23891,23981 ,12212,12168,12259 ,0,0,0}, - {23889,23934,23890 ,12166,12211,12167 ,0,0,0}, {23936,23981,23982 ,12213,12259,12260 ,0,0,0}, - {23935,23889,23891 ,12212,12166,12168 ,0,0,0}, {23937,23982,23983 ,12214,12260,12261 ,0,0,0}, - {23981,23936,23935 ,12259,12213,12212 ,0,0,0}, {23938,23983,23984 ,12215,12261,12262 ,0,0,0}, - {23982,23937,23936 ,12260,12214,12213 ,0,0,0}, {23939,23984,23985 ,12216,12262,12263 ,0,0,0}, - {23983,23938,23937 ,12261,12215,12214 ,0,0,0}, {23884,23985,23986 ,12161,12263,12264 ,0,0,0}, - {23939,23938,23984 ,12216,12215,12262 ,0,0,0}, {23943,23986,23941 ,12220,12264,12218 ,0,0,0}, - {23884,23939,23985 ,12161,12216,12263 ,0,0,0}, {23944,23941,23987 ,12221,12218,12265 ,0,0,0}, - {23943,23884,23986 ,12220,12161,12264 ,0,0,0}, {23945,23987,23988 ,12222,12265,12266 ,0,0,0}, - {23941,23944,23943 ,12218,12221,12220 ,0,0,0}, {23946,23988,23989 ,12223,12266,12267 ,0,0,0}, - {23987,23945,23944 ,12265,12222,12221 ,0,0,0}, {23947,23989,23990 ,12224,12267,12268 ,0,0,0}, - {23988,23946,23945 ,12266,12223,12222 ,0,0,0}, {23948,23990,23991 ,12225,12268,12269 ,0,0,0}, - {23989,23947,23946 ,12267,12224,12223 ,0,0,0}, {23949,23991,23992 ,12226,12269,12270 ,0,0,0}, - {23990,23948,23947 ,12268,12225,12224 ,0,0,0}, {23880,23992,23993 ,12157,12270,12271 ,0,0,0}, - {23991,23949,23948 ,12269,12226,12225 ,0,0,0}, {23950,23993,23951 ,12227,12271,12228 ,0,0,0}, - {23880,23949,23992 ,12157,12226,12270 ,0,0,0}, {23994,23867,23866 ,12272,12139,12138 ,0,0,0}, - {23950,23880,23993 ,12227,12157,12271 ,0,0,0}, {23876,23995,23871 ,12149,12273,12143 ,0,0,0}, - {23865,23950,23951 ,12137,12227,12228 ,0,0,0}, {23994,23855,23952 ,12272,12127,12229 ,0,0,0}, - {23854,23996,23862 ,12126,12274,12134 ,0,0,0}, {23952,23869,23852 ,12229,12141,12124 ,0,0,0}, - {23994,23952,23867 ,12272,12229,12139 ,0,0,0}, {23997,23954,23953 ,12275,12231,12230 ,0,0,0}, - {23952,23855,23869 ,12229,12127,12141 ,0,0,0}, {23412,23954,23997 ,12276,12231,12275 ,0,0,0}, - {23954,23411,23856 ,12231,12232,12128 ,0,0,0}, {23860,23953,23858 ,12132,12230,12130 ,0,0,0}, - {23996,23997,23953 ,12274,12275,12230 ,0,0,0}, {23412,23411,23954 ,12276,12232,12231 ,0,0,0}, - {23956,23905,23770 ,12234,12182,12042 ,0,0,0}, {23902,23772,23912 ,12179,12044,12189 ,0,0,0}, - {23998,23774,23780 ,12277,12046,12052 ,0,0,0}, {23956,23773,23914 ,12234,12045,12191 ,0,0,0}, - {23956,23770,23999 ,12234,12042,12278 ,0,0,0}, {24000,24001,24002 ,12279,12280,12281 ,0,0,0}, - {23779,23773,23956 ,12051,12045,12234 ,0,0,0}, {23998,24000,23957 ,12277,12279,12235 ,0,0,0}, - {23780,23774,23773 ,12052,12046,12045 ,0,0,0}, {24000,24003,23958 ,12279,12282,12236 ,0,0,0}, - {23998,23957,23774 ,12277,12235,12046 ,0,0,0}, {24003,24004,23959 ,12282,12283,12237 ,0,0,0}, - {24000,23958,23957 ,12279,12236,12235 ,0,0,0}, {24004,24005,23960 ,12283,12284,12238 ,0,0,0}, - {24003,23959,23958 ,12282,12237,12236 ,0,0,0}, {24005,24006,23961 ,12284,12285,12239 ,0,0,0}, - {24004,23960,23959 ,12283,12238,12237 ,0,0,0}, {24006,24007,23962 ,12285,12286,12240 ,0,0,0}, - {24005,23961,23960 ,12284,12239,12238 ,0,0,0}, {24007,24008,23963 ,12286,12287,12241 ,0,0,0}, - {24006,23962,23961 ,12285,12240,12239 ,0,0,0}, {24008,24009,23921 ,12287,12288,12198 ,0,0,0}, - {24007,23963,23962 ,12286,12241,12240 ,0,0,0}, {24009,23965,23922 ,12288,12243,12199 ,0,0,0}, - {23921,23963,24008 ,12198,12241,12287 ,0,0,0}, {24010,24011,24012 ,12289,12290,12291 ,0,0,0}, - {23922,23921,24009 ,12199,12198,12288 ,0,0,0}, {23966,24010,23967 ,12244,12289,12245 ,0,0,0}, - {23965,23964,23922 ,12243,12242,12199 ,0,0,0}, {24010,24013,23968 ,12289,12292,12246 ,0,0,0}, - {23966,23967,23964 ,12244,12245,12242 ,0,0,0}, {24013,24014,23969 ,12292,12293,12247 ,0,0,0}, - {24010,23968,23967 ,12289,12246,12245 ,0,0,0}, {24014,24015,23970 ,12293,12294,12248 ,0,0,0}, - {24013,23969,23968 ,12292,12247,12246 ,0,0,0}, {24015,24016,23899 ,12294,12295,12176 ,0,0,0}, - {24014,23970,23969 ,12293,12248,12247 ,0,0,0}, {23897,24016,24017 ,12174,12295,12296 ,0,0,0}, - {23899,23970,24015 ,12176,12248,12294 ,0,0,0}, {24017,23971,23974 ,12296,12249,12252 ,0,0,0}, - {24016,23897,23899 ,12295,12174,12176 ,0,0,0}, {23971,24018,23975 ,12249,12297,12253 ,0,0,0}, - {24017,23974,23897 ,12296,12252,12174 ,0,0,0}, {24018,24019,23976 ,12297,12298,12254 ,0,0,0}, - {23971,23975,23974 ,12249,12253,12252 ,0,0,0}, {24019,24020,23977 ,12298,12299,12255 ,0,0,0}, - {24018,23976,23975 ,12297,12254,12253 ,0,0,0}, {24020,24021,23890 ,12299,12300,12167 ,0,0,0}, - {24019,23977,23976 ,12298,12255,12254 ,0,0,0}, {24021,24022,23891 ,12300,12301,12168 ,0,0,0}, - {23890,23977,24020 ,12167,12255,12299 ,0,0,0}, {24022,23978,23981 ,12301,12256,12259 ,0,0,0}, - {23891,23890,24021 ,12168,12167,12300 ,0,0,0}, {23978,24023,23982 ,12256,12302,12260 ,0,0,0}, - {24022,23981,23891 ,12301,12259,12168 ,0,0,0}, {24023,24024,23983 ,12302,12303,12261 ,0,0,0}, - {23978,23982,23981 ,12256,12260,12259 ,0,0,0}, {24024,24025,23984 ,12303,12304,12262 ,0,0,0}, - {24023,23983,23982 ,12302,12261,12260 ,0,0,0}, {24025,24026,23985 ,12304,12305,12263 ,0,0,0}, - {24024,23984,23983 ,12303,12262,12261 ,0,0,0}, {24026,23942,23986 ,12305,12219,12264 ,0,0,0}, - {23985,23984,24025 ,12263,12262,12304 ,0,0,0}, {24027,24028,24029 ,12306,12307,12308 ,0,0,0}, - {23986,23985,24026 ,12264,12263,12305 ,0,0,0}, {23940,24027,23987 ,12217,12306,12265 ,0,0,0}, - {23942,23941,23986 ,12219,12218,12264 ,0,0,0}, {24027,24030,23988 ,12306,12309,12266 ,0,0,0}, - {23940,23987,23941 ,12217,12265,12218 ,0,0,0}, {24030,24031,23989 ,12309,12310,12267 ,0,0,0}, - {24027,23988,23987 ,12306,12266,12265 ,0,0,0}, {24031,24032,23990 ,12310,12311,12268 ,0,0,0}, - {24030,23989,23988 ,12309,12267,12266 ,0,0,0}, {24032,24033,23991 ,12311,12312,12269 ,0,0,0}, - {24031,23990,23989 ,12310,12268,12267 ,0,0,0}, {24033,24034,23992 ,12312,12313,12270 ,0,0,0}, - {24032,23991,23990 ,12311,12269,12268 ,0,0,0}, {24034,24035,23993 ,12313,12314,12271 ,0,0,0}, - {24033,23992,23991 ,12312,12270,12269 ,0,0,0}, {24035,24036,23951 ,12314,12315,12228 ,0,0,0}, - {24034,23993,23992 ,12313,12271,12270 ,0,0,0}, {24036,24037,23866 ,12315,12316,12138 ,0,0,0}, - {24035,23951,23993 ,12314,12228,12271 ,0,0,0}, {24037,23868,23994 ,12316,12140,12272 ,0,0,0}, - {23866,23951,24036 ,12138,12228,12315 ,0,0,0}, {24038,23408,23270 ,12317,12318,12319 ,0,0,0}, - {24037,23994,23866 ,12316,12272,12138 ,0,0,0}, {23870,23853,23868 ,12142,12125,12140 ,0,0,0}, - {23994,23868,23855 ,12272,12140,12127 ,0,0,0}, {23403,23997,24038 ,12320,12275,12317 ,0,0,0}, - {23403,23414,23997 ,12320,12321,12275 ,0,0,0}, {23862,23996,23953 ,12134,12274,12230 ,0,0,0}, - {23872,24038,23996 ,12144,12317,12274 ,0,0,0}, {23412,23997,23414 ,12276,12275,12321 ,0,0,0}, - {23772,23999,23770 ,12044,12278,12042 ,0,0,0}, {23913,23776,23902 ,12190,12048,12179 ,0,0,0}, - {23779,24039,24040 ,12051,12322,12323 ,0,0,0}, {23999,23779,23956 ,12278,12051,12234 ,0,0,0}, - {24041,23999,23772 ,12324,12278,12044 ,0,0,0}, {23780,24040,24042 ,12052,12323,12325 ,0,0,0}, - {23999,24039,23779 ,12278,12322,12051 ,0,0,0}, {23998,24042,24001 ,12277,12325,12280 ,0,0,0}, - {24040,23780,23779 ,12323,12052,12051 ,0,0,0}, {24043,24003,24002 ,12326,12282,12281 ,0,0,0}, - {24042,23998,23780 ,12325,12277,12052 ,0,0,0}, {24044,24004,24043 ,12327,12283,12326 ,0,0,0}, - {24001,24000,23998 ,12280,12279,12277 ,0,0,0}, {24045,24046,24047 ,12328,12329,12330 ,0,0,0}, - {24002,24003,24000 ,12281,12282,12279 ,0,0,0}, {24044,24045,24005 ,12327,12328,12284 ,0,0,0}, - {24043,24004,24003 ,12326,12283,12282 ,0,0,0}, {24045,24048,24006 ,12328,12331,12285 ,0,0,0}, - {24044,24005,24004 ,12327,12284,12283 ,0,0,0}, {24048,24049,24007 ,12331,12332,12286 ,0,0,0}, - {24045,24006,24005 ,12328,12285,12284 ,0,0,0}, {24049,24050,24008 ,12332,12333,12287 ,0,0,0}, - {24048,24007,24006 ,12331,12286,12285 ,0,0,0}, {24050,24051,24009 ,12333,12334,12288 ,0,0,0}, - {24049,24008,24007 ,12332,12287,12286 ,0,0,0}, {23965,24051,24052 ,12243,12334,12335 ,0,0,0}, - {24050,24009,24008 ,12333,12288,12287 ,0,0,0}, {23966,24052,24011 ,12244,12335,12290 ,0,0,0}, - {24051,23965,24009 ,12334,12243,12288 ,0,0,0}, {24053,24054,24055 ,12336,12337,12338 ,0,0,0}, - {24052,23966,23965 ,12335,12244,12243 ,0,0,0}, {24012,24053,24013 ,12291,12336,12292 ,0,0,0}, - {24011,24010,23966 ,12290,12289,12244 ,0,0,0}, {24053,24056,24014 ,12336,12339,12293 ,0,0,0}, - {24012,24013,24010 ,12291,12292,12289 ,0,0,0}, {24056,24057,24015 ,12339,12340,12294 ,0,0,0}, - {24053,24014,24013 ,12336,12293,12292 ,0,0,0}, {24016,24057,24058 ,12295,12340,12341 ,0,0,0}, - {24056,24015,24014 ,12339,12294,12293 ,0,0,0}, {24017,24058,23972 ,12296,12341,12250 ,0,0,0}, - {24016,24015,24057 ,12295,12294,12340 ,0,0,0}, {24059,24060,24061 ,12342,12343,12344 ,0,0,0}, - {24058,24017,24016 ,12341,12296,12295 ,0,0,0}, {23973,24059,24018 ,12251,12342,12297 ,0,0,0}, - {23972,23971,24017 ,12250,12249,12296 ,0,0,0}, {24059,24062,24019 ,12342,12345,12298 ,0,0,0}, - {23973,24018,23971 ,12251,12297,12249 ,0,0,0}, {24062,24063,24020 ,12345,12346,12299 ,0,0,0}, - {24059,24019,24018 ,12342,12298,12297 ,0,0,0}, {24063,24064,24021 ,12346,12347,12300 ,0,0,0}, - {24062,24020,24019 ,12345,12299,12298 ,0,0,0}, {24022,24064,23979 ,12301,12347,12257 ,0,0,0}, - {24021,24020,24063 ,12300,12299,12346 ,0,0,0}, {24065,24066,24067 ,12348,12349,12350 ,0,0,0}, - {24064,24022,24021 ,12347,12301,12300 ,0,0,0}, {23980,24065,24023 ,12258,12348,12302 ,0,0,0}, - {23979,23978,24022 ,12257,12256,12301 ,0,0,0}, {24065,24068,24024 ,12348,12351,12303 ,0,0,0}, - {23980,24023,23978 ,12258,12302,12256 ,0,0,0}, {24068,24069,24025 ,12351,12352,12304 ,0,0,0}, - {24065,24024,24023 ,12348,12303,12302 ,0,0,0}, {24069,24070,24026 ,12352,12353,12305 ,0,0,0}, - {24068,24025,24024 ,12351,12304,12303 ,0,0,0}, {23942,24070,24071 ,12219,12353,12354 ,0,0,0}, - {24069,24026,24025 ,12352,12305,12304 ,0,0,0}, {23940,24071,24028 ,12217,12354,12307 ,0,0,0}, - {24070,23942,24026 ,12353,12219,12305 ,0,0,0}, {24072,24030,24029 ,12355,12309,12308 ,0,0,0}, - {24071,23940,23942 ,12354,12217,12219 ,0,0,0}, {24073,24074,24075 ,12356,12357,12358 ,0,0,0}, - {24028,24027,23940 ,12307,12306,12217 ,0,0,0}, {24072,24073,24031 ,12355,12356,12310 ,0,0,0}, - {24029,24030,24027 ,12308,12309,12306 ,0,0,0}, {24073,24076,24032 ,12356,12359,12311 ,0,0,0}, - {24072,24031,24030 ,12355,12310,12309 ,0,0,0}, {24076,24077,24033 ,12359,12360,12312 ,0,0,0}, - {24073,24032,24031 ,12356,12311,12310 ,0,0,0}, {24077,24078,24034 ,12360,12361,12313 ,0,0,0}, - {24076,24033,24032 ,12359,12312,12311 ,0,0,0}, {24078,24079,24035 ,12361,12362,12314 ,0,0,0}, - {24077,24034,24033 ,12360,12313,12312 ,0,0,0}, {24079,24080,24036 ,12362,12363,12315 ,0,0,0}, - {24078,24035,24034 ,12361,12314,12313 ,0,0,0}, {24080,24081,24037 ,12363,12364,12316 ,0,0,0}, - {24079,24036,24035 ,12362,12315,12314 ,0,0,0}, {23868,24081,23870 ,12140,12364,12142 ,0,0,0}, - {24037,24036,24080 ,12316,12315,12363 ,0,0,0}, {23875,23870,24081 ,12147,12142,12364 ,0,0,0}, - {23868,24037,24081 ,12140,12316,12364 ,0,0,0}, {23872,23995,24038 ,12144,12273,12317 ,0,0,0}, - {23996,24038,23997 ,12274,12317,12275 ,0,0,0}, {23854,23872,23996 ,12126,12144,12274 ,0,0,0}, - {23871,23995,23872 ,12143,12273,12144 ,0,0,0}, {23403,24038,23270 ,12320,12317,12319 ,0,0,0}, - {23776,24041,23772 ,12048,12324,12044 ,0,0,0}, {23784,23778,23777 ,12056,12050,12049 ,0,0,0}, - {24039,24082,24083 ,12322,12365,12366 ,0,0,0}, {24041,24039,23999 ,12324,12322,12278 ,0,0,0}, - {23776,24084,24041 ,12048,12367,12324 ,0,0,0}, {24040,24083,24085 ,12323,12366,12368 ,0,0,0}, - {24041,24082,24039 ,12324,12365,12322 ,0,0,0}, {24042,24085,24086 ,12325,12368,12369 ,0,0,0}, - {24039,24083,24040 ,12322,12366,12323 ,0,0,0}, {24001,24086,24087 ,12280,12369,12370 ,0,0,0}, - {24040,24085,24042 ,12323,12368,12325 ,0,0,0}, {24002,24087,24088 ,12281,12370,12371 ,0,0,0}, - {24042,24086,24001 ,12325,12369,12280 ,0,0,0}, {24043,24088,24089 ,12326,12371,12372 ,0,0,0}, - {24001,24087,24002 ,12280,12370,12281 ,0,0,0}, {24044,24089,24046 ,12327,12372,12329 ,0,0,0}, - {24088,24043,24002 ,12371,12326,12281 ,0,0,0}, {24090,24048,24047 ,12373,12331,12330 ,0,0,0}, - {24089,24044,24043 ,12372,12327,12326 ,0,0,0}, {24091,24092,24090 ,12374,12375,12373 ,0,0,0}, - {24046,24045,24044 ,12329,12328,12327 ,0,0,0}, {24090,24092,24049 ,12373,12375,12332 ,0,0,0}, - {24047,24048,24045 ,12330,12331,12328 ,0,0,0}, {24092,24093,24050 ,12375,12376,12333 ,0,0,0}, - {24090,24049,24048 ,12373,12332,12331 ,0,0,0}, {24051,24093,24094 ,12334,12376,12377 ,0,0,0}, - {24092,24050,24049 ,12375,12333,12332 ,0,0,0}, {24052,24094,24095 ,12335,12377,12378 ,0,0,0}, - {24050,24093,24051 ,12333,12376,12334 ,0,0,0}, {24011,24095,24096 ,12290,12378,12379 ,0,0,0}, - {24051,24094,24052 ,12334,12377,12335 ,0,0,0}, {24012,24096,24054 ,12291,12379,12337 ,0,0,0}, - {24095,24011,24052 ,12378,12290,12335 ,0,0,0}, {24097,24098,24055 ,12380,12381,12338 ,0,0,0}, - {24096,24012,24011 ,12379,12291,12290 ,0,0,0}, {24055,24098,24056 ,12338,12381,12339 ,0,0,0}, - {24054,24053,24012 ,12337,12336,12291 ,0,0,0}, {24098,24099,24057 ,12381,12382,12340 ,0,0,0}, - {24055,24056,24053 ,12338,12339,12336 ,0,0,0}, {24058,24099,24100 ,12341,12382,12383 ,0,0,0}, - {24098,24057,24056 ,12381,12340,12339 ,0,0,0}, {23972,24100,24101 ,12250,12383,12384 ,0,0,0}, - {24057,24099,24058 ,12340,12382,12341 ,0,0,0}, {23973,24101,24060 ,12251,12384,12343 ,0,0,0}, - {24100,23972,24058 ,12383,12250,12341 ,0,0,0}, {24102,24103,24061 ,12385,12386,12344 ,0,0,0}, - {24101,23973,23972 ,12384,12251,12250 ,0,0,0}, {24061,24103,24062 ,12344,12386,12345 ,0,0,0}, - {24060,24059,23973 ,12343,12342,12251 ,0,0,0}, {24103,24104,24063 ,12386,12387,12346 ,0,0,0}, - {24061,24062,24059 ,12344,12345,12342 ,0,0,0}, {24064,24104,24105 ,12347,12387,12388 ,0,0,0}, - {24103,24063,24062 ,12386,12346,12345 ,0,0,0}, {23979,24105,24106 ,12257,12388,12389 ,0,0,0}, - {24063,24104,24064 ,12346,12387,12347 ,0,0,0}, {23980,24106,24066 ,12258,12389,12349 ,0,0,0}, - {24105,23979,24064 ,12388,12257,12347 ,0,0,0}, {24107,24108,24067 ,12390,12391,12350 ,0,0,0}, - {24106,23980,23979 ,12389,12258,12257 ,0,0,0}, {24067,24108,24068 ,12350,12391,12351 ,0,0,0}, - {24066,24065,23980 ,12349,12348,12258 ,0,0,0}, {24108,24109,24069 ,12391,12392,12352 ,0,0,0}, - {24067,24068,24065 ,12350,12351,12348 ,0,0,0}, {24070,24109,24110 ,12353,12392,12393 ,0,0,0}, - {24108,24069,24068 ,12391,12352,12351 ,0,0,0}, {24071,24110,24111 ,12354,12393,12394 ,0,0,0}, - {24069,24109,24070 ,12352,12392,12353 ,0,0,0}, {24028,24111,24112 ,12307,12394,12395 ,0,0,0}, - {24070,24110,24071 ,12353,12393,12354 ,0,0,0}, {24029,24112,24113 ,12308,12395,12396 ,0,0,0}, - {24071,24111,24028 ,12354,12394,12307 ,0,0,0}, {24072,24113,24074 ,12355,12396,12357 ,0,0,0}, - {24112,24029,24028 ,12395,12308,12307 ,0,0,0}, {24114,24076,24075 ,12397,12359,12358 ,0,0,0}, - {24113,24072,24029 ,12396,12355,12308 ,0,0,0}, {24115,24116,24114 ,12398,12399,12397 ,0,0,0}, - {24074,24073,24072 ,12357,12356,12355 ,0,0,0}, {24114,24116,24077 ,12397,12399,12360 ,0,0,0}, - {24075,24076,24073 ,12358,12359,12356 ,0,0,0}, {24116,24117,24078 ,12399,12400,12361 ,0,0,0}, - {24114,24077,24076 ,12397,12360,12359 ,0,0,0}, {24117,24118,24079 ,12400,12401,12362 ,0,0,0}, - {24116,24078,24077 ,12399,12361,12360 ,0,0,0}, {24118,24119,24080 ,12401,12402,12363 ,0,0,0}, - {24117,24079,24078 ,12400,12362,12361 ,0,0,0}, {24081,24119,23875 ,12364,12402,12147 ,0,0,0}, - {24118,24080,24079 ,12401,12363,12362 ,0,0,0}, {23875,24120,23870 ,12147,12403,12142 ,0,0,0}, - {24080,24119,24081 ,12363,12402,12364 ,0,0,0}, {23275,23995,23876 ,12404,12273,12149 ,0,0,0}, - {23995,23408,24038 ,12273,12318,12317 ,0,0,0}, {23853,23871,23872 ,12125,12143,12144 ,0,0,0}, - {24120,23876,23871 ,12403,12149,12143 ,0,0,0}, {23275,23408,23995 ,12404,12318,12273 ,0,0,0}, - {23778,24084,23776 ,12050,12367,12048 ,0,0,0}, {24121,23783,23784 ,12405,12055,12056 ,0,0,0}, - {24122,24082,24084 ,12406,12365,12367 ,0,0,0}, {24084,24082,24041 ,12367,12365,12324 ,0,0,0}, - {24084,23955,24122 ,12367,12233,12406 ,0,0,0}, {24123,24083,24082 ,12407,12366,12365 ,0,0,0}, - {24082,24122,24123 ,12365,12406,12407 ,0,0,0}, {24124,24085,24083 ,12408,12368,12366 ,0,0,0}, - {24083,24123,24124 ,12366,12407,12408 ,0,0,0}, {24125,24086,24085 ,12409,12369,12368 ,0,0,0}, - {24085,24124,24125 ,12368,12408,12409 ,0,0,0}, {24126,24087,24086 ,12410,12370,12369 ,0,0,0}, - {24086,24125,24126 ,12369,12409,12410 ,0,0,0}, {24127,24088,24087 ,12411,12371,12370 ,0,0,0}, - {24087,24126,24127 ,12370,12410,12411 ,0,0,0}, {24128,24089,24088 ,12412,12372,12371 ,0,0,0}, - {24088,24127,24128 ,12371,12411,12412 ,0,0,0}, {24129,24046,24089 ,12413,12329,12372 ,0,0,0}, - {24089,24128,24129 ,12372,12412,12413 ,0,0,0}, {24130,24047,24046 ,12414,12330,12329 ,0,0,0}, - {24046,24129,24130 ,12329,12413,12414 ,0,0,0}, {24131,24090,24047 ,12415,12373,12330 ,0,0,0}, - {24130,24131,24047 ,12414,12415,12330 ,0,0,0}, {24132,24133,24134 ,12416,12417,12418 ,0,0,0}, - {24131,24091,24090 ,12415,12374,12373 ,0,0,0}, {24135,24093,24092 ,12419,12376,12375 ,0,0,0}, - {24091,24135,24092 ,12374,12419,12375 ,0,0,0}, {24136,24094,24093 ,12420,12377,12376 ,0,0,0}, - {24093,24135,24136 ,12376,12419,12420 ,0,0,0}, {24137,24095,24094 ,12421,12378,12377 ,0,0,0}, - {24094,24136,24137 ,12377,12420,12421 ,0,0,0}, {24138,24096,24095 ,12422,12379,12378 ,0,0,0}, - {24095,24137,24138 ,12378,12421,12422 ,0,0,0}, {24139,24054,24096 ,12423,12337,12379 ,0,0,0}, - {24096,24138,24139 ,12379,12422,12423 ,0,0,0}, {24140,24055,24054 ,12424,12338,12337 ,0,0,0}, - {24139,24140,24054 ,12423,12424,12337 ,0,0,0}, {24141,24097,24142 ,12425,12380,12426 ,0,0,0}, - {24140,24097,24055 ,12424,12380,12338 ,0,0,0}, {24141,24099,24098 ,12425,12382,12381 ,0,0,0}, - {24097,24141,24098 ,12380,12425,12381 ,0,0,0}, {24143,24100,24099 ,12427,12383,12382 ,0,0,0}, - {24099,24141,24143 ,12382,12425,12427 ,0,0,0}, {24144,24101,24100 ,12428,12384,12383 ,0,0,0}, - {24100,24143,24144 ,12383,12427,12428 ,0,0,0}, {24145,24060,24101 ,12429,12343,12384 ,0,0,0}, - {24101,24144,24145 ,12384,12428,12429 ,0,0,0}, {24146,24061,24060 ,12430,12344,12343 ,0,0,0}, - {24145,24146,24060 ,12429,12430,12343 ,0,0,0}, {24147,24148,24149 ,12431,12432,12433 ,0,0,0}, - {24146,24102,24061 ,12430,12385,12344 ,0,0,0}, {24150,24104,24103 ,12434,12387,12386 ,0,0,0}, - {24102,24150,24103 ,12385,12434,12386 ,0,0,0}, {24151,24105,24104 ,12435,12388,12387 ,0,0,0}, - {24104,24150,24151 ,12387,12434,12435 ,0,0,0}, {24152,24106,24105 ,12436,12389,12388 ,0,0,0}, - {24105,24151,24152 ,12388,12435,12436 ,0,0,0}, {24153,24066,24106 ,12437,12349,12389 ,0,0,0}, - {24106,24152,24153 ,12389,12436,12437 ,0,0,0}, {24154,24067,24066 ,12438,12350,12349 ,0,0,0}, - {24153,24154,24066 ,12437,12438,12349 ,0,0,0}, {24108,24155,24109 ,12391,12439,12392 ,0,0,0}, - {24154,24107,24067 ,12438,12390,12350 ,0,0,0}, {24156,24157,24155 ,12440,12441,12439 ,0,0,0}, - {24107,24155,24108 ,12390,12439,12391 ,0,0,0}, {24157,24110,24109 ,12441,12393,12392 ,0,0,0}, - {24109,24155,24157 ,12392,12439,12441 ,0,0,0}, {24158,24111,24110 ,12442,12394,12393 ,0,0,0}, - {24110,24157,24158 ,12393,12441,12442 ,0,0,0}, {24159,24112,24111 ,12443,12395,12394 ,0,0,0}, - {24111,24158,24159 ,12394,12442,12443 ,0,0,0}, {24160,24113,24112 ,12444,12396,12395 ,0,0,0}, - {24112,24159,24160 ,12395,12443,12444 ,0,0,0}, {24161,24074,24113 ,12445,12357,12396 ,0,0,0}, - {24113,24160,24161 ,12396,12444,12445 ,0,0,0}, {24162,24075,24074 ,12446,12358,12357 ,0,0,0}, - {24074,24161,24162 ,12357,12445,12446 ,0,0,0}, {24163,24114,24075 ,12447,12397,12358 ,0,0,0}, - {24162,24163,24075 ,12446,12447,12358 ,0,0,0}, {24116,24164,24117 ,12399,12448,12400 ,0,0,0}, - {24163,24115,24114 ,12447,12398,12397 ,0,0,0}, {24117,24165,24118 ,12400,12449,12401 ,0,0,0}, - {24115,24164,24116 ,12398,12448,12399 ,0,0,0}, {24118,24166,24119 ,12401,12450,12402 ,0,0,0}, - {24164,24165,24117 ,12448,12449,12400 ,0,0,0}, {24119,23873,23875 ,12402,12145,12147 ,0,0,0}, - {24165,24166,24118 ,12449,12450,12401 ,0,0,0}, {23874,23878,23877 ,12146,12151,12150 ,0,0,0}, - {24166,23873,24119 ,12450,12145,12402 ,0,0,0}, {23874,24120,23875 ,12146,12403,12147 ,0,0,0}, - {23457,23275,23876 ,12451,12404,12149 ,0,0,0}, {23870,24120,23871 ,12142,12403,12143 ,0,0,0}, - {24120,23874,23877 ,12403,12146,12150 ,0,0,0}, {23272,23457,23876 ,12148,12451,12149 ,0,0,0}, - {23783,23955,23778 ,12055,12233,12050 ,0,0,0}, {24121,23786,23781 ,12405,12058,12053 ,0,0,0}, - {24122,23955,24167 ,12406,12233,12452 ,0,0,0}, {23778,23955,24084 ,12050,12233,12367 ,0,0,0}, - {23955,23782,24167 ,12233,12054,12452 ,0,0,0}, {24123,24122,24168 ,12407,12406,12453 ,0,0,0}, - {24122,24167,24168 ,12406,12452,12453 ,0,0,0}, {24124,24123,24169 ,12408,12407,12454 ,0,0,0}, - {24123,24168,24169 ,12407,12453,12454 ,0,0,0}, {24125,24124,24170 ,12409,12408,12455 ,0,0,0}, - {24124,24169,24170 ,12408,12454,12455 ,0,0,0}, {24126,24125,24171 ,12410,12409,12456 ,0,0,0}, - {24125,24170,24171 ,12409,12455,12456 ,0,0,0}, {24127,24126,24172 ,12411,12410,12457 ,0,0,0}, - {24126,24171,24172 ,12410,12456,12457 ,0,0,0}, {24128,24127,24173 ,12412,12411,12458 ,0,0,0}, - {24127,24172,24173 ,12411,12457,12458 ,0,0,0}, {24129,24128,24174 ,12413,12412,12459 ,0,0,0}, - {24128,24173,24174 ,12412,12458,12459 ,0,0,0}, {24130,24129,24175 ,12414,12413,12460 ,0,0,0}, - {24129,24174,24175 ,12413,12459,12460 ,0,0,0}, {24131,24130,24176 ,12415,12414,12461 ,0,0,0}, - {24130,24175,24176 ,12414,12460,12461 ,0,0,0}, {24091,24131,24177 ,12374,12415,12462 ,0,0,0}, - {24131,24176,24177 ,12415,12461,12462 ,0,0,0}, {24135,24091,24132 ,12419,12374,12416 ,0,0,0}, - {24177,24132,24091 ,12462,12416,12374 ,0,0,0}, {24136,24135,24134 ,12420,12419,12418 ,0,0,0}, - {24135,24132,24134 ,12419,12416,12418 ,0,0,0}, {24137,24136,24178 ,12421,12420,12463 ,0,0,0}, - {24136,24134,24178 ,12420,12418,12463 ,0,0,0}, {24138,24137,24179 ,12422,12421,12464 ,0,0,0}, - {24137,24178,24179 ,12421,12463,12464 ,0,0,0}, {24139,24138,24180 ,12423,12422,12465 ,0,0,0}, - {24138,24179,24180 ,12422,12464,12465 ,0,0,0}, {24140,24139,24181 ,12424,12423,12466 ,0,0,0}, - {24139,24180,24181 ,12423,12465,12466 ,0,0,0}, {24097,24140,24182 ,12380,12424,12467 ,0,0,0}, - {24140,24181,24182 ,12424,12466,12467 ,0,0,0}, {24182,24183,24142 ,12467,12468,12426 ,0,0,0}, - {24182,24142,24097 ,12467,12426,12380 ,0,0,0}, {24143,24141,24184 ,12427,12425,12469 ,0,0,0}, - {24141,24142,24184 ,12425,12426,12469 ,0,0,0}, {24144,24143,24185 ,12428,12427,12470 ,0,0,0}, - {24143,24184,24185 ,12427,12469,12470 ,0,0,0}, {24145,24144,24186 ,12429,12428,12471 ,0,0,0}, - {24144,24185,24186 ,12428,12470,12471 ,0,0,0}, {24146,24145,24187 ,12430,12429,12472 ,0,0,0}, - {24145,24186,24187 ,12429,12471,12472 ,0,0,0}, {24102,24146,24188 ,12385,12430,12473 ,0,0,0}, - {24146,24187,24188 ,12430,12472,12473 ,0,0,0}, {24150,24102,24147 ,12434,12385,12431 ,0,0,0}, - {24188,24147,24102 ,12473,12431,12385 ,0,0,0}, {24151,24150,24149 ,12435,12434,12433 ,0,0,0}, - {24150,24147,24149 ,12434,12431,12433 ,0,0,0}, {24152,24151,24189 ,12436,12435,12474 ,0,0,0}, - {24151,24149,24189 ,12435,12433,12474 ,0,0,0}, {24153,24152,24190 ,12437,12436,12475 ,0,0,0}, - {24152,24189,24190 ,12436,12474,12475 ,0,0,0}, {24154,24153,24191 ,12438,12437,12476 ,0,0,0}, - {24153,24190,24191 ,12437,12475,12476 ,0,0,0}, {24107,24154,24192 ,12390,12438,12477 ,0,0,0}, - {24154,24191,24192 ,12438,12476,12477 ,0,0,0}, {24155,24107,24193 ,12439,12390,12478 ,0,0,0}, - {24107,24192,24193 ,12390,12477,12478 ,0,0,0}, {24156,24193,24194 ,12440,12478,12479 ,0,0,0}, - {24193,24156,24155 ,12478,12440,12439 ,0,0,0}, {24158,24157,24195 ,12442,12441,12480 ,0,0,0}, - {24157,24156,24195 ,12441,12440,12480 ,0,0,0}, {24159,24158,24196 ,12443,12442,12481 ,0,0,0}, - {24158,24195,24196 ,12442,12480,12481 ,0,0,0}, {24160,24159,24197 ,12444,12443,12482 ,0,0,0}, - {24159,24196,24197 ,12443,12481,12482 ,0,0,0}, {24161,24160,24198 ,12445,12444,12483 ,0,0,0}, - {24160,24197,24198 ,12444,12482,12483 ,0,0,0}, {24162,24161,24199 ,12446,12445,12484 ,0,0,0}, - {24161,24198,24199 ,12445,12483,12484 ,0,0,0}, {24163,24162,24200 ,12447,12446,12485 ,0,0,0}, - {24162,24199,24200 ,12446,12484,12485 ,0,0,0}, {24115,24163,24201 ,12398,12447,12486 ,0,0,0}, - {24163,24200,24201 ,12447,12485,12486 ,0,0,0}, {24164,24115,24202 ,12448,12398,12487 ,0,0,0}, - {24115,24201,24202 ,12398,12486,12487 ,0,0,0}, {24165,24164,24203 ,12449,12448,12488 ,0,0,0}, - {24164,24202,24203 ,12448,12487,12488 ,0,0,0}, {24166,24165,24204 ,12450,12449,12489 ,0,0,0}, - {24165,24203,24204 ,12449,12488,12489 ,0,0,0}, {23873,24166,24205 ,12145,12450,12490 ,0,0,0}, - {24166,24204,24205 ,12450,12489,12490 ,0,0,0}, {24206,23874,23873 ,12491,12146,12145 ,0,0,0}, - {24205,24206,23873 ,12490,12491,12145 ,0,0,0}, {24120,23877,23876 ,12403,12150,12149 ,0,0,0}, - {24206,23878,23874 ,12491,12151,12146 ,0,0,0}, {23272,23877,23627 ,12148,12150,12152 ,0,0,0}, - {23781,23783,24121 ,12053,12055,12405 ,0,0,0}, {23790,23787,23781 ,12062,12059,12053 ,0,0,0}, - {23787,24207,23782 ,12059,12492,12054 ,0,0,0}, {23782,24207,24167 ,12054,12492,12452 ,0,0,0}, - {24207,24208,24167 ,12492,12493,12452 ,0,0,0}, {24167,24208,24168 ,12452,12493,12453 ,0,0,0}, - {24208,24209,24168 ,12493,12494,12453 ,0,0,0}, {24168,24209,24169 ,12453,12494,12454 ,0,0,0}, - {24209,24210,24169 ,12494,12495,12454 ,0,0,0}, {24169,24210,24170 ,12454,12495,12455 ,0,0,0}, - {24210,24211,24170 ,12495,12496,12455 ,0,0,0}, {24170,24211,24171 ,12455,12496,12456 ,0,0,0}, - {24211,24212,24171 ,12496,12497,12456 ,0,0,0}, {24171,24212,24172 ,12456,12497,12457 ,0,0,0}, - {24212,24213,24172 ,12497,12498,12457 ,0,0,0}, {24172,24213,24173 ,12457,12498,12458 ,0,0,0}, - {24213,24214,24173 ,12498,12499,12458 ,0,0,0}, {24214,24215,24174 ,12499,12500,12459 ,0,0,0}, - {24214,24174,24173 ,12499,12459,12458 ,0,0,0}, {24215,24216,24175 ,12500,12501,12460 ,0,0,0}, - {24215,24175,24174 ,12500,12460,12459 ,0,0,0}, {24216,24217,24176 ,12501,12502,12461 ,0,0,0}, - {24216,24176,24175 ,12501,12461,12460 ,0,0,0}, {24217,24218,24177 ,12502,12503,12462 ,0,0,0}, - {24217,24177,24176 ,12502,12462,12461 ,0,0,0}, {24218,24219,24132 ,12503,12504,12416 ,0,0,0}, - {24218,24132,24177 ,12503,12416,12462 ,0,0,0}, {24133,24132,24219 ,12417,12416,12504 ,0,0,0}, - {24133,24220,24134 ,12417,12505,12418 ,0,0,0}, {24134,24220,24178 ,12418,12505,12463 ,0,0,0}, - {24220,24221,24178 ,12505,12506,12463 ,0,0,0}, {24178,24221,24179 ,12463,12506,12464 ,0,0,0}, - {24221,24222,24179 ,12506,12507,12464 ,0,0,0}, {24222,24223,24180 ,12507,12508,12465 ,0,0,0}, - {24222,24180,24179 ,12507,12465,12464 ,0,0,0}, {24223,24224,24181 ,12508,12509,12466 ,0,0,0}, - {24223,24181,24180 ,12508,12466,12465 ,0,0,0}, {24224,24183,24182 ,12509,12468,12467 ,0,0,0}, - {24224,24182,24181 ,12509,12467,12466 ,0,0,0}, {24183,24225,24142 ,12468,12510,12426 ,0,0,0}, - {24225,24226,24142 ,12510,12511,12426 ,0,0,0}, {24142,24226,24184 ,12426,12511,12469 ,0,0,0}, - {24226,24227,24184 ,12511,12512,12469 ,0,0,0}, {24184,24227,24185 ,12469,12512,12470 ,0,0,0}, - {24227,24228,24185 ,12512,12513,12470 ,0,0,0}, {24228,24229,24186 ,12513,12514,12471 ,0,0,0}, - {24228,24186,24185 ,12513,12471,12470 ,0,0,0}, {24229,24230,24187 ,12514,12515,12472 ,0,0,0}, - {24229,24187,24186 ,12514,12472,12471 ,0,0,0}, {24230,24231,24188 ,12515,12516,12473 ,0,0,0}, - {24230,24188,24187 ,12515,12473,12472 ,0,0,0}, {24231,24232,24147 ,12516,12517,12431 ,0,0,0}, - {24231,24147,24188 ,12516,12431,12473 ,0,0,0}, {24148,24147,24232 ,12432,12431,12517 ,0,0,0}, - {24148,24233,24149 ,12432,12518,12433 ,0,0,0}, {24149,24233,24189 ,12433,12518,12474 ,0,0,0}, - {24233,24234,24189 ,12518,12519,12474 ,0,0,0}, {24234,24235,24190 ,12519,12520,12475 ,0,0,0}, - {24234,24190,24189 ,12519,12475,12474 ,0,0,0}, {24235,24236,24191 ,12520,12521,12476 ,0,0,0}, - {24235,24191,24190 ,12520,12476,12475 ,0,0,0}, {24236,24237,24192 ,12521,12522,12477 ,0,0,0}, - {24236,24192,24191 ,12521,12477,12476 ,0,0,0}, {24237,24194,24193 ,12522,12479,12478 ,0,0,0}, - {24237,24193,24192 ,12522,12478,12477 ,0,0,0}, {24194,24238,24156 ,12479,12523,12440 ,0,0,0}, - {24238,24239,24156 ,12523,12524,12440 ,0,0,0}, {24156,24239,24195 ,12440,12524,12480 ,0,0,0}, - {24239,24240,24195 ,12524,12525,12480 ,0,0,0}, {24195,24240,24196 ,12480,12525,12481 ,0,0,0}, - {24240,24241,24196 ,12525,12526,12481 ,0,0,0}, {24196,24241,24197 ,12481,12526,12482 ,0,0,0}, - {24241,24242,24197 ,12526,12527,12482 ,0,0,0}, {24242,24243,24198 ,12527,12528,12483 ,0,0,0}, - {24242,24198,24197 ,12527,12483,12482 ,0,0,0}, {24243,24244,24199 ,12528,12529,12484 ,0,0,0}, - {24243,24199,24198 ,12528,12484,12483 ,0,0,0}, {24244,24245,24200 ,12529,12530,12485 ,0,0,0}, - {24244,24200,24199 ,12529,12485,12484 ,0,0,0}, {24245,24246,24201 ,12530,12531,12486 ,0,0,0}, - {24245,24201,24200 ,12530,12486,12485 ,0,0,0}, {24246,24247,24202 ,12531,12532,12487 ,0,0,0}, - {24246,24202,24201 ,12531,12487,12486 ,0,0,0}, {24247,24248,24203 ,12532,12533,12488 ,0,0,0}, - {24247,24203,24202 ,12532,12488,12487 ,0,0,0}, {24248,24249,24204 ,12533,12534,12489 ,0,0,0}, - {24248,24204,24203 ,12533,12489,12488 ,0,0,0}, {24249,24250,24205 ,12534,12535,12490 ,0,0,0}, - {24249,24205,24204 ,12534,12490,12489 ,0,0,0}, {24250,24251,24206 ,12535,12536,12491 ,0,0,0}, - {24250,24206,24205 ,12535,12491,12490 ,0,0,0}, {23879,24206,24251 ,12154,12491,12536 ,0,0,0}, - {24206,23879,23878 ,12491,12154,12151 ,0,0,0}, {23280,23878,23879 ,12153,12151,12154 ,0,0,0}, - {24252,24253,24223 ,12537,12538,12539 ,0,0,0}, {24223,24222,24252 ,12539,12540,12537 ,0,0,0}, - {24254,24255,24256 ,12541,12542,12543 ,0,0,0}, {24257,24221,24220 ,12544,12545,12546 ,0,0,0}, - {24222,24221,24258 ,12540,12545,12547 ,0,0,0}, {24257,24258,24221 ,12544,12547,12545 ,0,0,0}, - {24133,24219,24259 ,12548,12549,12550 ,0,0,0}, {24260,24133,24259 ,12551,12548,12550 ,0,0,0}, - {24220,24133,24260 ,12546,12548,12551 ,0,0,0}, {24259,24218,24261 ,12550,12552,12553 ,0,0,0}, - {24220,24260,24257 ,12546,12551,12544 ,0,0,0}, {24259,24219,24218 ,12550,12549,12552 ,0,0,0}, - {24258,24252,24222 ,12547,12537,12540 ,0,0,0}, {24262,24217,24216 ,12554,12555,12556 ,0,0,0}, - {24262,24261,24217 ,12554,12553,12555 ,0,0,0}, {24263,24262,24216 ,12557,12554,12556 ,0,0,0}, - {24264,24265,24266 ,12558,12559,12560 ,0,0,0}, {24267,24263,24215 ,12561,12557,12562 ,0,0,0}, - {24214,24267,24215 ,12563,12561,12562 ,0,0,0}, {24268,24214,24213 ,12564,12563,12565 ,0,0,0}, - {24267,24214,24268 ,12561,12563,12564 ,0,0,0}, {24269,24268,24213 ,12566,12564,12565 ,0,0,0}, - {24215,24263,24216 ,12562,12557,12556 ,0,0,0}, {24261,24218,24217 ,12553,12552,12555 ,0,0,0}, - {24270,24211,24271 ,12567,12568,12569 ,0,0,0}, {24212,24270,24269 ,12570,12567,12566 ,0,0,0}, - {24210,24272,24271 ,12571,12572,12569 ,0,0,0}, {24212,24211,24270 ,12570,12568,12567 ,0,0,0}, - {24272,24209,24273 ,12572,12573,12574 ,0,0,0}, {24209,24272,24210 ,12573,12572,12571 ,0,0,0}, - {24273,24208,24274 ,12574,12575,12576 ,0,0,0}, {24211,24210,24271 ,12568,12571,12569 ,0,0,0}, - {24209,24208,24273 ,12573,12575,12574 ,0,0,0}, {24273,24275,24276 ,12574,12577,12578 ,0,0,0}, - {23907,24277,23911 ,12579,12580,12188 ,0,0,0}, {24278,24279,24280 ,12581,12582,12583 ,0,0,0}, - {24277,24281,23911 ,12580,12584,12188 ,0,0,0}, {24282,24283,24284 ,12585,12586,12587 ,0,0,0}, - {24277,23907,24282 ,12580,12579,12585 ,0,0,0}, {24274,24208,24207 ,12576,12575,12588 ,0,0,0}, - {24276,24285,24286 ,12578,12589,12590 ,0,0,0}, {24287,24288,24286 ,12591,12592,12590 ,0,0,0}, - {24286,24285,24289 ,12590,12589,12593 ,0,0,0}, {24207,23787,24290 ,12588,12594,12595 ,0,0,0}, - {24291,24292,24293 ,12596,12597,12598 ,0,0,0}, {24292,24294,24295 ,12597,12599,12600 ,0,0,0}, - {24294,24296,24295 ,12599,12601,12600 ,0,0,0}, {24297,24293,24298 ,12602,12598,12603 ,0,0,0}, - {24299,24298,23785 ,12604,12603,12057 ,0,0,0}, {23787,24298,24290 ,12594,12603,12595 ,0,0,0}, - {24298,23790,23785 ,12603,12605,12057 ,0,0,0}, {24299,24297,24298 ,12604,12602,12603 ,0,0,0}, - {24279,24300,24301 ,12582,12606,12607 ,0,0,0}, {24212,24269,24213 ,12570,12566,12565 ,0,0,0}, - {24253,24224,24223 ,12538,12608,12539 ,0,0,0}, {24183,24224,24302 ,12609,12608,12610 ,0,0,0}, - {24253,24302,24224 ,12538,12610,12608 ,0,0,0}, {24303,24225,24183 ,12611,12612,12609 ,0,0,0}, - {24183,24302,24303 ,12609,12610,12611 ,0,0,0}, {24226,24303,24304 ,12613,12611,12614 ,0,0,0}, - {24303,24226,24225 ,12611,12613,12612 ,0,0,0}, {24305,24227,24304 ,12615,12616,12614 ,0,0,0}, - {24226,24304,24227 ,12613,12614,12616 ,0,0,0}, {24228,24227,24305 ,12617,12616,12615 ,0,0,0}, - {24305,24306,24228 ,12615,12618,12617 ,0,0,0}, {24228,24306,24229 ,12617,12618,12619 ,0,0,0}, - {24229,24306,24307 ,12619,12618,12620 ,0,0,0}, {24308,24309,24310 ,12621,12622,12623 ,0,0,0}, - {24311,24230,24307 ,12624,12625,12620 ,0,0,0}, {24229,24307,24230 ,12619,12620,12625 ,0,0,0}, - {24311,24312,24231 ,12624,12626,12627 ,0,0,0}, {24231,24230,24311 ,12627,12625,12624 ,0,0,0}, - {24148,24232,24312 ,12628,12629,12626 ,0,0,0}, {24312,24232,24231 ,12626,12629,12627 ,0,0,0}, - {24313,24233,24148 ,12630,12631,12628 ,0,0,0}, {24148,24312,24313 ,12628,12626,12630 ,0,0,0}, - {24233,24314,24234 ,12631,12632,12633 ,0,0,0}, {24314,24233,24313 ,12632,12631,12630 ,0,0,0}, - {24235,24234,24315 ,12634,12633,12635 ,0,0,0}, {24314,24315,24234 ,12632,12635,12633 ,0,0,0}, - {24316,24235,24315 ,12636,12634,12635 ,0,0,0}, {24316,24236,24235 ,12636,12637,12634 ,0,0,0}, - {24316,24317,24236 ,12636,12638,12637 ,0,0,0}, {24318,24319,24320 ,12639,12640,12641 ,0,0,0}, - {24237,24317,24321 ,12642,12638,12643 ,0,0,0}, {24317,24237,24236 ,12638,12642,12637 ,0,0,0}, - {24322,24194,24321 ,12644,12645,12643 ,0,0,0}, {24237,24321,24194 ,12642,12643,12645 ,0,0,0}, - {24238,24322,24239 ,12646,12644,12647 ,0,0,0}, {24238,24194,24322 ,12646,12645,12644 ,0,0,0}, - {24240,24239,24323 ,12648,12647,12649 ,0,0,0}, {24322,24323,24239 ,12644,12649,12647 ,0,0,0}, - {24324,24241,24240 ,12650,12651,12648 ,0,0,0}, {24240,24323,24324 ,12648,12649,12650 ,0,0,0}, - {24241,24325,24242 ,12651,12652,12653 ,0,0,0}, {24325,24241,24324 ,12652,12651,12650 ,0,0,0}, - {24243,24242,24326 ,12654,12653,12655 ,0,0,0}, {24325,24326,24242 ,12652,12655,12653 ,0,0,0}, - {24327,24243,24326 ,12656,12654,12655 ,0,0,0}, {24327,24244,24243 ,12656,12657,12654 ,0,0,0}, - {24327,24328,24244 ,12656,12658,12657 ,0,0,0}, {24329,24330,24331 ,12659,12660,12661 ,0,0,0}, - {24245,24328,24330 ,12662,12658,12660 ,0,0,0}, {24328,24245,24244 ,12658,12662,12657 ,0,0,0}, - {24332,24246,24330 ,12663,12664,12660 ,0,0,0}, {24245,24330,24246 ,12662,12660,12664 ,0,0,0}, - {24333,24334,24335 ,12665,12666,12667 ,0,0,0}, {24247,24246,24332 ,12668,12664,12663 ,0,0,0}, - {24336,24337,24338 ,12669,12670,12671 ,0,0,0}, {24339,24340,24341 ,12672,12673,12674 ,0,0,0}, - {24342,24343,24344 ,12675,12676,12677 ,0,0,0}, {24345,24346,24347 ,12678,12679,12680 ,0,0,0}, - {24348,24349,24336 ,12681,12682,12669 ,0,0,0}, {24350,24351,24352 ,12683,12684,12685 ,0,0,0}, - {24353,24354,24349 ,12686,12687,12682 ,0,0,0}, {24350,24345,24351 ,12683,12678,12684 ,0,0,0}, - {24349,24355,24356 ,12682,12688,12689 ,0,0,0}, {23859,23410,24352 ,12690,726,12685 ,0,0,0}, - {24357,24247,24332 ,12691,12668,12663 ,0,0,0}, {24247,24357,24248 ,12668,12691,12692 ,0,0,0}, - {24248,24333,24249 ,12692,12665,12693 ,0,0,0}, {24329,24332,24330 ,12659,12663,12660 ,0,0,0}, - {24358,24359,24250 ,12694,12695,12696 ,0,0,0}, {24333,24358,24249 ,12665,12694,12693 ,0,0,0}, - {24356,24358,24335 ,12689,12694,12667 ,0,0,0}, {24249,24358,24250 ,12693,12694,12696 ,0,0,0}, - {24359,24360,23879 ,12695,12697,12698 ,0,0,0}, {24359,23879,24251 ,12695,12698,12699 ,0,0,0}, - {23281,23879,24361 ,730,12698,12700 ,0,0,0}, {24298,23787,23790 ,12603,12594,12605 ,0,0,0}, - {24291,24293,24297 ,12596,12598,12602 ,0,0,0}, {24301,24300,24362 ,12607,12606,12701 ,0,0,0}, - {24290,24274,24207 ,12595,12576,12588 ,0,0,0}, {24290,24293,24363 ,12595,12598,12702 ,0,0,0}, - {24364,24272,24276 ,12703,12572,12578 ,0,0,0}, {24274,24363,24275 ,12576,12702,12577 ,0,0,0}, - {24365,24271,24364 ,12704,12569,12703 ,0,0,0}, {24275,24273,24274 ,12577,12574,12576 ,0,0,0}, - {24366,24270,24365 ,12705,12567,12704 ,0,0,0}, {24276,24272,24273 ,12578,12572,12574 ,0,0,0}, - {24367,24269,24366 ,12706,12566,12705 ,0,0,0}, {24364,24271,24272 ,12703,12569,12572 ,0,0,0}, - {24368,24268,24367 ,12707,12564,12706 ,0,0,0}, {24365,24270,24271 ,12704,12567,12569 ,0,0,0}, - {24369,24267,24368 ,12708,12561,12707 ,0,0,0}, {24366,24269,24270 ,12705,12566,12567 ,0,0,0}, - {24370,24263,24369 ,12709,12557,12708 ,0,0,0}, {24367,24268,24269 ,12706,12564,12566 ,0,0,0}, - {24370,24371,24262 ,12709,12710,12554 ,0,0,0}, {24267,24268,24368 ,12561,12564,12707 ,0,0,0}, - {24372,24261,24371 ,12711,12553,12710 ,0,0,0}, {24263,24267,24369 ,12557,12561,12708 ,0,0,0}, - {24265,24259,24372 ,12559,12550,12711 ,0,0,0}, {24262,24263,24370 ,12554,12557,12709 ,0,0,0}, - {24373,24260,24265 ,12712,12551,12559 ,0,0,0}, {24261,24262,24371 ,12553,12554,12710 ,0,0,0}, - {24374,24257,24373 ,12713,12544,12712 ,0,0,0}, {24259,24261,24372 ,12550,12553,12711 ,0,0,0}, - {24375,24258,24374 ,12714,12547,12713 ,0,0,0}, {24265,24260,24259 ,12559,12551,12550 ,0,0,0}, - {24376,24252,24375 ,12715,12537,12714 ,0,0,0}, {24373,24257,24260 ,12712,12544,12551 ,0,0,0}, - {24376,24377,24253 ,12715,12716,12538 ,0,0,0}, {24258,24257,24374 ,12547,12544,12713 ,0,0,0}, - {24378,24302,24377 ,12717,12610,12716 ,0,0,0}, {24252,24258,24375 ,12537,12547,12714 ,0,0,0}, - {24379,24303,24378 ,12718,12611,12717 ,0,0,0}, {24253,24252,24376 ,12538,12537,12715 ,0,0,0}, - {24380,24304,24379 ,12719,12614,12718 ,0,0,0}, {24302,24253,24377 ,12610,12538,12716 ,0,0,0}, - {24381,24305,24380 ,12720,12615,12719 ,0,0,0}, {24303,24302,24378 ,12611,12610,12717 ,0,0,0}, - {24382,24306,24381 ,12721,12618,12720 ,0,0,0}, {24379,24304,24303 ,12718,12614,12611 ,0,0,0}, - {24382,24383,24307 ,12721,12722,12620 ,0,0,0}, {24305,24304,24380 ,12615,12614,12719 ,0,0,0}, - {24384,24311,24383 ,12723,12624,12722 ,0,0,0}, {24306,24305,24381 ,12618,12615,12720 ,0,0,0}, - {24308,24312,24384 ,12621,12626,12723 ,0,0,0}, {24307,24306,24382 ,12620,12618,12721 ,0,0,0}, - {24385,24313,24308 ,12724,12630,12621 ,0,0,0}, {24311,24307,24383 ,12624,12620,12722 ,0,0,0}, - {24386,24314,24385 ,12725,12632,12724 ,0,0,0}, {24312,24311,24384 ,12626,12624,12723 ,0,0,0}, - {24387,24315,24386 ,12726,12635,12725 ,0,0,0}, {24308,24313,24312 ,12621,12630,12626 ,0,0,0}, - {24388,24316,24387 ,12727,12636,12726 ,0,0,0}, {24385,24314,24313 ,12724,12632,12630 ,0,0,0}, - {24388,24389,24317 ,12727,12728,12638 ,0,0,0}, {24315,24314,24386 ,12635,12632,12725 ,0,0,0}, - {24390,24321,24389 ,12729,12643,12728 ,0,0,0}, {24316,24315,24387 ,12636,12635,12726 ,0,0,0}, - {24391,24322,24390 ,12730,12644,12729 ,0,0,0}, {24317,24316,24388 ,12638,12636,12727 ,0,0,0}, - {24392,24323,24391 ,12731,12649,12730 ,0,0,0}, {24321,24317,24389 ,12643,12638,12728 ,0,0,0}, - {24393,24324,24392 ,12732,12650,12731 ,0,0,0}, {24390,24322,24321 ,12729,12644,12643 ,0,0,0}, - {24394,24325,24393 ,12733,12652,12732 ,0,0,0}, {24391,24323,24322 ,12730,12649,12644 ,0,0,0}, - {24395,24326,24394 ,12734,12655,12733 ,0,0,0}, {24392,24324,24323 ,12731,12650,12649 ,0,0,0}, - {24396,24327,24395 ,12735,12656,12734 ,0,0,0}, {24393,24325,24324 ,12732,12652,12650 ,0,0,0}, - {24396,24331,24328 ,12735,12661,12658 ,0,0,0}, {24326,24325,24394 ,12655,12652,12733 ,0,0,0}, - {24332,24329,24397 ,12663,12659,12736 ,0,0,0}, {24327,24326,24395 ,12656,12655,12734 ,0,0,0}, - {24353,24335,24341 ,12686,12667,12674 ,0,0,0}, {24328,24327,24396 ,12658,12656,12735 ,0,0,0}, - {24357,24397,24334 ,12691,12736,12666 ,0,0,0}, {24328,24331,24330 ,12658,12661,12660 ,0,0,0}, - {24397,24398,24334 ,12736,12737,12666 ,0,0,0}, {24356,24359,24358 ,12689,12695,12694 ,0,0,0}, - {24357,24333,24248 ,12691,12665,12692 ,0,0,0}, {24397,24357,24332 ,12736,12691,12663 ,0,0,0}, - {24356,24353,24349 ,12689,12686,12682 ,0,0,0}, {24333,24357,24334 ,12665,12691,12666 ,0,0,0}, - {24360,24355,24399 ,12697,12688,12738 ,0,0,0}, {24360,24361,23879 ,12697,12700,12698 ,0,0,0}, - {24250,24359,24251 ,12696,12695,12699 ,0,0,0}, {24360,24359,24355 ,12697,12695,12688 ,0,0,0}, - {24400,24361,24360 ,12739,12700,12697 ,0,0,0}, {24298,24293,24290 ,12603,12598,12595 ,0,0,0}, - {24294,24292,24291 ,12599,12597,12596 ,0,0,0}, {24282,23907,23903 ,12585,12579,12740 ,0,0,0}, - {24290,24363,24274 ,12595,12702,12576 ,0,0,0}, {24401,24363,24292 ,12741,12702,12597 ,0,0,0}, - {24286,24288,24364 ,12590,12592,12703 ,0,0,0}, {24285,24275,24401 ,12589,12577,12741 ,0,0,0}, - {24288,24402,24365 ,12592,12742,12704 ,0,0,0}, {24285,24276,24275 ,12589,12578,12577 ,0,0,0}, - {24402,24403,24366 ,12742,12743,12705 ,0,0,0}, {24286,24364,24276 ,12590,12703,12578 ,0,0,0}, - {24403,24404,24367 ,12743,12744,12706 ,0,0,0}, {24288,24365,24364 ,12592,12704,12703 ,0,0,0}, - {24404,24405,24368 ,12744,12745,12707 ,0,0,0}, {24402,24366,24365 ,12742,12705,12704 ,0,0,0}, - {24405,24406,24369 ,12745,12746,12708 ,0,0,0}, {24403,24367,24366 ,12743,12706,12705 ,0,0,0}, - {24406,24407,24370 ,12746,12747,12709 ,0,0,0}, {24404,24368,24367 ,12744,12707,12706 ,0,0,0}, - {24407,24408,24371 ,12747,12748,12710 ,0,0,0}, {24405,24369,24368 ,12745,12708,12707 ,0,0,0}, - {24408,24266,24372 ,12748,12560,12711 ,0,0,0}, {24370,24369,24406 ,12709,12708,12746 ,0,0,0}, - {24409,24410,24411 ,12749,12750,12751 ,0,0,0}, {24371,24370,24407 ,12710,12709,12747 ,0,0,0}, - {24264,24410,24373 ,12558,12750,12712 ,0,0,0}, {24372,24371,24408 ,12711,12710,12748 ,0,0,0}, - {24410,24409,24374 ,12750,12749,12713 ,0,0,0}, {24265,24372,24266 ,12559,12711,12560 ,0,0,0}, - {24409,24412,24375 ,12749,12752,12714 ,0,0,0}, {24264,24373,24265 ,12558,12712,12559 ,0,0,0}, - {24412,24413,24376 ,12752,12753,12715 ,0,0,0}, {24410,24374,24373 ,12750,12713,12712 ,0,0,0}, - {24413,24414,24377 ,12753,12754,12716 ,0,0,0}, {24409,24375,24374 ,12749,12714,12713 ,0,0,0}, - {24414,24415,24378 ,12754,12755,12717 ,0,0,0}, {24376,24375,24412 ,12715,12714,12752 ,0,0,0}, - {24256,24379,24415 ,12543,12718,12755 ,0,0,0}, {24377,24376,24413 ,12716,12715,12753 ,0,0,0}, - {24256,24255,24380 ,12543,12542,12719 ,0,0,0}, {24378,24377,24414 ,12717,12716,12754 ,0,0,0}, - {24255,24416,24381 ,12542,12756,12720 ,0,0,0}, {24415,24379,24378 ,12755,12718,12717 ,0,0,0}, - {24416,24417,24382 ,12756,12757,12721 ,0,0,0}, {24256,24380,24379 ,12543,12719,12718 ,0,0,0}, - {24417,24418,24383 ,12757,12758,12722 ,0,0,0}, {24255,24381,24380 ,12542,12720,12719 ,0,0,0}, - {24418,24309,24384 ,12758,12622,12723 ,0,0,0}, {24382,24381,24416 ,12721,12720,12756 ,0,0,0}, - {24419,24420,24421 ,12759,12760,12761 ,0,0,0}, {24383,24382,24417 ,12722,12721,12757 ,0,0,0}, - {24310,24422,24385 ,12623,12762,12724 ,0,0,0}, {24384,24383,24418 ,12723,12722,12758 ,0,0,0}, - {24422,24423,24386 ,12762,12763,12725 ,0,0,0}, {24308,24384,24309 ,12621,12723,12622 ,0,0,0}, - {24423,24424,24387 ,12763,12764,12726 ,0,0,0}, {24310,24385,24308 ,12623,12724,12621 ,0,0,0}, - {24424,24425,24388 ,12764,12765,12727 ,0,0,0}, {24422,24386,24385 ,12762,12725,12724 ,0,0,0}, - {24425,24426,24389 ,12765,12766,12728 ,0,0,0}, {24423,24387,24386 ,12763,12726,12725 ,0,0,0}, - {24426,24427,24390 ,12766,12767,12729 ,0,0,0}, {24388,24387,24424 ,12727,12726,12764 ,0,0,0}, - {24427,24318,24391 ,12767,12639,12730 ,0,0,0}, {24389,24388,24425 ,12728,12727,12765 ,0,0,0}, - {24318,24320,24392 ,12639,12641,12731 ,0,0,0}, {24390,24389,24426 ,12729,12728,12766 ,0,0,0}, - {24320,24428,24393 ,12641,12768,12732 ,0,0,0}, {24427,24391,24390 ,12767,12730,12729 ,0,0,0}, - {24428,24429,24394 ,12768,12769,12733 ,0,0,0}, {24318,24392,24391 ,12639,12731,12730 ,0,0,0}, - {24429,24430,24395 ,12769,12770,12734 ,0,0,0}, {24320,24393,24392 ,12641,12732,12731 ,0,0,0}, - {24430,24431,24396 ,12770,12771,12735 ,0,0,0}, {24428,24394,24393 ,12768,12733,12732 ,0,0,0}, - {24431,24432,24331 ,12771,12772,12661 ,0,0,0}, {24429,24395,24394 ,12769,12734,12733 ,0,0,0}, - {24432,24433,24329 ,12772,12773,12659 ,0,0,0}, {24430,24396,24395 ,12770,12735,12734 ,0,0,0}, - {24433,24398,24397 ,12773,12737,12736 ,0,0,0}, {24431,24331,24396 ,12771,12661,12735 ,0,0,0}, - {24398,24341,24334 ,12737,12674,12666 ,0,0,0}, {24329,24331,24432 ,12659,12661,12772 ,0,0,0}, - {24434,24435,24436 ,12774,12775,12776 ,0,0,0}, {24433,24397,24329 ,12773,12736,12659 ,0,0,0}, - {24354,24336,24349 ,12687,12669,12682 ,0,0,0}, {24348,24437,24399 ,12681,12777,12738 ,0,0,0}, - {24333,24335,24358 ,12665,12667,12694 ,0,0,0}, {24341,24335,24334 ,12674,12667,12666 ,0,0,0}, - {24438,24399,24437 ,12778,12738,12777 ,0,0,0}, {24399,24400,24360 ,12738,12739,12697 ,0,0,0}, - {24359,24356,24355 ,12695,12689,12688 ,0,0,0}, {24355,24348,24399 ,12688,12681,12738 ,0,0,0}, - {24438,24400,24399 ,12778,12739,12738 ,0,0,0}, {24292,24363,24293 ,12597,12702,12598 ,0,0,0}, - {24439,24295,24296 ,12779,12600,12601 ,0,0,0}, {24439,24300,24295 ,12779,12606,12600 ,0,0,0}, - {24363,24401,24275 ,12702,12741,12577 ,0,0,0}, {24440,24401,24295 ,12780,12741,12600 ,0,0,0}, - {24288,24441,24402 ,12592,12781,12742 ,0,0,0}, {24289,24285,24440 ,12593,12589,12780 ,0,0,0}, - {24402,24442,24403 ,12742,12782,12743 ,0,0,0}, {24289,24287,24286 ,12593,12591,12590 ,0,0,0}, - {24443,24444,24445 ,12783,12784,12785 ,0,0,0}, {24287,24441,24288 ,12591,12781,12592 ,0,0,0}, - {24404,24403,24446 ,12744,12743,12786 ,0,0,0}, {24441,24442,24402 ,12781,12782,12742 ,0,0,0}, - {24405,24404,24445 ,12745,12744,12785 ,0,0,0}, {24442,24446,24403 ,12782,12786,12743 ,0,0,0}, - {24406,24405,24444 ,12746,12745,12784 ,0,0,0}, {24446,24445,24404 ,12786,12785,12744 ,0,0,0}, - {24407,24406,24447 ,12747,12746,12787 ,0,0,0}, {24445,24444,24405 ,12785,12784,12745 ,0,0,0}, - {24408,24407,24448 ,12748,12747,12788 ,0,0,0}, {24444,24447,24406 ,12784,12787,12746 ,0,0,0}, - {24266,24408,24449 ,12560,12748,12789 ,0,0,0}, {24447,24448,24407 ,12787,12788,12747 ,0,0,0}, - {24264,24266,24450 ,12558,12560,12790 ,0,0,0}, {24448,24449,24408 ,12788,12789,12748 ,0,0,0}, - {24410,24264,24451 ,12750,12558,12791 ,0,0,0}, {24450,24266,24449 ,12790,12560,12789 ,0,0,0}, - {24452,24453,24454 ,12792,12793,12794 ,0,0,0}, {24451,24264,24450 ,12791,12558,12790 ,0,0,0}, - {24412,24409,24455 ,12752,12749,12795 ,0,0,0}, {24451,24411,24410 ,12791,12751,12750 ,0,0,0}, - {24413,24412,24454 ,12753,12752,12794 ,0,0,0}, {24411,24455,24409 ,12751,12795,12749 ,0,0,0}, - {24414,24413,24453 ,12754,12753,12793 ,0,0,0}, {24455,24454,24412 ,12795,12794,12752 ,0,0,0}, - {24415,24414,24456 ,12755,12754,12796 ,0,0,0}, {24454,24453,24413 ,12794,12793,12753 ,0,0,0}, - {24256,24415,24457 ,12543,12755,12797 ,0,0,0}, {24456,24414,24453 ,12796,12754,12793 ,0,0,0}, - {24458,24459,24460 ,12798,12799,12800 ,0,0,0}, {24457,24415,24456 ,12797,12755,12796 ,0,0,0}, - {24416,24255,24461 ,12756,12542,12801 ,0,0,0}, {24457,24254,24256 ,12797,12541,12543 ,0,0,0}, - {24417,24416,24460 ,12757,12756,12800 ,0,0,0}, {24254,24461,24255 ,12541,12801,12542 ,0,0,0}, - {24418,24417,24459 ,12758,12757,12799 ,0,0,0}, {24461,24460,24416 ,12801,12800,12756 ,0,0,0}, - {24309,24418,24462 ,12622,12758,12802 ,0,0,0}, {24460,24459,24417 ,12800,12799,12757 ,0,0,0}, - {24310,24309,24463 ,12623,12622,12803 ,0,0,0}, {24459,24462,24418 ,12799,12802,12758 ,0,0,0}, - {24422,24310,24464 ,12762,12623,12804 ,0,0,0}, {24463,24309,24462 ,12803,12622,12802 ,0,0,0}, - {24423,24422,24465 ,12763,12762,12805 ,0,0,0}, {24464,24310,24463 ,12804,12623,12803 ,0,0,0}, - {24424,24423,24419 ,12764,12763,12759 ,0,0,0}, {24464,24465,24422 ,12804,12805,12762 ,0,0,0}, - {24425,24424,24421 ,12765,12764,12761 ,0,0,0}, {24465,24419,24423 ,12805,12759,12763 ,0,0,0}, - {24426,24425,24466 ,12766,12765,12806 ,0,0,0}, {24419,24421,24424 ,12759,12761,12764 ,0,0,0}, - {24427,24426,24467 ,12767,12766,12807 ,0,0,0}, {24421,24466,24425 ,12761,12806,12765 ,0,0,0}, - {24318,24427,24468 ,12639,12767,12808 ,0,0,0}, {24467,24426,24466 ,12807,12766,12806 ,0,0,0}, - {24469,24470,24471 ,12809,12810,12811 ,0,0,0}, {24468,24427,24467 ,12808,12767,12807 ,0,0,0}, - {24428,24320,24472 ,12768,12641,12812 ,0,0,0}, {24468,24319,24318 ,12808,12640,12639 ,0,0,0}, - {24429,24428,24471 ,12769,12768,12811 ,0,0,0}, {24319,24472,24320 ,12640,12812,12641 ,0,0,0}, - {24430,24429,24470 ,12770,12769,12810 ,0,0,0}, {24472,24471,24428 ,12812,12811,12768 ,0,0,0}, - {24431,24430,24473 ,12771,12770,12813 ,0,0,0}, {24471,24470,24429 ,12811,12810,12769 ,0,0,0}, - {24432,24431,24474 ,12772,12771,12814 ,0,0,0}, {24470,24473,24430 ,12810,12813,12770 ,0,0,0}, - {24433,24432,24475 ,12773,12772,12815 ,0,0,0}, {24473,24474,24431 ,12813,12814,12771 ,0,0,0}, - {24398,24433,24476 ,12737,12773,12816 ,0,0,0}, {24474,24475,24432 ,12814,12815,12772 ,0,0,0}, - {24341,24398,24339 ,12674,12737,12672 ,0,0,0}, {24475,24476,24433 ,12815,12816,12773 ,0,0,0}, - {24353,24341,24340 ,12686,12674,12673 ,0,0,0}, {24476,24339,24398 ,12816,12672,12737 ,0,0,0}, - {24477,24347,24436 ,12817,12680,12776 ,0,0,0}, {24478,24337,24336 ,12818,12670,12669 ,0,0,0}, - {24335,24353,24356 ,12667,12686,12689 ,0,0,0}, {24340,24354,24353 ,12673,12687,12686 ,0,0,0}, - {24479,24437,24435 ,12819,12777,12775 ,0,0,0}, {24479,24480,24437 ,12819,12820,12777 ,0,0,0}, - {24355,24349,24348 ,12688,12682,12681 ,0,0,0}, {24348,24338,24437 ,12681,12671,12777 ,0,0,0}, - {24438,24437,24480 ,12778,12777,12820 ,0,0,0}, {24292,24295,24401 ,12597,12600,12741 ,0,0,0}, - {24362,24300,24439 ,12701,12606,12779 ,0,0,0}, {24289,24481,24287 ,12593,12821,12591 ,0,0,0}, - {24401,24440,24285 ,12741,12780,12589 ,0,0,0}, {24300,24482,24440 ,12606,12822,12780 ,0,0,0}, - {24441,24287,24483 ,12781,12591,12823 ,0,0,0}, {24482,24481,24289 ,12822,12821,12593 ,0,0,0}, - {24442,24441,24484 ,12782,12781,12824 ,0,0,0}, {24287,24481,24483 ,12591,12821,12823 ,0,0,0}, - {24446,24442,24485 ,12786,12782,12825 ,0,0,0}, {24441,24483,24484 ,12781,12823,12824 ,0,0,0}, - {24445,24446,24486 ,12785,12786,12826 ,0,0,0}, {24484,24485,24442 ,12824,12825,12782 ,0,0,0}, - {24487,24447,24444 ,12827,12787,12784 ,0,0,0}, {24485,24486,24446 ,12825,12826,12786 ,0,0,0}, - {24488,24489,24490 ,12828,12829,12830 ,0,0,0}, {24486,24443,24445 ,12826,12783,12785 ,0,0,0}, - {24447,24491,24448 ,12787,12831,12788 ,0,0,0}, {24443,24487,24444 ,12783,12827,12784 ,0,0,0}, - {24448,24489,24449 ,12788,12829,12789 ,0,0,0}, {24487,24491,24447 ,12827,12831,12787 ,0,0,0}, - {24449,24488,24450 ,12789,12828,12790 ,0,0,0}, {24491,24489,24448 ,12831,12829,12788 ,0,0,0}, - {24450,24492,24451 ,12790,12832,12791 ,0,0,0}, {24489,24488,24449 ,12829,12828,12789 ,0,0,0}, - {24451,24493,24411 ,12791,12833,12751 ,0,0,0}, {24488,24492,24450 ,12828,12832,12790 ,0,0,0}, - {24455,24411,24494 ,12795,12751,12834 ,0,0,0}, {24492,24493,24451 ,12832,12833,12791 ,0,0,0}, - {24454,24455,24495 ,12794,12795,12835 ,0,0,0}, {24493,24494,24411 ,12833,12834,12751 ,0,0,0}, - {24496,24497,24498 ,12836,12837,12838 ,0,0,0}, {24494,24495,24455 ,12834,12835,12795 ,0,0,0}, - {24453,24499,24456 ,12793,12839,12796 ,0,0,0}, {24495,24452,24454 ,12835,12792,12794 ,0,0,0}, - {24456,24500,24457 ,12796,12840,12797 ,0,0,0}, {24452,24499,24453 ,12792,12839,12793 ,0,0,0}, - {24457,24501,24254 ,12797,12841,12541 ,0,0,0}, {24499,24500,24456 ,12839,12840,12796 ,0,0,0}, - {24461,24254,24502 ,12801,12541,12842 ,0,0,0}, {24500,24501,24457 ,12840,12841,12797 ,0,0,0}, - {24460,24461,24503 ,12800,12801,12843 ,0,0,0}, {24501,24502,24254 ,12841,12842,12541 ,0,0,0}, - {24504,24505,24506 ,12844,12845,12846 ,0,0,0}, {24502,24503,24461 ,12842,12843,12801 ,0,0,0}, - {24459,24507,24462 ,12799,12847,12802 ,0,0,0}, {24503,24458,24460 ,12843,12798,12800 ,0,0,0}, - {24462,24508,24463 ,12802,12848,12803 ,0,0,0}, {24458,24507,24459 ,12798,12847,12799 ,0,0,0}, - {24463,24509,24464 ,12803,12849,12804 ,0,0,0}, {24507,24508,24462 ,12847,12848,12802 ,0,0,0}, - {24464,24510,24465 ,12804,12850,12805 ,0,0,0}, {24508,24509,24463 ,12848,12849,12803 ,0,0,0}, - {24419,24465,24511 ,12759,12805,12851 ,0,0,0}, {24509,24510,24464 ,12849,12850,12804 ,0,0,0}, - {24512,24513,24514 ,12852,12853,12854 ,0,0,0}, {24510,24511,24465 ,12850,12851,12805 ,0,0,0}, - {24421,24515,24466 ,12761,12855,12806 ,0,0,0}, {24511,24420,24419 ,12851,12760,12759 ,0,0,0}, - {24466,24513,24467 ,12806,12853,12807 ,0,0,0}, {24420,24515,24421 ,12760,12855,12761 ,0,0,0}, - {24467,24512,24468 ,12807,12852,12808 ,0,0,0}, {24515,24513,24466 ,12855,12853,12806 ,0,0,0}, - {24468,24516,24319 ,12808,12856,12640 ,0,0,0}, {24513,24512,24467 ,12853,12852,12807 ,0,0,0}, - {24472,24319,24517 ,12812,12640,12857 ,0,0,0}, {24512,24516,24468 ,12852,12856,12808 ,0,0,0}, - {24471,24472,24518 ,12811,12812,12858 ,0,0,0}, {24516,24517,24319 ,12856,12857,12640 ,0,0,0}, - {24519,24473,24470 ,12859,12813,12810 ,0,0,0}, {24517,24518,24472 ,12857,12858,12812 ,0,0,0}, - {24520,24521,24522 ,12860,12861,12862 ,0,0,0}, {24518,24469,24471 ,12858,12809,12811 ,0,0,0}, - {24473,24523,24474 ,12813,12863,12814 ,0,0,0}, {24469,24519,24470 ,12809,12859,12810 ,0,0,0}, - {24474,24521,24475 ,12814,12861,12815 ,0,0,0}, {24519,24523,24473 ,12859,12863,12813 ,0,0,0}, - {24475,24520,24476 ,12815,12860,12816 ,0,0,0}, {24523,24521,24474 ,12863,12861,12814 ,0,0,0}, - {24476,24524,24339 ,12816,12864,12672 ,0,0,0}, {24521,24520,24475 ,12861,12860,12815 ,0,0,0}, - {24339,24525,24340 ,12672,12865,12673 ,0,0,0}, {24520,24524,24476 ,12860,12864,12816 ,0,0,0}, - {24340,24526,24354 ,12673,12866,12687 ,0,0,0}, {24524,24525,24339 ,12864,12865,12672 ,0,0,0}, - {24354,24478,24336 ,12687,12818,12669 ,0,0,0}, {24526,24340,24525 ,12866,12673,12865 ,0,0,0}, - {24343,24337,24527 ,12676,12670,12867 ,0,0,0}, {24354,24526,24478 ,12687,12866,12818 ,0,0,0}, - {24435,24528,24436 ,12775,12868,12776 ,0,0,0}, {24437,24338,24435 ,12777,12671,12775 ,0,0,0}, - {24348,24336,24338 ,12681,12669,12671 ,0,0,0}, {24338,24528,24435 ,12671,12868,12775 ,0,0,0}, - {24479,24435,24434 ,12819,12775,12774 ,0,0,0}, {24295,24300,24440 ,12600,12606,12780 ,0,0,0}, - {24280,24279,24301 ,12583,12582,12607 ,0,0,0}, {24481,24529,24483 ,12821,12869,12823 ,0,0,0}, - {24440,24482,24289 ,12780,12822,12593 ,0,0,0}, {24279,24530,24482 ,12582,12870,12822 ,0,0,0}, - {24484,24483,24531 ,12824,12823,12871 ,0,0,0}, {24481,24530,24529 ,12821,12870,12869 ,0,0,0}, - {24485,24484,24532 ,12825,12824,12872 ,0,0,0}, {24483,24529,24531 ,12823,12869,12871 ,0,0,0}, - {24486,24485,24533 ,12826,12825,12873 ,0,0,0}, {24484,24531,24532 ,12824,12871,12872 ,0,0,0}, - {24443,24486,24534 ,12783,12826,12874 ,0,0,0}, {24485,24532,24533 ,12825,12872,12873 ,0,0,0}, - {24487,24443,24535 ,12827,12783,12875 ,0,0,0}, {24486,24533,24534 ,12826,12873,12874 ,0,0,0}, - {24491,24487,24536 ,12831,12827,12876 ,0,0,0}, {24443,24534,24535 ,12783,12874,12875 ,0,0,0}, - {24489,24491,24537 ,12829,12831,12877 ,0,0,0}, {24535,24536,24487 ,12875,12876,12827 ,0,0,0}, - {24538,24539,24540 ,12878,12879,12880 ,0,0,0}, {24536,24537,24491 ,12876,12877,12831 ,0,0,0}, - {24488,24541,24492 ,12828,12881,12832 ,0,0,0}, {24537,24490,24489 ,12877,12830,12829 ,0,0,0}, - {24492,24540,24493 ,12832,12880,12833 ,0,0,0}, {24490,24541,24488 ,12830,12881,12828 ,0,0,0}, - {24493,24542,24494 ,12833,12882,12834 ,0,0,0}, {24541,24540,24492 ,12881,12880,12832 ,0,0,0}, - {24495,24494,24543 ,12835,12834,12883 ,0,0,0}, {24540,24542,24493 ,12880,12882,12833 ,0,0,0}, - {24452,24495,24544 ,12792,12835,12884 ,0,0,0}, {24494,24542,24543 ,12834,12882,12883 ,0,0,0}, - {24499,24452,24545 ,12839,12792,12885 ,0,0,0}, {24495,24543,24544 ,12835,12883,12884 ,0,0,0}, - {24500,24499,24546 ,12840,12839,12886 ,0,0,0}, {24544,24545,24452 ,12884,12885,12792 ,0,0,0}, - {24500,24547,24501 ,12840,12887,12841 ,0,0,0}, {24545,24546,24499 ,12885,12886,12839 ,0,0,0}, - {24501,24497,24502 ,12841,12837,12842 ,0,0,0}, {24546,24547,24500 ,12886,12887,12840 ,0,0,0}, - {24503,24502,24548 ,12843,12842,12888 ,0,0,0}, {24547,24497,24501 ,12887,12837,12841 ,0,0,0}, - {24458,24503,24549 ,12798,12843,12889 ,0,0,0}, {24502,24497,24548 ,12842,12837,12888 ,0,0,0}, - {24507,24458,24550 ,12847,12798,12890 ,0,0,0}, {24503,24548,24549 ,12843,12888,12889 ,0,0,0}, - {24508,24507,24551 ,12848,12847,12891 ,0,0,0}, {24549,24550,24458 ,12889,12890,12798 ,0,0,0}, - {24508,24552,24509 ,12848,12892,12849 ,0,0,0}, {24550,24551,24507 ,12890,12891,12847 ,0,0,0}, - {24509,24505,24510 ,12849,12845,12850 ,0,0,0}, {24551,24552,24508 ,12891,12892,12848 ,0,0,0}, - {24511,24510,24553 ,12851,12850,12893 ,0,0,0}, {24552,24505,24509 ,12892,12845,12849 ,0,0,0}, - {24420,24511,24554 ,12760,12851,12894 ,0,0,0}, {24510,24505,24553 ,12850,12845,12893 ,0,0,0}, - {24515,24420,24555 ,12855,12760,12895 ,0,0,0}, {24511,24553,24554 ,12851,12893,12894 ,0,0,0}, - {24513,24515,24556 ,12853,12855,12896 ,0,0,0}, {24554,24555,24420 ,12894,12895,12760 ,0,0,0}, - {24557,24558,24559 ,12897,12898,12899 ,0,0,0}, {24555,24556,24515 ,12895,12896,12855 ,0,0,0}, - {24512,24560,24516 ,12852,12900,12856 ,0,0,0}, {24556,24514,24513 ,12896,12854,12853 ,0,0,0}, - {24516,24559,24517 ,12856,12899,12857 ,0,0,0}, {24514,24560,24512 ,12854,12900,12852 ,0,0,0}, - {24518,24517,24561 ,12858,12857,12901 ,0,0,0}, {24560,24559,24516 ,12900,12899,12856 ,0,0,0}, - {24469,24518,24562 ,12809,12858,12902 ,0,0,0}, {24517,24559,24561 ,12857,12899,12901 ,0,0,0}, - {24519,24469,24563 ,12859,12809,12903 ,0,0,0}, {24518,24561,24562 ,12858,12901,12902 ,0,0,0}, - {24523,24519,24564 ,12863,12859,12904 ,0,0,0}, {24469,24562,24563 ,12809,12902,12903 ,0,0,0}, - {24521,24523,24565 ,12861,12863,12905 ,0,0,0}, {24563,24564,24519 ,12903,12904,12859 ,0,0,0}, - {24566,24524,24520 ,12906,12864,12860 ,0,0,0}, {24564,24565,24523 ,12904,12905,12863 ,0,0,0}, - {24567,24568,24569 ,12907,12908,12909 ,0,0,0}, {24565,24522,24521 ,12905,12862,12861 ,0,0,0}, - {24524,24570,24525 ,12864,12910,12865 ,0,0,0}, {24522,24566,24520 ,12862,12906,12860 ,0,0,0}, - {24525,24569,24526 ,12865,12909,12866 ,0,0,0}, {24566,24570,24524 ,12906,12910,12864 ,0,0,0}, - {24526,24571,24478 ,12866,12911,12818 ,0,0,0}, {24570,24569,24525 ,12910,12909,12865 ,0,0,0}, - {24478,24527,24337 ,12818,12867,12670 ,0,0,0}, {24569,24571,24526 ,12909,12911,12866 ,0,0,0}, - {24337,24343,24528 ,12670,12676,12868 ,0,0,0}, {24478,24571,24527 ,12818,12911,12867 ,0,0,0}, - {24572,24436,24347 ,12912,12776,12680 ,0,0,0}, {24573,24434,24436 ,12913,12774,12776 ,0,0,0}, - {24338,24337,24528 ,12671,12670,12868 ,0,0,0}, {24528,24477,24436 ,12868,12817,12776 ,0,0,0}, - {24572,24573,24436 ,12912,12913,12776 ,0,0,0}, {24300,24279,24482 ,12606,12582,12822 ,0,0,0}, - {24574,24278,24280 ,12914,12581,12583 ,0,0,0}, {24531,24529,24284 ,12871,12869,12587 ,0,0,0}, - {24482,24530,24481 ,12822,12870,12821 ,0,0,0}, {24278,24575,24530 ,12581,12915,12870 ,0,0,0}, - {24532,24531,24576 ,12872,12871,12916 ,0,0,0}, {24529,24575,24284 ,12869,12915,12587 ,0,0,0}, - {24577,24576,24578 ,12917,12916,12918 ,0,0,0}, {24531,24284,24576 ,12871,12587,12916 ,0,0,0}, - {24577,24579,24533 ,12917,12919,12873 ,0,0,0}, {24533,24532,24577 ,12873,12872,12917 ,0,0,0}, - {24579,24580,24534 ,12919,12920,12874 ,0,0,0}, {24534,24533,24579 ,12874,12873,12919 ,0,0,0}, - {24580,24581,24535 ,12920,12921,12875 ,0,0,0}, {24535,24534,24580 ,12875,12874,12920 ,0,0,0}, - {24581,24582,24536 ,12921,12922,12876 ,0,0,0}, {24536,24535,24581 ,12876,12875,12921 ,0,0,0}, - {24582,24583,24537 ,12922,12923,12877 ,0,0,0}, {24537,24536,24582 ,12877,12876,12922 ,0,0,0}, - {24583,24584,24490 ,12923,12924,12830 ,0,0,0}, {24490,24537,24583 ,12830,12877,12923 ,0,0,0}, - {24584,24538,24541 ,12924,12878,12881 ,0,0,0}, {24490,24584,24541 ,12830,12924,12881 ,0,0,0}, - {23894,24585,24586 ,12925,12926,12927 ,0,0,0}, {24541,24538,24540 ,12881,12878,12880 ,0,0,0}, - {24542,24587,24543 ,12882,12928,12883 ,0,0,0}, {24540,24539,24542 ,12880,12879,12882 ,0,0,0}, - {24588,24587,24586 ,12929,12928,12927 ,0,0,0}, {24539,24587,24542 ,12879,12928,12882 ,0,0,0}, - {24588,24589,24544 ,12929,12930,12884 ,0,0,0}, {24544,24543,24588 ,12884,12883,12929 ,0,0,0}, - {24589,24590,24545 ,12930,12931,12885 ,0,0,0}, {24545,24544,24589 ,12885,12884,12930 ,0,0,0}, - {24590,24591,24546 ,12931,12932,12886 ,0,0,0}, {24546,24545,24590 ,12886,12885,12931 ,0,0,0}, - {24591,24498,24547 ,12932,12838,12887 ,0,0,0}, {24546,24591,24547 ,12886,12932,12887 ,0,0,0}, - {24592,24593,24594 ,12933,12934,12935 ,0,0,0}, {24547,24498,24497 ,12887,12838,12837 ,0,0,0}, - {24496,24593,24548 ,12836,12934,12888 ,0,0,0}, {24497,24496,24548 ,12837,12836,12888 ,0,0,0}, - {24593,24595,24549 ,12934,12936,12889 ,0,0,0}, {24549,24548,24593 ,12889,12888,12934 ,0,0,0}, - {24595,24596,24550 ,12936,12937,12890 ,0,0,0}, {24550,24549,24595 ,12890,12889,12936 ,0,0,0}, - {24596,24597,24551 ,12937,12938,12891 ,0,0,0}, {24551,24550,24596 ,12891,12890,12937 ,0,0,0}, - {24597,24506,24552 ,12938,12846,12892 ,0,0,0}, {24551,24597,24552 ,12891,12938,12892 ,0,0,0}, - {24598,23885,24599 ,12939,12940,12941 ,0,0,0}, {24552,24506,24505 ,12892,12846,12845 ,0,0,0}, - {24554,24553,24600 ,12894,12893,12942 ,0,0,0}, {24505,24504,24553 ,12845,12844,12893 ,0,0,0}, - {24601,24600,24598 ,12943,12942,12939 ,0,0,0}, {24553,24504,24600 ,12893,12844,12942 ,0,0,0}, - {24601,24602,24555 ,12943,12944,12895 ,0,0,0}, {24555,24554,24601 ,12895,12894,12943 ,0,0,0}, - {24602,24603,24556 ,12944,12945,12896 ,0,0,0}, {24556,24555,24602 ,12896,12895,12944 ,0,0,0}, - {24603,24604,24514 ,12945,12946,12854 ,0,0,0}, {24514,24556,24603 ,12854,12896,12945 ,0,0,0}, - {24604,24557,24560 ,12946,12897,12900 ,0,0,0}, {24514,24604,24560 ,12854,12946,12900 ,0,0,0}, - {24605,24606,24607 ,12947,12948,12949 ,0,0,0}, {24560,24557,24559 ,12900,12897,12899 ,0,0,0}, - {24558,24606,24561 ,12898,12948,12901 ,0,0,0}, {24559,24558,24561 ,12899,12898,12901 ,0,0,0}, - {24606,24608,24562 ,12948,12950,12902 ,0,0,0}, {24562,24561,24606 ,12902,12901,12948 ,0,0,0}, - {24608,24609,24563 ,12950,12951,12903 ,0,0,0}, {24563,24562,24608 ,12903,12902,12950 ,0,0,0}, - {24609,24610,24564 ,12951,12952,12904 ,0,0,0}, {24564,24563,24609 ,12904,12903,12951 ,0,0,0}, - {24610,24611,24565 ,12952,12953,12905 ,0,0,0}, {24565,24564,24610 ,12905,12904,12952 ,0,0,0}, - {24611,24612,24522 ,12953,12954,12862 ,0,0,0}, {24522,24565,24611 ,12862,12905,12953 ,0,0,0}, - {24612,24613,24566 ,12954,12955,12906 ,0,0,0}, {24566,24522,24612 ,12906,12862,12954 ,0,0,0}, - {24613,24567,24570 ,12955,12907,12910 ,0,0,0}, {24566,24613,24570 ,12906,12955,12910 ,0,0,0}, - {24571,24568,24614 ,12911,12908,12956 ,0,0,0}, {24570,24567,24569 ,12910,12907,12909 ,0,0,0}, - {24344,24343,24527 ,12677,12676,12867 ,0,0,0}, {24569,24568,24571 ,12909,12908,12911 ,0,0,0}, - {24342,24477,24343 ,12675,12817,12676 ,0,0,0}, {24571,24614,24527 ,12911,12956,12867 ,0,0,0}, - {24615,24351,24345 ,12957,12684,12678 ,0,0,0}, {24614,24344,24527 ,12956,12677,12867 ,0,0,0}, - {24342,24616,24617 ,12675,12958,12959 ,0,0,0}, {24618,24572,24347 ,12960,12912,12680 ,0,0,0}, - {24528,24343,24477 ,12868,12676,12817 ,0,0,0}, {24347,24477,24617 ,12680,12817,12959 ,0,0,0}, - {24346,24618,24347 ,12679,12960,12680 ,0,0,0}, {24279,24278,24530 ,12582,12581,12870 ,0,0,0}, - {24574,24281,24277 ,12914,12584,12580 ,0,0,0}, {24575,24277,24282 ,12915,12580,12585 ,0,0,0}, - {24530,24575,24529 ,12870,12915,12869 ,0,0,0}, {24284,24575,24282 ,12587,12915,12585 ,0,0,0}, - {24283,24578,24576 ,12586,12918,12916 ,0,0,0}, {24576,24284,24283 ,12916,12587,12586 ,0,0,0}, - {24578,24619,24577 ,12918,12961,12917 ,0,0,0}, {24620,24579,24619 ,12962,12919,12961 ,0,0,0}, - {24532,24576,24577 ,12872,12916,12917 ,0,0,0}, {24579,24577,24619 ,12919,12917,12961 ,0,0,0}, - {24621,24580,24620 ,12963,12920,12962 ,0,0,0}, {24580,24579,24620 ,12920,12919,12962 ,0,0,0}, - {24622,24581,24621 ,12964,12921,12963 ,0,0,0}, {24581,24580,24621 ,12921,12920,12963 ,0,0,0}, - {24623,24582,24622 ,12965,12922,12964 ,0,0,0}, {24582,24581,24622 ,12922,12921,12964 ,0,0,0}, - {24624,24583,24623 ,12966,12923,12965 ,0,0,0}, {24583,24582,24623 ,12923,12922,12965 ,0,0,0}, - {24625,24584,24624 ,12967,12924,12966 ,0,0,0}, {24584,24583,24624 ,12924,12923,12966 ,0,0,0}, - {24626,24538,24625 ,12968,12878,12967 ,0,0,0}, {24538,24584,24625 ,12878,12924,12967 ,0,0,0}, - {24627,24539,24626 ,12969,12879,12968 ,0,0,0}, {24539,24538,24626 ,12879,12878,12968 ,0,0,0}, - {24586,24587,24627 ,12927,12928,12969 ,0,0,0}, {24539,24627,24587 ,12879,12969,12928 ,0,0,0}, - {24586,24585,24588 ,12927,12926,12929 ,0,0,0}, {24628,24589,24585 ,12970,12930,12926 ,0,0,0}, - {24543,24587,24588 ,12883,12928,12929 ,0,0,0}, {24589,24588,24585 ,12930,12929,12926 ,0,0,0}, - {24629,24590,24628 ,12971,12931,12970 ,0,0,0}, {24590,24589,24628 ,12931,12930,12970 ,0,0,0}, - {24630,24591,24629 ,12972,12932,12971 ,0,0,0}, {24591,24590,24629 ,12932,12931,12971 ,0,0,0}, - {24631,24498,24630 ,12973,12838,12972 ,0,0,0}, {24498,24591,24630 ,12838,12932,12972 ,0,0,0}, - {24594,24496,24631 ,12935,12836,12973 ,0,0,0}, {24496,24498,24631 ,12836,12838,12973 ,0,0,0}, - {24594,23809,24592 ,12935,12974,12933 ,0,0,0}, {24496,24594,24593 ,12836,12935,12934 ,0,0,0}, - {24632,24595,24592 ,12975,12936,12933 ,0,0,0}, {24595,24593,24592 ,12936,12934,12933 ,0,0,0}, - {24633,24596,24632 ,12976,12937,12975 ,0,0,0}, {24596,24595,24632 ,12937,12936,12975 ,0,0,0}, - {24634,24597,24633 ,12977,12938,12976 ,0,0,0}, {24597,24596,24633 ,12938,12937,12976 ,0,0,0}, - {24635,24506,24634 ,12978,12846,12977 ,0,0,0}, {24506,24597,24634 ,12846,12938,12977 ,0,0,0}, - {24636,24504,24635 ,12979,12844,12978 ,0,0,0}, {24504,24506,24635 ,12844,12846,12978 ,0,0,0}, - {24598,24600,24636 ,12939,12942,12979 ,0,0,0}, {24504,24636,24600 ,12844,12979,12942 ,0,0,0}, - {24598,24599,24601 ,12939,12941,12943 ,0,0,0}, {24637,24602,24599 ,12980,12944,12941 ,0,0,0}, - {24554,24600,24601 ,12894,12942,12943 ,0,0,0}, {24602,24601,24599 ,12944,12943,12941 ,0,0,0}, - {24638,24603,24637 ,12981,12945,12980 ,0,0,0}, {24603,24602,24637 ,12945,12944,12980 ,0,0,0}, - {24639,24604,24638 ,12982,12946,12981 ,0,0,0}, {24604,24603,24638 ,12946,12945,12981 ,0,0,0}, - {24640,24557,24639 ,12983,12897,12982 ,0,0,0}, {24557,24604,24639 ,12897,12946,12982 ,0,0,0}, - {24607,24558,24640 ,12949,12898,12983 ,0,0,0}, {24558,24557,24640 ,12898,12897,12983 ,0,0,0}, - {24607,23831,24605 ,12949,12984,12947 ,0,0,0}, {24558,24607,24606 ,12898,12949,12948 ,0,0,0}, - {24641,24608,24605 ,12985,12950,12947 ,0,0,0}, {24608,24606,24605 ,12950,12948,12947 ,0,0,0}, - {24642,24609,24641 ,12986,12951,12985 ,0,0,0}, {24609,24608,24641 ,12951,12950,12985 ,0,0,0}, - {24643,24610,24642 ,12987,12952,12986 ,0,0,0}, {24610,24609,24642 ,12952,12951,12986 ,0,0,0}, - {24644,24611,24643 ,12988,12953,12987 ,0,0,0}, {24611,24610,24643 ,12953,12952,12987 ,0,0,0}, - {24645,24612,24644 ,12989,12954,12988 ,0,0,0}, {24612,24611,24644 ,12954,12953,12988 ,0,0,0}, - {24646,24613,24645 ,12990,12955,12989 ,0,0,0}, {24613,24612,24645 ,12955,12954,12989 ,0,0,0}, - {24647,24567,24646 ,12991,12907,12990 ,0,0,0}, {24567,24613,24646 ,12907,12955,12990 ,0,0,0}, - {24648,24568,24647 ,12992,12908,12991 ,0,0,0}, {24568,24567,24647 ,12908,12907,12991 ,0,0,0}, - {24649,24614,24648 ,12993,12956,12992 ,0,0,0}, {24614,24568,24648 ,12956,12908,12992 ,0,0,0}, - {24650,24344,24649 ,12994,12677,12993 ,0,0,0}, {24344,24614,24649 ,12677,12956,12993 ,0,0,0}, - {24650,24616,24342 ,12994,12958,12675 ,0,0,0}, {24342,24344,24650 ,12675,12677,12994 ,0,0,0}, - {24616,24615,24617 ,12958,12957,12959 ,0,0,0}, {24347,24617,24345 ,12680,12959,12678 ,0,0,0}, - {24477,24342,24617 ,12817,12675,12959 ,0,0,0}, {24615,24345,24617 ,12957,12678,12959 ,0,0,0}, - {24346,24345,24350 ,12679,12678,12683 ,0,0,0}, {24575,24278,24277 ,12915,12581,12580 ,0,0,0}, - {24277,24278,24574 ,12580,12581,12914 ,0,0,0}, {23903,23901,24282 ,12740,12995,12585 ,0,0,0}, - {24282,23901,24283 ,12585,12995,12586 ,0,0,0}, {23901,23769,24283 ,12995,12996,12586 ,0,0,0}, - {24283,23769,24578 ,12586,12996,12918 ,0,0,0}, {23769,23768,24578 ,12996,12997,12918 ,0,0,0}, - {24578,23768,24619 ,12918,12997,12961 ,0,0,0}, {23768,23789,24619 ,12997,12998,12961 ,0,0,0}, - {24619,23789,24620 ,12961,12998,12962 ,0,0,0}, {23789,23759,24620 ,12998,12999,12962 ,0,0,0}, - {24620,23759,24621 ,12962,12999,12963 ,0,0,0}, {23759,23794,24621 ,12999,13000,12963 ,0,0,0}, - {24621,23794,24622 ,12963,13000,12964 ,0,0,0}, {23794,23791,24622 ,13000,13001,12964 ,0,0,0}, - {24622,23791,24623 ,12964,13001,12965 ,0,0,0}, {23791,23796,24623 ,13001,13002,12965 ,0,0,0}, - {23796,23798,24624 ,13002,13003,12966 ,0,0,0}, {23796,24624,24623 ,13002,12966,12965 ,0,0,0}, - {23798,23764,24625 ,13003,13004,12967 ,0,0,0}, {23798,24625,24624 ,13003,12967,12966 ,0,0,0}, - {23764,23763,24626 ,13004,13005,12968 ,0,0,0}, {23764,24626,24625 ,13004,12968,12967 ,0,0,0}, - {23763,23800,24627 ,13005,13006,12969 ,0,0,0}, {23763,24627,24626 ,13005,12969,12968 ,0,0,0}, - {23800,23895,24586 ,13006,13007,12927 ,0,0,0}, {23800,24586,24627 ,13006,12927,12969 ,0,0,0}, - {23894,24586,23895 ,12925,12927,13007 ,0,0,0}, {23894,23803,24585 ,12925,13008,12926 ,0,0,0}, - {24585,23803,24628 ,12926,13008,12970 ,0,0,0}, {23803,23808,24628 ,13008,13009,12970 ,0,0,0}, - {24628,23808,24629 ,12970,13009,12971 ,0,0,0}, {23808,23806,24629 ,13009,13010,12971 ,0,0,0}, - {23806,23805,24630 ,13010,13011,12972 ,0,0,0}, {23806,24630,24629 ,13010,12972,12971 ,0,0,0}, - {23805,23893,24631 ,13011,13012,12973 ,0,0,0}, {23805,24631,24630 ,13011,12973,12972 ,0,0,0}, - {23893,23809,24594 ,13012,12974,12935 ,0,0,0}, {23893,24594,24631 ,13012,12935,12973 ,0,0,0}, - {23809,23892,24592 ,12974,13013,12933 ,0,0,0}, {23892,23888,24592 ,13013,13014,12933 ,0,0,0}, - {24592,23888,24632 ,12933,13014,12975 ,0,0,0}, {23888,23813,24632 ,13014,13015,12975 ,0,0,0}, - {24632,23813,24633 ,12975,13015,12976 ,0,0,0}, {23813,23815,24633 ,13015,13016,12976 ,0,0,0}, - {23815,23820,24634 ,13016,13017,12977 ,0,0,0}, {23815,24634,24633 ,13016,12977,12976 ,0,0,0}, - {23820,23818,24635 ,13017,13018,12978 ,0,0,0}, {23820,24635,24634 ,13017,12978,12977 ,0,0,0}, - {23818,23817,24636 ,13018,13019,12979 ,0,0,0}, {23818,24636,24635 ,13018,12979,12978 ,0,0,0}, - {23817,23886,24598 ,13019,13020,12939 ,0,0,0}, {23817,24598,24636 ,13019,12939,12979 ,0,0,0}, - {23885,24598,23886 ,12940,12939,13020 ,0,0,0}, {23885,23822,24599 ,12940,13021,12941 ,0,0,0}, - {24599,23822,24637 ,12941,13021,12980 ,0,0,0}, {23822,23829,24637 ,13021,13022,12980 ,0,0,0}, - {23829,23828,24638 ,13022,13023,12981 ,0,0,0}, {23829,24638,24637 ,13022,12981,12980 ,0,0,0}, - {23828,23827,24639 ,13023,13024,12982 ,0,0,0}, {23828,24639,24638 ,13023,12982,12981 ,0,0,0}, - {23827,23882,24640 ,13024,13025,12983 ,0,0,0}, {23827,24640,24639 ,13024,12983,12982 ,0,0,0}, - {23882,23831,24607 ,13025,12984,12949 ,0,0,0}, {23882,24607,24640 ,13025,12949,12983 ,0,0,0}, - {23831,23830,24605 ,12984,13026,12947 ,0,0,0}, {23830,23836,24605 ,13026,13027,12947 ,0,0,0}, - {24605,23836,24641 ,12947,13027,12985 ,0,0,0}, {23836,23835,24641 ,13027,13028,12985 ,0,0,0}, - {24641,23835,24642 ,12985,13028,12986 ,0,0,0}, {23835,23840,24642 ,13028,13029,12986 ,0,0,0}, - {24642,23840,24643 ,12986,13029,12987 ,0,0,0}, {23840,23838,24643 ,13029,13030,12987 ,0,0,0}, - {23838,23845,24644 ,13030,13031,12988 ,0,0,0}, {23838,24644,24643 ,13030,12988,12987 ,0,0,0}, - {23845,23842,24645 ,13031,13032,12989 ,0,0,0}, {23845,24645,24644 ,13031,12989,12988 ,0,0,0}, - {23842,23849,24646 ,13032,13033,12990 ,0,0,0}, {23842,24646,24645 ,13032,12990,12989 ,0,0,0}, - {23849,23846,24647 ,13033,13034,12991 ,0,0,0}, {23849,24647,24646 ,13033,12991,12990 ,0,0,0}, - {23846,23851,24648 ,13034,13035,12992 ,0,0,0}, {23846,24648,24647 ,13034,12992,12991 ,0,0,0}, - {23851,23850,24649 ,13035,13036,12993 ,0,0,0}, {23851,24649,24648 ,13035,12993,12992 ,0,0,0}, - {23850,23864,24650 ,13036,13037,12994 ,0,0,0}, {23850,24650,24649 ,13036,12994,12993 ,0,0,0}, - {23864,23863,24616 ,13037,13038,12958 ,0,0,0}, {23864,24616,24650 ,13037,12958,12994 ,0,0,0}, - {23863,23857,24615 ,13038,13039,12957 ,0,0,0}, {23863,24615,24616 ,13038,12957,12958 ,0,0,0}, - {23857,23859,24351 ,13039,12690,12684 ,0,0,0}, {23857,24351,24615 ,13039,12684,12957 ,0,0,0}, - {24352,24351,23859 ,12685,12684,12690 ,0,0,0}, {24651,24652,24653 ,13040,13041,13042 ,0,0,0}, - {24654,23728,23727 ,13043,13044,13045 ,0,0,0}, {24654,24655,23728 ,13043,13046,13044 ,0,0,0}, - {24656,23726,24657 ,13047,13048,13049 ,0,0,0}, {23727,24656,24654 ,13045,13047,13043 ,0,0,0}, - {24656,23727,23726 ,13047,13045,13048 ,0,0,0}, {23724,24658,23725 ,13050,13051,13052 ,0,0,0}, - {23639,23725,24658 ,13053,13052,13051 ,0,0,0}, {23639,24658,24657 ,13053,13051,13049 ,0,0,0}, - {23724,23723,24659 ,13050,13054,13055 ,0,0,0}, {23639,24657,23726 ,13053,13049,13048 ,0,0,0}, - {24658,23724,24659 ,13051,13050,13055 ,0,0,0}, {23729,23728,24655 ,13056,13044,13046 ,0,0,0}, - {24660,23722,24661 ,13057,13058,13059 ,0,0,0}, {24660,23723,23722 ,13057,13054,13058 ,0,0,0}, - {24662,24663,24664 ,13060,13061,13062 ,0,0,0}, {24665,24661,23721 ,13063,13059,13064 ,0,0,0}, - {23722,23721,24661 ,13058,13064,13059 ,0,0,0}, {24666,24665,23720 ,13065,13063,13066 ,0,0,0}, - {24666,23719,24667 ,13065,13067,13068 ,0,0,0}, {23720,23719,24666 ,13066,13067,13065 ,0,0,0}, - {24667,23719,23718 ,13068,13067,13069 ,0,0,0}, {23721,23720,24665 ,13064,13066,13063 ,0,0,0}, - {24659,23723,24660 ,13055,13054,13057 ,0,0,0}, {23717,23716,24668 ,13070,13071,13072 ,0,0,0}, - {23717,24669,23718 ,13070,13073,13069 ,0,0,0}, {23715,24670,23716 ,13074,13075,13071 ,0,0,0}, - {23717,24668,24669 ,13070,13072,13073 ,0,0,0}, {23715,23714,24671 ,13074,13076,13077 ,0,0,0}, - {24671,24670,23715 ,13077,13075,13074 ,0,0,0}, {24352,23410,23407 ,13078,11682,13079 ,0,0,0}, - {23716,24670,24668 ,13071,13075,13072 ,0,0,0}, {24671,23714,24672 ,13077,13076,13080 ,0,0,0}, - {24673,24352,23407 ,13081,13078,13079 ,0,0,0}, {24674,24675,24671 ,13082,13083,13077 ,0,0,0}, - {24676,24677,24678 ,13084,13085,13086 ,0,0,0}, {24679,24680,24681 ,13087,13088,13089 ,0,0,0}, - {24682,24683,24572 ,13090,13091,13092 ,0,0,0}, {24682,24346,24684 ,13090,13093,13094 ,0,0,0}, - {24672,23714,23713 ,13080,13076,13095 ,0,0,0}, {24673,23407,24678 ,13081,13079,13086 ,0,0,0}, - {24675,24685,24681 ,13083,13096,13089 ,0,0,0}, {24573,24683,24686 ,13097,13091,13098 ,0,0,0}, - {24687,24400,24688 ,13099,13100,13101 ,0,0,0}, {23276,24689,23713 ,13102,13103,13095 ,0,0,0}, - {24690,24479,24686 ,13104,13105,13098 ,0,0,0}, {24480,24479,24690 ,13106,13105,13104 ,0,0,0}, - {24573,24686,24434 ,13097,13098,13107 ,0,0,0}, {23281,24361,23279 ,11553,13108,13109 ,0,0,0}, - {23276,24687,24689 ,13102,13099,13103 ,0,0,0}, {24400,24687,24361 ,13100,13099,13108 ,0,0,0}, - {24687,23279,24361 ,13099,13109,13108 ,0,0,0}, {24685,24691,24681 ,13096,13110,13089 ,0,0,0}, - {24669,24667,23718 ,13073,13068,13069 ,0,0,0}, {24692,23729,24655 ,13111,13056,13046 ,0,0,0}, - {23730,24692,24693 ,13112,13111,13113 ,0,0,0}, {24692,23730,23729 ,13111,13112,13056 ,0,0,0}, - {24694,23689,24693 ,13114,13115,13113 ,0,0,0}, {23730,24693,23689 ,13112,13113,13115 ,0,0,0}, - {23731,24694,23732 ,13116,13114,13117 ,0,0,0}, {23731,23689,24694 ,13116,13115,13114 ,0,0,0}, - {23733,23732,24695 ,13118,13117,13119 ,0,0,0}, {24694,24695,23732 ,13114,13119,13117 ,0,0,0}, - {24696,23734,23733 ,13120,13121,13118 ,0,0,0}, {23733,24695,24696 ,13118,13119,13120 ,0,0,0}, - {24696,24697,23734 ,13120,13122,13121 ,0,0,0}, {23734,24697,23735 ,13121,13122,13123 ,0,0,0}, - {23735,24697,24698 ,13123,13122,13124 ,0,0,0}, {24699,24700,24701 ,13125,13126,13127 ,0,0,0}, - {24702,23736,24698 ,13128,13129,13124 ,0,0,0}, {23735,24698,23736 ,13123,13124,13129 ,0,0,0}, - {24702,24703,23737 ,13128,13130,13131 ,0,0,0}, {23737,23736,24702 ,13131,13129,13128 ,0,0,0}, - {23654,23738,24703 ,13132,13133,13130 ,0,0,0}, {24703,23738,23737 ,13130,13133,13131 ,0,0,0}, - {24704,23739,23654 ,13134,13135,13132 ,0,0,0}, {23654,24703,24704 ,13132,13130,13134 ,0,0,0}, - {23739,24705,23740 ,13135,13136,13137 ,0,0,0}, {24705,23739,24704 ,13136,13135,13134 ,0,0,0}, - {23741,23740,24706 ,13138,13137,13139 ,0,0,0}, {24705,24706,23740 ,13136,13139,13137 ,0,0,0}, - {24707,23741,24706 ,13140,13138,13139 ,0,0,0}, {24707,23742,23741 ,13140,13141,13138 ,0,0,0}, - {24707,24708,23742 ,13140,13142,13141 ,0,0,0}, {24709,24710,24711 ,13143,13144,13145 ,0,0,0}, - {23743,24708,24712 ,13146,13142,13147 ,0,0,0}, {24708,23743,23742 ,13142,13146,13141 ,0,0,0}, - {24713,23700,24712 ,13148,13149,13147 ,0,0,0}, {23743,24712,23700 ,13146,13147,13149 ,0,0,0}, - {23744,24713,23745 ,13150,13148,13151 ,0,0,0}, {23744,23700,24713 ,13150,13149,13148 ,0,0,0}, - {23746,23745,24714 ,13152,13151,13153 ,0,0,0}, {24713,24714,23745 ,13148,13153,13151 ,0,0,0}, - {24715,23747,23746 ,13154,13155,13152 ,0,0,0}, {23746,24714,24715 ,13152,13153,13154 ,0,0,0}, - {23747,24716,23748 ,13155,13156,13157 ,0,0,0}, {24716,23747,24715 ,13156,13155,13154 ,0,0,0}, - {23749,23748,24717 ,13158,13157,13159 ,0,0,0}, {24716,24717,23748 ,13156,13159,13157 ,0,0,0}, - {24718,23749,24717 ,13160,13158,13159 ,0,0,0}, {24718,23750,23749 ,13160,13161,13158 ,0,0,0}, - {24718,24719,23750 ,13160,13162,13161 ,0,0,0}, {24720,24721,24722 ,13163,13164,13165 ,0,0,0}, - {23751,24719,24721 ,13166,13162,13164 ,0,0,0}, {24719,23751,23750 ,13162,13166,13161 ,0,0,0}, - {24723,23752,24721 ,13167,13168,13164 ,0,0,0}, {23751,24721,23752 ,13166,13164,13168 ,0,0,0}, - {24724,24725,24726 ,13169,13170,13171 ,0,0,0}, {23753,23752,24723 ,13172,13168,13167 ,0,0,0}, - {24727,24728,24729 ,13173,13174,13175 ,0,0,0}, {24730,24731,24732 ,13176,13177,13178 ,0,0,0}, - {24733,24727,24734 ,13179,13173,13180 ,0,0,0}, {24735,24736,24737 ,13181,13182,13183 ,0,0,0}, - {24738,24739,24740 ,13184,13185,13186 ,0,0,0}, {24735,24741,24742 ,13181,13187,13188 ,0,0,0}, - {24743,24744,24745 ,13189,13190,13191 ,0,0,0}, {24742,24741,24746 ,13188,13187,13192 ,0,0,0}, - {23754,23753,24747 ,13193,13172,13194 ,0,0,0}, {23344,24746,24741 ,11616,13192,13187 ,0,0,0}, - {24748,24749,24750 ,13195,13196,13197 ,0,0,0}, {23753,24723,24747 ,13172,13167,13194 ,0,0,0}, - {23754,24732,23755 ,13193,13178,13198 ,0,0,0}, {24720,24723,24721 ,13163,13167,13164 ,0,0,0}, - {23756,23755,24749 ,13199,13198,13196 ,0,0,0}, {24732,24749,23755 ,13178,13196,13198 ,0,0,0}, - {23757,24748,23758 ,13200,13195,13201 ,0,0,0}, {23756,24749,24748 ,13199,13196,13195 ,0,0,0}, - {23758,24751,23378 ,13201,13202,11650 ,0,0,0}, {24748,24751,23758 ,13195,13202,13201 ,0,0,0}, - {23279,24687,23276 ,13109,13099,13102 ,0,0,0}, {24438,24688,24400 ,13203,13101,13100 ,0,0,0}, - {24438,24690,24688 ,13203,13104,13101 ,0,0,0}, {24689,24672,23713 ,13103,13080,13095 ,0,0,0}, - {24689,24688,24752 ,13103,13101,13204 ,0,0,0}, {24753,24670,24675 ,13205,13075,13083 ,0,0,0}, - {24672,24752,24674 ,13080,13204,13082 ,0,0,0}, {24754,24668,24753 ,13206,13072,13205 ,0,0,0}, - {24674,24671,24672 ,13082,13077,13080 ,0,0,0}, {24755,24669,24754 ,13207,13073,13206 ,0,0,0}, - {24675,24670,24671 ,13083,13075,13077 ,0,0,0}, {24756,24667,24755 ,13208,13068,13207 ,0,0,0}, - {24753,24668,24670 ,13205,13072,13075 ,0,0,0}, {24757,24666,24756 ,13209,13065,13208 ,0,0,0}, - {24754,24669,24668 ,13206,13073,13072 ,0,0,0}, {24758,24665,24757 ,13210,13063,13209 ,0,0,0}, - {24755,24667,24669 ,13207,13068,13073 ,0,0,0}, {24759,24661,24758 ,13211,13059,13210 ,0,0,0}, - {24756,24666,24667 ,13208,13065,13068 ,0,0,0}, {24759,24760,24660 ,13211,13212,13057 ,0,0,0}, - {24665,24666,24757 ,13063,13065,13209 ,0,0,0}, {24761,24659,24760 ,13213,13055,13212 ,0,0,0}, - {24661,24665,24758 ,13059,13063,13210 ,0,0,0}, {24662,24658,24761 ,13060,13051,13213 ,0,0,0}, - {24660,24661,24759 ,13057,13059,13211 ,0,0,0}, {24762,24657,24662 ,13214,13049,13060 ,0,0,0}, - {24659,24660,24760 ,13055,13057,13212 ,0,0,0}, {24763,24656,24762 ,13215,13047,13214 ,0,0,0}, - {24658,24659,24761 ,13051,13055,13213 ,0,0,0}, {24764,24654,24763 ,13216,13043,13215 ,0,0,0}, - {24662,24657,24658 ,13060,13049,13051 ,0,0,0}, {24765,24655,24764 ,13217,13046,13216 ,0,0,0}, - {24762,24656,24657 ,13214,13047,13049 ,0,0,0}, {24765,24766,24692 ,13217,13218,13111 ,0,0,0}, - {24654,24656,24763 ,13043,13047,13215 ,0,0,0}, {24767,24693,24766 ,13219,13113,13218 ,0,0,0}, - {24655,24654,24764 ,13046,13043,13216 ,0,0,0}, {24768,24694,24767 ,13220,13114,13219 ,0,0,0}, - {24692,24655,24765 ,13111,13046,13217 ,0,0,0}, {24769,24695,24768 ,13221,13119,13220 ,0,0,0}, - {24693,24692,24766 ,13113,13111,13218 ,0,0,0}, {24770,24696,24769 ,13222,13120,13221 ,0,0,0}, - {24694,24693,24767 ,13114,13113,13219 ,0,0,0}, {24771,24697,24770 ,13223,13122,13222 ,0,0,0}, - {24768,24695,24694 ,13220,13119,13114 ,0,0,0}, {24771,24772,24698 ,13223,13224,13124 ,0,0,0}, - {24696,24695,24769 ,13120,13119,13221 ,0,0,0}, {24773,24702,24772 ,13225,13128,13224 ,0,0,0}, - {24697,24696,24770 ,13122,13120,13222 ,0,0,0}, {24699,24703,24773 ,13125,13130,13225 ,0,0,0}, - {24698,24697,24771 ,13124,13122,13223 ,0,0,0}, {24774,24704,24699 ,13226,13134,13125 ,0,0,0}, - {24702,24698,24772 ,13128,13124,13224 ,0,0,0}, {24775,24705,24774 ,13227,13136,13226 ,0,0,0}, - {24703,24702,24773 ,13130,13128,13225 ,0,0,0}, {24776,24706,24775 ,13228,13139,13227 ,0,0,0}, - {24699,24704,24703 ,13125,13134,13130 ,0,0,0}, {24777,24707,24776 ,13229,13140,13228 ,0,0,0}, - {24774,24705,24704 ,13226,13136,13134 ,0,0,0}, {24777,24778,24708 ,13229,13230,13142 ,0,0,0}, - {24706,24705,24775 ,13139,13136,13227 ,0,0,0}, {24779,24712,24778 ,13231,13147,13230 ,0,0,0}, - {24707,24706,24776 ,13140,13139,13228 ,0,0,0}, {24780,24713,24779 ,13232,13148,13231 ,0,0,0}, - {24708,24707,24777 ,13142,13140,13229 ,0,0,0}, {24781,24714,24780 ,13233,13153,13232 ,0,0,0}, - {24712,24708,24778 ,13147,13142,13230 ,0,0,0}, {24782,24715,24781 ,13234,13154,13233 ,0,0,0}, - {24779,24713,24712 ,13231,13148,13147 ,0,0,0}, {24783,24716,24782 ,13235,13156,13234 ,0,0,0}, - {24780,24714,24713 ,13232,13153,13148 ,0,0,0}, {24784,24717,24783 ,13236,13159,13235 ,0,0,0}, - {24781,24715,24714 ,13233,13154,13153 ,0,0,0}, {24785,24718,24784 ,13237,13160,13236 ,0,0,0}, - {24782,24716,24715 ,13234,13156,13154 ,0,0,0}, {24785,24722,24719 ,13237,13165,13162 ,0,0,0}, - {24717,24716,24783 ,13159,13156,13235 ,0,0,0}, {24723,24720,24786 ,13167,13163,13238 ,0,0,0}, - {24718,24717,24784 ,13160,13159,13236 ,0,0,0}, {24740,24731,24744 ,13186,13177,13190 ,0,0,0}, - {24719,24718,24785 ,13162,13160,13237 ,0,0,0}, {24730,24747,24786 ,13176,13194,13238 ,0,0,0}, - {24721,24719,24722 ,13164,13162,13165 ,0,0,0}, {24730,24786,24787 ,13176,13238,13239 ,0,0,0}, - {24739,24750,24740 ,13185,13197,13186 ,0,0,0}, {24747,24732,23754 ,13194,13178,13193 ,0,0,0}, - {24747,24723,24786 ,13194,13167,13238 ,0,0,0}, {24788,24751,24789 ,13240,13202,13241 ,0,0,0}, - {24747,24730,24732 ,13194,13176,13178 ,0,0,0}, {24750,24749,24731 ,13197,13196,13177 ,0,0,0}, - {24790,24791,24751 ,13242,13243,13202 ,0,0,0}, {23756,24748,23757 ,13199,13195,13200 ,0,0,0}, - {24748,24789,24751 ,13195,13241,13202 ,0,0,0}, {23378,24751,24791 ,11650,13202,13243 ,0,0,0}, - {24687,24688,24689 ,13099,13101,13103 ,0,0,0}, {24480,24690,24438 ,13106,13104,13203 ,0,0,0}, - {24572,24618,24682 ,13092,13244,13090 ,0,0,0}, {24689,24752,24672 ,13103,13204,13080 ,0,0,0}, - {24752,24690,24792 ,13204,13104,13245 ,0,0,0}, {24681,24680,24753 ,13089,13088,13205 ,0,0,0}, - {24685,24674,24792 ,13096,13082,13245 ,0,0,0}, {24680,24793,24754 ,13088,13246,13206 ,0,0,0}, - {24685,24675,24674 ,13096,13083,13082 ,0,0,0}, {24793,24794,24755 ,13246,13247,13207 ,0,0,0}, - {24681,24753,24675 ,13089,13205,13083 ,0,0,0}, {24794,24795,24756 ,13247,13248,13208 ,0,0,0}, - {24680,24754,24753 ,13088,13206,13205 ,0,0,0}, {24795,24796,24757 ,13248,13249,13209 ,0,0,0}, - {24793,24755,24754 ,13246,13207,13206 ,0,0,0}, {24796,24797,24758 ,13249,13250,13210 ,0,0,0}, - {24794,24756,24755 ,13247,13208,13207 ,0,0,0}, {24797,24798,24759 ,13250,13251,13211 ,0,0,0}, - {24795,24757,24756 ,13248,13209,13208 ,0,0,0}, {24798,24799,24760 ,13251,13252,13212 ,0,0,0}, - {24796,24758,24757 ,13249,13210,13209 ,0,0,0}, {24799,24663,24761 ,13252,13061,13213 ,0,0,0}, - {24759,24758,24797 ,13211,13210,13250 ,0,0,0}, {24800,24801,24802 ,13253,13254,13255 ,0,0,0}, - {24760,24759,24798 ,13212,13211,13251 ,0,0,0}, {24664,24801,24762 ,13062,13254,13214 ,0,0,0}, - {24761,24760,24799 ,13213,13212,13252 ,0,0,0}, {24801,24800,24763 ,13254,13253,13215 ,0,0,0}, - {24662,24761,24663 ,13060,13213,13061 ,0,0,0}, {24800,24803,24764 ,13253,13256,13216 ,0,0,0}, - {24664,24762,24662 ,13062,13214,13060 ,0,0,0}, {24803,24804,24765 ,13256,13257,13217 ,0,0,0}, - {24801,24763,24762 ,13254,13215,13214 ,0,0,0}, {24804,24805,24766 ,13257,13258,13218 ,0,0,0}, - {24800,24764,24763 ,13253,13216,13215 ,0,0,0}, {24805,24806,24767 ,13258,13259,13219 ,0,0,0}, - {24765,24764,24803 ,13217,13216,13256 ,0,0,0}, {24652,24768,24806 ,13041,13220,13259 ,0,0,0}, - {24766,24765,24804 ,13218,13217,13257 ,0,0,0}, {24652,24651,24769 ,13041,13040,13221 ,0,0,0}, - {24767,24766,24805 ,13219,13218,13258 ,0,0,0}, {24651,24807,24770 ,13040,13260,13222 ,0,0,0}, - {24806,24768,24767 ,13259,13220,13219 ,0,0,0}, {24807,24808,24771 ,13260,13261,13223 ,0,0,0}, - {24652,24769,24768 ,13041,13221,13220 ,0,0,0}, {24808,24809,24772 ,13261,13262,13224 ,0,0,0}, - {24651,24770,24769 ,13040,13222,13221 ,0,0,0}, {24809,24700,24773 ,13262,13126,13225 ,0,0,0}, - {24771,24770,24807 ,13223,13222,13260 ,0,0,0}, {24810,24811,24812 ,13263,13264,13265 ,0,0,0}, - {24772,24771,24808 ,13224,13223,13261 ,0,0,0}, {24701,24813,24774 ,13127,13266,13226 ,0,0,0}, - {24773,24772,24809 ,13225,13224,13262 ,0,0,0}, {24813,24814,24775 ,13266,13267,13227 ,0,0,0}, - {24699,24773,24700 ,13125,13225,13126 ,0,0,0}, {24814,24815,24776 ,13267,13268,13228 ,0,0,0}, - {24701,24774,24699 ,13127,13226,13125 ,0,0,0}, {24815,24816,24777 ,13268,13269,13229 ,0,0,0}, - {24813,24775,24774 ,13266,13227,13226 ,0,0,0}, {24816,24817,24778 ,13269,13270,13230 ,0,0,0}, - {24814,24776,24775 ,13267,13228,13227 ,0,0,0}, {24817,24818,24779 ,13270,13271,13231 ,0,0,0}, - {24777,24776,24815 ,13229,13228,13268 ,0,0,0}, {24818,24709,24780 ,13271,13143,13232 ,0,0,0}, - {24778,24777,24816 ,13230,13229,13269 ,0,0,0}, {24709,24711,24781 ,13143,13145,13233 ,0,0,0}, - {24779,24778,24817 ,13231,13230,13270 ,0,0,0}, {24711,24819,24782 ,13145,13272,13234 ,0,0,0}, - {24818,24780,24779 ,13271,13232,13231 ,0,0,0}, {24819,24820,24783 ,13272,13273,13235 ,0,0,0}, - {24709,24781,24780 ,13143,13233,13232 ,0,0,0}, {24820,24821,24784 ,13273,13274,13236 ,0,0,0}, - {24711,24782,24781 ,13145,13234,13233 ,0,0,0}, {24821,24822,24785 ,13274,13275,13237 ,0,0,0}, - {24819,24783,24782 ,13272,13235,13234 ,0,0,0}, {24822,24823,24722 ,13275,13276,13165 ,0,0,0}, - {24820,24784,24783 ,13273,13236,13235 ,0,0,0}, {24823,24824,24720 ,13276,13277,13163 ,0,0,0}, - {24821,24785,24784 ,13274,13237,13236 ,0,0,0}, {24824,24787,24786 ,13277,13239,13238 ,0,0,0}, - {24822,24722,24785 ,13275,13165,13237 ,0,0,0}, {24787,24744,24730 ,13239,13190,13176 ,0,0,0}, - {24720,24722,24823 ,13163,13165,13276 ,0,0,0}, {24825,24739,24826 ,13278,13185,13279 ,0,0,0}, - {24720,24824,24786 ,13163,13277,13238 ,0,0,0}, {24750,24739,24789 ,13197,13185,13241 ,0,0,0}, - {24738,24826,24739 ,13184,13279,13185 ,0,0,0}, {24732,24731,24749 ,13178,13177,13196 ,0,0,0}, - {24744,24731,24730 ,13190,13177,13176 ,0,0,0}, {24827,24788,24724 ,13280,13240,13169 ,0,0,0}, - {24788,24790,24751 ,13240,13242,13202 ,0,0,0}, {24748,24750,24789 ,13195,13197,13241 ,0,0,0}, - {24788,24789,24825 ,13240,13241,13278 ,0,0,0}, {24827,24790,24788 ,13280,13242,13240 ,0,0,0}, - {24688,24690,24752 ,13101,13104,13204 ,0,0,0}, {24434,24686,24479 ,13107,13098,13105 ,0,0,0}, - {23405,24678,23407 ,13281,13086,13079 ,0,0,0}, {24752,24792,24674 ,13204,13245,13082 ,0,0,0}, - {24792,24686,24828 ,13245,13098,13282 ,0,0,0}, {24680,24829,24793 ,13088,13283,13246 ,0,0,0}, - {24691,24685,24828 ,13110,13096,13282 ,0,0,0}, {24793,24830,24794 ,13246,13284,13247 ,0,0,0}, - {24691,24679,24681 ,13110,13087,13089 ,0,0,0}, {24831,24832,24833 ,13285,13286,13287 ,0,0,0}, - {24679,24829,24680 ,13087,13283,13088 ,0,0,0}, {24795,24794,24834 ,13248,13247,13288 ,0,0,0}, - {24829,24830,24793 ,13283,13284,13246 ,0,0,0}, {24796,24795,24833 ,13249,13248,13287 ,0,0,0}, - {24830,24834,24794 ,13284,13288,13247 ,0,0,0}, {24797,24796,24832 ,13250,13249,13286 ,0,0,0}, - {24834,24833,24795 ,13288,13287,13248 ,0,0,0}, {24798,24797,24835 ,13251,13250,13289 ,0,0,0}, - {24833,24832,24796 ,13287,13286,13249 ,0,0,0}, {24799,24798,24836 ,13252,13251,13290 ,0,0,0}, - {24832,24835,24797 ,13286,13289,13250 ,0,0,0}, {24663,24799,24837 ,13061,13252,13291 ,0,0,0}, - {24835,24836,24798 ,13289,13290,13251 ,0,0,0}, {24664,24663,24838 ,13062,13061,13292 ,0,0,0}, - {24836,24837,24799 ,13290,13291,13252 ,0,0,0}, {24801,24664,24839 ,13254,13062,13293 ,0,0,0}, - {24838,24663,24837 ,13292,13061,13291 ,0,0,0}, {24840,24841,24842 ,13294,13295,13296 ,0,0,0}, - {24839,24664,24838 ,13293,13062,13292 ,0,0,0}, {24803,24800,24843 ,13256,13253,13297 ,0,0,0}, - {24839,24802,24801 ,13293,13255,13254 ,0,0,0}, {24804,24803,24842 ,13257,13256,13296 ,0,0,0}, - {24802,24843,24800 ,13255,13297,13253 ,0,0,0}, {24805,24804,24841 ,13258,13257,13295 ,0,0,0}, - {24843,24842,24803 ,13297,13296,13256 ,0,0,0}, {24806,24805,24844 ,13259,13258,13298 ,0,0,0}, - {24842,24841,24804 ,13296,13295,13257 ,0,0,0}, {24652,24806,24845 ,13041,13259,13299 ,0,0,0}, - {24844,24805,24841 ,13298,13258,13295 ,0,0,0}, {24846,24847,24848 ,13300,13301,13302 ,0,0,0}, - {24845,24806,24844 ,13299,13259,13298 ,0,0,0}, {24807,24651,24849 ,13260,13040,13303 ,0,0,0}, - {24845,24653,24652 ,13299,13042,13041 ,0,0,0}, {24808,24807,24848 ,13261,13260,13302 ,0,0,0}, - {24653,24849,24651 ,13042,13303,13040 ,0,0,0}, {24809,24808,24847 ,13262,13261,13301 ,0,0,0}, - {24849,24848,24807 ,13303,13302,13260 ,0,0,0}, {24700,24809,24850 ,13126,13262,13304 ,0,0,0}, - {24848,24847,24808 ,13302,13301,13261 ,0,0,0}, {24701,24700,24851 ,13127,13126,13305 ,0,0,0}, - {24847,24850,24809 ,13301,13304,13262 ,0,0,0}, {24813,24701,24852 ,13266,13127,13306 ,0,0,0}, - {24851,24700,24850 ,13305,13126,13304 ,0,0,0}, {24814,24813,24853 ,13267,13266,13307 ,0,0,0}, - {24852,24701,24851 ,13306,13127,13305 ,0,0,0}, {24815,24814,24810 ,13268,13267,13263 ,0,0,0}, - {24852,24853,24813 ,13306,13307,13266 ,0,0,0}, {24816,24815,24812 ,13269,13268,13265 ,0,0,0}, - {24853,24810,24814 ,13307,13263,13267 ,0,0,0}, {24817,24816,24854 ,13270,13269,13308 ,0,0,0}, - {24810,24812,24815 ,13263,13265,13268 ,0,0,0}, {24818,24817,24855 ,13271,13270,13309 ,0,0,0}, - {24812,24854,24816 ,13265,13308,13269 ,0,0,0}, {24709,24818,24856 ,13143,13271,13310 ,0,0,0}, - {24855,24817,24854 ,13309,13270,13308 ,0,0,0}, {24857,24858,24859 ,13311,13312,13313 ,0,0,0}, - {24856,24818,24855 ,13310,13271,13309 ,0,0,0}, {24819,24711,24860 ,13272,13145,13314 ,0,0,0}, - {24856,24710,24709 ,13310,13144,13143 ,0,0,0}, {24820,24819,24859 ,13273,13272,13313 ,0,0,0}, - {24710,24860,24711 ,13144,13314,13145 ,0,0,0}, {24821,24820,24858 ,13274,13273,13312 ,0,0,0}, - {24860,24859,24819 ,13314,13313,13272 ,0,0,0}, {24822,24821,24861 ,13275,13274,13315 ,0,0,0}, - {24859,24858,24820 ,13313,13312,13273 ,0,0,0}, {24823,24822,24862 ,13276,13275,13316 ,0,0,0}, - {24858,24861,24821 ,13312,13315,13274 ,0,0,0}, {24824,24823,24863 ,13277,13276,13317 ,0,0,0}, - {24861,24862,24822 ,13315,13316,13275 ,0,0,0}, {24787,24824,24864 ,13239,13277,13318 ,0,0,0}, - {24862,24863,24823 ,13316,13317,13276 ,0,0,0}, {24744,24787,24745 ,13190,13239,13191 ,0,0,0}, - {24863,24864,24824 ,13317,13318,13277 ,0,0,0}, {24740,24744,24743 ,13186,13190,13189 ,0,0,0}, - {24864,24745,24787 ,13318,13191,13239 ,0,0,0}, {24725,24826,24728 ,13170,13279,13174 ,0,0,0}, - {24826,24865,24728 ,13279,13319,13174 ,0,0,0}, {24731,24740,24750 ,13177,13186,13197 ,0,0,0}, - {24743,24738,24740 ,13189,13184,13186 ,0,0,0}, {24866,24724,24726 ,13320,13169,13171 ,0,0,0}, - {24788,24825,24724 ,13240,13278,13169 ,0,0,0}, {24789,24739,24825 ,13241,13185,13278 ,0,0,0}, - {24825,24725,24724 ,13278,13170,13169 ,0,0,0}, {24827,24724,24866 ,13280,13169,13320 ,0,0,0}, - {24686,24792,24690 ,13098,13245,13104 ,0,0,0}, {24572,24683,24573 ,13092,13091,13097 ,0,0,0}, - {24691,24867,24679 ,13110,13321,13087 ,0,0,0}, {24792,24828,24685 ,13245,13282,13096 ,0,0,0}, - {24683,24868,24828 ,13091,13322,13282 ,0,0,0}, {24829,24679,24869 ,13283,13087,13323 ,0,0,0}, - {24868,24867,24691 ,13322,13321,13110 ,0,0,0}, {24830,24829,24870 ,13284,13283,13324 ,0,0,0}, - {24679,24867,24869 ,13087,13321,13323 ,0,0,0}, {24834,24830,24871 ,13288,13284,13325 ,0,0,0}, - {24829,24869,24870 ,13283,13323,13324 ,0,0,0}, {24833,24834,24872 ,13287,13288,13326 ,0,0,0}, - {24870,24871,24830 ,13324,13325,13284 ,0,0,0}, {24873,24835,24832 ,13327,13289,13286 ,0,0,0}, - {24871,24872,24834 ,13325,13326,13288 ,0,0,0}, {24874,24875,24876 ,13328,13329,13330 ,0,0,0}, - {24872,24831,24833 ,13326,13285,13287 ,0,0,0}, {24835,24877,24836 ,13289,13331,13290 ,0,0,0}, - {24831,24873,24832 ,13285,13327,13286 ,0,0,0}, {24836,24875,24837 ,13290,13329,13291 ,0,0,0}, - {24873,24877,24835 ,13327,13331,13289 ,0,0,0}, {24837,24874,24838 ,13291,13328,13292 ,0,0,0}, - {24877,24875,24836 ,13331,13329,13290 ,0,0,0}, {24838,24878,24839 ,13292,13332,13293 ,0,0,0}, - {24875,24874,24837 ,13329,13328,13291 ,0,0,0}, {24839,24879,24802 ,13293,13333,13255 ,0,0,0}, - {24874,24878,24838 ,13328,13332,13292 ,0,0,0}, {24843,24802,24880 ,13297,13255,13334 ,0,0,0}, - {24878,24879,24839 ,13332,13333,13293 ,0,0,0}, {24842,24843,24881 ,13296,13297,13335 ,0,0,0}, - {24879,24880,24802 ,13333,13334,13255 ,0,0,0}, {24882,24883,24884 ,13336,13337,13338 ,0,0,0}, - {24880,24881,24843 ,13334,13335,13297 ,0,0,0}, {24841,24885,24844 ,13295,13339,13298 ,0,0,0}, - {24881,24840,24842 ,13335,13294,13296 ,0,0,0}, {24844,24886,24845 ,13298,13340,13299 ,0,0,0}, - {24840,24885,24841 ,13294,13339,13295 ,0,0,0}, {24845,24887,24653 ,13299,13341,13042 ,0,0,0}, - {24885,24886,24844 ,13339,13340,13298 ,0,0,0}, {24849,24653,24888 ,13303,13042,13342 ,0,0,0}, - {24886,24887,24845 ,13340,13341,13299 ,0,0,0}, {24848,24849,24889 ,13302,13303,13343 ,0,0,0}, - {24887,24888,24653 ,13341,13342,13042 ,0,0,0}, {24890,24891,24892 ,13344,13345,13346 ,0,0,0}, - {24888,24889,24849 ,13342,13343,13303 ,0,0,0}, {24847,24893,24850 ,13301,13347,13304 ,0,0,0}, - {24889,24846,24848 ,13343,13300,13302 ,0,0,0}, {24850,24894,24851 ,13304,13348,13305 ,0,0,0}, - {24846,24893,24847 ,13300,13347,13301 ,0,0,0}, {24851,24895,24852 ,13305,13349,13306 ,0,0,0}, - {24893,24894,24850 ,13347,13348,13304 ,0,0,0}, {24852,24896,24853 ,13306,13350,13307 ,0,0,0}, - {24894,24895,24851 ,13348,13349,13305 ,0,0,0}, {24810,24853,24897 ,13263,13307,13351 ,0,0,0}, - {24895,24896,24852 ,13349,13350,13306 ,0,0,0}, {24898,24899,24900 ,13352,13353,13354 ,0,0,0}, - {24896,24897,24853 ,13350,13351,13307 ,0,0,0}, {24812,24901,24854 ,13265,13355,13308 ,0,0,0}, - {24897,24811,24810 ,13351,13264,13263 ,0,0,0}, {24854,24899,24855 ,13308,13353,13309 ,0,0,0}, - {24811,24901,24812 ,13264,13355,13265 ,0,0,0}, {24855,24898,24856 ,13309,13352,13310 ,0,0,0}, - {24901,24899,24854 ,13355,13353,13308 ,0,0,0}, {24856,24902,24710 ,13310,13356,13144 ,0,0,0}, - {24899,24898,24855 ,13353,13352,13309 ,0,0,0}, {24860,24710,24903 ,13314,13144,13357 ,0,0,0}, - {24898,24902,24856 ,13352,13356,13310 ,0,0,0}, {24859,24860,24904 ,13313,13314,13358 ,0,0,0}, - {24902,24903,24710 ,13356,13357,13144 ,0,0,0}, {24905,24861,24858 ,13359,13315,13312 ,0,0,0}, - {24903,24904,24860 ,13357,13358,13314 ,0,0,0}, {24906,24907,24908 ,13360,13361,13362 ,0,0,0}, - {24904,24857,24859 ,13358,13311,13313 ,0,0,0}, {24861,24909,24862 ,13315,13363,13316 ,0,0,0}, - {24857,24905,24858 ,13311,13359,13312 ,0,0,0}, {24862,24907,24863 ,13316,13361,13317 ,0,0,0}, - {24905,24909,24861 ,13359,13363,13315 ,0,0,0}, {24863,24906,24864 ,13317,13360,13318 ,0,0,0}, - {24909,24907,24862 ,13363,13361,13316 ,0,0,0}, {24864,24910,24745 ,13318,13364,13191 ,0,0,0}, - {24907,24906,24863 ,13361,13360,13317 ,0,0,0}, {24745,24911,24743 ,13191,13365,13189 ,0,0,0}, - {24906,24910,24864 ,13360,13364,13318 ,0,0,0}, {24743,24912,24738 ,13189,13366,13184 ,0,0,0}, - {24910,24911,24745 ,13364,13365,13191 ,0,0,0}, {24738,24865,24826 ,13184,13319,13279 ,0,0,0}, - {24912,24743,24911 ,13366,13189,13365 ,0,0,0}, {24913,24914,24726 ,13367,13368,13171 ,0,0,0}, - {24738,24912,24865 ,13184,13366,13319 ,0,0,0}, {24915,24726,24914 ,13369,13171,13368 ,0,0,0}, - {24916,24866,24726 ,13370,13320,13171 ,0,0,0}, {24825,24826,24725 ,13278,13279,13170 ,0,0,0}, - {24725,24913,24726 ,13170,13367,13171 ,0,0,0}, {24915,24916,24726 ,13369,13370,13171 ,0,0,0}, - {24683,24828,24686 ,13091,13282,13098 ,0,0,0}, {24346,24682,24618 ,13093,13090,13244 ,0,0,0}, - {24867,24917,24869 ,13321,13371,13323 ,0,0,0}, {24828,24868,24691 ,13282,13322,13110 ,0,0,0}, - {24682,24918,24868 ,13090,13372,13322 ,0,0,0}, {24870,24869,24919 ,13324,13323,13373 ,0,0,0}, - {24867,24918,24917 ,13321,13372,13371 ,0,0,0}, {24871,24870,24920 ,13325,13324,13374 ,0,0,0}, - {24869,24917,24919 ,13323,13371,13373 ,0,0,0}, {24872,24871,24921 ,13326,13325,13375 ,0,0,0}, - {24870,24919,24920 ,13324,13373,13374 ,0,0,0}, {24831,24872,24922 ,13285,13326,13376 ,0,0,0}, - {24871,24920,24921 ,13325,13374,13375 ,0,0,0}, {24873,24831,24923 ,13327,13285,13377 ,0,0,0}, - {24872,24921,24922 ,13326,13375,13376 ,0,0,0}, {24877,24873,24924 ,13331,13327,13378 ,0,0,0}, - {24831,24922,24923 ,13285,13376,13377 ,0,0,0}, {24875,24877,24925 ,13329,13331,13379 ,0,0,0}, - {24923,24924,24873 ,13377,13378,13327 ,0,0,0}, {24926,24927,24928 ,13380,13381,13382 ,0,0,0}, - {24924,24925,24877 ,13378,13379,13331 ,0,0,0}, {24874,24929,24878 ,13328,13383,13332 ,0,0,0}, - {24925,24876,24875 ,13379,13330,13329 ,0,0,0}, {24878,24928,24879 ,13332,13382,13333 ,0,0,0}, - {24876,24929,24874 ,13330,13383,13328 ,0,0,0}, {24879,24930,24880 ,13333,13384,13334 ,0,0,0}, - {24929,24928,24878 ,13383,13382,13332 ,0,0,0}, {24881,24880,24931 ,13335,13334,13385 ,0,0,0}, - {24928,24930,24879 ,13382,13384,13333 ,0,0,0}, {24840,24881,24932 ,13294,13335,13386 ,0,0,0}, - {24880,24930,24931 ,13334,13384,13385 ,0,0,0}, {24885,24840,24933 ,13339,13294,13387 ,0,0,0}, - {24881,24931,24932 ,13335,13385,13386 ,0,0,0}, {24886,24885,24934 ,13340,13339,13388 ,0,0,0}, - {24932,24933,24840 ,13386,13387,13294 ,0,0,0}, {24886,24935,24887 ,13340,13389,13341 ,0,0,0}, - {24933,24934,24885 ,13387,13388,13339 ,0,0,0}, {24887,24883,24888 ,13341,13337,13342 ,0,0,0}, - {24934,24935,24886 ,13388,13389,13340 ,0,0,0}, {24889,24888,24936 ,13343,13342,13390 ,0,0,0}, - {24935,24883,24887 ,13389,13337,13341 ,0,0,0}, {24846,24889,24937 ,13300,13343,13391 ,0,0,0}, - {24888,24883,24936 ,13342,13337,13390 ,0,0,0}, {24893,24846,24938 ,13347,13300,13392 ,0,0,0}, - {24889,24936,24937 ,13343,13390,13391 ,0,0,0}, {24894,24893,24939 ,13348,13347,13393 ,0,0,0}, - {24937,24938,24846 ,13391,13392,13300 ,0,0,0}, {24894,24940,24895 ,13348,13394,13349 ,0,0,0}, - {24938,24939,24893 ,13392,13393,13347 ,0,0,0}, {24895,24891,24896 ,13349,13345,13350 ,0,0,0}, - {24939,24940,24894 ,13393,13394,13348 ,0,0,0}, {24897,24896,24941 ,13351,13350,13395 ,0,0,0}, - {24940,24891,24895 ,13394,13345,13349 ,0,0,0}, {24811,24897,24942 ,13264,13351,13396 ,0,0,0}, - {24896,24891,24941 ,13350,13345,13395 ,0,0,0}, {24901,24811,24943 ,13355,13264,13397 ,0,0,0}, - {24897,24941,24942 ,13351,13395,13396 ,0,0,0}, {24899,24901,24944 ,13353,13355,13398 ,0,0,0}, - {24942,24943,24811 ,13396,13397,13264 ,0,0,0}, {24945,24946,24947 ,13399,13400,13401 ,0,0,0}, - {24943,24944,24901 ,13397,13398,13355 ,0,0,0}, {24898,24948,24902 ,13352,13402,13356 ,0,0,0}, - {24944,24900,24899 ,13398,13354,13353 ,0,0,0}, {24902,24947,24903 ,13356,13401,13357 ,0,0,0}, - {24900,24948,24898 ,13354,13402,13352 ,0,0,0}, {24904,24903,24949 ,13358,13357,13403 ,0,0,0}, - {24948,24947,24902 ,13402,13401,13356 ,0,0,0}, {24857,24904,24950 ,13311,13358,13404 ,0,0,0}, - {24903,24947,24949 ,13357,13401,13403 ,0,0,0}, {24905,24857,24951 ,13359,13311,13405 ,0,0,0}, - {24904,24949,24950 ,13358,13403,13404 ,0,0,0}, {24909,24905,24952 ,13363,13359,13406 ,0,0,0}, - {24857,24950,24951 ,13311,13404,13405 ,0,0,0}, {24907,24909,24953 ,13361,13363,13407 ,0,0,0}, - {24951,24952,24905 ,13405,13406,13359 ,0,0,0}, {24954,24910,24906 ,13408,13364,13360 ,0,0,0}, - {24952,24953,24909 ,13406,13407,13363 ,0,0,0}, {24955,24956,24957 ,13409,13410,13411 ,0,0,0}, - {24953,24908,24907 ,13407,13362,13361 ,0,0,0}, {24910,24958,24911 ,13364,13412,13365 ,0,0,0}, - {24908,24954,24906 ,13362,13408,13360 ,0,0,0}, {24911,24957,24912 ,13365,13411,13366 ,0,0,0}, - {24954,24958,24910 ,13408,13412,13364 ,0,0,0}, {24912,24959,24865 ,13366,13413,13319 ,0,0,0}, - {24958,24957,24911 ,13412,13411,13365 ,0,0,0}, {24865,24729,24728 ,13319,13175,13174 ,0,0,0}, - {24957,24959,24912 ,13411,13413,13366 ,0,0,0}, {24728,24727,24913 ,13174,13173,13367 ,0,0,0}, - {24729,24865,24959 ,13175,13319,13413 ,0,0,0}, {24914,24960,24737 ,13368,13414,13183 ,0,0,0}, - {24961,24962,24914 ,13415,13416,13368 ,0,0,0}, {24725,24728,24913 ,13170,13174,13367 ,0,0,0}, - {24913,24960,24914 ,13367,13414,13368 ,0,0,0}, {24915,24914,24962 ,13369,13368,13416 ,0,0,0}, - {24683,24682,24868 ,13091,13090,13322 ,0,0,0}, {24350,24684,24346 ,13417,13094,13093 ,0,0,0}, - {24919,24917,24677 ,13373,13371,13085 ,0,0,0}, {24868,24918,24867 ,13322,13372,13321 ,0,0,0}, - {24684,24963,24918 ,13094,13418,13372 ,0,0,0}, {24920,24919,24964 ,13374,13373,13419 ,0,0,0}, - {24917,24963,24677 ,13371,13418,13085 ,0,0,0}, {24965,24964,24966 ,13420,13419,13421 ,0,0,0}, - {24919,24677,24964 ,13373,13085,13419 ,0,0,0}, {24965,24967,24921 ,13420,13422,13375 ,0,0,0}, - {24921,24920,24965 ,13375,13374,13420 ,0,0,0}, {24967,24968,24922 ,13422,13423,13376 ,0,0,0}, - {24922,24921,24967 ,13376,13375,13422 ,0,0,0}, {24968,24969,24923 ,13423,13424,13377 ,0,0,0}, - {24923,24922,24968 ,13377,13376,13423 ,0,0,0}, {24969,24970,24924 ,13424,13425,13378 ,0,0,0}, - {24924,24923,24969 ,13378,13377,13424 ,0,0,0}, {24970,24971,24925 ,13425,13426,13379 ,0,0,0}, - {24925,24924,24970 ,13379,13378,13425 ,0,0,0}, {24971,24972,24876 ,13426,13427,13330 ,0,0,0}, - {24876,24925,24971 ,13330,13379,13426 ,0,0,0}, {24972,24926,24929 ,13427,13380,13383 ,0,0,0}, - {24876,24972,24929 ,13330,13427,13383 ,0,0,0}, {23393,24973,24974 ,13428,13429,13430 ,0,0,0}, - {24929,24926,24928 ,13383,13380,13382 ,0,0,0}, {24930,24975,24931 ,13384,13431,13385 ,0,0,0}, - {24928,24927,24930 ,13382,13381,13384 ,0,0,0}, {24976,24975,24974 ,13432,13431,13430 ,0,0,0}, - {24927,24975,24930 ,13381,13431,13384 ,0,0,0}, {24976,24977,24932 ,13432,13433,13386 ,0,0,0}, - {24932,24931,24976 ,13386,13385,13432 ,0,0,0}, {24977,24978,24933 ,13433,13434,13387 ,0,0,0}, - {24933,24932,24977 ,13387,13386,13433 ,0,0,0}, {24978,24979,24934 ,13434,13435,13388 ,0,0,0}, - {24934,24933,24978 ,13388,13387,13434 ,0,0,0}, {24979,24884,24935 ,13435,13338,13389 ,0,0,0}, - {24934,24979,24935 ,13388,13435,13389 ,0,0,0}, {24980,24981,24982 ,13436,13437,13438 ,0,0,0}, - {24935,24884,24883 ,13389,13338,13337 ,0,0,0}, {24882,24981,24936 ,13336,13437,13390 ,0,0,0}, - {24883,24882,24936 ,13337,13336,13390 ,0,0,0}, {24981,24983,24937 ,13437,13439,13391 ,0,0,0}, - {24937,24936,24981 ,13391,13390,13437 ,0,0,0}, {24983,24984,24938 ,13439,13440,13392 ,0,0,0}, - {24938,24937,24983 ,13392,13391,13439 ,0,0,0}, {24984,24985,24939 ,13440,13441,13393 ,0,0,0}, - {24939,24938,24984 ,13393,13392,13440 ,0,0,0}, {24985,24892,24940 ,13441,13346,13394 ,0,0,0}, - {24939,24985,24940 ,13393,13441,13394 ,0,0,0}, {24986,23384,24987 ,13442,13443,13444 ,0,0,0}, - {24940,24892,24891 ,13394,13346,13345 ,0,0,0}, {24942,24941,24988 ,13396,13395,13445 ,0,0,0}, - {24891,24890,24941 ,13345,13344,13395 ,0,0,0}, {24989,24988,24986 ,13446,13445,13442 ,0,0,0}, - {24941,24890,24988 ,13395,13344,13445 ,0,0,0}, {24989,24990,24943 ,13446,13447,13397 ,0,0,0}, - {24943,24942,24989 ,13397,13396,13446 ,0,0,0}, {24990,24991,24944 ,13447,13448,13398 ,0,0,0}, - {24944,24943,24990 ,13398,13397,13447 ,0,0,0}, {24991,24992,24900 ,13448,13449,13354 ,0,0,0}, - {24900,24944,24991 ,13354,13398,13448 ,0,0,0}, {24992,24945,24948 ,13449,13399,13402 ,0,0,0}, - {24900,24992,24948 ,13354,13449,13402 ,0,0,0}, {24993,24994,24995 ,13450,13451,13452 ,0,0,0}, - {24948,24945,24947 ,13402,13399,13401 ,0,0,0}, {24946,24994,24949 ,13400,13451,13403 ,0,0,0}, - {24947,24946,24949 ,13401,13400,13403 ,0,0,0}, {24994,24996,24950 ,13451,13453,13404 ,0,0,0}, - {24950,24949,24994 ,13404,13403,13451 ,0,0,0}, {24996,24997,24951 ,13453,13454,13405 ,0,0,0}, - {24951,24950,24996 ,13405,13404,13453 ,0,0,0}, {24997,24998,24952 ,13454,13455,13406 ,0,0,0}, - {24952,24951,24997 ,13406,13405,13454 ,0,0,0}, {24998,24999,24953 ,13455,13456,13407 ,0,0,0}, - {24953,24952,24998 ,13407,13406,13455 ,0,0,0}, {24999,25000,24908 ,13456,13457,13362 ,0,0,0}, - {24908,24953,24999 ,13362,13407,13456 ,0,0,0}, {25000,25001,24954 ,13457,13458,13408 ,0,0,0}, - {24954,24908,25000 ,13408,13362,13457 ,0,0,0}, {25001,24955,24958 ,13458,13409,13412 ,0,0,0}, - {24954,25001,24958 ,13408,13458,13412 ,0,0,0}, {24959,24956,25002 ,13413,13410,13459 ,0,0,0}, - {24958,24955,24957 ,13412,13409,13411 ,0,0,0}, {24734,24727,24729 ,13180,13173,13175 ,0,0,0}, - {24957,24956,24959 ,13411,13410,13413 ,0,0,0}, {24733,24960,24727 ,13179,13414,13173 ,0,0,0}, - {24959,25002,24729 ,13413,13459,13175 ,0,0,0}, {24741,24735,25003 ,13187,13181,13460 ,0,0,0}, - {25002,24734,24729 ,13459,13180,13175 ,0,0,0}, {24733,25004,25005 ,13179,13461,13462 ,0,0,0}, - {24737,24961,24914 ,13183,13415,13368 ,0,0,0}, {24913,24727,24960 ,13367,13173,13414 ,0,0,0}, - {24737,24960,25005 ,13183,13414,13462 ,0,0,0}, {24736,24961,24737 ,13182,13415,13183 ,0,0,0}, - {24682,24684,24918 ,13090,13094,13372 ,0,0,0}, {24350,24352,24673 ,13417,13078,13081 ,0,0,0}, - {24963,24673,24678 ,13418,13081,13086 ,0,0,0}, {24918,24963,24917 ,13372,13418,13371 ,0,0,0}, - {24677,24963,24678 ,13085,13418,13086 ,0,0,0}, {24676,24966,24964 ,13084,13421,13419 ,0,0,0}, - {24964,24677,24676 ,13419,13085,13084 ,0,0,0}, {24966,25006,24965 ,13421,13463,13420 ,0,0,0}, - {25007,24967,25006 ,13464,13422,13463 ,0,0,0}, {24920,24964,24965 ,13374,13419,13420 ,0,0,0}, - {24967,24965,25006 ,13422,13420,13463 ,0,0,0}, {25008,24968,25007 ,13465,13423,13464 ,0,0,0}, - {24968,24967,25007 ,13423,13422,13464 ,0,0,0}, {25009,24969,25008 ,13466,13424,13465 ,0,0,0}, - {24969,24968,25008 ,13424,13423,13465 ,0,0,0}, {25010,24970,25009 ,13467,13425,13466 ,0,0,0}, - {24970,24969,25009 ,13425,13424,13466 ,0,0,0}, {25011,24971,25010 ,13468,13426,13467 ,0,0,0}, - {24971,24970,25010 ,13426,13425,13467 ,0,0,0}, {25012,24972,25011 ,13469,13427,13468 ,0,0,0}, - {24972,24971,25011 ,13427,13426,13468 ,0,0,0}, {25013,24926,25012 ,13470,13380,13469 ,0,0,0}, - {24926,24972,25012 ,13380,13427,13469 ,0,0,0}, {25014,24927,25013 ,13471,13381,13470 ,0,0,0}, - {24927,24926,25013 ,13381,13380,13470 ,0,0,0}, {24974,24975,25014 ,13430,13431,13471 ,0,0,0}, - {24927,25014,24975 ,13381,13471,13431 ,0,0,0}, {24974,24973,24976 ,13430,13429,13432 ,0,0,0}, - {25015,24977,24973 ,13472,13433,13429 ,0,0,0}, {24931,24975,24976 ,13385,13431,13432 ,0,0,0}, - {24977,24976,24973 ,13433,13432,13429 ,0,0,0}, {25016,24978,25015 ,13473,13434,13472 ,0,0,0}, - {24978,24977,25015 ,13434,13433,13472 ,0,0,0}, {25017,24979,25016 ,13474,13435,13473 ,0,0,0}, - {24979,24978,25016 ,13435,13434,13473 ,0,0,0}, {25018,24884,25017 ,13475,13338,13474 ,0,0,0}, - {24884,24979,25017 ,13338,13435,13474 ,0,0,0}, {24982,24882,25018 ,13438,13336,13475 ,0,0,0}, - {24882,24884,25018 ,13336,13338,13475 ,0,0,0}, {24982,23301,24980 ,13438,13476,13436 ,0,0,0}, - {24882,24982,24981 ,13336,13438,13437 ,0,0,0}, {25019,24983,24980 ,13477,13439,13436 ,0,0,0}, - {24983,24981,24980 ,13439,13437,13436 ,0,0,0}, {25020,24984,25019 ,13478,13440,13477 ,0,0,0}, - {24984,24983,25019 ,13440,13439,13477 ,0,0,0}, {25021,24985,25020 ,13479,13441,13478 ,0,0,0}, - {24985,24984,25020 ,13441,13440,13478 ,0,0,0}, {25022,24892,25021 ,13480,13346,13479 ,0,0,0}, - {24892,24985,25021 ,13346,13441,13479 ,0,0,0}, {25023,24890,25022 ,13481,13344,13480 ,0,0,0}, - {24890,24892,25022 ,13344,13346,13480 ,0,0,0}, {24986,24988,25023 ,13442,13445,13481 ,0,0,0}, - {24890,25023,24988 ,13344,13481,13445 ,0,0,0}, {24986,24987,24989 ,13442,13444,13446 ,0,0,0}, - {25024,24990,24987 ,13482,13447,13444 ,0,0,0}, {24942,24988,24989 ,13396,13445,13446 ,0,0,0}, - {24990,24989,24987 ,13447,13446,13444 ,0,0,0}, {25025,24991,25024 ,13483,13448,13482 ,0,0,0}, - {24991,24990,25024 ,13448,13447,13482 ,0,0,0}, {25026,24992,25025 ,13484,13449,13483 ,0,0,0}, - {24992,24991,25025 ,13449,13448,13483 ,0,0,0}, {25027,24945,25026 ,13485,13399,13484 ,0,0,0}, - {24945,24992,25026 ,13399,13449,13484 ,0,0,0}, {24995,24946,25027 ,13452,13400,13485 ,0,0,0}, - {24946,24945,25027 ,13400,13399,13485 ,0,0,0}, {24995,23323,24993 ,13452,13486,13450 ,0,0,0}, - {24946,24995,24994 ,13400,13452,13451 ,0,0,0}, {25028,24996,24993 ,13487,13453,13450 ,0,0,0}, - {24996,24994,24993 ,13453,13451,13450 ,0,0,0}, {25029,24997,25028 ,13488,13454,13487 ,0,0,0}, - {24997,24996,25028 ,13454,13453,13487 ,0,0,0}, {25030,24998,25029 ,13489,13455,13488 ,0,0,0}, - {24998,24997,25029 ,13455,13454,13488 ,0,0,0}, {25031,24999,25030 ,13490,13456,13489 ,0,0,0}, - {24999,24998,25030 ,13456,13455,13489 ,0,0,0}, {25032,25000,25031 ,13491,13457,13490 ,0,0,0}, - {25000,24999,25031 ,13457,13456,13490 ,0,0,0}, {25033,25001,25032 ,13492,13458,13491 ,0,0,0}, - {25001,25000,25032 ,13458,13457,13491 ,0,0,0}, {25034,24955,25033 ,13493,13409,13492 ,0,0,0}, - {24955,25001,25033 ,13409,13458,13492 ,0,0,0}, {25035,24956,25034 ,13494,13410,13493 ,0,0,0}, - {24956,24955,25034 ,13410,13409,13493 ,0,0,0}, {25036,25002,25035 ,13495,13459,13494 ,0,0,0}, - {25002,24956,25035 ,13459,13410,13494 ,0,0,0}, {25037,24734,25036 ,13496,13180,13495 ,0,0,0}, - {24734,25002,25036 ,13180,13459,13495 ,0,0,0}, {25037,25004,24733 ,13496,13461,13179 ,0,0,0}, - {24733,24734,25037 ,13179,13180,13496 ,0,0,0}, {25004,25003,25005 ,13461,13460,13462 ,0,0,0}, - {24737,25005,24735 ,13183,13462,13181 ,0,0,0}, {24960,24733,25005 ,13414,13179,13462 ,0,0,0}, - {25003,24735,25005 ,13460,13181,13462 ,0,0,0}, {24736,24735,24742 ,13182,13181,13188 ,0,0,0}, - {24963,24684,24673 ,13418,13094,13081 ,0,0,0}, {24673,24684,24350 ,13081,13094,13417 ,0,0,0}, - {23405,23401,24678 ,13281,13497,13086 ,0,0,0}, {24678,23401,24676 ,13086,13497,13084 ,0,0,0}, - {23401,23400,24676 ,13497,13498,13084 ,0,0,0}, {24676,23400,24966 ,13084,13498,13421 ,0,0,0}, - {23400,23399,24966 ,13498,13499,13421 ,0,0,0}, {24966,23399,25006 ,13421,13499,13463 ,0,0,0}, - {23399,23262,25006 ,13499,13500,13463 ,0,0,0}, {25006,23262,25007 ,13463,13500,13464 ,0,0,0}, - {23262,23252,25007 ,13500,13501,13464 ,0,0,0}, {25007,23252,25008 ,13464,13501,13465 ,0,0,0}, - {23252,23285,25008 ,13501,13502,13465 ,0,0,0}, {25008,23285,25009 ,13465,13502,13466 ,0,0,0}, - {23285,23282,25009 ,13502,13503,13466 ,0,0,0}, {25009,23282,25010 ,13466,13503,13467 ,0,0,0}, - {23282,23287,25010 ,13503,13504,13467 ,0,0,0}, {23287,23290,25011 ,13504,13505,13468 ,0,0,0}, - {23287,25011,25010 ,13504,13468,13467 ,0,0,0}, {23290,23257,25012 ,13505,13506,13469 ,0,0,0}, - {23290,25012,25011 ,13505,13469,13468 ,0,0,0}, {23257,23256,25013 ,13506,13507,13470 ,0,0,0}, - {23257,25013,25012 ,13506,13470,13469 ,0,0,0}, {23256,23292,25014 ,13507,13508,13471 ,0,0,0}, - {23256,25014,25013 ,13507,13471,13470 ,0,0,0}, {23292,23394,24974 ,13508,13509,13430 ,0,0,0}, - {23292,24974,25014 ,13508,13430,13471 ,0,0,0}, {23393,24974,23394 ,13428,13430,13509 ,0,0,0}, - {23393,23295,24973 ,13428,13510,13429 ,0,0,0}, {24973,23295,25015 ,13429,13510,13472 ,0,0,0}, - {23295,23300,25015 ,13510,13511,13472 ,0,0,0}, {25015,23300,25016 ,13472,13511,13473 ,0,0,0}, - {23300,23298,25016 ,13511,13512,13473 ,0,0,0}, {23298,23297,25017 ,13512,13513,13474 ,0,0,0}, - {23298,25017,25016 ,13512,13474,13473 ,0,0,0}, {23297,23392,25018 ,13513,13514,13475 ,0,0,0}, - {23297,25018,25017 ,13513,13475,13474 ,0,0,0}, {23392,23301,24982 ,13514,13476,13438 ,0,0,0}, - {23392,24982,25018 ,13514,13438,13475 ,0,0,0}, {23301,23391,24980 ,13476,13515,13436 ,0,0,0}, - {23391,23387,24980 ,13515,13516,13436 ,0,0,0}, {24980,23387,25019 ,13436,13516,13477 ,0,0,0}, - {23387,23305,25019 ,13516,13517,13477 ,0,0,0}, {25019,23305,25020 ,13477,13517,13478 ,0,0,0}, - {23305,23307,25020 ,13517,13518,13478 ,0,0,0}, {23307,23312,25021 ,13518,13519,13479 ,0,0,0}, - {23307,25021,25020 ,13518,13479,13478 ,0,0,0}, {23312,23310,25022 ,13519,13520,13480 ,0,0,0}, - {23312,25022,25021 ,13519,13480,13479 ,0,0,0}, {23310,23309,25023 ,13520,13521,13481 ,0,0,0}, - {23310,25023,25022 ,13520,13481,13480 ,0,0,0}, {23309,23385,24986 ,13521,13522,13442 ,0,0,0}, - {23309,24986,25023 ,13521,13442,13481 ,0,0,0}, {23384,24986,23385 ,13443,13442,13522 ,0,0,0}, - {23384,23314,24987 ,13443,13523,13444 ,0,0,0}, {24987,23314,25024 ,13444,13523,13482 ,0,0,0}, - {23314,23321,25024 ,13523,13524,13482 ,0,0,0}, {23321,23320,25025 ,13524,13525,13483 ,0,0,0}, - {23321,25025,25024 ,13524,13483,13482 ,0,0,0}, {23320,23319,25026 ,13525,13526,13484 ,0,0,0}, - {23320,25026,25025 ,13525,13484,13483 ,0,0,0}, {23319,23381,25027 ,13526,13527,13485 ,0,0,0}, - {23319,25027,25026 ,13526,13485,13484 ,0,0,0}, {23381,23323,24995 ,13527,13486,13452 ,0,0,0}, - {23381,24995,25027 ,13527,13452,13485 ,0,0,0}, {23323,23322,24993 ,13486,13528,13450 ,0,0,0}, - {23322,23328,24993 ,13528,13529,13450 ,0,0,0}, {24993,23328,25028 ,13450,13529,13487 ,0,0,0}, - {23328,23327,25028 ,13529,13530,13487 ,0,0,0}, {25028,23327,25029 ,13487,13530,13488 ,0,0,0}, - {23327,23332,25029 ,13530,13531,13488 ,0,0,0}, {25029,23332,25030 ,13488,13531,13489 ,0,0,0}, - {23332,23330,25030 ,13531,13532,13489 ,0,0,0}, {23330,23338,25031 ,13532,13533,13490 ,0,0,0}, - {23330,25031,25030 ,13532,13490,13489 ,0,0,0}, {23338,23334,25032 ,13533,13534,13491 ,0,0,0}, - {23338,25032,25031 ,13533,13491,13490 ,0,0,0}, {23334,23336,25033 ,13534,13535,13492 ,0,0,0}, - {23334,25033,25032 ,13534,13492,13491 ,0,0,0}, {23336,23339,25034 ,13535,13536,13493 ,0,0,0}, - {23336,25034,25033 ,13535,13493,13492 ,0,0,0}, {23339,23341,25035 ,13536,13537,13494 ,0,0,0}, - {23339,25035,25034 ,13536,13494,13493 ,0,0,0}, {23341,23346,25036 ,13537,13538,13495 ,0,0,0}, - {23341,25036,25035 ,13537,13495,13494 ,0,0,0}, {23346,23352,25037 ,13538,13539,13496 ,0,0,0}, - {23346,25037,25036 ,13538,13496,13495 ,0,0,0}, {23352,23353,25004 ,13539,13540,13461 ,0,0,0}, - {23352,25004,25037 ,13539,13461,13496 ,0,0,0}, {23353,23351,25003 ,13540,13541,13460 ,0,0,0}, - {23353,25003,25004 ,13540,13460,13461 ,0,0,0}, {23351,23345,24741 ,13541,13542,13187 ,0,0,0}, - {23351,24741,25003 ,13541,13187,13460 ,0,0,0}, {24741,23345,23344 ,13187,13542,11616 ,0,0,0}, - {24574,24280,24301 ,13543,13543,13543 ,0,0,0}, {23910,24297,23906 ,13543,13543,13543 ,0,0,0}, - {24296,24301,24362 ,13543,13543,13543 ,0,0,0}, {24574,24301,24281 ,13543,13543,13543 ,0,0,0}, - {24296,24362,24439 ,13543,13543,13543 ,0,0,0}, {24281,24296,23911 ,13543,13543,13543 ,0,0,0}, - {24301,24296,24281 ,13543,13543,13543 ,0,0,0}, {23771,23906,24297 ,13543,13543,13543 ,0,0,0}, - {23910,24294,24291 ,13543,13543,13543 ,0,0,0}, {23777,23786,24121 ,13543,13543,13543 ,0,0,0}, - {23912,23771,24297 ,13543,13543,13543 ,0,0,0}, {23913,23912,23777 ,13543,13543,13543 ,0,0,0}, - {23912,23913,23902 ,13543,13543,13543 ,0,0,0}, {23784,23777,24121 ,13543,13543,13543 ,0,0,0}, - {23785,23786,23912 ,13543,13543,13543 ,0,0,0}, {23786,23777,23912 ,13543,13543,13543 ,0,0,0}, - {24299,23912,24297 ,13543,13543,13543 ,0,0,0}, {24299,23785,23912 ,13543,13543,13543 ,0,0,0}, - {24297,23910,24291 ,13543,13543,13543 ,0,0,0}, {24294,23910,24296 ,13543,13543,13543 ,0,0,0}, - {23911,24296,23909 ,13543,13543,13543 ,0,0,0}, {23910,23909,24296 ,13543,13543,13543 ,0,0,0}, - {24961,24736,24742 ,13544,13544,13544 ,0,0,0}, {24790,24827,23540 ,13544,13544,13544 ,0,0,0}, - {24746,24962,24742 ,13544,13544,13544 ,0,0,0}, {24866,24916,23456 ,13544,13544,13544 ,0,0,0}, - {24915,24962,24916 ,13544,13544,13544 ,0,0,0}, {24962,24746,23344 ,13544,13544,13544 ,0,0,0}, - {24961,24742,24962 ,13544,13544,13544 ,0,0,0}, {23456,24916,24962 ,13544,13544,13544 ,0,0,0}, - {24962,23344,23456 ,13544,13544,13544 ,0,0,0}, {23455,24866,23456 ,13544,13544,13544 ,0,0,0}, - {23455,23498,24866 ,13544,13544,13544 ,0,0,0}, {24827,24866,23540 ,13544,13544,13544 ,0,0,0}, - {23498,23540,24866 ,13544,13544,13544 ,0,0,0}, {24791,24790,23540 ,13544,13544,13544 ,0,0,0}, - {23584,23626,23585 ,13544,13544,13544 ,0,0,0}, {23585,24791,23540 ,13544,13544,13544 ,0,0,0}, - {24791,23585,23626 ,13544,13544,13544 ,0,0,0}, {23377,23625,23372 ,13544,13544,13544 ,0,0,0}, - {24791,23626,23378 ,13544,13544,13544 ,0,0,0}, {23626,23377,23376 ,13544,13544,13544 ,0,0,0}, - {23377,23626,23625 ,13544,13544,13544 ,0,0,0}, {23626,23376,23378 ,13544,13544,13544 ,0,0,0} -// Landegestell.prt - , {25038,25039,25040 ,13545,13546,13547 ,0,0,0}, {25041,25042,25043 ,13548,13549,13550 ,0,0,0}, - {25044,25045,25046 ,13551,13552,13553 ,0,0,0}, {25047,25039,25048 ,13554,13546,13555 ,0,0,0}, - {25049,25046,25050 ,13556,13553,13557 ,0,0,0}, {25051,25052,25053 ,13558,13559,13560 ,0,0,0}, - {25054,25055,25056 ,13561,13562,13563 ,0,0,0}, {25057,25050,25045 ,13564,13557,13552 ,0,0,0}, - {25058,25059,25060 ,13565,13566,13567 ,0,0,0}, {25054,25061,25060 ,13561,13568,13567 ,0,0,0}, - {25062,25063,25064 ,13569,13570,13571 ,0,0,0}, {25064,25063,25059 ,13571,13570,13566 ,0,0,0}, - {25065,25064,25066 ,13572,13571,13573 ,0,0,0}, {25048,25039,25038 ,13555,13546,13545 ,0,0,0}, - {25066,25067,25065 ,13573,13574,13572 ,0,0,0}, {25068,25069,25070 ,13575,13576,13577 ,0,0,0}, - {25040,25071,25038 ,13547,13578,13545 ,0,0,0}, {25072,25073,25070 ,13579,13580,13577 ,0,0,0}, - {25074,25075,25072 ,13581,13582,13579 ,0,0,0}, {25075,25076,25072 ,13582,13583,13579 ,0,0,0}, - {25070,25073,25068 ,13577,13580,13575 ,0,0,0}, {25077,25078,25042 ,13584,13585,13549 ,0,0,0}, - {25079,25080,25081 ,13586,13587,13588 ,0,0,0}, {25077,25082,25078 ,13584,13589,13585 ,0,0,0}, - {25083,25084,25085 ,13590,13591,13592 ,0,0,0}, {25080,25086,25081 ,13587,13593,13588 ,0,0,0}, - {25087,25088,25089 ,13594,13595,13596 ,0,0,0}, {25083,25085,25090 ,13590,13592,13597 ,0,0,0}, - {25091,25092,25093 ,13598,13599,13600 ,0,0,0}, {25092,25091,25094 ,13599,13598,13601 ,0,0,0}, - {25095,25096,25097 ,13602,13603,13604 ,0,0,0}, {25098,25099,25096 ,13605,13606,13603 ,0,0,0}, - {25100,25101,25102 ,13607,13608,13609 ,0,0,0}, {25095,25097,25103 ,13602,13604,13610 ,0,0,0}, - {25104,25105,25106 ,13611,13612,13613 ,0,0,0}, {25100,25102,25107 ,13607,13609,13614 ,0,0,0}, - {25108,25109,25110 ,13615,13616,13617 ,0,0,0}, {25111,25105,25104 ,13618,13612,13611 ,0,0,0}, - {25112,25113,25114 ,13619,13620,13621 ,0,0,0}, {25114,25110,25112 ,13621,13617,13619 ,0,0,0}, - {25115,25116,25117 ,13622,13623,13624 ,0,0,0}, {25118,25113,25119 ,13625,13620,13626 ,0,0,0}, - {25120,25121,25122 ,13627,13628,13629 ,0,0,0}, {25123,25120,25124 ,13630,13627,13631 ,0,0,0}, - {25125,25126,25127 ,13632,13633,13634 ,0,0,0}, {25128,25125,25122 ,13635,13632,13629 ,0,0,0}, - {25129,25130,25131 ,13636,13637,13638 ,0,0,0}, {25132,25127,25133 ,13639,13634,13640 ,0,0,0}, - {25134,25135,25136 ,13641,13642,13643 ,0,0,0}, {25131,25137,25129 ,13638,13644,13636 ,0,0,0}, - {25138,25134,25139 ,13645,13641,13646 ,0,0,0}, {25129,25137,25140 ,13636,13644,13647 ,0,0,0}, - {25141,25138,25132 ,13648,13645,13639 ,0,0,0}, {25134,25138,25141 ,13641,13645,13648 ,0,0,0}, - {25142,25143,25144 ,13649,13650,13651 ,0,0,0}, {25145,25128,25146 ,13652,13635,13653 ,0,0,0}, - {25147,25148,25149 ,13654,13655,13656 ,0,0,0}, {25145,25146,25150 ,13652,13653,13657 ,0,0,0}, - {25151,25152,25153 ,13658,13659,13660 ,0,0,0}, {25149,25154,25155 ,13656,13661,13662 ,0,0,0}, - {25156,25157,25153 ,13663,13664,13660 ,0,0,0}, {25158,25159,25160 ,13665,13666,13667 ,0,0,0}, - {25161,25162,25163 ,13668,13669,13670 ,0,0,0}, {25163,25160,25161 ,13670,13667,13668 ,0,0,0}, - {25162,25161,25164 ,13669,13668,13671 ,0,0,0}, {25133,25127,25126 ,13640,13634,13633 ,0,0,0}, - {25134,25140,25139 ,13641,13647,13646 ,0,0,0}, {25128,25122,25121 ,13635,13629,13628 ,0,0,0}, - {25128,25126,25125 ,13635,13633,13632 ,0,0,0}, {25123,25124,25115 ,13630,13631,13622 ,0,0,0}, - {25120,25123,25121 ,13627,13630,13628 ,0,0,0}, {25117,25116,25118 ,13624,13623,13625 ,0,0,0}, - {25124,25116,25115 ,13631,13623,13622 ,0,0,0}, {25117,25118,25119 ,13624,13625,13626 ,0,0,0}, - {25165,25123,25115 ,13672,13630,13622 ,0,0,0}, {25114,25108,25110 ,13621,13615,13617 ,0,0,0}, - {25113,25112,25119 ,13620,13619,13626 ,0,0,0}, {25104,25106,25166 ,13611,13613,13673 ,0,0,0}, - {25167,25111,25168 ,13674,13618,13675 ,0,0,0}, {25110,25109,25168 ,13617,13616,13675 ,0,0,0}, - {25105,25111,25167 ,13612,13618,13674 ,0,0,0}, {25109,25167,25168 ,13616,13674,13675 ,0,0,0}, - {25166,25106,25107 ,13673,13613,13614 ,0,0,0}, {25169,25104,25166 ,13676,13611,13673 ,0,0,0}, - {25107,25102,25166 ,13614,13609,13673 ,0,0,0}, {25103,25101,25170 ,13610,13608,13677 ,0,0,0}, - {25100,25170,25101 ,13607,13677,13608 ,0,0,0}, {25171,25103,25170 ,13678,13610,13677 ,0,0,0}, - {25099,25097,25096 ,13606,13604,13603 ,0,0,0}, {25095,25103,25171 ,13602,13610,13678 ,0,0,0}, - {25098,25172,25099 ,13605,13679,13606 ,0,0,0}, {25093,25092,25172 ,13600,13599,13679 ,0,0,0}, - {25172,25098,25093 ,13679,13605,13600 ,0,0,0}, {25094,25173,25089 ,13601,13680,13596 ,0,0,0}, - {25174,25175,25176 ,13681,13682,13683 ,0,0,0}, {25089,25173,25177 ,13596,13680,13684 ,0,0,0}, - {25173,25094,25091 ,13680,13601,13598 ,0,0,0}, {25178,25090,25088 ,13685,13597,13595 ,0,0,0}, - {25087,25089,25177 ,13594,13596,13684 ,0,0,0}, {25090,25178,25083 ,13597,13685,13590 ,0,0,0}, - {25178,25088,25087 ,13685,13595,13594 ,0,0,0}, {25082,25179,25180 ,13589,13686,13687 ,0,0,0}, - {25084,25086,25181 ,13591,13593,13688 ,0,0,0}, {25085,25084,25181 ,13592,13591,13688 ,0,0,0}, - {25181,25086,25080 ,13688,13593,13587 ,0,0,0}, {25182,25183,25184 ,13689,13690,13691 ,0,0,0}, - {25179,25079,25081 ,13686,13586,13588 ,0,0,0}, {25071,25040,25069 ,13578,13547,13576 ,0,0,0}, - {25082,25079,25179 ,13589,13586,13686 ,0,0,0}, {25082,25180,25078 ,13589,13687,13585 ,0,0,0}, - {25042,25041,25077 ,13549,13548,13584 ,0,0,0}, {25076,25075,25043 ,13583,13582,13550 ,0,0,0}, - {25043,25075,25041 ,13550,13582,13548 ,0,0,0}, {25068,25071,25069 ,13575,13578,13576 ,0,0,0}, - {25076,25073,25072 ,13583,13580,13579 ,0,0,0}, {25053,25185,25186 ,13560,13692,13693 ,0,0,0}, - {25047,25048,25185 ,13554,13555,13692 ,0,0,0}, {25186,25051,25053 ,13693,13558,13560 ,0,0,0}, - {25047,25185,25053 ,13554,13692,13560 ,0,0,0}, {25186,25187,25051 ,13693,13694,13558 ,0,0,0}, - {25188,25189,25055 ,13695,13696,13562 ,0,0,0}, {25051,25187,25190 ,13558,13694,13697 ,0,0,0}, - {25190,25187,25191 ,13697,13694,13698 ,0,0,0}, {25192,25190,25193 ,13699,13697,13700 ,0,0,0}, - {25191,25193,25190 ,13698,13700,13697 ,0,0,0}, {25056,25194,25054 ,13563,13701,13561 ,0,0,0}, - {25195,25192,25193 ,13702,13699,13700 ,0,0,0}, {25196,25195,25193 ,13703,13702,13700 ,0,0,0}, - {25192,25195,25197 ,13699,13702,13704 ,0,0,0}, {25198,25199,25197 ,13705,13706,13704 ,0,0,0}, - {25189,25188,25200 ,13696,13695,13707 ,0,0,0}, {25197,25199,25192 ,13704,13706,13699 ,0,0,0}, - {25198,25188,25199 ,13705,13695,13706 ,0,0,0}, {25192,25201,25190 ,13699,13708,13697 ,0,0,0}, - {25202,25047,25053 ,13709,13554,13560 ,0,0,0}, {25190,25044,25051 ,13697,13551,13558 ,0,0,0}, - {25203,25039,25047 ,13710,13546,13554 ,0,0,0}, {25052,25051,25044 ,13559,13558,13551 ,0,0,0}, - {25204,25040,25039 ,13711,13547,13546 ,0,0,0}, {25202,25053,25052 ,13709,13560,13559 ,0,0,0}, - {25205,25069,25040 ,13712,13576,13547 ,0,0,0}, {25203,25047,25202 ,13710,13554,13709 ,0,0,0}, - {25206,25070,25069 ,13713,13577,13576 ,0,0,0}, {25204,25039,25203 ,13711,13546,13710 ,0,0,0}, - {25207,25072,25070 ,13714,13579,13577 ,0,0,0}, {25040,25204,25205 ,13547,13711,13712 ,0,0,0}, - {25208,25209,25210 ,13715,13716,13717 ,0,0,0}, {25069,25205,25206 ,13576,13712,13713 ,0,0,0}, - {25210,25041,25075 ,13717,13548,13582 ,0,0,0}, {25070,25206,25207 ,13577,13713,13714 ,0,0,0}, - {25211,25077,25041 ,13718,13584,13548 ,0,0,0}, {25072,25207,25074 ,13579,13714,13581 ,0,0,0}, - {25212,25082,25077 ,13719,13589,13584 ,0,0,0}, {25075,25074,25210 ,13582,13581,13717 ,0,0,0}, - {25213,25079,25082 ,13720,13586,13589 ,0,0,0}, {25041,25210,25211 ,13548,13717,13718 ,0,0,0}, - {25214,25080,25079 ,13721,13587,13586 ,0,0,0}, {25212,25077,25211 ,13719,13584,13718 ,0,0,0}, - {25215,25181,25080 ,13722,13688,13587 ,0,0,0}, {25213,25082,25212 ,13720,13589,13719 ,0,0,0}, - {25216,25085,25181 ,13723,13592,13688 ,0,0,0}, {25079,25213,25214 ,13586,13720,13721 ,0,0,0}, - {25183,25090,25085 ,13690,13597,13592 ,0,0,0}, {25080,25214,25215 ,13587,13721,13722 ,0,0,0}, - {25217,25088,25090 ,13724,13595,13597 ,0,0,0}, {25181,25215,25216 ,13688,13722,13723 ,0,0,0}, - {25218,25089,25088 ,13725,13596,13595 ,0,0,0}, {25085,25216,25183 ,13592,13723,13690 ,0,0,0}, - {25219,25094,25089 ,13726,13601,13596 ,0,0,0}, {25217,25090,25183 ,13724,13597,13690 ,0,0,0}, - {25220,25092,25094 ,13727,13599,13601 ,0,0,0}, {25218,25088,25217 ,13725,13595,13724 ,0,0,0}, - {25221,25172,25092 ,13728,13679,13599 ,0,0,0}, {25089,25218,25219 ,13596,13725,13726 ,0,0,0}, - {25099,25172,25174 ,13606,13679,13681 ,0,0,0}, {25094,25219,25220 ,13601,13726,13727 ,0,0,0}, - {25222,25097,25099 ,13729,13604,13606 ,0,0,0}, {25092,25220,25221 ,13599,13727,13728 ,0,0,0}, - {25223,25103,25097 ,13730,13610,13604 ,0,0,0}, {25172,25221,25174 ,13679,13728,13681 ,0,0,0}, - {25224,25101,25103 ,13731,13608,13610 ,0,0,0}, {25222,25099,25174 ,13729,13606,13681 ,0,0,0}, - {25225,25102,25101 ,13732,13609,13608 ,0,0,0}, {25223,25097,25222 ,13730,13604,13729 ,0,0,0}, - {25226,25166,25102 ,13733,13673,13609 ,0,0,0}, {25103,25223,25224 ,13610,13730,13731 ,0,0,0}, - {25227,25228,25229 ,13734,13735,13736 ,0,0,0}, {25101,25224,25225 ,13608,13731,13732 ,0,0,0}, - {25230,25111,25104 ,13737,13618,13611 ,0,0,0}, {25102,25225,25226 ,13609,13732,13733 ,0,0,0}, - {25231,25168,25111 ,13738,13675,13618 ,0,0,0}, {25166,25226,25169 ,13673,13733,13676 ,0,0,0}, - {25232,25110,25168 ,13739,13617,13675 ,0,0,0}, {25104,25169,25230 ,13611,13676,13737 ,0,0,0}, - {25233,25112,25110 ,13740,13619,13617 ,0,0,0}, {25231,25111,25230 ,13738,13618,13737 ,0,0,0}, - {25234,25119,25112 ,13741,13626,13619 ,0,0,0}, {25232,25168,25231 ,13739,13675,13738 ,0,0,0}, - {25235,25117,25119 ,13742,13624,13626 ,0,0,0}, {25233,25110,25232 ,13740,13617,13739 ,0,0,0}, - {25236,25115,25117 ,13743,13622,13624 ,0,0,0}, {25112,25233,25234 ,13619,13740,13741 ,0,0,0}, - {25123,25237,25121 ,13630,13744,13628 ,0,0,0}, {25119,25234,25235 ,13626,13741,13742 ,0,0,0}, - {25146,25238,25150 ,13653,13745,13657 ,0,0,0}, {25117,25235,25236 ,13624,13742,13743 ,0,0,0}, - {25146,25128,25121 ,13653,13635,13628 ,0,0,0}, {25115,25236,25165 ,13622,13743,13672 ,0,0,0}, - {25145,25126,25128 ,13652,13633,13635 ,0,0,0}, {25123,25165,25237 ,13630,13672,13744 ,0,0,0}, - {25133,25126,25239 ,13640,13633,13746 ,0,0,0}, {25237,25146,25121 ,13744,13653,13628 ,0,0,0}, - {25148,25135,25141 ,13655,13642,13648 ,0,0,0}, {25135,25148,25147 ,13642,13655,13654 ,0,0,0}, - {25133,25141,25132 ,13640,13648,13639 ,0,0,0}, {25126,25145,25239 ,13633,13652,13746 ,0,0,0}, - {25129,25140,25240 ,13636,13647,13747 ,0,0,0}, {25133,25148,25141 ,13640,13655,13648 ,0,0,0}, - {25134,25141,25135 ,13641,13648,13642 ,0,0,0}, {25241,25242,25129 ,13748,13749,13636 ,0,0,0}, - {25139,25140,25137 ,13646,13647,13644 ,0,0,0}, {25136,25240,25140 ,13643,13747,13647 ,0,0,0}, - {25130,25129,25242 ,13637,13636,13749 ,0,0,0}, {25199,25201,25192 ,13706,13708,13699 ,0,0,0}, - {25200,25188,25198 ,13707,13695,13705 ,0,0,0}, {25061,25243,25060 ,13568,13750,13567 ,0,0,0}, - {25201,25044,25190 ,13708,13551,13697 ,0,0,0}, {25199,25244,25201 ,13706,13751,13708 ,0,0,0}, - {25052,25046,25245 ,13559,13553,13752 ,0,0,0}, {25045,25044,25201 ,13552,13551,13708 ,0,0,0}, - {25202,25245,25246 ,13709,13752,13753 ,0,0,0}, {25046,25052,25044 ,13553,13559,13551 ,0,0,0}, - {25203,25246,25247 ,13710,13753,13754 ,0,0,0}, {25245,25202,25052 ,13752,13709,13559 ,0,0,0}, - {25204,25247,25248 ,13711,13754,13755 ,0,0,0}, {25246,25203,25202 ,13753,13710,13709 ,0,0,0}, - {25205,25248,25249 ,13712,13755,13756 ,0,0,0}, {25247,25204,25203 ,13754,13711,13710 ,0,0,0}, - {25206,25249,25250 ,13713,13756,13757 ,0,0,0}, {25248,25205,25204 ,13755,13712,13711 ,0,0,0}, - {25207,25250,25251 ,13714,13757,13758 ,0,0,0}, {25249,25206,25205 ,13756,13713,13712 ,0,0,0}, - {25074,25251,25208 ,13581,13758,13715 ,0,0,0}, {25207,25206,25250 ,13714,13713,13757 ,0,0,0}, - {25252,25253,25254 ,13759,13760,13761 ,0,0,0}, {25074,25207,25251 ,13581,13714,13758 ,0,0,0}, - {25211,25209,25252 ,13718,13716,13759 ,0,0,0}, {25210,25074,25208 ,13717,13581,13715 ,0,0,0}, - {25212,25252,25255 ,13719,13759,13762 ,0,0,0}, {25211,25210,25209 ,13718,13717,13716 ,0,0,0}, - {25213,25255,25256 ,13720,13762,13763 ,0,0,0}, {25252,25212,25211 ,13759,13719,13718 ,0,0,0}, - {25214,25256,25257 ,13721,13763,13764 ,0,0,0}, {25255,25213,25212 ,13762,13720,13719 ,0,0,0}, - {25215,25257,25258 ,13722,13764,13765 ,0,0,0}, {25256,25214,25213 ,13763,13721,13720 ,0,0,0}, - {25216,25258,25184 ,13723,13765,13691 ,0,0,0}, {25215,25214,25257 ,13722,13721,13764 ,0,0,0}, - {25259,25260,25261 ,13766,13767,13768 ,0,0,0}, {25216,25215,25258 ,13723,13722,13765 ,0,0,0}, - {25217,25182,25262 ,13724,13689,13769 ,0,0,0}, {25183,25216,25184 ,13690,13723,13691 ,0,0,0}, - {25218,25262,25263 ,13725,13769,13770 ,0,0,0}, {25182,25217,25183 ,13689,13724,13690 ,0,0,0}, - {25219,25263,25264 ,13726,13770,13771 ,0,0,0}, {25262,25218,25217 ,13769,13725,13724 ,0,0,0}, - {25220,25264,25265 ,13727,13771,13772 ,0,0,0}, {25263,25219,25218 ,13770,13726,13725 ,0,0,0}, - {25221,25265,25175 ,13728,13772,13682 ,0,0,0}, {25220,25219,25264 ,13727,13726,13771 ,0,0,0}, - {25266,25267,25268 ,13773,13774,13775 ,0,0,0}, {25221,25220,25265 ,13728,13727,13772 ,0,0,0}, - {25222,25176,25269 ,13729,13683,13776 ,0,0,0}, {25174,25221,25175 ,13681,13728,13682 ,0,0,0}, - {25223,25269,25270 ,13730,13776,13777 ,0,0,0}, {25222,25174,25176 ,13729,13681,13683 ,0,0,0}, - {25224,25270,25271 ,13731,13777,13778 ,0,0,0}, {25269,25223,25222 ,13776,13730,13729 ,0,0,0}, - {25225,25271,25272 ,13732,13778,13779 ,0,0,0}, {25270,25224,25223 ,13777,13731,13730 ,0,0,0}, - {25226,25272,25273 ,13733,13779,13780 ,0,0,0}, {25271,25225,25224 ,13778,13732,13731 ,0,0,0}, - {25169,25273,25274 ,13676,13780,13781 ,0,0,0}, {25226,25225,25272 ,13733,13732,13779 ,0,0,0}, - {25230,25274,25228 ,13737,13781,13735 ,0,0,0}, {25169,25226,25273 ,13676,13733,13780 ,0,0,0}, - {25231,25228,25275 ,13738,13735,13782 ,0,0,0}, {25230,25169,25274 ,13737,13676,13781 ,0,0,0}, - {25232,25275,25276 ,13739,13782,13783 ,0,0,0}, {25228,25231,25230 ,13735,13738,13737 ,0,0,0}, - {25233,25276,25277 ,13740,13783,13784 ,0,0,0}, {25275,25232,25231 ,13782,13739,13738 ,0,0,0}, - {25234,25277,25278 ,13741,13784,13785 ,0,0,0}, {25276,25233,25232 ,13783,13740,13739 ,0,0,0}, - {25235,25278,25279 ,13742,13785,13786 ,0,0,0}, {25277,25234,25233 ,13784,13741,13740 ,0,0,0}, - {25236,25279,25280 ,13743,13786,13787 ,0,0,0}, {25278,25235,25234 ,13785,13742,13741 ,0,0,0}, - {25165,25280,25281 ,13672,13787,13788 ,0,0,0}, {25279,25236,25235 ,13786,13743,13742 ,0,0,0}, - {25237,25281,25238 ,13744,13788,13745 ,0,0,0}, {25165,25236,25280 ,13672,13743,13787 ,0,0,0}, - {25282,25145,25150 ,13789,13652,13657 ,0,0,0}, {25237,25165,25281 ,13744,13672,13788 ,0,0,0}, - {25155,25151,25283 ,13662,13658,13790 ,0,0,0}, {25146,25237,25238 ,13653,13744,13745 ,0,0,0}, - {25282,25149,25239 ,13789,13656,13746 ,0,0,0}, {25142,25135,25147 ,13649,13642,13654 ,0,0,0}, - {25239,25148,25133 ,13746,13655,13640 ,0,0,0}, {25282,25239,25145 ,13789,13746,13652 ,0,0,0}, - {25155,25147,25149 ,13662,13654,13656 ,0,0,0}, {25239,25149,25148 ,13746,13656,13655 ,0,0,0}, - {25284,25240,25144 ,13791,13747,13651 ,0,0,0}, {25240,25241,25129 ,13747,13748,13636 ,0,0,0}, - {25134,25136,25140 ,13641,13643,13647 ,0,0,0}, {25136,25142,25144 ,13643,13649,13651 ,0,0,0}, - {25284,25241,25240 ,13791,13748,13747 ,0,0,0}, {25188,25244,25199 ,13695,13751,13706 ,0,0,0}, - {25056,25055,25189 ,13563,13562,13696 ,0,0,0}, {25059,25063,25285 ,13566,13570,13792 ,0,0,0}, - {25244,25045,25201 ,13751,13552,13708 ,0,0,0}, {25188,25286,25244 ,13695,13793,13751 ,0,0,0}, - {25287,25288,25289 ,13794,13795,13796 ,0,0,0}, {25057,25045,25244 ,13564,13552,13751 ,0,0,0}, - {25049,25287,25245 ,13556,13794,13752 ,0,0,0}, {25050,25046,25045 ,13557,13553,13552 ,0,0,0}, - {25287,25290,25246 ,13794,13797,13753 ,0,0,0}, {25049,25245,25046 ,13556,13752,13553 ,0,0,0}, - {25290,25291,25247 ,13797,13798,13754 ,0,0,0}, {25287,25246,25245 ,13794,13753,13752 ,0,0,0}, - {25291,25292,25248 ,13798,13799,13755 ,0,0,0}, {25290,25247,25246 ,13797,13754,13753 ,0,0,0}, - {25292,25293,25249 ,13799,13800,13756 ,0,0,0}, {25291,25248,25247 ,13798,13755,13754 ,0,0,0}, - {25293,25294,25250 ,13800,13801,13757 ,0,0,0}, {25292,25249,25248 ,13799,13756,13755 ,0,0,0}, - {25294,25295,25251 ,13801,13802,13758 ,0,0,0}, {25293,25250,25249 ,13800,13757,13756 ,0,0,0}, - {25295,25296,25208 ,13802,13803,13715 ,0,0,0}, {25294,25251,25250 ,13801,13758,13757 ,0,0,0}, - {25296,25253,25209 ,13803,13760,13716 ,0,0,0}, {25208,25251,25295 ,13715,13758,13802 ,0,0,0}, - {25297,25298,25299 ,13804,13805,13806 ,0,0,0}, {25209,25208,25296 ,13716,13715,13803 ,0,0,0}, - {25254,25297,25255 ,13761,13804,13762 ,0,0,0}, {25253,25252,25209 ,13760,13759,13716 ,0,0,0}, - {25297,25300,25256 ,13804,13807,13763 ,0,0,0}, {25254,25255,25252 ,13761,13762,13759 ,0,0,0}, - {25300,25301,25257 ,13807,13808,13764 ,0,0,0}, {25297,25256,25255 ,13804,13763,13762 ,0,0,0}, - {25301,25302,25258 ,13808,13809,13765 ,0,0,0}, {25300,25257,25256 ,13807,13764,13763 ,0,0,0}, - {25302,25303,25184 ,13809,13810,13691 ,0,0,0}, {25301,25258,25257 ,13808,13765,13764 ,0,0,0}, - {25182,25303,25304 ,13689,13810,13811 ,0,0,0}, {25184,25258,25302 ,13691,13765,13809 ,0,0,0}, - {25304,25259,25262 ,13811,13766,13769 ,0,0,0}, {25303,25182,25184 ,13810,13689,13691 ,0,0,0}, - {25259,25305,25263 ,13766,13812,13770 ,0,0,0}, {25304,25262,25182 ,13811,13769,13689 ,0,0,0}, - {25305,25306,25264 ,13812,13813,13771 ,0,0,0}, {25259,25263,25262 ,13766,13770,13769 ,0,0,0}, - {25306,25307,25265 ,13813,13814,13772 ,0,0,0}, {25305,25264,25263 ,13812,13771,13770 ,0,0,0}, - {25307,25308,25175 ,13814,13815,13682 ,0,0,0}, {25306,25265,25264 ,13813,13772,13771 ,0,0,0}, - {25308,25309,25176 ,13815,13816,13683 ,0,0,0}, {25175,25265,25307 ,13682,13772,13814 ,0,0,0}, - {25309,25266,25269 ,13816,13773,13776 ,0,0,0}, {25176,25175,25308 ,13683,13682,13815 ,0,0,0}, - {25266,25310,25270 ,13773,13817,13777 ,0,0,0}, {25309,25269,25176 ,13816,13776,13683 ,0,0,0}, - {25310,25311,25271 ,13817,13818,13778 ,0,0,0}, {25266,25270,25269 ,13773,13777,13776 ,0,0,0}, - {25311,25312,25272 ,13818,13819,13779 ,0,0,0}, {25310,25271,25270 ,13817,13778,13777 ,0,0,0}, - {25312,25313,25273 ,13819,13820,13780 ,0,0,0}, {25311,25272,25271 ,13818,13779,13778 ,0,0,0}, - {25313,25229,25274 ,13820,13736,13781 ,0,0,0}, {25273,25272,25312 ,13780,13779,13819 ,0,0,0}, - {25314,25315,25316 ,13821,13822,13823 ,0,0,0}, {25274,25273,25313 ,13781,13780,13820 ,0,0,0}, - {25227,25314,25275 ,13734,13821,13782 ,0,0,0}, {25229,25228,25274 ,13736,13735,13781 ,0,0,0}, - {25314,25317,25276 ,13821,13824,13783 ,0,0,0}, {25227,25275,25228 ,13734,13782,13735 ,0,0,0}, - {25317,25318,25277 ,13824,13825,13784 ,0,0,0}, {25314,25276,25275 ,13821,13783,13782 ,0,0,0}, - {25318,25319,25278 ,13825,13826,13785 ,0,0,0}, {25317,25277,25276 ,13824,13784,13783 ,0,0,0}, - {25319,25320,25279 ,13826,13827,13786 ,0,0,0}, {25318,25278,25277 ,13825,13785,13784 ,0,0,0}, - {25320,25321,25280 ,13827,13828,13787 ,0,0,0}, {25319,25279,25278 ,13826,13786,13785 ,0,0,0}, - {25321,25322,25281 ,13828,13829,13788 ,0,0,0}, {25320,25280,25279 ,13827,13787,13786 ,0,0,0}, - {25322,25323,25238 ,13829,13830,13745 ,0,0,0}, {25321,25281,25280 ,13828,13788,13787 ,0,0,0}, - {25323,25324,25150 ,13830,13831,13657 ,0,0,0}, {25322,25238,25281 ,13829,13745,13788 ,0,0,0}, - {25324,25154,25282 ,13831,13661,13789 ,0,0,0}, {25150,25238,25323 ,13657,13745,13830 ,0,0,0}, - {25325,25147,25155 ,13832,13654,13662 ,0,0,0}, {25150,25324,25282 ,13657,13831,13789 ,0,0,0}, - {25154,25151,25155 ,13661,13658,13662 ,0,0,0}, {25282,25154,25149 ,13789,13661,13656 ,0,0,0}, - {25326,25144,25143 ,13833,13651,13650 ,0,0,0}, {25136,25144,25240 ,13643,13651,13747 ,0,0,0}, - {25135,25142,25136 ,13642,13649,13643 ,0,0,0}, {25325,25143,25142 ,13832,13650,13649 ,0,0,0}, - {25284,25144,25326 ,13791,13651,13833 ,0,0,0}, {25286,25188,25055 ,13793,13695,13562 ,0,0,0}, - {25061,25054,25194 ,13568,13561,13701 ,0,0,0}, {25057,25327,25328 ,13564,13834,13835 ,0,0,0}, - {25286,25057,25244 ,13793,13564,13751 ,0,0,0}, {25329,25286,25055 ,13836,13793,13562 ,0,0,0}, - {25050,25328,25330 ,13557,13835,13837 ,0,0,0}, {25286,25327,25057 ,13793,13834,13564 ,0,0,0}, - {25049,25330,25288 ,13556,13837,13795 ,0,0,0}, {25328,25050,25057 ,13835,13557,13564 ,0,0,0}, - {25331,25290,25289 ,13838,13797,13796 ,0,0,0}, {25330,25049,25050 ,13837,13556,13557 ,0,0,0}, - {25332,25291,25331 ,13839,13798,13838 ,0,0,0}, {25288,25287,25049 ,13795,13794,13556 ,0,0,0}, - {25333,25334,25335 ,13840,13841,13842 ,0,0,0}, {25289,25290,25287 ,13796,13797,13794 ,0,0,0}, - {25332,25333,25292 ,13839,13840,13799 ,0,0,0}, {25331,25291,25290 ,13838,13798,13797 ,0,0,0}, - {25333,25336,25293 ,13840,13843,13800 ,0,0,0}, {25332,25292,25291 ,13839,13799,13798 ,0,0,0}, - {25336,25337,25294 ,13843,13844,13801 ,0,0,0}, {25333,25293,25292 ,13840,13800,13799 ,0,0,0}, - {25337,25338,25295 ,13844,13845,13802 ,0,0,0}, {25336,25294,25293 ,13843,13801,13800 ,0,0,0}, - {25338,25339,25296 ,13845,13846,13803 ,0,0,0}, {25337,25295,25294 ,13844,13802,13801 ,0,0,0}, - {25253,25339,25340 ,13760,13846,13847 ,0,0,0}, {25338,25296,25295 ,13845,13803,13802 ,0,0,0}, - {25254,25340,25298 ,13761,13847,13805 ,0,0,0}, {25339,25253,25296 ,13846,13760,13803 ,0,0,0}, - {25341,25342,25343 ,13848,13849,13850 ,0,0,0}, {25340,25254,25253 ,13847,13761,13760 ,0,0,0}, - {25299,25341,25300 ,13806,13848,13807 ,0,0,0}, {25298,25297,25254 ,13805,13804,13761 ,0,0,0}, - {25341,25344,25301 ,13848,13851,13808 ,0,0,0}, {25299,25300,25297 ,13806,13807,13804 ,0,0,0}, - {25344,25345,25302 ,13851,13852,13809 ,0,0,0}, {25341,25301,25300 ,13848,13808,13807 ,0,0,0}, - {25303,25345,25346 ,13810,13852,13853 ,0,0,0}, {25344,25302,25301 ,13851,13809,13808 ,0,0,0}, - {25304,25346,25260 ,13811,13853,13767 ,0,0,0}, {25303,25302,25345 ,13810,13809,13852 ,0,0,0}, - {25347,25348,25349 ,13854,13855,13856 ,0,0,0}, {25346,25304,25303 ,13853,13811,13810 ,0,0,0}, - {25261,25347,25305 ,13768,13854,13812 ,0,0,0}, {25260,25259,25304 ,13767,13766,13811 ,0,0,0}, - {25347,25350,25306 ,13854,13857,13813 ,0,0,0}, {25261,25305,25259 ,13768,13812,13766 ,0,0,0}, - {25350,25351,25307 ,13857,13858,13814 ,0,0,0}, {25347,25306,25305 ,13854,13813,13812 ,0,0,0}, - {25351,25352,25308 ,13858,13859,13815 ,0,0,0}, {25350,25307,25306 ,13857,13814,13813 ,0,0,0}, - {25309,25352,25267 ,13816,13859,13774 ,0,0,0}, {25308,25307,25351 ,13815,13814,13858 ,0,0,0}, - {25353,25354,25355 ,13860,13861,13862 ,0,0,0}, {25352,25309,25308 ,13859,13816,13815 ,0,0,0}, - {25268,25353,25310 ,13775,13860,13817 ,0,0,0}, {25267,25266,25309 ,13774,13773,13816 ,0,0,0}, - {25353,25356,25311 ,13860,13863,13818 ,0,0,0}, {25268,25310,25266 ,13775,13817,13773 ,0,0,0}, - {25356,25357,25312 ,13863,13864,13819 ,0,0,0}, {25353,25311,25310 ,13860,13818,13817 ,0,0,0}, - {25357,25358,25313 ,13864,13865,13820 ,0,0,0}, {25356,25312,25311 ,13863,13819,13818 ,0,0,0}, - {25229,25358,25359 ,13736,13865,13866 ,0,0,0}, {25357,25313,25312 ,13864,13820,13819 ,0,0,0}, - {25227,25359,25315 ,13734,13866,13822 ,0,0,0}, {25358,25229,25313 ,13865,13736,13820 ,0,0,0}, - {25360,25317,25316 ,13867,13824,13823 ,0,0,0}, {25359,25227,25229 ,13866,13734,13736 ,0,0,0}, - {25361,25362,25363 ,13868,13869,13870 ,0,0,0}, {25315,25314,25227 ,13822,13821,13734 ,0,0,0}, - {25360,25361,25318 ,13867,13868,13825 ,0,0,0}, {25316,25317,25314 ,13823,13824,13821 ,0,0,0}, - {25361,25364,25319 ,13868,13871,13826 ,0,0,0}, {25360,25318,25317 ,13867,13825,13824 ,0,0,0}, - {25364,25365,25320 ,13871,13872,13827 ,0,0,0}, {25361,25319,25318 ,13868,13826,13825 ,0,0,0}, - {25365,25366,25321 ,13872,13873,13828 ,0,0,0}, {25364,25320,25319 ,13871,13827,13826 ,0,0,0}, - {25366,25367,25322 ,13873,13874,13829 ,0,0,0}, {25365,25321,25320 ,13872,13828,13827 ,0,0,0}, - {25367,25368,25323 ,13874,13875,13830 ,0,0,0}, {25366,25322,25321 ,13873,13829,13828 ,0,0,0}, - {25368,25152,25324 ,13875,13659,13831 ,0,0,0}, {25367,25323,25322 ,13874,13830,13829 ,0,0,0}, - {25154,25152,25151 ,13661,13659,13658 ,0,0,0}, {25323,25368,25324 ,13830,13875,13831 ,0,0,0}, - {25369,25143,25325 ,13876,13650,13832 ,0,0,0}, {25154,25324,25152 ,13661,13831,13659 ,0,0,0}, - {25370,25143,25369 ,13877,13650,13876 ,0,0,0}, {25371,25326,25143 ,13878,13833,13650 ,0,0,0}, - {25147,25325,25142 ,13654,13832,13649 ,0,0,0}, {25283,25369,25325 ,13790,13876,13832 ,0,0,0}, - {25370,25371,25143 ,13877,13878,13650 ,0,0,0}, {25329,25055,25054 ,13836,13562,13561 ,0,0,0}, - {25058,25060,25243 ,13565,13567,13750 ,0,0,0}, {25327,25372,25373 ,13834,13879,13880 ,0,0,0}, - {25329,25327,25286 ,13836,13834,13793 ,0,0,0}, {25054,25374,25329 ,13561,13881,13836 ,0,0,0}, - {25328,25373,25375 ,13835,13880,13882 ,0,0,0}, {25329,25372,25327 ,13836,13879,13834 ,0,0,0}, - {25330,25375,25376 ,13837,13882,13883 ,0,0,0}, {25327,25373,25328 ,13834,13880,13835 ,0,0,0}, - {25288,25376,25377 ,13795,13883,13884 ,0,0,0}, {25328,25375,25330 ,13835,13882,13837 ,0,0,0}, - {25289,25377,25378 ,13796,13884,13885 ,0,0,0}, {25330,25376,25288 ,13837,13883,13795 ,0,0,0}, - {25331,25378,25379 ,13838,13885,13886 ,0,0,0}, {25288,25377,25289 ,13795,13884,13796 ,0,0,0}, - {25332,25379,25334 ,13839,13886,13841 ,0,0,0}, {25378,25331,25289 ,13885,13838,13796 ,0,0,0}, - {25380,25336,25335 ,13887,13843,13842 ,0,0,0}, {25379,25332,25331 ,13886,13839,13838 ,0,0,0}, - {25381,25382,25380 ,13888,13889,13887 ,0,0,0}, {25334,25333,25332 ,13841,13840,13839 ,0,0,0}, - {25380,25382,25337 ,13887,13889,13844 ,0,0,0}, {25335,25336,25333 ,13842,13843,13840 ,0,0,0}, - {25382,25383,25338 ,13889,13890,13845 ,0,0,0}, {25380,25337,25336 ,13887,13844,13843 ,0,0,0}, - {25339,25383,25384 ,13846,13890,13891 ,0,0,0}, {25382,25338,25337 ,13889,13845,13844 ,0,0,0}, - {25340,25384,25385 ,13847,13891,13892 ,0,0,0}, {25338,25383,25339 ,13845,13890,13846 ,0,0,0}, - {25298,25385,25386 ,13805,13892,13893 ,0,0,0}, {25339,25384,25340 ,13846,13891,13847 ,0,0,0}, - {25299,25386,25342 ,13806,13893,13849 ,0,0,0}, {25385,25298,25340 ,13892,13805,13847 ,0,0,0}, - {25387,25388,25343 ,13894,13895,13850 ,0,0,0}, {25386,25299,25298 ,13893,13806,13805 ,0,0,0}, - {25343,25388,25344 ,13850,13895,13851 ,0,0,0}, {25342,25341,25299 ,13849,13848,13806 ,0,0,0}, - {25388,25389,25345 ,13895,13896,13852 ,0,0,0}, {25343,25344,25341 ,13850,13851,13848 ,0,0,0}, - {25346,25389,25390 ,13853,13896,13897 ,0,0,0}, {25388,25345,25344 ,13895,13852,13851 ,0,0,0}, - {25260,25390,25391 ,13767,13897,13898 ,0,0,0}, {25345,25389,25346 ,13852,13896,13853 ,0,0,0}, - {25261,25391,25348 ,13768,13898,13855 ,0,0,0}, {25390,25260,25346 ,13897,13767,13853 ,0,0,0}, - {25392,25393,25349 ,13899,13900,13856 ,0,0,0}, {25391,25261,25260 ,13898,13768,13767 ,0,0,0}, - {25349,25393,25350 ,13856,13900,13857 ,0,0,0}, {25348,25347,25261 ,13855,13854,13768 ,0,0,0}, - {25393,25394,25351 ,13900,13901,13858 ,0,0,0}, {25349,25350,25347 ,13856,13857,13854 ,0,0,0}, - {25352,25394,25395 ,13859,13901,13902 ,0,0,0}, {25393,25351,25350 ,13900,13858,13857 ,0,0,0}, - {25267,25395,25396 ,13774,13902,13903 ,0,0,0}, {25351,25394,25352 ,13858,13901,13859 ,0,0,0}, - {25268,25396,25354 ,13775,13903,13861 ,0,0,0}, {25395,25267,25352 ,13902,13774,13859 ,0,0,0}, - {25397,25398,25355 ,13904,13905,13862 ,0,0,0}, {25396,25268,25267 ,13903,13775,13774 ,0,0,0}, - {25355,25398,25356 ,13862,13905,13863 ,0,0,0}, {25354,25353,25268 ,13861,13860,13775 ,0,0,0}, - {25398,25399,25357 ,13905,13906,13864 ,0,0,0}, {25355,25356,25353 ,13862,13863,13860 ,0,0,0}, - {25358,25399,25400 ,13865,13906,13907 ,0,0,0}, {25398,25357,25356 ,13905,13864,13863 ,0,0,0}, - {25359,25400,25401 ,13866,13907,13908 ,0,0,0}, {25357,25399,25358 ,13864,13906,13865 ,0,0,0}, - {25315,25401,25402 ,13822,13908,13909 ,0,0,0}, {25358,25400,25359 ,13865,13907,13866 ,0,0,0}, - {25316,25402,25403 ,13823,13909,13910 ,0,0,0}, {25359,25401,25315 ,13866,13908,13822 ,0,0,0}, - {25360,25403,25362 ,13867,13910,13869 ,0,0,0}, {25402,25316,25315 ,13909,13823,13822 ,0,0,0}, - {25404,25364,25363 ,13911,13871,13870 ,0,0,0}, {25403,25360,25316 ,13910,13867,13823 ,0,0,0}, - {25405,25406,25404 ,13912,13913,13911 ,0,0,0}, {25362,25361,25360 ,13869,13868,13867 ,0,0,0}, - {25404,25406,25365 ,13911,13913,13872 ,0,0,0}, {25363,25364,25361 ,13870,13871,13868 ,0,0,0}, - {25406,25407,25366 ,13913,13914,13873 ,0,0,0}, {25404,25365,25364 ,13911,13872,13871 ,0,0,0}, - {25407,25408,25367 ,13914,13915,13874 ,0,0,0}, {25406,25366,25365 ,13913,13873,13872 ,0,0,0}, - {25408,25409,25368 ,13915,13916,13875 ,0,0,0}, {25407,25367,25366 ,13914,13874,13873 ,0,0,0}, - {25152,25409,25153 ,13659,13916,13660 ,0,0,0}, {25408,25368,25367 ,13915,13875,13874 ,0,0,0}, - {25153,25410,25151 ,13660,13917,13658 ,0,0,0}, {25152,25368,25409 ,13659,13875,13916 ,0,0,0}, - {25411,25369,25159 ,13918,13876,13666 ,0,0,0}, {25411,25412,25369 ,13918,13919,13876 ,0,0,0}, - {25155,25283,25325 ,13662,13790,13832 ,0,0,0}, {25410,25159,25283 ,13917,13666,13790 ,0,0,0}, - {25370,25369,25412 ,13877,13876,13919 ,0,0,0}, {25060,25374,25054 ,13567,13881,13561 ,0,0,0}, - {25413,25059,25058 ,13920,13566,13565 ,0,0,0}, {25414,25372,25374 ,13921,13879,13881 ,0,0,0}, - {25374,25372,25329 ,13881,13879,13836 ,0,0,0}, {25374,25285,25414 ,13881,13792,13921 ,0,0,0}, - {25415,25373,25372 ,13922,13880,13879 ,0,0,0}, {25372,25414,25415 ,13879,13921,13922 ,0,0,0}, - {25416,25375,25373 ,13923,13882,13880 ,0,0,0}, {25373,25415,25416 ,13880,13922,13923 ,0,0,0}, - {25417,25376,25375 ,13924,13883,13882 ,0,0,0}, {25375,25416,25417 ,13882,13923,13924 ,0,0,0}, - {25418,25377,25376 ,13925,13884,13883 ,0,0,0}, {25376,25417,25418 ,13883,13924,13925 ,0,0,0}, - {25419,25378,25377 ,13926,13885,13884 ,0,0,0}, {25377,25418,25419 ,13884,13925,13926 ,0,0,0}, - {25420,25379,25378 ,13927,13886,13885 ,0,0,0}, {25378,25419,25420 ,13885,13926,13927 ,0,0,0}, - {25421,25334,25379 ,13928,13841,13886 ,0,0,0}, {25379,25420,25421 ,13886,13927,13928 ,0,0,0}, - {25422,25335,25334 ,13929,13842,13841 ,0,0,0}, {25334,25421,25422 ,13841,13928,13929 ,0,0,0}, - {25423,25380,25335 ,13930,13887,13842 ,0,0,0}, {25422,25423,25335 ,13929,13930,13842 ,0,0,0}, - {25424,25425,25426 ,13931,13932,13933 ,0,0,0}, {25423,25381,25380 ,13930,13888,13887 ,0,0,0}, - {25427,25383,25382 ,13934,13890,13889 ,0,0,0}, {25381,25427,25382 ,13888,13934,13889 ,0,0,0}, - {25428,25384,25383 ,13935,13891,13890 ,0,0,0}, {25383,25427,25428 ,13890,13934,13935 ,0,0,0}, - {25429,25385,25384 ,13936,13892,13891 ,0,0,0}, {25384,25428,25429 ,13891,13935,13936 ,0,0,0}, - {25430,25386,25385 ,13937,13893,13892 ,0,0,0}, {25385,25429,25430 ,13892,13936,13937 ,0,0,0}, - {25431,25342,25386 ,13938,13849,13893 ,0,0,0}, {25386,25430,25431 ,13893,13937,13938 ,0,0,0}, - {25432,25343,25342 ,13939,13850,13849 ,0,0,0}, {25431,25432,25342 ,13938,13939,13849 ,0,0,0}, - {25433,25387,25434 ,13940,13894,13941 ,0,0,0}, {25432,25387,25343 ,13939,13894,13850 ,0,0,0}, - {25433,25389,25388 ,13940,13896,13895 ,0,0,0}, {25387,25433,25388 ,13894,13940,13895 ,0,0,0}, - {25435,25390,25389 ,13942,13897,13896 ,0,0,0}, {25389,25433,25435 ,13896,13940,13942 ,0,0,0}, - {25436,25391,25390 ,13943,13898,13897 ,0,0,0}, {25390,25435,25436 ,13897,13942,13943 ,0,0,0}, - {25437,25348,25391 ,13944,13855,13898 ,0,0,0}, {25391,25436,25437 ,13898,13943,13944 ,0,0,0}, - {25438,25349,25348 ,13945,13856,13855 ,0,0,0}, {25437,25438,25348 ,13944,13945,13855 ,0,0,0}, - {25439,25440,25441 ,13946,13947,13948 ,0,0,0}, {25438,25392,25349 ,13945,13899,13856 ,0,0,0}, - {25442,25394,25393 ,13949,13901,13900 ,0,0,0}, {25392,25442,25393 ,13899,13949,13900 ,0,0,0}, - {25443,25395,25394 ,13950,13902,13901 ,0,0,0}, {25394,25442,25443 ,13901,13949,13950 ,0,0,0}, - {25444,25396,25395 ,13951,13903,13902 ,0,0,0}, {25395,25443,25444 ,13902,13950,13951 ,0,0,0}, - {25445,25354,25396 ,13952,13861,13903 ,0,0,0}, {25396,25444,25445 ,13903,13951,13952 ,0,0,0}, - {25446,25355,25354 ,13953,13862,13861 ,0,0,0}, {25445,25446,25354 ,13952,13953,13861 ,0,0,0}, - {25398,25447,25399 ,13905,13954,13906 ,0,0,0}, {25446,25397,25355 ,13953,13904,13862 ,0,0,0}, - {25448,25449,25447 ,13955,13956,13954 ,0,0,0}, {25397,25447,25398 ,13904,13954,13905 ,0,0,0}, - {25449,25400,25399 ,13956,13907,13906 ,0,0,0}, {25399,25447,25449 ,13906,13954,13956 ,0,0,0}, - {25450,25401,25400 ,13957,13908,13907 ,0,0,0}, {25400,25449,25450 ,13907,13956,13957 ,0,0,0}, - {25451,25402,25401 ,13958,13909,13908 ,0,0,0}, {25401,25450,25451 ,13908,13957,13958 ,0,0,0}, - {25452,25403,25402 ,13959,13910,13909 ,0,0,0}, {25402,25451,25452 ,13909,13958,13959 ,0,0,0}, - {25453,25362,25403 ,13960,13869,13910 ,0,0,0}, {25403,25452,25453 ,13910,13959,13960 ,0,0,0}, - {25454,25363,25362 ,13961,13870,13869 ,0,0,0}, {25362,25453,25454 ,13869,13960,13961 ,0,0,0}, - {25455,25404,25363 ,13962,13911,13870 ,0,0,0}, {25454,25455,25363 ,13961,13962,13870 ,0,0,0}, - {25406,25456,25407 ,13913,13963,13914 ,0,0,0}, {25455,25405,25404 ,13962,13912,13911 ,0,0,0}, - {25407,25457,25408 ,13914,13964,13915 ,0,0,0}, {25405,25456,25406 ,13912,13963,13913 ,0,0,0}, - {25408,25458,25409 ,13915,13965,13916 ,0,0,0}, {25456,25457,25407 ,13963,13964,13914 ,0,0,0}, - {25409,25156,25153 ,13916,13663,13660 ,0,0,0}, {25457,25458,25408 ,13964,13965,13915 ,0,0,0}, - {25161,25160,25157 ,13668,13667,13664 ,0,0,0}, {25458,25156,25409 ,13965,13663,13916 ,0,0,0}, - {25157,25410,25153 ,13664,13917,13660 ,0,0,0}, {25283,25159,25369 ,13790,13666,13876 ,0,0,0}, - {25151,25410,25283 ,13658,13917,13790 ,0,0,0}, {25410,25157,25160 ,13917,13664,13667 ,0,0,0}, - {25411,25159,25158 ,13918,13666,13665 ,0,0,0}, {25059,25285,25060 ,13566,13792,13567 ,0,0,0}, - {25413,25066,25064 ,13920,13573,13571 ,0,0,0}, {25414,25285,25459 ,13921,13792,13966 ,0,0,0}, - {25060,25285,25374 ,13567,13792,13881 ,0,0,0}, {25285,25063,25459 ,13792,13570,13966 ,0,0,0}, - {25415,25414,25460 ,13922,13921,13967 ,0,0,0}, {25414,25459,25460 ,13921,13966,13967 ,0,0,0}, - {25416,25415,25461 ,13923,13922,13968 ,0,0,0}, {25415,25460,25461 ,13922,13967,13968 ,0,0,0}, - {25417,25416,25462 ,13924,13923,13969 ,0,0,0}, {25416,25461,25462 ,13923,13968,13969 ,0,0,0}, - {25418,25417,25463 ,13925,13924,13970 ,0,0,0}, {25417,25462,25463 ,13924,13969,13970 ,0,0,0}, - {25419,25418,25464 ,13926,13925,13971 ,0,0,0}, {25418,25463,25464 ,13925,13970,13971 ,0,0,0}, - {25420,25419,25465 ,13927,13926,13972 ,0,0,0}, {25419,25464,25465 ,13926,13971,13972 ,0,0,0}, - {25421,25420,25466 ,13928,13927,13973 ,0,0,0}, {25420,25465,25466 ,13927,13972,13973 ,0,0,0}, - {25422,25421,25467 ,13929,13928,13974 ,0,0,0}, {25421,25466,25467 ,13928,13973,13974 ,0,0,0}, - {25423,25422,25468 ,13930,13929,13975 ,0,0,0}, {25422,25467,25468 ,13929,13974,13975 ,0,0,0}, - {25381,25423,25469 ,13888,13930,13976 ,0,0,0}, {25423,25468,25469 ,13930,13975,13976 ,0,0,0}, - {25427,25381,25424 ,13934,13888,13931 ,0,0,0}, {25469,25424,25381 ,13976,13931,13888 ,0,0,0}, - {25428,25427,25426 ,13935,13934,13933 ,0,0,0}, {25427,25424,25426 ,13934,13931,13933 ,0,0,0}, - {25429,25428,25470 ,13936,13935,13977 ,0,0,0}, {25428,25426,25470 ,13935,13933,13977 ,0,0,0}, - {25430,25429,25471 ,13937,13936,13978 ,0,0,0}, {25429,25470,25471 ,13936,13977,13978 ,0,0,0}, - {25431,25430,25472 ,13938,13937,13979 ,0,0,0}, {25430,25471,25472 ,13937,13978,13979 ,0,0,0}, - {25432,25431,25473 ,13939,13938,13980 ,0,0,0}, {25431,25472,25473 ,13938,13979,13980 ,0,0,0}, - {25387,25432,25474 ,13894,13939,13981 ,0,0,0}, {25432,25473,25474 ,13939,13980,13981 ,0,0,0}, - {25474,25475,25434 ,13981,13982,13941 ,0,0,0}, {25474,25434,25387 ,13981,13941,13894 ,0,0,0}, - {25435,25433,25476 ,13942,13940,13983 ,0,0,0}, {25433,25434,25476 ,13940,13941,13983 ,0,0,0}, - {25436,25435,25477 ,13943,13942,13984 ,0,0,0}, {25435,25476,25477 ,13942,13983,13984 ,0,0,0}, - {25437,25436,25478 ,13944,13943,13985 ,0,0,0}, {25436,25477,25478 ,13943,13984,13985 ,0,0,0}, - {25438,25437,25479 ,13945,13944,13986 ,0,0,0}, {25437,25478,25479 ,13944,13985,13986 ,0,0,0}, - {25392,25438,25480 ,13899,13945,13987 ,0,0,0}, {25438,25479,25480 ,13945,13986,13987 ,0,0,0}, - {25442,25392,25439 ,13949,13899,13946 ,0,0,0}, {25480,25439,25392 ,13987,13946,13899 ,0,0,0}, - {25443,25442,25441 ,13950,13949,13948 ,0,0,0}, {25442,25439,25441 ,13949,13946,13948 ,0,0,0}, - {25444,25443,25481 ,13951,13950,13988 ,0,0,0}, {25443,25441,25481 ,13950,13948,13988 ,0,0,0}, - {25445,25444,25482 ,13952,13951,13989 ,0,0,0}, {25444,25481,25482 ,13951,13988,13989 ,0,0,0}, - {25446,25445,25483 ,13953,13952,13990 ,0,0,0}, {25445,25482,25483 ,13952,13989,13990 ,0,0,0}, - {25397,25446,25484 ,13904,13953,13991 ,0,0,0}, {25446,25483,25484 ,13953,13990,13991 ,0,0,0}, - {25447,25397,25485 ,13954,13904,13992 ,0,0,0}, {25397,25484,25485 ,13904,13991,13992 ,0,0,0}, - {25448,25485,25486 ,13955,13992,13993 ,0,0,0}, {25485,25448,25447 ,13992,13955,13954 ,0,0,0}, - {25450,25449,25487 ,13957,13956,13994 ,0,0,0}, {25449,25448,25487 ,13956,13955,13994 ,0,0,0}, - {25451,25450,25488 ,13958,13957,13995 ,0,0,0}, {25450,25487,25488 ,13957,13994,13995 ,0,0,0}, - {25452,25451,25489 ,13959,13958,13996 ,0,0,0}, {25451,25488,25489 ,13958,13995,13996 ,0,0,0}, - {25453,25452,25490 ,13960,13959,13997 ,0,0,0}, {25452,25489,25490 ,13959,13996,13997 ,0,0,0}, - {25454,25453,25491 ,13961,13960,13998 ,0,0,0}, {25453,25490,25491 ,13960,13997,13998 ,0,0,0}, - {25455,25454,25492 ,13962,13961,13999 ,0,0,0}, {25454,25491,25492 ,13961,13998,13999 ,0,0,0}, - {25405,25455,25493 ,13912,13962,14000 ,0,0,0}, {25455,25492,25493 ,13962,13999,14000 ,0,0,0}, - {25456,25405,25494 ,13963,13912,14001 ,0,0,0}, {25405,25493,25494 ,13912,14000,14001 ,0,0,0}, - {25457,25456,25495 ,13964,13963,14002 ,0,0,0}, {25456,25494,25495 ,13963,14001,14002 ,0,0,0}, - {25458,25457,25496 ,13965,13964,14003 ,0,0,0}, {25457,25495,25496 ,13964,14002,14003 ,0,0,0}, - {25156,25458,25497 ,13663,13965,14004 ,0,0,0}, {25458,25496,25497 ,13965,14003,14004 ,0,0,0}, - {25498,25157,25156 ,14005,13664,13663 ,0,0,0}, {25498,25156,25497 ,14005,13663,14004 ,0,0,0}, - {25410,25160,25159 ,13917,13667,13666 ,0,0,0}, {25498,25161,25157 ,14005,13668,13664 ,0,0,0}, - {25158,25160,25163 ,13665,13667,13670 ,0,0,0}, {25064,25059,25413 ,13571,13566,13920 ,0,0,0}, - {25065,25062,25064 ,13572,13569,13571 ,0,0,0}, {25062,25499,25063 ,13569,14006,13570 ,0,0,0}, - {25063,25499,25459 ,13570,14006,13966 ,0,0,0}, {25499,25500,25459 ,14006,14007,13966 ,0,0,0}, - {25459,25500,25460 ,13966,14007,13967 ,0,0,0}, {25500,25501,25460 ,14007,14008,13967 ,0,0,0}, - {25460,25501,25461 ,13967,14008,13968 ,0,0,0}, {25501,25502,25461 ,14008,14009,13968 ,0,0,0}, - {25461,25502,25462 ,13968,14009,13969 ,0,0,0}, {25502,25503,25462 ,14009,14010,13969 ,0,0,0}, - {25462,25503,25463 ,13969,14010,13970 ,0,0,0}, {25503,25504,25463 ,14010,14011,13970 ,0,0,0}, - {25463,25504,25464 ,13970,14011,13971 ,0,0,0}, {25504,25505,25464 ,14011,14012,13971 ,0,0,0}, - {25464,25505,25465 ,13971,14012,13972 ,0,0,0}, {25505,25506,25465 ,14012,14013,13972 ,0,0,0}, - {25506,25507,25466 ,14013,14014,13973 ,0,0,0}, {25506,25466,25465 ,14013,13973,13972 ,0,0,0}, - {25507,25508,25467 ,14014,14015,13974 ,0,0,0}, {25507,25467,25466 ,14014,13974,13973 ,0,0,0}, - {25508,25509,25468 ,14015,14016,13975 ,0,0,0}, {25508,25468,25467 ,14015,13975,13974 ,0,0,0}, - {25509,25510,25469 ,14016,14017,13976 ,0,0,0}, {25509,25469,25468 ,14016,13976,13975 ,0,0,0}, - {25510,25511,25424 ,14017,14018,13931 ,0,0,0}, {25510,25424,25469 ,14017,13931,13976 ,0,0,0}, - {25425,25424,25511 ,13932,13931,14018 ,0,0,0}, {25425,25512,25426 ,13932,14019,13933 ,0,0,0}, - {25426,25512,25470 ,13933,14019,13977 ,0,0,0}, {25512,25513,25470 ,14019,14020,13977 ,0,0,0}, - {25470,25513,25471 ,13977,14020,13978 ,0,0,0}, {25513,25514,25471 ,14020,14021,13978 ,0,0,0}, - {25514,25515,25472 ,14021,14022,13979 ,0,0,0}, {25514,25472,25471 ,14021,13979,13978 ,0,0,0}, - {25515,25516,25473 ,14022,14023,13980 ,0,0,0}, {25515,25473,25472 ,14022,13980,13979 ,0,0,0}, - {25516,25475,25474 ,14023,13982,13981 ,0,0,0}, {25516,25474,25473 ,14023,13981,13980 ,0,0,0}, - {25475,25517,25434 ,13982,14024,13941 ,0,0,0}, {25517,25518,25434 ,14024,14025,13941 ,0,0,0}, - {25434,25518,25476 ,13941,14025,13983 ,0,0,0}, {25518,25519,25476 ,14025,14026,13983 ,0,0,0}, - {25476,25519,25477 ,13983,14026,13984 ,0,0,0}, {25519,25520,25477 ,14026,14027,13984 ,0,0,0}, - {25520,25521,25478 ,14027,14028,13985 ,0,0,0}, {25520,25478,25477 ,14027,13985,13984 ,0,0,0}, - {25521,25522,25479 ,14028,14029,13986 ,0,0,0}, {25521,25479,25478 ,14028,13986,13985 ,0,0,0}, - {25522,25523,25480 ,14029,14030,13987 ,0,0,0}, {25522,25480,25479 ,14029,13987,13986 ,0,0,0}, - {25523,25524,25439 ,14030,14031,13946 ,0,0,0}, {25523,25439,25480 ,14030,13946,13987 ,0,0,0}, - {25440,25439,25524 ,13947,13946,14031 ,0,0,0}, {25440,25525,25441 ,13947,14032,13948 ,0,0,0}, - {25441,25525,25481 ,13948,14032,13988 ,0,0,0}, {25525,25526,25481 ,14032,14033,13988 ,0,0,0}, - {25526,25527,25482 ,14033,14034,13989 ,0,0,0}, {25526,25482,25481 ,14033,13989,13988 ,0,0,0}, - {25527,25528,25483 ,14034,14035,13990 ,0,0,0}, {25527,25483,25482 ,14034,13990,13989 ,0,0,0}, - {25528,25529,25484 ,14035,14036,13991 ,0,0,0}, {25528,25484,25483 ,14035,13991,13990 ,0,0,0}, - {25529,25486,25485 ,14036,13993,13992 ,0,0,0}, {25529,25485,25484 ,14036,13992,13991 ,0,0,0}, - {25486,25530,25448 ,13993,14037,13955 ,0,0,0}, {25530,25531,25448 ,14037,14038,13955 ,0,0,0}, - {25448,25531,25487 ,13955,14038,13994 ,0,0,0}, {25531,25532,25487 ,14038,14039,13994 ,0,0,0}, - {25487,25532,25488 ,13994,14039,13995 ,0,0,0}, {25532,25533,25488 ,14039,14040,13995 ,0,0,0}, - {25488,25533,25489 ,13995,14040,13996 ,0,0,0}, {25533,25534,25489 ,14040,14041,13996 ,0,0,0}, - {25534,25535,25490 ,14041,14042,13997 ,0,0,0}, {25534,25490,25489 ,14041,13997,13996 ,0,0,0}, - {25535,25536,25491 ,14042,14043,13998 ,0,0,0}, {25535,25491,25490 ,14042,13998,13997 ,0,0,0}, - {25536,25537,25492 ,14043,14044,13999 ,0,0,0}, {25536,25492,25491 ,14043,13999,13998 ,0,0,0}, - {25537,25538,25493 ,14044,14045,14000 ,0,0,0}, {25537,25493,25492 ,14044,14000,13999 ,0,0,0}, - {25538,25539,25494 ,14045,14046,14001 ,0,0,0}, {25538,25494,25493 ,14045,14001,14000 ,0,0,0}, - {25539,25540,25495 ,14046,14047,14002 ,0,0,0}, {25539,25495,25494 ,14046,14002,14001 ,0,0,0}, - {25540,25541,25496 ,14047,14048,14003 ,0,0,0}, {25540,25496,25495 ,14047,14003,14002 ,0,0,0}, - {25541,25542,25497 ,14048,14049,14004 ,0,0,0}, {25541,25497,25496 ,14048,14004,14003 ,0,0,0}, - {25542,25543,25498 ,14049,14050,14005 ,0,0,0}, {25542,25498,25497 ,14049,14005,14004 ,0,0,0}, - {25544,25498,25543 ,14051,14005,14050 ,0,0,0}, {25498,25544,25161 ,14005,14051,13668 ,0,0,0}, - {25161,25544,25164 ,13668,14051,13671 ,0,0,0}, {25545,25546,25547 ,14052,14053,14054 ,0,0,0}, - {25548,25549,25550 ,14055,14056,14057 ,0,0,0}, {25551,25552,25553 ,14058,14059,14060 ,0,0,0}, - {25554,25555,25551 ,14061,14062,14058 ,0,0,0}, {25556,25557,25558 ,14063,14064,14065 ,0,0,0}, - {25559,25560,25561 ,14066,14067,14068 ,0,0,0}, {25562,25563,25564 ,14069,14070,14071 ,0,0,0}, - {25565,25566,25559 ,14072,14073,14066 ,0,0,0}, {25567,25568,25569 ,14074,14075,14076 ,0,0,0}, - {25569,25564,25570 ,14076,14071,14077 ,0,0,0}, {25571,25567,25572 ,14078,14074,14079 ,0,0,0}, - {25568,25567,25573 ,14075,14074,14080 ,0,0,0}, {25554,25574,25575 ,14061,14081,14082 ,0,0,0}, - {25571,25576,25567 ,14078,14083,14074 ,0,0,0}, {25577,25578,25579 ,14084,14085,14086 ,0,0,0}, - {25578,25580,25547 ,14085,14087,14054 ,0,0,0}, {25581,25582,25579 ,14088,14089,14086 ,0,0,0}, - {25580,25578,25577 ,14087,14085,14084 ,0,0,0}, {25583,25584,25581 ,14090,14091,14088 ,0,0,0}, - {25579,25582,25577 ,14086,14089,14084 ,0,0,0}, {25585,25586,25549 ,14092,14093,14056 ,0,0,0}, - {25587,25588,25589 ,14094,14095,14096 ,0,0,0}, {25585,25590,25586 ,14092,14097,14093 ,0,0,0}, - {25591,25592,25593 ,14098,14099,14100 ,0,0,0}, {25588,25594,25589 ,14095,14101,14096 ,0,0,0}, - {25595,25596,25597 ,14102,14103,14104 ,0,0,0}, {25591,25593,25598 ,14098,14100,14105 ,0,0,0}, - {25599,25600,25601 ,14106,14107,14108 ,0,0,0}, {25600,25599,25602 ,14107,14106,14109 ,0,0,0}, - {25603,25604,25605 ,14110,14111,14112 ,0,0,0}, {25606,25607,25604 ,14113,14114,14111 ,0,0,0}, - {25608,25609,25610 ,14115,14116,14117 ,0,0,0}, {25603,25605,25611 ,14110,14112,14118 ,0,0,0}, - {25612,25613,25614 ,14119,14120,14121 ,0,0,0}, {25608,25610,25615 ,14115,14117,14122 ,0,0,0}, - {25616,25617,25618 ,14123,14124,14125 ,0,0,0}, {25619,25613,25612 ,14126,14120,14119 ,0,0,0}, - {25620,25621,25622 ,14127,14128,14129 ,0,0,0}, {25622,25618,25620 ,14129,14125,14127 ,0,0,0}, - {25623,25624,25625 ,14130,14131,14132 ,0,0,0}, {25626,25621,25627 ,14133,14128,14134 ,0,0,0}, - {25628,25629,25630 ,14135,14136,14137 ,0,0,0}, {25629,25628,25631 ,14136,14135,14138 ,0,0,0}, - {25632,25633,25634 ,14139,14140,14141 ,0,0,0}, {25630,25633,25635 ,14137,14140,14142 ,0,0,0}, - {25636,25637,25638 ,14143,14144,14145 ,0,0,0}, {25639,25640,25641 ,14146,14147,14148 ,0,0,0}, - {25642,25643,25644 ,14149,14150,14151 ,0,0,0}, {25643,25642,25645 ,14150,14149,14152 ,0,0,0}, - {25646,25647,25648 ,14153,14154,14155 ,0,0,0}, {25649,25650,25646 ,14156,14157,14153 ,0,0,0}, - {25647,25646,25650 ,14154,14153,14157 ,0,0,0}, {25647,25650,25636 ,14154,14157,14143 ,0,0,0}, - {25651,25652,25653 ,14158,14159,14160 ,0,0,0}, {25634,25638,25637 ,14141,14145,14144 ,0,0,0}, - {25654,25639,25641 ,14161,14146,14148 ,0,0,0}, {25640,25655,25641 ,14147,14162,14148 ,0,0,0}, - {25656,25657,25639 ,14163,14164,14146 ,0,0,0}, {25639,25658,25640 ,14146,14165,14147 ,0,0,0}, - {25659,25660,25661 ,14166,14167,14168 ,0,0,0}, {25058,25662,25663 ,14169,14170,14171 ,0,0,0}, - {25663,25664,25413 ,14171,14172,14173 ,0,0,0}, {25664,25066,25413 ,14172,14174,14173 ,0,0,0}, - {25067,25066,25665 ,730,14174,14175 ,0,0,0}, {25653,25633,25651 ,14160,14140,14158 ,0,0,0}, - {25644,25649,25646 ,14151,14156,14153 ,0,0,0}, {25634,25637,25632 ,14141,14144,14139 ,0,0,0}, - {25196,25645,25195 ,14176,14152,14177 ,0,0,0}, {25628,25630,25635 ,14135,14137,14142 ,0,0,0}, - {25633,25632,25635 ,14140,14139,14142 ,0,0,0}, {25623,25631,25624 ,14130,14138,14131 ,0,0,0}, - {25629,25631,25623 ,14136,14138,14130 ,0,0,0}, {25623,25666,25629 ,14130,14178,14136 ,0,0,0}, - {25624,25626,25625 ,14131,14133,14132 ,0,0,0}, {25627,25621,25620 ,14134,14128,14127 ,0,0,0}, - {25626,25627,25625 ,14133,14134,14132 ,0,0,0}, {25616,25618,25622 ,14123,14125,14129 ,0,0,0}, - {25612,25614,25667 ,14119,14121,14179 ,0,0,0}, {25668,25619,25669 ,14180,14126,14181 ,0,0,0}, - {25618,25617,25669 ,14125,14124,14181 ,0,0,0}, {25613,25619,25668 ,14120,14126,14180 ,0,0,0}, - {25617,25668,25669 ,14124,14180,14181 ,0,0,0}, {25667,25614,25615 ,14179,14121,14122 ,0,0,0}, - {25670,25612,25667 ,14182,14119,14179 ,0,0,0}, {25615,25610,25667 ,14122,14117,14179 ,0,0,0}, - {25611,25609,25671 ,14118,14116,14183 ,0,0,0}, {25608,25671,25609 ,14115,14183,14116 ,0,0,0}, - {25672,25611,25671 ,14184,14118,14183 ,0,0,0}, {25607,25605,25604 ,14114,14112,14111 ,0,0,0}, - {25603,25611,25672 ,14110,14118,14184 ,0,0,0}, {25606,25673,25607 ,14113,14185,14114 ,0,0,0}, - {25601,25600,25673 ,14108,14107,14185 ,0,0,0}, {25673,25606,25601 ,14185,14113,14108 ,0,0,0}, - {25602,25674,25597 ,14109,14186,14104 ,0,0,0}, {25675,25676,25677 ,14187,14188,14189 ,0,0,0}, - {25597,25674,25678 ,14104,14186,14190 ,0,0,0}, {25674,25602,25599 ,14186,14109,14106 ,0,0,0}, - {25679,25598,25596 ,14191,14105,14103 ,0,0,0}, {25595,25597,25678 ,14102,14104,14190 ,0,0,0}, - {25598,25679,25591 ,14105,14191,14098 ,0,0,0}, {25679,25596,25595 ,14191,14103,14102 ,0,0,0}, - {25590,25680,25681 ,14097,14192,14193 ,0,0,0}, {25592,25594,25682 ,14099,14101,14194 ,0,0,0}, - {25593,25592,25682 ,14100,14099,14194 ,0,0,0}, {25682,25594,25588 ,14194,14101,14095 ,0,0,0}, - {25683,25684,25685 ,14195,14196,14197 ,0,0,0}, {25680,25587,25589 ,14192,14094,14096 ,0,0,0}, - {25547,25580,25545 ,14054,14087,14052 ,0,0,0}, {25590,25587,25680 ,14097,14094,14192 ,0,0,0}, - {25590,25681,25586 ,14097,14193,14093 ,0,0,0}, {25549,25548,25585 ,14056,14055,14092 ,0,0,0}, - {25584,25583,25550 ,14091,14090,14057 ,0,0,0}, {25550,25583,25548 ,14057,14090,14055 ,0,0,0}, - {25686,25583,25581 ,14198,14090,14088 ,0,0,0}, {25584,25582,25581 ,14091,14089,14088 ,0,0,0}, - {25546,25575,25574 ,14053,14082,14081 ,0,0,0}, {25545,25575,25546 ,14052,14082,14053 ,0,0,0}, - {25555,25552,25551 ,14062,14059,14058 ,0,0,0}, {25554,25551,25574 ,14061,14058,14081 ,0,0,0}, - {25555,25687,25552 ,14062,14199,14059 ,0,0,0}, {25558,25688,25562 ,14065,14200,14069 ,0,0,0}, - {25689,25690,25687 ,14201,14202,14199 ,0,0,0}, {25556,25691,25692 ,14063,14203,14204 ,0,0,0}, - {25690,25693,25694 ,14202,14205,14206 ,0,0,0}, {25689,25693,25690 ,14201,14205,14202 ,0,0,0}, - {25690,25552,25687 ,14202,14059,14199 ,0,0,0}, {25694,25695,25696 ,14206,14207,14208 ,0,0,0}, - {25695,25694,25697 ,14207,14206,14209 ,0,0,0}, {25693,25697,25694 ,14205,14209,14206 ,0,0,0}, - {25692,25691,25696 ,14204,14203,14208 ,0,0,0}, {25698,25558,25557 ,14210,14065,14064 ,0,0,0}, - {25694,25696,25691 ,14206,14208,14203 ,0,0,0}, {25563,25562,25699 ,14070,14069,14211 ,0,0,0}, - {25694,25700,25690 ,14206,14212,14202 ,0,0,0}, {25701,25574,25551 ,14213,14081,14058 ,0,0,0}, - {25690,25561,25552 ,14202,14068,14059 ,0,0,0}, {25702,25546,25574 ,14214,14053,14081 ,0,0,0}, - {25553,25552,25561 ,14060,14059,14068 ,0,0,0}, {25703,25547,25546 ,14215,14054,14053 ,0,0,0}, - {25701,25551,25553 ,14213,14058,14060 ,0,0,0}, {25704,25578,25547 ,14216,14085,14054 ,0,0,0}, - {25702,25574,25701 ,14214,14081,14213 ,0,0,0}, {25705,25579,25578 ,14217,14086,14085 ,0,0,0}, - {25703,25546,25702 ,14215,14053,14214 ,0,0,0}, {25706,25581,25579 ,14218,14088,14086 ,0,0,0}, - {25547,25703,25704 ,14054,14215,14216 ,0,0,0}, {25707,25708,25709 ,14219,14220,14221 ,0,0,0}, - {25578,25704,25705 ,14085,14216,14217 ,0,0,0}, {25709,25548,25583 ,14221,14055,14090 ,0,0,0}, - {25579,25705,25706 ,14086,14217,14218 ,0,0,0}, {25710,25585,25548 ,14222,14092,14055 ,0,0,0}, - {25581,25706,25686 ,14088,14218,14198 ,0,0,0}, {25711,25590,25585 ,14223,14097,14092 ,0,0,0}, - {25583,25686,25709 ,14090,14198,14221 ,0,0,0}, {25712,25587,25590 ,14224,14094,14097 ,0,0,0}, - {25548,25709,25710 ,14055,14221,14222 ,0,0,0}, {25713,25588,25587 ,14225,14095,14094 ,0,0,0}, - {25711,25585,25710 ,14223,14092,14222 ,0,0,0}, {25714,25682,25588 ,14226,14194,14095 ,0,0,0}, - {25712,25590,25711 ,14224,14097,14223 ,0,0,0}, {25715,25593,25682 ,14227,14100,14194 ,0,0,0}, - {25587,25712,25713 ,14094,14224,14225 ,0,0,0}, {25684,25598,25593 ,14196,14105,14100 ,0,0,0}, - {25588,25713,25714 ,14095,14225,14226 ,0,0,0}, {25716,25596,25598 ,14228,14103,14105 ,0,0,0}, - {25682,25714,25715 ,14194,14226,14227 ,0,0,0}, {25717,25597,25596 ,14229,14104,14103 ,0,0,0}, - {25593,25715,25684 ,14100,14227,14196 ,0,0,0}, {25718,25602,25597 ,14230,14109,14104 ,0,0,0}, - {25716,25598,25684 ,14228,14105,14196 ,0,0,0}, {25719,25600,25602 ,14231,14107,14109 ,0,0,0}, - {25717,25596,25716 ,14229,14103,14228 ,0,0,0}, {25720,25673,25600 ,14232,14185,14107 ,0,0,0}, - {25597,25717,25718 ,14104,14229,14230 ,0,0,0}, {25607,25673,25675 ,14114,14185,14187 ,0,0,0}, - {25602,25718,25719 ,14109,14230,14231 ,0,0,0}, {25721,25605,25607 ,14233,14112,14114 ,0,0,0}, - {25600,25719,25720 ,14107,14231,14232 ,0,0,0}, {25722,25611,25605 ,14234,14118,14112 ,0,0,0}, - {25673,25720,25675 ,14185,14232,14187 ,0,0,0}, {25723,25609,25611 ,14235,14116,14118 ,0,0,0}, - {25721,25607,25675 ,14233,14114,14187 ,0,0,0}, {25724,25610,25609 ,14236,14117,14116 ,0,0,0}, - {25722,25605,25721 ,14234,14112,14233 ,0,0,0}, {25725,25667,25610 ,14237,14179,14117 ,0,0,0}, - {25611,25722,25723 ,14118,14234,14235 ,0,0,0}, {25726,25727,25728 ,14238,14239,14240 ,0,0,0}, - {25609,25723,25724 ,14116,14235,14236 ,0,0,0}, {25729,25619,25612 ,14241,14126,14119 ,0,0,0}, - {25610,25724,25725 ,14117,14236,14237 ,0,0,0}, {25730,25669,25619 ,14242,14181,14126 ,0,0,0}, - {25667,25725,25670 ,14179,14237,14182 ,0,0,0}, {25731,25618,25669 ,14243,14125,14181 ,0,0,0}, - {25612,25670,25729 ,14119,14182,14241 ,0,0,0}, {25732,25620,25618 ,14244,14127,14125 ,0,0,0}, - {25730,25619,25729 ,14242,14126,14241 ,0,0,0}, {25733,25627,25620 ,14245,14134,14127 ,0,0,0}, - {25731,25669,25730 ,14243,14181,14242 ,0,0,0}, {25734,25625,25627 ,14246,14132,14134 ,0,0,0}, - {25732,25618,25731 ,14244,14125,14243 ,0,0,0}, {25735,25623,25625 ,14247,14130,14132 ,0,0,0}, - {25620,25732,25733 ,14127,14244,14245 ,0,0,0}, {25629,25736,25630 ,14136,14248,14137 ,0,0,0}, - {25627,25733,25734 ,14134,14245,14246 ,0,0,0}, {25651,25737,25652 ,14158,14249,14159 ,0,0,0}, - {25625,25734,25735 ,14132,14246,14247 ,0,0,0}, {25651,25633,25630 ,14158,14140,14137 ,0,0,0}, - {25623,25735,25666 ,14130,14247,14178 ,0,0,0}, {25653,25634,25633 ,14160,14141,14140 ,0,0,0}, - {25629,25666,25736 ,14136,14178,14248 ,0,0,0}, {25638,25634,25738 ,14145,14141,14250 ,0,0,0}, - {25651,25630,25736 ,14158,14137,14248 ,0,0,0}, {25655,25648,25647 ,14162,14155,14154 ,0,0,0}, - {25739,25646,25648 ,14251,14153,14155 ,0,0,0}, {25638,25647,25636 ,14145,14154,14143 ,0,0,0}, - {25738,25634,25653 ,14250,14141,14160 ,0,0,0}, {25655,25640,25648 ,14162,14147,14155 ,0,0,0}, - {25647,25638,25655 ,14154,14145,14162 ,0,0,0}, {25644,25740,25642 ,14151,14252,14149 ,0,0,0}, - {25642,25195,25645 ,14149,14177,14152 ,0,0,0}, {25649,25644,25643 ,14156,14151,14150 ,0,0,0}, - {25644,25739,25740 ,14151,14251,14252 ,0,0,0}, {25197,25195,25642 ,14253,14177,14149 ,0,0,0}, - {25691,25700,25694 ,14203,14212,14206 ,0,0,0}, {25557,25556,25692 ,14064,14063,14204 ,0,0,0}, - {25741,25569,25568 ,14254,14076,14075 ,0,0,0}, {25700,25561,25690 ,14212,14068,14202 ,0,0,0}, - {25700,25691,25742 ,14212,14203,14255 ,0,0,0}, {25553,25560,25743 ,14060,14067,14256 ,0,0,0}, - {25559,25561,25700 ,14066,14068,14212 ,0,0,0}, {25701,25743,25744 ,14213,14256,14257 ,0,0,0}, - {25560,25553,25561 ,14067,14060,14068 ,0,0,0}, {25702,25744,25745 ,14214,14257,14258 ,0,0,0}, - {25743,25701,25553 ,14256,14213,14060 ,0,0,0}, {25703,25745,25746 ,14215,14258,14259 ,0,0,0}, - {25744,25702,25701 ,14257,14214,14213 ,0,0,0}, {25704,25746,25747 ,14216,14259,14260 ,0,0,0}, - {25745,25703,25702 ,14258,14215,14214 ,0,0,0}, {25705,25747,25748 ,14217,14260,14261 ,0,0,0}, - {25746,25704,25703 ,14259,14216,14215 ,0,0,0}, {25706,25748,25749 ,14218,14261,14262 ,0,0,0}, - {25747,25705,25704 ,14260,14217,14216 ,0,0,0}, {25686,25749,25707 ,14198,14262,14219 ,0,0,0}, - {25706,25705,25748 ,14218,14217,14261 ,0,0,0}, {25750,25751,25752 ,14263,14264,14265 ,0,0,0}, - {25686,25706,25749 ,14198,14218,14262 ,0,0,0}, {25710,25708,25750 ,14222,14220,14263 ,0,0,0}, - {25709,25686,25707 ,14221,14198,14219 ,0,0,0}, {25711,25750,25753 ,14223,14263,14266 ,0,0,0}, - {25710,25709,25708 ,14222,14221,14220 ,0,0,0}, {25712,25753,25754 ,14224,14266,14267 ,0,0,0}, - {25750,25711,25710 ,14263,14223,14222 ,0,0,0}, {25713,25754,25755 ,14225,14267,14268 ,0,0,0}, - {25753,25712,25711 ,14266,14224,14223 ,0,0,0}, {25714,25755,25756 ,14226,14268,14269 ,0,0,0}, - {25754,25713,25712 ,14267,14225,14224 ,0,0,0}, {25715,25756,25685 ,14227,14269,14197 ,0,0,0}, - {25714,25713,25755 ,14226,14225,14268 ,0,0,0}, {25757,25758,25759 ,14270,14271,14272 ,0,0,0}, - {25715,25714,25756 ,14227,14226,14269 ,0,0,0}, {25716,25683,25760 ,14228,14195,14273 ,0,0,0}, - {25684,25715,25685 ,14196,14227,14197 ,0,0,0}, {25717,25760,25761 ,14229,14273,14274 ,0,0,0}, - {25683,25716,25684 ,14195,14228,14196 ,0,0,0}, {25718,25761,25762 ,14230,14274,14275 ,0,0,0}, - {25760,25717,25716 ,14273,14229,14228 ,0,0,0}, {25719,25762,25763 ,14231,14275,14276 ,0,0,0}, - {25761,25718,25717 ,14274,14230,14229 ,0,0,0}, {25720,25763,25676 ,14232,14276,14188 ,0,0,0}, - {25719,25718,25762 ,14231,14230,14275 ,0,0,0}, {25764,25765,25766 ,14277,14278,14279 ,0,0,0}, - {25720,25719,25763 ,14232,14231,14276 ,0,0,0}, {25721,25677,25767 ,14233,14189,14280 ,0,0,0}, - {25675,25720,25676 ,14187,14232,14188 ,0,0,0}, {25722,25767,25768 ,14234,14280,14281 ,0,0,0}, - {25721,25675,25677 ,14233,14187,14189 ,0,0,0}, {25723,25768,25769 ,14235,14281,14282 ,0,0,0}, - {25767,25722,25721 ,14280,14234,14233 ,0,0,0}, {25724,25769,25770 ,14236,14282,14283 ,0,0,0}, - {25768,25723,25722 ,14281,14235,14234 ,0,0,0}, {25725,25770,25771 ,14237,14283,14284 ,0,0,0}, - {25769,25724,25723 ,14282,14236,14235 ,0,0,0}, {25670,25771,25772 ,14182,14284,14285 ,0,0,0}, - {25725,25724,25770 ,14237,14236,14283 ,0,0,0}, {25729,25772,25727 ,14241,14285,14239 ,0,0,0}, - {25670,25725,25771 ,14182,14237,14284 ,0,0,0}, {25730,25727,25773 ,14242,14239,14286 ,0,0,0}, - {25729,25670,25772 ,14241,14182,14285 ,0,0,0}, {25731,25773,25774 ,14243,14286,14287 ,0,0,0}, - {25727,25730,25729 ,14239,14242,14241 ,0,0,0}, {25732,25774,25775 ,14244,14287,14288 ,0,0,0}, - {25773,25731,25730 ,14286,14243,14242 ,0,0,0}, {25733,25775,25776 ,14245,14288,14289 ,0,0,0}, - {25774,25732,25731 ,14287,14244,14243 ,0,0,0}, {25734,25776,25777 ,14246,14289,14290 ,0,0,0}, - {25775,25733,25732 ,14288,14245,14244 ,0,0,0}, {25735,25777,25778 ,14247,14290,14291 ,0,0,0}, - {25776,25734,25733 ,14289,14246,14245 ,0,0,0}, {25666,25778,25779 ,14178,14291,14292 ,0,0,0}, - {25777,25735,25734 ,14290,14247,14246 ,0,0,0}, {25736,25779,25737 ,14248,14292,14249 ,0,0,0}, - {25666,25735,25778 ,14178,14247,14291 ,0,0,0}, {25780,25653,25652 ,14293,14160,14159 ,0,0,0}, - {25736,25666,25779 ,14248,14178,14292 ,0,0,0}, {25662,25781,25657 ,14170,14294,14164 ,0,0,0}, - {25651,25736,25737 ,14158,14248,14249 ,0,0,0}, {25780,25641,25738 ,14293,14148,14250 ,0,0,0}, - {25640,25782,25648 ,14147,14295,14155 ,0,0,0}, {25738,25655,25638 ,14250,14162,14145 ,0,0,0}, - {25780,25738,25653 ,14293,14250,14160 ,0,0,0}, {25783,25740,25739 ,14296,14252,14251 ,0,0,0}, - {25738,25641,25655 ,14250,14148,14162 ,0,0,0}, {25198,25740,25783 ,14297,14252,14296 ,0,0,0}, - {25740,25197,25642 ,14252,14253,14149 ,0,0,0}, {25646,25739,25644 ,14153,14251,14151 ,0,0,0}, - {25782,25783,25739 ,14295,14296,14251 ,0,0,0}, {25198,25197,25740 ,14297,14253,14252 ,0,0,0}, - {25742,25691,25556 ,14255,14203,14063 ,0,0,0}, {25688,25558,25698 ,14200,14065,14210 ,0,0,0}, - {25784,25560,25566 ,14298,14067,14073 ,0,0,0}, {25742,25559,25700 ,14255,14066,14212 ,0,0,0}, - {25742,25556,25785 ,14255,14063,14299 ,0,0,0}, {25786,25787,25788 ,14300,14301,14302 ,0,0,0}, - {25565,25559,25742 ,14072,14066,14255 ,0,0,0}, {25784,25786,25743 ,14298,14300,14256 ,0,0,0}, - {25566,25560,25559 ,14073,14067,14066 ,0,0,0}, {25786,25789,25744 ,14300,14303,14257 ,0,0,0}, - {25784,25743,25560 ,14298,14256,14067 ,0,0,0}, {25789,25790,25745 ,14303,14304,14258 ,0,0,0}, - {25786,25744,25743 ,14300,14257,14256 ,0,0,0}, {25790,25791,25746 ,14304,14305,14259 ,0,0,0}, - {25789,25745,25744 ,14303,14258,14257 ,0,0,0}, {25791,25792,25747 ,14305,14306,14260 ,0,0,0}, - {25790,25746,25745 ,14304,14259,14258 ,0,0,0}, {25792,25793,25748 ,14306,14307,14261 ,0,0,0}, - {25791,25747,25746 ,14305,14260,14259 ,0,0,0}, {25793,25794,25749 ,14307,14308,14262 ,0,0,0}, - {25792,25748,25747 ,14306,14261,14260 ,0,0,0}, {25794,25795,25707 ,14308,14309,14219 ,0,0,0}, - {25793,25749,25748 ,14307,14262,14261 ,0,0,0}, {25795,25751,25708 ,14309,14264,14220 ,0,0,0}, - {25707,25749,25794 ,14219,14262,14308 ,0,0,0}, {25796,25797,25798 ,14310,14311,14312 ,0,0,0}, - {25708,25707,25795 ,14220,14219,14309 ,0,0,0}, {25752,25796,25753 ,14265,14310,14266 ,0,0,0}, - {25751,25750,25708 ,14264,14263,14220 ,0,0,0}, {25796,25799,25754 ,14310,14313,14267 ,0,0,0}, - {25752,25753,25750 ,14265,14266,14263 ,0,0,0}, {25799,25800,25755 ,14313,14314,14268 ,0,0,0}, - {25796,25754,25753 ,14310,14267,14266 ,0,0,0}, {25800,25801,25756 ,14314,14315,14269 ,0,0,0}, - {25799,25755,25754 ,14313,14268,14267 ,0,0,0}, {25801,25802,25685 ,14315,14316,14197 ,0,0,0}, - {25800,25756,25755 ,14314,14269,14268 ,0,0,0}, {25683,25802,25803 ,14195,14316,14317 ,0,0,0}, - {25685,25756,25801 ,14197,14269,14315 ,0,0,0}, {25803,25757,25760 ,14317,14270,14273 ,0,0,0}, - {25802,25683,25685 ,14316,14195,14197 ,0,0,0}, {25757,25804,25761 ,14270,14318,14274 ,0,0,0}, - {25803,25760,25683 ,14317,14273,14195 ,0,0,0}, {25804,25805,25762 ,14318,14319,14275 ,0,0,0}, - {25757,25761,25760 ,14270,14274,14273 ,0,0,0}, {25805,25806,25763 ,14319,14320,14276 ,0,0,0}, - {25804,25762,25761 ,14318,14275,14274 ,0,0,0}, {25806,25807,25676 ,14320,14321,14188 ,0,0,0}, - {25805,25763,25762 ,14319,14276,14275 ,0,0,0}, {25807,25808,25677 ,14321,14322,14189 ,0,0,0}, - {25676,25763,25806 ,14188,14276,14320 ,0,0,0}, {25808,25764,25767 ,14322,14277,14280 ,0,0,0}, - {25677,25676,25807 ,14189,14188,14321 ,0,0,0}, {25764,25809,25768 ,14277,14323,14281 ,0,0,0}, - {25808,25767,25677 ,14322,14280,14189 ,0,0,0}, {25809,25810,25769 ,14323,14324,14282 ,0,0,0}, - {25764,25768,25767 ,14277,14281,14280 ,0,0,0}, {25810,25811,25770 ,14324,14325,14283 ,0,0,0}, - {25809,25769,25768 ,14323,14282,14281 ,0,0,0}, {25811,25812,25771 ,14325,14326,14284 ,0,0,0}, - {25810,25770,25769 ,14324,14283,14282 ,0,0,0}, {25812,25728,25772 ,14326,14240,14285 ,0,0,0}, - {25771,25770,25811 ,14284,14283,14325 ,0,0,0}, {25813,25814,25815 ,14327,14328,14329 ,0,0,0}, - {25772,25771,25812 ,14285,14284,14326 ,0,0,0}, {25726,25813,25773 ,14238,14327,14286 ,0,0,0}, - {25728,25727,25772 ,14240,14239,14285 ,0,0,0}, {25813,25816,25774 ,14327,14330,14287 ,0,0,0}, - {25726,25773,25727 ,14238,14286,14239 ,0,0,0}, {25816,25817,25775 ,14330,14331,14288 ,0,0,0}, - {25813,25774,25773 ,14327,14287,14286 ,0,0,0}, {25817,25818,25776 ,14331,14332,14289 ,0,0,0}, - {25816,25775,25774 ,14330,14288,14287 ,0,0,0}, {25818,25819,25777 ,14332,14333,14290 ,0,0,0}, - {25817,25776,25775 ,14331,14289,14288 ,0,0,0}, {25819,25820,25778 ,14333,14334,14291 ,0,0,0}, - {25818,25777,25776 ,14332,14290,14289 ,0,0,0}, {25820,25821,25779 ,14334,14335,14292 ,0,0,0}, - {25819,25778,25777 ,14333,14291,14290 ,0,0,0}, {25821,25822,25737 ,14335,14336,14249 ,0,0,0}, - {25820,25779,25778 ,14334,14292,14291 ,0,0,0}, {25822,25823,25652 ,14336,14337,14159 ,0,0,0}, - {25821,25737,25779 ,14335,14249,14292 ,0,0,0}, {25823,25654,25780 ,14337,14161,14293 ,0,0,0}, - {25652,25737,25822 ,14159,14249,14336 ,0,0,0}, {25824,25194,25056 ,14338,14339,14340 ,0,0,0}, - {25823,25780,25652 ,14337,14293,14159 ,0,0,0}, {25656,25639,25654 ,14163,14146,14161 ,0,0,0}, - {25780,25654,25641 ,14293,14161,14148 ,0,0,0}, {25189,25783,25824 ,14341,14296,14338 ,0,0,0}, - {25189,25200,25783 ,14341,14342,14296 ,0,0,0}, {25648,25782,25739 ,14155,14295,14251 ,0,0,0}, - {25658,25824,25782 ,14165,14338,14295 ,0,0,0}, {25198,25783,25200 ,14297,14296,14342 ,0,0,0}, - {25558,25785,25556 ,14065,14299,14063 ,0,0,0}, {25699,25562,25688 ,14211,14069,14200 ,0,0,0}, - {25565,25825,25826 ,14072,14343,14344 ,0,0,0}, {25785,25565,25742 ,14299,14072,14255 ,0,0,0}, - {25827,25785,25558 ,14345,14299,14065 ,0,0,0}, {25566,25826,25828 ,14073,14344,14346 ,0,0,0}, - {25785,25825,25565 ,14299,14343,14072 ,0,0,0}, {25784,25828,25787 ,14298,14346,14301 ,0,0,0}, - {25826,25566,25565 ,14344,14073,14072 ,0,0,0}, {25829,25789,25788 ,14347,14303,14302 ,0,0,0}, - {25828,25784,25566 ,14346,14298,14073 ,0,0,0}, {25830,25790,25829 ,14348,14304,14347 ,0,0,0}, - {25787,25786,25784 ,14301,14300,14298 ,0,0,0}, {25831,25832,25833 ,14349,14350,14351 ,0,0,0}, - {25788,25789,25786 ,14302,14303,14300 ,0,0,0}, {25830,25831,25791 ,14348,14349,14305 ,0,0,0}, - {25829,25790,25789 ,14347,14304,14303 ,0,0,0}, {25831,25834,25792 ,14349,14352,14306 ,0,0,0}, - {25830,25791,25790 ,14348,14305,14304 ,0,0,0}, {25834,25835,25793 ,14352,14353,14307 ,0,0,0}, - {25831,25792,25791 ,14349,14306,14305 ,0,0,0}, {25835,25836,25794 ,14353,14354,14308 ,0,0,0}, - {25834,25793,25792 ,14352,14307,14306 ,0,0,0}, {25836,25837,25795 ,14354,14355,14309 ,0,0,0}, - {25835,25794,25793 ,14353,14308,14307 ,0,0,0}, {25751,25837,25838 ,14264,14355,14356 ,0,0,0}, - {25836,25795,25794 ,14354,14309,14308 ,0,0,0}, {25752,25838,25797 ,14265,14356,14311 ,0,0,0}, - {25837,25751,25795 ,14355,14264,14309 ,0,0,0}, {25839,25840,25841 ,14357,14358,14359 ,0,0,0}, - {25838,25752,25751 ,14356,14265,14264 ,0,0,0}, {25798,25839,25799 ,14312,14357,14313 ,0,0,0}, - {25797,25796,25752 ,14311,14310,14265 ,0,0,0}, {25839,25842,25800 ,14357,14360,14314 ,0,0,0}, - {25798,25799,25796 ,14312,14313,14310 ,0,0,0}, {25842,25843,25801 ,14360,14361,14315 ,0,0,0}, - {25839,25800,25799 ,14357,14314,14313 ,0,0,0}, {25802,25843,25844 ,14316,14361,14362 ,0,0,0}, - {25842,25801,25800 ,14360,14315,14314 ,0,0,0}, {25803,25844,25758 ,14317,14362,14271 ,0,0,0}, - {25802,25801,25843 ,14316,14315,14361 ,0,0,0}, {25845,25846,25847 ,14363,14364,14365 ,0,0,0}, - {25844,25803,25802 ,14362,14317,14316 ,0,0,0}, {25759,25845,25804 ,14272,14363,14318 ,0,0,0}, - {25758,25757,25803 ,14271,14270,14317 ,0,0,0}, {25845,25848,25805 ,14363,14366,14319 ,0,0,0}, - {25759,25804,25757 ,14272,14318,14270 ,0,0,0}, {25848,25849,25806 ,14366,14367,14320 ,0,0,0}, - {25845,25805,25804 ,14363,14319,14318 ,0,0,0}, {25849,25850,25807 ,14367,14368,14321 ,0,0,0}, - {25848,25806,25805 ,14366,14320,14319 ,0,0,0}, {25808,25850,25765 ,14322,14368,14278 ,0,0,0}, - {25807,25806,25849 ,14321,14320,14367 ,0,0,0}, {25851,25852,25853 ,14369,14370,14371 ,0,0,0}, - {25850,25808,25807 ,14368,14322,14321 ,0,0,0}, {25766,25851,25809 ,14279,14369,14323 ,0,0,0}, - {25765,25764,25808 ,14278,14277,14322 ,0,0,0}, {25851,25854,25810 ,14369,14372,14324 ,0,0,0}, - {25766,25809,25764 ,14279,14323,14277 ,0,0,0}, {25854,25855,25811 ,14372,14373,14325 ,0,0,0}, - {25851,25810,25809 ,14369,14324,14323 ,0,0,0}, {25855,25856,25812 ,14373,14374,14326 ,0,0,0}, - {25854,25811,25810 ,14372,14325,14324 ,0,0,0}, {25728,25856,25857 ,14240,14374,14375 ,0,0,0}, - {25855,25812,25811 ,14373,14326,14325 ,0,0,0}, {25726,25857,25814 ,14238,14375,14328 ,0,0,0}, - {25856,25728,25812 ,14374,14240,14326 ,0,0,0}, {25858,25816,25815 ,14376,14330,14329 ,0,0,0}, - {25857,25726,25728 ,14375,14238,14240 ,0,0,0}, {25859,25860,25861 ,14377,14378,14379 ,0,0,0}, - {25814,25813,25726 ,14328,14327,14238 ,0,0,0}, {25858,25859,25817 ,14376,14377,14331 ,0,0,0}, - {25815,25816,25813 ,14329,14330,14327 ,0,0,0}, {25859,25862,25818 ,14377,14380,14332 ,0,0,0}, - {25858,25817,25816 ,14376,14331,14330 ,0,0,0}, {25862,25863,25819 ,14380,14381,14333 ,0,0,0}, - {25859,25818,25817 ,14377,14332,14331 ,0,0,0}, {25863,25864,25820 ,14381,14382,14334 ,0,0,0}, - {25862,25819,25818 ,14380,14333,14332 ,0,0,0}, {25864,25865,25821 ,14382,14383,14335 ,0,0,0}, - {25863,25820,25819 ,14381,14334,14333 ,0,0,0}, {25865,25866,25822 ,14383,14384,14336 ,0,0,0}, - {25864,25821,25820 ,14382,14335,14334 ,0,0,0}, {25866,25867,25823 ,14384,14385,14337 ,0,0,0}, - {25865,25822,25821 ,14383,14336,14335 ,0,0,0}, {25654,25867,25656 ,14161,14385,14163 ,0,0,0}, - {25823,25822,25866 ,14337,14336,14384 ,0,0,0}, {25661,25656,25867 ,14168,14163,14385 ,0,0,0}, - {25654,25823,25867 ,14161,14337,14385 ,0,0,0}, {25658,25781,25824 ,14165,14294,14338 ,0,0,0}, - {25782,25824,25783 ,14295,14338,14296 ,0,0,0}, {25640,25658,25782 ,14147,14165,14295 ,0,0,0}, - {25657,25781,25658 ,14164,14294,14165 ,0,0,0}, {25189,25824,25056 ,14341,14338,14340 ,0,0,0}, - {25562,25827,25558 ,14069,14345,14065 ,0,0,0}, {25570,25564,25563 ,14077,14071,14070 ,0,0,0}, - {25825,25868,25869 ,14343,14386,14387 ,0,0,0}, {25827,25825,25785 ,14345,14343,14299 ,0,0,0}, - {25562,25870,25827 ,14069,14388,14345 ,0,0,0}, {25826,25869,25871 ,14344,14387,14389 ,0,0,0}, - {25827,25868,25825 ,14345,14386,14343 ,0,0,0}, {25828,25871,25872 ,14346,14389,14390 ,0,0,0}, - {25825,25869,25826 ,14343,14387,14344 ,0,0,0}, {25787,25872,25873 ,14301,14390,14391 ,0,0,0}, - {25826,25871,25828 ,14344,14389,14346 ,0,0,0}, {25788,25873,25874 ,14302,14391,14392 ,0,0,0}, - {25828,25872,25787 ,14346,14390,14301 ,0,0,0}, {25829,25874,25875 ,14347,14392,14393 ,0,0,0}, - {25787,25873,25788 ,14301,14391,14302 ,0,0,0}, {25830,25875,25832 ,14348,14393,14350 ,0,0,0}, - {25874,25829,25788 ,14392,14347,14302 ,0,0,0}, {25876,25834,25833 ,14394,14352,14351 ,0,0,0}, - {25875,25830,25829 ,14393,14348,14347 ,0,0,0}, {25877,25878,25876 ,14395,14396,14394 ,0,0,0}, - {25832,25831,25830 ,14350,14349,14348 ,0,0,0}, {25876,25878,25835 ,14394,14396,14353 ,0,0,0}, - {25833,25834,25831 ,14351,14352,14349 ,0,0,0}, {25878,25879,25836 ,14396,14397,14354 ,0,0,0}, - {25876,25835,25834 ,14394,14353,14352 ,0,0,0}, {25837,25879,25880 ,14355,14397,14398 ,0,0,0}, - {25878,25836,25835 ,14396,14354,14353 ,0,0,0}, {25838,25880,25881 ,14356,14398,14399 ,0,0,0}, - {25836,25879,25837 ,14354,14397,14355 ,0,0,0}, {25797,25881,25882 ,14311,14399,14400 ,0,0,0}, - {25837,25880,25838 ,14355,14398,14356 ,0,0,0}, {25798,25882,25840 ,14312,14400,14358 ,0,0,0}, - {25881,25797,25838 ,14399,14311,14356 ,0,0,0}, {25883,25884,25841 ,14401,14402,14359 ,0,0,0}, - {25882,25798,25797 ,14400,14312,14311 ,0,0,0}, {25841,25884,25842 ,14359,14402,14360 ,0,0,0}, - {25840,25839,25798 ,14358,14357,14312 ,0,0,0}, {25884,25885,25843 ,14402,14403,14361 ,0,0,0}, - {25841,25842,25839 ,14359,14360,14357 ,0,0,0}, {25844,25885,25886 ,14362,14403,14404 ,0,0,0}, - {25884,25843,25842 ,14402,14361,14360 ,0,0,0}, {25758,25886,25887 ,14271,14404,14405 ,0,0,0}, - {25843,25885,25844 ,14361,14403,14362 ,0,0,0}, {25759,25887,25846 ,14272,14405,14364 ,0,0,0}, - {25886,25758,25844 ,14404,14271,14362 ,0,0,0}, {25888,25889,25847 ,14406,14407,14365 ,0,0,0}, - {25887,25759,25758 ,14405,14272,14271 ,0,0,0}, {25847,25889,25848 ,14365,14407,14366 ,0,0,0}, - {25846,25845,25759 ,14364,14363,14272 ,0,0,0}, {25889,25890,25849 ,14407,14408,14367 ,0,0,0}, - {25847,25848,25845 ,14365,14366,14363 ,0,0,0}, {25850,25890,25891 ,14368,14408,14409 ,0,0,0}, - {25889,25849,25848 ,14407,14367,14366 ,0,0,0}, {25765,25891,25892 ,14278,14409,14410 ,0,0,0}, - {25849,25890,25850 ,14367,14408,14368 ,0,0,0}, {25766,25892,25852 ,14279,14410,14370 ,0,0,0}, - {25891,25765,25850 ,14409,14278,14368 ,0,0,0}, {25893,25894,25853 ,14411,14412,14371 ,0,0,0}, - {25892,25766,25765 ,14410,14279,14278 ,0,0,0}, {25853,25894,25854 ,14371,14412,14372 ,0,0,0}, - {25852,25851,25766 ,14370,14369,14279 ,0,0,0}, {25894,25895,25855 ,14412,14413,14373 ,0,0,0}, - {25853,25854,25851 ,14371,14372,14369 ,0,0,0}, {25856,25895,25896 ,14374,14413,14414 ,0,0,0}, - {25894,25855,25854 ,14412,14373,14372 ,0,0,0}, {25857,25896,25897 ,14375,14414,14415 ,0,0,0}, - {25855,25895,25856 ,14373,14413,14374 ,0,0,0}, {25814,25897,25898 ,14328,14415,14416 ,0,0,0}, - {25856,25896,25857 ,14374,14414,14375 ,0,0,0}, {25815,25898,25899 ,14329,14416,14417 ,0,0,0}, - {25857,25897,25814 ,14375,14415,14328 ,0,0,0}, {25858,25899,25860 ,14376,14417,14378 ,0,0,0}, - {25898,25815,25814 ,14416,14329,14328 ,0,0,0}, {25900,25862,25861 ,14418,14380,14379 ,0,0,0}, - {25899,25858,25815 ,14417,14376,14329 ,0,0,0}, {25901,25902,25900 ,14419,14420,14418 ,0,0,0}, - {25860,25859,25858 ,14378,14377,14376 ,0,0,0}, {25900,25902,25863 ,14418,14420,14381 ,0,0,0}, - {25861,25862,25859 ,14379,14380,14377 ,0,0,0}, {25902,25903,25864 ,14420,14421,14382 ,0,0,0}, - {25900,25863,25862 ,14418,14381,14380 ,0,0,0}, {25903,25904,25865 ,14421,14422,14383 ,0,0,0}, - {25902,25864,25863 ,14420,14382,14381 ,0,0,0}, {25904,25905,25866 ,14422,14423,14384 ,0,0,0}, - {25903,25865,25864 ,14421,14383,14382 ,0,0,0}, {25867,25905,25661 ,14385,14423,14168 ,0,0,0}, - {25904,25866,25865 ,14422,14384,14383 ,0,0,0}, {25661,25906,25656 ,14168,14424,14163 ,0,0,0}, - {25866,25905,25867 ,14384,14423,14385 ,0,0,0}, {25061,25781,25662 ,14425,14294,14170 ,0,0,0}, - {25781,25194,25824 ,14294,14339,14338 ,0,0,0}, {25639,25657,25658 ,14146,14164,14165 ,0,0,0}, - {25906,25662,25657 ,14424,14170,14164 ,0,0,0}, {25061,25194,25781 ,14425,14339,14294 ,0,0,0}, - {25564,25870,25562 ,14071,14388,14069 ,0,0,0}, {25907,25569,25570 ,14426,14076,14077 ,0,0,0}, - {25908,25868,25870 ,14427,14386,14388 ,0,0,0}, {25870,25868,25827 ,14388,14386,14345 ,0,0,0}, - {25870,25741,25908 ,14388,14254,14427 ,0,0,0}, {25909,25869,25868 ,14428,14387,14386 ,0,0,0}, - {25868,25908,25909 ,14386,14427,14428 ,0,0,0}, {25910,25871,25869 ,14429,14389,14387 ,0,0,0}, - {25869,25909,25910 ,14387,14428,14429 ,0,0,0}, {25911,25872,25871 ,14430,14390,14389 ,0,0,0}, - {25871,25910,25911 ,14389,14429,14430 ,0,0,0}, {25912,25873,25872 ,14431,14391,14390 ,0,0,0}, - {25872,25911,25912 ,14390,14430,14431 ,0,0,0}, {25913,25874,25873 ,14432,14392,14391 ,0,0,0}, - {25873,25912,25913 ,14391,14431,14432 ,0,0,0}, {25914,25875,25874 ,14433,14393,14392 ,0,0,0}, - {25874,25913,25914 ,14392,14432,14433 ,0,0,0}, {25915,25832,25875 ,14434,14350,14393 ,0,0,0}, - {25875,25914,25915 ,14393,14433,14434 ,0,0,0}, {25916,25833,25832 ,14435,14351,14350 ,0,0,0}, - {25832,25915,25916 ,14350,14434,14435 ,0,0,0}, {25917,25876,25833 ,14436,14394,14351 ,0,0,0}, - {25916,25917,25833 ,14435,14436,14351 ,0,0,0}, {25918,25919,25920 ,14437,14438,14439 ,0,0,0}, - {25917,25877,25876 ,14436,14395,14394 ,0,0,0}, {25921,25879,25878 ,14440,14397,14396 ,0,0,0}, - {25877,25921,25878 ,14395,14440,14396 ,0,0,0}, {25922,25880,25879 ,14441,14398,14397 ,0,0,0}, - {25879,25921,25922 ,14397,14440,14441 ,0,0,0}, {25923,25881,25880 ,14442,14399,14398 ,0,0,0}, - {25880,25922,25923 ,14398,14441,14442 ,0,0,0}, {25924,25882,25881 ,14443,14400,14399 ,0,0,0}, - {25881,25923,25924 ,14399,14442,14443 ,0,0,0}, {25925,25840,25882 ,14444,14358,14400 ,0,0,0}, - {25882,25924,25925 ,14400,14443,14444 ,0,0,0}, {25926,25841,25840 ,14445,14359,14358 ,0,0,0}, - {25925,25926,25840 ,14444,14445,14358 ,0,0,0}, {25927,25883,25928 ,14446,14401,14447 ,0,0,0}, - {25926,25883,25841 ,14445,14401,14359 ,0,0,0}, {25927,25885,25884 ,14446,14403,14402 ,0,0,0}, - {25883,25927,25884 ,14401,14446,14402 ,0,0,0}, {25929,25886,25885 ,14448,14404,14403 ,0,0,0}, - {25885,25927,25929 ,14403,14446,14448 ,0,0,0}, {25930,25887,25886 ,14449,14405,14404 ,0,0,0}, - {25886,25929,25930 ,14404,14448,14449 ,0,0,0}, {25931,25846,25887 ,14450,14364,14405 ,0,0,0}, - {25887,25930,25931 ,14405,14449,14450 ,0,0,0}, {25932,25847,25846 ,14451,14365,14364 ,0,0,0}, - {25931,25932,25846 ,14450,14451,14364 ,0,0,0}, {25933,25934,25935 ,14452,14453,14454 ,0,0,0}, - {25932,25888,25847 ,14451,14406,14365 ,0,0,0}, {25936,25890,25889 ,14455,14408,14407 ,0,0,0}, - {25888,25936,25889 ,14406,14455,14407 ,0,0,0}, {25937,25891,25890 ,14456,14409,14408 ,0,0,0}, - {25890,25936,25937 ,14408,14455,14456 ,0,0,0}, {25938,25892,25891 ,14457,14410,14409 ,0,0,0}, - {25891,25937,25938 ,14409,14456,14457 ,0,0,0}, {25939,25852,25892 ,14458,14370,14410 ,0,0,0}, - {25892,25938,25939 ,14410,14457,14458 ,0,0,0}, {25940,25853,25852 ,14459,14371,14370 ,0,0,0}, - {25939,25940,25852 ,14458,14459,14370 ,0,0,0}, {25894,25941,25895 ,14412,14460,14413 ,0,0,0}, - {25940,25893,25853 ,14459,14411,14371 ,0,0,0}, {25942,25943,25941 ,14461,14462,14460 ,0,0,0}, - {25893,25941,25894 ,14411,14460,14412 ,0,0,0}, {25943,25896,25895 ,14462,14414,14413 ,0,0,0}, - {25895,25941,25943 ,14413,14460,14462 ,0,0,0}, {25944,25897,25896 ,14463,14415,14414 ,0,0,0}, - {25896,25943,25944 ,14414,14462,14463 ,0,0,0}, {25945,25898,25897 ,14464,14416,14415 ,0,0,0}, - {25897,25944,25945 ,14415,14463,14464 ,0,0,0}, {25946,25899,25898 ,14465,14417,14416 ,0,0,0}, - {25898,25945,25946 ,14416,14464,14465 ,0,0,0}, {25947,25860,25899 ,14466,14378,14417 ,0,0,0}, - {25899,25946,25947 ,14417,14465,14466 ,0,0,0}, {25948,25861,25860 ,14467,14379,14378 ,0,0,0}, - {25860,25947,25948 ,14378,14466,14467 ,0,0,0}, {25949,25900,25861 ,14468,14418,14379 ,0,0,0}, - {25948,25949,25861 ,14467,14468,14379 ,0,0,0}, {25902,25950,25903 ,14420,14469,14421 ,0,0,0}, - {25949,25901,25900 ,14468,14419,14418 ,0,0,0}, {25903,25951,25904 ,14421,14470,14422 ,0,0,0}, - {25901,25950,25902 ,14419,14469,14420 ,0,0,0}, {25904,25952,25905 ,14422,14471,14423 ,0,0,0}, - {25950,25951,25903 ,14469,14470,14421 ,0,0,0}, {25905,25659,25661 ,14423,14166,14168 ,0,0,0}, - {25951,25952,25904 ,14470,14471,14422 ,0,0,0}, {25660,25664,25663 ,14167,14172,14171 ,0,0,0}, - {25952,25659,25905 ,14471,14166,14423 ,0,0,0}, {25660,25906,25661 ,14167,14424,14168 ,0,0,0}, - {25243,25061,25662 ,14472,14425,14170 ,0,0,0}, {25656,25906,25657 ,14163,14424,14164 ,0,0,0}, - {25906,25660,25663 ,14424,14167,14171 ,0,0,0}, {25058,25243,25662 ,14169,14472,14170 ,0,0,0}, - {25569,25741,25564 ,14076,14254,14071 ,0,0,0}, {25907,25572,25567 ,14426,14079,14074 ,0,0,0}, - {25908,25741,25953 ,14427,14254,14473 ,0,0,0}, {25564,25741,25870 ,14071,14254,14388 ,0,0,0}, - {25741,25568,25953 ,14254,14075,14473 ,0,0,0}, {25909,25908,25954 ,14428,14427,14474 ,0,0,0}, - {25908,25953,25954 ,14427,14473,14474 ,0,0,0}, {25910,25909,25955 ,14429,14428,14475 ,0,0,0}, - {25909,25954,25955 ,14428,14474,14475 ,0,0,0}, {25911,25910,25956 ,14430,14429,14476 ,0,0,0}, - {25910,25955,25956 ,14429,14475,14476 ,0,0,0}, {25912,25911,25957 ,14431,14430,14477 ,0,0,0}, - {25911,25956,25957 ,14430,14476,14477 ,0,0,0}, {25913,25912,25958 ,14432,14431,14478 ,0,0,0}, - {25912,25957,25958 ,14431,14477,14478 ,0,0,0}, {25914,25913,25959 ,14433,14432,14479 ,0,0,0}, - {25913,25958,25959 ,14432,14478,14479 ,0,0,0}, {25915,25914,25960 ,14434,14433,14480 ,0,0,0}, - {25914,25959,25960 ,14433,14479,14480 ,0,0,0}, {25916,25915,25961 ,14435,14434,14481 ,0,0,0}, - {25915,25960,25961 ,14434,14480,14481 ,0,0,0}, {25917,25916,25962 ,14436,14435,14482 ,0,0,0}, - {25916,25961,25962 ,14435,14481,14482 ,0,0,0}, {25877,25917,25963 ,14395,14436,14483 ,0,0,0}, - {25917,25962,25963 ,14436,14482,14483 ,0,0,0}, {25921,25877,25918 ,14440,14395,14437 ,0,0,0}, - {25963,25918,25877 ,14483,14437,14395 ,0,0,0}, {25922,25921,25920 ,14441,14440,14439 ,0,0,0}, - {25921,25918,25920 ,14440,14437,14439 ,0,0,0}, {25923,25922,25964 ,14442,14441,14484 ,0,0,0}, - {25922,25920,25964 ,14441,14439,14484 ,0,0,0}, {25924,25923,25965 ,14443,14442,14485 ,0,0,0}, - {25923,25964,25965 ,14442,14484,14485 ,0,0,0}, {25925,25924,25966 ,14444,14443,14486 ,0,0,0}, - {25924,25965,25966 ,14443,14485,14486 ,0,0,0}, {25926,25925,25967 ,14445,14444,14487 ,0,0,0}, - {25925,25966,25967 ,14444,14486,14487 ,0,0,0}, {25883,25926,25968 ,14401,14445,14488 ,0,0,0}, - {25926,25967,25968 ,14445,14487,14488 ,0,0,0}, {25968,25969,25928 ,14488,14489,14447 ,0,0,0}, - {25968,25928,25883 ,14488,14447,14401 ,0,0,0}, {25929,25927,25970 ,14448,14446,14490 ,0,0,0}, - {25927,25928,25970 ,14446,14447,14490 ,0,0,0}, {25930,25929,25971 ,14449,14448,14491 ,0,0,0}, - {25929,25970,25971 ,14448,14490,14491 ,0,0,0}, {25931,25930,25972 ,14450,14449,14492 ,0,0,0}, - {25930,25971,25972 ,14449,14491,14492 ,0,0,0}, {25932,25931,25973 ,14451,14450,14493 ,0,0,0}, - {25931,25972,25973 ,14450,14492,14493 ,0,0,0}, {25888,25932,25974 ,14406,14451,14494 ,0,0,0}, - {25932,25973,25974 ,14451,14493,14494 ,0,0,0}, {25936,25888,25933 ,14455,14406,14452 ,0,0,0}, - {25974,25933,25888 ,14494,14452,14406 ,0,0,0}, {25937,25936,25935 ,14456,14455,14454 ,0,0,0}, - {25936,25933,25935 ,14455,14452,14454 ,0,0,0}, {25938,25937,25975 ,14457,14456,14495 ,0,0,0}, - {25937,25935,25975 ,14456,14454,14495 ,0,0,0}, {25939,25938,25976 ,14458,14457,14496 ,0,0,0}, - {25938,25975,25976 ,14457,14495,14496 ,0,0,0}, {25940,25939,25977 ,14459,14458,14497 ,0,0,0}, - {25939,25976,25977 ,14458,14496,14497 ,0,0,0}, {25893,25940,25978 ,14411,14459,14498 ,0,0,0}, - {25940,25977,25978 ,14459,14497,14498 ,0,0,0}, {25941,25893,25979 ,14460,14411,14499 ,0,0,0}, - {25893,25978,25979 ,14411,14498,14499 ,0,0,0}, {25942,25979,25980 ,14461,14499,14500 ,0,0,0}, - {25979,25942,25941 ,14499,14461,14460 ,0,0,0}, {25944,25943,25981 ,14463,14462,14501 ,0,0,0}, - {25943,25942,25981 ,14462,14461,14501 ,0,0,0}, {25945,25944,25982 ,14464,14463,14502 ,0,0,0}, - {25944,25981,25982 ,14463,14501,14502 ,0,0,0}, {25946,25945,25983 ,14465,14464,14503 ,0,0,0}, - {25945,25982,25983 ,14464,14502,14503 ,0,0,0}, {25947,25946,25984 ,14466,14465,14504 ,0,0,0}, - {25946,25983,25984 ,14465,14503,14504 ,0,0,0}, {25948,25947,25985 ,14467,14466,14505 ,0,0,0}, - {25947,25984,25985 ,14466,14504,14505 ,0,0,0}, {25949,25948,25986 ,14468,14467,14506 ,0,0,0}, - {25948,25985,25986 ,14467,14505,14506 ,0,0,0}, {25901,25949,25987 ,14419,14468,14507 ,0,0,0}, - {25949,25986,25987 ,14468,14506,14507 ,0,0,0}, {25950,25901,25988 ,14469,14419,14508 ,0,0,0}, - {25901,25987,25988 ,14419,14507,14508 ,0,0,0}, {25951,25950,25989 ,14470,14469,14509 ,0,0,0}, - {25950,25988,25989 ,14469,14508,14509 ,0,0,0}, {25952,25951,25990 ,14471,14470,14510 ,0,0,0}, - {25951,25989,25990 ,14470,14509,14510 ,0,0,0}, {25659,25952,25991 ,14166,14471,14511 ,0,0,0}, - {25952,25990,25991 ,14471,14510,14511 ,0,0,0}, {25992,25660,25659 ,14512,14167,14166 ,0,0,0}, - {25991,25992,25659 ,14511,14512,14166 ,0,0,0}, {25906,25663,25662 ,14424,14171,14170 ,0,0,0}, - {25992,25664,25660 ,14512,14172,14167 ,0,0,0}, {25058,25663,25413 ,14169,14171,14173 ,0,0,0}, - {25567,25569,25907 ,14074,14076,14426 ,0,0,0}, {25576,25573,25567 ,14083,14080,14074 ,0,0,0}, - {25573,25993,25568 ,14080,14513,14075 ,0,0,0}, {25568,25993,25953 ,14075,14513,14473 ,0,0,0}, - {25993,25994,25953 ,14513,14514,14473 ,0,0,0}, {25953,25994,25954 ,14473,14514,14474 ,0,0,0}, - {25994,25995,25954 ,14514,14515,14474 ,0,0,0}, {25954,25995,25955 ,14474,14515,14475 ,0,0,0}, - {25995,25996,25955 ,14515,14516,14475 ,0,0,0}, {25955,25996,25956 ,14475,14516,14476 ,0,0,0}, - {25996,25997,25956 ,14516,14517,14476 ,0,0,0}, {25956,25997,25957 ,14476,14517,14477 ,0,0,0}, - {25997,25998,25957 ,14517,14518,14477 ,0,0,0}, {25957,25998,25958 ,14477,14518,14478 ,0,0,0}, - {25998,25999,25958 ,14518,14519,14478 ,0,0,0}, {25958,25999,25959 ,14478,14519,14479 ,0,0,0}, - {25999,26000,25959 ,14519,14520,14479 ,0,0,0}, {26000,26001,25960 ,14520,14521,14480 ,0,0,0}, - {26000,25960,25959 ,14520,14480,14479 ,0,0,0}, {26001,26002,25961 ,14521,14522,14481 ,0,0,0}, - {26001,25961,25960 ,14521,14481,14480 ,0,0,0}, {26002,26003,25962 ,14522,14523,14482 ,0,0,0}, - {26002,25962,25961 ,14522,14482,14481 ,0,0,0}, {26003,26004,25963 ,14523,14524,14483 ,0,0,0}, - {26003,25963,25962 ,14523,14483,14482 ,0,0,0}, {26004,26005,25918 ,14524,14525,14437 ,0,0,0}, - {26004,25918,25963 ,14524,14437,14483 ,0,0,0}, {25919,25918,26005 ,14438,14437,14525 ,0,0,0}, - {25919,26006,25920 ,14438,14526,14439 ,0,0,0}, {25920,26006,25964 ,14439,14526,14484 ,0,0,0}, - {26006,26007,25964 ,14526,14527,14484 ,0,0,0}, {25964,26007,25965 ,14484,14527,14485 ,0,0,0}, - {26007,26008,25965 ,14527,14528,14485 ,0,0,0}, {26008,26009,25966 ,14528,14529,14486 ,0,0,0}, - {26008,25966,25965 ,14528,14486,14485 ,0,0,0}, {26009,26010,25967 ,14529,14530,14487 ,0,0,0}, - {26009,25967,25966 ,14529,14487,14486 ,0,0,0}, {26010,25969,25968 ,14530,14489,14488 ,0,0,0}, - {26010,25968,25967 ,14530,14488,14487 ,0,0,0}, {25969,26011,25928 ,14489,14531,14447 ,0,0,0}, - {26011,26012,25928 ,14531,14532,14447 ,0,0,0}, {25928,26012,25970 ,14447,14532,14490 ,0,0,0}, - {26012,26013,25970 ,14532,14533,14490 ,0,0,0}, {25970,26013,25971 ,14490,14533,14491 ,0,0,0}, - {26013,26014,25971 ,14533,14534,14491 ,0,0,0}, {26014,26015,25972 ,14534,14535,14492 ,0,0,0}, - {26014,25972,25971 ,14534,14492,14491 ,0,0,0}, {26015,26016,25973 ,14535,14536,14493 ,0,0,0}, - {26015,25973,25972 ,14535,14493,14492 ,0,0,0}, {26016,26017,25974 ,14536,14537,14494 ,0,0,0}, - {26016,25974,25973 ,14536,14494,14493 ,0,0,0}, {26017,26018,25933 ,14537,14538,14452 ,0,0,0}, - {26017,25933,25974 ,14537,14452,14494 ,0,0,0}, {25934,25933,26018 ,14453,14452,14538 ,0,0,0}, - {25934,26019,25935 ,14453,14539,14454 ,0,0,0}, {25935,26019,25975 ,14454,14539,14495 ,0,0,0}, - {26019,26020,25975 ,14539,14540,14495 ,0,0,0}, {26020,26021,25976 ,14540,14541,14496 ,0,0,0}, - {26020,25976,25975 ,14540,14496,14495 ,0,0,0}, {26021,26022,25977 ,14541,14542,14497 ,0,0,0}, - {26021,25977,25976 ,14541,14497,14496 ,0,0,0}, {26022,26023,25978 ,14542,14543,14498 ,0,0,0}, - {26022,25978,25977 ,14542,14498,14497 ,0,0,0}, {26023,25980,25979 ,14543,14500,14499 ,0,0,0}, - {26023,25979,25978 ,14543,14499,14498 ,0,0,0}, {25980,26024,25942 ,14500,14544,14461 ,0,0,0}, - {26024,26025,25942 ,14544,14545,14461 ,0,0,0}, {25942,26025,25981 ,14461,14545,14501 ,0,0,0}, - {26025,26026,25981 ,14545,14546,14501 ,0,0,0}, {25981,26026,25982 ,14501,14546,14502 ,0,0,0}, - {26026,26027,25982 ,14546,14547,14502 ,0,0,0}, {25982,26027,25983 ,14502,14547,14503 ,0,0,0}, - {26027,26028,25983 ,14547,14548,14503 ,0,0,0}, {26028,26029,25984 ,14548,14549,14504 ,0,0,0}, - {26028,25984,25983 ,14548,14504,14503 ,0,0,0}, {26029,26030,25985 ,14549,14550,14505 ,0,0,0}, - {26029,25985,25984 ,14549,14505,14504 ,0,0,0}, {26030,26031,25986 ,14550,14551,14506 ,0,0,0}, - {26030,25986,25985 ,14550,14506,14505 ,0,0,0}, {26031,26032,25987 ,14551,14552,14507 ,0,0,0}, - {26031,25987,25986 ,14551,14507,14506 ,0,0,0}, {26032,26033,25988 ,14552,14553,14508 ,0,0,0}, - {26032,25988,25987 ,14552,14508,14507 ,0,0,0}, {26033,26034,25989 ,14553,14554,14509 ,0,0,0}, - {26033,25989,25988 ,14553,14509,14508 ,0,0,0}, {26034,26035,25990 ,14554,14555,14510 ,0,0,0}, - {26034,25990,25989 ,14554,14510,14509 ,0,0,0}, {26035,26036,25991 ,14555,14556,14511 ,0,0,0}, - {26035,25991,25990 ,14555,14511,14510 ,0,0,0}, {26036,26037,25992 ,14556,14557,14512 ,0,0,0}, - {26036,25992,25991 ,14556,14512,14511 ,0,0,0}, {25665,25992,26037 ,14175,14512,14557 ,0,0,0}, - {25992,25665,25664 ,14512,14175,14172 ,0,0,0}, {25066,25664,25665 ,14174,14172,14175 ,0,0,0}, - {26038,26039,26009 ,14558,14559,14560 ,0,0,0}, {26009,26008,26038 ,14560,14561,14558 ,0,0,0}, - {26040,26041,26042 ,14562,14563,14564 ,0,0,0}, {26043,26007,26006 ,14565,14566,14567 ,0,0,0}, - {26008,26007,26044 ,14561,14566,14568 ,0,0,0}, {26043,26044,26007 ,14565,14568,14566 ,0,0,0}, - {25919,26005,26045 ,14569,14570,14571 ,0,0,0}, {26046,25919,26045 ,14572,14569,14571 ,0,0,0}, - {26006,25919,26046 ,14567,14569,14572 ,0,0,0}, {26045,26004,26047 ,14571,14573,14574 ,0,0,0}, - {26006,26046,26043 ,14567,14572,14565 ,0,0,0}, {26045,26005,26004 ,14571,14570,14573 ,0,0,0}, - {26044,26038,26008 ,14568,14558,14561 ,0,0,0}, {26048,26003,26002 ,14575,14576,14577 ,0,0,0}, - {26048,26047,26003 ,14575,14574,14576 ,0,0,0}, {26049,26048,26002 ,14578,14575,14577 ,0,0,0}, - {26050,26051,26052 ,14579,14580,14581 ,0,0,0}, {26053,26049,26001 ,14582,14578,14583 ,0,0,0}, - {26000,26053,26001 ,14584,14582,14583 ,0,0,0}, {26054,26000,25999 ,14585,14584,14586 ,0,0,0}, - {26053,26000,26054 ,14582,14584,14585 ,0,0,0}, {26055,26054,25999 ,14587,14585,14586 ,0,0,0}, - {26001,26049,26002 ,14583,14578,14577 ,0,0,0}, {26047,26004,26003 ,14574,14573,14576 ,0,0,0}, - {26056,25997,26057 ,14588,14589,14590 ,0,0,0}, {25998,26056,26055 ,14591,14588,14587 ,0,0,0}, - {25996,26058,26057 ,14592,14593,14590 ,0,0,0}, {25998,25997,26056 ,14591,14589,14588 ,0,0,0}, - {26058,25995,26059 ,14593,14594,14595 ,0,0,0}, {25995,26058,25996 ,14594,14593,14592 ,0,0,0}, - {26059,25994,26060 ,14595,14596,14597 ,0,0,0}, {25997,25996,26057 ,14589,14592,14590 ,0,0,0}, - {25995,25994,26059 ,14594,14596,14595 ,0,0,0}, {26059,26061,26062 ,14595,14598,14599 ,0,0,0}, - {25693,26063,25697 ,14600,14601,14209 ,0,0,0}, {26064,26065,26066 ,14602,14603,14604 ,0,0,0}, - {26063,26067,25697 ,14601,14605,14209 ,0,0,0}, {26068,26069,26070 ,14606,14607,14608 ,0,0,0}, - {26063,25693,26068 ,14601,14600,14606 ,0,0,0}, {26060,25994,25993 ,14597,14596,14609 ,0,0,0}, - {26062,26071,26072 ,14599,14610,14611 ,0,0,0}, {26073,26074,26072 ,14612,14613,14611 ,0,0,0}, - {26072,26071,26075 ,14611,14610,14614 ,0,0,0}, {25993,25573,26076 ,14609,14615,14616 ,0,0,0}, - {26077,26078,26079 ,14617,14618,14619 ,0,0,0}, {26078,26080,26081 ,14618,14620,14621 ,0,0,0}, - {26080,26082,26081 ,14620,14622,14621 ,0,0,0}, {26083,26079,26084 ,14623,14619,14624 ,0,0,0}, - {26085,26084,25571 ,14625,14624,14078 ,0,0,0}, {25573,26084,26076 ,14615,14624,14616 ,0,0,0}, - {26084,25576,25571 ,14624,14626,14078 ,0,0,0}, {26085,26083,26084 ,14625,14623,14624 ,0,0,0}, - {26065,26086,26087 ,14603,14627,14628 ,0,0,0}, {25998,26055,25999 ,14591,14587,14586 ,0,0,0}, - {26039,26010,26009 ,14559,14629,14560 ,0,0,0}, {25969,26010,26088 ,14630,14629,14631 ,0,0,0}, - {26039,26088,26010 ,14559,14631,14629 ,0,0,0}, {26089,26011,25969 ,14632,14633,14630 ,0,0,0}, - {25969,26088,26089 ,14630,14631,14632 ,0,0,0}, {26012,26089,26090 ,14634,14632,14635 ,0,0,0}, - {26089,26012,26011 ,14632,14634,14633 ,0,0,0}, {26091,26013,26090 ,14636,14637,14635 ,0,0,0}, - {26012,26090,26013 ,14634,14635,14637 ,0,0,0}, {26014,26013,26091 ,14638,14637,14636 ,0,0,0}, - {26091,26092,26014 ,14636,14639,14638 ,0,0,0}, {26014,26092,26015 ,14638,14639,14640 ,0,0,0}, - {26015,26092,26093 ,14640,14639,14641 ,0,0,0}, {26094,26095,26096 ,14642,14643,14644 ,0,0,0}, - {26097,26016,26093 ,14645,14646,14641 ,0,0,0}, {26015,26093,26016 ,14640,14641,14646 ,0,0,0}, - {26097,26098,26017 ,14645,14647,14648 ,0,0,0}, {26017,26016,26097 ,14648,14646,14645 ,0,0,0}, - {25934,26018,26098 ,14649,14650,14647 ,0,0,0}, {26098,26018,26017 ,14647,14650,14648 ,0,0,0}, - {26099,26019,25934 ,14651,14652,14649 ,0,0,0}, {25934,26098,26099 ,14649,14647,14651 ,0,0,0}, - {26019,26100,26020 ,14652,14653,14654 ,0,0,0}, {26100,26019,26099 ,14653,14652,14651 ,0,0,0}, - {26021,26020,26101 ,14655,14654,14656 ,0,0,0}, {26100,26101,26020 ,14653,14656,14654 ,0,0,0}, - {26102,26021,26101 ,14657,14655,14656 ,0,0,0}, {26102,26022,26021 ,14657,14658,14655 ,0,0,0}, - {26102,26103,26022 ,14657,14659,14658 ,0,0,0}, {26104,26105,26106 ,14660,14661,14662 ,0,0,0}, - {26023,26103,26107 ,14663,14659,14664 ,0,0,0}, {26103,26023,26022 ,14659,14663,14658 ,0,0,0}, - {26108,25980,26107 ,14665,14666,14664 ,0,0,0}, {26023,26107,25980 ,14663,14664,14666 ,0,0,0}, - {26024,26108,26025 ,14667,14665,14668 ,0,0,0}, {26024,25980,26108 ,14667,14666,14665 ,0,0,0}, - {26026,26025,26109 ,14669,14668,14670 ,0,0,0}, {26108,26109,26025 ,14665,14670,14668 ,0,0,0}, - {26110,26027,26026 ,14671,14672,14669 ,0,0,0}, {26026,26109,26110 ,14669,14670,14671 ,0,0,0}, - {26027,26111,26028 ,14672,14673,14674 ,0,0,0}, {26111,26027,26110 ,14673,14672,14671 ,0,0,0}, - {26029,26028,26112 ,14675,14674,14676 ,0,0,0}, {26111,26112,26028 ,14673,14676,14674 ,0,0,0}, - {26113,26029,26112 ,14677,14675,14676 ,0,0,0}, {26113,26030,26029 ,14677,14678,14675 ,0,0,0}, - {26113,26114,26030 ,14677,14679,14678 ,0,0,0}, {26115,26116,26117 ,14680,14681,14682 ,0,0,0}, - {26031,26114,26116 ,14683,14679,14681 ,0,0,0}, {26114,26031,26030 ,14679,14683,14678 ,0,0,0}, - {26118,26032,26116 ,14684,14685,14681 ,0,0,0}, {26031,26116,26032 ,14683,14681,14685 ,0,0,0}, - {26119,26120,26121 ,14686,14687,14688 ,0,0,0}, {26033,26032,26118 ,14689,14685,14684 ,0,0,0}, - {26122,26123,26124 ,14690,14691,14692 ,0,0,0}, {26125,26126,26127 ,14693,14694,14695 ,0,0,0}, - {26128,26129,26130 ,14696,14697,14698 ,0,0,0}, {26131,26132,26133 ,14699,14700,14701 ,0,0,0}, - {26134,26135,26122 ,14702,14703,14690 ,0,0,0}, {26136,26137,26138 ,14704,14705,14706 ,0,0,0}, - {26139,26140,26135 ,14707,14708,14703 ,0,0,0}, {26136,26131,26137 ,14704,14699,14705 ,0,0,0}, - {26135,26141,26142 ,14703,14709,14710 ,0,0,0}, {25645,25196,26138 ,14711,726,14706 ,0,0,0}, - {26143,26033,26118 ,14712,14689,14684 ,0,0,0}, {26033,26143,26034 ,14689,14712,14713 ,0,0,0}, - {26034,26119,26035 ,14713,14686,14714 ,0,0,0}, {26115,26118,26116 ,14680,14684,14681 ,0,0,0}, - {26144,26145,26036 ,14715,14716,14717 ,0,0,0}, {26119,26144,26035 ,14686,14715,14714 ,0,0,0}, - {26142,26144,26121 ,14710,14715,14688 ,0,0,0}, {26035,26144,26036 ,14714,14715,14717 ,0,0,0}, - {26145,26146,25665 ,14716,14718,14719 ,0,0,0}, {26145,25665,26037 ,14716,14719,14720 ,0,0,0}, - {25067,25665,26147 ,730,14719,14721 ,0,0,0}, {26084,25573,25576 ,14624,14615,14626 ,0,0,0}, - {26077,26079,26083 ,14617,14619,14623 ,0,0,0}, {26087,26086,26148 ,14628,14627,14722 ,0,0,0}, - {26076,26060,25993 ,14616,14597,14609 ,0,0,0}, {26076,26079,26149 ,14616,14619,14723 ,0,0,0}, - {26150,26058,26062 ,14724,14593,14599 ,0,0,0}, {26060,26149,26061 ,14597,14723,14598 ,0,0,0}, - {26151,26057,26150 ,14725,14590,14724 ,0,0,0}, {26061,26059,26060 ,14598,14595,14597 ,0,0,0}, - {26152,26056,26151 ,14726,14588,14725 ,0,0,0}, {26062,26058,26059 ,14599,14593,14595 ,0,0,0}, - {26153,26055,26152 ,14727,14587,14726 ,0,0,0}, {26150,26057,26058 ,14724,14590,14593 ,0,0,0}, - {26154,26054,26153 ,14728,14585,14727 ,0,0,0}, {26151,26056,26057 ,14725,14588,14590 ,0,0,0}, - {26155,26053,26154 ,14729,14582,14728 ,0,0,0}, {26152,26055,26056 ,14726,14587,14588 ,0,0,0}, - {26156,26049,26155 ,14730,14578,14729 ,0,0,0}, {26153,26054,26055 ,14727,14585,14587 ,0,0,0}, - {26156,26157,26048 ,14730,14731,14575 ,0,0,0}, {26053,26054,26154 ,14582,14585,14728 ,0,0,0}, - {26158,26047,26157 ,14732,14574,14731 ,0,0,0}, {26049,26053,26155 ,14578,14582,14729 ,0,0,0}, - {26051,26045,26158 ,14580,14571,14732 ,0,0,0}, {26048,26049,26156 ,14575,14578,14730 ,0,0,0}, - {26159,26046,26051 ,14733,14572,14580 ,0,0,0}, {26047,26048,26157 ,14574,14575,14731 ,0,0,0}, - {26160,26043,26159 ,14734,14565,14733 ,0,0,0}, {26045,26047,26158 ,14571,14574,14732 ,0,0,0}, - {26161,26044,26160 ,14735,14568,14734 ,0,0,0}, {26051,26046,26045 ,14580,14572,14571 ,0,0,0}, - {26162,26038,26161 ,14736,14558,14735 ,0,0,0}, {26159,26043,26046 ,14733,14565,14572 ,0,0,0}, - {26162,26163,26039 ,14736,14737,14559 ,0,0,0}, {26044,26043,26160 ,14568,14565,14734 ,0,0,0}, - {26164,26088,26163 ,14738,14631,14737 ,0,0,0}, {26038,26044,26161 ,14558,14568,14735 ,0,0,0}, - {26165,26089,26164 ,14739,14632,14738 ,0,0,0}, {26039,26038,26162 ,14559,14558,14736 ,0,0,0}, - {26166,26090,26165 ,14740,14635,14739 ,0,0,0}, {26088,26039,26163 ,14631,14559,14737 ,0,0,0}, - {26167,26091,26166 ,14741,14636,14740 ,0,0,0}, {26089,26088,26164 ,14632,14631,14738 ,0,0,0}, - {26168,26092,26167 ,14742,14639,14741 ,0,0,0}, {26165,26090,26089 ,14739,14635,14632 ,0,0,0}, - {26168,26169,26093 ,14742,14743,14641 ,0,0,0}, {26091,26090,26166 ,14636,14635,14740 ,0,0,0}, - {26170,26097,26169 ,14744,14645,14743 ,0,0,0}, {26092,26091,26167 ,14639,14636,14741 ,0,0,0}, - {26094,26098,26170 ,14642,14647,14744 ,0,0,0}, {26093,26092,26168 ,14641,14639,14742 ,0,0,0}, - {26171,26099,26094 ,14745,14651,14642 ,0,0,0}, {26097,26093,26169 ,14645,14641,14743 ,0,0,0}, - {26172,26100,26171 ,14746,14653,14745 ,0,0,0}, {26098,26097,26170 ,14647,14645,14744 ,0,0,0}, - {26173,26101,26172 ,14747,14656,14746 ,0,0,0}, {26094,26099,26098 ,14642,14651,14647 ,0,0,0}, - {26174,26102,26173 ,14748,14657,14747 ,0,0,0}, {26171,26100,26099 ,14745,14653,14651 ,0,0,0}, - {26174,26175,26103 ,14748,14749,14659 ,0,0,0}, {26101,26100,26172 ,14656,14653,14746 ,0,0,0}, - {26176,26107,26175 ,14750,14664,14749 ,0,0,0}, {26102,26101,26173 ,14657,14656,14747 ,0,0,0}, - {26177,26108,26176 ,14751,14665,14750 ,0,0,0}, {26103,26102,26174 ,14659,14657,14748 ,0,0,0}, - {26178,26109,26177 ,14752,14670,14751 ,0,0,0}, {26107,26103,26175 ,14664,14659,14749 ,0,0,0}, - {26179,26110,26178 ,14753,14671,14752 ,0,0,0}, {26176,26108,26107 ,14750,14665,14664 ,0,0,0}, - {26180,26111,26179 ,14754,14673,14753 ,0,0,0}, {26177,26109,26108 ,14751,14670,14665 ,0,0,0}, - {26181,26112,26180 ,14755,14676,14754 ,0,0,0}, {26178,26110,26109 ,14752,14671,14670 ,0,0,0}, - {26182,26113,26181 ,14756,14677,14755 ,0,0,0}, {26179,26111,26110 ,14753,14673,14671 ,0,0,0}, - {26182,26117,26114 ,14756,14682,14679 ,0,0,0}, {26112,26111,26180 ,14676,14673,14754 ,0,0,0}, - {26118,26115,26183 ,14684,14680,14757 ,0,0,0}, {26113,26112,26181 ,14677,14676,14755 ,0,0,0}, - {26139,26121,26127 ,14707,14688,14695 ,0,0,0}, {26114,26113,26182 ,14679,14677,14756 ,0,0,0}, - {26143,26183,26120 ,14712,14757,14687 ,0,0,0}, {26114,26117,26116 ,14679,14682,14681 ,0,0,0}, - {26183,26184,26120 ,14757,14758,14687 ,0,0,0}, {26142,26145,26144 ,14710,14716,14715 ,0,0,0}, - {26143,26119,26034 ,14712,14686,14713 ,0,0,0}, {26183,26143,26118 ,14757,14712,14684 ,0,0,0}, - {26142,26139,26135 ,14710,14707,14703 ,0,0,0}, {26119,26143,26120 ,14686,14712,14687 ,0,0,0}, - {26146,26141,26185 ,14718,14709,14759 ,0,0,0}, {26146,26147,25665 ,14718,14721,14719 ,0,0,0}, - {26036,26145,26037 ,14717,14716,14720 ,0,0,0}, {26146,26145,26141 ,14718,14716,14709 ,0,0,0}, - {26186,26147,26146 ,14760,14721,14718 ,0,0,0}, {26084,26079,26076 ,14624,14619,14616 ,0,0,0}, - {26080,26078,26077 ,14620,14618,14617 ,0,0,0}, {26068,25693,25689 ,14606,14600,14761 ,0,0,0}, - {26076,26149,26060 ,14616,14723,14597 ,0,0,0}, {26187,26149,26078 ,14762,14723,14618 ,0,0,0}, - {26072,26074,26150 ,14611,14613,14724 ,0,0,0}, {26071,26061,26187 ,14610,14598,14762 ,0,0,0}, - {26074,26188,26151 ,14613,14763,14725 ,0,0,0}, {26071,26062,26061 ,14610,14599,14598 ,0,0,0}, - {26188,26189,26152 ,14763,14764,14726 ,0,0,0}, {26072,26150,26062 ,14611,14724,14599 ,0,0,0}, - {26189,26190,26153 ,14764,14765,14727 ,0,0,0}, {26074,26151,26150 ,14613,14725,14724 ,0,0,0}, - {26190,26191,26154 ,14765,14766,14728 ,0,0,0}, {26188,26152,26151 ,14763,14726,14725 ,0,0,0}, - {26191,26192,26155 ,14766,14767,14729 ,0,0,0}, {26189,26153,26152 ,14764,14727,14726 ,0,0,0}, - {26192,26193,26156 ,14767,14768,14730 ,0,0,0}, {26190,26154,26153 ,14765,14728,14727 ,0,0,0}, - {26193,26194,26157 ,14768,14769,14731 ,0,0,0}, {26191,26155,26154 ,14766,14729,14728 ,0,0,0}, - {26194,26052,26158 ,14769,14581,14732 ,0,0,0}, {26156,26155,26192 ,14730,14729,14767 ,0,0,0}, - {26195,26196,26197 ,14770,14771,14772 ,0,0,0}, {26157,26156,26193 ,14731,14730,14768 ,0,0,0}, - {26050,26196,26159 ,14579,14771,14733 ,0,0,0}, {26158,26157,26194 ,14732,14731,14769 ,0,0,0}, - {26196,26195,26160 ,14771,14770,14734 ,0,0,0}, {26051,26158,26052 ,14580,14732,14581 ,0,0,0}, - {26195,26198,26161 ,14770,14773,14735 ,0,0,0}, {26050,26159,26051 ,14579,14733,14580 ,0,0,0}, - {26198,26199,26162 ,14773,14774,14736 ,0,0,0}, {26196,26160,26159 ,14771,14734,14733 ,0,0,0}, - {26199,26200,26163 ,14774,14775,14737 ,0,0,0}, {26195,26161,26160 ,14770,14735,14734 ,0,0,0}, - {26200,26201,26164 ,14775,14776,14738 ,0,0,0}, {26162,26161,26198 ,14736,14735,14773 ,0,0,0}, - {26042,26165,26201 ,14564,14739,14776 ,0,0,0}, {26163,26162,26199 ,14737,14736,14774 ,0,0,0}, - {26042,26041,26166 ,14564,14563,14740 ,0,0,0}, {26164,26163,26200 ,14738,14737,14775 ,0,0,0}, - {26041,26202,26167 ,14563,14777,14741 ,0,0,0}, {26201,26165,26164 ,14776,14739,14738 ,0,0,0}, - {26202,26203,26168 ,14777,14778,14742 ,0,0,0}, {26042,26166,26165 ,14564,14740,14739 ,0,0,0}, - {26203,26204,26169 ,14778,14779,14743 ,0,0,0}, {26041,26167,26166 ,14563,14741,14740 ,0,0,0}, - {26204,26095,26170 ,14779,14643,14744 ,0,0,0}, {26168,26167,26202 ,14742,14741,14777 ,0,0,0}, - {26205,26206,26207 ,14780,14781,14782 ,0,0,0}, {26169,26168,26203 ,14743,14742,14778 ,0,0,0}, - {26096,26208,26171 ,14644,14783,14745 ,0,0,0}, {26170,26169,26204 ,14744,14743,14779 ,0,0,0}, - {26208,26209,26172 ,14783,14784,14746 ,0,0,0}, {26094,26170,26095 ,14642,14744,14643 ,0,0,0}, - {26209,26210,26173 ,14784,14785,14747 ,0,0,0}, {26096,26171,26094 ,14644,14745,14642 ,0,0,0}, - {26210,26211,26174 ,14785,14786,14748 ,0,0,0}, {26208,26172,26171 ,14783,14746,14745 ,0,0,0}, - {26211,26212,26175 ,14786,14787,14749 ,0,0,0}, {26209,26173,26172 ,14784,14747,14746 ,0,0,0}, - {26212,26213,26176 ,14787,14788,14750 ,0,0,0}, {26174,26173,26210 ,14748,14747,14785 ,0,0,0}, - {26213,26104,26177 ,14788,14660,14751 ,0,0,0}, {26175,26174,26211 ,14749,14748,14786 ,0,0,0}, - {26104,26106,26178 ,14660,14662,14752 ,0,0,0}, {26176,26175,26212 ,14750,14749,14787 ,0,0,0}, - {26106,26214,26179 ,14662,14789,14753 ,0,0,0}, {26213,26177,26176 ,14788,14751,14750 ,0,0,0}, - {26214,26215,26180 ,14789,14790,14754 ,0,0,0}, {26104,26178,26177 ,14660,14752,14751 ,0,0,0}, - {26215,26216,26181 ,14790,14791,14755 ,0,0,0}, {26106,26179,26178 ,14662,14753,14752 ,0,0,0}, - {26216,26217,26182 ,14791,14792,14756 ,0,0,0}, {26214,26180,26179 ,14789,14754,14753 ,0,0,0}, - {26217,26218,26117 ,14792,14793,14682 ,0,0,0}, {26215,26181,26180 ,14790,14755,14754 ,0,0,0}, - {26218,26219,26115 ,14793,14794,14680 ,0,0,0}, {26216,26182,26181 ,14791,14756,14755 ,0,0,0}, - {26219,26184,26183 ,14794,14758,14757 ,0,0,0}, {26217,26117,26182 ,14792,14682,14756 ,0,0,0}, - {26184,26127,26120 ,14758,14695,14687 ,0,0,0}, {26115,26117,26218 ,14680,14682,14793 ,0,0,0}, - {26220,26221,26222 ,14795,14796,14797 ,0,0,0}, {26219,26183,26115 ,14794,14757,14680 ,0,0,0}, - {26140,26122,26135 ,14708,14690,14703 ,0,0,0}, {26134,26223,26185 ,14702,14798,14759 ,0,0,0}, - {26119,26121,26144 ,14686,14688,14715 ,0,0,0}, {26127,26121,26120 ,14695,14688,14687 ,0,0,0}, - {26224,26185,26223 ,14799,14759,14798 ,0,0,0}, {26185,26186,26146 ,14759,14760,14718 ,0,0,0}, - {26145,26142,26141 ,14716,14710,14709 ,0,0,0}, {26141,26134,26185 ,14709,14702,14759 ,0,0,0}, - {26224,26186,26185 ,14799,14760,14759 ,0,0,0}, {26078,26149,26079 ,14618,14723,14619 ,0,0,0}, - {26225,26081,26082 ,14800,14621,14622 ,0,0,0}, {26225,26086,26081 ,14800,14627,14621 ,0,0,0}, - {26149,26187,26061 ,14723,14762,14598 ,0,0,0}, {26226,26187,26081 ,14801,14762,14621 ,0,0,0}, - {26074,26227,26188 ,14613,14802,14763 ,0,0,0}, {26075,26071,26226 ,14614,14610,14801 ,0,0,0}, - {26188,26228,26189 ,14763,14803,14764 ,0,0,0}, {26075,26073,26072 ,14614,14612,14611 ,0,0,0}, - {26229,26230,26231 ,14804,14805,14806 ,0,0,0}, {26073,26227,26074 ,14612,14802,14613 ,0,0,0}, - {26190,26189,26232 ,14765,14764,14807 ,0,0,0}, {26227,26228,26188 ,14802,14803,14763 ,0,0,0}, - {26191,26190,26231 ,14766,14765,14806 ,0,0,0}, {26228,26232,26189 ,14803,14807,14764 ,0,0,0}, - {26192,26191,26230 ,14767,14766,14805 ,0,0,0}, {26232,26231,26190 ,14807,14806,14765 ,0,0,0}, - {26193,26192,26233 ,14768,14767,14808 ,0,0,0}, {26231,26230,26191 ,14806,14805,14766 ,0,0,0}, - {26194,26193,26234 ,14769,14768,14809 ,0,0,0}, {26230,26233,26192 ,14805,14808,14767 ,0,0,0}, - {26052,26194,26235 ,14581,14769,14810 ,0,0,0}, {26233,26234,26193 ,14808,14809,14768 ,0,0,0}, - {26050,26052,26236 ,14579,14581,14811 ,0,0,0}, {26234,26235,26194 ,14809,14810,14769 ,0,0,0}, - {26196,26050,26237 ,14771,14579,14812 ,0,0,0}, {26236,26052,26235 ,14811,14581,14810 ,0,0,0}, - {26238,26239,26240 ,14813,14814,14815 ,0,0,0}, {26237,26050,26236 ,14812,14579,14811 ,0,0,0}, - {26198,26195,26241 ,14773,14770,14816 ,0,0,0}, {26237,26197,26196 ,14812,14772,14771 ,0,0,0}, - {26199,26198,26240 ,14774,14773,14815 ,0,0,0}, {26197,26241,26195 ,14772,14816,14770 ,0,0,0}, - {26200,26199,26239 ,14775,14774,14814 ,0,0,0}, {26241,26240,26198 ,14816,14815,14773 ,0,0,0}, - {26201,26200,26242 ,14776,14775,14817 ,0,0,0}, {26240,26239,26199 ,14815,14814,14774 ,0,0,0}, - {26042,26201,26243 ,14564,14776,14818 ,0,0,0}, {26242,26200,26239 ,14817,14775,14814 ,0,0,0}, - {26244,26245,26246 ,14819,14820,14821 ,0,0,0}, {26243,26201,26242 ,14818,14776,14817 ,0,0,0}, - {26202,26041,26247 ,14777,14563,14822 ,0,0,0}, {26243,26040,26042 ,14818,14562,14564 ,0,0,0}, - {26203,26202,26246 ,14778,14777,14821 ,0,0,0}, {26040,26247,26041 ,14562,14822,14563 ,0,0,0}, - {26204,26203,26245 ,14779,14778,14820 ,0,0,0}, {26247,26246,26202 ,14822,14821,14777 ,0,0,0}, - {26095,26204,26248 ,14643,14779,14823 ,0,0,0}, {26246,26245,26203 ,14821,14820,14778 ,0,0,0}, - {26096,26095,26249 ,14644,14643,14824 ,0,0,0}, {26245,26248,26204 ,14820,14823,14779 ,0,0,0}, - {26208,26096,26250 ,14783,14644,14825 ,0,0,0}, {26249,26095,26248 ,14824,14643,14823 ,0,0,0}, - {26209,26208,26251 ,14784,14783,14826 ,0,0,0}, {26250,26096,26249 ,14825,14644,14824 ,0,0,0}, - {26210,26209,26205 ,14785,14784,14780 ,0,0,0}, {26250,26251,26208 ,14825,14826,14783 ,0,0,0}, - {26211,26210,26207 ,14786,14785,14782 ,0,0,0}, {26251,26205,26209 ,14826,14780,14784 ,0,0,0}, - {26212,26211,26252 ,14787,14786,14827 ,0,0,0}, {26205,26207,26210 ,14780,14782,14785 ,0,0,0}, - {26213,26212,26253 ,14788,14787,14828 ,0,0,0}, {26207,26252,26211 ,14782,14827,14786 ,0,0,0}, - {26104,26213,26254 ,14660,14788,14829 ,0,0,0}, {26253,26212,26252 ,14828,14787,14827 ,0,0,0}, - {26255,26256,26257 ,14830,14831,14832 ,0,0,0}, {26254,26213,26253 ,14829,14788,14828 ,0,0,0}, - {26214,26106,26258 ,14789,14662,14833 ,0,0,0}, {26254,26105,26104 ,14829,14661,14660 ,0,0,0}, - {26215,26214,26257 ,14790,14789,14832 ,0,0,0}, {26105,26258,26106 ,14661,14833,14662 ,0,0,0}, - {26216,26215,26256 ,14791,14790,14831 ,0,0,0}, {26258,26257,26214 ,14833,14832,14789 ,0,0,0}, - {26217,26216,26259 ,14792,14791,14834 ,0,0,0}, {26257,26256,26215 ,14832,14831,14790 ,0,0,0}, - {26218,26217,26260 ,14793,14792,14835 ,0,0,0}, {26256,26259,26216 ,14831,14834,14791 ,0,0,0}, - {26219,26218,26261 ,14794,14793,14836 ,0,0,0}, {26259,26260,26217 ,14834,14835,14792 ,0,0,0}, - {26184,26219,26262 ,14758,14794,14837 ,0,0,0}, {26260,26261,26218 ,14835,14836,14793 ,0,0,0}, - {26127,26184,26125 ,14695,14758,14693 ,0,0,0}, {26261,26262,26219 ,14836,14837,14794 ,0,0,0}, - {26139,26127,26126 ,14707,14695,14694 ,0,0,0}, {26262,26125,26184 ,14837,14693,14758 ,0,0,0}, - {26263,26133,26222 ,14838,14701,14797 ,0,0,0}, {26264,26123,26122 ,14839,14691,14690 ,0,0,0}, - {26121,26139,26142 ,14688,14707,14710 ,0,0,0}, {26126,26140,26139 ,14694,14708,14707 ,0,0,0}, - {26265,26223,26221 ,14840,14798,14796 ,0,0,0}, {26265,26266,26223 ,14840,14841,14798 ,0,0,0}, - {26141,26135,26134 ,14709,14703,14702 ,0,0,0}, {26134,26124,26223 ,14702,14692,14798 ,0,0,0}, - {26224,26223,26266 ,14799,14798,14841 ,0,0,0}, {26078,26081,26187 ,14618,14621,14762 ,0,0,0}, - {26148,26086,26225 ,14722,14627,14800 ,0,0,0}, {26075,26267,26073 ,14614,14842,14612 ,0,0,0}, - {26187,26226,26071 ,14762,14801,14610 ,0,0,0}, {26086,26268,26226 ,14627,14843,14801 ,0,0,0}, - {26227,26073,26269 ,14802,14612,14844 ,0,0,0}, {26268,26267,26075 ,14843,14842,14614 ,0,0,0}, - {26228,26227,26270 ,14803,14802,14845 ,0,0,0}, {26073,26267,26269 ,14612,14842,14844 ,0,0,0}, - {26232,26228,26271 ,14807,14803,14846 ,0,0,0}, {26227,26269,26270 ,14802,14844,14845 ,0,0,0}, - {26231,26232,26272 ,14806,14807,14847 ,0,0,0}, {26270,26271,26228 ,14845,14846,14803 ,0,0,0}, - {26273,26233,26230 ,14848,14808,14805 ,0,0,0}, {26271,26272,26232 ,14846,14847,14807 ,0,0,0}, - {26274,26275,26276 ,14849,14850,14851 ,0,0,0}, {26272,26229,26231 ,14847,14804,14806 ,0,0,0}, - {26233,26277,26234 ,14808,14852,14809 ,0,0,0}, {26229,26273,26230 ,14804,14848,14805 ,0,0,0}, - {26234,26275,26235 ,14809,14850,14810 ,0,0,0}, {26273,26277,26233 ,14848,14852,14808 ,0,0,0}, - {26235,26274,26236 ,14810,14849,14811 ,0,0,0}, {26277,26275,26234 ,14852,14850,14809 ,0,0,0}, - {26236,26278,26237 ,14811,14853,14812 ,0,0,0}, {26275,26274,26235 ,14850,14849,14810 ,0,0,0}, - {26237,26279,26197 ,14812,14854,14772 ,0,0,0}, {26274,26278,26236 ,14849,14853,14811 ,0,0,0}, - {26241,26197,26280 ,14816,14772,14855 ,0,0,0}, {26278,26279,26237 ,14853,14854,14812 ,0,0,0}, - {26240,26241,26281 ,14815,14816,14856 ,0,0,0}, {26279,26280,26197 ,14854,14855,14772 ,0,0,0}, - {26282,26283,26284 ,14857,14858,14859 ,0,0,0}, {26280,26281,26241 ,14855,14856,14816 ,0,0,0}, - {26239,26285,26242 ,14814,14860,14817 ,0,0,0}, {26281,26238,26240 ,14856,14813,14815 ,0,0,0}, - {26242,26286,26243 ,14817,14861,14818 ,0,0,0}, {26238,26285,26239 ,14813,14860,14814 ,0,0,0}, - {26243,26287,26040 ,14818,14862,14562 ,0,0,0}, {26285,26286,26242 ,14860,14861,14817 ,0,0,0}, - {26247,26040,26288 ,14822,14562,14863 ,0,0,0}, {26286,26287,26243 ,14861,14862,14818 ,0,0,0}, - {26246,26247,26289 ,14821,14822,14864 ,0,0,0}, {26287,26288,26040 ,14862,14863,14562 ,0,0,0}, - {26290,26291,26292 ,14865,14866,14867 ,0,0,0}, {26288,26289,26247 ,14863,14864,14822 ,0,0,0}, - {26245,26293,26248 ,14820,14868,14823 ,0,0,0}, {26289,26244,26246 ,14864,14819,14821 ,0,0,0}, - {26248,26294,26249 ,14823,14869,14824 ,0,0,0}, {26244,26293,26245 ,14819,14868,14820 ,0,0,0}, - {26249,26295,26250 ,14824,14870,14825 ,0,0,0}, {26293,26294,26248 ,14868,14869,14823 ,0,0,0}, - {26250,26296,26251 ,14825,14871,14826 ,0,0,0}, {26294,26295,26249 ,14869,14870,14824 ,0,0,0}, - {26205,26251,26297 ,14780,14826,14872 ,0,0,0}, {26295,26296,26250 ,14870,14871,14825 ,0,0,0}, - {26298,26299,26300 ,14873,14874,14875 ,0,0,0}, {26296,26297,26251 ,14871,14872,14826 ,0,0,0}, - {26207,26301,26252 ,14782,14876,14827 ,0,0,0}, {26297,26206,26205 ,14872,14781,14780 ,0,0,0}, - {26252,26299,26253 ,14827,14874,14828 ,0,0,0}, {26206,26301,26207 ,14781,14876,14782 ,0,0,0}, - {26253,26298,26254 ,14828,14873,14829 ,0,0,0}, {26301,26299,26252 ,14876,14874,14827 ,0,0,0}, - {26254,26302,26105 ,14829,14877,14661 ,0,0,0}, {26299,26298,26253 ,14874,14873,14828 ,0,0,0}, - {26258,26105,26303 ,14833,14661,14878 ,0,0,0}, {26298,26302,26254 ,14873,14877,14829 ,0,0,0}, - {26257,26258,26304 ,14832,14833,14879 ,0,0,0}, {26302,26303,26105 ,14877,14878,14661 ,0,0,0}, - {26305,26259,26256 ,14880,14834,14831 ,0,0,0}, {26303,26304,26258 ,14878,14879,14833 ,0,0,0}, - {26306,26307,26308 ,14881,14882,14883 ,0,0,0}, {26304,26255,26257 ,14879,14830,14832 ,0,0,0}, - {26259,26309,26260 ,14834,14884,14835 ,0,0,0}, {26255,26305,26256 ,14830,14880,14831 ,0,0,0}, - {26260,26307,26261 ,14835,14882,14836 ,0,0,0}, {26305,26309,26259 ,14880,14884,14834 ,0,0,0}, - {26261,26306,26262 ,14836,14881,14837 ,0,0,0}, {26309,26307,26260 ,14884,14882,14835 ,0,0,0}, - {26262,26310,26125 ,14837,14885,14693 ,0,0,0}, {26307,26306,26261 ,14882,14881,14836 ,0,0,0}, - {26125,26311,26126 ,14693,14886,14694 ,0,0,0}, {26306,26310,26262 ,14881,14885,14837 ,0,0,0}, - {26126,26312,26140 ,14694,14887,14708 ,0,0,0}, {26310,26311,26125 ,14885,14886,14693 ,0,0,0}, - {26140,26264,26122 ,14708,14839,14690 ,0,0,0}, {26312,26126,26311 ,14887,14694,14886 ,0,0,0}, - {26129,26123,26313 ,14697,14691,14888 ,0,0,0}, {26140,26312,26264 ,14708,14887,14839 ,0,0,0}, - {26221,26314,26222 ,14796,14889,14797 ,0,0,0}, {26223,26124,26221 ,14798,14692,14796 ,0,0,0}, - {26134,26122,26124 ,14702,14690,14692 ,0,0,0}, {26124,26314,26221 ,14692,14889,14796 ,0,0,0}, - {26265,26221,26220 ,14840,14796,14795 ,0,0,0}, {26081,26086,26226 ,14621,14627,14801 ,0,0,0}, - {26066,26065,26087 ,14604,14603,14628 ,0,0,0}, {26267,26315,26269 ,14842,14890,14844 ,0,0,0}, - {26226,26268,26075 ,14801,14843,14614 ,0,0,0}, {26065,26316,26268 ,14603,14891,14843 ,0,0,0}, - {26270,26269,26317 ,14845,14844,14892 ,0,0,0}, {26267,26316,26315 ,14842,14891,14890 ,0,0,0}, - {26271,26270,26318 ,14846,14845,14893 ,0,0,0}, {26269,26315,26317 ,14844,14890,14892 ,0,0,0}, - {26272,26271,26319 ,14847,14846,14894 ,0,0,0}, {26270,26317,26318 ,14845,14892,14893 ,0,0,0}, - {26229,26272,26320 ,14804,14847,14895 ,0,0,0}, {26271,26318,26319 ,14846,14893,14894 ,0,0,0}, - {26273,26229,26321 ,14848,14804,14896 ,0,0,0}, {26272,26319,26320 ,14847,14894,14895 ,0,0,0}, - {26277,26273,26322 ,14852,14848,14897 ,0,0,0}, {26229,26320,26321 ,14804,14895,14896 ,0,0,0}, - {26275,26277,26323 ,14850,14852,14898 ,0,0,0}, {26321,26322,26273 ,14896,14897,14848 ,0,0,0}, - {26324,26325,26326 ,14899,14900,14901 ,0,0,0}, {26322,26323,26277 ,14897,14898,14852 ,0,0,0}, - {26274,26327,26278 ,14849,14902,14853 ,0,0,0}, {26323,26276,26275 ,14898,14851,14850 ,0,0,0}, - {26278,26326,26279 ,14853,14901,14854 ,0,0,0}, {26276,26327,26274 ,14851,14902,14849 ,0,0,0}, - {26279,26328,26280 ,14854,14903,14855 ,0,0,0}, {26327,26326,26278 ,14902,14901,14853 ,0,0,0}, - {26281,26280,26329 ,14856,14855,14904 ,0,0,0}, {26326,26328,26279 ,14901,14903,14854 ,0,0,0}, - {26238,26281,26330 ,14813,14856,14905 ,0,0,0}, {26280,26328,26329 ,14855,14903,14904 ,0,0,0}, - {26285,26238,26331 ,14860,14813,14906 ,0,0,0}, {26281,26329,26330 ,14856,14904,14905 ,0,0,0}, - {26286,26285,26332 ,14861,14860,14907 ,0,0,0}, {26330,26331,26238 ,14905,14906,14813 ,0,0,0}, - {26286,26333,26287 ,14861,14908,14862 ,0,0,0}, {26331,26332,26285 ,14906,14907,14860 ,0,0,0}, - {26287,26283,26288 ,14862,14858,14863 ,0,0,0}, {26332,26333,26286 ,14907,14908,14861 ,0,0,0}, - {26289,26288,26334 ,14864,14863,14909 ,0,0,0}, {26333,26283,26287 ,14908,14858,14862 ,0,0,0}, - {26244,26289,26335 ,14819,14864,14910 ,0,0,0}, {26288,26283,26334 ,14863,14858,14909 ,0,0,0}, - {26293,26244,26336 ,14868,14819,14911 ,0,0,0}, {26289,26334,26335 ,14864,14909,14910 ,0,0,0}, - {26294,26293,26337 ,14869,14868,14912 ,0,0,0}, {26335,26336,26244 ,14910,14911,14819 ,0,0,0}, - {26294,26338,26295 ,14869,14913,14870 ,0,0,0}, {26336,26337,26293 ,14911,14912,14868 ,0,0,0}, - {26295,26291,26296 ,14870,14866,14871 ,0,0,0}, {26337,26338,26294 ,14912,14913,14869 ,0,0,0}, - {26297,26296,26339 ,14872,14871,14914 ,0,0,0}, {26338,26291,26295 ,14913,14866,14870 ,0,0,0}, - {26206,26297,26340 ,14781,14872,14915 ,0,0,0}, {26296,26291,26339 ,14871,14866,14914 ,0,0,0}, - {26301,26206,26341 ,14876,14781,14916 ,0,0,0}, {26297,26339,26340 ,14872,14914,14915 ,0,0,0}, - {26299,26301,26342 ,14874,14876,14917 ,0,0,0}, {26340,26341,26206 ,14915,14916,14781 ,0,0,0}, - {26343,26344,26345 ,14918,14919,14920 ,0,0,0}, {26341,26342,26301 ,14916,14917,14876 ,0,0,0}, - {26298,26346,26302 ,14873,14921,14877 ,0,0,0}, {26342,26300,26299 ,14917,14875,14874 ,0,0,0}, - {26302,26345,26303 ,14877,14920,14878 ,0,0,0}, {26300,26346,26298 ,14875,14921,14873 ,0,0,0}, - {26304,26303,26347 ,14879,14878,14922 ,0,0,0}, {26346,26345,26302 ,14921,14920,14877 ,0,0,0}, - {26255,26304,26348 ,14830,14879,14923 ,0,0,0}, {26303,26345,26347 ,14878,14920,14922 ,0,0,0}, - {26305,26255,26349 ,14880,14830,14924 ,0,0,0}, {26304,26347,26348 ,14879,14922,14923 ,0,0,0}, - {26309,26305,26350 ,14884,14880,14925 ,0,0,0}, {26255,26348,26349 ,14830,14923,14924 ,0,0,0}, - {26307,26309,26351 ,14882,14884,14926 ,0,0,0}, {26349,26350,26305 ,14924,14925,14880 ,0,0,0}, - {26352,26310,26306 ,14927,14885,14881 ,0,0,0}, {26350,26351,26309 ,14925,14926,14884 ,0,0,0}, - {26353,26354,26355 ,14928,14929,14930 ,0,0,0}, {26351,26308,26307 ,14926,14883,14882 ,0,0,0}, - {26310,26356,26311 ,14885,14931,14886 ,0,0,0}, {26308,26352,26306 ,14883,14927,14881 ,0,0,0}, - {26311,26355,26312 ,14886,14930,14887 ,0,0,0}, {26352,26356,26310 ,14927,14931,14885 ,0,0,0}, - {26312,26357,26264 ,14887,14932,14839 ,0,0,0}, {26356,26355,26311 ,14931,14930,14886 ,0,0,0}, - {26264,26313,26123 ,14839,14888,14691 ,0,0,0}, {26355,26357,26312 ,14930,14932,14887 ,0,0,0}, - {26123,26129,26314 ,14691,14697,14889 ,0,0,0}, {26264,26357,26313 ,14839,14932,14888 ,0,0,0}, - {26358,26222,26133 ,14933,14797,14701 ,0,0,0}, {26359,26220,26222 ,14934,14795,14797 ,0,0,0}, - {26124,26123,26314 ,14692,14691,14889 ,0,0,0}, {26314,26263,26222 ,14889,14838,14797 ,0,0,0}, - {26358,26359,26222 ,14933,14934,14797 ,0,0,0}, {26086,26065,26268 ,14627,14603,14843 ,0,0,0}, - {26360,26064,26066 ,14935,14602,14604 ,0,0,0}, {26317,26315,26070 ,14892,14890,14608 ,0,0,0}, - {26268,26316,26267 ,14843,14891,14842 ,0,0,0}, {26064,26361,26316 ,14602,14936,14891 ,0,0,0}, - {26318,26317,26362 ,14893,14892,14937 ,0,0,0}, {26315,26361,26070 ,14890,14936,14608 ,0,0,0}, - {26363,26362,26364 ,14938,14937,14939 ,0,0,0}, {26317,26070,26362 ,14892,14608,14937 ,0,0,0}, - {26363,26365,26319 ,14938,14940,14894 ,0,0,0}, {26319,26318,26363 ,14894,14893,14938 ,0,0,0}, - {26365,26366,26320 ,14940,14941,14895 ,0,0,0}, {26320,26319,26365 ,14895,14894,14940 ,0,0,0}, - {26366,26367,26321 ,14941,14942,14896 ,0,0,0}, {26321,26320,26366 ,14896,14895,14941 ,0,0,0}, - {26367,26368,26322 ,14942,14943,14897 ,0,0,0}, {26322,26321,26367 ,14897,14896,14942 ,0,0,0}, - {26368,26369,26323 ,14943,14944,14898 ,0,0,0}, {26323,26322,26368 ,14898,14897,14943 ,0,0,0}, - {26369,26370,26276 ,14944,14945,14851 ,0,0,0}, {26276,26323,26369 ,14851,14898,14944 ,0,0,0}, - {26370,26324,26327 ,14945,14899,14902 ,0,0,0}, {26276,26370,26327 ,14851,14945,14902 ,0,0,0}, - {25680,26371,26372 ,14946,14947,14948 ,0,0,0}, {26327,26324,26326 ,14902,14899,14901 ,0,0,0}, - {26328,26373,26329 ,14903,14949,14904 ,0,0,0}, {26326,26325,26328 ,14901,14900,14903 ,0,0,0}, - {26374,26373,26372 ,14950,14949,14948 ,0,0,0}, {26325,26373,26328 ,14900,14949,14903 ,0,0,0}, - {26374,26375,26330 ,14950,14951,14905 ,0,0,0}, {26330,26329,26374 ,14905,14904,14950 ,0,0,0}, - {26375,26376,26331 ,14951,14952,14906 ,0,0,0}, {26331,26330,26375 ,14906,14905,14951 ,0,0,0}, - {26376,26377,26332 ,14952,14953,14907 ,0,0,0}, {26332,26331,26376 ,14907,14906,14952 ,0,0,0}, - {26377,26284,26333 ,14953,14859,14908 ,0,0,0}, {26332,26377,26333 ,14907,14953,14908 ,0,0,0}, - {26378,26379,26380 ,14954,14955,14956 ,0,0,0}, {26333,26284,26283 ,14908,14859,14858 ,0,0,0}, - {26282,26379,26334 ,14857,14955,14909 ,0,0,0}, {26283,26282,26334 ,14858,14857,14909 ,0,0,0}, - {26379,26381,26335 ,14955,14957,14910 ,0,0,0}, {26335,26334,26379 ,14910,14909,14955 ,0,0,0}, - {26381,26382,26336 ,14957,14958,14911 ,0,0,0}, {26336,26335,26381 ,14911,14910,14957 ,0,0,0}, - {26382,26383,26337 ,14958,14959,14912 ,0,0,0}, {26337,26336,26382 ,14912,14911,14958 ,0,0,0}, - {26383,26292,26338 ,14959,14867,14913 ,0,0,0}, {26337,26383,26338 ,14912,14959,14913 ,0,0,0}, - {26384,25671,26385 ,14960,14961,14962 ,0,0,0}, {26338,26292,26291 ,14913,14867,14866 ,0,0,0}, - {26340,26339,26386 ,14915,14914,14963 ,0,0,0}, {26291,26290,26339 ,14866,14865,14914 ,0,0,0}, - {26387,26386,26384 ,14964,14963,14960 ,0,0,0}, {26339,26290,26386 ,14914,14865,14963 ,0,0,0}, - {26387,26388,26341 ,14964,14965,14916 ,0,0,0}, {26341,26340,26387 ,14916,14915,14964 ,0,0,0}, - {26388,26389,26342 ,14965,14966,14917 ,0,0,0}, {26342,26341,26388 ,14917,14916,14965 ,0,0,0}, - {26389,26390,26300 ,14966,14967,14875 ,0,0,0}, {26300,26342,26389 ,14875,14917,14966 ,0,0,0}, - {26390,26343,26346 ,14967,14918,14921 ,0,0,0}, {26300,26390,26346 ,14875,14967,14921 ,0,0,0}, - {26391,26392,26393 ,14968,14969,14970 ,0,0,0}, {26346,26343,26345 ,14921,14918,14920 ,0,0,0}, - {26344,26392,26347 ,14919,14969,14922 ,0,0,0}, {26345,26344,26347 ,14920,14919,14922 ,0,0,0}, - {26392,26394,26348 ,14969,14971,14923 ,0,0,0}, {26348,26347,26392 ,14923,14922,14969 ,0,0,0}, - {26394,26395,26349 ,14971,14972,14924 ,0,0,0}, {26349,26348,26394 ,14924,14923,14971 ,0,0,0}, - {26395,26396,26350 ,14972,14973,14925 ,0,0,0}, {26350,26349,26395 ,14925,14924,14972 ,0,0,0}, - {26396,26397,26351 ,14973,14974,14926 ,0,0,0}, {26351,26350,26396 ,14926,14925,14973 ,0,0,0}, - {26397,26398,26308 ,14974,14975,14883 ,0,0,0}, {26308,26351,26397 ,14883,14926,14974 ,0,0,0}, - {26398,26399,26352 ,14975,14976,14927 ,0,0,0}, {26352,26308,26398 ,14927,14883,14975 ,0,0,0}, - {26399,26353,26356 ,14976,14928,14931 ,0,0,0}, {26352,26399,26356 ,14927,14976,14931 ,0,0,0}, - {26357,26354,26400 ,14932,14929,14977 ,0,0,0}, {26356,26353,26355 ,14931,14928,14930 ,0,0,0}, - {26130,26129,26313 ,14698,14697,14888 ,0,0,0}, {26355,26354,26357 ,14930,14929,14932 ,0,0,0}, - {26128,26263,26129 ,14696,14838,14697 ,0,0,0}, {26357,26400,26313 ,14932,14977,14888 ,0,0,0}, - {26401,26137,26131 ,14978,14705,14699 ,0,0,0}, {26400,26130,26313 ,14977,14698,14888 ,0,0,0}, - {26128,26402,26403 ,14696,14979,14980 ,0,0,0}, {26404,26358,26133 ,14981,14933,14701 ,0,0,0}, - {26314,26129,26263 ,14889,14697,14838 ,0,0,0}, {26133,26263,26403 ,14701,14838,14980 ,0,0,0}, - {26132,26404,26133 ,14700,14981,14701 ,0,0,0}, {26065,26064,26316 ,14603,14602,14891 ,0,0,0}, - {26360,26067,26063 ,14935,14605,14601 ,0,0,0}, {26361,26063,26068 ,14936,14601,14606 ,0,0,0}, - {26316,26361,26315 ,14891,14936,14890 ,0,0,0}, {26070,26361,26068 ,14608,14936,14606 ,0,0,0}, - {26069,26364,26362 ,14607,14939,14937 ,0,0,0}, {26362,26070,26069 ,14937,14608,14607 ,0,0,0}, - {26364,26405,26363 ,14939,14982,14938 ,0,0,0}, {26406,26365,26405 ,14983,14940,14982 ,0,0,0}, - {26318,26362,26363 ,14893,14937,14938 ,0,0,0}, {26365,26363,26405 ,14940,14938,14982 ,0,0,0}, - {26407,26366,26406 ,14984,14941,14983 ,0,0,0}, {26366,26365,26406 ,14941,14940,14983 ,0,0,0}, - {26408,26367,26407 ,14985,14942,14984 ,0,0,0}, {26367,26366,26407 ,14942,14941,14984 ,0,0,0}, - {26409,26368,26408 ,14986,14943,14985 ,0,0,0}, {26368,26367,26408 ,14943,14942,14985 ,0,0,0}, - {26410,26369,26409 ,14987,14944,14986 ,0,0,0}, {26369,26368,26409 ,14944,14943,14986 ,0,0,0}, - {26411,26370,26410 ,14988,14945,14987 ,0,0,0}, {26370,26369,26410 ,14945,14944,14987 ,0,0,0}, - {26412,26324,26411 ,14989,14899,14988 ,0,0,0}, {26324,26370,26411 ,14899,14945,14988 ,0,0,0}, - {26413,26325,26412 ,14990,14900,14989 ,0,0,0}, {26325,26324,26412 ,14900,14899,14989 ,0,0,0}, - {26372,26373,26413 ,14948,14949,14990 ,0,0,0}, {26325,26413,26373 ,14900,14990,14949 ,0,0,0}, - {26372,26371,26374 ,14948,14947,14950 ,0,0,0}, {26414,26375,26371 ,14991,14951,14947 ,0,0,0}, - {26329,26373,26374 ,14904,14949,14950 ,0,0,0}, {26375,26374,26371 ,14951,14950,14947 ,0,0,0}, - {26415,26376,26414 ,14992,14952,14991 ,0,0,0}, {26376,26375,26414 ,14952,14951,14991 ,0,0,0}, - {26416,26377,26415 ,14993,14953,14992 ,0,0,0}, {26377,26376,26415 ,14953,14952,14992 ,0,0,0}, - {26417,26284,26416 ,14994,14859,14993 ,0,0,0}, {26284,26377,26416 ,14859,14953,14993 ,0,0,0}, - {26380,26282,26417 ,14956,14857,14994 ,0,0,0}, {26282,26284,26417 ,14857,14859,14994 ,0,0,0}, - {26380,25595,26378 ,14956,14995,14954 ,0,0,0}, {26282,26380,26379 ,14857,14956,14955 ,0,0,0}, - {26418,26381,26378 ,14996,14957,14954 ,0,0,0}, {26381,26379,26378 ,14957,14955,14954 ,0,0,0}, - {26419,26382,26418 ,14997,14958,14996 ,0,0,0}, {26382,26381,26418 ,14958,14957,14996 ,0,0,0}, - {26420,26383,26419 ,14998,14959,14997 ,0,0,0}, {26383,26382,26419 ,14959,14958,14997 ,0,0,0}, - {26421,26292,26420 ,14999,14867,14998 ,0,0,0}, {26292,26383,26420 ,14867,14959,14998 ,0,0,0}, - {26422,26290,26421 ,15000,14865,14999 ,0,0,0}, {26290,26292,26421 ,14865,14867,14999 ,0,0,0}, - {26384,26386,26422 ,14960,14963,15000 ,0,0,0}, {26290,26422,26386 ,14865,15000,14963 ,0,0,0}, - {26384,26385,26387 ,14960,14962,14964 ,0,0,0}, {26423,26388,26385 ,15001,14965,14962 ,0,0,0}, - {26340,26386,26387 ,14915,14963,14964 ,0,0,0}, {26388,26387,26385 ,14965,14964,14962 ,0,0,0}, - {26424,26389,26423 ,15002,14966,15001 ,0,0,0}, {26389,26388,26423 ,14966,14965,15001 ,0,0,0}, - {26425,26390,26424 ,15003,14967,15002 ,0,0,0}, {26390,26389,26424 ,14967,14966,15002 ,0,0,0}, - {26426,26343,26425 ,15004,14918,15003 ,0,0,0}, {26343,26390,26425 ,14918,14967,15003 ,0,0,0}, - {26393,26344,26426 ,14970,14919,15004 ,0,0,0}, {26344,26343,26426 ,14919,14918,15004 ,0,0,0}, - {26393,25617,26391 ,14970,15005,14968 ,0,0,0}, {26344,26393,26392 ,14919,14970,14969 ,0,0,0}, - {26427,26394,26391 ,15006,14971,14968 ,0,0,0}, {26394,26392,26391 ,14971,14969,14968 ,0,0,0}, - {26428,26395,26427 ,15007,14972,15006 ,0,0,0}, {26395,26394,26427 ,14972,14971,15006 ,0,0,0}, - {26429,26396,26428 ,15008,14973,15007 ,0,0,0}, {26396,26395,26428 ,14973,14972,15007 ,0,0,0}, - {26430,26397,26429 ,15009,14974,15008 ,0,0,0}, {26397,26396,26429 ,14974,14973,15008 ,0,0,0}, - {26431,26398,26430 ,15010,14975,15009 ,0,0,0}, {26398,26397,26430 ,14975,14974,15009 ,0,0,0}, - {26432,26399,26431 ,15011,14976,15010 ,0,0,0}, {26399,26398,26431 ,14976,14975,15010 ,0,0,0}, - {26433,26353,26432 ,15012,14928,15011 ,0,0,0}, {26353,26399,26432 ,14928,14976,15011 ,0,0,0}, - {26434,26354,26433 ,15013,14929,15012 ,0,0,0}, {26354,26353,26433 ,14929,14928,15012 ,0,0,0}, - {26435,26400,26434 ,15014,14977,15013 ,0,0,0}, {26400,26354,26434 ,14977,14929,15013 ,0,0,0}, - {26436,26130,26435 ,15015,14698,15014 ,0,0,0}, {26130,26400,26435 ,14698,14977,15014 ,0,0,0}, - {26436,26402,26128 ,15015,14979,14696 ,0,0,0}, {26128,26130,26436 ,14696,14698,15015 ,0,0,0}, - {26402,26401,26403 ,14979,14978,14980 ,0,0,0}, {26133,26403,26131 ,14701,14980,14699 ,0,0,0}, - {26263,26128,26403 ,14838,14696,14980 ,0,0,0}, {26401,26131,26403 ,14978,14699,14980 ,0,0,0}, - {26132,26131,26136 ,14700,14699,14704 ,0,0,0}, {26361,26064,26063 ,14936,14602,14601 ,0,0,0}, - {26063,26064,26360 ,14601,14602,14935 ,0,0,0}, {25689,25687,26068 ,14761,15016,14606 ,0,0,0}, - {26068,25687,26069 ,14606,15016,14607 ,0,0,0}, {25687,25555,26069 ,15016,15017,14607 ,0,0,0}, - {26069,25555,26364 ,14607,15017,14939 ,0,0,0}, {25555,25554,26364 ,15017,15018,14939 ,0,0,0}, - {26364,25554,26405 ,14939,15018,14982 ,0,0,0}, {25554,25575,26405 ,15018,15019,14982 ,0,0,0}, - {26405,25575,26406 ,14982,15019,14983 ,0,0,0}, {25575,25545,26406 ,15019,15020,14983 ,0,0,0}, - {26406,25545,26407 ,14983,15020,14984 ,0,0,0}, {25545,25580,26407 ,15020,15021,14984 ,0,0,0}, - {26407,25580,26408 ,14984,15021,14985 ,0,0,0}, {25580,25577,26408 ,15021,15022,14985 ,0,0,0}, - {26408,25577,26409 ,14985,15022,14986 ,0,0,0}, {25577,25582,26409 ,15022,15023,14986 ,0,0,0}, - {25582,25584,26410 ,15023,15024,14987 ,0,0,0}, {25582,26410,26409 ,15023,14987,14986 ,0,0,0}, - {25584,25550,26411 ,15024,15025,14988 ,0,0,0}, {25584,26411,26410 ,15024,14988,14987 ,0,0,0}, - {25550,25549,26412 ,15025,15026,14989 ,0,0,0}, {25550,26412,26411 ,15025,14989,14988 ,0,0,0}, - {25549,25586,26413 ,15026,15027,14990 ,0,0,0}, {25549,26413,26412 ,15026,14990,14989 ,0,0,0}, - {25586,25681,26372 ,15027,15028,14948 ,0,0,0}, {25586,26372,26413 ,15027,14948,14990 ,0,0,0}, - {25680,26372,25681 ,14946,14948,15028 ,0,0,0}, {25680,25589,26371 ,14946,15029,14947 ,0,0,0}, - {26371,25589,26414 ,14947,15029,14991 ,0,0,0}, {25589,25594,26414 ,15029,15030,14991 ,0,0,0}, - {26414,25594,26415 ,14991,15030,14992 ,0,0,0}, {25594,25592,26415 ,15030,15031,14992 ,0,0,0}, - {25592,25591,26416 ,15031,15032,14993 ,0,0,0}, {25592,26416,26415 ,15031,14993,14992 ,0,0,0}, - {25591,25679,26417 ,15032,15033,14994 ,0,0,0}, {25591,26417,26416 ,15032,14994,14993 ,0,0,0}, - {25679,25595,26380 ,15033,14995,14956 ,0,0,0}, {25679,26380,26417 ,15033,14956,14994 ,0,0,0}, - {25595,25678,26378 ,14995,15034,14954 ,0,0,0}, {25678,25674,26378 ,15034,15035,14954 ,0,0,0}, - {26378,25674,26418 ,14954,15035,14996 ,0,0,0}, {25674,25599,26418 ,15035,15036,14996 ,0,0,0}, - {26418,25599,26419 ,14996,15036,14997 ,0,0,0}, {25599,25601,26419 ,15036,15037,14997 ,0,0,0}, - {25601,25606,26420 ,15037,15038,14998 ,0,0,0}, {25601,26420,26419 ,15037,14998,14997 ,0,0,0}, - {25606,25604,26421 ,15038,15039,14999 ,0,0,0}, {25606,26421,26420 ,15038,14999,14998 ,0,0,0}, - {25604,25603,26422 ,15039,15040,15000 ,0,0,0}, {25604,26422,26421 ,15039,15000,14999 ,0,0,0}, - {25603,25672,26384 ,15040,15041,14960 ,0,0,0}, {25603,26384,26422 ,15040,14960,15000 ,0,0,0}, - {25671,26384,25672 ,14961,14960,15041 ,0,0,0}, {25671,25608,26385 ,14961,15042,14962 ,0,0,0}, - {26385,25608,26423 ,14962,15042,15001 ,0,0,0}, {25608,25615,26423 ,15042,15043,15001 ,0,0,0}, - {25615,25614,26424 ,15043,15044,15002 ,0,0,0}, {25615,26424,26423 ,15043,15002,15001 ,0,0,0}, - {25614,25613,26425 ,15044,15045,15003 ,0,0,0}, {25614,26425,26424 ,15044,15003,15002 ,0,0,0}, - {25613,25668,26426 ,15045,15046,15004 ,0,0,0}, {25613,26426,26425 ,15045,15004,15003 ,0,0,0}, - {25668,25617,26393 ,15046,15005,14970 ,0,0,0}, {25668,26393,26426 ,15046,14970,15004 ,0,0,0}, - {25617,25616,26391 ,15005,15047,14968 ,0,0,0}, {25616,25622,26391 ,15047,15048,14968 ,0,0,0}, - {26391,25622,26427 ,14968,15048,15006 ,0,0,0}, {25622,25621,26427 ,15048,15049,15006 ,0,0,0}, - {26427,25621,26428 ,15006,15049,15007 ,0,0,0}, {25621,25626,26428 ,15049,15050,15007 ,0,0,0}, - {26428,25626,26429 ,15007,15050,15008 ,0,0,0}, {25626,25624,26429 ,15050,15051,15008 ,0,0,0}, - {25624,25631,26430 ,15051,15052,15009 ,0,0,0}, {25624,26430,26429 ,15051,15009,15008 ,0,0,0}, - {25631,25628,26431 ,15052,15053,15010 ,0,0,0}, {25631,26431,26430 ,15052,15010,15009 ,0,0,0}, - {25628,25635,26432 ,15053,15054,15011 ,0,0,0}, {25628,26432,26431 ,15053,15011,15010 ,0,0,0}, - {25635,25632,26433 ,15054,15055,15012 ,0,0,0}, {25635,26433,26432 ,15054,15012,15011 ,0,0,0}, - {25632,25637,26434 ,15055,15056,15013 ,0,0,0}, {25632,26434,26433 ,15055,15013,15012 ,0,0,0}, - {25637,25636,26435 ,15056,15057,15014 ,0,0,0}, {25637,26435,26434 ,15056,15014,15013 ,0,0,0}, - {25636,25650,26436 ,15057,15058,15015 ,0,0,0}, {25636,26436,26435 ,15057,15015,15014 ,0,0,0}, - {25650,25649,26402 ,15058,15059,14979 ,0,0,0}, {25650,26402,26436 ,15058,14979,15015 ,0,0,0}, - {25649,25643,26401 ,15059,15060,14978 ,0,0,0}, {25649,26401,26402 ,15059,14978,14979 ,0,0,0}, - {25643,25645,26137 ,15060,14711,14705 ,0,0,0}, {25643,26137,26401 ,15060,14705,14978 ,0,0,0}, - {26138,26137,25645 ,14706,14705,14711 ,0,0,0}, {26437,26438,26439 ,15061,15062,15063 ,0,0,0}, - {26440,25514,25513 ,15064,15065,15066 ,0,0,0}, {26440,26441,25514 ,15064,15067,15065 ,0,0,0}, - {26442,25512,26443 ,15068,15069,15070 ,0,0,0}, {25513,26442,26440 ,15066,15068,15064 ,0,0,0}, - {26442,25513,25512 ,15068,15066,15069 ,0,0,0}, {25510,26444,25511 ,15071,15072,15073 ,0,0,0}, - {25425,25511,26444 ,15074,15073,15072 ,0,0,0}, {25425,26444,26443 ,15074,15072,15070 ,0,0,0}, - {25510,25509,26445 ,15071,15075,15076 ,0,0,0}, {25425,26443,25512 ,15074,15070,15069 ,0,0,0}, - {26444,25510,26445 ,15072,15071,15076 ,0,0,0}, {25515,25514,26441 ,15077,15065,15067 ,0,0,0}, - {26446,25508,26447 ,15078,15079,15080 ,0,0,0}, {26446,25509,25508 ,15078,15075,15079 ,0,0,0}, - {26448,26449,26450 ,15081,15082,15083 ,0,0,0}, {26451,26447,25507 ,15084,15080,15085 ,0,0,0}, - {25508,25507,26447 ,15079,15085,15080 ,0,0,0}, {26452,26451,25506 ,15086,15084,15087 ,0,0,0}, - {26452,25505,26453 ,15086,15088,15089 ,0,0,0}, {25506,25505,26452 ,15087,15088,15086 ,0,0,0}, - {26453,25505,25504 ,15089,15088,15090 ,0,0,0}, {25507,25506,26451 ,15085,15087,15084 ,0,0,0}, - {26445,25509,26446 ,15076,15075,15078 ,0,0,0}, {25503,25502,26454 ,15091,15092,15093 ,0,0,0}, - {25503,26455,25504 ,15091,15094,15090 ,0,0,0}, {25501,26456,25502 ,15095,15096,15092 ,0,0,0}, - {25503,26454,26455 ,15091,15093,15094 ,0,0,0}, {25501,25500,26457 ,15095,15097,15098 ,0,0,0}, - {26457,26456,25501 ,15098,15096,15095 ,0,0,0}, {26138,25196,25193 ,15099,13703,15100 ,0,0,0}, - {25502,26456,26454 ,15092,15096,15093 ,0,0,0}, {26457,25500,26458 ,15098,15097,15101 ,0,0,0}, - {26459,26138,25193 ,15102,15099,15100 ,0,0,0}, {26460,26461,26457 ,15103,15104,15098 ,0,0,0}, - {26462,26463,26464 ,15105,15106,15107 ,0,0,0}, {26465,26466,26467 ,15108,15109,15110 ,0,0,0}, - {26468,26469,26358 ,15111,15112,15113 ,0,0,0}, {26468,26132,26470 ,15111,15114,15115 ,0,0,0}, - {26458,25500,25499 ,15101,15097,15116 ,0,0,0}, {26459,25193,26464 ,15102,15100,15107 ,0,0,0}, - {26461,26471,26467 ,15104,15117,15110 ,0,0,0}, {26359,26469,26472 ,15118,15112,15119 ,0,0,0}, - {26473,26186,26474 ,15120,15121,15122 ,0,0,0}, {25062,26475,25499 ,15123,15124,15116 ,0,0,0}, - {26476,26265,26472 ,15125,15126,15119 ,0,0,0}, {26266,26265,26476 ,15127,15126,15125 ,0,0,0}, - {26359,26472,26220 ,15118,15119,15128 ,0,0,0}, {25067,26147,25065 ,13574,15129,15130 ,0,0,0}, - {25062,26473,26475 ,15123,15120,15124 ,0,0,0}, {26186,26473,26147 ,15121,15120,15129 ,0,0,0}, - {26473,25065,26147 ,15120,15130,15129 ,0,0,0}, {26471,26477,26467 ,15117,15131,15110 ,0,0,0}, - {26455,26453,25504 ,15094,15089,15090 ,0,0,0}, {26478,25515,26441 ,15132,15077,15067 ,0,0,0}, - {25516,26478,26479 ,15133,15132,15134 ,0,0,0}, {26478,25516,25515 ,15132,15133,15077 ,0,0,0}, - {26480,25475,26479 ,15135,15136,15134 ,0,0,0}, {25516,26479,25475 ,15133,15134,15136 ,0,0,0}, - {25517,26480,25518 ,15137,15135,15138 ,0,0,0}, {25517,25475,26480 ,15137,15136,15135 ,0,0,0}, - {25519,25518,26481 ,15139,15138,15140 ,0,0,0}, {26480,26481,25518 ,15135,15140,15138 ,0,0,0}, - {26482,25520,25519 ,15141,15142,15139 ,0,0,0}, {25519,26481,26482 ,15139,15140,15141 ,0,0,0}, - {26482,26483,25520 ,15141,15143,15142 ,0,0,0}, {25520,26483,25521 ,15142,15143,15144 ,0,0,0}, - {25521,26483,26484 ,15144,15143,15145 ,0,0,0}, {26485,26486,26487 ,15146,15147,15148 ,0,0,0}, - {26488,25522,26484 ,15149,15150,15145 ,0,0,0}, {25521,26484,25522 ,15144,15145,15150 ,0,0,0}, - {26488,26489,25523 ,15149,15151,15152 ,0,0,0}, {25523,25522,26488 ,15152,15150,15149 ,0,0,0}, - {25440,25524,26489 ,15153,15154,15151 ,0,0,0}, {26489,25524,25523 ,15151,15154,15152 ,0,0,0}, - {26490,25525,25440 ,15155,15156,15153 ,0,0,0}, {25440,26489,26490 ,15153,15151,15155 ,0,0,0}, - {25525,26491,25526 ,15156,15157,15158 ,0,0,0}, {26491,25525,26490 ,15157,15156,15155 ,0,0,0}, - {25527,25526,26492 ,15159,15158,15160 ,0,0,0}, {26491,26492,25526 ,15157,15160,15158 ,0,0,0}, - {26493,25527,26492 ,15161,15159,15160 ,0,0,0}, {26493,25528,25527 ,15161,15162,15159 ,0,0,0}, - {26493,26494,25528 ,15161,15163,15162 ,0,0,0}, {26495,26496,26497 ,15164,15165,15166 ,0,0,0}, - {25529,26494,26498 ,15167,15163,15168 ,0,0,0}, {26494,25529,25528 ,15163,15167,15162 ,0,0,0}, - {26499,25486,26498 ,15169,15170,15168 ,0,0,0}, {25529,26498,25486 ,15167,15168,15170 ,0,0,0}, - {25530,26499,25531 ,15171,15169,15172 ,0,0,0}, {25530,25486,26499 ,15171,15170,15169 ,0,0,0}, - {25532,25531,26500 ,15173,15172,15174 ,0,0,0}, {26499,26500,25531 ,15169,15174,15172 ,0,0,0}, - {26501,25533,25532 ,15175,15176,15173 ,0,0,0}, {25532,26500,26501 ,15173,15174,15175 ,0,0,0}, - {25533,26502,25534 ,15176,15177,15178 ,0,0,0}, {26502,25533,26501 ,15177,15176,15175 ,0,0,0}, - {25535,25534,26503 ,15179,15178,15180 ,0,0,0}, {26502,26503,25534 ,15177,15180,15178 ,0,0,0}, - {26504,25535,26503 ,15181,15179,15180 ,0,0,0}, {26504,25536,25535 ,15181,15182,15179 ,0,0,0}, - {26504,26505,25536 ,15181,15183,15182 ,0,0,0}, {26506,26507,26508 ,15184,15185,15186 ,0,0,0}, - {25537,26505,26507 ,15187,15183,15185 ,0,0,0}, {26505,25537,25536 ,15183,15187,15182 ,0,0,0}, - {26509,25538,26507 ,15188,15189,15185 ,0,0,0}, {25537,26507,25538 ,15187,15185,15189 ,0,0,0}, - {26510,26511,26512 ,15190,15191,15192 ,0,0,0}, {25539,25538,26509 ,15193,15189,15188 ,0,0,0}, - {26513,26514,26515 ,15194,15195,15196 ,0,0,0}, {26516,26517,26518 ,15197,15198,15199 ,0,0,0}, - {26519,26513,26520 ,15200,15194,15201 ,0,0,0}, {26521,26522,26523 ,15202,15203,15204 ,0,0,0}, - {26524,26525,26526 ,15205,15206,15207 ,0,0,0}, {26521,26527,26528 ,15202,15208,15209 ,0,0,0}, - {26529,26530,26531 ,15210,15211,15212 ,0,0,0}, {26528,26527,26532 ,15209,15208,15213 ,0,0,0}, - {25540,25539,26533 ,15214,15193,15215 ,0,0,0}, {25130,26532,26527 ,13637,15213,15208 ,0,0,0}, - {26534,26535,26536 ,15216,15217,15218 ,0,0,0}, {25539,26509,26533 ,15193,15188,15215 ,0,0,0}, - {25540,26518,25541 ,15214,15199,15219 ,0,0,0}, {26506,26509,26507 ,15184,15188,15185 ,0,0,0}, - {25542,25541,26535 ,15220,15219,15217 ,0,0,0}, {26518,26535,25541 ,15199,15217,15219 ,0,0,0}, - {25543,26534,25544 ,15221,15216,15222 ,0,0,0}, {25542,26535,26534 ,15220,15217,15216 ,0,0,0}, - {25544,26537,25164 ,15222,15223,13671 ,0,0,0}, {26534,26537,25544 ,15216,15223,15222 ,0,0,0}, - {25065,26473,25062 ,15130,15120,15123 ,0,0,0}, {26224,26474,26186 ,15224,15122,15121 ,0,0,0}, - {26224,26476,26474 ,15224,15125,15122 ,0,0,0}, {26475,26458,25499 ,15124,15101,15116 ,0,0,0}, - {26475,26474,26538 ,15124,15122,15225 ,0,0,0}, {26539,26456,26461 ,15226,15096,15104 ,0,0,0}, - {26458,26538,26460 ,15101,15225,15103 ,0,0,0}, {26540,26454,26539 ,15227,15093,15226 ,0,0,0}, - {26460,26457,26458 ,15103,15098,15101 ,0,0,0}, {26541,26455,26540 ,15228,15094,15227 ,0,0,0}, - {26461,26456,26457 ,15104,15096,15098 ,0,0,0}, {26542,26453,26541 ,15229,15089,15228 ,0,0,0}, - {26539,26454,26456 ,15226,15093,15096 ,0,0,0}, {26543,26452,26542 ,15230,15086,15229 ,0,0,0}, - {26540,26455,26454 ,15227,15094,15093 ,0,0,0}, {26544,26451,26543 ,15231,15084,15230 ,0,0,0}, - {26541,26453,26455 ,15228,15089,15094 ,0,0,0}, {26545,26447,26544 ,15232,15080,15231 ,0,0,0}, - {26542,26452,26453 ,15229,15086,15089 ,0,0,0}, {26545,26546,26446 ,15232,15233,15078 ,0,0,0}, - {26451,26452,26543 ,15084,15086,15230 ,0,0,0}, {26547,26445,26546 ,15234,15076,15233 ,0,0,0}, - {26447,26451,26544 ,15080,15084,15231 ,0,0,0}, {26448,26444,26547 ,15081,15072,15234 ,0,0,0}, - {26446,26447,26545 ,15078,15080,15232 ,0,0,0}, {26548,26443,26448 ,15235,15070,15081 ,0,0,0}, - {26445,26446,26546 ,15076,15078,15233 ,0,0,0}, {26549,26442,26548 ,15236,15068,15235 ,0,0,0}, - {26444,26445,26547 ,15072,15076,15234 ,0,0,0}, {26550,26440,26549 ,15237,15064,15236 ,0,0,0}, - {26448,26443,26444 ,15081,15070,15072 ,0,0,0}, {26551,26441,26550 ,15238,15067,15237 ,0,0,0}, - {26548,26442,26443 ,15235,15068,15070 ,0,0,0}, {26551,26552,26478 ,15238,15239,15132 ,0,0,0}, - {26440,26442,26549 ,15064,15068,15236 ,0,0,0}, {26553,26479,26552 ,15240,15134,15239 ,0,0,0}, - {26441,26440,26550 ,15067,15064,15237 ,0,0,0}, {26554,26480,26553 ,15241,15135,15240 ,0,0,0}, - {26478,26441,26551 ,15132,15067,15238 ,0,0,0}, {26555,26481,26554 ,15242,15140,15241 ,0,0,0}, - {26479,26478,26552 ,15134,15132,15239 ,0,0,0}, {26556,26482,26555 ,15243,15141,15242 ,0,0,0}, - {26480,26479,26553 ,15135,15134,15240 ,0,0,0}, {26557,26483,26556 ,15244,15143,15243 ,0,0,0}, - {26554,26481,26480 ,15241,15140,15135 ,0,0,0}, {26557,26558,26484 ,15244,15245,15145 ,0,0,0}, - {26482,26481,26555 ,15141,15140,15242 ,0,0,0}, {26559,26488,26558 ,15246,15149,15245 ,0,0,0}, - {26483,26482,26556 ,15143,15141,15243 ,0,0,0}, {26485,26489,26559 ,15146,15151,15246 ,0,0,0}, - {26484,26483,26557 ,15145,15143,15244 ,0,0,0}, {26560,26490,26485 ,15247,15155,15146 ,0,0,0}, - {26488,26484,26558 ,15149,15145,15245 ,0,0,0}, {26561,26491,26560 ,15248,15157,15247 ,0,0,0}, - {26489,26488,26559 ,15151,15149,15246 ,0,0,0}, {26562,26492,26561 ,15249,15160,15248 ,0,0,0}, - {26485,26490,26489 ,15146,15155,15151 ,0,0,0}, {26563,26493,26562 ,15250,15161,15249 ,0,0,0}, - {26560,26491,26490 ,15247,15157,15155 ,0,0,0}, {26563,26564,26494 ,15250,15251,15163 ,0,0,0}, - {26492,26491,26561 ,15160,15157,15248 ,0,0,0}, {26565,26498,26564 ,15252,15168,15251 ,0,0,0}, - {26493,26492,26562 ,15161,15160,15249 ,0,0,0}, {26566,26499,26565 ,15253,15169,15252 ,0,0,0}, - {26494,26493,26563 ,15163,15161,15250 ,0,0,0}, {26567,26500,26566 ,15254,15174,15253 ,0,0,0}, - {26498,26494,26564 ,15168,15163,15251 ,0,0,0}, {26568,26501,26567 ,15255,15175,15254 ,0,0,0}, - {26565,26499,26498 ,15252,15169,15168 ,0,0,0}, {26569,26502,26568 ,15256,15177,15255 ,0,0,0}, - {26566,26500,26499 ,15253,15174,15169 ,0,0,0}, {26570,26503,26569 ,15257,15180,15256 ,0,0,0}, - {26567,26501,26500 ,15254,15175,15174 ,0,0,0}, {26571,26504,26570 ,15258,15181,15257 ,0,0,0}, - {26568,26502,26501 ,15255,15177,15175 ,0,0,0}, {26571,26508,26505 ,15258,15186,15183 ,0,0,0}, - {26503,26502,26569 ,15180,15177,15256 ,0,0,0}, {26509,26506,26572 ,15188,15184,15259 ,0,0,0}, - {26504,26503,26570 ,15181,15180,15257 ,0,0,0}, {26526,26517,26530 ,15207,15198,15211 ,0,0,0}, - {26505,26504,26571 ,15183,15181,15258 ,0,0,0}, {26516,26533,26572 ,15197,15215,15259 ,0,0,0}, - {26507,26505,26508 ,15185,15183,15186 ,0,0,0}, {26516,26572,26573 ,15197,15259,15260 ,0,0,0}, - {26525,26536,26526 ,15206,15218,15207 ,0,0,0}, {26533,26518,25540 ,15215,15199,15214 ,0,0,0}, - {26533,26509,26572 ,15215,15188,15259 ,0,0,0}, {26574,26537,26575 ,15261,15223,15262 ,0,0,0}, - {26533,26516,26518 ,15215,15197,15199 ,0,0,0}, {26536,26535,26517 ,15218,15217,15198 ,0,0,0}, - {26576,26577,26537 ,15263,15264,15223 ,0,0,0}, {25542,26534,25543 ,15220,15216,15221 ,0,0,0}, - {26534,26575,26537 ,15216,15262,15223 ,0,0,0}, {25164,26537,26577 ,13671,15223,15264 ,0,0,0}, - {26473,26474,26475 ,15120,15122,15124 ,0,0,0}, {26266,26476,26224 ,15127,15125,15224 ,0,0,0}, - {26358,26404,26468 ,15113,15265,15111 ,0,0,0}, {26475,26538,26458 ,15124,15225,15101 ,0,0,0}, - {26538,26476,26578 ,15225,15125,15266 ,0,0,0}, {26467,26466,26539 ,15110,15109,15226 ,0,0,0}, - {26471,26460,26578 ,15117,15103,15266 ,0,0,0}, {26466,26579,26540 ,15109,15267,15227 ,0,0,0}, - {26471,26461,26460 ,15117,15104,15103 ,0,0,0}, {26579,26580,26541 ,15267,15268,15228 ,0,0,0}, - {26467,26539,26461 ,15110,15226,15104 ,0,0,0}, {26580,26581,26542 ,15268,15269,15229 ,0,0,0}, - {26466,26540,26539 ,15109,15227,15226 ,0,0,0}, {26581,26582,26543 ,15269,15270,15230 ,0,0,0}, - {26579,26541,26540 ,15267,15228,15227 ,0,0,0}, {26582,26583,26544 ,15270,15271,15231 ,0,0,0}, - {26580,26542,26541 ,15268,15229,15228 ,0,0,0}, {26583,26584,26545 ,15271,15272,15232 ,0,0,0}, - {26581,26543,26542 ,15269,15230,15229 ,0,0,0}, {26584,26585,26546 ,15272,15273,15233 ,0,0,0}, - {26582,26544,26543 ,15270,15231,15230 ,0,0,0}, {26585,26449,26547 ,15273,15082,15234 ,0,0,0}, - {26545,26544,26583 ,15232,15231,15271 ,0,0,0}, {26586,26587,26588 ,15274,15275,15276 ,0,0,0}, - {26546,26545,26584 ,15233,15232,15272 ,0,0,0}, {26450,26587,26548 ,15083,15275,15235 ,0,0,0}, - {26547,26546,26585 ,15234,15233,15273 ,0,0,0}, {26587,26586,26549 ,15275,15274,15236 ,0,0,0}, - {26448,26547,26449 ,15081,15234,15082 ,0,0,0}, {26586,26589,26550 ,15274,15277,15237 ,0,0,0}, - {26450,26548,26448 ,15083,15235,15081 ,0,0,0}, {26589,26590,26551 ,15277,15278,15238 ,0,0,0}, - {26587,26549,26548 ,15275,15236,15235 ,0,0,0}, {26590,26591,26552 ,15278,15279,15239 ,0,0,0}, - {26586,26550,26549 ,15274,15237,15236 ,0,0,0}, {26591,26592,26553 ,15279,15280,15240 ,0,0,0}, - {26551,26550,26589 ,15238,15237,15277 ,0,0,0}, {26438,26554,26592 ,15062,15241,15280 ,0,0,0}, - {26552,26551,26590 ,15239,15238,15278 ,0,0,0}, {26438,26437,26555 ,15062,15061,15242 ,0,0,0}, - {26553,26552,26591 ,15240,15239,15279 ,0,0,0}, {26437,26593,26556 ,15061,15281,15243 ,0,0,0}, - {26592,26554,26553 ,15280,15241,15240 ,0,0,0}, {26593,26594,26557 ,15281,15282,15244 ,0,0,0}, - {26438,26555,26554 ,15062,15242,15241 ,0,0,0}, {26594,26595,26558 ,15282,15283,15245 ,0,0,0}, - {26437,26556,26555 ,15061,15243,15242 ,0,0,0}, {26595,26486,26559 ,15283,15147,15246 ,0,0,0}, - {26557,26556,26593 ,15244,15243,15281 ,0,0,0}, {26596,26597,26598 ,15284,15285,15286 ,0,0,0}, - {26558,26557,26594 ,15245,15244,15282 ,0,0,0}, {26487,26599,26560 ,15148,15287,15247 ,0,0,0}, - {26559,26558,26595 ,15246,15245,15283 ,0,0,0}, {26599,26600,26561 ,15287,15288,15248 ,0,0,0}, - {26485,26559,26486 ,15146,15246,15147 ,0,0,0}, {26600,26601,26562 ,15288,15289,15249 ,0,0,0}, - {26487,26560,26485 ,15148,15247,15146 ,0,0,0}, {26601,26602,26563 ,15289,15290,15250 ,0,0,0}, - {26599,26561,26560 ,15287,15248,15247 ,0,0,0}, {26602,26603,26564 ,15290,15291,15251 ,0,0,0}, - {26600,26562,26561 ,15288,15249,15248 ,0,0,0}, {26603,26604,26565 ,15291,15292,15252 ,0,0,0}, - {26563,26562,26601 ,15250,15249,15289 ,0,0,0}, {26604,26495,26566 ,15292,15164,15253 ,0,0,0}, - {26564,26563,26602 ,15251,15250,15290 ,0,0,0}, {26495,26497,26567 ,15164,15166,15254 ,0,0,0}, - {26565,26564,26603 ,15252,15251,15291 ,0,0,0}, {26497,26605,26568 ,15166,15293,15255 ,0,0,0}, - {26604,26566,26565 ,15292,15253,15252 ,0,0,0}, {26605,26606,26569 ,15293,15294,15256 ,0,0,0}, - {26495,26567,26566 ,15164,15254,15253 ,0,0,0}, {26606,26607,26570 ,15294,15295,15257 ,0,0,0}, - {26497,26568,26567 ,15166,15255,15254 ,0,0,0}, {26607,26608,26571 ,15295,15296,15258 ,0,0,0}, - {26605,26569,26568 ,15293,15256,15255 ,0,0,0}, {26608,26609,26508 ,15296,15297,15186 ,0,0,0}, - {26606,26570,26569 ,15294,15257,15256 ,0,0,0}, {26609,26610,26506 ,15297,15298,15184 ,0,0,0}, - {26607,26571,26570 ,15295,15258,15257 ,0,0,0}, {26610,26573,26572 ,15298,15260,15259 ,0,0,0}, - {26608,26508,26571 ,15296,15186,15258 ,0,0,0}, {26573,26530,26516 ,15260,15211,15197 ,0,0,0}, - {26506,26508,26609 ,15184,15186,15297 ,0,0,0}, {26611,26525,26612 ,15299,15206,15300 ,0,0,0}, - {26506,26610,26572 ,15184,15298,15259 ,0,0,0}, {26536,26525,26575 ,15218,15206,15262 ,0,0,0}, - {26524,26612,26525 ,15205,15300,15206 ,0,0,0}, {26518,26517,26535 ,15199,15198,15217 ,0,0,0}, - {26530,26517,26516 ,15211,15198,15197 ,0,0,0}, {26613,26574,26510 ,15301,15261,15190 ,0,0,0}, - {26574,26576,26537 ,15261,15263,15223 ,0,0,0}, {26534,26536,26575 ,15216,15218,15262 ,0,0,0}, - {26574,26575,26611 ,15261,15262,15299 ,0,0,0}, {26613,26576,26574 ,15301,15263,15261 ,0,0,0}, - {26474,26476,26538 ,15122,15125,15225 ,0,0,0}, {26220,26472,26265 ,15128,15119,15126 ,0,0,0}, - {25191,26464,25193 ,15302,15107,15100 ,0,0,0}, {26538,26578,26460 ,15225,15266,15103 ,0,0,0}, - {26578,26472,26614 ,15266,15119,15303 ,0,0,0}, {26466,26615,26579 ,15109,15304,15267 ,0,0,0}, - {26477,26471,26614 ,15131,15117,15303 ,0,0,0}, {26579,26616,26580 ,15267,15305,15268 ,0,0,0}, - {26477,26465,26467 ,15131,15108,15110 ,0,0,0}, {26617,26618,26619 ,15306,15307,15308 ,0,0,0}, - {26465,26615,26466 ,15108,15304,15109 ,0,0,0}, {26581,26580,26620 ,15269,15268,15309 ,0,0,0}, - {26615,26616,26579 ,15304,15305,15267 ,0,0,0}, {26582,26581,26619 ,15270,15269,15308 ,0,0,0}, - {26616,26620,26580 ,15305,15309,15268 ,0,0,0}, {26583,26582,26618 ,15271,15270,15307 ,0,0,0}, - {26620,26619,26581 ,15309,15308,15269 ,0,0,0}, {26584,26583,26621 ,15272,15271,15310 ,0,0,0}, - {26619,26618,26582 ,15308,15307,15270 ,0,0,0}, {26585,26584,26622 ,15273,15272,15311 ,0,0,0}, - {26618,26621,26583 ,15307,15310,15271 ,0,0,0}, {26449,26585,26623 ,15082,15273,15312 ,0,0,0}, - {26621,26622,26584 ,15310,15311,15272 ,0,0,0}, {26450,26449,26624 ,15083,15082,15313 ,0,0,0}, - {26622,26623,26585 ,15311,15312,15273 ,0,0,0}, {26587,26450,26625 ,15275,15083,15314 ,0,0,0}, - {26624,26449,26623 ,15313,15082,15312 ,0,0,0}, {26626,26627,26628 ,15315,15316,15317 ,0,0,0}, - {26625,26450,26624 ,15314,15083,15313 ,0,0,0}, {26589,26586,26629 ,15277,15274,15318 ,0,0,0}, - {26625,26588,26587 ,15314,15276,15275 ,0,0,0}, {26590,26589,26628 ,15278,15277,15317 ,0,0,0}, - {26588,26629,26586 ,15276,15318,15274 ,0,0,0}, {26591,26590,26627 ,15279,15278,15316 ,0,0,0}, - {26629,26628,26589 ,15318,15317,15277 ,0,0,0}, {26592,26591,26630 ,15280,15279,15319 ,0,0,0}, - {26628,26627,26590 ,15317,15316,15278 ,0,0,0}, {26438,26592,26631 ,15062,15280,15320 ,0,0,0}, - {26630,26591,26627 ,15319,15279,15316 ,0,0,0}, {26632,26633,26634 ,15321,15322,15323 ,0,0,0}, - {26631,26592,26630 ,15320,15280,15319 ,0,0,0}, {26593,26437,26635 ,15281,15061,15324 ,0,0,0}, - {26631,26439,26438 ,15320,15063,15062 ,0,0,0}, {26594,26593,26634 ,15282,15281,15323 ,0,0,0}, - {26439,26635,26437 ,15063,15324,15061 ,0,0,0}, {26595,26594,26633 ,15283,15282,15322 ,0,0,0}, - {26635,26634,26593 ,15324,15323,15281 ,0,0,0}, {26486,26595,26636 ,15147,15283,15325 ,0,0,0}, - {26634,26633,26594 ,15323,15322,15282 ,0,0,0}, {26487,26486,26637 ,15148,15147,15326 ,0,0,0}, - {26633,26636,26595 ,15322,15325,15283 ,0,0,0}, {26599,26487,26638 ,15287,15148,15327 ,0,0,0}, - {26637,26486,26636 ,15326,15147,15325 ,0,0,0}, {26600,26599,26639 ,15288,15287,15328 ,0,0,0}, - {26638,26487,26637 ,15327,15148,15326 ,0,0,0}, {26601,26600,26596 ,15289,15288,15284 ,0,0,0}, - {26638,26639,26599 ,15327,15328,15287 ,0,0,0}, {26602,26601,26598 ,15290,15289,15286 ,0,0,0}, - {26639,26596,26600 ,15328,15284,15288 ,0,0,0}, {26603,26602,26640 ,15291,15290,15329 ,0,0,0}, - {26596,26598,26601 ,15284,15286,15289 ,0,0,0}, {26604,26603,26641 ,15292,15291,15330 ,0,0,0}, - {26598,26640,26602 ,15286,15329,15290 ,0,0,0}, {26495,26604,26642 ,15164,15292,15331 ,0,0,0}, - {26641,26603,26640 ,15330,15291,15329 ,0,0,0}, {26643,26644,26645 ,15332,15333,15334 ,0,0,0}, - {26642,26604,26641 ,15331,15292,15330 ,0,0,0}, {26605,26497,26646 ,15293,15166,15335 ,0,0,0}, - {26642,26496,26495 ,15331,15165,15164 ,0,0,0}, {26606,26605,26645 ,15294,15293,15334 ,0,0,0}, - {26496,26646,26497 ,15165,15335,15166 ,0,0,0}, {26607,26606,26644 ,15295,15294,15333 ,0,0,0}, - {26646,26645,26605 ,15335,15334,15293 ,0,0,0}, {26608,26607,26647 ,15296,15295,15336 ,0,0,0}, - {26645,26644,26606 ,15334,15333,15294 ,0,0,0}, {26609,26608,26648 ,15297,15296,15337 ,0,0,0}, - {26644,26647,26607 ,15333,15336,15295 ,0,0,0}, {26610,26609,26649 ,15298,15297,15338 ,0,0,0}, - {26647,26648,26608 ,15336,15337,15296 ,0,0,0}, {26573,26610,26650 ,15260,15298,15339 ,0,0,0}, - {26648,26649,26609 ,15337,15338,15297 ,0,0,0}, {26530,26573,26531 ,15211,15260,15212 ,0,0,0}, - {26649,26650,26610 ,15338,15339,15298 ,0,0,0}, {26526,26530,26529 ,15207,15211,15210 ,0,0,0}, - {26650,26531,26573 ,15339,15212,15260 ,0,0,0}, {26511,26612,26514 ,15191,15300,15195 ,0,0,0}, - {26612,26651,26514 ,15300,15340,15195 ,0,0,0}, {26517,26526,26536 ,15198,15207,15218 ,0,0,0}, - {26529,26524,26526 ,15210,15205,15207 ,0,0,0}, {26652,26510,26512 ,15341,15190,15192 ,0,0,0}, - {26574,26611,26510 ,15261,15299,15190 ,0,0,0}, {26575,26525,26611 ,15262,15206,15299 ,0,0,0}, - {26611,26511,26510 ,15299,15191,15190 ,0,0,0}, {26613,26510,26652 ,15301,15190,15341 ,0,0,0}, - {26472,26578,26476 ,15119,15266,15125 ,0,0,0}, {26358,26469,26359 ,15113,15112,15118 ,0,0,0}, - {26477,26653,26465 ,15131,15342,15108 ,0,0,0}, {26578,26614,26471 ,15266,15303,15117 ,0,0,0}, - {26469,26654,26614 ,15112,15343,15303 ,0,0,0}, {26615,26465,26655 ,15304,15108,15344 ,0,0,0}, - {26654,26653,26477 ,15343,15342,15131 ,0,0,0}, {26616,26615,26656 ,15305,15304,15345 ,0,0,0}, - {26465,26653,26655 ,15108,15342,15344 ,0,0,0}, {26620,26616,26657 ,15309,15305,15346 ,0,0,0}, - {26615,26655,26656 ,15304,15344,15345 ,0,0,0}, {26619,26620,26658 ,15308,15309,15347 ,0,0,0}, - {26656,26657,26616 ,15345,15346,15305 ,0,0,0}, {26659,26621,26618 ,15348,15310,15307 ,0,0,0}, - {26657,26658,26620 ,15346,15347,15309 ,0,0,0}, {26660,26661,26662 ,15349,15350,15351 ,0,0,0}, - {26658,26617,26619 ,15347,15306,15308 ,0,0,0}, {26621,26663,26622 ,15310,15352,15311 ,0,0,0}, - {26617,26659,26618 ,15306,15348,15307 ,0,0,0}, {26622,26661,26623 ,15311,15350,15312 ,0,0,0}, - {26659,26663,26621 ,15348,15352,15310 ,0,0,0}, {26623,26660,26624 ,15312,15349,15313 ,0,0,0}, - {26663,26661,26622 ,15352,15350,15311 ,0,0,0}, {26624,26664,26625 ,15313,15353,15314 ,0,0,0}, - {26661,26660,26623 ,15350,15349,15312 ,0,0,0}, {26625,26665,26588 ,15314,15354,15276 ,0,0,0}, - {26660,26664,26624 ,15349,15353,15313 ,0,0,0}, {26629,26588,26666 ,15318,15276,15355 ,0,0,0}, - {26664,26665,26625 ,15353,15354,15314 ,0,0,0}, {26628,26629,26667 ,15317,15318,15356 ,0,0,0}, - {26665,26666,26588 ,15354,15355,15276 ,0,0,0}, {26668,26669,26670 ,15357,15358,15359 ,0,0,0}, - {26666,26667,26629 ,15355,15356,15318 ,0,0,0}, {26627,26671,26630 ,15316,15360,15319 ,0,0,0}, - {26667,26626,26628 ,15356,15315,15317 ,0,0,0}, {26630,26672,26631 ,15319,15361,15320 ,0,0,0}, - {26626,26671,26627 ,15315,15360,15316 ,0,0,0}, {26631,26673,26439 ,15320,15362,15063 ,0,0,0}, - {26671,26672,26630 ,15360,15361,15319 ,0,0,0}, {26635,26439,26674 ,15324,15063,15363 ,0,0,0}, - {26672,26673,26631 ,15361,15362,15320 ,0,0,0}, {26634,26635,26675 ,15323,15324,15364 ,0,0,0}, - {26673,26674,26439 ,15362,15363,15063 ,0,0,0}, {26676,26677,26678 ,15365,15366,15367 ,0,0,0}, - {26674,26675,26635 ,15363,15364,15324 ,0,0,0}, {26633,26679,26636 ,15322,15368,15325 ,0,0,0}, - {26675,26632,26634 ,15364,15321,15323 ,0,0,0}, {26636,26680,26637 ,15325,15369,15326 ,0,0,0}, - {26632,26679,26633 ,15321,15368,15322 ,0,0,0}, {26637,26681,26638 ,15326,15370,15327 ,0,0,0}, - {26679,26680,26636 ,15368,15369,15325 ,0,0,0}, {26638,26682,26639 ,15327,15371,15328 ,0,0,0}, - {26680,26681,26637 ,15369,15370,15326 ,0,0,0}, {26596,26639,26683 ,15284,15328,15372 ,0,0,0}, - {26681,26682,26638 ,15370,15371,15327 ,0,0,0}, {26684,26685,26686 ,15373,15374,15375 ,0,0,0}, - {26682,26683,26639 ,15371,15372,15328 ,0,0,0}, {26598,26687,26640 ,15286,15376,15329 ,0,0,0}, - {26683,26597,26596 ,15372,15285,15284 ,0,0,0}, {26640,26685,26641 ,15329,15374,15330 ,0,0,0}, - {26597,26687,26598 ,15285,15376,15286 ,0,0,0}, {26641,26684,26642 ,15330,15373,15331 ,0,0,0}, - {26687,26685,26640 ,15376,15374,15329 ,0,0,0}, {26642,26688,26496 ,15331,15377,15165 ,0,0,0}, - {26685,26684,26641 ,15374,15373,15330 ,0,0,0}, {26646,26496,26689 ,15335,15165,15378 ,0,0,0}, - {26684,26688,26642 ,15373,15377,15331 ,0,0,0}, {26645,26646,26690 ,15334,15335,15379 ,0,0,0}, - {26688,26689,26496 ,15377,15378,15165 ,0,0,0}, {26691,26647,26644 ,15380,15336,15333 ,0,0,0}, - {26689,26690,26646 ,15378,15379,15335 ,0,0,0}, {26692,26693,26694 ,15381,15382,15383 ,0,0,0}, - {26690,26643,26645 ,15379,15332,15334 ,0,0,0}, {26647,26695,26648 ,15336,15384,15337 ,0,0,0}, - {26643,26691,26644 ,15332,15380,15333 ,0,0,0}, {26648,26693,26649 ,15337,15382,15338 ,0,0,0}, - {26691,26695,26647 ,15380,15384,15336 ,0,0,0}, {26649,26692,26650 ,15338,15381,15339 ,0,0,0}, - {26695,26693,26648 ,15384,15382,15337 ,0,0,0}, {26650,26696,26531 ,15339,15385,15212 ,0,0,0}, - {26693,26692,26649 ,15382,15381,15338 ,0,0,0}, {26531,26697,26529 ,15212,15386,15210 ,0,0,0}, - {26692,26696,26650 ,15381,15385,15339 ,0,0,0}, {26529,26698,26524 ,15210,15387,15205 ,0,0,0}, - {26696,26697,26531 ,15385,15386,15212 ,0,0,0}, {26524,26651,26612 ,15205,15340,15300 ,0,0,0}, - {26698,26529,26697 ,15387,15210,15386 ,0,0,0}, {26699,26700,26512 ,15388,15389,15192 ,0,0,0}, - {26524,26698,26651 ,15205,15387,15340 ,0,0,0}, {26701,26512,26700 ,15390,15192,15389 ,0,0,0}, - {26702,26652,26512 ,15391,15341,15192 ,0,0,0}, {26611,26612,26511 ,15299,15300,15191 ,0,0,0}, - {26511,26699,26512 ,15191,15388,15192 ,0,0,0}, {26701,26702,26512 ,15390,15391,15192 ,0,0,0}, - {26469,26614,26472 ,15112,15303,15119 ,0,0,0}, {26132,26468,26404 ,15114,15111,15265 ,0,0,0}, - {26653,26703,26655 ,15342,15392,15344 ,0,0,0}, {26614,26654,26477 ,15303,15343,15131 ,0,0,0}, - {26468,26704,26654 ,15111,15393,15343 ,0,0,0}, {26656,26655,26705 ,15345,15344,15394 ,0,0,0}, - {26653,26704,26703 ,15342,15393,15392 ,0,0,0}, {26657,26656,26706 ,15346,15345,15395 ,0,0,0}, - {26655,26703,26705 ,15344,15392,15394 ,0,0,0}, {26658,26657,26707 ,15347,15346,15396 ,0,0,0}, - {26656,26705,26706 ,15345,15394,15395 ,0,0,0}, {26617,26658,26708 ,15306,15347,15397 ,0,0,0}, - {26657,26706,26707 ,15346,15395,15396 ,0,0,0}, {26659,26617,26709 ,15348,15306,15398 ,0,0,0}, - {26658,26707,26708 ,15347,15396,15397 ,0,0,0}, {26663,26659,26710 ,15352,15348,15399 ,0,0,0}, - {26617,26708,26709 ,15306,15397,15398 ,0,0,0}, {26661,26663,26711 ,15350,15352,15400 ,0,0,0}, - {26709,26710,26659 ,15398,15399,15348 ,0,0,0}, {26712,26713,26714 ,15401,15402,15403 ,0,0,0}, - {26710,26711,26663 ,15399,15400,15352 ,0,0,0}, {26660,26715,26664 ,15349,15404,15353 ,0,0,0}, - {26711,26662,26661 ,15400,15351,15350 ,0,0,0}, {26664,26714,26665 ,15353,15403,15354 ,0,0,0}, - {26662,26715,26660 ,15351,15404,15349 ,0,0,0}, {26665,26716,26666 ,15354,15405,15355 ,0,0,0}, - {26715,26714,26664 ,15404,15403,15353 ,0,0,0}, {26667,26666,26717 ,15356,15355,15406 ,0,0,0}, - {26714,26716,26665 ,15403,15405,15354 ,0,0,0}, {26626,26667,26718 ,15315,15356,15407 ,0,0,0}, - {26666,26716,26717 ,15355,15405,15406 ,0,0,0}, {26671,26626,26719 ,15360,15315,15408 ,0,0,0}, - {26667,26717,26718 ,15356,15406,15407 ,0,0,0}, {26672,26671,26720 ,15361,15360,15409 ,0,0,0}, - {26718,26719,26626 ,15407,15408,15315 ,0,0,0}, {26672,26721,26673 ,15361,15410,15362 ,0,0,0}, - {26719,26720,26671 ,15408,15409,15360 ,0,0,0}, {26673,26669,26674 ,15362,15358,15363 ,0,0,0}, - {26720,26721,26672 ,15409,15410,15361 ,0,0,0}, {26675,26674,26722 ,15364,15363,15411 ,0,0,0}, - {26721,26669,26673 ,15410,15358,15362 ,0,0,0}, {26632,26675,26723 ,15321,15364,15412 ,0,0,0}, - {26674,26669,26722 ,15363,15358,15411 ,0,0,0}, {26679,26632,26724 ,15368,15321,15413 ,0,0,0}, - {26675,26722,26723 ,15364,15411,15412 ,0,0,0}, {26680,26679,26725 ,15369,15368,15414 ,0,0,0}, - {26723,26724,26632 ,15412,15413,15321 ,0,0,0}, {26680,26726,26681 ,15369,15415,15370 ,0,0,0}, - {26724,26725,26679 ,15413,15414,15368 ,0,0,0}, {26681,26677,26682 ,15370,15366,15371 ,0,0,0}, - {26725,26726,26680 ,15414,15415,15369 ,0,0,0}, {26683,26682,26727 ,15372,15371,15416 ,0,0,0}, - {26726,26677,26681 ,15415,15366,15370 ,0,0,0}, {26597,26683,26728 ,15285,15372,15417 ,0,0,0}, - {26682,26677,26727 ,15371,15366,15416 ,0,0,0}, {26687,26597,26729 ,15376,15285,15418 ,0,0,0}, - {26683,26727,26728 ,15372,15416,15417 ,0,0,0}, {26685,26687,26730 ,15374,15376,15419 ,0,0,0}, - {26728,26729,26597 ,15417,15418,15285 ,0,0,0}, {26731,26732,26733 ,15420,15421,15422 ,0,0,0}, - {26729,26730,26687 ,15418,15419,15376 ,0,0,0}, {26684,26734,26688 ,15373,15423,15377 ,0,0,0}, - {26730,26686,26685 ,15419,15375,15374 ,0,0,0}, {26688,26733,26689 ,15377,15422,15378 ,0,0,0}, - {26686,26734,26684 ,15375,15423,15373 ,0,0,0}, {26690,26689,26735 ,15379,15378,15424 ,0,0,0}, - {26734,26733,26688 ,15423,15422,15377 ,0,0,0}, {26643,26690,26736 ,15332,15379,15425 ,0,0,0}, - {26689,26733,26735 ,15378,15422,15424 ,0,0,0}, {26691,26643,26737 ,15380,15332,15426 ,0,0,0}, - {26690,26735,26736 ,15379,15424,15425 ,0,0,0}, {26695,26691,26738 ,15384,15380,15427 ,0,0,0}, - {26643,26736,26737 ,15332,15425,15426 ,0,0,0}, {26693,26695,26739 ,15382,15384,15428 ,0,0,0}, - {26737,26738,26691 ,15426,15427,15380 ,0,0,0}, {26740,26696,26692 ,15429,15385,15381 ,0,0,0}, - {26738,26739,26695 ,15427,15428,15384 ,0,0,0}, {26741,26742,26743 ,15430,15431,15432 ,0,0,0}, - {26739,26694,26693 ,15428,15383,15382 ,0,0,0}, {26696,26744,26697 ,15385,15433,15386 ,0,0,0}, - {26694,26740,26692 ,15383,15429,15381 ,0,0,0}, {26697,26743,26698 ,15386,15432,15387 ,0,0,0}, - {26740,26744,26696 ,15429,15433,15385 ,0,0,0}, {26698,26745,26651 ,15387,15434,15340 ,0,0,0}, - {26744,26743,26697 ,15433,15432,15386 ,0,0,0}, {26651,26515,26514 ,15340,15196,15195 ,0,0,0}, - {26743,26745,26698 ,15432,15434,15387 ,0,0,0}, {26514,26513,26699 ,15195,15194,15388 ,0,0,0}, - {26515,26651,26745 ,15196,15340,15434 ,0,0,0}, {26700,26746,26523 ,15389,15435,15204 ,0,0,0}, - {26747,26748,26700 ,15436,15437,15389 ,0,0,0}, {26511,26514,26699 ,15191,15195,15388 ,0,0,0}, - {26699,26746,26700 ,15388,15435,15389 ,0,0,0}, {26701,26700,26748 ,15390,15389,15437 ,0,0,0}, - {26469,26468,26654 ,15112,15111,15343 ,0,0,0}, {26136,26470,26132 ,15438,15115,15114 ,0,0,0}, - {26705,26703,26463 ,15394,15392,15106 ,0,0,0}, {26654,26704,26653 ,15343,15393,15342 ,0,0,0}, - {26470,26749,26704 ,15115,15439,15393 ,0,0,0}, {26706,26705,26750 ,15395,15394,15440 ,0,0,0}, - {26703,26749,26463 ,15392,15439,15106 ,0,0,0}, {26751,26750,26752 ,15441,15440,15442 ,0,0,0}, - {26705,26463,26750 ,15394,15106,15440 ,0,0,0}, {26751,26753,26707 ,15441,15443,15396 ,0,0,0}, - {26707,26706,26751 ,15396,15395,15441 ,0,0,0}, {26753,26754,26708 ,15443,15444,15397 ,0,0,0}, - {26708,26707,26753 ,15397,15396,15443 ,0,0,0}, {26754,26755,26709 ,15444,15445,15398 ,0,0,0}, - {26709,26708,26754 ,15398,15397,15444 ,0,0,0}, {26755,26756,26710 ,15445,15446,15399 ,0,0,0}, - {26710,26709,26755 ,15399,15398,15445 ,0,0,0}, {26756,26757,26711 ,15446,15447,15400 ,0,0,0}, - {26711,26710,26756 ,15400,15399,15446 ,0,0,0}, {26757,26758,26662 ,15447,15448,15351 ,0,0,0}, - {26662,26711,26757 ,15351,15400,15447 ,0,0,0}, {26758,26712,26715 ,15448,15401,15404 ,0,0,0}, - {26662,26758,26715 ,15351,15448,15404 ,0,0,0}, {25179,26759,26760 ,15449,15450,15451 ,0,0,0}, - {26715,26712,26714 ,15404,15401,15403 ,0,0,0}, {26716,26761,26717 ,15405,15452,15406 ,0,0,0}, - {26714,26713,26716 ,15403,15402,15405 ,0,0,0}, {26762,26761,26760 ,15453,15452,15451 ,0,0,0}, - {26713,26761,26716 ,15402,15452,15405 ,0,0,0}, {26762,26763,26718 ,15453,15454,15407 ,0,0,0}, - {26718,26717,26762 ,15407,15406,15453 ,0,0,0}, {26763,26764,26719 ,15454,15455,15408 ,0,0,0}, - {26719,26718,26763 ,15408,15407,15454 ,0,0,0}, {26764,26765,26720 ,15455,15456,15409 ,0,0,0}, - {26720,26719,26764 ,15409,15408,15455 ,0,0,0}, {26765,26670,26721 ,15456,15359,15410 ,0,0,0}, - {26720,26765,26721 ,15409,15456,15410 ,0,0,0}, {26766,26767,26768 ,15457,15458,15459 ,0,0,0}, - {26721,26670,26669 ,15410,15359,15358 ,0,0,0}, {26668,26767,26722 ,15357,15458,15411 ,0,0,0}, - {26669,26668,26722 ,15358,15357,15411 ,0,0,0}, {26767,26769,26723 ,15458,15460,15412 ,0,0,0}, - {26723,26722,26767 ,15412,15411,15458 ,0,0,0}, {26769,26770,26724 ,15460,15461,15413 ,0,0,0}, - {26724,26723,26769 ,15413,15412,15460 ,0,0,0}, {26770,26771,26725 ,15461,15462,15414 ,0,0,0}, - {26725,26724,26770 ,15414,15413,15461 ,0,0,0}, {26771,26678,26726 ,15462,15367,15415 ,0,0,0}, - {26725,26771,26726 ,15414,15462,15415 ,0,0,0}, {26772,25170,26773 ,15463,15464,15465 ,0,0,0}, - {26726,26678,26677 ,15415,15367,15366 ,0,0,0}, {26728,26727,26774 ,15417,15416,15466 ,0,0,0}, - {26677,26676,26727 ,15366,15365,15416 ,0,0,0}, {26775,26774,26772 ,15467,15466,15463 ,0,0,0}, - {26727,26676,26774 ,15416,15365,15466 ,0,0,0}, {26775,26776,26729 ,15467,15468,15418 ,0,0,0}, - {26729,26728,26775 ,15418,15417,15467 ,0,0,0}, {26776,26777,26730 ,15468,15469,15419 ,0,0,0}, - {26730,26729,26776 ,15419,15418,15468 ,0,0,0}, {26777,26778,26686 ,15469,15470,15375 ,0,0,0}, - {26686,26730,26777 ,15375,15419,15469 ,0,0,0}, {26778,26731,26734 ,15470,15420,15423 ,0,0,0}, - {26686,26778,26734 ,15375,15470,15423 ,0,0,0}, {26779,26780,26781 ,15471,15472,15473 ,0,0,0}, - {26734,26731,26733 ,15423,15420,15422 ,0,0,0}, {26732,26780,26735 ,15421,15472,15424 ,0,0,0}, - {26733,26732,26735 ,15422,15421,15424 ,0,0,0}, {26780,26782,26736 ,15472,15474,15425 ,0,0,0}, - {26736,26735,26780 ,15425,15424,15472 ,0,0,0}, {26782,26783,26737 ,15474,15475,15426 ,0,0,0}, - {26737,26736,26782 ,15426,15425,15474 ,0,0,0}, {26783,26784,26738 ,15475,15476,15427 ,0,0,0}, - {26738,26737,26783 ,15427,15426,15475 ,0,0,0}, {26784,26785,26739 ,15476,15477,15428 ,0,0,0}, - {26739,26738,26784 ,15428,15427,15476 ,0,0,0}, {26785,26786,26694 ,15477,15478,15383 ,0,0,0}, - {26694,26739,26785 ,15383,15428,15477 ,0,0,0}, {26786,26787,26740 ,15478,15479,15429 ,0,0,0}, - {26740,26694,26786 ,15429,15383,15478 ,0,0,0}, {26787,26741,26744 ,15479,15430,15433 ,0,0,0}, - {26740,26787,26744 ,15429,15479,15433 ,0,0,0}, {26745,26742,26788 ,15434,15431,15480 ,0,0,0}, - {26744,26741,26743 ,15433,15430,15432 ,0,0,0}, {26520,26513,26515 ,15201,15194,15196 ,0,0,0}, - {26743,26742,26745 ,15432,15431,15434 ,0,0,0}, {26519,26746,26513 ,15200,15435,15194 ,0,0,0}, - {26745,26788,26515 ,15434,15480,15196 ,0,0,0}, {26527,26521,26789 ,15208,15202,15481 ,0,0,0}, - {26788,26520,26515 ,15480,15201,15196 ,0,0,0}, {26519,26790,26791 ,15200,15482,15483 ,0,0,0}, - {26523,26747,26700 ,15204,15436,15389 ,0,0,0}, {26699,26513,26746 ,15388,15194,15435 ,0,0,0}, - {26523,26746,26791 ,15204,15435,15483 ,0,0,0}, {26522,26747,26523 ,15203,15436,15204 ,0,0,0}, - {26468,26470,26704 ,15111,15115,15393 ,0,0,0}, {26136,26138,26459 ,15438,15099,15102 ,0,0,0}, - {26749,26459,26464 ,15439,15102,15107 ,0,0,0}, {26704,26749,26703 ,15393,15439,15392 ,0,0,0}, - {26463,26749,26464 ,15106,15439,15107 ,0,0,0}, {26462,26752,26750 ,15105,15442,15440 ,0,0,0}, - {26750,26463,26462 ,15440,15106,15105 ,0,0,0}, {26752,26792,26751 ,15442,15484,15441 ,0,0,0}, - {26793,26753,26792 ,15485,15443,15484 ,0,0,0}, {26706,26750,26751 ,15395,15440,15441 ,0,0,0}, - {26753,26751,26792 ,15443,15441,15484 ,0,0,0}, {26794,26754,26793 ,15486,15444,15485 ,0,0,0}, - {26754,26753,26793 ,15444,15443,15485 ,0,0,0}, {26795,26755,26794 ,15487,15445,15486 ,0,0,0}, - {26755,26754,26794 ,15445,15444,15486 ,0,0,0}, {26796,26756,26795 ,15488,15446,15487 ,0,0,0}, - {26756,26755,26795 ,15446,15445,15487 ,0,0,0}, {26797,26757,26796 ,15489,15447,15488 ,0,0,0}, - {26757,26756,26796 ,15447,15446,15488 ,0,0,0}, {26798,26758,26797 ,15490,15448,15489 ,0,0,0}, - {26758,26757,26797 ,15448,15447,15489 ,0,0,0}, {26799,26712,26798 ,15491,15401,15490 ,0,0,0}, - {26712,26758,26798 ,15401,15448,15490 ,0,0,0}, {26800,26713,26799 ,15492,15402,15491 ,0,0,0}, - {26713,26712,26799 ,15402,15401,15491 ,0,0,0}, {26760,26761,26800 ,15451,15452,15492 ,0,0,0}, - {26713,26800,26761 ,15402,15492,15452 ,0,0,0}, {26760,26759,26762 ,15451,15450,15453 ,0,0,0}, - {26801,26763,26759 ,15493,15454,15450 ,0,0,0}, {26717,26761,26762 ,15406,15452,15453 ,0,0,0}, - {26763,26762,26759 ,15454,15453,15450 ,0,0,0}, {26802,26764,26801 ,15494,15455,15493 ,0,0,0}, - {26764,26763,26801 ,15455,15454,15493 ,0,0,0}, {26803,26765,26802 ,15495,15456,15494 ,0,0,0}, - {26765,26764,26802 ,15456,15455,15494 ,0,0,0}, {26804,26670,26803 ,15496,15359,15495 ,0,0,0}, - {26670,26765,26803 ,15359,15456,15495 ,0,0,0}, {26768,26668,26804 ,15459,15357,15496 ,0,0,0}, - {26668,26670,26804 ,15357,15359,15496 ,0,0,0}, {26768,25087,26766 ,15459,15497,15457 ,0,0,0}, - {26668,26768,26767 ,15357,15459,15458 ,0,0,0}, {26805,26769,26766 ,15498,15460,15457 ,0,0,0}, - {26769,26767,26766 ,15460,15458,15457 ,0,0,0}, {26806,26770,26805 ,15499,15461,15498 ,0,0,0}, - {26770,26769,26805 ,15461,15460,15498 ,0,0,0}, {26807,26771,26806 ,15500,15462,15499 ,0,0,0}, - {26771,26770,26806 ,15462,15461,15499 ,0,0,0}, {26808,26678,26807 ,15501,15367,15500 ,0,0,0}, - {26678,26771,26807 ,15367,15462,15500 ,0,0,0}, {26809,26676,26808 ,15502,15365,15501 ,0,0,0}, - {26676,26678,26808 ,15365,15367,15501 ,0,0,0}, {26772,26774,26809 ,15463,15466,15502 ,0,0,0}, - {26676,26809,26774 ,15365,15502,15466 ,0,0,0}, {26772,26773,26775 ,15463,15465,15467 ,0,0,0}, - {26810,26776,26773 ,15503,15468,15465 ,0,0,0}, {26728,26774,26775 ,15417,15466,15467 ,0,0,0}, - {26776,26775,26773 ,15468,15467,15465 ,0,0,0}, {26811,26777,26810 ,15504,15469,15503 ,0,0,0}, - {26777,26776,26810 ,15469,15468,15503 ,0,0,0}, {26812,26778,26811 ,15505,15470,15504 ,0,0,0}, - {26778,26777,26811 ,15470,15469,15504 ,0,0,0}, {26813,26731,26812 ,15506,15420,15505 ,0,0,0}, - {26731,26778,26812 ,15420,15470,15505 ,0,0,0}, {26781,26732,26813 ,15473,15421,15506 ,0,0,0}, - {26732,26731,26813 ,15421,15420,15506 ,0,0,0}, {26781,25109,26779 ,15473,15507,15471 ,0,0,0}, - {26732,26781,26780 ,15421,15473,15472 ,0,0,0}, {26814,26782,26779 ,15508,15474,15471 ,0,0,0}, - {26782,26780,26779 ,15474,15472,15471 ,0,0,0}, {26815,26783,26814 ,15509,15475,15508 ,0,0,0}, - {26783,26782,26814 ,15475,15474,15508 ,0,0,0}, {26816,26784,26815 ,15510,15476,15509 ,0,0,0}, - {26784,26783,26815 ,15476,15475,15509 ,0,0,0}, {26817,26785,26816 ,15511,15477,15510 ,0,0,0}, - {26785,26784,26816 ,15477,15476,15510 ,0,0,0}, {26818,26786,26817 ,15512,15478,15511 ,0,0,0}, - {26786,26785,26817 ,15478,15477,15511 ,0,0,0}, {26819,26787,26818 ,15513,15479,15512 ,0,0,0}, - {26787,26786,26818 ,15479,15478,15512 ,0,0,0}, {26820,26741,26819 ,15514,15430,15513 ,0,0,0}, - {26741,26787,26819 ,15430,15479,15513 ,0,0,0}, {26821,26742,26820 ,15515,15431,15514 ,0,0,0}, - {26742,26741,26820 ,15431,15430,15514 ,0,0,0}, {26822,26788,26821 ,15516,15480,15515 ,0,0,0}, - {26788,26742,26821 ,15480,15431,15515 ,0,0,0}, {26823,26520,26822 ,15517,15201,15516 ,0,0,0}, - {26520,26788,26822 ,15201,15480,15516 ,0,0,0}, {26823,26790,26519 ,15517,15482,15200 ,0,0,0}, - {26519,26520,26823 ,15200,15201,15517 ,0,0,0}, {26790,26789,26791 ,15482,15481,15483 ,0,0,0}, - {26523,26791,26521 ,15204,15483,15202 ,0,0,0}, {26746,26519,26791 ,15435,15200,15483 ,0,0,0}, - {26789,26521,26791 ,15481,15202,15483 ,0,0,0}, {26522,26521,26528 ,15203,15202,15209 ,0,0,0}, - {26749,26470,26459 ,15439,15115,15102 ,0,0,0}, {26459,26470,26136 ,15102,15115,15438 ,0,0,0}, - {25191,25187,26464 ,15302,15518,15107 ,0,0,0}, {26464,25187,26462 ,15107,15518,15105 ,0,0,0}, - {25187,25186,26462 ,15518,15519,15105 ,0,0,0}, {26462,25186,26752 ,15105,15519,15442 ,0,0,0}, - {25186,25185,26752 ,15519,15520,15442 ,0,0,0}, {26752,25185,26792 ,15442,15520,15484 ,0,0,0}, - {25185,25048,26792 ,15520,15521,15484 ,0,0,0}, {26792,25048,26793 ,15484,15521,15485 ,0,0,0}, - {25048,25038,26793 ,15521,15522,15485 ,0,0,0}, {26793,25038,26794 ,15485,15522,15486 ,0,0,0}, - {25038,25071,26794 ,15522,15523,15486 ,0,0,0}, {26794,25071,26795 ,15486,15523,15487 ,0,0,0}, - {25071,25068,26795 ,15523,15524,15487 ,0,0,0}, {26795,25068,26796 ,15487,15524,15488 ,0,0,0}, - {25068,25073,26796 ,15524,15525,15488 ,0,0,0}, {25073,25076,26797 ,15525,15526,15489 ,0,0,0}, - {25073,26797,26796 ,15525,15489,15488 ,0,0,0}, {25076,25043,26798 ,15526,15527,15490 ,0,0,0}, - {25076,26798,26797 ,15526,15490,15489 ,0,0,0}, {25043,25042,26799 ,15527,15528,15491 ,0,0,0}, - {25043,26799,26798 ,15527,15491,15490 ,0,0,0}, {25042,25078,26800 ,15528,15529,15492 ,0,0,0}, - {25042,26800,26799 ,15528,15492,15491 ,0,0,0}, {25078,25180,26760 ,15529,15530,15451 ,0,0,0}, - {25078,26760,26800 ,15529,15451,15492 ,0,0,0}, {25179,26760,25180 ,15449,15451,15530 ,0,0,0}, - {25179,25081,26759 ,15449,15531,15450 ,0,0,0}, {26759,25081,26801 ,15450,15531,15493 ,0,0,0}, - {25081,25086,26801 ,15531,15532,15493 ,0,0,0}, {26801,25086,26802 ,15493,15532,15494 ,0,0,0}, - {25086,25084,26802 ,15532,15533,15494 ,0,0,0}, {25084,25083,26803 ,15533,15534,15495 ,0,0,0}, - {25084,26803,26802 ,15533,15495,15494 ,0,0,0}, {25083,25178,26804 ,15534,15535,15496 ,0,0,0}, - {25083,26804,26803 ,15534,15496,15495 ,0,0,0}, {25178,25087,26768 ,15535,15497,15459 ,0,0,0}, - {25178,26768,26804 ,15535,15459,15496 ,0,0,0}, {25087,25177,26766 ,15497,15536,15457 ,0,0,0}, - {25177,25173,26766 ,15536,15537,15457 ,0,0,0}, {26766,25173,26805 ,15457,15537,15498 ,0,0,0}, - {25173,25091,26805 ,15537,15538,15498 ,0,0,0}, {26805,25091,26806 ,15498,15538,15499 ,0,0,0}, - {25091,25093,26806 ,15538,15539,15499 ,0,0,0}, {25093,25098,26807 ,15539,15540,15500 ,0,0,0}, - {25093,26807,26806 ,15539,15500,15499 ,0,0,0}, {25098,25096,26808 ,15540,15541,15501 ,0,0,0}, - {25098,26808,26807 ,15540,15501,15500 ,0,0,0}, {25096,25095,26809 ,15541,15542,15502 ,0,0,0}, - {25096,26809,26808 ,15541,15502,15501 ,0,0,0}, {25095,25171,26772 ,15542,15543,15463 ,0,0,0}, - {25095,26772,26809 ,15542,15463,15502 ,0,0,0}, {25170,26772,25171 ,15464,15463,15543 ,0,0,0}, - {25170,25100,26773 ,15464,15544,15465 ,0,0,0}, {26773,25100,26810 ,15465,15544,15503 ,0,0,0}, - {25100,25107,26810 ,15544,15545,15503 ,0,0,0}, {25107,25106,26811 ,15545,15546,15504 ,0,0,0}, - {25107,26811,26810 ,15545,15504,15503 ,0,0,0}, {25106,25105,26812 ,15546,15547,15505 ,0,0,0}, - {25106,26812,26811 ,15546,15505,15504 ,0,0,0}, {25105,25167,26813 ,15547,15548,15506 ,0,0,0}, - {25105,26813,26812 ,15547,15506,15505 ,0,0,0}, {25167,25109,26781 ,15548,15507,15473 ,0,0,0}, - {25167,26781,26813 ,15548,15473,15506 ,0,0,0}, {25109,25108,26779 ,15507,15549,15471 ,0,0,0}, - {25108,25114,26779 ,15549,15550,15471 ,0,0,0}, {26779,25114,26814 ,15471,15550,15508 ,0,0,0}, - {25114,25113,26814 ,15550,15551,15508 ,0,0,0}, {26814,25113,26815 ,15508,15551,15509 ,0,0,0}, - {25113,25118,26815 ,15551,15552,15509 ,0,0,0}, {26815,25118,26816 ,15509,15552,15510 ,0,0,0}, - {25118,25116,26816 ,15552,15553,15510 ,0,0,0}, {25116,25124,26817 ,15553,15554,15511 ,0,0,0}, - {25116,26817,26816 ,15553,15511,15510 ,0,0,0}, {25124,25120,26818 ,15554,15555,15512 ,0,0,0}, - {25124,26818,26817 ,15554,15512,15511 ,0,0,0}, {25120,25122,26819 ,15555,15556,15513 ,0,0,0}, - {25120,26819,26818 ,15555,15513,15512 ,0,0,0}, {25122,25125,26820 ,15556,15557,15514 ,0,0,0}, - {25122,26820,26819 ,15556,15514,15513 ,0,0,0}, {25125,25127,26821 ,15557,15558,15515 ,0,0,0}, - {25125,26821,26820 ,15557,15515,15514 ,0,0,0}, {25127,25132,26822 ,15558,15559,15516 ,0,0,0}, - {25127,26822,26821 ,15558,15516,15515 ,0,0,0}, {25132,25138,26823 ,15559,15560,15517 ,0,0,0}, - {25132,26823,26822 ,15559,15517,15516 ,0,0,0}, {25138,25139,26790 ,15560,15561,15482 ,0,0,0}, - {25138,26790,26823 ,15560,15482,15517 ,0,0,0}, {25139,25137,26789 ,15561,15562,15481 ,0,0,0}, - {25139,26789,26790 ,15561,15481,15482 ,0,0,0}, {25137,25131,26527 ,15562,15563,15208 ,0,0,0}, - {25137,26527,26789 ,15562,15208,15481 ,0,0,0}, {26527,25131,25130 ,15208,15563,13637 ,0,0,0}, - {26360,26066,26087 ,15564,15564,15564 ,0,0,0}, {25696,26083,25692 ,15564,15564,15564 ,0,0,0}, - {26082,26087,26148 ,15564,15564,15564 ,0,0,0}, {26360,26087,26067 ,15564,15564,15564 ,0,0,0}, - {26082,26148,26225 ,15564,15564,15564 ,0,0,0}, {26067,26082,25697 ,15564,15564,15564 ,0,0,0}, - {26087,26082,26067 ,15564,15564,15564 ,0,0,0}, {25557,25692,26083 ,15564,15564,15564 ,0,0,0}, - {25696,26080,26077 ,15564,15564,15564 ,0,0,0}, {25563,25572,25907 ,15564,15564,15564 ,0,0,0}, - {25698,25557,26083 ,15564,15564,15564 ,0,0,0}, {25699,25698,25563 ,15564,15564,15564 ,0,0,0}, - {25698,25699,25688 ,15564,15564,15564 ,0,0,0}, {25570,25563,25907 ,15564,15564,15564 ,0,0,0}, - {25571,25572,25698 ,15564,15564,15564 ,0,0,0}, {25572,25563,25698 ,15564,15564,15564 ,0,0,0}, - {26085,25698,26083 ,15564,15564,15564 ,0,0,0}, {26085,25571,25698 ,15564,15564,15564 ,0,0,0}, - {26083,25696,26077 ,15564,15564,15564 ,0,0,0}, {26080,25696,26082 ,15564,15564,15564 ,0,0,0}, - {25697,26082,25695 ,15564,15564,15564 ,0,0,0}, {25696,25695,26082 ,15564,15564,15564 ,0,0,0}, - {26747,26522,26528 ,15565,15565,15565 ,0,0,0}, {26576,26613,25326 ,15565,15565,15565 ,0,0,0}, - {26532,26748,26528 ,15565,15565,15565 ,0,0,0}, {26652,26702,25242 ,15565,15565,15565 ,0,0,0}, - {26701,26748,26702 ,15565,15565,15565 ,0,0,0}, {26748,26532,25130 ,15565,15565,15565 ,0,0,0}, - {26747,26528,26748 ,15565,15565,15565 ,0,0,0}, {25242,26702,26748 ,15565,15565,15565 ,0,0,0}, - {26748,25130,25242 ,15565,15565,15565 ,0,0,0}, {25241,26652,25242 ,15565,15565,15565 ,0,0,0}, - {25241,25284,26652 ,15565,15565,15565 ,0,0,0}, {26613,26652,25326 ,15565,15565,15565 ,0,0,0}, - {25284,25326,26652 ,15565,15565,15565 ,0,0,0}, {26577,26576,25326 ,15565,15565,15565 ,0,0,0}, - {25370,25412,25371 ,15565,15565,15565 ,0,0,0}, {25371,26577,25326 ,15565,15565,15565 ,0,0,0}, - {26577,25371,25412 ,15565,15565,15565 ,0,0,0}, {25163,25411,25158 ,15565,15565,15565 ,0,0,0}, - {26577,25412,25164 ,15565,15565,15565 ,0,0,0}, {25412,25163,25162 ,15565,15565,15565 ,0,0,0}, - {25163,25412,25411 ,15565,15565,15565 ,0,0,0}, {25412,25162,25164 ,15565,15565,15565 ,0,0,0} -// Landegestell.prt - , {26824,26825,26826 ,15055,15013,15566 ,0,0,0}, {26827,26828,26829 ,15567,15049,15050 ,0,0,0}, - {26830,26831,26832 ,15568,15569,15570 ,0,0,0}, {26833,26825,26834 ,15571,15013,15572 ,0,0,0}, - {26835,26832,26836 ,15573,15570,15574 ,0,0,0}, {26837,26838,26839 ,15575,15576,15015 ,0,0,0}, - {26840,26841,26842 ,15577,15578,14934 ,0,0,0}, {26843,26836,26831 ,15579,15574,15569 ,0,0,0}, - {26844,26845,26846 ,15580,15581,15582 ,0,0,0}, {26840,26847,26846 ,15577,15583,15582 ,0,0,0}, - {26848,26849,26850 ,15584,15585,15586 ,0,0,0}, {26850,26849,26845 ,15586,15585,15581 ,0,0,0}, - {26851,26850,26852 ,15587,15586,15588 ,0,0,0}, {26834,26825,26824 ,15572,15013,15055 ,0,0,0}, - {26852,26853,26851 ,15588,15589,15587 ,0,0,0}, {26854,26855,26856 ,15590,15591,15592 ,0,0,0}, - {26826,26857,26824 ,15566,15593,15055 ,0,0,0}, {26858,26859,26856 ,15594,15595,15592 ,0,0,0}, - {26860,26861,26858 ,15596,15597,15594 ,0,0,0}, {26861,26862,26858 ,15597,15598,15594 ,0,0,0}, - {26856,26859,26854 ,15592,15595,15590 ,0,0,0}, {26863,26864,26828 ,15599,15600,15049 ,0,0,0}, - {26865,26866,26867 ,15601,15602,15603 ,0,0,0}, {26863,26868,26864 ,15599,15604,15600 ,0,0,0}, - {26869,26870,26871 ,15043,15044,15605 ,0,0,0}, {26866,26872,26867 ,15602,15606,15603 ,0,0,0}, - {26873,26874,26875 ,15607,14962,14960 ,0,0,0}, {26869,26871,26876 ,15043,15605,15608 ,0,0,0}, - {26877,26878,26879 ,15039,15609,15610 ,0,0,0}, {26878,26877,26880 ,15609,15039,15611 ,0,0,0}, - {26881,26882,26883 ,15035,15612,15613 ,0,0,0}, {26884,26885,26882 ,15614,15615,15612 ,0,0,0}, - {26886,26887,26888 ,15033,14956,15616 ,0,0,0}, {26881,26883,26889 ,15035,15613,14954 ,0,0,0}, - {26890,26891,26892 ,15617,15030,15031 ,0,0,0}, {26886,26888,26893 ,15033,15616,15032 ,0,0,0}, - {26894,26895,26896 ,15618,15619,14948 ,0,0,0}, {26897,26891,26890 ,15620,15030,15617 ,0,0,0}, - {26898,26899,26900 ,15621,15622,15027 ,0,0,0}, {26900,26896,26898 ,15027,14948,15621 ,0,0,0}, - {26901,26902,26903 ,15623,15624,14988 ,0,0,0}, {26904,26899,26905 ,15025,15622,14989 ,0,0,0}, - {26906,26907,26908 ,15625,15626,15627 ,0,0,0}, {26909,26906,26910 ,15628,15625,15629 ,0,0,0}, - {26911,26912,26913 ,15630,15631,15019 ,0,0,0}, {26914,26911,26908 ,15632,15630,15627 ,0,0,0}, - {26915,26916,26917 ,15633,15634,15635 ,0,0,0}, {26918,26913,26919 ,15018,15019,15636 ,0,0,0}, - {26920,26921,26922 ,14607,15637,15638 ,0,0,0}, {26917,26923,26915 ,15635,15639,15633 ,0,0,0}, - {26924,26920,26925 ,15017,14607,15640 ,0,0,0}, {26915,26923,26926 ,15633,15639,15641 ,0,0,0}, - {26927,26924,26918 ,15642,15017,15018 ,0,0,0}, {26920,26924,26927 ,14607,15017,15642 ,0,0,0}, - {26928,26929,26930 ,15643,15644,15645 ,0,0,0}, {26931,26914,26932 ,15646,15632,15647 ,0,0,0}, - {26933,26934,26935 ,14890,15648,15649 ,0,0,0}, {26931,26932,26936 ,15646,15647,15650 ,0,0,0}, - {26937,26938,26939 ,15651,15652,15653 ,0,0,0}, {26935,26940,26941 ,15649,15654,15655 ,0,0,0}, - {26942,26943,26939 ,15656,15657,15653 ,0,0,0}, {26944,26945,26946 ,15658,15659,15660 ,0,0,0}, - {26947,26948,26949 ,15661,15662,15663 ,0,0,0}, {26949,26946,26947 ,15663,15660,15661 ,0,0,0}, - {26948,26947,26950 ,15662,15661,15664 ,0,0,0}, {26919,26913,26912 ,15636,15019,15631 ,0,0,0}, - {26920,26926,26925 ,14607,15641,15640 ,0,0,0}, {26914,26908,26907 ,15632,15627,15626 ,0,0,0}, - {26914,26912,26911 ,15632,15631,15630 ,0,0,0}, {26909,26910,26901 ,15628,15629,15623 ,0,0,0}, - {26906,26909,26907 ,15625,15628,15626 ,0,0,0}, {26903,26902,26904 ,14988,15624,15025 ,0,0,0}, - {26910,26902,26901 ,15629,15624,15623 ,0,0,0}, {26903,26904,26905 ,14988,15025,14989 ,0,0,0}, - {26951,26909,26901 ,15665,15628,15623 ,0,0,0}, {26900,26894,26896 ,15027,15618,14948 ,0,0,0}, - {26899,26898,26905 ,15622,15621,14989 ,0,0,0}, {26890,26892,26952 ,15617,15031,15666 ,0,0,0}, - {26953,26897,26954 ,15667,15620,15668 ,0,0,0}, {26896,26895,26954 ,14948,15619,15668 ,0,0,0}, - {26891,26897,26953 ,15030,15620,15667 ,0,0,0}, {26895,26953,26954 ,15619,15667,15668 ,0,0,0}, - {26952,26892,26893 ,15666,15031,15032 ,0,0,0}, {26955,26890,26952 ,15669,15617,15666 ,0,0,0}, - {26893,26888,26952 ,15032,15616,15666 ,0,0,0}, {26889,26887,26956 ,14954,14956,14995 ,0,0,0}, - {26886,26956,26887 ,15033,14995,14956 ,0,0,0}, {26957,26889,26956 ,15670,14954,14995 ,0,0,0}, - {26885,26883,26882 ,15615,15613,15612 ,0,0,0}, {26881,26889,26957 ,15035,14954,15670 ,0,0,0}, - {26884,26958,26885 ,15614,14998,15615 ,0,0,0}, {26879,26878,26958 ,15610,15609,14998 ,0,0,0}, - {26958,26884,26879 ,14998,15614,15610 ,0,0,0}, {26880,26959,26875 ,15611,15040,14960 ,0,0,0}, - {26960,26961,26962 ,15671,15672,15673 ,0,0,0}, {26875,26959,26963 ,14960,15040,15674 ,0,0,0}, - {26959,26880,26877 ,15040,15611,15039 ,0,0,0}, {26964,26876,26874 ,15675,15608,14962 ,0,0,0}, - {26873,26875,26963 ,15607,14960,15674 ,0,0,0}, {26876,26964,26869 ,15608,15675,15043 ,0,0,0}, - {26964,26874,26873 ,15675,14962,15607 ,0,0,0}, {26868,26965,26966 ,15604,15005,15676 ,0,0,0}, - {26870,26872,26967 ,15044,15606,15677 ,0,0,0}, {26871,26870,26967 ,15605,15044,15677 ,0,0,0}, - {26967,26872,26866 ,15677,15606,15602 ,0,0,0}, {26968,26969,26970 ,15678,15679,15680 ,0,0,0}, - {26965,26865,26867 ,15005,15601,15603 ,0,0,0}, {26857,26826,26855 ,15593,15566,15591 ,0,0,0}, - {26868,26865,26965 ,15604,15601,15005 ,0,0,0}, {26868,26966,26864 ,15604,15676,15600 ,0,0,0}, - {26828,26827,26863 ,15049,15567,15599 ,0,0,0}, {26862,26861,26829 ,15598,15597,15050 ,0,0,0}, - {26829,26861,26827 ,15050,15597,15567 ,0,0,0}, {26854,26857,26855 ,15590,15593,15591 ,0,0,0}, - {26862,26859,26858 ,15598,15595,15594 ,0,0,0}, {26839,26971,26972 ,15015,15681,15682 ,0,0,0}, - {26833,26834,26971 ,15571,15572,15681 ,0,0,0}, {26972,26837,26839 ,15682,15575,15015 ,0,0,0}, - {26833,26971,26839 ,15571,15681,15015 ,0,0,0}, {26972,26973,26837 ,15682,15683,15575 ,0,0,0}, - {26974,26975,26841 ,15684,15685,15578 ,0,0,0}, {26837,26973,26976 ,15575,15683,15686 ,0,0,0}, - {26976,26973,26977 ,15686,15683,15687 ,0,0,0}, {26978,26976,26979 ,15688,15686,15689 ,0,0,0}, - {26977,26979,26976 ,15687,15689,15686 ,0,0,0}, {26842,26980,26840 ,14934,14795,15577 ,0,0,0}, - {26981,26978,26979 ,15690,15688,15689 ,0,0,0}, {26982,26981,26979 ,15691,15690,15689 ,0,0,0}, - {26978,26981,26983 ,15688,15690,15692 ,0,0,0}, {26984,26985,26983 ,15693,15694,15692 ,0,0,0}, - {26975,26974,26986 ,15685,15684,15695 ,0,0,0}, {26983,26985,26978 ,15692,15694,15688 ,0,0,0}, - {26984,26974,26985 ,15693,15684,15694 ,0,0,0}, {26978,26987,26976 ,15688,15696,15686 ,0,0,0}, - {26988,26833,26839 ,15697,15571,15015 ,0,0,0}, {26976,26830,26837 ,15686,15568,15575 ,0,0,0}, - {26989,26825,26833 ,15698,15013,15571 ,0,0,0}, {26838,26837,26830 ,15576,15575,15568 ,0,0,0}, - {26990,26826,26825 ,15699,15566,15013 ,0,0,0}, {26988,26839,26838 ,15697,15015,15576 ,0,0,0}, - {26991,26855,26826 ,15700,15591,15566 ,0,0,0}, {26989,26833,26988 ,15698,15571,15697 ,0,0,0}, - {26992,26856,26855 ,15701,15592,15591 ,0,0,0}, {26990,26825,26989 ,15699,15013,15698 ,0,0,0}, - {26993,26858,26856 ,15702,15594,15592 ,0,0,0}, {26826,26990,26991 ,15566,15699,15700 ,0,0,0}, - {26994,26995,26996 ,15703,15704,14972 ,0,0,0}, {26855,26991,26992 ,15591,15700,15701 ,0,0,0}, - {26996,26827,26861 ,14972,15567,15597 ,0,0,0}, {26856,26992,26993 ,15592,15701,15702 ,0,0,0}, - {26997,26863,26827 ,15705,15599,15567 ,0,0,0}, {26858,26993,26860 ,15594,15702,15596 ,0,0,0}, - {26998,26868,26863 ,15706,15604,15599 ,0,0,0}, {26861,26860,26996 ,15597,15596,14972 ,0,0,0}, - {26999,26865,26868 ,15707,15601,15604 ,0,0,0}, {26827,26996,26997 ,15567,14972,15705 ,0,0,0}, - {27000,26866,26865 ,15708,15602,15601 ,0,0,0}, {26998,26863,26997 ,15706,15599,15705 ,0,0,0}, - {27001,26967,26866 ,15709,15677,15602 ,0,0,0}, {26999,26868,26998 ,15707,15604,15706 ,0,0,0}, - {27002,26871,26967 ,15710,15605,15677 ,0,0,0}, {26865,26999,27000 ,15601,15707,15708 ,0,0,0}, - {26969,26876,26871 ,15679,15608,15605 ,0,0,0}, {26866,27000,27001 ,15602,15708,15709 ,0,0,0}, - {27003,26874,26876 ,15711,14962,15608 ,0,0,0}, {26967,27001,27002 ,15677,15709,15710 ,0,0,0}, - {27004,26875,26874 ,15712,14960,14962 ,0,0,0}, {26871,27002,26969 ,15605,15710,15679 ,0,0,0}, - {27005,26880,26875 ,15713,15611,14960 ,0,0,0}, {27003,26876,26969 ,15711,15608,15679 ,0,0,0}, - {27006,26878,26880 ,15714,15609,15611 ,0,0,0}, {27004,26874,27003 ,15712,14962,15711 ,0,0,0}, - {27007,26958,26878 ,15715,14998,15609 ,0,0,0}, {26875,27004,27005 ,14960,15712,15713 ,0,0,0}, - {26885,26958,26960 ,15615,14998,15671 ,0,0,0}, {26880,27005,27006 ,15611,15713,15714 ,0,0,0}, - {27008,26883,26885 ,15716,15613,15615 ,0,0,0}, {26878,27006,27007 ,15609,15714,15715 ,0,0,0}, - {27009,26889,26883 ,14955,14954,15613 ,0,0,0}, {26958,27007,26960 ,14998,15715,15671 ,0,0,0}, - {27010,26887,26889 ,15717,14956,14954 ,0,0,0}, {27008,26885,26960 ,15716,15615,15671 ,0,0,0}, - {27011,26888,26887 ,15718,15616,14956 ,0,0,0}, {27009,26883,27008 ,14955,15613,15716 ,0,0,0}, - {27012,26952,26888 ,15719,15666,15616 ,0,0,0}, {26889,27009,27010 ,14954,14955,15717 ,0,0,0}, - {27013,27014,27015 ,14854,15720,15721 ,0,0,0}, {26887,27010,27011 ,14956,15717,15718 ,0,0,0}, - {27016,26897,26890 ,15722,15620,15617 ,0,0,0}, {26888,27011,27012 ,15616,15718,15719 ,0,0,0}, - {27017,26954,26897 ,15723,15668,15620 ,0,0,0}, {26952,27012,26955 ,15666,15719,15669 ,0,0,0}, - {27018,26896,26954 ,15724,14948,15668 ,0,0,0}, {26890,26955,27016 ,15617,15669,15722 ,0,0,0}, - {27019,26898,26896 ,15725,15621,14948 ,0,0,0}, {27017,26897,27016 ,15723,15620,15722 ,0,0,0}, - {27020,26905,26898 ,15726,14989,15621 ,0,0,0}, {27018,26954,27017 ,15724,15668,15723 ,0,0,0}, - {27021,26903,26905 ,15727,14988,14989 ,0,0,0}, {27019,26896,27018 ,15725,14948,15724 ,0,0,0}, - {27022,26901,26903 ,15728,15623,14988 ,0,0,0}, {26898,27019,27020 ,15621,15725,15726 ,0,0,0}, - {26909,27023,26907 ,15628,15729,15626 ,0,0,0}, {26905,27020,27021 ,14989,15726,15727 ,0,0,0}, - {26932,27024,26936 ,15647,15730,15650 ,0,0,0}, {26903,27021,27022 ,14988,15727,15728 ,0,0,0}, - {26932,26914,26907 ,15647,15632,15626 ,0,0,0}, {26901,27022,26951 ,15623,15728,15665 ,0,0,0}, - {26931,26912,26914 ,15646,15631,15632 ,0,0,0}, {26909,26951,27023 ,15628,15665,15729 ,0,0,0}, - {26919,26912,27025 ,15636,15631,15731 ,0,0,0}, {27023,26932,26907 ,15729,15647,15626 ,0,0,0}, - {26934,26921,26927 ,15648,15637,15642 ,0,0,0}, {26921,26934,26933 ,15637,15648,14890 ,0,0,0}, - {26919,26927,26918 ,15636,15642,15018 ,0,0,0}, {26912,26931,27025 ,15631,15646,15731 ,0,0,0}, - {26915,26926,27026 ,15633,15641,15732 ,0,0,0}, {26919,26934,26927 ,15636,15648,15642 ,0,0,0}, - {26920,26927,26921 ,14607,15642,15637 ,0,0,0}, {27027,27028,26915 ,15733,15734,15633 ,0,0,0}, - {26925,26926,26923 ,15640,15641,15639 ,0,0,0}, {26922,27026,26926 ,15638,15732,15641 ,0,0,0}, - {26916,26915,27028 ,15634,15633,15734 ,0,0,0}, {26985,26987,26978 ,15694,15696,15688 ,0,0,0}, - {26986,26974,26984 ,15695,15684,15693 ,0,0,0}, {26847,27029,26846 ,15583,15735,15582 ,0,0,0}, - {26987,26830,26976 ,15696,15568,15686 ,0,0,0}, {26985,27030,26987 ,15694,15736,15696 ,0,0,0}, - {26838,26832,27031 ,15576,15570,15737 ,0,0,0}, {26831,26830,26987 ,15569,15568,15696 ,0,0,0}, - {26988,27031,27032 ,15697,15737,15738 ,0,0,0}, {26832,26838,26830 ,15570,15576,15568 ,0,0,0}, - {26989,27032,27033 ,15698,15738,15739 ,0,0,0}, {27031,26988,26838 ,15737,15697,15576 ,0,0,0}, - {26990,27033,27034 ,15699,15739,14927 ,0,0,0}, {27032,26989,26988 ,15738,15698,15697 ,0,0,0}, - {26991,27034,27035 ,15700,14927,14883 ,0,0,0}, {27033,26990,26989 ,15739,15699,15698 ,0,0,0}, - {26992,27035,27036 ,15701,14883,15740 ,0,0,0}, {27034,26991,26990 ,14927,15700,15699 ,0,0,0}, - {26993,27036,27037 ,15702,15740,15741 ,0,0,0}, {27035,26992,26991 ,14883,15701,15700 ,0,0,0}, - {26860,27037,26994 ,15596,15741,15703 ,0,0,0}, {26993,26992,27036 ,15702,15701,15740 ,0,0,0}, - {27038,27039,27040 ,15742,14878,15743 ,0,0,0}, {26860,26993,27037 ,15596,15702,15741 ,0,0,0}, - {26997,26995,27038 ,15705,15704,15742 ,0,0,0}, {26996,26860,26994 ,14972,15596,15703 ,0,0,0}, - {26998,27038,27041 ,15706,15742,15744 ,0,0,0}, {26997,26996,26995 ,15705,14972,15704 ,0,0,0}, - {26999,27041,27042 ,15707,15744,15745 ,0,0,0}, {27038,26998,26997 ,15742,15706,15705 ,0,0,0}, - {27000,27042,27043 ,15708,15745,15746 ,0,0,0}, {27041,26999,26998 ,15744,15707,15706 ,0,0,0}, - {27001,27043,27044 ,15709,15746,15747 ,0,0,0}, {27042,27000,26999 ,15745,15708,15707 ,0,0,0}, - {27002,27044,26970 ,15710,15747,15680 ,0,0,0}, {27001,27000,27043 ,15709,15708,15746 ,0,0,0}, - {27045,27046,27047 ,15748,15749,15750 ,0,0,0}, {27002,27001,27044 ,15710,15709,15747 ,0,0,0}, - {27003,26968,27048 ,15711,15678,15751 ,0,0,0}, {26969,27002,26970 ,15679,15710,15680 ,0,0,0}, - {27004,27048,27049 ,15712,15751,15752 ,0,0,0}, {26968,27003,26969 ,15678,15711,15679 ,0,0,0}, - {27005,27049,27050 ,15713,15752,15753 ,0,0,0}, {27048,27004,27003 ,15751,15712,15711 ,0,0,0}, - {27006,27050,27051 ,15714,15753,15754 ,0,0,0}, {27049,27005,27004 ,15752,15713,15712 ,0,0,0}, - {27007,27051,26961 ,15715,15754,15672 ,0,0,0}, {27006,27005,27050 ,15714,15713,15753 ,0,0,0}, - {27052,27053,27054 ,15755,15756,15757 ,0,0,0}, {27007,27006,27051 ,15715,15714,15754 ,0,0,0}, - {27008,26962,27055 ,15716,15673,15758 ,0,0,0}, {26960,27007,26961 ,15671,15715,15672 ,0,0,0}, - {27009,27055,27056 ,14955,15758,15759 ,0,0,0}, {27008,26960,26962 ,15716,15671,15673 ,0,0,0}, - {27010,27056,27057 ,15717,15759,15760 ,0,0,0}, {27055,27009,27008 ,15758,14955,15716 ,0,0,0}, - {27011,27057,27058 ,15718,15760,15761 ,0,0,0}, {27056,27010,27009 ,15759,15717,14955 ,0,0,0}, - {27012,27058,27059 ,15719,15761,15762 ,0,0,0}, {27057,27011,27010 ,15760,15718,15717 ,0,0,0}, - {26955,27059,27060 ,15669,15762,15763 ,0,0,0}, {27012,27011,27058 ,15719,15718,15761 ,0,0,0}, - {27016,27060,27014 ,15722,15763,15720 ,0,0,0}, {26955,27012,27059 ,15669,15719,15762 ,0,0,0}, - {27017,27014,27061 ,15723,15720,15764 ,0,0,0}, {27016,26955,27060 ,15722,15669,15763 ,0,0,0}, - {27018,27061,27062 ,15724,15764,15765 ,0,0,0}, {27014,27017,27016 ,15720,15723,15722 ,0,0,0}, - {27019,27062,27063 ,15725,15765,15766 ,0,0,0}, {27061,27018,27017 ,15764,15724,15723 ,0,0,0}, - {27020,27063,27064 ,15726,15766,15767 ,0,0,0}, {27062,27019,27018 ,15765,15725,15724 ,0,0,0}, - {27021,27064,27065 ,15727,15767,15768 ,0,0,0}, {27063,27020,27019 ,15766,15726,15725 ,0,0,0}, - {27022,27065,27066 ,15728,15768,14897 ,0,0,0}, {27064,27021,27020 ,15767,15727,15726 ,0,0,0}, - {26951,27066,27067 ,15665,14897,15769 ,0,0,0}, {27065,27022,27021 ,15768,15728,15727 ,0,0,0}, - {27023,27067,27024 ,15729,15769,15730 ,0,0,0}, {26951,27022,27066 ,15665,15728,14897 ,0,0,0}, - {27068,26931,26936 ,15770,15646,15650 ,0,0,0}, {27023,26951,27067 ,15729,15665,15769 ,0,0,0}, - {26941,26937,27069 ,15655,15651,15771 ,0,0,0}, {26932,27023,27024 ,15647,15729,15730 ,0,0,0}, - {27068,26935,27025 ,15770,15649,15731 ,0,0,0}, {26928,26921,26933 ,15643,15637,14890 ,0,0,0}, - {27025,26934,26919 ,15731,15648,15636 ,0,0,0}, {27068,27025,26931 ,15770,15731,15646 ,0,0,0}, - {26941,26933,26935 ,15655,14890,15649 ,0,0,0}, {27025,26935,26934 ,15731,15649,15648 ,0,0,0}, - {27070,27026,26930 ,15772,15732,15645 ,0,0,0}, {27026,27027,26915 ,15732,15733,15633 ,0,0,0}, - {26920,26922,26926 ,14607,15638,15641 ,0,0,0}, {26922,26928,26930 ,15638,15643,15645 ,0,0,0}, - {27070,27027,27026 ,15772,15733,15732 ,0,0,0}, {26974,27030,26985 ,15684,15736,15694 ,0,0,0}, - {26842,26841,26975 ,14934,15578,15685 ,0,0,0}, {26845,26849,27071 ,15581,15585,15773 ,0,0,0}, - {27030,26831,26987 ,15736,15569,15696 ,0,0,0}, {26974,27072,27030 ,15684,14889,15736 ,0,0,0}, - {27073,27074,27075 ,15774,15775,15776 ,0,0,0}, {26843,26831,27030 ,15579,15569,15736 ,0,0,0}, - {26835,27073,27031 ,15573,15774,15737 ,0,0,0}, {26836,26832,26831 ,15574,15570,15569 ,0,0,0}, - {27073,27076,27032 ,15774,14885,15738 ,0,0,0}, {26835,27031,26832 ,15573,15737,15570 ,0,0,0}, - {27076,27077,27033 ,14885,15777,15739 ,0,0,0}, {27073,27032,27031 ,15774,15738,15737 ,0,0,0}, - {27077,27078,27034 ,15777,14882,14927 ,0,0,0}, {27076,27033,27032 ,14885,15739,15738 ,0,0,0}, - {27078,27079,27035 ,14882,15778,14883 ,0,0,0}, {27077,27034,27033 ,15777,14927,15739 ,0,0,0}, - {27079,27080,27036 ,15778,15779,15740 ,0,0,0}, {27078,27035,27034 ,14882,14883,14927 ,0,0,0}, - {27080,27081,27037 ,15779,15780,15741 ,0,0,0}, {27079,27036,27035 ,15778,15740,14883 ,0,0,0}, - {27081,27082,26994 ,15780,15781,15703 ,0,0,0}, {27080,27037,27036 ,15779,15741,15740 ,0,0,0}, - {27082,27039,26995 ,15781,14878,15704 ,0,0,0}, {26994,27037,27081 ,15703,15741,15780 ,0,0,0}, - {27083,27084,27085 ,15782,15783,15784 ,0,0,0}, {26995,26994,27082 ,15704,15703,15781 ,0,0,0}, - {27040,27083,27041 ,15743,15782,15744 ,0,0,0}, {27039,27038,26995 ,14878,15742,15704 ,0,0,0}, - {27083,27086,27042 ,15782,15785,15745 ,0,0,0}, {27040,27041,27038 ,15743,15744,15742 ,0,0,0}, - {27086,27087,27043 ,15785,15786,15746 ,0,0,0}, {27083,27042,27041 ,15782,15745,15744 ,0,0,0}, - {27087,27088,27044 ,15786,14781,15747 ,0,0,0}, {27086,27043,27042 ,15785,15746,15745 ,0,0,0}, - {27088,27089,26970 ,14781,15787,15680 ,0,0,0}, {27087,27044,27043 ,15786,15747,15746 ,0,0,0}, - {26968,27089,27090 ,15678,15787,15788 ,0,0,0}, {26970,27044,27088 ,15680,15747,14781 ,0,0,0}, - {27090,27045,27048 ,15788,15748,15751 ,0,0,0}, {27089,26968,26970 ,15787,15678,15680 ,0,0,0}, - {27045,27091,27049 ,15748,15789,15752 ,0,0,0}, {27090,27048,26968 ,15788,15751,15678 ,0,0,0}, - {27091,27092,27050 ,15789,14868,15753 ,0,0,0}, {27045,27049,27048 ,15748,15752,15751 ,0,0,0}, - {27092,27093,27051 ,14868,15790,15754 ,0,0,0}, {27091,27050,27049 ,15789,15753,15752 ,0,0,0}, - {27093,27094,26961 ,15790,15791,15672 ,0,0,0}, {27092,27051,27050 ,14868,15754,15753 ,0,0,0}, - {27094,27095,26962 ,15791,15792,15673 ,0,0,0}, {26961,27051,27093 ,15672,15754,15790 ,0,0,0}, - {27095,27052,27055 ,15792,15755,15758 ,0,0,0}, {26962,26961,27094 ,15673,15672,15791 ,0,0,0}, - {27052,27096,27056 ,15755,15793,15759 ,0,0,0}, {27095,27055,26962 ,15792,15758,15673 ,0,0,0}, - {27096,27097,27057 ,15793,15794,15760 ,0,0,0}, {27052,27056,27055 ,15755,15759,15758 ,0,0,0}, - {27097,27098,27058 ,15794,15795,15761 ,0,0,0}, {27096,27057,27056 ,15793,15760,15759 ,0,0,0}, - {27098,27099,27059 ,15795,15796,15762 ,0,0,0}, {27097,27058,27057 ,15794,15761,15760 ,0,0,0}, - {27099,27015,27060 ,15796,15721,15763 ,0,0,0}, {27059,27058,27098 ,15762,15761,15795 ,0,0,0}, - {27100,27101,27102 ,15797,15798,15799 ,0,0,0}, {27060,27059,27099 ,15763,15762,15796 ,0,0,0}, - {27013,27100,27061 ,14854,15797,15764 ,0,0,0}, {27015,27014,27060 ,15721,15720,15763 ,0,0,0}, - {27100,27103,27062 ,15797,15800,15765 ,0,0,0}, {27013,27061,27014 ,14854,15764,15720 ,0,0,0}, - {27103,27104,27063 ,15800,15801,15766 ,0,0,0}, {27100,27062,27061 ,15797,15765,15764 ,0,0,0}, - {27104,27105,27064 ,15801,15802,15767 ,0,0,0}, {27103,27063,27062 ,15800,15766,15765 ,0,0,0}, - {27105,27106,27065 ,15802,14848,15768 ,0,0,0}, {27104,27064,27063 ,15801,15767,15766 ,0,0,0}, - {27106,27107,27066 ,14848,15803,14897 ,0,0,0}, {27105,27065,27064 ,15802,15768,15767 ,0,0,0}, - {27107,27108,27067 ,15803,15804,15769 ,0,0,0}, {27106,27066,27065 ,14848,14897,15768 ,0,0,0}, - {27108,27109,27024 ,15804,15805,15730 ,0,0,0}, {27107,27067,27066 ,15803,15769,14897 ,0,0,0}, - {27109,27110,26936 ,15805,15806,15650 ,0,0,0}, {27108,27024,27067 ,15804,15730,15769 ,0,0,0}, - {27110,26940,27068 ,15806,15654,15770 ,0,0,0}, {26936,27024,27109 ,15650,15730,15805 ,0,0,0}, - {27111,26933,26941 ,15807,14890,15655 ,0,0,0}, {26936,27110,27068 ,15650,15806,15770 ,0,0,0}, - {26940,26937,26941 ,15654,15651,15655 ,0,0,0}, {27068,26940,26935 ,15770,15654,15649 ,0,0,0}, - {27112,26930,26929 ,15808,15645,15644 ,0,0,0}, {26922,26930,27026 ,15638,15645,15732 ,0,0,0}, - {26921,26928,26922 ,15637,15643,15638 ,0,0,0}, {27111,26929,26928 ,15807,15644,15643 ,0,0,0}, - {27070,26930,27112 ,15772,15645,15808 ,0,0,0}, {27072,26974,26841 ,14889,15684,15578 ,0,0,0}, - {26847,26840,26980 ,15583,15577,14795 ,0,0,0}, {26843,27113,27114 ,15579,15809,15810 ,0,0,0}, - {27072,26843,27030 ,14889,15579,15736 ,0,0,0}, {27115,27072,26841 ,15811,14889,15578 ,0,0,0}, - {26836,27114,27116 ,15574,15810,15812 ,0,0,0}, {27072,27113,26843 ,14889,15809,15579 ,0,0,0}, - {26835,27116,27074 ,15573,15812,15775 ,0,0,0}, {27114,26836,26843 ,15810,15574,15579 ,0,0,0}, - {27117,27076,27075 ,15813,14885,15776 ,0,0,0}, {27116,26835,26836 ,15812,15573,15574 ,0,0,0}, - {27118,27077,27117 ,15814,15777,15813 ,0,0,0}, {27074,27073,26835 ,15775,15774,15573 ,0,0,0}, - {27119,27120,27121 ,15815,15816,15817 ,0,0,0}, {27075,27076,27073 ,15776,14885,15774 ,0,0,0}, - {27118,27119,27078 ,15814,15815,14882 ,0,0,0}, {27117,27077,27076 ,15813,15777,14885 ,0,0,0}, - {27119,27122,27079 ,15815,15818,15778 ,0,0,0}, {27118,27078,27077 ,15814,14882,15777 ,0,0,0}, - {27122,27123,27080 ,15818,15819,15779 ,0,0,0}, {27119,27079,27078 ,15815,15778,14882 ,0,0,0}, - {27123,27124,27081 ,15819,15820,15780 ,0,0,0}, {27122,27080,27079 ,15818,15779,15778 ,0,0,0}, - {27124,27125,27082 ,15820,15821,15781 ,0,0,0}, {27123,27081,27080 ,15819,15780,15779 ,0,0,0}, - {27039,27125,27126 ,14878,15821,15822 ,0,0,0}, {27124,27082,27081 ,15820,15781,15780 ,0,0,0}, - {27040,27126,27084 ,15743,15822,15783 ,0,0,0}, {27125,27039,27082 ,15821,14878,15781 ,0,0,0}, - {27127,27128,27129 ,15823,15824,15825 ,0,0,0}, {27126,27040,27039 ,15822,15743,14878 ,0,0,0}, - {27085,27127,27086 ,15784,15823,15785 ,0,0,0}, {27084,27083,27040 ,15783,15782,15743 ,0,0,0}, - {27127,27130,27087 ,15823,15826,15786 ,0,0,0}, {27085,27086,27083 ,15784,15785,15782 ,0,0,0}, - {27130,27131,27088 ,15826,15827,14781 ,0,0,0}, {27127,27087,27086 ,15823,15786,15785 ,0,0,0}, - {27089,27131,27132 ,15787,15827,15828 ,0,0,0}, {27130,27088,27087 ,15826,14781,15786 ,0,0,0}, - {27090,27132,27046 ,15788,15828,15749 ,0,0,0}, {27089,27088,27131 ,15787,14781,15827 ,0,0,0}, - {27133,27134,27135 ,15829,14778,15830 ,0,0,0}, {27132,27090,27089 ,15828,15788,15787 ,0,0,0}, - {27047,27133,27091 ,15750,15829,15789 ,0,0,0}, {27046,27045,27090 ,15749,15748,15788 ,0,0,0}, - {27133,27136,27092 ,15829,15831,14868 ,0,0,0}, {27047,27091,27045 ,15750,15789,15748 ,0,0,0}, - {27136,27137,27093 ,15831,15832,15790 ,0,0,0}, {27133,27092,27091 ,15829,14868,15789 ,0,0,0}, - {27137,27138,27094 ,15832,15833,15791 ,0,0,0}, {27136,27093,27092 ,15831,15790,14868 ,0,0,0}, - {27095,27138,27053 ,15792,15833,15756 ,0,0,0}, {27094,27093,27137 ,15791,15790,15832 ,0,0,0}, - {27139,27140,27141 ,15834,15835,15836 ,0,0,0}, {27138,27095,27094 ,15833,15792,15791 ,0,0,0}, - {27054,27139,27096 ,15757,15834,15793 ,0,0,0}, {27053,27052,27095 ,15756,15755,15792 ,0,0,0}, - {27139,27142,27097 ,15834,15837,15794 ,0,0,0}, {27054,27096,27052 ,15757,15793,15755 ,0,0,0}, - {27142,27143,27098 ,15837,15838,15795 ,0,0,0}, {27139,27097,27096 ,15834,15794,15793 ,0,0,0}, - {27143,27144,27099 ,15838,15839,15796 ,0,0,0}, {27142,27098,27097 ,15837,15795,15794 ,0,0,0}, - {27015,27144,27145 ,15721,15839,15840 ,0,0,0}, {27143,27099,27098 ,15838,15796,15795 ,0,0,0}, - {27013,27145,27101 ,14854,15840,15798 ,0,0,0}, {27144,27015,27099 ,15839,15721,15796 ,0,0,0}, - {27146,27103,27102 ,15841,15800,15799 ,0,0,0}, {27145,27013,27015 ,15840,14854,15721 ,0,0,0}, - {27147,27148,27149 ,15842,15843,14766 ,0,0,0}, {27101,27100,27013 ,15798,15797,14854 ,0,0,0}, - {27146,27147,27104 ,15841,15842,15801 ,0,0,0}, {27102,27103,27100 ,15799,15800,15797 ,0,0,0}, - {27147,27150,27105 ,15842,15844,15802 ,0,0,0}, {27146,27104,27103 ,15841,15801,15800 ,0,0,0}, - {27150,27151,27106 ,15844,15845,14848 ,0,0,0}, {27147,27105,27104 ,15842,15802,15801 ,0,0,0}, - {27151,27152,27107 ,15845,15846,15803 ,0,0,0}, {27150,27106,27105 ,15844,14848,15802 ,0,0,0}, - {27152,27153,27108 ,15846,15847,15804 ,0,0,0}, {27151,27107,27106 ,15845,15803,14848 ,0,0,0}, - {27153,27154,27109 ,15847,15848,15805 ,0,0,0}, {27152,27108,27107 ,15846,15804,15803 ,0,0,0}, - {27154,26938,27110 ,15848,15652,15806 ,0,0,0}, {27153,27109,27108 ,15847,15805,15804 ,0,0,0}, - {26940,26938,26937 ,15654,15652,15651 ,0,0,0}, {27109,27154,27110 ,15805,15848,15806 ,0,0,0}, - {27155,26929,27111 ,15849,15644,15807 ,0,0,0}, {26940,27110,26938 ,15654,15806,15652 ,0,0,0}, - {27156,26929,27155 ,15850,15644,15849 ,0,0,0}, {27157,27112,26929 ,15851,15808,15644 ,0,0,0}, - {26933,27111,26928 ,14890,15807,15643 ,0,0,0}, {27069,27155,27111 ,15771,15849,15807 ,0,0,0}, - {27156,27157,26929 ,15850,15851,15644 ,0,0,0}, {27115,26841,26840 ,15811,15578,15577 ,0,0,0}, - {26844,26846,27029 ,15580,15582,15735 ,0,0,0}, {27113,27158,27159 ,15809,15852,15853 ,0,0,0}, - {27115,27113,27072 ,15811,15809,14889 ,0,0,0}, {26840,27160,27115 ,15577,15854,15811 ,0,0,0}, - {27114,27159,27161 ,15810,15853,15855 ,0,0,0}, {27115,27158,27113 ,15811,15852,15809 ,0,0,0}, - {27116,27161,27162 ,15812,15855,15856 ,0,0,0}, {27113,27159,27114 ,15809,15853,15810 ,0,0,0}, - {27074,27162,27163 ,15775,15856,14794 ,0,0,0}, {27114,27161,27116 ,15810,15855,15812 ,0,0,0}, - {27075,27163,27164 ,15776,14794,15857 ,0,0,0}, {27116,27162,27074 ,15812,15856,15775 ,0,0,0}, - {27117,27164,27165 ,15813,15857,14792 ,0,0,0}, {27074,27163,27075 ,15775,14794,15776 ,0,0,0}, - {27118,27165,27120 ,15814,14792,15816 ,0,0,0}, {27164,27117,27075 ,15857,15813,15776 ,0,0,0}, - {27166,27122,27121 ,14789,15818,15817 ,0,0,0}, {27165,27118,27117 ,14792,15814,15813 ,0,0,0}, - {27167,27168,27166 ,15858,15859,14789 ,0,0,0}, {27120,27119,27118 ,15816,15815,15814 ,0,0,0}, - {27166,27168,27123 ,14789,15859,15819 ,0,0,0}, {27121,27122,27119 ,15817,15818,15815 ,0,0,0}, - {27168,27169,27124 ,15859,14660,15820 ,0,0,0}, {27166,27123,27122 ,14789,15819,15818 ,0,0,0}, - {27125,27169,27170 ,15821,14660,15860 ,0,0,0}, {27168,27124,27123 ,15859,15820,15819 ,0,0,0}, - {27126,27170,27171 ,15822,15860,15861 ,0,0,0}, {27124,27169,27125 ,15820,14660,15821 ,0,0,0}, - {27084,27171,27172 ,15783,15861,15862 ,0,0,0}, {27125,27170,27126 ,15821,15860,15822 ,0,0,0}, - {27085,27172,27128 ,15784,15862,15824 ,0,0,0}, {27171,27084,27126 ,15861,15783,15822 ,0,0,0}, - {27173,27174,27129 ,15863,15864,15825 ,0,0,0}, {27172,27085,27084 ,15862,15784,15783 ,0,0,0}, - {27129,27174,27130 ,15825,15864,15826 ,0,0,0}, {27128,27127,27085 ,15824,15823,15784 ,0,0,0}, - {27174,27175,27131 ,15864,15865,15827 ,0,0,0}, {27129,27130,27127 ,15825,15826,15823 ,0,0,0}, - {27132,27175,27176 ,15828,15865,15866 ,0,0,0}, {27174,27131,27130 ,15864,15827,15826 ,0,0,0}, - {27046,27176,27177 ,15749,15866,15867 ,0,0,0}, {27131,27175,27132 ,15827,15865,15828 ,0,0,0}, - {27047,27177,27134 ,15750,15867,14778 ,0,0,0}, {27176,27046,27132 ,15866,15749,15828 ,0,0,0}, - {27178,27179,27135 ,15868,15869,15830 ,0,0,0}, {27177,27047,27046 ,15867,15750,15749 ,0,0,0}, - {27135,27179,27136 ,15830,15869,15831 ,0,0,0}, {27134,27133,27047 ,14778,15829,15750 ,0,0,0}, - {27179,27180,27137 ,15869,15870,15832 ,0,0,0}, {27135,27136,27133 ,15830,15831,15829 ,0,0,0}, - {27138,27180,27181 ,15833,15870,15871 ,0,0,0}, {27179,27137,27136 ,15869,15832,15831 ,0,0,0}, - {27053,27181,27182 ,15756,15871,15872 ,0,0,0}, {27137,27180,27138 ,15832,15870,15833 ,0,0,0}, - {27054,27182,27140 ,15757,15872,15835 ,0,0,0}, {27181,27053,27138 ,15871,15756,15833 ,0,0,0}, - {27183,27184,27141 ,15873,15874,15836 ,0,0,0}, {27182,27054,27053 ,15872,15757,15756 ,0,0,0}, - {27141,27184,27142 ,15836,15874,15837 ,0,0,0}, {27140,27139,27054 ,15835,15834,15757 ,0,0,0}, - {27184,27185,27143 ,15874,15875,15838 ,0,0,0}, {27141,27142,27139 ,15836,15837,15834 ,0,0,0}, - {27144,27185,27186 ,15839,15875,14579 ,0,0,0}, {27184,27143,27142 ,15874,15838,15837 ,0,0,0}, - {27145,27186,27187 ,15840,14579,15876 ,0,0,0}, {27143,27185,27144 ,15838,15875,15839 ,0,0,0}, - {27101,27187,27188 ,15798,15876,14769 ,0,0,0}, {27144,27186,27145 ,15839,14579,15840 ,0,0,0}, - {27102,27188,27189 ,15799,14769,15877 ,0,0,0}, {27145,27187,27101 ,15840,15876,15798 ,0,0,0}, - {27146,27189,27148 ,15841,15877,15843 ,0,0,0}, {27188,27102,27101 ,14769,15799,15798 ,0,0,0}, - {27190,27150,27149 ,15878,15844,14766 ,0,0,0}, {27189,27146,27102 ,15877,15841,15799 ,0,0,0}, - {27191,27192,27190 ,15879,15880,15878 ,0,0,0}, {27148,27147,27146 ,15843,15842,15841 ,0,0,0}, - {27190,27192,27151 ,15878,15880,15845 ,0,0,0}, {27149,27150,27147 ,14766,15844,15842 ,0,0,0}, - {27192,27193,27152 ,15880,15881,15846 ,0,0,0}, {27190,27151,27150 ,15878,15845,15844 ,0,0,0}, - {27193,27194,27153 ,15881,15882,15847 ,0,0,0}, {27192,27152,27151 ,15880,15846,15845 ,0,0,0}, - {27194,27195,27154 ,15882,15883,15848 ,0,0,0}, {27193,27153,27152 ,15881,15847,15846 ,0,0,0}, - {26938,27195,26939 ,15652,15883,15653 ,0,0,0}, {27194,27154,27153 ,15882,15848,15847 ,0,0,0}, - {26939,27196,26937 ,15653,15884,15651 ,0,0,0}, {26938,27154,27195 ,15652,15848,15883 ,0,0,0}, - {27197,27155,26945 ,15885,15849,15659 ,0,0,0}, {27197,27198,27155 ,15885,15886,15849 ,0,0,0}, - {26941,27069,27111 ,15655,15771,15807 ,0,0,0}, {27196,26945,27069 ,15884,15659,15771 ,0,0,0}, - {27156,27155,27198 ,15850,15849,15886 ,0,0,0}, {26846,27160,26840 ,15582,15854,15577 ,0,0,0}, - {27199,26845,26844 ,14760,15581,15580 ,0,0,0}, {27200,27158,27160 ,15887,15852,15854 ,0,0,0}, - {27160,27158,27115 ,15854,15852,15811 ,0,0,0}, {27160,27071,27200 ,15854,15773,15887 ,0,0,0}, - {27201,27159,27158 ,15888,15853,15852 ,0,0,0}, {27158,27200,27201 ,15852,15887,15888 ,0,0,0}, - {27202,27161,27159 ,15889,15855,15853 ,0,0,0}, {27159,27201,27202 ,15853,15888,15889 ,0,0,0}, - {27203,27162,27161 ,15890,15856,15855 ,0,0,0}, {27161,27202,27203 ,15855,15889,15890 ,0,0,0}, - {27204,27163,27162 ,15891,14794,15856 ,0,0,0}, {27162,27203,27204 ,15856,15890,15891 ,0,0,0}, - {27205,27164,27163 ,15892,15857,14794 ,0,0,0}, {27163,27204,27205 ,14794,15891,15892 ,0,0,0}, - {27206,27165,27164 ,15893,14792,15857 ,0,0,0}, {27164,27205,27206 ,15857,15892,15893 ,0,0,0}, - {27207,27120,27165 ,15894,15816,14792 ,0,0,0}, {27165,27206,27207 ,14792,15893,15894 ,0,0,0}, - {27208,27121,27120 ,15895,15817,15816 ,0,0,0}, {27120,27207,27208 ,15816,15894,15895 ,0,0,0}, - {27209,27166,27121 ,15896,14789,15817 ,0,0,0}, {27208,27209,27121 ,15895,15896,15817 ,0,0,0}, - {27210,27211,27212 ,15897,15898,14664 ,0,0,0}, {27209,27167,27166 ,15896,15858,14789 ,0,0,0}, - {27213,27169,27168 ,15899,14660,15859 ,0,0,0}, {27167,27213,27168 ,15858,15899,15859 ,0,0,0}, - {27214,27170,27169 ,15900,15860,14660 ,0,0,0}, {27169,27213,27214 ,14660,15899,15900 ,0,0,0}, - {27215,27171,27170 ,15901,15861,15860 ,0,0,0}, {27170,27214,27215 ,15860,15900,15901 ,0,0,0}, - {27216,27172,27171 ,15902,15862,15861 ,0,0,0}, {27171,27215,27216 ,15861,15901,15902 ,0,0,0}, - {27217,27128,27172 ,14747,15824,15862 ,0,0,0}, {27172,27216,27217 ,15862,15902,14747 ,0,0,0}, - {27218,27129,27128 ,15903,15825,15824 ,0,0,0}, {27217,27218,27128 ,14747,15903,15824 ,0,0,0}, - {27219,27173,27220 ,15904,15863,15905 ,0,0,0}, {27218,27173,27129 ,15903,15863,15825 ,0,0,0}, - {27219,27175,27174 ,15904,15865,15864 ,0,0,0}, {27173,27219,27174 ,15863,15904,15864 ,0,0,0}, - {27221,27176,27175 ,15906,15866,15865 ,0,0,0}, {27175,27219,27221 ,15865,15904,15906 ,0,0,0}, - {27222,27177,27176 ,15907,15867,15866 ,0,0,0}, {27176,27221,27222 ,15866,15906,15907 ,0,0,0}, - {27223,27134,27177 ,14742,14778,15867 ,0,0,0}, {27177,27222,27223 ,15867,15907,14742 ,0,0,0}, - {27224,27135,27134 ,15908,15830,14778 ,0,0,0}, {27223,27224,27134 ,14742,15908,14778 ,0,0,0}, - {27225,27226,27227 ,15909,14630,15910 ,0,0,0}, {27224,27178,27135 ,15908,15868,15830 ,0,0,0}, - {27228,27180,27179 ,15911,15870,15869 ,0,0,0}, {27178,27228,27179 ,15868,15911,15869 ,0,0,0}, - {27229,27181,27180 ,15912,15871,15870 ,0,0,0}, {27180,27228,27229 ,15870,15911,15912 ,0,0,0}, - {27230,27182,27181 ,15913,15872,15871 ,0,0,0}, {27181,27229,27230 ,15871,15912,15913 ,0,0,0}, - {27231,27140,27182 ,15914,15835,15872 ,0,0,0}, {27182,27230,27231 ,15872,15913,15914 ,0,0,0}, - {27232,27141,27140 ,15915,15836,15835 ,0,0,0}, {27231,27232,27140 ,15914,15915,15835 ,0,0,0}, - {27184,27233,27185 ,15874,15916,15875 ,0,0,0}, {27232,27183,27141 ,15915,15873,15836 ,0,0,0}, - {27234,27235,27233 ,15917,14580,15916 ,0,0,0}, {27183,27233,27184 ,15873,15916,15874 ,0,0,0}, - {27235,27186,27185 ,14580,14579,15875 ,0,0,0}, {27185,27233,27235 ,15875,15916,14580 ,0,0,0}, - {27236,27187,27186 ,15918,15876,14579 ,0,0,0}, {27186,27235,27236 ,14579,14580,15918 ,0,0,0}, - {27237,27188,27187 ,15919,14769,15876 ,0,0,0}, {27187,27236,27237 ,15876,15918,15919 ,0,0,0}, - {27238,27189,27188 ,15920,15877,14769 ,0,0,0}, {27188,27237,27238 ,14769,15919,15920 ,0,0,0}, - {27239,27148,27189 ,15921,15843,15877 ,0,0,0}, {27189,27238,27239 ,15877,15920,15921 ,0,0,0}, - {27240,27149,27148 ,14728,14766,15843 ,0,0,0}, {27148,27239,27240 ,15843,15921,14728 ,0,0,0}, - {27241,27190,27149 ,15922,15878,14766 ,0,0,0}, {27240,27241,27149 ,14728,15922,14766 ,0,0,0}, - {27192,27242,27193 ,15880,15923,15881 ,0,0,0}, {27241,27191,27190 ,15922,15879,15878 ,0,0,0}, - {27193,27243,27194 ,15881,15924,15882 ,0,0,0}, {27191,27242,27192 ,15879,15923,15880 ,0,0,0}, - {27194,27244,27195 ,15882,15925,15883 ,0,0,0}, {27242,27243,27193 ,15923,15924,15881 ,0,0,0}, - {27195,26942,26939 ,15883,15656,15653 ,0,0,0}, {27243,27244,27194 ,15924,15925,15882 ,0,0,0}, - {26947,26946,26943 ,15661,15660,15657 ,0,0,0}, {27244,26942,27195 ,15925,15656,15883 ,0,0,0}, - {26943,27196,26939 ,15657,15884,15653 ,0,0,0}, {27069,26945,27155 ,15771,15659,15849 ,0,0,0}, - {26937,27196,27069 ,15651,15884,15771 ,0,0,0}, {27196,26943,26946 ,15884,15657,15660 ,0,0,0}, - {27197,26945,26944 ,15885,15659,15658 ,0,0,0}, {26845,27071,26846 ,15581,15773,15582 ,0,0,0}, - {27199,26852,26850 ,14760,15588,15586 ,0,0,0}, {27200,27071,27245 ,15887,15773,15926 ,0,0,0}, - {26846,27071,27160 ,15582,15773,15854 ,0,0,0}, {27071,26849,27245 ,15773,15585,15926 ,0,0,0}, - {27201,27200,27246 ,15888,15887,15927 ,0,0,0}, {27200,27245,27246 ,15887,15926,15927 ,0,0,0}, - {27202,27201,27247 ,15889,15888,15928 ,0,0,0}, {27201,27246,27247 ,15888,15927,15928 ,0,0,0}, - {27203,27202,27248 ,15890,15889,15929 ,0,0,0}, {27202,27247,27248 ,15889,15928,15929 ,0,0,0}, - {27204,27203,27249 ,15891,15890,15930 ,0,0,0}, {27203,27248,27249 ,15890,15929,15930 ,0,0,0}, - {27205,27204,27250 ,15892,15891,15931 ,0,0,0}, {27204,27249,27250 ,15891,15930,15931 ,0,0,0}, - {27206,27205,27251 ,15893,15892,15932 ,0,0,0}, {27205,27250,27251 ,15892,15931,15932 ,0,0,0}, - {27207,27206,27252 ,15894,15893,15933 ,0,0,0}, {27206,27251,27252 ,15893,15932,15933 ,0,0,0}, - {27208,27207,27253 ,15895,15894,15934 ,0,0,0}, {27207,27252,27253 ,15894,15933,15934 ,0,0,0}, - {27209,27208,27254 ,15896,15895,15935 ,0,0,0}, {27208,27253,27254 ,15895,15934,15935 ,0,0,0}, - {27167,27209,27255 ,15858,15896,15936 ,0,0,0}, {27209,27254,27255 ,15896,15935,15936 ,0,0,0}, - {27213,27167,27210 ,15899,15858,15897 ,0,0,0}, {27255,27210,27167 ,15936,15897,15858 ,0,0,0}, - {27214,27213,27212 ,15900,15899,14664 ,0,0,0}, {27213,27210,27212 ,15899,15897,14664 ,0,0,0}, - {27215,27214,27256 ,15901,15900,15937 ,0,0,0}, {27214,27212,27256 ,15900,14664,15937 ,0,0,0}, - {27216,27215,27257 ,15902,15901,15938 ,0,0,0}, {27215,27256,27257 ,15901,15937,15938 ,0,0,0}, - {27217,27216,27258 ,14747,15902,15939 ,0,0,0}, {27216,27257,27258 ,15902,15938,15939 ,0,0,0}, - {27218,27217,27259 ,15903,14747,15940 ,0,0,0}, {27217,27258,27259 ,14747,15939,15940 ,0,0,0}, - {27173,27218,27260 ,15863,15903,14651 ,0,0,0}, {27218,27259,27260 ,15903,15940,14651 ,0,0,0}, - {27260,27261,27220 ,14651,14649,15905 ,0,0,0}, {27260,27220,27173 ,14651,15905,15863 ,0,0,0}, - {27221,27219,27262 ,15906,15904,15941 ,0,0,0}, {27219,27220,27262 ,15904,15905,15941 ,0,0,0}, - {27222,27221,27263 ,15907,15906,15942 ,0,0,0}, {27221,27262,27263 ,15906,15941,15942 ,0,0,0}, - {27223,27222,27264 ,14742,15907,15943 ,0,0,0}, {27222,27263,27264 ,15907,15942,15943 ,0,0,0}, - {27224,27223,27265 ,15908,14742,15944 ,0,0,0}, {27223,27264,27265 ,14742,15943,15944 ,0,0,0}, - {27178,27224,27266 ,15868,15908,14635 ,0,0,0}, {27224,27265,27266 ,15908,15944,14635 ,0,0,0}, - {27228,27178,27225 ,15911,15868,15909 ,0,0,0}, {27266,27225,27178 ,14635,15909,15868 ,0,0,0}, - {27229,27228,27227 ,15912,15911,15910 ,0,0,0}, {27228,27225,27227 ,15911,15909,15910 ,0,0,0}, - {27230,27229,27267 ,15913,15912,15945 ,0,0,0}, {27229,27227,27267 ,15912,15910,15945 ,0,0,0}, - {27231,27230,27268 ,15914,15913,15946 ,0,0,0}, {27230,27267,27268 ,15913,15945,15946 ,0,0,0}, - {27232,27231,27269 ,15915,15914,15947 ,0,0,0}, {27231,27268,27269 ,15914,15946,15947 ,0,0,0}, - {27183,27232,27270 ,15873,15915,15948 ,0,0,0}, {27232,27269,27270 ,15915,15947,15948 ,0,0,0}, - {27233,27183,27271 ,15916,15873,14572 ,0,0,0}, {27183,27270,27271 ,15873,15948,14572 ,0,0,0}, - {27234,27271,27272 ,15917,14572,14569 ,0,0,0}, {27271,27234,27233 ,14572,15917,15916 ,0,0,0}, - {27236,27235,27273 ,15918,14580,14574 ,0,0,0}, {27235,27234,27273 ,14580,15917,14574 ,0,0,0}, - {27237,27236,27274 ,15919,15918,14575 ,0,0,0}, {27236,27273,27274 ,15918,14574,14575 ,0,0,0}, - {27238,27237,27275 ,15920,15919,15949 ,0,0,0}, {27237,27274,27275 ,15919,14575,15949 ,0,0,0}, - {27239,27238,27276 ,15921,15920,15950 ,0,0,0}, {27238,27275,27276 ,15920,15949,15950 ,0,0,0}, - {27240,27239,27277 ,14728,15921,14585 ,0,0,0}, {27239,27276,27277 ,15921,15950,14585 ,0,0,0}, - {27241,27240,27278 ,15922,14728,15951 ,0,0,0}, {27240,27277,27278 ,14728,14585,15951 ,0,0,0}, - {27191,27241,27279 ,15879,15922,15952 ,0,0,0}, {27241,27278,27279 ,15922,15951,15952 ,0,0,0}, - {27242,27191,27280 ,15923,15879,14590 ,0,0,0}, {27191,27279,27280 ,15879,15952,14590 ,0,0,0}, - {27243,27242,27281 ,15924,15923,15953 ,0,0,0}, {27242,27280,27281 ,15923,14590,15953 ,0,0,0}, - {27244,27243,27282 ,15925,15924,15954 ,0,0,0}, {27243,27281,27282 ,15924,15953,15954 ,0,0,0}, - {26942,27244,27283 ,15656,15925,15955 ,0,0,0}, {27244,27282,27283 ,15925,15954,15955 ,0,0,0}, - {27284,26943,26942 ,15956,15657,15656 ,0,0,0}, {27284,26942,27283 ,15956,15656,15955 ,0,0,0}, - {27196,26946,26945 ,15884,15660,15659 ,0,0,0}, {27284,26947,26943 ,15956,15661,15657 ,0,0,0}, - {26944,26946,26949 ,15658,15660,15663 ,0,0,0}, {26850,26845,27199 ,15586,15581,14760 ,0,0,0}, - {26851,26848,26850 ,15587,15584,15586 ,0,0,0}, {26848,27285,26849 ,15584,15957,15585 ,0,0,0}, - {26849,27285,27245 ,15585,15957,15926 ,0,0,0}, {27285,27286,27245 ,15957,14714,15926 ,0,0,0}, - {27245,27286,27246 ,15926,14714,15927 ,0,0,0}, {27286,27287,27246 ,14714,14713,15927 ,0,0,0}, - {27246,27287,27247 ,15927,14713,15928 ,0,0,0}, {27287,27288,27247 ,14713,15958,15928 ,0,0,0}, - {27247,27288,27248 ,15928,15958,15929 ,0,0,0}, {27288,27289,27248 ,15958,15959,15929 ,0,0,0}, - {27248,27289,27249 ,15929,15959,15930 ,0,0,0}, {27289,27290,27249 ,15959,15960,15930 ,0,0,0}, - {27249,27290,27250 ,15930,15960,15931 ,0,0,0}, {27290,27291,27250 ,15960,15961,15931 ,0,0,0}, - {27250,27291,27251 ,15931,15961,15932 ,0,0,0}, {27291,27292,27251 ,15961,15962,15932 ,0,0,0}, - {27292,27293,27252 ,15962,15963,15933 ,0,0,0}, {27292,27252,27251 ,15962,15933,15932 ,0,0,0}, - {27293,27294,27253 ,15963,15964,15934 ,0,0,0}, {27293,27253,27252 ,15963,15934,15933 ,0,0,0}, - {27294,27295,27254 ,15964,15965,15935 ,0,0,0}, {27294,27254,27253 ,15964,15935,15934 ,0,0,0}, - {27295,27296,27255 ,15965,15966,15936 ,0,0,0}, {27295,27255,27254 ,15965,15936,15935 ,0,0,0}, - {27296,27297,27210 ,15966,15967,15897 ,0,0,0}, {27296,27210,27255 ,15966,15897,15936 ,0,0,0}, - {27211,27210,27297 ,15898,15897,15967 ,0,0,0}, {27211,27298,27212 ,15898,14663,14664 ,0,0,0}, - {27212,27298,27256 ,14664,14663,15937 ,0,0,0}, {27298,27299,27256 ,14663,14658,15937 ,0,0,0}, - {27256,27299,27257 ,15937,14658,15938 ,0,0,0}, {27299,27300,27257 ,14658,14655,15938 ,0,0,0}, - {27300,27301,27258 ,14655,15968,15939 ,0,0,0}, {27300,27258,27257 ,14655,15939,15938 ,0,0,0}, - {27301,27302,27259 ,15968,14652,15940 ,0,0,0}, {27301,27259,27258 ,15968,15940,15939 ,0,0,0}, - {27302,27261,27260 ,14652,14649,14651 ,0,0,0}, {27302,27260,27259 ,14652,14651,15940 ,0,0,0}, - {27261,27303,27220 ,14649,15969,15905 ,0,0,0}, {27303,27304,27220 ,15969,14648,15905 ,0,0,0}, - {27220,27304,27262 ,15905,14648,15941 ,0,0,0}, {27304,27305,27262 ,14648,14646,15941 ,0,0,0}, - {27262,27305,27263 ,15941,14646,15942 ,0,0,0}, {27305,27306,27263 ,14646,15970,15942 ,0,0,0}, - {27306,27307,27264 ,15970,14638,15943 ,0,0,0}, {27306,27264,27263 ,15970,15943,15942 ,0,0,0}, - {27307,27308,27265 ,14638,15971,15944 ,0,0,0}, {27307,27265,27264 ,14638,15944,15943 ,0,0,0}, - {27308,27309,27266 ,15971,14634,14635 ,0,0,0}, {27308,27266,27265 ,15971,14635,15944 ,0,0,0}, - {27309,27310,27225 ,14634,15972,15909 ,0,0,0}, {27309,27225,27266 ,14634,15909,14635 ,0,0,0}, - {27226,27225,27310 ,14630,15909,15972 ,0,0,0}, {27226,27311,27227 ,14630,15973,15910 ,0,0,0}, - {27227,27311,27267 ,15910,15973,15945 ,0,0,0}, {27311,27312,27267 ,15973,14560,15945 ,0,0,0}, - {27312,27313,27268 ,14560,14561,15946 ,0,0,0}, {27312,27268,27267 ,14560,15946,15945 ,0,0,0}, - {27313,27314,27269 ,14561,15974,15947 ,0,0,0}, {27313,27269,27268 ,14561,15947,15946 ,0,0,0}, - {27314,27315,27270 ,15974,14567,15948 ,0,0,0}, {27314,27270,27269 ,15974,15948,15947 ,0,0,0}, - {27315,27272,27271 ,14567,14569,14572 ,0,0,0}, {27315,27271,27270 ,14567,14572,15948 ,0,0,0}, - {27272,27316,27234 ,14569,15975,15917 ,0,0,0}, {27316,27317,27234 ,15975,15976,15917 ,0,0,0}, - {27234,27317,27273 ,15917,15976,14574 ,0,0,0}, {27317,27318,27273 ,15976,14576,14574 ,0,0,0}, - {27273,27318,27274 ,14574,14576,14575 ,0,0,0}, {27318,27319,27274 ,14576,14577,14575 ,0,0,0}, - {27274,27319,27275 ,14575,14577,15949 ,0,0,0}, {27319,27320,27275 ,14577,14583,15949 ,0,0,0}, - {27320,27321,27276 ,14583,15977,15950 ,0,0,0}, {27320,27276,27275 ,14583,15950,15949 ,0,0,0}, - {27321,27322,27277 ,15977,15978,14585 ,0,0,0}, {27321,27277,27276 ,15977,14585,15950 ,0,0,0}, - {27322,27323,27278 ,15978,15979,15951 ,0,0,0}, {27322,27278,27277 ,15978,15951,14585 ,0,0,0}, - {27323,27324,27279 ,15979,14589,15952 ,0,0,0}, {27323,27279,27278 ,15979,15952,15951 ,0,0,0}, - {27324,27325,27280 ,14589,15980,14590 ,0,0,0}, {27324,27280,27279 ,14589,14590,15952 ,0,0,0}, - {27325,27326,27281 ,15980,15981,15953 ,0,0,0}, {27325,27281,27280 ,15980,15953,14590 ,0,0,0}, - {27326,27327,27282 ,15981,15982,15954 ,0,0,0}, {27326,27282,27281 ,15981,15954,15953 ,0,0,0}, - {27327,27328,27283 ,15982,15983,15955 ,0,0,0}, {27327,27283,27282 ,15982,15955,15954 ,0,0,0}, - {27328,27329,27284 ,15983,15984,15956 ,0,0,0}, {27328,27284,27283 ,15983,15956,15955 ,0,0,0}, - {27330,27284,27329 ,15985,15956,15984 ,0,0,0}, {27284,27330,26947 ,15956,15985,15661 ,0,0,0}, - {26947,27330,26950 ,15661,15985,15664 ,0,0,0}, {27331,27332,27333 ,15557,15515,15986 ,0,0,0}, - {27334,27335,27336 ,15987,15551,15552 ,0,0,0}, {27337,27338,27339 ,15988,15989,15990 ,0,0,0}, - {27340,27341,27337 ,15991,15992,15988 ,0,0,0}, {27342,27343,27344 ,15993,15994,15995 ,0,0,0}, - {27345,27346,27347 ,15996,15997,15998 ,0,0,0}, {27348,27349,27350 ,15999,16000,16001 ,0,0,0}, - {27351,27352,27345 ,16002,16003,15996 ,0,0,0}, {27353,27354,27355 ,16004,16005,16006 ,0,0,0}, - {27355,27350,27356 ,16006,16001,16007 ,0,0,0}, {27357,27353,27358 ,16008,16004,16009 ,0,0,0}, - {27354,27353,27359 ,16005,16004,16010 ,0,0,0}, {27340,27360,27361 ,15991,16011,16012 ,0,0,0}, - {27357,27362,27353 ,16008,16013,16004 ,0,0,0}, {27363,27364,27365 ,16014,16015,16016 ,0,0,0}, - {27364,27366,27333 ,16015,16017,15986 ,0,0,0}, {27367,27368,27365 ,16018,16019,16016 ,0,0,0}, - {27366,27364,27363 ,16017,16015,16014 ,0,0,0}, {27369,27370,27367 ,16020,16021,16018 ,0,0,0}, - {27365,27368,27363 ,16016,16019,16014 ,0,0,0}, {27371,27372,27335 ,15508,16022,15551 ,0,0,0}, - {27373,27374,27375 ,16023,16024,15548 ,0,0,0}, {27371,27376,27372 ,15508,16025,16022 ,0,0,0}, - {27377,27378,27379 ,15545,15546,16026 ,0,0,0}, {27374,27380,27375 ,16024,16027,15548 ,0,0,0}, - {27381,27382,27383 ,16028,15465,16029 ,0,0,0}, {27377,27379,27384 ,15545,16026,16030 ,0,0,0}, - {27385,27386,27387 ,15541,16031,16032 ,0,0,0}, {27386,27385,27388 ,16031,15541,16033 ,0,0,0}, - {27389,27390,27391 ,15537,16034,16035 ,0,0,0}, {27392,27393,27390 ,16036,16037,16034 ,0,0,0}, - {27394,27395,27396 ,15535,15459,16038 ,0,0,0}, {27389,27391,27397 ,15537,16035,15457 ,0,0,0}, - {27398,27399,27400 ,16039,15532,15533 ,0,0,0}, {27394,27396,27401 ,15535,16038,15534 ,0,0,0}, - {27402,27403,27404 ,16040,16041,16042 ,0,0,0}, {27405,27399,27398 ,16043,15532,16039 ,0,0,0}, - {27406,27407,27408 ,16044,16045,16046 ,0,0,0}, {27408,27404,27406 ,16046,16042,16044 ,0,0,0}, - {27409,27410,27411 ,16047,16048,16049 ,0,0,0}, {27412,27407,27413 ,15527,16045,15491 ,0,0,0}, - {27414,27415,27416 ,16050,16051,16052 ,0,0,0}, {27415,27414,27417 ,16051,16050,16053 ,0,0,0}, - {27418,27419,27420 ,16054,16055,16056 ,0,0,0}, {27416,27419,27421 ,16052,16055,16057 ,0,0,0}, - {27422,27423,27424 ,15520,15521,16058 ,0,0,0}, {27425,27426,27427 ,16059,15392,16060 ,0,0,0}, - {27428,27429,27430 ,16061,16062,16063 ,0,0,0}, {27429,27428,27431 ,16062,16061,16064 ,0,0,0}, - {27432,27433,27434 ,16065,16066,16067 ,0,0,0}, {27435,27436,27432 ,16068,16069,16065 ,0,0,0}, - {27433,27432,27436 ,16066,16065,16069 ,0,0,0}, {27433,27436,27422 ,16066,16069,15520 ,0,0,0}, - {27437,27438,27439 ,16070,16071,16072 ,0,0,0}, {27420,27424,27423 ,16056,16058,15521 ,0,0,0}, - {27440,27425,27427 ,16073,16059,16060 ,0,0,0}, {27426,27441,27427 ,15392,16074,16060 ,0,0,0}, - {27442,27443,27425 ,16075,16076,16059 ,0,0,0}, {27425,27444,27426 ,16059,16077,15392 ,0,0,0}, - {27445,27446,27447 ,16078,16079,16080 ,0,0,0}, {26844,27448,27449 ,16081,16082,16083 ,0,0,0}, - {27449,27450,27199 ,16083,16084,16085 ,0,0,0}, {27450,26852,27199 ,16084,16086,16085 ,0,0,0}, - {26853,26852,27451 ,16087,16086,16088 ,0,0,0}, {27439,27419,27437 ,16072,16055,16070 ,0,0,0}, - {27430,27435,27432 ,16063,16068,16065 ,0,0,0}, {27420,27423,27418 ,16056,15521,16054 ,0,0,0}, - {26982,27431,26981 ,16089,16064,16090 ,0,0,0}, {27414,27416,27421 ,16050,16052,16057 ,0,0,0}, - {27419,27418,27421 ,16055,16054,16057 ,0,0,0}, {27409,27417,27410 ,16047,16053,16048 ,0,0,0}, - {27415,27417,27409 ,16051,16053,16047 ,0,0,0}, {27409,27452,27415 ,16047,16091,16051 ,0,0,0}, - {27410,27412,27411 ,16048,15527,16049 ,0,0,0}, {27413,27407,27406 ,15491,16045,16044 ,0,0,0}, - {27412,27413,27411 ,15527,15491,16049 ,0,0,0}, {27402,27404,27408 ,16040,16042,16046 ,0,0,0}, - {27398,27400,27453 ,16039,15533,16092 ,0,0,0}, {27454,27405,27455 ,15531,16043,16093 ,0,0,0}, - {27404,27403,27455 ,16042,16041,16093 ,0,0,0}, {27399,27405,27454 ,15532,16043,15531 ,0,0,0}, - {27403,27454,27455 ,16041,15531,16093 ,0,0,0}, {27453,27400,27401 ,16092,15533,15534 ,0,0,0}, - {27456,27398,27453 ,16094,16039,16092 ,0,0,0}, {27401,27396,27453 ,15534,16038,16092 ,0,0,0}, - {27397,27395,27457 ,15457,15459,15497 ,0,0,0}, {27394,27457,27395 ,15535,15497,15459 ,0,0,0}, - {27458,27397,27457 ,16095,15457,15497 ,0,0,0}, {27393,27391,27390 ,16037,16035,16034 ,0,0,0}, - {27389,27397,27458 ,15537,15457,16095 ,0,0,0}, {27392,27459,27393 ,16036,15500,16037 ,0,0,0}, - {27387,27386,27459 ,16032,16031,15500 ,0,0,0}, {27459,27392,27387 ,15500,16036,16032 ,0,0,0}, - {27388,27460,27383 ,16033,15542,16029 ,0,0,0}, {27461,27462,27463 ,16096,16097,16098 ,0,0,0}, - {27383,27460,27464 ,16029,15542,16099 ,0,0,0}, {27460,27388,27385 ,15542,16033,15541 ,0,0,0}, - {27465,27384,27382 ,16100,16030,15465 ,0,0,0}, {27381,27383,27464 ,16028,16029,16099 ,0,0,0}, - {27384,27465,27377 ,16030,16100,15545 ,0,0,0}, {27465,27382,27381 ,16100,15465,16028 ,0,0,0}, - {27376,27466,27467 ,16025,15507,16101 ,0,0,0}, {27378,27380,27468 ,15546,16027,16102 ,0,0,0}, - {27379,27378,27468 ,16026,15546,16102 ,0,0,0}, {27468,27380,27374 ,16102,16027,16024 ,0,0,0}, - {27469,27470,27471 ,16103,16104,16105 ,0,0,0}, {27466,27373,27375 ,15507,16023,15548 ,0,0,0}, - {27333,27366,27331 ,15986,16017,15557 ,0,0,0}, {27376,27373,27466 ,16025,16023,15507 ,0,0,0}, - {27376,27467,27372 ,16025,16101,16022 ,0,0,0}, {27335,27334,27371 ,15551,15987,15508 ,0,0,0}, - {27370,27369,27336 ,16021,16020,15552 ,0,0,0}, {27336,27369,27334 ,15552,16020,15987 ,0,0,0}, - {27472,27369,27367 ,16106,16020,16018 ,0,0,0}, {27370,27368,27367 ,16021,16019,16018 ,0,0,0}, - {27332,27361,27360 ,15515,16012,16011 ,0,0,0}, {27331,27361,27332 ,15557,16012,15515 ,0,0,0}, - {27341,27338,27337 ,15992,15989,15988 ,0,0,0}, {27340,27337,27360 ,15991,15988,16011 ,0,0,0}, - {27341,27473,27338 ,15992,16107,15989 ,0,0,0}, {27344,27474,27348 ,15995,14800,15999 ,0,0,0}, - {27475,27476,27473 ,16108,16109,16107 ,0,0,0}, {27342,27477,27478 ,15993,16110,16111 ,0,0,0}, - {27476,27479,27480 ,16109,16112,16113 ,0,0,0}, {27475,27479,27476 ,16108,16112,16109 ,0,0,0}, - {27476,27338,27473 ,16109,15989,16107 ,0,0,0}, {27480,27481,27482 ,16113,16114,16115 ,0,0,0}, - {27481,27480,27483 ,16114,16113,16116 ,0,0,0}, {27479,27483,27480 ,16112,16116,16113 ,0,0,0}, - {27478,27477,27482 ,16111,16110,16115 ,0,0,0}, {27484,27344,27343 ,16117,15995,15994 ,0,0,0}, - {27480,27482,27477 ,16113,16115,16110 ,0,0,0}, {27349,27348,27485 ,16000,15999,16118 ,0,0,0}, - {27480,27486,27476 ,16113,16119,16109 ,0,0,0}, {27487,27360,27337 ,16120,16011,15988 ,0,0,0}, - {27476,27347,27338 ,16109,15998,15989 ,0,0,0}, {27488,27332,27360 ,16121,15515,16011 ,0,0,0}, - {27339,27338,27347 ,15990,15989,15998 ,0,0,0}, {27489,27333,27332 ,16122,15986,15515 ,0,0,0}, - {27487,27337,27339 ,16120,15988,15990 ,0,0,0}, {27490,27364,27333 ,16123,16015,15986 ,0,0,0}, - {27488,27360,27487 ,16121,16011,16120 ,0,0,0}, {27491,27365,27364 ,16124,16016,16015 ,0,0,0}, - {27489,27332,27488 ,16122,15515,16121 ,0,0,0}, {27492,27367,27365 ,16125,16018,16016 ,0,0,0}, - {27333,27489,27490 ,15986,16122,16123 ,0,0,0}, {27493,27494,27495 ,16126,16127,15475 ,0,0,0}, - {27364,27490,27491 ,16015,16123,16124 ,0,0,0}, {27495,27334,27369 ,15475,15987,16020 ,0,0,0}, - {27365,27491,27492 ,16016,16124,16125 ,0,0,0}, {27496,27371,27334 ,16128,15508,15987 ,0,0,0}, - {27367,27492,27472 ,16018,16125,16106 ,0,0,0}, {27497,27376,27371 ,16129,16025,15508 ,0,0,0}, - {27369,27472,27495 ,16020,16106,15475 ,0,0,0}, {27498,27373,27376 ,16130,16023,16025 ,0,0,0}, - {27334,27495,27496 ,15987,15475,16128 ,0,0,0}, {27499,27374,27373 ,16131,16024,16023 ,0,0,0}, - {27497,27371,27496 ,16129,15508,16128 ,0,0,0}, {27500,27468,27374 ,16132,16102,16024 ,0,0,0}, - {27498,27376,27497 ,16130,16025,16129 ,0,0,0}, {27501,27379,27468 ,16133,16026,16102 ,0,0,0}, - {27373,27498,27499 ,16023,16130,16131 ,0,0,0}, {27470,27384,27379 ,16104,16030,16026 ,0,0,0}, - {27374,27499,27500 ,16024,16131,16132 ,0,0,0}, {27502,27382,27384 ,16134,15465,16030 ,0,0,0}, - {27468,27500,27501 ,16102,16132,16133 ,0,0,0}, {27503,27383,27382 ,16135,16029,15465 ,0,0,0}, - {27379,27501,27470 ,16026,16133,16104 ,0,0,0}, {27504,27388,27383 ,16136,16033,16029 ,0,0,0}, - {27502,27384,27470 ,16134,16030,16104 ,0,0,0}, {27505,27386,27388 ,16137,16031,16033 ,0,0,0}, - {27503,27382,27502 ,16135,15465,16134 ,0,0,0}, {27506,27459,27386 ,16138,15500,16031 ,0,0,0}, - {27383,27503,27504 ,16029,16135,16136 ,0,0,0}, {27393,27459,27461 ,16037,15500,16096 ,0,0,0}, - {27388,27504,27505 ,16033,16136,16137 ,0,0,0}, {27507,27391,27393 ,16139,16035,16037 ,0,0,0}, - {27386,27505,27506 ,16031,16137,16138 ,0,0,0}, {27508,27397,27391 ,15458,15457,16035 ,0,0,0}, - {27459,27506,27461 ,15500,16138,16096 ,0,0,0}, {27509,27395,27397 ,16140,15459,15457 ,0,0,0}, - {27507,27393,27461 ,16139,16037,16096 ,0,0,0}, {27510,27396,27395 ,16141,16038,15459 ,0,0,0}, - {27508,27391,27507 ,15458,16035,16139 ,0,0,0}, {27511,27453,27396 ,16142,16092,16038 ,0,0,0}, - {27397,27508,27509 ,15457,15458,16140 ,0,0,0}, {27512,27513,27514 ,15354,16143,16144 ,0,0,0}, - {27395,27509,27510 ,15459,16140,16141 ,0,0,0}, {27515,27405,27398 ,16145,16043,16039 ,0,0,0}, - {27396,27510,27511 ,16038,16141,16142 ,0,0,0}, {27516,27455,27405 ,16146,16093,16043 ,0,0,0}, - {27453,27511,27456 ,16092,16142,16094 ,0,0,0}, {27517,27404,27455 ,16147,16042,16093 ,0,0,0}, - {27398,27456,27515 ,16039,16094,16145 ,0,0,0}, {27518,27406,27404 ,16148,16044,16042 ,0,0,0}, - {27516,27405,27515 ,16146,16043,16145 ,0,0,0}, {27519,27413,27406 ,16149,15491,16044 ,0,0,0}, - {27517,27455,27516 ,16147,16093,16146 ,0,0,0}, {27520,27411,27413 ,16150,16049,15491 ,0,0,0}, - {27518,27404,27517 ,16148,16042,16147 ,0,0,0}, {27521,27409,27411 ,16151,16047,16049 ,0,0,0}, - {27406,27518,27519 ,16044,16148,16149 ,0,0,0}, {27415,27522,27416 ,16051,16152,16052 ,0,0,0}, - {27413,27519,27520 ,15491,16149,16150 ,0,0,0}, {27437,27523,27438 ,16070,16153,16071 ,0,0,0}, - {27411,27520,27521 ,16049,16150,16151 ,0,0,0}, {27437,27419,27416 ,16070,16055,16052 ,0,0,0}, - {27409,27521,27452 ,16047,16151,16091 ,0,0,0}, {27439,27420,27419 ,16072,16056,16055 ,0,0,0}, - {27415,27452,27522 ,16051,16091,16152 ,0,0,0}, {27424,27420,27524 ,16058,16056,16154 ,0,0,0}, - {27437,27416,27522 ,16070,16052,16152 ,0,0,0}, {27441,27434,27433 ,16074,16067,16066 ,0,0,0}, - {27525,27432,27434 ,16155,16065,16067 ,0,0,0}, {27424,27433,27422 ,16058,16066,15520 ,0,0,0}, - {27524,27420,27439 ,16154,16056,16072 ,0,0,0}, {27441,27426,27434 ,16074,15392,16067 ,0,0,0}, - {27433,27424,27441 ,16066,16058,16074 ,0,0,0}, {27430,27526,27428 ,16063,16156,16061 ,0,0,0}, - {27428,26981,27431 ,16061,16090,16064 ,0,0,0}, {27435,27430,27429 ,16068,16063,16062 ,0,0,0}, - {27430,27525,27526 ,16063,16155,16156 ,0,0,0}, {26983,26981,27428 ,16157,16090,16061 ,0,0,0}, - {27477,27486,27480 ,16110,16119,16113 ,0,0,0}, {27343,27342,27478 ,15994,15993,16111 ,0,0,0}, - {27527,27355,27354 ,16158,16006,16005 ,0,0,0}, {27486,27347,27476 ,16119,15998,16109 ,0,0,0}, - {27486,27477,27528 ,16119,16110,16159 ,0,0,0}, {27339,27346,27529 ,15990,15997,16160 ,0,0,0}, - {27345,27347,27486 ,15996,15998,16119 ,0,0,0}, {27487,27529,27530 ,16120,16160,16161 ,0,0,0}, - {27346,27339,27347 ,15997,15990,15998 ,0,0,0}, {27488,27530,27531 ,16121,16161,16162 ,0,0,0}, - {27529,27487,27339 ,16160,16120,15990 ,0,0,0}, {27489,27531,27532 ,16122,16162,16163 ,0,0,0}, - {27530,27488,27487 ,16161,16121,16120 ,0,0,0}, {27490,27532,27533 ,16123,16163,15383 ,0,0,0}, - {27531,27489,27488 ,16162,16122,16121 ,0,0,0}, {27491,27533,27534 ,16124,15383,16164 ,0,0,0}, - {27532,27490,27489 ,16163,16123,16122 ,0,0,0}, {27492,27534,27535 ,16125,16164,16165 ,0,0,0}, - {27533,27491,27490 ,15383,16124,16123 ,0,0,0}, {27472,27535,27493 ,16106,16165,16126 ,0,0,0}, - {27492,27491,27534 ,16125,16124,16164 ,0,0,0}, {27536,27537,27538 ,16166,15378,16167 ,0,0,0}, - {27472,27492,27535 ,16106,16125,16165 ,0,0,0}, {27496,27494,27536 ,16128,16127,16166 ,0,0,0}, - {27495,27472,27493 ,15475,16106,16126 ,0,0,0}, {27497,27536,27539 ,16129,16166,16168 ,0,0,0}, - {27496,27495,27494 ,16128,15475,16127 ,0,0,0}, {27498,27539,27540 ,16130,16168,16169 ,0,0,0}, - {27536,27497,27496 ,16166,16129,16128 ,0,0,0}, {27499,27540,27541 ,16131,16169,16170 ,0,0,0}, - {27539,27498,27497 ,16168,16130,16129 ,0,0,0}, {27500,27541,27542 ,16132,16170,16171 ,0,0,0}, - {27540,27499,27498 ,16169,16131,16130 ,0,0,0}, {27501,27542,27471 ,16133,16171,16105 ,0,0,0}, - {27500,27499,27541 ,16132,16131,16170 ,0,0,0}, {27543,27544,27545 ,16172,16173,16174 ,0,0,0}, - {27501,27500,27542 ,16133,16132,16171 ,0,0,0}, {27502,27469,27546 ,16134,16103,16175 ,0,0,0}, - {27470,27501,27471 ,16104,16133,16105 ,0,0,0}, {27503,27546,27547 ,16135,16175,16176 ,0,0,0}, - {27469,27502,27470 ,16103,16134,16104 ,0,0,0}, {27504,27547,27548 ,16136,16176,16177 ,0,0,0}, - {27546,27503,27502 ,16175,16135,16134 ,0,0,0}, {27505,27548,27549 ,16137,16177,16178 ,0,0,0}, - {27547,27504,27503 ,16176,16136,16135 ,0,0,0}, {27506,27549,27462 ,16138,16178,16097 ,0,0,0}, - {27505,27504,27548 ,16137,16136,16177 ,0,0,0}, {27550,27551,27552 ,16179,16180,16181 ,0,0,0}, - {27506,27505,27549 ,16138,16137,16178 ,0,0,0}, {27507,27463,27553 ,16139,16098,16182 ,0,0,0}, - {27461,27506,27462 ,16096,16138,16097 ,0,0,0}, {27508,27553,27554 ,15458,16182,16183 ,0,0,0}, - {27507,27461,27463 ,16139,16096,16098 ,0,0,0}, {27509,27554,27555 ,16140,16183,16184 ,0,0,0}, - {27553,27508,27507 ,16182,15458,16139 ,0,0,0}, {27510,27555,27556 ,16141,16184,16185 ,0,0,0}, - {27554,27509,27508 ,16183,16140,15458 ,0,0,0}, {27511,27556,27557 ,16142,16185,16186 ,0,0,0}, - {27555,27510,27509 ,16184,16141,16140 ,0,0,0}, {27456,27557,27558 ,16094,16186,16187 ,0,0,0}, - {27511,27510,27556 ,16142,16141,16185 ,0,0,0}, {27515,27558,27513 ,16145,16187,16143 ,0,0,0}, - {27456,27511,27557 ,16094,16142,16186 ,0,0,0}, {27516,27513,27559 ,16146,16143,16188 ,0,0,0}, - {27515,27456,27558 ,16145,16094,16187 ,0,0,0}, {27517,27559,27560 ,16147,16188,16189 ,0,0,0}, - {27513,27516,27515 ,16143,16146,16145 ,0,0,0}, {27518,27560,27561 ,16148,16189,16190 ,0,0,0}, - {27559,27517,27516 ,16188,16147,16146 ,0,0,0}, {27519,27561,27562 ,16149,16190,16191 ,0,0,0}, - {27560,27518,27517 ,16189,16148,16147 ,0,0,0}, {27520,27562,27563 ,16150,16191,16192 ,0,0,0}, - {27561,27519,27518 ,16190,16149,16148 ,0,0,0}, {27521,27563,27564 ,16151,16192,15399 ,0,0,0}, - {27562,27520,27519 ,16191,16150,16149 ,0,0,0}, {27452,27564,27565 ,16091,15399,16193 ,0,0,0}, - {27563,27521,27520 ,16192,16151,16150 ,0,0,0}, {27522,27565,27523 ,16152,16193,16153 ,0,0,0}, - {27452,27521,27564 ,16091,16151,15399 ,0,0,0}, {27566,27439,27438 ,16194,16072,16071 ,0,0,0}, - {27522,27452,27565 ,16152,16091,16193 ,0,0,0}, {27448,27567,27443 ,16082,16195,16076 ,0,0,0}, - {27437,27522,27523 ,16070,16152,16153 ,0,0,0}, {27566,27427,27524 ,16194,16060,16154 ,0,0,0}, - {27426,27568,27434 ,15392,16196,16067 ,0,0,0}, {27524,27441,27424 ,16154,16074,16058 ,0,0,0}, - {27566,27524,27439 ,16194,16154,16072 ,0,0,0}, {27569,27526,27525 ,16197,16156,16155 ,0,0,0}, - {27524,27427,27441 ,16154,16060,16074 ,0,0,0}, {26984,27526,27569 ,16198,16156,16197 ,0,0,0}, - {27526,26983,27428 ,16156,16157,16061 ,0,0,0}, {27432,27525,27430 ,16065,16155,16063 ,0,0,0}, - {27568,27569,27525 ,16196,16197,16155 ,0,0,0}, {26984,26983,27526 ,16198,16157,16156 ,0,0,0}, - {27528,27477,27342 ,16159,16110,15993 ,0,0,0}, {27474,27344,27484 ,14800,15995,16117 ,0,0,0}, - {27570,27346,27352 ,16199,15997,16003 ,0,0,0}, {27528,27345,27486 ,16159,15996,16119 ,0,0,0}, - {27528,27342,27571 ,16159,15993,16200 ,0,0,0}, {27572,27573,27574 ,16201,16202,16203 ,0,0,0}, - {27351,27345,27528 ,16002,15996,16159 ,0,0,0}, {27570,27572,27529 ,16199,16201,16160 ,0,0,0}, - {27352,27346,27345 ,16003,15997,15996 ,0,0,0}, {27572,27575,27530 ,16201,16204,16161 ,0,0,0}, - {27570,27529,27346 ,16199,16160,15997 ,0,0,0}, {27575,27576,27531 ,16204,16205,16162 ,0,0,0}, - {27572,27530,27529 ,16201,16161,16160 ,0,0,0}, {27576,27577,27532 ,16205,15382,16163 ,0,0,0}, - {27575,27531,27530 ,16204,16162,16161 ,0,0,0}, {27577,27578,27533 ,15382,16206,15383 ,0,0,0}, - {27576,27532,27531 ,16205,16163,16162 ,0,0,0}, {27578,27579,27534 ,16206,16207,16164 ,0,0,0}, - {27577,27533,27532 ,15382,15383,16163 ,0,0,0}, {27579,27580,27535 ,16207,16208,16165 ,0,0,0}, - {27578,27534,27533 ,16206,16164,15383 ,0,0,0}, {27580,27581,27493 ,16208,16209,16126 ,0,0,0}, - {27579,27535,27534 ,16207,16165,16164 ,0,0,0}, {27581,27537,27494 ,16209,15378,16127 ,0,0,0}, - {27493,27535,27580 ,16126,16165,16208 ,0,0,0}, {27582,27583,27584 ,16210,16211,16212 ,0,0,0}, - {27494,27493,27581 ,16127,16126,16209 ,0,0,0}, {27538,27582,27539 ,16167,16210,16168 ,0,0,0}, - {27537,27536,27494 ,15378,16166,16127 ,0,0,0}, {27582,27585,27540 ,16210,16213,16169 ,0,0,0}, - {27538,27539,27536 ,16167,16168,16166 ,0,0,0}, {27585,27586,27541 ,16213,16214,16170 ,0,0,0}, - {27582,27540,27539 ,16210,16169,16168 ,0,0,0}, {27586,27587,27542 ,16214,16215,16171 ,0,0,0}, - {27585,27541,27540 ,16213,16170,16169 ,0,0,0}, {27587,27588,27471 ,16215,16216,16105 ,0,0,0}, - {27586,27542,27541 ,16214,16171,16170 ,0,0,0}, {27469,27588,27589 ,16103,16216,16217 ,0,0,0}, - {27471,27542,27587 ,16105,16171,16215 ,0,0,0}, {27589,27543,27546 ,16217,16172,16175 ,0,0,0}, - {27588,27469,27471 ,16216,16103,16105 ,0,0,0}, {27543,27590,27547 ,16172,16218,16176 ,0,0,0}, - {27589,27546,27469 ,16217,16175,16103 ,0,0,0}, {27590,27591,27548 ,16218,15368,16177 ,0,0,0}, - {27543,27547,27546 ,16172,16176,16175 ,0,0,0}, {27591,27592,27549 ,15368,16219,16178 ,0,0,0}, - {27590,27548,27547 ,16218,16177,16176 ,0,0,0}, {27592,27593,27462 ,16219,16220,16097 ,0,0,0}, - {27591,27549,27548 ,15368,16178,16177 ,0,0,0}, {27593,27594,27463 ,16220,16221,16098 ,0,0,0}, - {27462,27549,27592 ,16097,16178,16219 ,0,0,0}, {27594,27550,27553 ,16221,16179,16182 ,0,0,0}, - {27463,27462,27593 ,16098,16097,16220 ,0,0,0}, {27550,27595,27554 ,16179,16222,16183 ,0,0,0}, - {27594,27553,27463 ,16221,16182,16098 ,0,0,0}, {27595,27596,27555 ,16222,16223,16184 ,0,0,0}, - {27550,27554,27553 ,16179,16183,16182 ,0,0,0}, {27596,27597,27556 ,16223,16224,16185 ,0,0,0}, - {27595,27555,27554 ,16222,16184,16183 ,0,0,0}, {27597,27598,27557 ,16224,16225,16186 ,0,0,0}, - {27596,27556,27555 ,16223,16185,16184 ,0,0,0}, {27598,27514,27558 ,16225,16144,16187 ,0,0,0}, - {27557,27556,27597 ,16186,16185,16224 ,0,0,0}, {27599,27600,27601 ,16226,16227,16228 ,0,0,0}, - {27558,27557,27598 ,16187,16186,16225 ,0,0,0}, {27512,27599,27559 ,15354,16226,16188 ,0,0,0}, - {27514,27513,27558 ,16144,16143,16187 ,0,0,0}, {27599,27602,27560 ,16226,16229,16189 ,0,0,0}, - {27512,27559,27513 ,15354,16188,16143 ,0,0,0}, {27602,27603,27561 ,16229,16230,16190 ,0,0,0}, - {27599,27560,27559 ,16226,16189,16188 ,0,0,0}, {27603,27604,27562 ,16230,16231,16191 ,0,0,0}, - {27602,27561,27560 ,16229,16190,16189 ,0,0,0}, {27604,27605,27563 ,16231,15348,16192 ,0,0,0}, - {27603,27562,27561 ,16230,16191,16190 ,0,0,0}, {27605,27606,27564 ,15348,16232,15399 ,0,0,0}, - {27604,27563,27562 ,16231,16192,16191 ,0,0,0}, {27606,27607,27565 ,16232,16233,16193 ,0,0,0}, - {27605,27564,27563 ,15348,15399,16192 ,0,0,0}, {27607,27608,27523 ,16233,16234,16153 ,0,0,0}, - {27606,27565,27564 ,16232,16193,15399 ,0,0,0}, {27608,27609,27438 ,16234,16235,16071 ,0,0,0}, - {27607,27523,27565 ,16233,16153,16193 ,0,0,0}, {27609,27440,27566 ,16235,16073,16194 ,0,0,0}, - {27438,27523,27608 ,16071,16153,16234 ,0,0,0}, {27610,26980,26842 ,16236,15128,15118 ,0,0,0}, - {27609,27566,27438 ,16235,16194,16071 ,0,0,0}, {27442,27425,27440 ,16075,16059,16073 ,0,0,0}, - {27566,27440,27427 ,16194,16073,16060 ,0,0,0}, {26975,27569,27610 ,15113,16197,16236 ,0,0,0}, - {26975,26986,27569 ,15113,15265,16197 ,0,0,0}, {27434,27568,27525 ,16067,16196,16155 ,0,0,0}, - {27444,27610,27568 ,16077,16236,16196 ,0,0,0}, {26984,27569,26986 ,16198,16197,15265 ,0,0,0}, - {27344,27571,27342 ,15995,16200,15993 ,0,0,0}, {27485,27348,27474 ,16118,15999,14800 ,0,0,0}, - {27351,27611,27612 ,16002,16237,16238 ,0,0,0}, {27571,27351,27528 ,16200,16002,16159 ,0,0,0}, - {27613,27571,27344 ,16239,16200,15995 ,0,0,0}, {27352,27612,27614 ,16003,16238,16240 ,0,0,0}, - {27571,27611,27351 ,16200,16237,16002 ,0,0,0}, {27570,27614,27573 ,16199,16240,16202 ,0,0,0}, - {27612,27352,27351 ,16238,16003,16002 ,0,0,0}, {27615,27575,27574 ,16241,16204,16203 ,0,0,0}, - {27614,27570,27352 ,16240,16199,16003 ,0,0,0}, {27616,27576,27615 ,16242,16205,16241 ,0,0,0}, - {27573,27572,27570 ,16202,16201,16199 ,0,0,0}, {27617,27618,27619 ,16243,16244,16245 ,0,0,0}, - {27574,27575,27572 ,16203,16204,16201 ,0,0,0}, {27616,27617,27577 ,16242,16243,15382 ,0,0,0}, - {27615,27576,27575 ,16241,16205,16204 ,0,0,0}, {27617,27620,27578 ,16243,16246,16206 ,0,0,0}, - {27616,27577,27576 ,16242,15382,16205 ,0,0,0}, {27620,27621,27579 ,16246,16247,16207 ,0,0,0}, - {27617,27578,27577 ,16243,16206,15382 ,0,0,0}, {27621,27622,27580 ,16247,16248,16208 ,0,0,0}, - {27620,27579,27578 ,16246,16207,16206 ,0,0,0}, {27622,27623,27581 ,16248,16249,16209 ,0,0,0}, - {27621,27580,27579 ,16247,16208,16207 ,0,0,0}, {27537,27623,27624 ,15378,16249,16250 ,0,0,0}, - {27622,27581,27580 ,16248,16209,16208 ,0,0,0}, {27538,27624,27583 ,16167,16250,16211 ,0,0,0}, - {27623,27537,27581 ,16249,15378,16209 ,0,0,0}, {27625,27626,27627 ,16251,16252,16253 ,0,0,0}, - {27624,27538,27537 ,16250,16167,15378 ,0,0,0}, {27584,27625,27585 ,16212,16251,16213 ,0,0,0}, - {27583,27582,27538 ,16211,16210,16167 ,0,0,0}, {27625,27628,27586 ,16251,16254,16214 ,0,0,0}, - {27584,27585,27582 ,16212,16213,16210 ,0,0,0}, {27628,27629,27587 ,16254,16255,16215 ,0,0,0}, - {27625,27586,27585 ,16251,16214,16213 ,0,0,0}, {27588,27629,27630 ,16216,16255,16256 ,0,0,0}, - {27628,27587,27586 ,16254,16215,16214 ,0,0,0}, {27589,27630,27544 ,16217,16256,16173 ,0,0,0}, - {27588,27587,27629 ,16216,16215,16255 ,0,0,0}, {27631,27632,27633 ,16257,15282,16258 ,0,0,0}, - {27630,27589,27588 ,16256,16217,16216 ,0,0,0}, {27545,27631,27590 ,16174,16257,16218 ,0,0,0}, - {27544,27543,27589 ,16173,16172,16217 ,0,0,0}, {27631,27634,27591 ,16257,16259,15368 ,0,0,0}, - {27545,27590,27543 ,16174,16218,16172 ,0,0,0}, {27634,27635,27592 ,16259,16260,16219 ,0,0,0}, - {27631,27591,27590 ,16257,15368,16218 ,0,0,0}, {27635,27636,27593 ,16260,16261,16220 ,0,0,0}, - {27634,27592,27591 ,16259,16219,15368 ,0,0,0}, {27594,27636,27551 ,16221,16261,16180 ,0,0,0}, - {27593,27592,27635 ,16220,16219,16260 ,0,0,0}, {27637,27638,27639 ,16262,16263,16264 ,0,0,0}, - {27636,27594,27593 ,16261,16221,16220 ,0,0,0}, {27552,27637,27595 ,16181,16262,16222 ,0,0,0}, - {27551,27550,27594 ,16180,16179,16221 ,0,0,0}, {27637,27640,27596 ,16262,16265,16223 ,0,0,0}, - {27552,27595,27550 ,16181,16222,16179 ,0,0,0}, {27640,27641,27597 ,16265,16266,16224 ,0,0,0}, - {27637,27596,27595 ,16262,16223,16222 ,0,0,0}, {27641,27642,27598 ,16266,16267,16225 ,0,0,0}, - {27640,27597,27596 ,16265,16224,16223 ,0,0,0}, {27514,27642,27643 ,16144,16267,16268 ,0,0,0}, - {27641,27598,27597 ,16266,16225,16224 ,0,0,0}, {27512,27643,27600 ,15354,16268,16227 ,0,0,0}, - {27642,27514,27598 ,16267,16144,16225 ,0,0,0}, {27644,27602,27601 ,16269,16229,16228 ,0,0,0}, - {27643,27512,27514 ,16268,15354,16144 ,0,0,0}, {27645,27646,27647 ,16270,16271,15270 ,0,0,0}, - {27600,27599,27512 ,16227,16226,15354 ,0,0,0}, {27644,27645,27603 ,16269,16270,16230 ,0,0,0}, - {27601,27602,27599 ,16228,16229,16226 ,0,0,0}, {27645,27648,27604 ,16270,16272,16231 ,0,0,0}, - {27644,27603,27602 ,16269,16230,16229 ,0,0,0}, {27648,27649,27605 ,16272,16273,15348 ,0,0,0}, - {27645,27604,27603 ,16270,16231,16230 ,0,0,0}, {27649,27650,27606 ,16273,16274,16232 ,0,0,0}, - {27648,27605,27604 ,16272,15348,16231 ,0,0,0}, {27650,27651,27607 ,16274,16275,16233 ,0,0,0}, - {27649,27606,27605 ,16273,16232,15348 ,0,0,0}, {27651,27652,27608 ,16275,16276,16234 ,0,0,0}, - {27650,27607,27606 ,16274,16233,16232 ,0,0,0}, {27652,27653,27609 ,16276,16277,16235 ,0,0,0}, - {27651,27608,27607 ,16275,16234,16233 ,0,0,0}, {27440,27653,27442 ,16073,16277,16075 ,0,0,0}, - {27609,27608,27652 ,16235,16234,16276 ,0,0,0}, {27447,27442,27653 ,16080,16075,16277 ,0,0,0}, - {27440,27609,27653 ,16073,16235,16277 ,0,0,0}, {27444,27567,27610 ,16077,16195,16236 ,0,0,0}, - {27568,27610,27569 ,16196,16236,16197 ,0,0,0}, {27426,27444,27568 ,15392,16077,16196 ,0,0,0}, - {27443,27567,27444 ,16076,16195,16077 ,0,0,0}, {26975,27610,26842 ,15113,16236,15118 ,0,0,0}, - {27348,27613,27344 ,15999,16239,15995 ,0,0,0}, {27356,27350,27349 ,16007,16001,16000 ,0,0,0}, - {27611,27654,27655 ,16237,16278,16279 ,0,0,0}, {27613,27611,27571 ,16239,16237,16200 ,0,0,0}, - {27348,27656,27613 ,15999,16280,16239 ,0,0,0}, {27612,27655,27657 ,16238,16279,16281 ,0,0,0}, - {27613,27654,27611 ,16239,16278,16237 ,0,0,0}, {27614,27657,27658 ,16240,16281,16282 ,0,0,0}, - {27611,27655,27612 ,16237,16279,16238 ,0,0,0}, {27573,27658,27659 ,16202,16282,16283 ,0,0,0}, - {27612,27657,27614 ,16238,16281,16240 ,0,0,0}, {27574,27659,27660 ,16203,16283,16284 ,0,0,0}, - {27614,27658,27573 ,16240,16282,16202 ,0,0,0}, {27615,27660,27661 ,16241,16284,15296 ,0,0,0}, - {27573,27659,27574 ,16202,16283,16203 ,0,0,0}, {27616,27661,27618 ,16242,15296,16244 ,0,0,0}, - {27660,27615,27574 ,16284,16241,16203 ,0,0,0}, {27662,27620,27619 ,15293,16246,16245 ,0,0,0}, - {27661,27616,27615 ,15296,16242,16241 ,0,0,0}, {27663,27664,27662 ,16285,16286,15293 ,0,0,0}, - {27618,27617,27616 ,16244,16243,16242 ,0,0,0}, {27662,27664,27621 ,15293,16286,16247 ,0,0,0}, - {27619,27620,27617 ,16245,16246,16243 ,0,0,0}, {27664,27665,27622 ,16286,15164,16248 ,0,0,0}, - {27662,27621,27620 ,15293,16247,16246 ,0,0,0}, {27623,27665,27666 ,16249,15164,16287 ,0,0,0}, - {27664,27622,27621 ,16286,16248,16247 ,0,0,0}, {27624,27666,27667 ,16250,16287,16288 ,0,0,0}, - {27622,27665,27623 ,16248,15164,16249 ,0,0,0}, {27583,27667,27668 ,16211,16288,16289 ,0,0,0}, - {27623,27666,27624 ,16249,16287,16250 ,0,0,0}, {27584,27668,27626 ,16212,16289,16252 ,0,0,0}, - {27667,27583,27624 ,16288,16211,16250 ,0,0,0}, {27669,27670,27627 ,16290,16291,16253 ,0,0,0}, - {27668,27584,27583 ,16289,16212,16211 ,0,0,0}, {27627,27670,27628 ,16253,16291,16254 ,0,0,0}, - {27626,27625,27584 ,16252,16251,16212 ,0,0,0}, {27670,27671,27629 ,16291,16292,16255 ,0,0,0}, - {27627,27628,27625 ,16253,16254,16251 ,0,0,0}, {27630,27671,27672 ,16256,16292,16293 ,0,0,0}, - {27670,27629,27628 ,16291,16255,16254 ,0,0,0}, {27544,27672,27673 ,16173,16293,16294 ,0,0,0}, - {27629,27671,27630 ,16255,16292,16256 ,0,0,0}, {27545,27673,27632 ,16174,16294,15282 ,0,0,0}, - {27672,27544,27630 ,16293,16173,16256 ,0,0,0}, {27674,27675,27633 ,16295,16296,16258 ,0,0,0}, - {27673,27545,27544 ,16294,16174,16173 ,0,0,0}, {27633,27675,27634 ,16258,16296,16259 ,0,0,0}, - {27632,27631,27545 ,15282,16257,16174 ,0,0,0}, {27675,27676,27635 ,16296,16297,16260 ,0,0,0}, - {27633,27634,27631 ,16258,16259,16257 ,0,0,0}, {27636,27676,27677 ,16261,16297,16298 ,0,0,0}, - {27675,27635,27634 ,16296,16260,16259 ,0,0,0}, {27551,27677,27678 ,16180,16298,16299 ,0,0,0}, - {27635,27676,27636 ,16260,16297,16261 ,0,0,0}, {27552,27678,27638 ,16181,16299,16263 ,0,0,0}, - {27677,27551,27636 ,16298,16180,16261 ,0,0,0}, {27679,27680,27639 ,16300,16301,16264 ,0,0,0}, - {27678,27552,27551 ,16299,16181,16180 ,0,0,0}, {27639,27680,27640 ,16264,16301,16265 ,0,0,0}, - {27638,27637,27552 ,16263,16262,16181 ,0,0,0}, {27680,27681,27641 ,16301,16302,16266 ,0,0,0}, - {27639,27640,27637 ,16264,16265,16262 ,0,0,0}, {27642,27681,27682 ,16267,16302,15083 ,0,0,0}, - {27680,27641,27640 ,16301,16266,16265 ,0,0,0}, {27643,27682,27683 ,16268,15083,16303 ,0,0,0}, - {27641,27681,27642 ,16266,16302,16267 ,0,0,0}, {27600,27683,27684 ,16227,16303,15273 ,0,0,0}, - {27642,27682,27643 ,16267,15083,16268 ,0,0,0}, {27601,27684,27685 ,16228,15273,16304 ,0,0,0}, - {27643,27683,27600 ,16268,16303,16227 ,0,0,0}, {27644,27685,27646 ,16269,16304,16271 ,0,0,0}, - {27684,27601,27600 ,15273,16228,16227 ,0,0,0}, {27686,27648,27647 ,16305,16272,15270 ,0,0,0}, - {27685,27644,27601 ,16304,16269,16228 ,0,0,0}, {27687,27688,27686 ,16306,16307,16305 ,0,0,0}, - {27646,27645,27644 ,16271,16270,16269 ,0,0,0}, {27686,27688,27649 ,16305,16307,16273 ,0,0,0}, - {27647,27648,27645 ,15270,16272,16270 ,0,0,0}, {27688,27689,27650 ,16307,16308,16274 ,0,0,0}, - {27686,27649,27648 ,16305,16273,16272 ,0,0,0}, {27689,27690,27651 ,16308,16309,16275 ,0,0,0}, - {27688,27650,27649 ,16307,16274,16273 ,0,0,0}, {27690,27691,27652 ,16309,15110,16276 ,0,0,0}, - {27689,27651,27650 ,16308,16275,16274 ,0,0,0}, {27653,27691,27447 ,16277,15110,16080 ,0,0,0}, - {27690,27652,27651 ,16309,16276,16275 ,0,0,0}, {27447,27692,27442 ,16080,16310,16075 ,0,0,0}, - {27652,27691,27653 ,16276,15110,16277 ,0,0,0}, {26847,27567,27448 ,16311,16195,16082 ,0,0,0}, - {27567,26980,27610 ,16195,15128,16236 ,0,0,0}, {27425,27443,27444 ,16059,16076,16077 ,0,0,0}, - {27692,27448,27443 ,16310,16082,16076 ,0,0,0}, {26847,26980,27567 ,16311,15128,16195 ,0,0,0}, - {27350,27656,27348 ,16001,16280,15999 ,0,0,0}, {27693,27355,27356 ,16312,16006,16007 ,0,0,0}, - {27694,27654,27656 ,16313,16278,16280 ,0,0,0}, {27656,27654,27613 ,16280,16278,16239 ,0,0,0}, - {27656,27527,27694 ,16280,16158,16313 ,0,0,0}, {27695,27655,27654 ,16314,16279,16278 ,0,0,0}, - {27654,27694,27695 ,16278,16313,16314 ,0,0,0}, {27696,27657,27655 ,16315,16281,16279 ,0,0,0}, - {27655,27695,27696 ,16279,16314,16315 ,0,0,0}, {27697,27658,27657 ,16316,16282,16281 ,0,0,0}, - {27657,27696,27697 ,16281,16315,16316 ,0,0,0}, {27698,27659,27658 ,16317,16283,16282 ,0,0,0}, - {27658,27697,27698 ,16282,16316,16317 ,0,0,0}, {27699,27660,27659 ,16318,16284,16283 ,0,0,0}, - {27659,27698,27699 ,16283,16317,16318 ,0,0,0}, {27700,27661,27660 ,16319,15296,16284 ,0,0,0}, - {27660,27699,27700 ,16284,16318,16319 ,0,0,0}, {27701,27618,27661 ,16320,16244,15296 ,0,0,0}, - {27661,27700,27701 ,15296,16319,16320 ,0,0,0}, {27702,27619,27618 ,16321,16245,16244 ,0,0,0}, - {27618,27701,27702 ,16244,16320,16321 ,0,0,0}, {27703,27662,27619 ,16322,15293,16245 ,0,0,0}, - {27702,27703,27619 ,16321,16322,16245 ,0,0,0}, {27704,27705,27706 ,16323,16324,15168 ,0,0,0}, - {27703,27663,27662 ,16322,16285,15293 ,0,0,0}, {27707,27665,27664 ,16325,15164,16286 ,0,0,0}, - {27663,27707,27664 ,16285,16325,16286 ,0,0,0}, {27708,27666,27665 ,16326,16287,15164 ,0,0,0}, - {27665,27707,27708 ,15164,16325,16326 ,0,0,0}, {27709,27667,27666 ,16327,16288,16287 ,0,0,0}, - {27666,27708,27709 ,16287,16326,16327 ,0,0,0}, {27710,27668,27667 ,16328,16289,16288 ,0,0,0}, - {27667,27709,27710 ,16288,16327,16328 ,0,0,0}, {27711,27626,27668 ,15249,16252,16289 ,0,0,0}, - {27668,27710,27711 ,16289,16328,15249 ,0,0,0}, {27712,27627,27626 ,16329,16253,16252 ,0,0,0}, - {27711,27712,27626 ,15249,16329,16252 ,0,0,0}, {27713,27669,27714 ,16330,16290,16331 ,0,0,0}, - {27712,27669,27627 ,16329,16290,16253 ,0,0,0}, {27713,27671,27670 ,16330,16292,16291 ,0,0,0}, - {27669,27713,27670 ,16290,16330,16291 ,0,0,0}, {27715,27672,27671 ,16332,16293,16292 ,0,0,0}, - {27671,27713,27715 ,16292,16330,16332 ,0,0,0}, {27716,27673,27672 ,16333,16294,16293 ,0,0,0}, - {27672,27715,27716 ,16293,16332,16333 ,0,0,0}, {27717,27632,27673 ,15244,15282,16294 ,0,0,0}, - {27673,27716,27717 ,16294,16333,15244 ,0,0,0}, {27718,27633,27632 ,16334,16258,15282 ,0,0,0}, - {27717,27718,27632 ,15244,16334,15282 ,0,0,0}, {27719,27720,27721 ,15135,15136,16335 ,0,0,0}, - {27718,27674,27633 ,16334,16295,16258 ,0,0,0}, {27722,27676,27675 ,16336,16297,16296 ,0,0,0}, - {27674,27722,27675 ,16295,16336,16296 ,0,0,0}, {27723,27677,27676 ,16337,16298,16297 ,0,0,0}, - {27676,27722,27723 ,16297,16336,16337 ,0,0,0}, {27724,27678,27677 ,16338,16299,16298 ,0,0,0}, - {27677,27723,27724 ,16298,16337,16338 ,0,0,0}, {27725,27638,27678 ,16339,16263,16299 ,0,0,0}, - {27678,27724,27725 ,16299,16338,16339 ,0,0,0}, {27726,27639,27638 ,16340,16264,16263 ,0,0,0}, - {27725,27726,27638 ,16339,16340,16263 ,0,0,0}, {27680,27727,27681 ,16301,16341,16302 ,0,0,0}, - {27726,27679,27639 ,16340,16300,16264 ,0,0,0}, {27728,27729,27727 ,16342,15081,16341 ,0,0,0}, - {27679,27727,27680 ,16300,16341,16301 ,0,0,0}, {27729,27682,27681 ,15081,15083,16302 ,0,0,0}, - {27681,27727,27729 ,16302,16341,15081 ,0,0,0}, {27730,27683,27682 ,16343,16303,15083 ,0,0,0}, - {27682,27729,27730 ,15083,15081,16343 ,0,0,0}, {27731,27684,27683 ,16344,15273,16303 ,0,0,0}, - {27683,27730,27731 ,16303,16343,16344 ,0,0,0}, {27732,27685,27684 ,16345,16304,15273 ,0,0,0}, - {27684,27731,27732 ,15273,16344,16345 ,0,0,0}, {27733,27646,27685 ,16346,16271,16304 ,0,0,0}, - {27685,27732,27733 ,16304,16345,16346 ,0,0,0}, {27734,27647,27646 ,15230,15270,16271 ,0,0,0}, - {27646,27733,27734 ,16271,16346,15230 ,0,0,0}, {27735,27686,27647 ,16347,16305,15270 ,0,0,0}, - {27734,27735,27647 ,15230,16347,15270 ,0,0,0}, {27688,27736,27689 ,16307,16348,16308 ,0,0,0}, - {27735,27687,27686 ,16347,16306,16305 ,0,0,0}, {27689,27737,27690 ,16308,16349,16309 ,0,0,0}, - {27687,27736,27688 ,16306,16348,16307 ,0,0,0}, {27690,27738,27691 ,16309,16350,15110 ,0,0,0}, - {27736,27737,27689 ,16348,16349,16308 ,0,0,0}, {27691,27445,27447 ,15110,16078,16080 ,0,0,0}, - {27737,27738,27690 ,16349,16350,16309 ,0,0,0}, {27446,27450,27449 ,16079,16084,16083 ,0,0,0}, - {27738,27445,27691 ,16350,16078,15110 ,0,0,0}, {27446,27692,27447 ,16079,16310,16080 ,0,0,0}, - {27029,26847,27448 ,16351,16311,16082 ,0,0,0}, {27442,27692,27443 ,16075,16310,16076 ,0,0,0}, - {27692,27446,27449 ,16310,16079,16083 ,0,0,0}, {26844,27029,27448 ,16081,16351,16082 ,0,0,0}, - {27355,27527,27350 ,16006,16158,16001 ,0,0,0}, {27693,27358,27353 ,16312,16009,16004 ,0,0,0}, - {27694,27527,27739 ,16313,16158,15217 ,0,0,0}, {27350,27527,27656 ,16001,16158,16280 ,0,0,0}, - {27527,27354,27739 ,16158,16005,15217 ,0,0,0}, {27695,27694,27740 ,16314,16313,16352 ,0,0,0}, - {27694,27739,27740 ,16313,15217,16352 ,0,0,0}, {27696,27695,27741 ,16315,16314,16353 ,0,0,0}, - {27695,27740,27741 ,16314,16352,16353 ,0,0,0}, {27697,27696,27742 ,16316,16315,15188 ,0,0,0}, - {27696,27741,27742 ,16315,16353,15188 ,0,0,0}, {27698,27697,27743 ,16317,16316,16354 ,0,0,0}, - {27697,27742,27743 ,16316,15188,16354 ,0,0,0}, {27699,27698,27744 ,16318,16317,16355 ,0,0,0}, - {27698,27743,27744 ,16317,16354,16355 ,0,0,0}, {27700,27699,27745 ,16319,16318,16356 ,0,0,0}, - {27699,27744,27745 ,16318,16355,16356 ,0,0,0}, {27701,27700,27746 ,16320,16319,16357 ,0,0,0}, - {27700,27745,27746 ,16319,16356,16357 ,0,0,0}, {27702,27701,27747 ,16321,16320,16358 ,0,0,0}, - {27701,27746,27747 ,16320,16357,16358 ,0,0,0}, {27703,27702,27748 ,16322,16321,15175 ,0,0,0}, - {27702,27747,27748 ,16321,16358,15175 ,0,0,0}, {27663,27703,27749 ,16285,16322,16359 ,0,0,0}, - {27703,27748,27749 ,16322,15175,16359 ,0,0,0}, {27707,27663,27704 ,16325,16285,16323 ,0,0,0}, - {27749,27704,27663 ,16359,16323,16285 ,0,0,0}, {27708,27707,27706 ,16326,16325,15168 ,0,0,0}, - {27707,27704,27706 ,16325,16323,15168 ,0,0,0}, {27709,27708,27750 ,16327,16326,16360 ,0,0,0}, - {27708,27706,27750 ,16326,15168,16360 ,0,0,0}, {27710,27709,27751 ,16328,16327,16361 ,0,0,0}, - {27709,27750,27751 ,16327,16360,16361 ,0,0,0}, {27711,27710,27752 ,15249,16328,16362 ,0,0,0}, - {27710,27751,27752 ,16328,16361,16362 ,0,0,0}, {27712,27711,27753 ,16329,15249,16363 ,0,0,0}, - {27711,27752,27753 ,15249,16362,16363 ,0,0,0}, {27669,27712,27754 ,16290,16329,15155 ,0,0,0}, - {27712,27753,27754 ,16329,16363,15155 ,0,0,0}, {27754,27755,27714 ,15155,15153,16331 ,0,0,0}, - {27754,27714,27669 ,15155,16331,16290 ,0,0,0}, {27715,27713,27756 ,16332,16330,16364 ,0,0,0}, - {27713,27714,27756 ,16330,16331,16364 ,0,0,0}, {27716,27715,27757 ,16333,16332,16365 ,0,0,0}, - {27715,27756,27757 ,16332,16364,16365 ,0,0,0}, {27717,27716,27758 ,15244,16333,16366 ,0,0,0}, - {27716,27757,27758 ,16333,16365,16366 ,0,0,0}, {27718,27717,27759 ,16334,15244,16367 ,0,0,0}, - {27717,27758,27759 ,15244,16366,16367 ,0,0,0}, {27674,27718,27760 ,16295,16334,16368 ,0,0,0}, - {27718,27759,27760 ,16334,16367,16368 ,0,0,0}, {27722,27674,27719 ,16336,16295,15135 ,0,0,0}, - {27760,27719,27674 ,16368,15135,16295 ,0,0,0}, {27723,27722,27721 ,16337,16336,16335 ,0,0,0}, - {27722,27719,27721 ,16336,15135,16335 ,0,0,0}, {27724,27723,27761 ,16338,16337,16369 ,0,0,0}, - {27723,27721,27761 ,16337,16335,16369 ,0,0,0}, {27725,27724,27762 ,16339,16338,16370 ,0,0,0}, - {27724,27761,27762 ,16338,16369,16370 ,0,0,0}, {27726,27725,27763 ,16340,16339,16371 ,0,0,0}, - {27725,27762,27763 ,16339,16370,16371 ,0,0,0}, {27679,27726,27764 ,16300,16340,16372 ,0,0,0}, - {27726,27763,27764 ,16340,16371,16372 ,0,0,0}, {27727,27679,27765 ,16341,16300,15070 ,0,0,0}, - {27679,27764,27765 ,16300,16372,15070 ,0,0,0}, {27728,27765,27766 ,16342,15070,15074 ,0,0,0}, - {27765,27728,27727 ,15070,16342,16341 ,0,0,0}, {27730,27729,27767 ,16343,15081,16373 ,0,0,0}, - {27729,27728,27767 ,15081,16342,16373 ,0,0,0}, {27731,27730,27768 ,16344,16343,15078 ,0,0,0}, - {27730,27767,27768 ,16343,16373,15078 ,0,0,0}, {27732,27731,27769 ,16345,16344,16374 ,0,0,0}, - {27731,27768,27769 ,16344,15078,16374 ,0,0,0}, {27733,27732,27770 ,16346,16345,16375 ,0,0,0}, - {27732,27769,27770 ,16345,16374,16375 ,0,0,0}, {27734,27733,27771 ,15230,16346,16376 ,0,0,0}, - {27733,27770,27771 ,16346,16375,16376 ,0,0,0}, {27735,27734,27772 ,16347,15230,16377 ,0,0,0}, - {27734,27771,27772 ,15230,16376,16377 ,0,0,0}, {27687,27735,27773 ,16306,16347,16378 ,0,0,0}, - {27735,27772,27773 ,16347,16377,16378 ,0,0,0}, {27736,27687,27774 ,16348,16306,16379 ,0,0,0}, - {27687,27773,27774 ,16306,16378,16379 ,0,0,0}, {27737,27736,27775 ,16349,16348,16380 ,0,0,0}, - {27736,27774,27775 ,16348,16379,16380 ,0,0,0}, {27738,27737,27776 ,16350,16349,16381 ,0,0,0}, - {27737,27775,27776 ,16349,16380,16381 ,0,0,0}, {27445,27738,27777 ,16078,16350,16382 ,0,0,0}, - {27738,27776,27777 ,16350,16381,16382 ,0,0,0}, {27778,27446,27445 ,16383,16079,16078 ,0,0,0}, - {27777,27778,27445 ,16382,16383,16078 ,0,0,0}, {27692,27449,27448 ,16310,16083,16082 ,0,0,0}, - {27778,27450,27446 ,16383,16084,16079 ,0,0,0}, {26844,27449,27199 ,16081,16083,16085 ,0,0,0}, - {27353,27355,27693 ,16004,16006,16312 ,0,0,0}, {27362,27359,27353 ,16013,16010,16004 ,0,0,0}, - {27359,27779,27354 ,16010,16384,16005 ,0,0,0}, {27354,27779,27739 ,16005,16384,15217 ,0,0,0}, - {27779,27780,27739 ,16384,15219,15217 ,0,0,0}, {27739,27780,27740 ,15217,15219,16352 ,0,0,0}, - {27780,27781,27740 ,15219,15214,16352 ,0,0,0}, {27740,27781,27741 ,16352,15214,16353 ,0,0,0}, - {27781,27782,27741 ,15214,15193,16353 ,0,0,0}, {27741,27782,27742 ,16353,15193,15188 ,0,0,0}, - {27782,27783,27742 ,15193,16385,15188 ,0,0,0}, {27742,27783,27743 ,15188,16385,16354 ,0,0,0}, - {27783,27784,27743 ,16385,16386,16354 ,0,0,0}, {27743,27784,27744 ,16354,16386,16355 ,0,0,0}, - {27784,27785,27744 ,16386,16387,16355 ,0,0,0}, {27744,27785,27745 ,16355,16387,16356 ,0,0,0}, - {27785,27786,27745 ,16387,16388,16356 ,0,0,0}, {27786,27787,27746 ,16388,16389,16357 ,0,0,0}, - {27786,27746,27745 ,16388,16357,16356 ,0,0,0}, {27787,27788,27747 ,16389,16390,16358 ,0,0,0}, - {27787,27747,27746 ,16389,16358,16357 ,0,0,0}, {27788,27789,27748 ,16390,16391,15175 ,0,0,0}, - {27788,27748,27747 ,16390,15175,16358 ,0,0,0}, {27789,27790,27749 ,16391,15172,16359 ,0,0,0}, - {27789,27749,27748 ,16391,16359,15175 ,0,0,0}, {27790,27791,27704 ,15172,16392,16323 ,0,0,0}, - {27790,27704,27749 ,15172,16323,16359 ,0,0,0}, {27705,27704,27791 ,16324,16323,16392 ,0,0,0}, - {27705,27792,27706 ,16324,15167,15168 ,0,0,0}, {27706,27792,27750 ,15168,15167,16360 ,0,0,0}, - {27792,27793,27750 ,15167,15162,16360 ,0,0,0}, {27750,27793,27751 ,16360,15162,16361 ,0,0,0}, - {27793,27794,27751 ,15162,15159,16361 ,0,0,0}, {27794,27795,27752 ,15159,16393,16362 ,0,0,0}, - {27794,27752,27751 ,15159,16362,16361 ,0,0,0}, {27795,27796,27753 ,16393,15156,16363 ,0,0,0}, - {27795,27753,27752 ,16393,16363,16362 ,0,0,0}, {27796,27755,27754 ,15156,15153,15155 ,0,0,0}, - {27796,27754,27753 ,15156,15155,16363 ,0,0,0}, {27755,27797,27714 ,15153,16394,16331 ,0,0,0}, - {27797,27798,27714 ,16394,15152,16331 ,0,0,0}, {27714,27798,27756 ,16331,15152,16364 ,0,0,0}, - {27798,27799,27756 ,15152,15150,16364 ,0,0,0}, {27756,27799,27757 ,16364,15150,16365 ,0,0,0}, - {27799,27800,27757 ,15150,16395,16365 ,0,0,0}, {27800,27801,27758 ,16395,15142,16366 ,0,0,0}, - {27800,27758,27757 ,16395,16366,16365 ,0,0,0}, {27801,27802,27759 ,15142,16396,16367 ,0,0,0}, - {27801,27759,27758 ,15142,16367,16366 ,0,0,0}, {27802,27803,27760 ,16396,15138,16368 ,0,0,0}, - {27802,27760,27759 ,16396,16368,16367 ,0,0,0}, {27803,27804,27719 ,15138,16397,15135 ,0,0,0}, - {27803,27719,27760 ,15138,15135,16368 ,0,0,0}, {27720,27719,27804 ,15136,15135,16397 ,0,0,0}, - {27720,27805,27721 ,15136,16398,16335 ,0,0,0}, {27721,27805,27761 ,16335,16398,16369 ,0,0,0}, - {27805,27806,27761 ,16398,15077,16369 ,0,0,0}, {27806,27807,27762 ,15077,15065,16370 ,0,0,0}, - {27806,27762,27761 ,15077,16370,16369 ,0,0,0}, {27807,27808,27763 ,15065,16399,16371 ,0,0,0}, - {27807,27763,27762 ,15065,16371,16370 ,0,0,0}, {27808,27809,27764 ,16399,16400,16372 ,0,0,0}, - {27808,27764,27763 ,16399,16372,16371 ,0,0,0}, {27809,27766,27765 ,16400,15074,15070 ,0,0,0}, - {27809,27765,27764 ,16400,15070,16372 ,0,0,0}, {27766,27810,27728 ,15074,16401,16342 ,0,0,0}, - {27810,27811,27728 ,16401,16402,16342 ,0,0,0}, {27728,27811,27767 ,16342,16402,16373 ,0,0,0}, - {27811,27812,27767 ,16402,15075,16373 ,0,0,0}, {27767,27812,27768 ,16373,15075,15078 ,0,0,0}, - {27812,27813,27768 ,15075,15079,15078 ,0,0,0}, {27768,27813,27769 ,15078,15079,16374 ,0,0,0}, - {27813,27814,27769 ,15079,15085,16374 ,0,0,0}, {27814,27815,27770 ,15085,16403,16375 ,0,0,0}, - {27814,27770,27769 ,15085,16375,16374 ,0,0,0}, {27815,27816,27771 ,16403,16404,16376 ,0,0,0}, - {27815,27771,27770 ,16403,16376,16375 ,0,0,0}, {27816,27817,27772 ,16404,16405,16377 ,0,0,0}, - {27816,27772,27771 ,16404,16377,16376 ,0,0,0}, {27817,27818,27773 ,16405,15091,16378 ,0,0,0}, - {27817,27773,27772 ,16405,16378,16377 ,0,0,0}, {27818,27819,27774 ,15091,16406,16379 ,0,0,0}, - {27818,27774,27773 ,15091,16379,16378 ,0,0,0}, {27819,27820,27775 ,16406,16407,16380 ,0,0,0}, - {27819,27775,27774 ,16406,16380,16379 ,0,0,0}, {27820,27821,27776 ,16407,16408,16381 ,0,0,0}, - {27820,27776,27775 ,16407,16381,16380 ,0,0,0}, {27821,27822,27777 ,16408,16409,16382 ,0,0,0}, - {27821,27777,27776 ,16408,16382,16381 ,0,0,0}, {27822,27823,27778 ,16409,16410,16383 ,0,0,0}, - {27822,27778,27777 ,16409,16383,16382 ,0,0,0}, {27451,27778,27823 ,16088,16383,16410 ,0,0,0}, - {27778,27451,27450 ,16383,16088,16084 ,0,0,0}, {26852,27450,27451 ,16086,16084,16088 ,0,0,0}, - {27824,27825,27795 ,16411,16412,14033 ,0,0,0}, {27795,27794,27824 ,14033,14034,16411 ,0,0,0}, - {27826,27827,27828 ,16413,16414,16415 ,0,0,0}, {27829,27793,27792 ,16416,16417,14036 ,0,0,0}, - {27794,27793,27830 ,14034,16417,16418 ,0,0,0}, {27829,27830,27793 ,16416,16418,16417 ,0,0,0}, - {27705,27791,27831 ,13993,16419,16420 ,0,0,0}, {27832,27705,27831 ,13992,13993,16420 ,0,0,0}, - {27792,27705,27832 ,14036,13993,13992 ,0,0,0}, {27831,27790,27833 ,16420,16421,13994 ,0,0,0}, - {27792,27832,27829 ,14036,13992,16416 ,0,0,0}, {27831,27791,27790 ,16420,16419,16421 ,0,0,0}, - {27830,27824,27794 ,16418,16411,14034 ,0,0,0}, {27834,27789,27788 ,13995,14039,14040 ,0,0,0}, - {27834,27833,27789 ,13995,13994,14039 ,0,0,0}, {27835,27834,27788 ,16422,13995,14040 ,0,0,0}, - {27836,27837,27838 ,13907,13956,16423 ,0,0,0}, {27839,27835,27787 ,16424,16422,14041 ,0,0,0}, - {27786,27839,27787 ,16425,16424,14041 ,0,0,0}, {27840,27786,27785 ,13998,16425,16426 ,0,0,0}, - {27839,27786,27840 ,16424,16425,13998 ,0,0,0}, {27841,27840,27785 ,16427,13998,16426 ,0,0,0}, - {27787,27835,27788 ,14041,16422,14040 ,0,0,0}, {27833,27790,27789 ,13994,16421,14039 ,0,0,0}, - {27842,27783,27843 ,16428,14045,14001 ,0,0,0}, {27784,27842,27841 ,16429,16428,16427 ,0,0,0}, - {27782,27844,27843 ,16430,16431,14001 ,0,0,0}, {27784,27783,27842 ,16429,14045,16428 ,0,0,0}, - {27844,27781,27845 ,16431,16432,16433 ,0,0,0}, {27781,27844,27782 ,16432,16431,16430 ,0,0,0}, - {27845,27780,27846 ,16433,16434,16435 ,0,0,0}, {27783,27782,27843 ,14045,16430,14001 ,0,0,0}, - {27781,27780,27845 ,16432,16434,16433 ,0,0,0}, {27845,27847,27848 ,16433,16436,16437 ,0,0,0}, - {27479,27849,27483 ,16438,16439,16116 ,0,0,0}, {27850,27851,27852 ,16440,16441,16442 ,0,0,0}, - {27849,27853,27483 ,16439,16443,16116 ,0,0,0}, {27854,27855,27856 ,16444,13641,16445 ,0,0,0}, - {27849,27479,27854 ,16439,16438,16444 ,0,0,0}, {27846,27780,27779 ,16435,16434,16446 ,0,0,0}, - {27848,27857,27858 ,16437,16447,16448 ,0,0,0}, {27859,27860,27858 ,16449,16450,16448 ,0,0,0}, - {27858,27857,27861 ,16448,16447,16451 ,0,0,0}, {27779,27359,27862 ,16446,16452,16453 ,0,0,0}, - {27863,27864,27865 ,16454,16455,16456 ,0,0,0}, {27864,27866,27867 ,16455,16457,16458 ,0,0,0}, - {27866,27868,27867 ,16457,16459,16458 ,0,0,0}, {27869,27865,27870 ,16460,16456,16461 ,0,0,0}, - {27871,27870,27357 ,16462,16461,16008 ,0,0,0}, {27359,27870,27862 ,16452,16461,16453 ,0,0,0}, - {27870,27362,27357 ,16461,16463,16008 ,0,0,0}, {27871,27869,27870 ,16462,16460,16461 ,0,0,0}, - {27851,27872,27873 ,16441,16464,16465 ,0,0,0}, {27784,27841,27785 ,16429,16427,16426 ,0,0,0}, - {27825,27796,27795 ,16412,16466,14033 ,0,0,0}, {27755,27796,27874 ,13947,16466,16467 ,0,0,0}, - {27825,27874,27796 ,16412,16467,16466 ,0,0,0}, {27875,27797,27755 ,16468,16469,13947 ,0,0,0}, - {27755,27874,27875 ,13947,16467,16468 ,0,0,0}, {27798,27875,27876 ,14030,16468,13987 ,0,0,0}, - {27875,27798,27797 ,16468,14030,16469 ,0,0,0}, {27877,27799,27876 ,16470,16471,13987 ,0,0,0}, - {27798,27876,27799 ,14030,13987,16471 ,0,0,0}, {27800,27799,27877 ,14028,16471,16470 ,0,0,0}, - {27877,27878,27800 ,16470,16472,14028 ,0,0,0}, {27800,27878,27801 ,14028,16472,16473 ,0,0,0}, - {27801,27878,27879 ,16473,16472,16474 ,0,0,0}, {27880,27881,27882 ,16475,16476,16477 ,0,0,0}, - {27883,27802,27879 ,16478,14026,16474 ,0,0,0}, {27801,27879,27802 ,16473,16474,14026 ,0,0,0}, - {27883,27884,27803 ,16478,16479,14025 ,0,0,0}, {27803,27802,27883 ,14025,14026,16478 ,0,0,0}, - {27720,27804,27884 ,13982,16480,16479 ,0,0,0}, {27884,27804,27803 ,16479,16480,14025 ,0,0,0}, - {27885,27805,27720 ,13981,14023,13982 ,0,0,0}, {27720,27884,27885 ,13982,16479,13981 ,0,0,0}, - {27805,27886,27806 ,14023,16481,16482 ,0,0,0}, {27886,27805,27885 ,16481,14023,13981 ,0,0,0}, - {27807,27806,27887 ,14021,16482,16483 ,0,0,0}, {27886,27887,27806 ,16481,16483,16482 ,0,0,0}, - {27888,27807,27887 ,16484,14021,16483 ,0,0,0}, {27888,27808,27807 ,16484,14020,14021 ,0,0,0}, - {27888,27889,27808 ,16484,16485,14020 ,0,0,0}, {27890,27891,27892 ,13890,16486,16487 ,0,0,0}, - {27809,27889,27893 ,14019,16485,13933 ,0,0,0}, {27889,27809,27808 ,16485,14019,14020 ,0,0,0}, - {27894,27766,27893 ,16488,16489,13933 ,0,0,0}, {27809,27893,27766 ,14019,13933,16489 ,0,0,0}, - {27810,27894,27811 ,16490,16488,16491 ,0,0,0}, {27810,27766,27894 ,16490,16489,16488 ,0,0,0}, - {27812,27811,27895 ,16492,16491,16493 ,0,0,0}, {27894,27895,27811 ,16488,16493,16491 ,0,0,0}, - {27896,27813,27812 ,16494,16495,16492 ,0,0,0}, {27812,27895,27896 ,16492,16493,16494 ,0,0,0}, - {27813,27897,27814 ,16495,16496,16497 ,0,0,0}, {27897,27813,27896 ,16496,16495,16494 ,0,0,0}, - {27815,27814,27898 ,16498,16497,16499 ,0,0,0}, {27897,27898,27814 ,16496,16499,16497 ,0,0,0}, - {27899,27815,27898 ,16500,16498,16499 ,0,0,0}, {27899,27816,27815 ,16500,16501,16498 ,0,0,0}, - {27899,27900,27816 ,16500,16502,16501 ,0,0,0}, {27901,27902,27903 ,16503,16504,16505 ,0,0,0}, - {27817,27900,27902 ,16506,16502,16504 ,0,0,0}, {27900,27817,27816 ,16502,16506,16501 ,0,0,0}, - {27904,27818,27902 ,16507,16508,16504 ,0,0,0}, {27817,27902,27818 ,16506,16504,16508 ,0,0,0}, - {27905,27906,27907 ,16509,16510,16511 ,0,0,0}, {27819,27818,27904 ,16512,16508,16507 ,0,0,0}, - {27908,27909,27910 ,16513,16514,16515 ,0,0,0}, {27911,27912,27913 ,16516,16517,16518 ,0,0,0}, - {27914,27915,27916 ,16519,16520,16521 ,0,0,0}, {27917,27918,27919 ,16522,16523,16524 ,0,0,0}, - {27920,27921,27908 ,16525,16526,16513 ,0,0,0}, {27922,27923,27924 ,16527,16528,16529 ,0,0,0}, - {27925,27926,27921 ,16530,16531,16526 ,0,0,0}, {27922,27917,27923 ,16527,16522,16528 ,0,0,0}, - {27921,27927,27928 ,16526,16532,16533 ,0,0,0}, {27431,26982,27924 ,16534,726,16529 ,0,0,0}, - {27929,27819,27904 ,16535,16512,16507 ,0,0,0}, {27819,27929,27820 ,16512,16535,14008 ,0,0,0}, - {27820,27905,27821 ,14008,16509,14007 ,0,0,0}, {27901,27904,27902 ,16503,16507,16504 ,0,0,0}, - {27930,27931,27822 ,16536,16537,16538 ,0,0,0}, {27905,27930,27821 ,16509,16536,14007 ,0,0,0}, - {27928,27930,27907 ,16533,16536,16511 ,0,0,0}, {27821,27930,27822 ,14007,16536,16538 ,0,0,0}, - {27931,27932,27451 ,16537,16539,16540 ,0,0,0}, {27931,27451,27823 ,16537,16540,16541 ,0,0,0}, - {26853,27451,27933 ,16087,16540,16542 ,0,0,0}, {27870,27359,27362 ,16461,16452,16463 ,0,0,0}, - {27863,27865,27869 ,16454,16456,16460 ,0,0,0}, {27873,27872,27934 ,16465,16464,16543 ,0,0,0}, - {27862,27846,27779 ,16453,16435,16446 ,0,0,0}, {27862,27865,27935 ,16453,16456,16544 ,0,0,0}, - {27936,27844,27848 ,16545,16431,16437 ,0,0,0}, {27846,27935,27847 ,16435,16544,16436 ,0,0,0}, - {27937,27843,27936 ,16546,14001,16545 ,0,0,0}, {27847,27845,27846 ,16436,16433,16435 ,0,0,0}, - {27938,27842,27937 ,16547,16428,16546 ,0,0,0}, {27848,27844,27845 ,16437,16431,16433 ,0,0,0}, - {27939,27841,27938 ,16548,16427,16547 ,0,0,0}, {27936,27843,27844 ,16545,14001,16431 ,0,0,0}, - {27940,27840,27939 ,13961,13998,16548 ,0,0,0}, {27937,27842,27843 ,16546,16428,14001 ,0,0,0}, - {27941,27839,27940 ,16549,16424,13961 ,0,0,0}, {27938,27841,27842 ,16547,16427,16428 ,0,0,0}, - {27942,27835,27941 ,16550,16422,16549 ,0,0,0}, {27939,27840,27841 ,16548,13998,16427 ,0,0,0}, - {27942,27943,27834 ,16550,16551,13995 ,0,0,0}, {27839,27840,27940 ,16424,13998,13961 ,0,0,0}, - {27944,27833,27943 ,16552,13994,16551 ,0,0,0}, {27835,27839,27941 ,16422,16424,16549 ,0,0,0}, - {27837,27831,27944 ,13956,16420,16552 ,0,0,0}, {27834,27835,27942 ,13995,16422,16550 ,0,0,0}, - {27945,27832,27837 ,16553,13992,13956 ,0,0,0}, {27833,27834,27943 ,13994,13995,16551 ,0,0,0}, - {27946,27829,27945 ,16554,16416,16553 ,0,0,0}, {27831,27833,27944 ,16420,13994,16552 ,0,0,0}, - {27947,27830,27946 ,16555,16418,16554 ,0,0,0}, {27837,27832,27831 ,13956,13992,16420 ,0,0,0}, - {27948,27824,27947 ,16556,16411,16555 ,0,0,0}, {27945,27829,27832 ,16553,16416,13992 ,0,0,0}, - {27948,27949,27825 ,16556,16557,16412 ,0,0,0}, {27830,27829,27946 ,16418,16416,16554 ,0,0,0}, - {27950,27874,27949 ,16558,16467,16557 ,0,0,0}, {27824,27830,27947 ,16411,16418,16555 ,0,0,0}, - {27951,27875,27950 ,16559,16468,16558 ,0,0,0}, {27825,27824,27948 ,16412,16411,16556 ,0,0,0}, - {27952,27876,27951 ,16560,13987,16559 ,0,0,0}, {27874,27825,27949 ,16467,16412,16557 ,0,0,0}, - {27953,27877,27952 ,16561,16470,16560 ,0,0,0}, {27875,27874,27950 ,16468,16467,16558 ,0,0,0}, - {27954,27878,27953 ,13944,16472,16561 ,0,0,0}, {27951,27876,27875 ,16559,13987,16468 ,0,0,0}, - {27954,27955,27879 ,13944,16562,16474 ,0,0,0}, {27877,27876,27952 ,16470,13987,16560 ,0,0,0}, - {27956,27883,27955 ,16563,16478,16562 ,0,0,0}, {27878,27877,27953 ,16472,16470,16561 ,0,0,0}, - {27880,27884,27956 ,16475,16479,16563 ,0,0,0}, {27879,27878,27954 ,16474,16472,13944 ,0,0,0}, - {27957,27885,27880 ,16564,13981,16475 ,0,0,0}, {27883,27879,27955 ,16478,16474,16562 ,0,0,0}, - {27958,27886,27957 ,16565,16481,16564 ,0,0,0}, {27884,27883,27956 ,16479,16478,16563 ,0,0,0}, - {27959,27887,27958 ,13938,16483,16565 ,0,0,0}, {27880,27885,27884 ,16475,13981,16479 ,0,0,0}, - {27960,27888,27959 ,16566,16484,13938 ,0,0,0}, {27957,27886,27885 ,16564,16481,13981 ,0,0,0}, - {27960,27961,27889 ,16566,16567,16485 ,0,0,0}, {27887,27886,27958 ,16483,16481,16565 ,0,0,0}, - {27962,27893,27961 ,16568,13933,16567 ,0,0,0}, {27888,27887,27959 ,16484,16483,13938 ,0,0,0}, - {27963,27894,27962 ,16569,16488,16568 ,0,0,0}, {27889,27888,27960 ,16485,16484,16566 ,0,0,0}, - {27964,27895,27963 ,16570,16493,16569 ,0,0,0}, {27893,27889,27961 ,13933,16485,16567 ,0,0,0}, - {27965,27896,27964 ,16571,16494,16570 ,0,0,0}, {27962,27894,27893 ,16568,16488,13933 ,0,0,0}, - {27966,27897,27965 ,16572,16496,16571 ,0,0,0}, {27963,27895,27894 ,16569,16493,16488 ,0,0,0}, - {27967,27898,27966 ,16573,16499,16572 ,0,0,0}, {27964,27896,27895 ,16570,16494,16493 ,0,0,0}, - {27968,27899,27967 ,16574,16500,16573 ,0,0,0}, {27965,27897,27896 ,16571,16496,16494 ,0,0,0}, - {27968,27903,27900 ,16574,16505,16502 ,0,0,0}, {27898,27897,27966 ,16499,16496,16572 ,0,0,0}, - {27904,27901,27969 ,16507,16503,16575 ,0,0,0}, {27899,27898,27967 ,16500,16499,16573 ,0,0,0}, - {27925,27907,27913 ,16530,16511,16518 ,0,0,0}, {27900,27899,27968 ,16502,16500,16574 ,0,0,0}, - {27929,27969,27906 ,16535,16575,16510 ,0,0,0}, {27900,27903,27902 ,16502,16505,16504 ,0,0,0}, - {27969,27970,27906 ,16575,16576,16510 ,0,0,0}, {27928,27931,27930 ,16533,16537,16536 ,0,0,0}, - {27929,27905,27820 ,16535,16509,14008 ,0,0,0}, {27969,27929,27904 ,16575,16535,16507 ,0,0,0}, - {27928,27925,27921 ,16533,16530,16526 ,0,0,0}, {27905,27929,27906 ,16509,16535,16510 ,0,0,0}, - {27932,27927,27971 ,16539,16532,16577 ,0,0,0}, {27932,27933,27451 ,16539,16542,16540 ,0,0,0}, - {27822,27931,27823 ,16538,16537,16541 ,0,0,0}, {27932,27931,27927 ,16539,16537,16532 ,0,0,0}, - {27972,27933,27932 ,13920,16542,16539 ,0,0,0}, {27870,27865,27862 ,16461,16456,16453 ,0,0,0}, - {27866,27864,27863 ,16457,16455,16454 ,0,0,0}, {27854,27479,27475 ,16444,16438,16578 ,0,0,0}, - {27862,27935,27846 ,16453,16544,16435 ,0,0,0}, {27973,27935,27864 ,16579,16544,16455 ,0,0,0}, - {27858,27860,27936 ,16448,16450,16545 ,0,0,0}, {27857,27847,27973 ,16447,16436,16579 ,0,0,0}, - {27860,27974,27937 ,16450,16580,16546 ,0,0,0}, {27857,27848,27847 ,16447,16437,16436 ,0,0,0}, - {27974,27975,27938 ,16580,16581,16547 ,0,0,0}, {27858,27936,27848 ,16448,16545,16437 ,0,0,0}, - {27975,27976,27939 ,16581,16582,16548 ,0,0,0}, {27860,27937,27936 ,16450,16546,16545 ,0,0,0}, - {27976,27977,27940 ,16582,13870,13961 ,0,0,0}, {27974,27938,27937 ,16580,16547,16546 ,0,0,0}, - {27977,27978,27941 ,13870,16583,16549 ,0,0,0}, {27975,27939,27938 ,16581,16548,16547 ,0,0,0}, - {27978,27979,27942 ,16583,16584,16550 ,0,0,0}, {27976,27940,27939 ,16582,13961,16548 ,0,0,0}, - {27979,27980,27943 ,16584,13909,16551 ,0,0,0}, {27977,27941,27940 ,13870,16549,13961 ,0,0,0}, - {27980,27838,27944 ,13909,16423,16552 ,0,0,0}, {27942,27941,27978 ,16550,16549,16583 ,0,0,0}, - {27981,27982,27983 ,16585,16586,16587 ,0,0,0}, {27943,27942,27979 ,16551,16550,16584 ,0,0,0}, - {27836,27982,27945 ,13907,16586,16553 ,0,0,0}, {27944,27943,27980 ,16552,16551,13909 ,0,0,0}, - {27982,27981,27946 ,16586,16585,16554 ,0,0,0}, {27837,27944,27838 ,13956,16552,16423 ,0,0,0}, - {27981,27984,27947 ,16585,16588,16555 ,0,0,0}, {27836,27945,27837 ,13907,16553,13956 ,0,0,0}, - {27984,27985,27948 ,16588,16589,16556 ,0,0,0}, {27982,27946,27945 ,16586,16554,16553 ,0,0,0}, - {27985,27986,27949 ,16589,16590,16557 ,0,0,0}, {27981,27947,27946 ,16585,16555,16554 ,0,0,0}, - {27986,27987,27950 ,16590,16591,16558 ,0,0,0}, {27948,27947,27984 ,16556,16555,16588 ,0,0,0}, - {27828,27951,27987 ,16415,16559,16591 ,0,0,0}, {27949,27948,27985 ,16557,16556,16589 ,0,0,0}, - {27828,27827,27952 ,16415,16414,16560 ,0,0,0}, {27950,27949,27986 ,16558,16557,16590 ,0,0,0}, - {27827,27988,27953 ,16414,16592,16561 ,0,0,0}, {27987,27951,27950 ,16591,16559,16558 ,0,0,0}, - {27988,27989,27954 ,16592,13855,13944 ,0,0,0}, {27828,27952,27951 ,16415,16560,16559 ,0,0,0}, - {27989,27990,27955 ,13855,16593,16562 ,0,0,0}, {27827,27953,27952 ,16414,16561,16560 ,0,0,0}, - {27990,27881,27956 ,16593,16476,16563 ,0,0,0}, {27954,27953,27988 ,13944,16561,16592 ,0,0,0}, - {27991,27992,27993 ,16594,13809,16595 ,0,0,0}, {27955,27954,27989 ,16562,13944,13855 ,0,0,0}, - {27882,27994,27957 ,16477,16596,16564 ,0,0,0}, {27956,27955,27990 ,16563,16562,16593 ,0,0,0}, - {27994,27995,27958 ,16596,16597,16565 ,0,0,0}, {27880,27956,27881 ,16475,16563,16476 ,0,0,0}, - {27995,27996,27959 ,16597,16598,13938 ,0,0,0}, {27882,27957,27880 ,16477,16564,16475 ,0,0,0}, - {27996,27997,27960 ,16598,16599,16566 ,0,0,0}, {27994,27958,27957 ,16596,16565,16564 ,0,0,0}, - {27997,27998,27961 ,16599,16600,16567 ,0,0,0}, {27995,27959,27958 ,16597,13938,16565 ,0,0,0}, - {27998,27999,27962 ,16600,16601,16568 ,0,0,0}, {27960,27959,27996 ,16566,13938,16598 ,0,0,0}, - {27999,27890,27963 ,16601,13890,16569 ,0,0,0}, {27961,27960,27997 ,16567,16566,16599 ,0,0,0}, - {27890,27892,27964 ,13890,16487,16570 ,0,0,0}, {27962,27961,27998 ,16568,16567,16600 ,0,0,0}, - {27892,28000,27965 ,16487,13887,16571 ,0,0,0}, {27999,27963,27962 ,16601,16569,16568 ,0,0,0}, - {28000,28001,27966 ,13887,16602,16572 ,0,0,0}, {27890,27964,27963 ,13890,16570,16569 ,0,0,0}, - {28001,28002,27967 ,16602,16603,16573 ,0,0,0}, {27892,27965,27964 ,16487,16571,16570 ,0,0,0}, - {28002,28003,27968 ,16603,13886,16574 ,0,0,0}, {28000,27966,27965 ,13887,16572,16571 ,0,0,0}, - {28003,28004,27903 ,13886,16604,16505 ,0,0,0}, {28001,27967,27966 ,16602,16573,16572 ,0,0,0}, - {28004,28005,27901 ,16604,13884,16503 ,0,0,0}, {28002,27968,27967 ,16603,16574,16573 ,0,0,0}, - {28005,27970,27969 ,13884,16576,16575 ,0,0,0}, {28003,27903,27968 ,13886,16505,16574 ,0,0,0}, - {27970,27913,27906 ,16576,16518,16510 ,0,0,0}, {27901,27903,28004 ,16503,16505,16604 ,0,0,0}, - {28006,28007,28008 ,13701,16605,16606 ,0,0,0}, {28005,27969,27901 ,13884,16575,16503 ,0,0,0}, - {27926,27908,27921 ,16531,16513,16526 ,0,0,0}, {27920,28009,27971 ,16525,16607,16577 ,0,0,0}, - {27905,27907,27930 ,16509,16511,16536 ,0,0,0}, {27913,27907,27906 ,16518,16511,16510 ,0,0,0}, - {28010,27971,28009 ,16608,16577,16607 ,0,0,0}, {27971,27972,27932 ,16577,13920,16539 ,0,0,0}, - {27931,27928,27927 ,16537,16533,16532 ,0,0,0}, {27927,27920,27971 ,16532,16525,16577 ,0,0,0}, - {28010,27972,27971 ,16608,13920,16577 ,0,0,0}, {27864,27935,27865 ,16455,16544,16456 ,0,0,0}, - {28011,27867,27868 ,14200,16458,16459 ,0,0,0}, {28011,27872,27867 ,14200,16464,16458 ,0,0,0}, - {27935,27973,27847 ,16544,16579,16436 ,0,0,0}, {28012,27973,27867 ,16609,16579,16458 ,0,0,0}, - {27860,28013,27974 ,16450,16610,16580 ,0,0,0}, {27861,27857,28012 ,16451,16447,16609 ,0,0,0}, - {27974,28014,27975 ,16580,16611,16581 ,0,0,0}, {27861,27859,27858 ,16451,16449,16448 ,0,0,0}, - {28015,28016,28017 ,16612,16613,16614 ,0,0,0}, {27859,28013,27860 ,16449,16610,16450 ,0,0,0}, - {27976,27975,28018 ,16582,16581,16615 ,0,0,0}, {28013,28014,27974 ,16610,16611,16580 ,0,0,0}, - {27977,27976,28017 ,13870,16582,16614 ,0,0,0}, {28014,28018,27975 ,16611,16615,16581 ,0,0,0}, - {27978,27977,28016 ,16583,13870,16613 ,0,0,0}, {28018,28017,27976 ,16615,16614,16582 ,0,0,0}, - {27979,27978,28019 ,16584,16583,16616 ,0,0,0}, {28017,28016,27977 ,16614,16613,13870 ,0,0,0}, - {27980,27979,28020 ,13909,16584,16617 ,0,0,0}, {28016,28019,27978 ,16613,16616,16583 ,0,0,0}, - {27838,27980,28021 ,16423,13909,16618 ,0,0,0}, {28019,28020,27979 ,16616,16617,16584 ,0,0,0}, - {27836,27838,28022 ,13907,16423,16619 ,0,0,0}, {28020,28021,27980 ,16617,16618,13909 ,0,0,0}, - {27982,27836,28023 ,16586,13907,16620 ,0,0,0}, {28022,27838,28021 ,16619,16423,16618 ,0,0,0}, - {28024,28025,28026 ,16621,16622,16623 ,0,0,0}, {28023,27836,28022 ,16620,13907,16619 ,0,0,0}, - {27984,27981,28027 ,16588,16585,16624 ,0,0,0}, {28023,27983,27982 ,16620,16587,16586 ,0,0,0}, - {27985,27984,28026 ,16589,16588,16623 ,0,0,0}, {27983,28027,27981 ,16587,16624,16585 ,0,0,0}, - {27986,27985,28025 ,16590,16589,16622 ,0,0,0}, {28027,28026,27984 ,16624,16623,16588 ,0,0,0}, - {27987,27986,28028 ,16591,16590,16625 ,0,0,0}, {28026,28025,27985 ,16623,16622,16589 ,0,0,0}, - {27828,27987,28029 ,16415,16591,16626 ,0,0,0}, {28028,27986,28025 ,16625,16590,16622 ,0,0,0}, - {28030,28031,28032 ,16627,16628,16629 ,0,0,0}, {28029,27987,28028 ,16626,16591,16625 ,0,0,0}, - {27988,27827,28033 ,16592,16414,16630 ,0,0,0}, {28029,27826,27828 ,16626,16413,16415 ,0,0,0}, - {27989,27988,28032 ,13855,16592,16629 ,0,0,0}, {27826,28033,27827 ,16413,16630,16414 ,0,0,0}, - {27990,27989,28031 ,16593,13855,16628 ,0,0,0}, {28033,28032,27988 ,16630,16629,16592 ,0,0,0}, - {27881,27990,28034 ,16476,16593,16631 ,0,0,0}, {28032,28031,27989 ,16629,16628,13855 ,0,0,0}, - {27882,27881,28035 ,16477,16476,16632 ,0,0,0}, {28031,28034,27990 ,16628,16631,16593 ,0,0,0}, - {27994,27882,28036 ,16596,16477,16633 ,0,0,0}, {28035,27881,28034 ,16632,16476,16631 ,0,0,0}, - {27995,27994,28037 ,16597,16596,16634 ,0,0,0}, {28036,27882,28035 ,16633,16477,16632 ,0,0,0}, - {27996,27995,27991 ,16598,16597,16594 ,0,0,0}, {28036,28037,27994 ,16633,16634,16596 ,0,0,0}, - {27997,27996,27993 ,16599,16598,16595 ,0,0,0}, {28037,27991,27995 ,16634,16594,16597 ,0,0,0}, - {27998,27997,28038 ,16600,16599,16635 ,0,0,0}, {27991,27993,27996 ,16594,16595,16598 ,0,0,0}, - {27999,27998,28039 ,16601,16600,16636 ,0,0,0}, {27993,28038,27997 ,16595,16635,16599 ,0,0,0}, - {27890,27999,28040 ,13890,16601,16637 ,0,0,0}, {28039,27998,28038 ,16636,16600,16635 ,0,0,0}, - {28041,28042,28043 ,16638,16639,16640 ,0,0,0}, {28040,27999,28039 ,16637,16601,16636 ,0,0,0}, - {28000,27892,28044 ,13887,16487,16641 ,0,0,0}, {28040,27891,27890 ,16637,16486,13890 ,0,0,0}, - {28001,28000,28043 ,16602,13887,16640 ,0,0,0}, {27891,28044,27892 ,16486,16641,16487 ,0,0,0}, - {28002,28001,28042 ,16603,16602,16639 ,0,0,0}, {28044,28043,28000 ,16641,16640,13887 ,0,0,0}, - {28003,28002,28045 ,13886,16603,16642 ,0,0,0}, {28043,28042,28001 ,16640,16639,16602 ,0,0,0}, - {28004,28003,28046 ,16604,13886,16643 ,0,0,0}, {28042,28045,28002 ,16639,16642,16603 ,0,0,0}, - {28005,28004,28047 ,13884,16604,16644 ,0,0,0}, {28045,28046,28003 ,16642,16643,13886 ,0,0,0}, - {27970,28005,28048 ,16576,13884,16645 ,0,0,0}, {28046,28047,28004 ,16643,16644,16604 ,0,0,0}, - {27913,27970,27911 ,16518,16576,16516 ,0,0,0}, {28047,28048,28005 ,16644,16645,13884 ,0,0,0}, - {27925,27913,27912 ,16530,16518,16517 ,0,0,0}, {28048,27911,27970 ,16645,16516,16576 ,0,0,0}, - {28049,27919,28008 ,16646,16524,16606 ,0,0,0}, {28050,27909,27908 ,16647,16514,16513 ,0,0,0}, - {27907,27925,27928 ,16511,16530,16533 ,0,0,0}, {27912,27926,27925 ,16517,16531,16530 ,0,0,0}, - {28051,28009,28007 ,16648,16607,16605 ,0,0,0}, {28051,28052,28009 ,16648,16649,16607 ,0,0,0}, - {27927,27921,27920 ,16532,16526,16525 ,0,0,0}, {27920,27910,28009 ,16525,16515,16607 ,0,0,0}, - {28010,28009,28052 ,16608,16607,16649 ,0,0,0}, {27864,27867,27973 ,16455,16458,16579 ,0,0,0}, - {27934,27872,28011 ,16543,16464,14200 ,0,0,0}, {27861,28053,27859 ,16451,16650,16449 ,0,0,0}, - {27973,28012,27857 ,16579,16609,16447 ,0,0,0}, {27872,28054,28012 ,16464,16651,16609 ,0,0,0}, - {28013,27859,28055 ,16610,16449,16652 ,0,0,0}, {28054,28053,27861 ,16651,16650,16451 ,0,0,0}, - {28014,28013,28056 ,16611,16610,16653 ,0,0,0}, {27859,28053,28055 ,16449,16650,16652 ,0,0,0}, - {28018,28014,28057 ,16615,16611,16654 ,0,0,0}, {28013,28055,28056 ,16610,16652,16653 ,0,0,0}, - {28017,28018,28058 ,16614,16615,16655 ,0,0,0}, {28056,28057,28014 ,16653,16654,16611 ,0,0,0}, - {28059,28019,28016 ,13827,16616,16613 ,0,0,0}, {28057,28058,28018 ,16654,16655,16615 ,0,0,0}, - {28060,28061,28062 ,16656,16657,16658 ,0,0,0}, {28058,28015,28017 ,16655,16612,16614 ,0,0,0}, - {28019,28063,28020 ,16616,16659,16617 ,0,0,0}, {28015,28059,28016 ,16612,13827,16613 ,0,0,0}, - {28020,28061,28021 ,16617,16657,16618 ,0,0,0}, {28059,28063,28019 ,13827,16659,16616 ,0,0,0}, - {28021,28060,28022 ,16618,16656,16619 ,0,0,0}, {28063,28061,28020 ,16659,16657,16617 ,0,0,0}, - {28022,28064,28023 ,16619,16660,16620 ,0,0,0}, {28061,28060,28021 ,16657,16656,16618 ,0,0,0}, - {28023,28065,27983 ,16620,13734,16587 ,0,0,0}, {28060,28064,28022 ,16656,16660,16619 ,0,0,0}, - {28027,27983,28066 ,16624,16587,16661 ,0,0,0}, {28064,28065,28023 ,16660,13734,16620 ,0,0,0}, - {28026,28027,28067 ,16623,16624,16662 ,0,0,0}, {28065,28066,27983 ,13734,16661,16587 ,0,0,0}, - {28068,28069,28070 ,16663,16664,16665 ,0,0,0}, {28066,28067,28027 ,16661,16662,16624 ,0,0,0}, - {28025,28071,28028 ,16622,16666,16625 ,0,0,0}, {28067,28024,28026 ,16662,16621,16623 ,0,0,0}, - {28028,28072,28029 ,16625,16667,16626 ,0,0,0}, {28024,28071,28025 ,16621,16666,16622 ,0,0,0}, - {28029,28073,27826 ,16626,16668,16413 ,0,0,0}, {28071,28072,28028 ,16666,16667,16625 ,0,0,0}, - {28033,27826,28074 ,16630,16413,16669 ,0,0,0}, {28072,28073,28029 ,16667,16668,16626 ,0,0,0}, - {28032,28033,28075 ,16629,16630,16670 ,0,0,0}, {28073,28074,27826 ,16668,16669,16413 ,0,0,0}, - {28076,28077,28078 ,16671,16672,16673 ,0,0,0}, {28074,28075,28033 ,16669,16670,16630 ,0,0,0}, - {28031,28079,28034 ,16628,13813,16631 ,0,0,0}, {28075,28030,28032 ,16670,16627,16629 ,0,0,0}, - {28034,28080,28035 ,16631,16674,16632 ,0,0,0}, {28030,28079,28031 ,16627,13813,16628 ,0,0,0}, - {28035,28081,28036 ,16632,16675,16633 ,0,0,0}, {28079,28080,28034 ,13813,16674,16631 ,0,0,0}, - {28036,28082,28037 ,16633,16676,16634 ,0,0,0}, {28080,28081,28035 ,16674,16675,16632 ,0,0,0}, - {27991,28037,28083 ,16594,16634,16677 ,0,0,0}, {28081,28082,28036 ,16675,16676,16633 ,0,0,0}, - {28084,28085,28086 ,16678,16679,16680 ,0,0,0}, {28082,28083,28037 ,16676,16677,16634 ,0,0,0}, - {27993,28087,28038 ,16595,16681,16635 ,0,0,0}, {28083,27992,27991 ,16677,13809,16594 ,0,0,0}, - {28038,28085,28039 ,16635,16679,16636 ,0,0,0}, {27992,28087,27993 ,13809,16681,16595 ,0,0,0}, - {28039,28084,28040 ,16636,16678,16637 ,0,0,0}, {28087,28085,28038 ,16681,16679,16635 ,0,0,0}, - {28040,28088,27891 ,16637,16682,16486 ,0,0,0}, {28085,28084,28039 ,16679,16678,16636 ,0,0,0}, - {28044,27891,28089 ,16641,16486,13760 ,0,0,0}, {28084,28088,28040 ,16678,16682,16637 ,0,0,0}, - {28043,28044,28090 ,16640,16641,16683 ,0,0,0}, {28088,28089,27891 ,16682,13760,16486 ,0,0,0}, - {28091,28045,28042 ,16684,16642,16639 ,0,0,0}, {28089,28090,28044 ,13760,16683,16641 ,0,0,0}, - {28092,28093,28094 ,16685,13799,13756 ,0,0,0}, {28090,28041,28043 ,16683,16638,16640 ,0,0,0}, - {28045,28095,28046 ,16642,16686,16643 ,0,0,0}, {28041,28091,28042 ,16638,16684,16639 ,0,0,0}, - {28046,28093,28047 ,16643,13799,16644 ,0,0,0}, {28091,28095,28045 ,16684,16686,16642 ,0,0,0}, - {28047,28092,28048 ,16644,16685,16645 ,0,0,0}, {28095,28093,28046 ,16686,13799,16643 ,0,0,0}, - {28048,28096,27911 ,16645,13797,16516 ,0,0,0}, {28093,28092,28047 ,13799,16685,16644 ,0,0,0}, - {27911,28097,27912 ,16516,16687,16517 ,0,0,0}, {28092,28096,28048 ,16685,13797,16645 ,0,0,0}, - {27912,28098,27926 ,16517,16688,16531 ,0,0,0}, {28096,28097,27911 ,13797,16687,16516 ,0,0,0}, - {27926,28050,27908 ,16531,16647,16513 ,0,0,0}, {28098,27912,28097 ,16688,16517,16687 ,0,0,0}, - {27915,27909,28099 ,16520,16514,16689 ,0,0,0}, {27926,28098,28050 ,16531,16688,16647 ,0,0,0}, - {28007,28100,28008 ,16605,13793,16606 ,0,0,0}, {28009,27910,28007 ,16607,16515,16605 ,0,0,0}, - {27920,27908,27910 ,16525,16513,16515 ,0,0,0}, {27910,28100,28007 ,16515,13793,16605 ,0,0,0}, - {28051,28007,28006 ,16648,16605,13701 ,0,0,0}, {27867,27872,28012 ,16458,16464,16609 ,0,0,0}, - {27852,27851,27873 ,16442,16441,16465 ,0,0,0}, {28053,28101,28055 ,16650,13654,16652 ,0,0,0}, - {28012,28054,27861 ,16609,16651,16451 ,0,0,0}, {27851,28102,28054 ,16441,16690,16651 ,0,0,0}, - {28056,28055,28103 ,16653,16652,16691 ,0,0,0}, {28053,28102,28101 ,16650,16690,13654 ,0,0,0}, - {28057,28056,28104 ,16654,16653,16692 ,0,0,0}, {28055,28101,28103 ,16652,13654,16691 ,0,0,0}, - {28058,28057,28105 ,16655,16654,16693 ,0,0,0}, {28056,28103,28104 ,16653,16691,16692 ,0,0,0}, - {28015,28058,28106 ,16612,16655,16694 ,0,0,0}, {28057,28104,28105 ,16654,16692,16693 ,0,0,0}, - {28059,28015,28107 ,13827,16612,16695 ,0,0,0}, {28058,28105,28106 ,16655,16693,16694 ,0,0,0}, - {28063,28059,28108 ,16659,13827,13787 ,0,0,0}, {28015,28106,28107 ,16612,16694,16695 ,0,0,0}, - {28061,28063,28109 ,16657,16659,16696 ,0,0,0}, {28107,28108,28059 ,16695,13787,13827 ,0,0,0}, - {28110,28111,28112 ,16697,16698,16699 ,0,0,0}, {28108,28109,28063 ,13787,16696,16659 ,0,0,0}, - {28060,28113,28064 ,16656,16700,16660 ,0,0,0}, {28109,28062,28061 ,16696,16658,16657 ,0,0,0}, - {28064,28112,28065 ,16660,16699,13734 ,0,0,0}, {28062,28113,28060 ,16658,16700,16656 ,0,0,0}, - {28065,28114,28066 ,13734,16701,16661 ,0,0,0}, {28113,28112,28064 ,16700,16699,16660 ,0,0,0}, - {28067,28066,28115 ,16662,16661,16702 ,0,0,0}, {28112,28114,28065 ,16699,16701,13734 ,0,0,0}, - {28024,28067,28116 ,16621,16662,16703 ,0,0,0}, {28066,28114,28115 ,16661,16701,16702 ,0,0,0}, - {28071,28024,28117 ,16666,16621,16704 ,0,0,0}, {28067,28115,28116 ,16662,16702,16703 ,0,0,0}, - {28072,28071,28118 ,16667,16666,16705 ,0,0,0}, {28116,28117,28024 ,16703,16704,16621 ,0,0,0}, - {28072,28119,28073 ,16667,16706,16668 ,0,0,0}, {28117,28118,28071 ,16704,16705,16666 ,0,0,0}, - {28073,28069,28074 ,16668,16664,16669 ,0,0,0}, {28118,28119,28072 ,16705,16706,16667 ,0,0,0}, - {28075,28074,28120 ,16670,16669,16707 ,0,0,0}, {28119,28069,28073 ,16706,16664,16668 ,0,0,0}, - {28030,28075,28121 ,16627,16670,16708 ,0,0,0}, {28074,28069,28120 ,16669,16664,16707 ,0,0,0}, - {28079,28030,28122 ,13813,16627,16709 ,0,0,0}, {28075,28120,28121 ,16670,16707,16708 ,0,0,0}, - {28080,28079,28123 ,16674,13813,16710 ,0,0,0}, {28121,28122,28030 ,16708,16709,16627 ,0,0,0}, - {28080,28124,28081 ,16674,16711,16675 ,0,0,0}, {28122,28123,28079 ,16709,16710,13813 ,0,0,0}, - {28081,28077,28082 ,16675,16672,16676 ,0,0,0}, {28123,28124,28080 ,16710,16711,16674 ,0,0,0}, - {28083,28082,28125 ,16677,16676,16712 ,0,0,0}, {28124,28077,28081 ,16711,16672,16675 ,0,0,0}, - {27992,28083,28126 ,13809,16677,16713 ,0,0,0}, {28082,28077,28125 ,16676,16672,16712 ,0,0,0}, - {28087,27992,28127 ,16681,13809,16714 ,0,0,0}, {28083,28125,28126 ,16677,16712,16713 ,0,0,0}, - {28085,28087,28128 ,16679,16681,16715 ,0,0,0}, {28126,28127,27992 ,16713,16714,13809 ,0,0,0}, - {28129,28130,28131 ,16716,16717,16718 ,0,0,0}, {28127,28128,28087 ,16714,16715,16681 ,0,0,0}, - {28084,28132,28088 ,16678,16719,16682 ,0,0,0}, {28128,28086,28085 ,16715,16680,16679 ,0,0,0}, - {28088,28131,28089 ,16682,16718,13760 ,0,0,0}, {28086,28132,28084 ,16680,16719,16678 ,0,0,0}, - {28090,28089,28133 ,16683,13760,16720 ,0,0,0}, {28132,28131,28088 ,16719,16718,16682 ,0,0,0}, - {28041,28090,28134 ,16638,16683,16721 ,0,0,0}, {28089,28131,28133 ,13760,16718,16720 ,0,0,0}, - {28091,28041,28135 ,16684,16638,16722 ,0,0,0}, {28090,28133,28134 ,16683,16720,16721 ,0,0,0}, - {28095,28091,28136 ,16686,16684,16723 ,0,0,0}, {28041,28134,28135 ,16638,16721,16722 ,0,0,0}, - {28093,28095,28137 ,13799,16686,16724 ,0,0,0}, {28135,28136,28091 ,16722,16723,16684 ,0,0,0}, - {28138,28096,28092 ,13755,13797,16685 ,0,0,0}, {28136,28137,28095 ,16723,16724,16686 ,0,0,0}, - {28139,28140,28141 ,16725,16726,16727 ,0,0,0}, {28137,28094,28093 ,16724,13756,13799 ,0,0,0}, - {28096,28142,28097 ,13797,16728,16687 ,0,0,0}, {28094,28138,28092 ,13756,13755,16685 ,0,0,0}, - {28097,28141,28098 ,16687,16727,16688 ,0,0,0}, {28138,28142,28096 ,13755,16728,13797 ,0,0,0}, - {28098,28143,28050 ,16688,16729,16647 ,0,0,0}, {28142,28141,28097 ,16728,16727,16687 ,0,0,0}, - {28050,28099,27909 ,16647,16689,16514 ,0,0,0}, {28141,28143,28098 ,16727,16729,16688 ,0,0,0}, - {27909,27915,28100 ,16514,16520,13793 ,0,0,0}, {28050,28143,28099 ,16647,16729,16689 ,0,0,0}, - {28144,28008,27919 ,16730,16606,16524 ,0,0,0}, {28145,28006,28008 ,13563,13701,16606 ,0,0,0}, - {27910,27909,28100 ,16515,16514,13793 ,0,0,0}, {28100,28049,28008 ,13793,16646,16606 ,0,0,0}, - {28144,28145,28008 ,16730,13563,16606 ,0,0,0}, {27872,27851,28054 ,16464,16441,16651 ,0,0,0}, - {28146,27850,27852 ,16731,16440,16442 ,0,0,0}, {28103,28101,27856 ,16691,13654,16445 ,0,0,0}, - {28054,28102,28053 ,16651,16690,16650 ,0,0,0}, {27850,28147,28102 ,16440,16732,16690 ,0,0,0}, - {28104,28103,28148 ,16692,16691,16733 ,0,0,0}, {28101,28147,27856 ,13654,16732,16445 ,0,0,0}, - {28149,28148,28150 ,16734,16733,16735 ,0,0,0}, {28103,27856,28148 ,16691,16445,16733 ,0,0,0}, - {28149,28151,28105 ,16734,16736,16693 ,0,0,0}, {28105,28104,28149 ,16693,16692,16734 ,0,0,0}, - {28151,28152,28106 ,16736,16737,16694 ,0,0,0}, {28106,28105,28151 ,16694,16693,16736 ,0,0,0}, - {28152,28153,28107 ,16737,16738,16695 ,0,0,0}, {28107,28106,28152 ,16695,16694,16737 ,0,0,0}, - {28153,28154,28108 ,16738,16739,13787 ,0,0,0}, {28108,28107,28153 ,13787,16695,16738 ,0,0,0}, - {28154,28155,28109 ,16739,16740,16696 ,0,0,0}, {28109,28108,28154 ,16696,13787,16739 ,0,0,0}, - {28155,28156,28062 ,16740,16741,16658 ,0,0,0}, {28062,28109,28155 ,16658,16696,16740 ,0,0,0}, - {28156,28110,28113 ,16741,16697,16700 ,0,0,0}, {28062,28156,28113 ,16658,16741,16700 ,0,0,0}, - {27466,28157,28158 ,16742,16743,13617 ,0,0,0}, {28113,28110,28112 ,16700,16697,16699 ,0,0,0}, - {28114,28159,28115 ,16701,16744,16702 ,0,0,0}, {28112,28111,28114 ,16699,16698,16701 ,0,0,0}, - {28160,28159,28158 ,16745,16744,13617 ,0,0,0}, {28111,28159,28114 ,16698,16744,16701 ,0,0,0}, - {28160,28161,28116 ,16745,16746,16703 ,0,0,0}, {28116,28115,28160 ,16703,16702,16745 ,0,0,0}, - {28161,28162,28117 ,16746,16747,16704 ,0,0,0}, {28117,28116,28161 ,16704,16703,16746 ,0,0,0}, - {28162,28163,28118 ,16747,16748,16705 ,0,0,0}, {28118,28117,28162 ,16705,16704,16747 ,0,0,0}, - {28163,28070,28119 ,16748,16665,16706 ,0,0,0}, {28118,28163,28119 ,16705,16748,16706 ,0,0,0}, - {28164,28165,28166 ,13610,13730,13608 ,0,0,0}, {28119,28070,28069 ,16706,16665,16664 ,0,0,0}, - {28068,28165,28120 ,16663,13730,16707 ,0,0,0}, {28069,28068,28120 ,16664,16663,16707 ,0,0,0}, - {28165,28167,28121 ,13730,16749,16708 ,0,0,0}, {28121,28120,28165 ,16708,16707,13730 ,0,0,0}, - {28167,28168,28122 ,16749,16750,16709 ,0,0,0}, {28122,28121,28167 ,16709,16708,16749 ,0,0,0}, - {28168,28169,28123 ,16750,16751,16710 ,0,0,0}, {28123,28122,28168 ,16710,16709,16750 ,0,0,0}, - {28169,28078,28124 ,16751,16673,16711 ,0,0,0}, {28123,28169,28124 ,16710,16751,16711 ,0,0,0}, - {28170,27457,28171 ,13596,16752,13595 ,0,0,0}, {28124,28078,28077 ,16711,16673,16672 ,0,0,0}, - {28126,28125,28172 ,16713,16712,16753 ,0,0,0}, {28077,28076,28125 ,16672,16671,16712 ,0,0,0}, - {28173,28172,28170 ,16754,16753,13596 ,0,0,0}, {28125,28076,28172 ,16712,16671,16753 ,0,0,0}, - {28173,28174,28127 ,16754,16755,16714 ,0,0,0}, {28127,28126,28173 ,16714,16713,16754 ,0,0,0}, - {28174,28175,28128 ,16755,16756,16715 ,0,0,0}, {28128,28127,28174 ,16715,16714,16755 ,0,0,0}, - {28175,28176,28086 ,16756,16757,16680 ,0,0,0}, {28086,28128,28175 ,16680,16715,16756 ,0,0,0}, - {28176,28129,28132 ,16757,16716,16719 ,0,0,0}, {28086,28176,28132 ,16680,16757,16719 ,0,0,0}, - {28177,28178,28179 ,16758,16759,16760 ,0,0,0}, {28132,28129,28131 ,16719,16716,16718 ,0,0,0}, - {28130,28178,28133 ,16717,16759,16720 ,0,0,0}, {28131,28130,28133 ,16718,16717,16720 ,0,0,0}, - {28178,28180,28134 ,16759,16761,16721 ,0,0,0}, {28134,28133,28178 ,16721,16720,16759 ,0,0,0}, - {28180,28181,28135 ,16761,13717,16722 ,0,0,0}, {28135,28134,28180 ,16722,16721,16761 ,0,0,0}, - {28181,28182,28136 ,13717,16762,16723 ,0,0,0}, {28136,28135,28181 ,16723,16722,13717 ,0,0,0}, - {28182,28183,28137 ,16762,16763,16724 ,0,0,0}, {28137,28136,28182 ,16724,16723,16762 ,0,0,0}, - {28183,28184,28094 ,16763,16764,13756 ,0,0,0}, {28094,28137,28183 ,13756,16724,16763 ,0,0,0}, - {28184,28185,28138 ,16764,16765,13755 ,0,0,0}, {28138,28094,28184 ,13755,13756,16764 ,0,0,0}, - {28185,28139,28142 ,16765,16725,16728 ,0,0,0}, {28138,28185,28142 ,13755,16765,16728 ,0,0,0}, - {28143,28140,28186 ,16729,16726,16766 ,0,0,0}, {28142,28139,28141 ,16728,16725,16727 ,0,0,0}, - {27916,27915,28099 ,16521,16520,16689 ,0,0,0}, {28141,28140,28143 ,16727,16726,16729 ,0,0,0}, - {27914,28049,27915 ,16519,16646,16520 ,0,0,0}, {28143,28186,28099 ,16729,16766,16689 ,0,0,0}, - {28187,27923,27917 ,16767,16528,16522 ,0,0,0}, {28186,27916,28099 ,16766,16521,16689 ,0,0,0}, - {27914,28188,28189 ,16519,16768,16769 ,0,0,0}, {28190,28144,27919 ,16770,16730,16524 ,0,0,0}, - {28100,27915,28049 ,13793,16520,16646 ,0,0,0}, {27919,28049,28189 ,16524,16646,16769 ,0,0,0}, - {27918,28190,27919 ,16523,16770,16524 ,0,0,0}, {27851,27850,28102 ,16441,16440,16690 ,0,0,0}, - {28146,27853,27849 ,16731,16443,16439 ,0,0,0}, {28147,27849,27854 ,16732,16439,16444 ,0,0,0}, - {28102,28147,28101 ,16690,16732,13654 ,0,0,0}, {27856,28147,27854 ,16445,16732,16444 ,0,0,0}, - {27855,28150,28148 ,13641,16735,16733 ,0,0,0}, {28148,27856,27855 ,16733,16445,13641 ,0,0,0}, - {28150,28191,28149 ,16735,16771,16734 ,0,0,0}, {28192,28151,28191 ,16772,16736,16771 ,0,0,0}, - {28104,28148,28149 ,16692,16733,16734 ,0,0,0}, {28151,28149,28191 ,16736,16734,16771 ,0,0,0}, - {28193,28152,28192 ,16773,16737,16772 ,0,0,0}, {28152,28151,28192 ,16737,16736,16772 ,0,0,0}, - {28194,28153,28193 ,16774,16738,16773 ,0,0,0}, {28153,28152,28193 ,16738,16737,16773 ,0,0,0}, - {28195,28154,28194 ,16775,16739,16774 ,0,0,0}, {28154,28153,28194 ,16739,16738,16774 ,0,0,0}, - {28196,28155,28195 ,16776,16740,16775 ,0,0,0}, {28155,28154,28195 ,16740,16739,16775 ,0,0,0}, - {28197,28156,28196 ,13624,16741,16776 ,0,0,0}, {28156,28155,28196 ,16741,16740,16776 ,0,0,0}, - {28198,28110,28197 ,13626,16697,13624 ,0,0,0}, {28110,28156,28197 ,16697,16741,13624 ,0,0,0}, - {28199,28111,28198 ,16777,16698,13626 ,0,0,0}, {28111,28110,28198 ,16698,16697,13626 ,0,0,0}, - {28158,28159,28199 ,13617,16744,16777 ,0,0,0}, {28111,28199,28159 ,16698,16777,16744 ,0,0,0}, - {28158,28157,28160 ,13617,16743,16745 ,0,0,0}, {28200,28161,28157 ,16778,16746,16743 ,0,0,0}, - {28115,28159,28160 ,16702,16744,16745 ,0,0,0}, {28161,28160,28157 ,16746,16745,16743 ,0,0,0}, - {28201,28162,28200 ,16779,16747,16778 ,0,0,0}, {28162,28161,28200 ,16747,16746,16778 ,0,0,0}, - {28202,28163,28201 ,16780,16748,16779 ,0,0,0}, {28163,28162,28201 ,16748,16747,16779 ,0,0,0}, - {28203,28070,28202 ,16781,16665,16780 ,0,0,0}, {28070,28163,28202 ,16665,16748,16780 ,0,0,0}, - {28166,28068,28203 ,13608,16663,16781 ,0,0,0}, {28068,28070,28203 ,16663,16665,16781 ,0,0,0}, - {28166,27381,28164 ,13608,13677,13610 ,0,0,0}, {28068,28166,28165 ,16663,13608,13730 ,0,0,0}, - {28204,28167,28164 ,16782,16749,13610 ,0,0,0}, {28167,28165,28164 ,16749,13730,13610 ,0,0,0}, - {28205,28168,28204 ,16783,16750,16782 ,0,0,0}, {28168,28167,28204 ,16750,16749,16782 ,0,0,0}, - {28206,28169,28205 ,13679,16751,16783 ,0,0,0}, {28169,28168,28205 ,16751,16750,16783 ,0,0,0}, - {28207,28078,28206 ,16784,16673,13679 ,0,0,0}, {28078,28169,28206 ,16673,16751,13679 ,0,0,0}, - {28208,28076,28207 ,16785,16671,16784 ,0,0,0}, {28076,28078,28207 ,16671,16673,16784 ,0,0,0}, - {28170,28172,28208 ,13596,16753,16785 ,0,0,0}, {28076,28208,28172 ,16671,16785,16753 ,0,0,0}, - {28170,28171,28173 ,13596,13595,16754 ,0,0,0}, {28209,28174,28171 ,16786,16755,13595 ,0,0,0}, - {28126,28172,28173 ,16713,16753,16754 ,0,0,0}, {28174,28173,28171 ,16755,16754,13595 ,0,0,0}, - {28210,28175,28209 ,16787,16756,16786 ,0,0,0}, {28175,28174,28209 ,16756,16755,16786 ,0,0,0}, - {28211,28176,28210 ,16788,16757,16787 ,0,0,0}, {28176,28175,28210 ,16757,16756,16787 ,0,0,0}, - {28212,28129,28211 ,16789,16716,16788 ,0,0,0}, {28129,28176,28211 ,16716,16757,16788 ,0,0,0}, - {28179,28130,28212 ,16760,16717,16789 ,0,0,0}, {28130,28129,28212 ,16717,16716,16789 ,0,0,0}, - {28179,27403,28177 ,16760,13686,16758 ,0,0,0}, {28130,28179,28178 ,16717,16760,16759 ,0,0,0}, - {28213,28180,28177 ,16790,16761,16758 ,0,0,0}, {28180,28178,28177 ,16761,16759,16758 ,0,0,0}, - {28214,28181,28213 ,16791,13717,16790 ,0,0,0}, {28181,28180,28213 ,13717,16761,16790 ,0,0,0}, - {28215,28182,28214 ,16792,16762,16791 ,0,0,0}, {28182,28181,28214 ,16762,13717,16791 ,0,0,0}, - {28216,28183,28215 ,16793,16763,16792 ,0,0,0}, {28183,28182,28215 ,16763,16762,16792 ,0,0,0}, - {28217,28184,28216 ,16794,16764,16793 ,0,0,0}, {28184,28183,28216 ,16764,16763,16793 ,0,0,0}, - {28218,28185,28217 ,16795,16765,16794 ,0,0,0}, {28185,28184,28217 ,16765,16764,16794 ,0,0,0}, - {28219,28139,28218 ,16796,16725,16795 ,0,0,0}, {28139,28185,28218 ,16725,16765,16795 ,0,0,0}, - {28220,28140,28219 ,13546,16726,16796 ,0,0,0}, {28140,28139,28219 ,16726,16725,16796 ,0,0,0}, - {28221,28186,28220 ,16797,16766,13546 ,0,0,0}, {28186,28140,28220 ,16766,16726,13546 ,0,0,0}, - {28222,27916,28221 ,13560,16521,16797 ,0,0,0}, {27916,28186,28221 ,16521,16766,16797 ,0,0,0}, - {28222,28188,27914 ,13560,16768,16519 ,0,0,0}, {27914,27916,28222 ,16519,16521,13560 ,0,0,0}, - {28188,28187,28189 ,16768,16767,16769 ,0,0,0}, {27919,28189,27917 ,16524,16769,16522 ,0,0,0}, - {28049,27914,28189 ,16646,16519,16769 ,0,0,0}, {28187,27917,28189 ,16767,16522,16769 ,0,0,0}, - {27918,27917,27922 ,16523,16522,16527 ,0,0,0}, {28147,27850,27849 ,16732,16440,16439 ,0,0,0}, - {27849,27850,28146 ,16439,16440,16731 ,0,0,0}, {27475,27473,27854 ,16578,16798,16444 ,0,0,0}, - {27854,27473,27855 ,16444,16798,13641 ,0,0,0}, {27473,27341,27855 ,16798,13645,13641 ,0,0,0}, - {27855,27341,28150 ,13641,13645,16735 ,0,0,0}, {27341,27340,28150 ,13645,13639,16735 ,0,0,0}, - {28150,27340,28191 ,16735,13639,16771 ,0,0,0}, {27340,27361,28191 ,13639,13634,16771 ,0,0,0}, - {28191,27361,28192 ,16771,13634,16772 ,0,0,0}, {27361,27331,28192 ,13634,16799,16772 ,0,0,0}, - {28192,27331,28193 ,16772,16799,16773 ,0,0,0}, {27331,27366,28193 ,16799,16800,16773 ,0,0,0}, - {28193,27366,28194 ,16773,16800,16774 ,0,0,0}, {27366,27363,28194 ,16800,16801,16774 ,0,0,0}, - {28194,27363,28195 ,16774,16801,16775 ,0,0,0}, {27363,27368,28195 ,16801,16802,16775 ,0,0,0}, - {27368,27370,28196 ,16802,16803,16776 ,0,0,0}, {27368,28196,28195 ,16802,16776,16775 ,0,0,0}, - {27370,27336,28197 ,16803,13625,13624 ,0,0,0}, {27370,28197,28196 ,16803,13624,16776 ,0,0,0}, - {27336,27335,28198 ,13625,16804,13626 ,0,0,0}, {27336,28198,28197 ,13625,13626,13624 ,0,0,0}, - {27335,27372,28199 ,16804,13621,16777 ,0,0,0}, {27335,28199,28198 ,16804,16777,13626 ,0,0,0}, - {27372,27467,28158 ,13621,16805,13617 ,0,0,0}, {27372,28158,28199 ,13621,13617,16777 ,0,0,0}, - {27466,28158,27467 ,16742,13617,16805 ,0,0,0}, {27466,27375,28157 ,16742,16806,16743 ,0,0,0}, - {28157,27375,28200 ,16743,16806,16778 ,0,0,0}, {27375,27380,28200 ,16806,13612,16778 ,0,0,0}, - {28200,27380,28201 ,16778,13612,16779 ,0,0,0}, {27380,27378,28201 ,13612,13613,16779 ,0,0,0}, - {27378,27377,28202 ,13613,13614,16780 ,0,0,0}, {27378,28202,28201 ,13613,16780,16779 ,0,0,0}, - {27377,27465,28203 ,13614,13607,16781 ,0,0,0}, {27377,28203,28202 ,13614,16781,16780 ,0,0,0}, - {27465,27381,28166 ,13607,13677,13608 ,0,0,0}, {27465,28166,28203 ,13607,13608,16781 ,0,0,0}, - {27381,27464,28164 ,13677,16807,13610 ,0,0,0}, {27464,27460,28164 ,16807,13602,13610 ,0,0,0}, - {28164,27460,28204 ,13610,13602,16782 ,0,0,0}, {27460,27385,28204 ,13602,16808,16782 ,0,0,0}, - {28204,27385,28205 ,16782,16808,16783 ,0,0,0}, {27385,27387,28205 ,16808,16809,16783 ,0,0,0}, - {27387,27392,28206 ,16809,16810,13679 ,0,0,0}, {27387,28206,28205 ,16809,13679,16783 ,0,0,0}, - {27392,27390,28207 ,16810,13598,16784 ,0,0,0}, {27392,28207,28206 ,16810,16784,13679 ,0,0,0}, - {27390,27389,28208 ,13598,13680,16785 ,0,0,0}, {27390,28208,28207 ,13598,16785,16784 ,0,0,0}, - {27389,27458,28170 ,13680,16811,13596 ,0,0,0}, {27389,28170,28208 ,13680,13596,16785 ,0,0,0}, - {27457,28170,27458 ,16752,13596,16811 ,0,0,0}, {27457,27394,28171 ,16752,16812,13595 ,0,0,0}, - {28171,27394,28209 ,13595,16812,16786 ,0,0,0}, {27394,27401,28209 ,16812,13590,16786 ,0,0,0}, - {27401,27400,28210 ,13590,13591,16787 ,0,0,0}, {27401,28210,28209 ,13590,16787,16786 ,0,0,0}, - {27400,27399,28211 ,13591,16813,16788 ,0,0,0}, {27400,28211,28210 ,13591,16788,16787 ,0,0,0}, - {27399,27454,28212 ,16813,16814,16789 ,0,0,0}, {27399,28212,28211 ,16813,16789,16788 ,0,0,0}, - {27454,27403,28179 ,16814,13686,16760 ,0,0,0}, {27454,28179,28212 ,16814,16760,16789 ,0,0,0}, - {27403,27402,28177 ,13686,16815,16758 ,0,0,0}, {27402,27408,28177 ,16815,16816,16758 ,0,0,0}, - {28177,27408,28213 ,16758,16816,16790 ,0,0,0}, {27408,27407,28213 ,16816,13549,16790 ,0,0,0}, - {28213,27407,28214 ,16790,13549,16791 ,0,0,0}, {27407,27412,28214 ,13549,13550,16791 ,0,0,0}, - {28214,27412,28215 ,16791,13550,16792 ,0,0,0}, {27412,27410,28215 ,13550,16817,16792 ,0,0,0}, - {27410,27417,28216 ,16817,16818,16793 ,0,0,0}, {27410,28216,28215 ,16817,16793,16792 ,0,0,0}, - {27417,27414,28217 ,16818,16819,16794 ,0,0,0}, {27417,28217,28216 ,16818,16794,16793 ,0,0,0}, - {27414,27421,28218 ,16819,16820,16795 ,0,0,0}, {27414,28218,28217 ,16819,16795,16794 ,0,0,0}, - {27421,27418,28219 ,16820,13545,16796 ,0,0,0}, {27421,28219,28218 ,16820,16796,16795 ,0,0,0}, - {27418,27423,28220 ,13545,16821,13546 ,0,0,0}, {27418,28220,28219 ,13545,13546,16796 ,0,0,0}, - {27423,27422,28221 ,16821,16822,16797 ,0,0,0}, {27423,28221,28220 ,16821,16797,13546 ,0,0,0}, - {27422,27436,28222 ,16822,16823,13560 ,0,0,0}, {27422,28222,28221 ,16822,13560,16797 ,0,0,0}, - {27436,27435,28188 ,16823,16824,16768 ,0,0,0}, {27436,28188,28222 ,16823,16768,13560 ,0,0,0}, - {27435,27429,28187 ,16824,16825,16767 ,0,0,0}, {27435,28187,28188 ,16824,16767,16768 ,0,0,0}, - {27429,27431,27923 ,16825,16534,16528 ,0,0,0}, {27429,27923,28187 ,16825,16528,16767 ,0,0,0}, - {27924,27923,27431 ,16529,16528,16534 ,0,0,0}, {28223,28224,28225 ,16826,16827,16828 ,0,0,0}, - {28226,27300,27299 ,16829,14541,16830 ,0,0,0}, {28226,28227,27300 ,16829,16831,14541 ,0,0,0}, - {28228,27298,28229 ,16832,16833,14499 ,0,0,0}, {27299,28228,28226 ,16830,16832,16829 ,0,0,0}, - {28228,27299,27298 ,16832,16830,16833 ,0,0,0}, {27296,28230,27297 ,16834,16835,16836 ,0,0,0}, - {27211,27297,28230 ,14500,16836,16835 ,0,0,0}, {27211,28230,28229 ,14500,16835,14499 ,0,0,0}, - {27296,27295,28231 ,16834,14546,16837 ,0,0,0}, {27211,28229,27298 ,14500,14499,16833 ,0,0,0}, - {28230,27296,28231 ,16835,16834,16837 ,0,0,0}, {27301,27300,28227 ,14540,14541,16831 ,0,0,0}, - {28232,27294,28233 ,14502,14547,16838 ,0,0,0}, {28232,27295,27294 ,14502,14546,14547 ,0,0,0}, - {28234,28235,28236 ,14462,16839,14414 ,0,0,0}, {28237,28233,27293 ,16840,16838,14548 ,0,0,0}, - {27294,27293,28233 ,14547,14548,16838 ,0,0,0}, {28238,28237,27292 ,16841,16840,16842 ,0,0,0}, - {28238,27291,28239 ,16841,16843,16844 ,0,0,0}, {27292,27291,28238 ,16842,16843,16841 ,0,0,0}, - {28239,27291,27290 ,16844,16843,16845 ,0,0,0}, {27293,27292,28237 ,14548,16842,16840 ,0,0,0}, - {28231,27295,28232 ,16837,14546,14502 ,0,0,0}, {27289,27288,28240 ,14552,16846,16847 ,0,0,0}, - {27289,28241,27290 ,14552,16848,16845 ,0,0,0}, {27287,28242,27288 ,16849,16850,16846 ,0,0,0}, - {27289,28240,28241 ,14552,16847,16848 ,0,0,0}, {27287,27286,28243 ,16849,16851,16852 ,0,0,0}, - {28243,28242,27287 ,16852,16850,16849 ,0,0,0}, {27924,26982,26979 ,16853,15691,16854 ,0,0,0}, - {27288,28242,28240 ,16846,16850,16847 ,0,0,0}, {28243,27286,28244 ,16852,16851,16855 ,0,0,0}, - {28245,27924,26979 ,16856,16853,16854 ,0,0,0}, {28246,28247,28243 ,16857,16858,16852 ,0,0,0}, - {28248,28249,28250 ,16859,16860,16861 ,0,0,0}, {28251,28252,28253 ,16862,16863,14423 ,0,0,0}, - {28254,28255,28144 ,16864,16865,14341 ,0,0,0}, {28254,27918,28256 ,16864,16866,16867 ,0,0,0}, - {28244,27286,27285 ,16855,16851,16868 ,0,0,0}, {28245,26979,28250 ,16856,16854,16861 ,0,0,0}, - {28247,28257,28253 ,16858,16869,14423 ,0,0,0}, {28145,28255,28258 ,14340,16865,16870 ,0,0,0}, - {28259,27972,28260 ,16871,16872,16873 ,0,0,0}, {26848,28261,27285 ,16874,16875,16868 ,0,0,0}, - {28262,28051,28258 ,16876,16877,16870 ,0,0,0}, {28052,28051,28262 ,16878,16877,16876 ,0,0,0}, - {28145,28258,28006 ,14340,16870,14339 ,0,0,0}, {26853,27933,26851 ,15589,16879,16880 ,0,0,0}, - {26848,28259,28261 ,16874,16871,16875 ,0,0,0}, {27972,28259,27933 ,16872,16871,16879 ,0,0,0}, - {28259,26851,27933 ,16871,16880,16879 ,0,0,0}, {28257,28263,28253 ,16869,16881,14423 ,0,0,0}, - {28241,28239,27290 ,16848,16844,16845 ,0,0,0}, {28264,27301,28227 ,16882,14540,16831 ,0,0,0}, - {27302,28264,28265 ,16883,16882,16884 ,0,0,0}, {28264,27302,27301 ,16882,16883,14540 ,0,0,0}, - {28266,27261,28265 ,14452,14453,16884 ,0,0,0}, {27302,28265,27261 ,16883,16884,14453 ,0,0,0}, - {27303,28266,27304 ,16885,14452,14537 ,0,0,0}, {27303,27261,28266 ,16885,14453,14452 ,0,0,0}, - {27305,27304,28267 ,16886,14537,16887 ,0,0,0}, {28266,28267,27304 ,14452,16887,14537 ,0,0,0}, - {28268,27306,27305 ,16888,14535,16886 ,0,0,0}, {27305,28267,28268 ,16886,16887,16888 ,0,0,0}, - {28268,28269,27306 ,16888,16889,14535 ,0,0,0}, {27306,28269,27307 ,14535,16889,16890 ,0,0,0}, - {27307,28269,28270 ,16890,16889,16891 ,0,0,0}, {28271,28272,28273 ,16892,16893,16894 ,0,0,0}, - {28274,27308,28270 ,16895,14533,16891 ,0,0,0}, {27307,28270,27308 ,16890,16891,14533 ,0,0,0}, - {28274,28275,27309 ,16895,16896,14532 ,0,0,0}, {27309,27308,28274 ,14532,14533,16895 ,0,0,0}, - {27226,27310,28275 ,14489,16897,16896 ,0,0,0}, {28275,27310,27309 ,16896,16897,14532 ,0,0,0}, - {28276,27311,27226 ,14488,14530,14489 ,0,0,0}, {27226,28275,28276 ,14489,16896,14488 ,0,0,0}, - {27311,28277,27312 ,14530,16898,16899 ,0,0,0}, {28277,27311,28276 ,16898,14530,14488 ,0,0,0}, - {27313,27312,28278 ,14528,16899,16900 ,0,0,0}, {28277,28278,27312 ,16898,16900,16899 ,0,0,0}, - {28279,27313,28278 ,16901,14528,16900 ,0,0,0}, {28279,27314,27313 ,16901,14527,14528 ,0,0,0}, - {28279,28280,27314 ,16901,16902,14527 ,0,0,0}, {28281,28282,28283 ,14397,16903,16904 ,0,0,0}, - {27315,28280,28284 ,14526,16902,14439 ,0,0,0}, {28280,27315,27314 ,16902,14526,14527 ,0,0,0}, - {28285,27272,28284 ,16905,16906,14439 ,0,0,0}, {27315,28284,27272 ,14526,14439,16906 ,0,0,0}, - {27316,28285,27317 ,16907,16905,14524 ,0,0,0}, {27316,27272,28285 ,16907,16906,16905 ,0,0,0}, - {27318,27317,28286 ,16908,14524,16909 ,0,0,0}, {28285,28286,27317 ,16905,16909,14524 ,0,0,0}, - {28287,27319,27318 ,14482,16910,16908 ,0,0,0}, {27318,28286,28287 ,16908,16909,14482 ,0,0,0}, - {27319,28288,27320 ,16910,16911,16912 ,0,0,0}, {28288,27319,28287 ,16911,16910,14482 ,0,0,0}, - {27321,27320,28289 ,16913,16912,16914 ,0,0,0}, {28288,28289,27320 ,16911,16914,16912 ,0,0,0}, - {28290,27321,28289 ,16915,16913,16914 ,0,0,0}, {28290,27322,27321 ,16915,16916,16913 ,0,0,0}, - {28290,28291,27322 ,16915,16917,16916 ,0,0,0}, {28292,28293,28294 ,16918,16919,16920 ,0,0,0}, - {27323,28291,28293 ,16921,16917,16919 ,0,0,0}, {28291,27323,27322 ,16917,16921,16916 ,0,0,0}, - {28295,27324,28293 ,14476,16922,16919 ,0,0,0}, {27323,28293,27324 ,16921,16919,16922 ,0,0,0}, - {28296,28297,28298 ,16923,16924,16925 ,0,0,0}, {27325,27324,28295 ,14516,16922,14476 ,0,0,0}, - {28299,28300,28301 ,16926,16927,16928 ,0,0,0}, {28302,28303,28304 ,16929,16930,16931 ,0,0,0}, - {28305,28299,28306 ,16932,16926,16933 ,0,0,0}, {28307,28308,28309 ,16934,16935,16936 ,0,0,0}, - {28310,28311,28312 ,16937,16938,16939 ,0,0,0}, {28307,28313,28314 ,16934,16940,16941 ,0,0,0}, - {28315,28316,28317 ,16942,16943,16944 ,0,0,0}, {28314,28313,28318 ,16941,16940,16945 ,0,0,0}, - {27326,27325,28319 ,14515,14516,16946 ,0,0,0}, {26916,28318,28313 ,15634,16945,16940 ,0,0,0}, - {28320,28321,28322 ,16947,14473,16948 ,0,0,0}, {27325,28295,28319 ,14516,14476,16946 ,0,0,0}, - {27326,28304,27327 ,14515,16931,14514 ,0,0,0}, {28292,28295,28293 ,16918,14476,16919 ,0,0,0}, - {27328,27327,28321 ,16949,14514,14473 ,0,0,0}, {28304,28321,27327 ,16931,14473,14514 ,0,0,0}, - {27329,28320,27330 ,16950,16947,16951 ,0,0,0}, {27328,28321,28320 ,16949,14473,16947 ,0,0,0}, - {27330,28323,26950 ,16951,16952,15664 ,0,0,0}, {28320,28323,27330 ,16947,16952,16951 ,0,0,0}, - {26851,28259,26848 ,16880,16871,16874 ,0,0,0}, {28010,28260,27972 ,16953,16873,16872 ,0,0,0}, - {28010,28262,28260 ,16953,16876,16873 ,0,0,0}, {28261,28244,27285 ,16875,16855,16868 ,0,0,0}, - {28261,28260,28324 ,16875,16873,16954 ,0,0,0}, {28325,28242,28247 ,16955,16850,16858 ,0,0,0}, - {28244,28324,28246 ,16855,16954,16857 ,0,0,0}, {28326,28240,28325 ,16956,16847,16955 ,0,0,0}, - {28246,28243,28244 ,16857,16852,16855 ,0,0,0}, {28327,28241,28326 ,16957,16848,16956 ,0,0,0}, - {28247,28242,28243 ,16858,16850,16852 ,0,0,0}, {28328,28239,28327 ,16958,16844,16957 ,0,0,0}, - {28325,28240,28242 ,16955,16847,16850 ,0,0,0}, {28329,28238,28328 ,14467,16841,16958 ,0,0,0}, - {28326,28241,28240 ,16956,16848,16847 ,0,0,0}, {28330,28237,28329 ,16959,16840,14467 ,0,0,0}, - {28327,28239,28241 ,16957,16844,16848 ,0,0,0}, {28331,28233,28330 ,16960,16838,16959 ,0,0,0}, - {28328,28238,28239 ,16958,16841,16844 ,0,0,0}, {28331,28332,28232 ,16960,16961,14502 ,0,0,0}, - {28237,28238,28329 ,16840,16841,14467 ,0,0,0}, {28333,28231,28332 ,16962,16837,16961 ,0,0,0}, - {28233,28237,28330 ,16838,16840,16959 ,0,0,0}, {28234,28230,28333 ,14462,16835,16962 ,0,0,0}, - {28232,28233,28331 ,14502,16838,16960 ,0,0,0}, {28334,28229,28234 ,16963,14499,14462 ,0,0,0}, - {28231,28232,28332 ,16837,14502,16961 ,0,0,0}, {28335,28228,28334 ,16964,16832,16963 ,0,0,0}, - {28230,28231,28333 ,16835,16837,16962 ,0,0,0}, {28336,28226,28335 ,16965,16829,16964 ,0,0,0}, - {28234,28229,28230 ,14462,14499,16835 ,0,0,0}, {28337,28227,28336 ,16966,16831,16965 ,0,0,0}, - {28334,28228,28229 ,16963,16832,14499 ,0,0,0}, {28337,28338,28264 ,16966,16967,16882 ,0,0,0}, - {28226,28228,28335 ,16829,16832,16964 ,0,0,0}, {28339,28265,28338 ,16968,16884,16967 ,0,0,0}, - {28227,28226,28336 ,16831,16829,16965 ,0,0,0}, {28340,28266,28339 ,16969,14452,16968 ,0,0,0}, - {28264,28227,28337 ,16882,16831,16966 ,0,0,0}, {28341,28267,28340 ,16970,16887,16969 ,0,0,0}, - {28265,28264,28338 ,16884,16882,16967 ,0,0,0}, {28342,28268,28341 ,16971,16888,16970 ,0,0,0}, - {28266,28265,28339 ,14452,16884,16968 ,0,0,0}, {28343,28269,28342 ,14450,16889,16971 ,0,0,0}, - {28340,28267,28266 ,16969,16887,14452 ,0,0,0}, {28343,28344,28270 ,14450,16972,16891 ,0,0,0}, - {28268,28267,28341 ,16888,16887,16970 ,0,0,0}, {28345,28274,28344 ,16973,16895,16972 ,0,0,0}, - {28269,28268,28342 ,16889,16888,16971 ,0,0,0}, {28271,28275,28345 ,16892,16896,16973 ,0,0,0}, - {28270,28269,28343 ,16891,16889,14450 ,0,0,0}, {28346,28276,28271 ,16974,14488,16892 ,0,0,0}, - {28274,28270,28344 ,16895,16891,16972 ,0,0,0}, {28347,28277,28346 ,16975,16898,16974 ,0,0,0}, - {28275,28274,28345 ,16896,16895,16973 ,0,0,0}, {28348,28278,28347 ,14444,16900,16975 ,0,0,0}, - {28271,28276,28275 ,16892,14488,16896 ,0,0,0}, {28349,28279,28348 ,16976,16901,14444 ,0,0,0}, - {28346,28277,28276 ,16974,16898,14488 ,0,0,0}, {28349,28350,28280 ,16976,16977,16902 ,0,0,0}, - {28278,28277,28347 ,16900,16898,16975 ,0,0,0}, {28351,28284,28350 ,16978,14439,16977 ,0,0,0}, - {28279,28278,28348 ,16901,16900,14444 ,0,0,0}, {28352,28285,28351 ,16979,16905,16978 ,0,0,0}, - {28280,28279,28349 ,16902,16901,16976 ,0,0,0}, {28353,28286,28352 ,16980,16909,16979 ,0,0,0}, - {28284,28280,28350 ,14439,16902,16977 ,0,0,0}, {28354,28287,28353 ,16981,14482,16980 ,0,0,0}, - {28351,28285,28284 ,16978,16905,14439 ,0,0,0}, {28355,28288,28354 ,16982,16911,16981 ,0,0,0}, - {28352,28286,28285 ,16979,16909,16905 ,0,0,0}, {28356,28289,28355 ,16983,16914,16982 ,0,0,0}, - {28353,28287,28286 ,16980,14482,16909 ,0,0,0}, {28357,28290,28356 ,16984,16915,16983 ,0,0,0}, - {28354,28288,28287 ,16981,16911,14482 ,0,0,0}, {28357,28294,28291 ,16984,16920,16917 ,0,0,0}, - {28289,28288,28355 ,16914,16911,16982 ,0,0,0}, {28295,28292,28358 ,14476,16918,16985 ,0,0,0}, - {28290,28289,28356 ,16915,16914,16983 ,0,0,0}, {28312,28303,28316 ,16939,16930,16943 ,0,0,0}, - {28291,28290,28357 ,16917,16915,16984 ,0,0,0}, {28302,28319,28358 ,16929,16946,16985 ,0,0,0}, - {28293,28291,28294 ,16919,16917,16920 ,0,0,0}, {28302,28358,28359 ,16929,16985,16986 ,0,0,0}, - {28311,28322,28312 ,16938,16948,16939 ,0,0,0}, {28319,28304,27326 ,16946,16931,14515 ,0,0,0}, - {28319,28295,28358 ,16946,14476,16985 ,0,0,0}, {28360,28323,28361 ,16987,16952,16988 ,0,0,0}, - {28319,28302,28304 ,16946,16929,16931 ,0,0,0}, {28322,28321,28303 ,16948,14473,16930 ,0,0,0}, - {28362,28363,28323 ,16989,16990,16952 ,0,0,0}, {27328,28320,27329 ,16949,16947,16950 ,0,0,0}, - {28320,28361,28323 ,16947,16988,16952 ,0,0,0}, {26950,28323,28363 ,15664,16952,16990 ,0,0,0}, - {28259,28260,28261 ,16871,16873,16875 ,0,0,0}, {28052,28262,28010 ,16878,16876,16953 ,0,0,0}, - {28144,28190,28254 ,14341,14342,16864 ,0,0,0}, {28261,28324,28244 ,16875,16954,16855 ,0,0,0}, - {28324,28262,28364 ,16954,16876,16991 ,0,0,0}, {28253,28252,28325 ,14423,16863,16955 ,0,0,0}, - {28257,28246,28364 ,16869,16857,16991 ,0,0,0}, {28252,28365,28326 ,16863,16992,16956 ,0,0,0}, - {28257,28247,28246 ,16869,16858,16857 ,0,0,0}, {28365,28366,28327 ,16992,16993,16957 ,0,0,0}, - {28253,28325,28247 ,14423,16955,16858 ,0,0,0}, {28366,28367,28328 ,16993,16994,16958 ,0,0,0}, - {28252,28326,28325 ,16863,16956,16955 ,0,0,0}, {28367,28368,28329 ,16994,14379,14467 ,0,0,0}, - {28365,28327,28326 ,16992,16957,16956 ,0,0,0}, {28368,28369,28330 ,14379,16995,16959 ,0,0,0}, - {28366,28328,28327 ,16993,16958,16957 ,0,0,0}, {28369,28370,28331 ,16995,16996,16960 ,0,0,0}, - {28367,28329,28328 ,16994,14467,16958 ,0,0,0}, {28370,28371,28332 ,16996,14416,16961 ,0,0,0}, - {28368,28330,28329 ,14379,16959,14467 ,0,0,0}, {28371,28235,28333 ,14416,16839,16962 ,0,0,0}, - {28331,28330,28369 ,16960,16959,16995 ,0,0,0}, {28372,28373,28374 ,16997,16998,16999 ,0,0,0}, - {28332,28331,28370 ,16961,16960,16996 ,0,0,0}, {28236,28373,28334 ,14414,16998,16963 ,0,0,0}, - {28333,28332,28371 ,16962,16961,14416 ,0,0,0}, {28373,28372,28335 ,16998,16997,16964 ,0,0,0}, - {28234,28333,28235 ,14462,16962,16839 ,0,0,0}, {28372,28375,28336 ,16997,17000,16965 ,0,0,0}, - {28236,28334,28234 ,14414,16963,14462 ,0,0,0}, {28375,28376,28337 ,17000,17001,16966 ,0,0,0}, - {28373,28335,28334 ,16998,16964,16963 ,0,0,0}, {28376,28377,28338 ,17001,17002,16967 ,0,0,0}, - {28372,28336,28335 ,16997,16965,16964 ,0,0,0}, {28377,28378,28339 ,17002,17003,16968 ,0,0,0}, - {28337,28336,28375 ,16966,16965,17000 ,0,0,0}, {28224,28340,28378 ,16827,16969,17003 ,0,0,0}, - {28338,28337,28376 ,16967,16966,17001 ,0,0,0}, {28224,28223,28341 ,16827,16826,16970 ,0,0,0}, - {28339,28338,28377 ,16968,16967,17002 ,0,0,0}, {28223,28379,28342 ,16826,17004,16971 ,0,0,0}, - {28378,28340,28339 ,17003,16969,16968 ,0,0,0}, {28379,28380,28343 ,17004,14364,14450 ,0,0,0}, - {28224,28341,28340 ,16827,16970,16969 ,0,0,0}, {28380,28381,28344 ,14364,17005,16972 ,0,0,0}, - {28223,28342,28341 ,16826,16971,16970 ,0,0,0}, {28381,28272,28345 ,17005,16893,16973 ,0,0,0}, - {28343,28342,28379 ,14450,16971,17004 ,0,0,0}, {28382,28383,28384 ,17006,17007,17008 ,0,0,0}, - {28344,28343,28380 ,16972,14450,14364 ,0,0,0}, {28273,28385,28346 ,16894,17009,16974 ,0,0,0}, - {28345,28344,28381 ,16973,16972,17005 ,0,0,0}, {28385,28386,28347 ,17009,17010,16975 ,0,0,0}, - {28271,28345,28272 ,16892,16973,16893 ,0,0,0}, {28386,28387,28348 ,17010,17011,14444 ,0,0,0}, - {28273,28346,28271 ,16894,16974,16892 ,0,0,0}, {28387,28388,28349 ,17011,17012,16976 ,0,0,0}, - {28385,28347,28346 ,17009,16975,16974 ,0,0,0}, {28388,28389,28350 ,17012,17013,16977 ,0,0,0}, - {28386,28348,28347 ,17010,14444,16975 ,0,0,0}, {28389,28390,28351 ,17013,17014,16978 ,0,0,0}, - {28349,28348,28387 ,16976,14444,17011 ,0,0,0}, {28390,28281,28352 ,17014,14397,16979 ,0,0,0}, - {28350,28349,28388 ,16977,16976,17012 ,0,0,0}, {28281,28283,28353 ,14397,16904,16980 ,0,0,0}, - {28351,28350,28389 ,16978,16977,17013 ,0,0,0}, {28283,28391,28354 ,16904,14394,16981 ,0,0,0}, - {28390,28352,28351 ,17014,16979,16978 ,0,0,0}, {28391,28392,28355 ,14394,17015,16982 ,0,0,0}, - {28281,28353,28352 ,14397,16980,16979 ,0,0,0}, {28392,28393,28356 ,17015,17016,16983 ,0,0,0}, - {28283,28354,28353 ,16904,16981,16980 ,0,0,0}, {28393,28394,28357 ,17016,14393,16984 ,0,0,0}, - {28391,28355,28354 ,14394,16982,16981 ,0,0,0}, {28394,28395,28294 ,14393,17017,16920 ,0,0,0}, - {28392,28356,28355 ,17015,16983,16982 ,0,0,0}, {28395,28396,28292 ,17017,17018,16918 ,0,0,0}, - {28393,28357,28356 ,17016,16984,16983 ,0,0,0}, {28396,28359,28358 ,17018,16986,16985 ,0,0,0}, - {28394,28294,28357 ,14393,16920,16984 ,0,0,0}, {28359,28316,28302 ,16986,16943,16929 ,0,0,0}, - {28292,28294,28395 ,16918,16920,17017 ,0,0,0}, {28397,28311,28398 ,17019,16938,17020 ,0,0,0}, - {28292,28396,28358 ,16918,17018,16985 ,0,0,0}, {28322,28311,28361 ,16948,16938,16988 ,0,0,0}, - {28310,28398,28311 ,16937,17020,16938 ,0,0,0}, {28304,28303,28321 ,16931,16930,14473 ,0,0,0}, - {28316,28303,28302 ,16943,16930,16929 ,0,0,0}, {28399,28360,28296 ,17021,16987,16923 ,0,0,0}, - {28360,28362,28323 ,16987,16989,16952 ,0,0,0}, {28320,28322,28361 ,16947,16948,16988 ,0,0,0}, - {28360,28361,28397 ,16987,16988,17019 ,0,0,0}, {28399,28362,28360 ,17021,16989,16987 ,0,0,0}, - {28260,28262,28324 ,16873,16876,16954 ,0,0,0}, {28006,28258,28051 ,14339,16870,16877 ,0,0,0}, - {26977,28250,26979 ,17022,16861,16854 ,0,0,0}, {28324,28364,28246 ,16954,16991,16857 ,0,0,0}, - {28364,28258,28400 ,16991,16870,17023 ,0,0,0}, {28252,28401,28365 ,16863,17024,16992 ,0,0,0}, - {28263,28257,28400 ,16881,16869,17023 ,0,0,0}, {28365,28402,28366 ,16992,17025,16993 ,0,0,0}, - {28263,28251,28253 ,16881,16862,14423 ,0,0,0}, {28403,28404,28405 ,17026,17027,17028 ,0,0,0}, - {28251,28401,28252 ,16862,17024,16863 ,0,0,0}, {28367,28366,28406 ,16994,16993,17029 ,0,0,0}, - {28401,28402,28365 ,17024,17025,16992 ,0,0,0}, {28368,28367,28405 ,14379,16994,17028 ,0,0,0}, - {28402,28406,28366 ,17025,17029,16993 ,0,0,0}, {28369,28368,28404 ,16995,14379,17027 ,0,0,0}, - {28406,28405,28367 ,17029,17028,16994 ,0,0,0}, {28370,28369,28407 ,16996,16995,17030 ,0,0,0}, - {28405,28404,28368 ,17028,17027,14379 ,0,0,0}, {28371,28370,28408 ,14416,16996,17031 ,0,0,0}, - {28404,28407,28369 ,17027,17030,16995 ,0,0,0}, {28235,28371,28409 ,16839,14416,17032 ,0,0,0}, - {28407,28408,28370 ,17030,17031,16996 ,0,0,0}, {28236,28235,28410 ,14414,16839,17033 ,0,0,0}, - {28408,28409,28371 ,17031,17032,14416 ,0,0,0}, {28373,28236,28411 ,16998,14414,17034 ,0,0,0}, - {28410,28235,28409 ,17033,16839,17032 ,0,0,0}, {28412,28413,28414 ,17035,17036,17037 ,0,0,0}, - {28411,28236,28410 ,17034,14414,17033 ,0,0,0}, {28375,28372,28415 ,17000,16997,17038 ,0,0,0}, - {28411,28374,28373 ,17034,16999,16998 ,0,0,0}, {28376,28375,28414 ,17001,17000,17037 ,0,0,0}, - {28374,28415,28372 ,16999,17038,16997 ,0,0,0}, {28377,28376,28413 ,17002,17001,17036 ,0,0,0}, - {28415,28414,28375 ,17038,17037,17000 ,0,0,0}, {28378,28377,28416 ,17003,17002,17039 ,0,0,0}, - {28414,28413,28376 ,17037,17036,17001 ,0,0,0}, {28224,28378,28417 ,16827,17003,17040 ,0,0,0}, - {28416,28377,28413 ,17039,17002,17036 ,0,0,0}, {28418,28419,28420 ,17041,17042,17043 ,0,0,0}, - {28417,28378,28416 ,17040,17003,17039 ,0,0,0}, {28379,28223,28421 ,17004,16826,17044 ,0,0,0}, - {28417,28225,28224 ,17040,16828,16827 ,0,0,0}, {28380,28379,28420 ,14364,17004,17043 ,0,0,0}, - {28225,28421,28223 ,16828,17044,16826 ,0,0,0}, {28381,28380,28419 ,17005,14364,17042 ,0,0,0}, - {28421,28420,28379 ,17044,17043,17004 ,0,0,0}, {28272,28381,28422 ,16893,17005,17045 ,0,0,0}, - {28420,28419,28380 ,17043,17042,14364 ,0,0,0}, {28273,28272,28423 ,16894,16893,17046 ,0,0,0}, - {28419,28422,28381 ,17042,17045,17005 ,0,0,0}, {28385,28273,28424 ,17009,16894,17047 ,0,0,0}, - {28423,28272,28422 ,17046,16893,17045 ,0,0,0}, {28386,28385,28425 ,17010,17009,17048 ,0,0,0}, - {28424,28273,28423 ,17047,16894,17046 ,0,0,0}, {28387,28386,28382 ,17011,17010,17006 ,0,0,0}, - {28424,28425,28385 ,17047,17048,17009 ,0,0,0}, {28388,28387,28384 ,17012,17011,17008 ,0,0,0}, - {28425,28382,28386 ,17048,17006,17010 ,0,0,0}, {28389,28388,28426 ,17013,17012,17049 ,0,0,0}, - {28382,28384,28387 ,17006,17008,17011 ,0,0,0}, {28390,28389,28427 ,17014,17013,17050 ,0,0,0}, - {28384,28426,28388 ,17008,17049,17012 ,0,0,0}, {28281,28390,28428 ,14397,17014,17051 ,0,0,0}, - {28427,28389,28426 ,17050,17013,17049 ,0,0,0}, {28429,28430,28431 ,17052,17053,17054 ,0,0,0}, - {28428,28390,28427 ,17051,17014,17050 ,0,0,0}, {28391,28283,28432 ,14394,16904,17055 ,0,0,0}, - {28428,28282,28281 ,17051,16903,14397 ,0,0,0}, {28392,28391,28431 ,17015,14394,17054 ,0,0,0}, - {28282,28432,28283 ,16903,17055,16904 ,0,0,0}, {28393,28392,28430 ,17016,17015,17053 ,0,0,0}, - {28432,28431,28391 ,17055,17054,14394 ,0,0,0}, {28394,28393,28433 ,14393,17016,17056 ,0,0,0}, - {28431,28430,28392 ,17054,17053,17015 ,0,0,0}, {28395,28394,28434 ,17017,14393,17057 ,0,0,0}, - {28430,28433,28393 ,17053,17056,17016 ,0,0,0}, {28396,28395,28435 ,17018,17017,17058 ,0,0,0}, - {28433,28434,28394 ,17056,17057,14393 ,0,0,0}, {28359,28396,28436 ,16986,17018,17059 ,0,0,0}, - {28434,28435,28395 ,17057,17058,17017 ,0,0,0}, {28316,28359,28317 ,16943,16986,16944 ,0,0,0}, - {28435,28436,28396 ,17058,17059,17018 ,0,0,0}, {28312,28316,28315 ,16939,16943,16942 ,0,0,0}, - {28436,28317,28359 ,17059,16944,16986 ,0,0,0}, {28297,28398,28300 ,16924,17020,16927 ,0,0,0}, - {28398,28437,28300 ,17020,17060,16927 ,0,0,0}, {28303,28312,28322 ,16930,16939,16948 ,0,0,0}, - {28315,28310,28312 ,16942,16937,16939 ,0,0,0}, {28438,28296,28298 ,17061,16923,16925 ,0,0,0}, - {28360,28397,28296 ,16987,17019,16923 ,0,0,0}, {28361,28311,28397 ,16988,16938,17019 ,0,0,0}, - {28397,28297,28296 ,17019,16924,16923 ,0,0,0}, {28399,28296,28438 ,17021,16923,17061 ,0,0,0}, - {28258,28364,28262 ,16870,16991,16876 ,0,0,0}, {28144,28255,28145 ,14341,16865,14340 ,0,0,0}, - {28263,28439,28251 ,16881,17062,16862 ,0,0,0}, {28364,28400,28257 ,16991,17023,16869 ,0,0,0}, - {28255,28440,28400 ,16865,17063,17023 ,0,0,0}, {28401,28251,28441 ,17024,16862,17064 ,0,0,0}, - {28440,28439,28263 ,17063,17062,16881 ,0,0,0}, {28402,28401,28442 ,17025,17024,17065 ,0,0,0}, - {28251,28439,28441 ,16862,17062,17064 ,0,0,0}, {28406,28402,28443 ,17029,17025,17066 ,0,0,0}, - {28401,28441,28442 ,17024,17064,17065 ,0,0,0}, {28405,28406,28444 ,17028,17029,17067 ,0,0,0}, - {28442,28443,28402 ,17065,17066,17025 ,0,0,0}, {28445,28407,28404 ,14333,17030,17027 ,0,0,0}, - {28443,28444,28406 ,17066,17067,17029 ,0,0,0}, {28446,28447,28448 ,17068,17069,17070 ,0,0,0}, - {28444,28403,28405 ,17067,17026,17028 ,0,0,0}, {28407,28449,28408 ,17030,17071,17031 ,0,0,0}, - {28403,28445,28404 ,17026,14333,17027 ,0,0,0}, {28408,28447,28409 ,17031,17069,17032 ,0,0,0}, - {28445,28449,28407 ,14333,17071,17030 ,0,0,0}, {28409,28446,28410 ,17032,17068,17033 ,0,0,0}, - {28449,28447,28408 ,17071,17069,17031 ,0,0,0}, {28410,28450,28411 ,17033,17072,17034 ,0,0,0}, - {28447,28446,28409 ,17069,17068,17032 ,0,0,0}, {28411,28451,28374 ,17034,14238,16999 ,0,0,0}, - {28446,28450,28410 ,17068,17072,17033 ,0,0,0}, {28415,28374,28452 ,17038,16999,17073 ,0,0,0}, - {28450,28451,28411 ,17072,14238,17034 ,0,0,0}, {28414,28415,28453 ,17037,17038,17074 ,0,0,0}, - {28451,28452,28374 ,14238,17073,16999 ,0,0,0}, {28454,28455,28456 ,17075,17076,17077 ,0,0,0}, - {28452,28453,28415 ,17073,17074,17038 ,0,0,0}, {28413,28457,28416 ,17036,17078,17039 ,0,0,0}, - {28453,28412,28414 ,17074,17035,17037 ,0,0,0}, {28416,28458,28417 ,17039,17079,17040 ,0,0,0}, - {28412,28457,28413 ,17035,17078,17036 ,0,0,0}, {28417,28459,28225 ,17040,17080,16828 ,0,0,0}, - {28457,28458,28416 ,17078,17079,17039 ,0,0,0}, {28421,28225,28460 ,17044,16828,17081 ,0,0,0}, - {28458,28459,28417 ,17079,17080,17040 ,0,0,0}, {28420,28421,28461 ,17043,17044,17082 ,0,0,0}, - {28459,28460,28225 ,17080,17081,16828 ,0,0,0}, {28462,28463,28464 ,17083,17084,17085 ,0,0,0}, - {28460,28461,28421 ,17081,17082,17044 ,0,0,0}, {28419,28465,28422 ,17042,14319,17045 ,0,0,0}, - {28461,28418,28420 ,17082,17041,17043 ,0,0,0}, {28422,28466,28423 ,17045,17086,17046 ,0,0,0}, - {28418,28465,28419 ,17041,14319,17042 ,0,0,0}, {28423,28467,28424 ,17046,17087,17047 ,0,0,0}, - {28465,28466,28422 ,14319,17086,17045 ,0,0,0}, {28424,28468,28425 ,17047,17088,17048 ,0,0,0}, - {28466,28467,28423 ,17086,17087,17046 ,0,0,0}, {28382,28425,28469 ,17006,17048,17089 ,0,0,0}, - {28467,28468,28424 ,17087,17088,17047 ,0,0,0}, {28470,28471,28472 ,17090,17091,17092 ,0,0,0}, - {28468,28469,28425 ,17088,17089,17048 ,0,0,0}, {28384,28473,28426 ,17008,17093,17049 ,0,0,0}, - {28469,28383,28382 ,17089,17007,17006 ,0,0,0}, {28426,28471,28427 ,17049,17091,17050 ,0,0,0}, - {28383,28473,28384 ,17007,17093,17008 ,0,0,0}, {28427,28470,28428 ,17050,17090,17051 ,0,0,0}, - {28473,28471,28426 ,17093,17091,17049 ,0,0,0}, {28428,28474,28282 ,17051,17094,16903 ,0,0,0}, - {28471,28470,28427 ,17091,17090,17050 ,0,0,0}, {28432,28282,28475 ,17055,16903,14264 ,0,0,0}, - {28470,28474,28428 ,17090,17094,17051 ,0,0,0}, {28431,28432,28476 ,17054,17055,17095 ,0,0,0}, - {28474,28475,28282 ,17094,14264,16903 ,0,0,0}, {28477,28433,28430 ,17096,17056,17053 ,0,0,0}, - {28475,28476,28432 ,14264,17095,17055 ,0,0,0}, {28478,28479,28480 ,17097,14305,14260 ,0,0,0}, - {28476,28429,28431 ,17095,17052,17054 ,0,0,0}, {28433,28481,28434 ,17056,17098,17057 ,0,0,0}, - {28429,28477,28430 ,17052,17096,17053 ,0,0,0}, {28434,28479,28435 ,17057,14305,17058 ,0,0,0}, - {28477,28481,28433 ,17096,17098,17056 ,0,0,0}, {28435,28478,28436 ,17058,17097,17059 ,0,0,0}, - {28481,28479,28434 ,17098,14305,17057 ,0,0,0}, {28436,28482,28317 ,17059,17099,16944 ,0,0,0}, - {28479,28478,28435 ,14305,17097,17058 ,0,0,0}, {28317,28483,28315 ,16944,17100,16942 ,0,0,0}, - {28478,28482,28436 ,17097,17099,17059 ,0,0,0}, {28315,28484,28310 ,16942,17101,16937 ,0,0,0}, - {28482,28483,28317 ,17099,17100,16944 ,0,0,0}, {28310,28437,28398 ,16937,17060,17020 ,0,0,0}, - {28484,28315,28483 ,17101,16942,17100 ,0,0,0}, {28485,28486,28298 ,17102,17103,16925 ,0,0,0}, - {28310,28484,28437 ,16937,17101,17060 ,0,0,0}, {28487,28298,28486 ,17104,16925,17103 ,0,0,0}, - {28488,28438,28298 ,17105,17061,16925 ,0,0,0}, {28397,28398,28297 ,17019,17020,16924 ,0,0,0}, - {28297,28485,28298 ,16924,17102,16925 ,0,0,0}, {28487,28488,28298 ,17104,17105,16925 ,0,0,0}, - {28255,28400,28258 ,16865,17023,16870 ,0,0,0}, {27918,28254,28190 ,16866,16864,14342 ,0,0,0}, - {28439,28489,28441 ,17062,14147,17064 ,0,0,0}, {28400,28440,28263 ,17023,17063,16881 ,0,0,0}, - {28254,28490,28440 ,16864,17106,17063 ,0,0,0}, {28442,28441,28491 ,17065,17064,17107 ,0,0,0}, - {28439,28490,28489 ,17062,17106,14147 ,0,0,0}, {28443,28442,28492 ,17066,17065,17108 ,0,0,0}, - {28441,28489,28491 ,17064,14147,17107 ,0,0,0}, {28444,28443,28493 ,17067,17066,17109 ,0,0,0}, - {28442,28491,28492 ,17065,17107,17108 ,0,0,0}, {28403,28444,28494 ,17026,17067,17110 ,0,0,0}, - {28443,28492,28493 ,17066,17108,17109 ,0,0,0}, {28445,28403,28495 ,14333,17026,17111 ,0,0,0}, - {28444,28493,28494 ,17067,17109,17110 ,0,0,0}, {28449,28445,28496 ,17071,14333,14291 ,0,0,0}, - {28403,28494,28495 ,17026,17110,17111 ,0,0,0}, {28447,28449,28497 ,17069,17071,17112 ,0,0,0}, - {28495,28496,28445 ,17111,14291,14333 ,0,0,0}, {28498,28499,28500 ,17113,17114,17115 ,0,0,0}, - {28496,28497,28449 ,14291,17112,17071 ,0,0,0}, {28446,28501,28450 ,17068,17116,17072 ,0,0,0}, - {28497,28448,28447 ,17112,17070,17069 ,0,0,0}, {28450,28500,28451 ,17072,17115,14238 ,0,0,0}, - {28448,28501,28446 ,17070,17116,17068 ,0,0,0}, {28451,28502,28452 ,14238,17117,17073 ,0,0,0}, - {28501,28500,28450 ,17116,17115,17072 ,0,0,0}, {28453,28452,28503 ,17074,17073,17118 ,0,0,0}, - {28500,28502,28451 ,17115,17117,14238 ,0,0,0}, {28412,28453,28504 ,17035,17074,17119 ,0,0,0}, - {28452,28502,28503 ,17073,17117,17118 ,0,0,0}, {28457,28412,28505 ,17078,17035,17120 ,0,0,0}, - {28453,28503,28504 ,17074,17118,17119 ,0,0,0}, {28458,28457,28506 ,17079,17078,17121 ,0,0,0}, - {28504,28505,28412 ,17119,17120,17035 ,0,0,0}, {28458,28507,28459 ,17079,17122,17080 ,0,0,0}, - {28505,28506,28457 ,17120,17121,17078 ,0,0,0}, {28459,28455,28460 ,17080,17076,17081 ,0,0,0}, - {28506,28507,28458 ,17121,17122,17079 ,0,0,0}, {28461,28460,28508 ,17082,17081,17123 ,0,0,0}, - {28507,28455,28459 ,17122,17076,17080 ,0,0,0}, {28418,28461,28509 ,17041,17082,17124 ,0,0,0}, - {28460,28455,28508 ,17081,17076,17123 ,0,0,0}, {28465,28418,28510 ,14319,17041,17125 ,0,0,0}, - {28461,28508,28509 ,17082,17123,17124 ,0,0,0}, {28466,28465,28511 ,17086,14319,17126 ,0,0,0}, - {28509,28510,28418 ,17124,17125,17041 ,0,0,0}, {28466,28512,28467 ,17086,17127,17087 ,0,0,0}, - {28510,28511,28465 ,17125,17126,14319 ,0,0,0}, {28467,28463,28468 ,17087,17084,17088 ,0,0,0}, - {28511,28512,28466 ,17126,17127,17086 ,0,0,0}, {28469,28468,28513 ,17089,17088,17128 ,0,0,0}, - {28512,28463,28467 ,17127,17084,17087 ,0,0,0}, {28383,28469,28514 ,17007,17089,17129 ,0,0,0}, - {28468,28463,28513 ,17088,17084,17128 ,0,0,0}, {28473,28383,28515 ,17093,17007,17130 ,0,0,0}, - {28469,28513,28514 ,17089,17128,17129 ,0,0,0}, {28471,28473,28516 ,17091,17093,17131 ,0,0,0}, - {28514,28515,28383 ,17129,17130,17007 ,0,0,0}, {28517,28518,28519 ,17132,17133,17134 ,0,0,0}, - {28515,28516,28473 ,17130,17131,17093 ,0,0,0}, {28470,28520,28474 ,17090,17135,17094 ,0,0,0}, - {28516,28472,28471 ,17131,17092,17091 ,0,0,0}, {28474,28519,28475 ,17094,17134,14264 ,0,0,0}, - {28472,28520,28470 ,17092,17135,17090 ,0,0,0}, {28476,28475,28521 ,17095,14264,17136 ,0,0,0}, - {28520,28519,28474 ,17135,17134,17094 ,0,0,0}, {28429,28476,28522 ,17052,17095,17137 ,0,0,0}, - {28475,28519,28521 ,14264,17134,17136 ,0,0,0}, {28477,28429,28523 ,17096,17052,17138 ,0,0,0}, - {28476,28521,28522 ,17095,17136,17137 ,0,0,0}, {28481,28477,28524 ,17098,17096,17139 ,0,0,0}, - {28429,28522,28523 ,17052,17137,17138 ,0,0,0}, {28479,28481,28525 ,14305,17098,17140 ,0,0,0}, - {28523,28524,28477 ,17138,17139,17096 ,0,0,0}, {28526,28482,28478 ,17141,17099,17097 ,0,0,0}, - {28524,28525,28481 ,17139,17140,17098 ,0,0,0}, {28527,28528,28529 ,17142,17143,17144 ,0,0,0}, - {28525,28480,28479 ,17140,14260,14305 ,0,0,0}, {28482,28530,28483 ,17099,17145,17100 ,0,0,0}, - {28480,28526,28478 ,14260,17141,17097 ,0,0,0}, {28483,28529,28484 ,17100,17144,17101 ,0,0,0}, - {28526,28530,28482 ,17141,17145,17099 ,0,0,0}, {28484,28531,28437 ,17101,17146,17060 ,0,0,0}, - {28530,28529,28483 ,17145,17144,17100 ,0,0,0}, {28437,28301,28300 ,17060,16928,16927 ,0,0,0}, - {28529,28531,28484 ,17144,17146,17101 ,0,0,0}, {28300,28299,28485 ,16927,16926,17102 ,0,0,0}, - {28301,28437,28531 ,16928,17060,17146 ,0,0,0}, {28486,28532,28309 ,17103,17147,16936 ,0,0,0}, - {28533,28534,28486 ,17148,17149,17103 ,0,0,0}, {28297,28300,28485 ,16924,16927,17102 ,0,0,0}, - {28485,28532,28486 ,17102,17147,17103 ,0,0,0}, {28487,28486,28534 ,17104,17103,17149 ,0,0,0}, - {28255,28254,28440 ,16865,16864,17063 ,0,0,0}, {27922,28256,27918 ,17150,16867,16866 ,0,0,0}, - {28491,28489,28249 ,17107,14147,16860 ,0,0,0}, {28440,28490,28439 ,17063,17106,17062 ,0,0,0}, - {28256,28535,28490 ,16867,17151,17106 ,0,0,0}, {28492,28491,28536 ,17108,17107,17152 ,0,0,0}, - {28489,28535,28249 ,14147,17151,16860 ,0,0,0}, {28537,28536,28538 ,17153,17152,17154 ,0,0,0}, - {28491,28249,28536 ,17107,16860,17152 ,0,0,0}, {28537,28539,28493 ,17153,17155,17109 ,0,0,0}, - {28493,28492,28537 ,17109,17108,17153 ,0,0,0}, {28539,28540,28494 ,17155,17156,17110 ,0,0,0}, - {28494,28493,28539 ,17110,17109,17155 ,0,0,0}, {28540,28541,28495 ,17156,17157,17111 ,0,0,0}, - {28495,28494,28540 ,17111,17110,17156 ,0,0,0}, {28541,28542,28496 ,17157,17158,14291 ,0,0,0}, - {28496,28495,28541 ,14291,17111,17157 ,0,0,0}, {28542,28543,28497 ,17158,17159,17112 ,0,0,0}, - {28497,28496,28542 ,17112,14291,17158 ,0,0,0}, {28543,28544,28448 ,17159,17160,17070 ,0,0,0}, - {28448,28497,28543 ,17070,17112,17159 ,0,0,0}, {28544,28498,28501 ,17160,17113,17116 ,0,0,0}, - {28448,28544,28501 ,17070,17160,17116 ,0,0,0}, {26965,28545,28546 ,17161,17162,17163 ,0,0,0}, - {28501,28498,28500 ,17116,17113,17115 ,0,0,0}, {28502,28547,28503 ,17117,17164,17118 ,0,0,0}, - {28500,28499,28502 ,17115,17114,17117 ,0,0,0}, {28548,28547,28546 ,17165,17164,17163 ,0,0,0}, - {28499,28547,28502 ,17114,17164,17117 ,0,0,0}, {28548,28549,28504 ,17165,17166,17119 ,0,0,0}, - {28504,28503,28548 ,17119,17118,17165 ,0,0,0}, {28549,28550,28505 ,17166,17167,17120 ,0,0,0}, - {28505,28504,28549 ,17120,17119,17166 ,0,0,0}, {28550,28551,28506 ,17167,17168,17121 ,0,0,0}, - {28506,28505,28550 ,17121,17120,17167 ,0,0,0}, {28551,28456,28507 ,17168,17077,17122 ,0,0,0}, - {28506,28551,28507 ,17121,17168,17122 ,0,0,0}, {28552,28553,28554 ,14118,14234,14116 ,0,0,0}, - {28507,28456,28455 ,17122,17077,17076 ,0,0,0}, {28454,28553,28508 ,17075,14234,17123 ,0,0,0}, - {28455,28454,28508 ,17076,17075,17123 ,0,0,0}, {28553,28555,28509 ,14234,17169,17124 ,0,0,0}, - {28509,28508,28553 ,17124,17123,14234 ,0,0,0}, {28555,28556,28510 ,17169,17170,17125 ,0,0,0}, - {28510,28509,28555 ,17125,17124,17169 ,0,0,0}, {28556,28557,28511 ,17170,17171,17126 ,0,0,0}, - {28511,28510,28556 ,17126,17125,17170 ,0,0,0}, {28557,28464,28512 ,17171,17085,17127 ,0,0,0}, - {28511,28557,28512 ,17126,17171,17127 ,0,0,0}, {28558,26956,28559 ,17172,17173,14103 ,0,0,0}, - {28512,28464,28463 ,17127,17085,17084 ,0,0,0}, {28514,28513,28560 ,17129,17128,17174 ,0,0,0}, - {28463,28462,28513 ,17084,17083,17128 ,0,0,0}, {28561,28560,28558 ,17175,17174,17172 ,0,0,0}, - {28513,28462,28560 ,17128,17083,17174 ,0,0,0}, {28561,28562,28515 ,17175,17176,17130 ,0,0,0}, - {28515,28514,28561 ,17130,17129,17175 ,0,0,0}, {28562,28563,28516 ,17176,17177,17131 ,0,0,0}, - {28516,28515,28562 ,17131,17130,17176 ,0,0,0}, {28563,28564,28472 ,17177,17178,17092 ,0,0,0}, - {28472,28516,28563 ,17092,17131,17177 ,0,0,0}, {28564,28517,28520 ,17178,17132,17135 ,0,0,0}, - {28472,28564,28520 ,17092,17178,17135 ,0,0,0}, {28565,28566,28567 ,17179,17180,17181 ,0,0,0}, - {28520,28517,28519 ,17135,17132,17134 ,0,0,0}, {28518,28566,28521 ,17133,17180,17136 ,0,0,0}, - {28519,28518,28521 ,17134,17133,17136 ,0,0,0}, {28566,28568,28522 ,17180,17182,17137 ,0,0,0}, - {28522,28521,28566 ,17137,17136,17180 ,0,0,0}, {28568,28569,28523 ,17182,14221,17138 ,0,0,0}, - {28523,28522,28568 ,17138,17137,17182 ,0,0,0}, {28569,28570,28524 ,14221,17183,17139 ,0,0,0}, - {28524,28523,28569 ,17139,17138,14221 ,0,0,0}, {28570,28571,28525 ,17183,17184,17140 ,0,0,0}, - {28525,28524,28570 ,17140,17139,17183 ,0,0,0}, {28571,28572,28480 ,17184,17185,14260 ,0,0,0}, - {28480,28525,28571 ,14260,17140,17184 ,0,0,0}, {28572,28573,28526 ,17185,17186,17141 ,0,0,0}, - {28526,28480,28572 ,17141,14260,17185 ,0,0,0}, {28573,28527,28530 ,17186,17142,17145 ,0,0,0}, - {28526,28573,28530 ,17141,17186,17145 ,0,0,0}, {28531,28528,28574 ,17146,17143,17187 ,0,0,0}, - {28530,28527,28529 ,17145,17142,17144 ,0,0,0}, {28306,28299,28301 ,16933,16926,16928 ,0,0,0}, - {28529,28528,28531 ,17144,17143,17146 ,0,0,0}, {28305,28532,28299 ,16932,17147,16926 ,0,0,0}, - {28531,28574,28301 ,17146,17187,16928 ,0,0,0}, {28313,28307,28575 ,16940,16934,17188 ,0,0,0}, - {28574,28306,28301 ,17187,16933,16928 ,0,0,0}, {28305,28576,28577 ,16932,17189,17190 ,0,0,0}, - {28309,28533,28486 ,16936,17148,17103 ,0,0,0}, {28485,28299,28532 ,17102,16926,17147 ,0,0,0}, - {28309,28532,28577 ,16936,17147,17190 ,0,0,0}, {28308,28533,28309 ,16935,17148,16936 ,0,0,0}, - {28254,28256,28490 ,16864,16867,17106 ,0,0,0}, {27922,27924,28245 ,17150,16853,16856 ,0,0,0}, - {28535,28245,28250 ,17151,16856,16861 ,0,0,0}, {28490,28535,28489 ,17106,17151,14147 ,0,0,0}, - {28249,28535,28250 ,16860,17151,16861 ,0,0,0}, {28248,28538,28536 ,16859,17154,17152 ,0,0,0}, - {28536,28249,28248 ,17152,16860,16859 ,0,0,0}, {28538,28578,28537 ,17154,17191,17153 ,0,0,0}, - {28579,28539,28578 ,17192,17155,17191 ,0,0,0}, {28492,28536,28537 ,17108,17152,17153 ,0,0,0}, - {28539,28537,28578 ,17155,17153,17191 ,0,0,0}, {28580,28540,28579 ,17193,17156,17192 ,0,0,0}, - {28540,28539,28579 ,17156,17155,17192 ,0,0,0}, {28581,28541,28580 ,17194,17157,17193 ,0,0,0}, - {28541,28540,28580 ,17157,17156,17193 ,0,0,0}, {28582,28542,28581 ,17195,17158,17194 ,0,0,0}, - {28542,28541,28581 ,17158,17157,17194 ,0,0,0}, {28583,28543,28582 ,17196,17159,17195 ,0,0,0}, - {28543,28542,28582 ,17159,17158,17195 ,0,0,0}, {28584,28544,28583 ,17197,17160,17196 ,0,0,0}, - {28544,28543,28583 ,17160,17159,17196 ,0,0,0}, {28585,28498,28584 ,14134,17113,17197 ,0,0,0}, - {28498,28544,28584 ,17113,17160,17197 ,0,0,0}, {28586,28499,28585 ,17198,17114,14134 ,0,0,0}, - {28499,28498,28585 ,17114,17113,14134 ,0,0,0}, {28546,28547,28586 ,17163,17164,17198 ,0,0,0}, - {28499,28586,28547 ,17114,17198,17164 ,0,0,0}, {28546,28545,28548 ,17163,17162,17165 ,0,0,0}, - {28587,28549,28545 ,17199,17166,17162 ,0,0,0}, {28503,28547,28548 ,17118,17164,17165 ,0,0,0}, - {28549,28548,28545 ,17166,17165,17162 ,0,0,0}, {28588,28550,28587 ,17200,17167,17199 ,0,0,0}, - {28550,28549,28587 ,17167,17166,17199 ,0,0,0}, {28589,28551,28588 ,17201,17168,17200 ,0,0,0}, - {28551,28550,28588 ,17168,17167,17200 ,0,0,0}, {28590,28456,28589 ,17202,17077,17201 ,0,0,0}, - {28456,28551,28589 ,17077,17168,17201 ,0,0,0}, {28554,28454,28590 ,14116,17075,17202 ,0,0,0}, - {28454,28456,28590 ,17075,17077,17202 ,0,0,0}, {28554,26873,28552 ,14116,14183,14118 ,0,0,0}, - {28454,28554,28553 ,17075,14116,14234 ,0,0,0}, {28591,28555,28552 ,17203,17169,14118 ,0,0,0}, - {28555,28553,28552 ,17169,14234,14118 ,0,0,0}, {28592,28556,28591 ,17204,17170,17203 ,0,0,0}, - {28556,28555,28591 ,17170,17169,17203 ,0,0,0}, {28593,28557,28592 ,14185,17171,17204 ,0,0,0}, - {28557,28556,28592 ,17171,17170,17204 ,0,0,0}, {28594,28464,28593 ,17205,17085,14185 ,0,0,0}, - {28464,28557,28593 ,17085,17171,14185 ,0,0,0}, {28595,28462,28594 ,17206,17083,17205 ,0,0,0}, - {28462,28464,28594 ,17083,17085,17205 ,0,0,0}, {28558,28560,28595 ,17172,17174,17206 ,0,0,0}, - {28462,28595,28560 ,17083,17206,17174 ,0,0,0}, {28558,28559,28561 ,17172,14103,17175 ,0,0,0}, - {28596,28562,28559 ,17207,17176,14103 ,0,0,0}, {28514,28560,28561 ,17129,17174,17175 ,0,0,0}, - {28562,28561,28559 ,17176,17175,14103 ,0,0,0}, {28597,28563,28596 ,17208,17177,17207 ,0,0,0}, - {28563,28562,28596 ,17177,17176,17207 ,0,0,0}, {28598,28564,28597 ,17209,17178,17208 ,0,0,0}, - {28564,28563,28597 ,17178,17177,17208 ,0,0,0}, {28599,28517,28598 ,17210,17132,17209 ,0,0,0}, - {28517,28564,28598 ,17132,17178,17209 ,0,0,0}, {28567,28518,28599 ,17181,17133,17210 ,0,0,0}, - {28518,28517,28599 ,17133,17132,17210 ,0,0,0}, {28567,26895,28565 ,17181,14192,17179 ,0,0,0}, - {28518,28567,28566 ,17133,17181,17180 ,0,0,0}, {28600,28568,28565 ,14092,17182,17179 ,0,0,0}, - {28568,28566,28565 ,17182,17180,17179 ,0,0,0}, {28601,28569,28600 ,17211,14221,14092 ,0,0,0}, - {28569,28568,28600 ,14221,17182,14092 ,0,0,0}, {28602,28570,28601 ,17212,17183,17211 ,0,0,0}, - {28570,28569,28601 ,17183,14221,17211 ,0,0,0}, {28603,28571,28602 ,17213,17184,17212 ,0,0,0}, - {28571,28570,28602 ,17184,17183,17212 ,0,0,0}, {28604,28572,28603 ,17214,17185,17213 ,0,0,0}, - {28572,28571,28603 ,17185,17184,17213 ,0,0,0}, {28605,28573,28604 ,17215,17186,17214 ,0,0,0}, - {28573,28572,28604 ,17186,17185,17214 ,0,0,0}, {28606,28527,28605 ,17216,17142,17215 ,0,0,0}, - {28527,28573,28605 ,17142,17186,17215 ,0,0,0}, {28607,28528,28606 ,14053,17143,17216 ,0,0,0}, - {28528,28527,28606 ,17143,17142,17216 ,0,0,0}, {28608,28574,28607 ,17217,17187,14053 ,0,0,0}, - {28574,28528,28607 ,17187,17143,14053 ,0,0,0}, {28609,28306,28608 ,17218,16933,17217 ,0,0,0}, - {28306,28574,28608 ,16933,17187,17217 ,0,0,0}, {28609,28576,28305 ,17218,17189,16932 ,0,0,0}, - {28305,28306,28609 ,16932,16933,17218 ,0,0,0}, {28576,28575,28577 ,17189,17188,17190 ,0,0,0}, - {28309,28577,28307 ,16936,17190,16934 ,0,0,0}, {28532,28305,28577 ,17147,16932,17190 ,0,0,0}, - {28575,28307,28577 ,17188,16934,17190 ,0,0,0}, {28308,28307,28314 ,16935,16934,16941 ,0,0,0}, - {28535,28256,28245 ,17151,16867,16856 ,0,0,0}, {28245,28256,27922 ,16856,16867,17150 ,0,0,0}, - {26977,26973,28250 ,17022,17219,16861 ,0,0,0}, {28250,26973,28248 ,16861,17219,16859 ,0,0,0}, - {26973,26972,28248 ,17219,17220,16859 ,0,0,0}, {28248,26972,28538 ,16859,17220,17154 ,0,0,0}, - {26972,26971,28538 ,17220,14143,17154 ,0,0,0}, {28538,26971,28578 ,17154,14143,17191 ,0,0,0}, - {26971,26834,28578 ,14143,14144,17191 ,0,0,0}, {28578,26834,28579 ,17191,14144,17192 ,0,0,0}, - {26834,26824,28579 ,14144,17221,17192 ,0,0,0}, {28579,26824,28580 ,17192,17221,17193 ,0,0,0}, - {26824,26857,28580 ,17221,17222,17193 ,0,0,0}, {28580,26857,28581 ,17193,17222,17194 ,0,0,0}, - {26857,26854,28581 ,17222,17223,17194 ,0,0,0}, {28581,26854,28582 ,17194,17223,17195 ,0,0,0}, - {26854,26859,28582 ,17223,17224,17195 ,0,0,0}, {26859,26862,28583 ,17224,17225,17196 ,0,0,0}, - {26859,28583,28582 ,17224,17196,17195 ,0,0,0}, {26862,26829,28584 ,17225,14133,17197 ,0,0,0}, - {26862,28584,28583 ,17225,17197,17196 ,0,0,0}, {26829,26828,28585 ,14133,17226,14134 ,0,0,0}, - {26829,28585,28584 ,14133,14134,17197 ,0,0,0}, {26828,26864,28586 ,17226,17227,17198 ,0,0,0}, - {26828,28586,28585 ,17226,17198,14134 ,0,0,0}, {26864,26966,28546 ,17227,17228,17163 ,0,0,0}, - {26864,28546,28586 ,17227,17163,17198 ,0,0,0}, {26965,28546,26966 ,17161,17163,17228 ,0,0,0}, - {26965,26867,28545 ,17161,14180,17162 ,0,0,0}, {28545,26867,28587 ,17162,14180,17199 ,0,0,0}, - {26867,26872,28587 ,14180,14120,17199 ,0,0,0}, {28587,26872,28588 ,17199,14120,17200 ,0,0,0}, - {26872,26870,28588 ,14120,14121,17200 ,0,0,0}, {26870,26869,28589 ,14121,14122,17201 ,0,0,0}, - {26870,28589,28588 ,14121,17201,17200 ,0,0,0}, {26869,26964,28590 ,14122,14115,17202 ,0,0,0}, - {26869,28590,28589 ,14122,17202,17201 ,0,0,0}, {26964,26873,28554 ,14115,14183,14116 ,0,0,0}, - {26964,28554,28590 ,14115,14116,17202 ,0,0,0}, {26873,26963,28552 ,14183,17229,14118 ,0,0,0}, - {26963,26959,28552 ,17229,14110,14118 ,0,0,0}, {28552,26959,28591 ,14118,14110,17203 ,0,0,0}, - {26959,26877,28591 ,14110,17230,17203 ,0,0,0}, {28591,26877,28592 ,17203,17230,17204 ,0,0,0}, - {26877,26879,28592 ,17230,17231,17204 ,0,0,0}, {26879,26884,28593 ,17231,17232,14185 ,0,0,0}, - {26879,28593,28592 ,17231,14185,17204 ,0,0,0}, {26884,26882,28594 ,17232,14106,17205 ,0,0,0}, - {26884,28594,28593 ,17232,17205,14185 ,0,0,0}, {26882,26881,28595 ,14106,14186,17206 ,0,0,0}, - {26882,28595,28594 ,14106,17206,17205 ,0,0,0}, {26881,26957,28558 ,14186,17233,17172 ,0,0,0}, - {26881,28558,28595 ,14186,17172,17206 ,0,0,0}, {26956,28558,26957 ,17173,17172,17233 ,0,0,0}, - {26956,26886,28559 ,17173,17234,14103 ,0,0,0}, {28559,26886,28596 ,14103,17234,17207 ,0,0,0}, - {26886,26893,28596 ,17234,14098,17207 ,0,0,0}, {26893,26892,28597 ,14098,14099,17208 ,0,0,0}, - {26893,28597,28596 ,14098,17208,17207 ,0,0,0}, {26892,26891,28598 ,14099,17235,17209 ,0,0,0}, - {26892,28598,28597 ,14099,17209,17208 ,0,0,0}, {26891,26953,28599 ,17235,14096,17210 ,0,0,0}, - {26891,28599,28598 ,17235,17210,17209 ,0,0,0}, {26953,26895,28567 ,14096,14192,17181 ,0,0,0}, - {26953,28567,28599 ,14096,17181,17210 ,0,0,0}, {26895,26894,28565 ,14192,17236,17179 ,0,0,0}, - {26894,26900,28565 ,17236,17237,17179 ,0,0,0}, {28565,26900,28600 ,17179,17237,14092 ,0,0,0}, - {26900,26899,28600 ,17237,14056,14092 ,0,0,0}, {28600,26899,28601 ,14092,14056,17211 ,0,0,0}, - {26899,26904,28601 ,14056,14057,17211 ,0,0,0}, {28601,26904,28602 ,17211,14057,17212 ,0,0,0}, - {26904,26902,28602 ,14057,17238,17212 ,0,0,0}, {26902,26910,28603 ,17238,17239,17213 ,0,0,0}, - {26902,28603,28602 ,17238,17213,17212 ,0,0,0}, {26910,26906,28604 ,17239,17240,17214 ,0,0,0}, - {26910,28604,28603 ,17239,17214,17213 ,0,0,0}, {26906,26908,28605 ,17240,17241,17215 ,0,0,0}, - {26906,28605,28604 ,17240,17215,17214 ,0,0,0}, {26908,26911,28606 ,17241,14052,17216 ,0,0,0}, - {26908,28606,28605 ,17241,17216,17215 ,0,0,0}, {26911,26913,28607 ,14052,17242,14053 ,0,0,0}, - {26911,28607,28606 ,14052,14053,17216 ,0,0,0}, {26913,26918,28608 ,17242,17243,17217 ,0,0,0}, - {26913,28608,28607 ,17242,17217,14053 ,0,0,0}, {26918,26924,28609 ,17243,17244,17218 ,0,0,0}, - {26918,28609,28608 ,17243,17218,17217 ,0,0,0}, {26924,26925,28576 ,17244,17245,17189 ,0,0,0}, - {26924,28576,28609 ,17244,17189,17218 ,0,0,0}, {26925,26923,28575 ,17245,17246,17188 ,0,0,0}, - {26925,28575,28576 ,17245,17188,17189 ,0,0,0}, {26923,26917,28313 ,17246,17247,16940 ,0,0,0}, - {26923,28313,28575 ,17246,16940,17188 ,0,0,0}, {28313,26917,26916 ,16940,17247,15634 ,0,0,0}, - {28146,27852,27873 ,17248,17248,17248 ,0,0,0}, {27482,27869,27478 ,17248,17248,17248 ,0,0,0}, - {27868,27873,27934 ,17248,17248,17248 ,0,0,0}, {28146,27873,27853 ,17248,17248,17248 ,0,0,0}, - {27868,27934,28011 ,17248,17248,17248 ,0,0,0}, {27853,27868,27483 ,17248,17248,17248 ,0,0,0}, - {27873,27868,27853 ,17248,17248,17248 ,0,0,0}, {27343,27478,27869 ,17248,17248,17248 ,0,0,0}, - {27482,27866,27863 ,17248,17248,17248 ,0,0,0}, {27349,27358,27693 ,17248,17248,17248 ,0,0,0}, - {27484,27343,27869 ,17248,17248,17248 ,0,0,0}, {27485,27484,27349 ,17248,17248,17248 ,0,0,0}, - {27484,27485,27474 ,17248,17248,17248 ,0,0,0}, {27356,27349,27693 ,17248,17248,17248 ,0,0,0}, - {27357,27358,27484 ,17248,17248,17248 ,0,0,0}, {27358,27349,27484 ,17248,17248,17248 ,0,0,0}, - {27871,27484,27869 ,17248,17248,17248 ,0,0,0}, {27871,27357,27484 ,17248,17248,17248 ,0,0,0}, - {27869,27482,27863 ,17248,17248,17248 ,0,0,0}, {27866,27482,27868 ,17248,17248,17248 ,0,0,0}, - {27483,27868,27481 ,17248,17248,17248 ,0,0,0}, {27482,27481,27868 ,17248,17248,17248 ,0,0,0}, - {28533,28308,28314 ,17249,17249,17249 ,0,0,0}, {28362,28399,27112 ,17249,17249,17249 ,0,0,0}, - {28318,28534,28314 ,17249,17249,17249 ,0,0,0}, {28438,28488,27028 ,17249,17249,17249 ,0,0,0}, - {28487,28534,28488 ,17249,17249,17249 ,0,0,0}, {28534,28318,26916 ,17249,17249,17249 ,0,0,0}, - {28533,28314,28534 ,17249,17249,17249 ,0,0,0}, {27028,28488,28534 ,17249,17249,17249 ,0,0,0}, - {28534,26916,27028 ,17249,17249,17249 ,0,0,0}, {27027,28438,27028 ,17249,17249,17249 ,0,0,0}, - {27027,27070,28438 ,17249,17249,17249 ,0,0,0}, {28399,28438,27112 ,17249,17249,17249 ,0,0,0}, - {27070,27112,28438 ,17249,17249,17249 ,0,0,0}, {28363,28362,27112 ,17249,17249,17249 ,0,0,0}, - {27156,27198,27157 ,17249,17249,17249 ,0,0,0}, {27157,28363,27112 ,17249,17249,17249 ,0,0,0}, - {28363,27157,27198 ,17249,17249,17249 ,0,0,0}, {26949,27197,26944 ,17249,17249,17249 ,0,0,0}, - {28363,27198,26950 ,17249,17249,17249 ,0,0,0}, {27198,26949,26948 ,17249,17249,17249 ,0,0,0}, - {26949,27198,27197 ,17249,17249,17249 ,0,0,0}, {27198,26948,26950 ,17249,17249,17249 ,0,0,0} -// Landegestell.prt - , {28610,28611,28612 ,11524,11525,11526 ,0,0,0}, {28613,28614,28615 ,11527,11528,11529 ,0,0,0}, - {28616,28617,28618 ,11530,11531,11532 ,0,0,0}, {28619,28611,28620 ,11533,11525,11534 ,0,0,0}, - {28621,28618,28622 ,11535,11532,11536 ,0,0,0}, {28623,28624,28625 ,11537,11538,11539 ,0,0,0}, - {28626,28627,28628 ,11540,11541,11542 ,0,0,0}, {28629,28622,28617 ,11543,11536,11531 ,0,0,0}, - {28630,28631,28632 ,11544,11545,11546 ,0,0,0}, {28626,28633,28632 ,11540,11547,11546 ,0,0,0}, - {28634,28635,28636 ,11548,11549,11550 ,0,0,0}, {28636,28635,28631 ,11550,11549,11545 ,0,0,0}, - {28637,28636,28638 ,11551,11550,11552 ,0,0,0}, {28620,28611,28610 ,11534,11525,11524 ,0,0,0}, - {28638,28639,28637 ,11552,11553,11551 ,0,0,0}, {28640,28641,28642 ,11554,11555,11556 ,0,0,0}, - {28612,28643,28610 ,11526,11557,11524 ,0,0,0}, {28644,28645,28642 ,11558,11559,11556 ,0,0,0}, - {28646,28647,28644 ,11560,11561,11558 ,0,0,0}, {28647,28648,28644 ,11561,11562,11558 ,0,0,0}, - {28642,28645,28640 ,11556,11559,11554 ,0,0,0}, {28649,28650,28614 ,11563,11564,11528 ,0,0,0}, - {28651,28652,28653 ,11565,11566,11567 ,0,0,0}, {28649,28654,28650 ,11563,11568,11564 ,0,0,0}, - {28655,28656,28657 ,11569,11570,11571 ,0,0,0}, {28652,28658,28653 ,11566,11572,11567 ,0,0,0}, - {28659,28660,28661 ,11573,11574,11575 ,0,0,0}, {28655,28657,28662 ,11569,11571,11576 ,0,0,0}, - {28663,28664,28665 ,11577,11578,11579 ,0,0,0}, {28664,28663,28666 ,11578,11577,11580 ,0,0,0}, - {28667,28668,28669 ,11581,11582,11583 ,0,0,0}, {28670,28671,28668 ,11584,11585,11582 ,0,0,0}, - {28672,28673,28674 ,11586,11587,11588 ,0,0,0}, {28667,28669,28675 ,11581,11583,11589 ,0,0,0}, - {28676,28677,28678 ,11590,11591,11592 ,0,0,0}, {28672,28674,28679 ,11586,11588,11593 ,0,0,0}, - {28680,28681,28682 ,11594,11595,11596 ,0,0,0}, {28683,28677,28676 ,11597,11591,11590 ,0,0,0}, - {28684,28685,28686 ,11598,11599,11600 ,0,0,0}, {28686,28682,28684 ,11600,11596,11598 ,0,0,0}, - {28687,28688,28689 ,11601,11602,11603 ,0,0,0}, {28690,28685,28691 ,11604,11599,11605 ,0,0,0}, - {28692,28693,28694 ,11606,11607,11608 ,0,0,0}, {28695,28692,28696 ,11609,11606,11610 ,0,0,0}, - {28697,28698,28699 ,11611,11612,11613 ,0,0,0}, {28700,28697,28694 ,11614,11611,11608 ,0,0,0}, - {28701,28702,28703 ,11615,11616,11617 ,0,0,0}, {28704,28699,28705 ,11618,11613,11619 ,0,0,0}, - {28706,28707,28708 ,11620,11621,11622 ,0,0,0}, {28703,28709,28701 ,11617,11623,11615 ,0,0,0}, - {28710,28706,28711 ,11624,11620,11625 ,0,0,0}, {28701,28709,28712 ,11615,11623,11626 ,0,0,0}, - {28713,28710,28704 ,11627,11624,11618 ,0,0,0}, {28706,28710,28713 ,11620,11624,11627 ,0,0,0}, - {28714,28715,28716 ,11628,11629,11630 ,0,0,0}, {28717,28700,28718 ,11631,11614,11632 ,0,0,0}, - {28719,28720,28721 ,11633,11634,11635 ,0,0,0}, {28717,28718,28722 ,11631,11632,11636 ,0,0,0}, - {28723,28724,28725 ,11637,11638,11639 ,0,0,0}, {28721,28726,28727 ,11635,11640,11641 ,0,0,0}, - {28728,28729,28725 ,11642,11643,11639 ,0,0,0}, {28730,28731,28732 ,11644,11645,11646 ,0,0,0}, - {28733,28734,28735 ,11647,11648,11649 ,0,0,0}, {28735,28732,28733 ,11649,11646,11647 ,0,0,0}, - {28734,28733,28736 ,11648,11647,11650 ,0,0,0}, {28705,28699,28698 ,11619,11613,11612 ,0,0,0}, - {28706,28712,28711 ,11620,11626,11625 ,0,0,0}, {28700,28694,28693 ,11614,11608,11607 ,0,0,0}, - {28700,28698,28697 ,11614,11612,11611 ,0,0,0}, {28695,28696,28687 ,11609,11610,11601 ,0,0,0}, - {28692,28695,28693 ,11606,11609,11607 ,0,0,0}, {28689,28688,28690 ,11603,11602,11604 ,0,0,0}, - {28696,28688,28687 ,11610,11602,11601 ,0,0,0}, {28689,28690,28691 ,11603,11604,11605 ,0,0,0}, - {28737,28695,28687 ,11651,11609,11601 ,0,0,0}, {28686,28680,28682 ,11600,11594,11596 ,0,0,0}, - {28685,28684,28691 ,11599,11598,11605 ,0,0,0}, {28676,28678,28738 ,11590,11592,11652 ,0,0,0}, - {28739,28683,28740 ,11653,11597,11654 ,0,0,0}, {28682,28681,28740 ,11596,11595,11654 ,0,0,0}, - {28677,28683,28739 ,11591,11597,11653 ,0,0,0}, {28681,28739,28740 ,11595,11653,11654 ,0,0,0}, - {28738,28678,28679 ,11652,11592,11593 ,0,0,0}, {28741,28676,28738 ,11655,11590,11652 ,0,0,0}, - {28679,28674,28738 ,11593,11588,11652 ,0,0,0}, {28675,28673,28742 ,11589,11587,11656 ,0,0,0}, - {28672,28742,28673 ,11586,11656,11587 ,0,0,0}, {28743,28675,28742 ,11657,11589,11656 ,0,0,0}, - {28671,28669,28668 ,11585,11583,11582 ,0,0,0}, {28667,28675,28743 ,11581,11589,11657 ,0,0,0}, - {28670,28744,28671 ,11584,11658,11585 ,0,0,0}, {28665,28664,28744 ,11579,11578,11658 ,0,0,0}, - {28744,28670,28665 ,11658,11584,11579 ,0,0,0}, {28666,28745,28661 ,11580,11659,11575 ,0,0,0}, - {28746,28747,28748 ,11660,11661,11662 ,0,0,0}, {28661,28745,28749 ,11575,11659,11663 ,0,0,0}, - {28745,28666,28663 ,11659,11580,11577 ,0,0,0}, {28750,28662,28660 ,11664,11576,11574 ,0,0,0}, - {28659,28661,28749 ,11573,11575,11663 ,0,0,0}, {28662,28750,28655 ,11576,11664,11569 ,0,0,0}, - {28750,28660,28659 ,11664,11574,11573 ,0,0,0}, {28654,28751,28752 ,11568,11665,11666 ,0,0,0}, - {28656,28658,28753 ,11570,11572,11667 ,0,0,0}, {28657,28656,28753 ,11571,11570,11667 ,0,0,0}, - {28753,28658,28652 ,11667,11572,11566 ,0,0,0}, {28754,28755,28756 ,11668,11669,11670 ,0,0,0}, - {28751,28651,28653 ,11665,11565,11567 ,0,0,0}, {28643,28612,28641 ,11557,11526,11555 ,0,0,0}, - {28654,28651,28751 ,11568,11565,11665 ,0,0,0}, {28654,28752,28650 ,11568,11666,11564 ,0,0,0}, - {28614,28613,28649 ,11528,11527,11563 ,0,0,0}, {28648,28647,28615 ,11562,11561,11529 ,0,0,0}, - {28615,28647,28613 ,11529,11561,11527 ,0,0,0}, {28640,28643,28641 ,11554,11557,11555 ,0,0,0}, - {28648,28645,28644 ,11562,11559,11558 ,0,0,0}, {28625,28757,28758 ,11539,11671,11672 ,0,0,0}, - {28619,28620,28757 ,11533,11534,11671 ,0,0,0}, {28758,28623,28625 ,11672,11537,11539 ,0,0,0}, - {28619,28757,28625 ,11533,11671,11539 ,0,0,0}, {28758,28759,28623 ,11672,11673,11537 ,0,0,0}, - {28760,28761,28627 ,11674,11675,11541 ,0,0,0}, {28623,28759,28762 ,11537,11673,11676 ,0,0,0}, - {28762,28759,28763 ,11676,11673,11677 ,0,0,0}, {28764,28762,28765 ,11678,11676,11679 ,0,0,0}, - {28763,28765,28762 ,11677,11679,11676 ,0,0,0}, {28628,28766,28626 ,11542,11680,11540 ,0,0,0}, - {28767,28764,28765 ,11681,11678,11679 ,0,0,0}, {28768,28767,28765 ,11682,11681,11679 ,0,0,0}, - {28764,28767,28769 ,11678,11681,11683 ,0,0,0}, {28770,28771,28769 ,11684,11685,11683 ,0,0,0}, - {28761,28760,28772 ,11675,11674,11686 ,0,0,0}, {28769,28771,28764 ,11683,11685,11678 ,0,0,0}, - {28770,28760,28771 ,11684,11674,11685 ,0,0,0}, {28764,28773,28762 ,11678,11687,11676 ,0,0,0}, - {28774,28619,28625 ,11688,11533,11539 ,0,0,0}, {28762,28616,28623 ,11676,11530,11537 ,0,0,0}, - {28775,28611,28619 ,11689,11525,11533 ,0,0,0}, {28624,28623,28616 ,11538,11537,11530 ,0,0,0}, - {28776,28612,28611 ,11690,11526,11525 ,0,0,0}, {28774,28625,28624 ,11688,11539,11538 ,0,0,0}, - {28777,28641,28612 ,11691,11555,11526 ,0,0,0}, {28775,28619,28774 ,11689,11533,11688 ,0,0,0}, - {28778,28642,28641 ,11692,11556,11555 ,0,0,0}, {28776,28611,28775 ,11690,11525,11689 ,0,0,0}, - {28779,28644,28642 ,11693,11558,11556 ,0,0,0}, {28612,28776,28777 ,11526,11690,11691 ,0,0,0}, - {28780,28781,28782 ,11694,11695,11696 ,0,0,0}, {28641,28777,28778 ,11555,11691,11692 ,0,0,0}, - {28782,28613,28647 ,11696,11527,11561 ,0,0,0}, {28642,28778,28779 ,11556,11692,11693 ,0,0,0}, - {28783,28649,28613 ,11697,11563,11527 ,0,0,0}, {28644,28779,28646 ,11558,11693,11560 ,0,0,0}, - {28784,28654,28649 ,11698,11568,11563 ,0,0,0}, {28647,28646,28782 ,11561,11560,11696 ,0,0,0}, - {28785,28651,28654 ,11699,11565,11568 ,0,0,0}, {28613,28782,28783 ,11527,11696,11697 ,0,0,0}, - {28786,28652,28651 ,11700,11566,11565 ,0,0,0}, {28784,28649,28783 ,11698,11563,11697 ,0,0,0}, - {28787,28753,28652 ,11701,11667,11566 ,0,0,0}, {28785,28654,28784 ,11699,11568,11698 ,0,0,0}, - {28788,28657,28753 ,11702,11571,11667 ,0,0,0}, {28651,28785,28786 ,11565,11699,11700 ,0,0,0}, - {28755,28662,28657 ,11669,11576,11571 ,0,0,0}, {28652,28786,28787 ,11566,11700,11701 ,0,0,0}, - {28789,28660,28662 ,11703,11574,11576 ,0,0,0}, {28753,28787,28788 ,11667,11701,11702 ,0,0,0}, - {28790,28661,28660 ,11704,11575,11574 ,0,0,0}, {28657,28788,28755 ,11571,11702,11669 ,0,0,0}, - {28791,28666,28661 ,11705,11580,11575 ,0,0,0}, {28789,28662,28755 ,11703,11576,11669 ,0,0,0}, - {28792,28664,28666 ,11706,11578,11580 ,0,0,0}, {28790,28660,28789 ,11704,11574,11703 ,0,0,0}, - {28793,28744,28664 ,11707,11658,11578 ,0,0,0}, {28661,28790,28791 ,11575,11704,11705 ,0,0,0}, - {28671,28744,28746 ,11585,11658,11660 ,0,0,0}, {28666,28791,28792 ,11580,11705,11706 ,0,0,0}, - {28794,28669,28671 ,11708,11583,11585 ,0,0,0}, {28664,28792,28793 ,11578,11706,11707 ,0,0,0}, - {28795,28675,28669 ,11709,11589,11583 ,0,0,0}, {28744,28793,28746 ,11658,11707,11660 ,0,0,0}, - {28796,28673,28675 ,11710,11587,11589 ,0,0,0}, {28794,28671,28746 ,11708,11585,11660 ,0,0,0}, - {28797,28674,28673 ,11711,11588,11587 ,0,0,0}, {28795,28669,28794 ,11709,11583,11708 ,0,0,0}, - {28798,28738,28674 ,11712,11652,11588 ,0,0,0}, {28675,28795,28796 ,11589,11709,11710 ,0,0,0}, - {28799,28800,28801 ,11713,11714,11715 ,0,0,0}, {28673,28796,28797 ,11587,11710,11711 ,0,0,0}, - {28802,28683,28676 ,11716,11597,11590 ,0,0,0}, {28674,28797,28798 ,11588,11711,11712 ,0,0,0}, - {28803,28740,28683 ,11717,11654,11597 ,0,0,0}, {28738,28798,28741 ,11652,11712,11655 ,0,0,0}, - {28804,28682,28740 ,11718,11596,11654 ,0,0,0}, {28676,28741,28802 ,11590,11655,11716 ,0,0,0}, - {28805,28684,28682 ,11719,11598,11596 ,0,0,0}, {28803,28683,28802 ,11717,11597,11716 ,0,0,0}, - {28806,28691,28684 ,11720,11605,11598 ,0,0,0}, {28804,28740,28803 ,11718,11654,11717 ,0,0,0}, - {28807,28689,28691 ,11721,11603,11605 ,0,0,0}, {28805,28682,28804 ,11719,11596,11718 ,0,0,0}, - {28808,28687,28689 ,11722,11601,11603 ,0,0,0}, {28684,28805,28806 ,11598,11719,11720 ,0,0,0}, - {28695,28809,28693 ,11609,11723,11607 ,0,0,0}, {28691,28806,28807 ,11605,11720,11721 ,0,0,0}, - {28718,28810,28722 ,11632,11724,11636 ,0,0,0}, {28689,28807,28808 ,11603,11721,11722 ,0,0,0}, - {28718,28700,28693 ,11632,11614,11607 ,0,0,0}, {28687,28808,28737 ,11601,11722,11651 ,0,0,0}, - {28717,28698,28700 ,11631,11612,11614 ,0,0,0}, {28695,28737,28809 ,11609,11651,11723 ,0,0,0}, - {28705,28698,28811 ,11619,11612,11725 ,0,0,0}, {28809,28718,28693 ,11723,11632,11607 ,0,0,0}, - {28720,28707,28713 ,11634,11621,11627 ,0,0,0}, {28707,28720,28719 ,11621,11634,11633 ,0,0,0}, - {28705,28713,28704 ,11619,11627,11618 ,0,0,0}, {28698,28717,28811 ,11612,11631,11725 ,0,0,0}, - {28701,28712,28812 ,11615,11626,11726 ,0,0,0}, {28705,28720,28713 ,11619,11634,11627 ,0,0,0}, - {28706,28713,28707 ,11620,11627,11621 ,0,0,0}, {28813,28814,28701 ,11727,11728,11615 ,0,0,0}, - {28711,28712,28709 ,11625,11626,11623 ,0,0,0}, {28708,28812,28712 ,11622,11726,11626 ,0,0,0}, - {28702,28701,28814 ,11616,11615,11728 ,0,0,0}, {28771,28773,28764 ,11685,11687,11678 ,0,0,0}, - {28772,28760,28770 ,11686,11674,11684 ,0,0,0}, {28633,28815,28632 ,11547,11729,11546 ,0,0,0}, - {28773,28616,28762 ,11687,11530,11676 ,0,0,0}, {28771,28816,28773 ,11685,11730,11687 ,0,0,0}, - {28624,28618,28817 ,11538,11532,11731 ,0,0,0}, {28617,28616,28773 ,11531,11530,11687 ,0,0,0}, - {28774,28817,28818 ,11688,11731,11732 ,0,0,0}, {28618,28624,28616 ,11532,11538,11530 ,0,0,0}, - {28775,28818,28819 ,11689,11732,11733 ,0,0,0}, {28817,28774,28624 ,11731,11688,11538 ,0,0,0}, - {28776,28819,28820 ,11690,11733,11734 ,0,0,0}, {28818,28775,28774 ,11732,11689,11688 ,0,0,0}, - {28777,28820,28821 ,11691,11734,11735 ,0,0,0}, {28819,28776,28775 ,11733,11690,11689 ,0,0,0}, - {28778,28821,28822 ,11692,11735,11736 ,0,0,0}, {28820,28777,28776 ,11734,11691,11690 ,0,0,0}, - {28779,28822,28823 ,11693,11736,11737 ,0,0,0}, {28821,28778,28777 ,11735,11692,11691 ,0,0,0}, - {28646,28823,28780 ,11560,11737,11694 ,0,0,0}, {28779,28778,28822 ,11693,11692,11736 ,0,0,0}, - {28824,28825,28826 ,11738,11739,11740 ,0,0,0}, {28646,28779,28823 ,11560,11693,11737 ,0,0,0}, - {28783,28781,28824 ,11697,11695,11738 ,0,0,0}, {28782,28646,28780 ,11696,11560,11694 ,0,0,0}, - {28784,28824,28827 ,11698,11738,11741 ,0,0,0}, {28783,28782,28781 ,11697,11696,11695 ,0,0,0}, - {28785,28827,28828 ,11699,11741,11742 ,0,0,0}, {28824,28784,28783 ,11738,11698,11697 ,0,0,0}, - {28786,28828,28829 ,11700,11742,11743 ,0,0,0}, {28827,28785,28784 ,11741,11699,11698 ,0,0,0}, - {28787,28829,28830 ,11701,11743,11744 ,0,0,0}, {28828,28786,28785 ,11742,11700,11699 ,0,0,0}, - {28788,28830,28756 ,11702,11744,11670 ,0,0,0}, {28787,28786,28829 ,11701,11700,11743 ,0,0,0}, - {28831,28832,28833 ,11745,11746,11747 ,0,0,0}, {28788,28787,28830 ,11702,11701,11744 ,0,0,0}, - {28789,28754,28834 ,11703,11668,11748 ,0,0,0}, {28755,28788,28756 ,11669,11702,11670 ,0,0,0}, - {28790,28834,28835 ,11704,11748,11749 ,0,0,0}, {28754,28789,28755 ,11668,11703,11669 ,0,0,0}, - {28791,28835,28836 ,11705,11749,11750 ,0,0,0}, {28834,28790,28789 ,11748,11704,11703 ,0,0,0}, - {28792,28836,28837 ,11706,11750,11751 ,0,0,0}, {28835,28791,28790 ,11749,11705,11704 ,0,0,0}, - {28793,28837,28747 ,11707,11751,11661 ,0,0,0}, {28792,28791,28836 ,11706,11705,11750 ,0,0,0}, - {28838,28839,28840 ,11752,11753,11754 ,0,0,0}, {28793,28792,28837 ,11707,11706,11751 ,0,0,0}, - {28794,28748,28841 ,11708,11662,11755 ,0,0,0}, {28746,28793,28747 ,11660,11707,11661 ,0,0,0}, - {28795,28841,28842 ,11709,11755,11756 ,0,0,0}, {28794,28746,28748 ,11708,11660,11662 ,0,0,0}, - {28796,28842,28843 ,11710,11756,11757 ,0,0,0}, {28841,28795,28794 ,11755,11709,11708 ,0,0,0}, - {28797,28843,28844 ,11711,11757,11758 ,0,0,0}, {28842,28796,28795 ,11756,11710,11709 ,0,0,0}, - {28798,28844,28845 ,11712,11758,11759 ,0,0,0}, {28843,28797,28796 ,11757,11711,11710 ,0,0,0}, - {28741,28845,28846 ,11655,11759,11760 ,0,0,0}, {28798,28797,28844 ,11712,11711,11758 ,0,0,0}, - {28802,28846,28800 ,11716,11760,11714 ,0,0,0}, {28741,28798,28845 ,11655,11712,11759 ,0,0,0}, - {28803,28800,28847 ,11717,11714,11761 ,0,0,0}, {28802,28741,28846 ,11716,11655,11760 ,0,0,0}, - {28804,28847,28848 ,11718,11761,11762 ,0,0,0}, {28800,28803,28802 ,11714,11717,11716 ,0,0,0}, - {28805,28848,28849 ,11719,11762,11763 ,0,0,0}, {28847,28804,28803 ,11761,11718,11717 ,0,0,0}, - {28806,28849,28850 ,11720,11763,11764 ,0,0,0}, {28848,28805,28804 ,11762,11719,11718 ,0,0,0}, - {28807,28850,28851 ,11721,11764,11765 ,0,0,0}, {28849,28806,28805 ,11763,11720,11719 ,0,0,0}, - {28808,28851,28852 ,11722,11765,11766 ,0,0,0}, {28850,28807,28806 ,11764,11721,11720 ,0,0,0}, - {28737,28852,28853 ,11651,11766,11767 ,0,0,0}, {28851,28808,28807 ,11765,11722,11721 ,0,0,0}, - {28809,28853,28810 ,11723,11767,11724 ,0,0,0}, {28737,28808,28852 ,11651,11722,11766 ,0,0,0}, - {28854,28717,28722 ,11768,11631,11636 ,0,0,0}, {28809,28737,28853 ,11723,11651,11767 ,0,0,0}, - {28727,28723,28855 ,11641,11637,11769 ,0,0,0}, {28718,28809,28810 ,11632,11723,11724 ,0,0,0}, - {28854,28721,28811 ,11768,11635,11725 ,0,0,0}, {28714,28707,28719 ,11628,11621,11633 ,0,0,0}, - {28811,28720,28705 ,11725,11634,11619 ,0,0,0}, {28854,28811,28717 ,11768,11725,11631 ,0,0,0}, - {28727,28719,28721 ,11641,11633,11635 ,0,0,0}, {28811,28721,28720 ,11725,11635,11634 ,0,0,0}, - {28856,28812,28716 ,11770,11726,11630 ,0,0,0}, {28812,28813,28701 ,11726,11727,11615 ,0,0,0}, - {28706,28708,28712 ,11620,11622,11626 ,0,0,0}, {28708,28714,28716 ,11622,11628,11630 ,0,0,0}, - {28856,28813,28812 ,11770,11727,11726 ,0,0,0}, {28760,28816,28771 ,11674,11730,11685 ,0,0,0}, - {28628,28627,28761 ,11542,11541,11675 ,0,0,0}, {28631,28635,28857 ,11545,11549,11771 ,0,0,0}, - {28816,28617,28773 ,11730,11531,11687 ,0,0,0}, {28760,28858,28816 ,11674,11772,11730 ,0,0,0}, - {28859,28860,28861 ,11773,11774,11775 ,0,0,0}, {28629,28617,28816 ,11543,11531,11730 ,0,0,0}, - {28621,28859,28817 ,11535,11773,11731 ,0,0,0}, {28622,28618,28617 ,11536,11532,11531 ,0,0,0}, - {28859,28862,28818 ,11773,11776,11732 ,0,0,0}, {28621,28817,28618 ,11535,11731,11532 ,0,0,0}, - {28862,28863,28819 ,11776,11777,11733 ,0,0,0}, {28859,28818,28817 ,11773,11732,11731 ,0,0,0}, - {28863,28864,28820 ,11777,11778,11734 ,0,0,0}, {28862,28819,28818 ,11776,11733,11732 ,0,0,0}, - {28864,28865,28821 ,11778,11779,11735 ,0,0,0}, {28863,28820,28819 ,11777,11734,11733 ,0,0,0}, - {28865,28866,28822 ,11779,11780,11736 ,0,0,0}, {28864,28821,28820 ,11778,11735,11734 ,0,0,0}, - {28866,28867,28823 ,11780,11781,11737 ,0,0,0}, {28865,28822,28821 ,11779,11736,11735 ,0,0,0}, - {28867,28868,28780 ,11781,11782,11694 ,0,0,0}, {28866,28823,28822 ,11780,11737,11736 ,0,0,0}, - {28868,28825,28781 ,11782,11739,11695 ,0,0,0}, {28780,28823,28867 ,11694,11737,11781 ,0,0,0}, - {28869,28870,28871 ,11783,11784,11785 ,0,0,0}, {28781,28780,28868 ,11695,11694,11782 ,0,0,0}, - {28826,28869,28827 ,11740,11783,11741 ,0,0,0}, {28825,28824,28781 ,11739,11738,11695 ,0,0,0}, - {28869,28872,28828 ,11783,11786,11742 ,0,0,0}, {28826,28827,28824 ,11740,11741,11738 ,0,0,0}, - {28872,28873,28829 ,11786,11787,11743 ,0,0,0}, {28869,28828,28827 ,11783,11742,11741 ,0,0,0}, - {28873,28874,28830 ,11787,11788,11744 ,0,0,0}, {28872,28829,28828 ,11786,11743,11742 ,0,0,0}, - {28874,28875,28756 ,11788,11789,11670 ,0,0,0}, {28873,28830,28829 ,11787,11744,11743 ,0,0,0}, - {28754,28875,28876 ,11668,11789,11790 ,0,0,0}, {28756,28830,28874 ,11670,11744,11788 ,0,0,0}, - {28876,28831,28834 ,11790,11745,11748 ,0,0,0}, {28875,28754,28756 ,11789,11668,11670 ,0,0,0}, - {28831,28877,28835 ,11745,11791,11749 ,0,0,0}, {28876,28834,28754 ,11790,11748,11668 ,0,0,0}, - {28877,28878,28836 ,11791,11792,11750 ,0,0,0}, {28831,28835,28834 ,11745,11749,11748 ,0,0,0}, - {28878,28879,28837 ,11792,11793,11751 ,0,0,0}, {28877,28836,28835 ,11791,11750,11749 ,0,0,0}, - {28879,28880,28747 ,11793,11794,11661 ,0,0,0}, {28878,28837,28836 ,11792,11751,11750 ,0,0,0}, - {28880,28881,28748 ,11794,11795,11662 ,0,0,0}, {28747,28837,28879 ,11661,11751,11793 ,0,0,0}, - {28881,28838,28841 ,11795,11752,11755 ,0,0,0}, {28748,28747,28880 ,11662,11661,11794 ,0,0,0}, - {28838,28882,28842 ,11752,11796,11756 ,0,0,0}, {28881,28841,28748 ,11795,11755,11662 ,0,0,0}, - {28882,28883,28843 ,11796,11797,11757 ,0,0,0}, {28838,28842,28841 ,11752,11756,11755 ,0,0,0}, - {28883,28884,28844 ,11797,11798,11758 ,0,0,0}, {28882,28843,28842 ,11796,11757,11756 ,0,0,0}, - {28884,28885,28845 ,11798,11799,11759 ,0,0,0}, {28883,28844,28843 ,11797,11758,11757 ,0,0,0}, - {28885,28801,28846 ,11799,11715,11760 ,0,0,0}, {28845,28844,28884 ,11759,11758,11798 ,0,0,0}, - {28886,28887,28888 ,11800,11801,11802 ,0,0,0}, {28846,28845,28885 ,11760,11759,11799 ,0,0,0}, - {28799,28886,28847 ,11713,11800,11761 ,0,0,0}, {28801,28800,28846 ,11715,11714,11760 ,0,0,0}, - {28886,28889,28848 ,11800,11803,11762 ,0,0,0}, {28799,28847,28800 ,11713,11761,11714 ,0,0,0}, - {28889,28890,28849 ,11803,11804,11763 ,0,0,0}, {28886,28848,28847 ,11800,11762,11761 ,0,0,0}, - {28890,28891,28850 ,11804,11805,11764 ,0,0,0}, {28889,28849,28848 ,11803,11763,11762 ,0,0,0}, - {28891,28892,28851 ,11805,11806,11765 ,0,0,0}, {28890,28850,28849 ,11804,11764,11763 ,0,0,0}, - {28892,28893,28852 ,11806,11807,11766 ,0,0,0}, {28891,28851,28850 ,11805,11765,11764 ,0,0,0}, - {28893,28894,28853 ,11807,11808,11767 ,0,0,0}, {28892,28852,28851 ,11806,11766,11765 ,0,0,0}, - {28894,28895,28810 ,11808,11809,11724 ,0,0,0}, {28893,28853,28852 ,11807,11767,11766 ,0,0,0}, - {28895,28896,28722 ,11809,11810,11636 ,0,0,0}, {28894,28810,28853 ,11808,11724,11767 ,0,0,0}, - {28896,28726,28854 ,11810,11640,11768 ,0,0,0}, {28722,28810,28895 ,11636,11724,11809 ,0,0,0}, - {28897,28719,28727 ,11811,11633,11641 ,0,0,0}, {28722,28896,28854 ,11636,11810,11768 ,0,0,0}, - {28726,28723,28727 ,11640,11637,11641 ,0,0,0}, {28854,28726,28721 ,11768,11640,11635 ,0,0,0}, - {28898,28716,28715 ,11812,11630,11629 ,0,0,0}, {28708,28716,28812 ,11622,11630,11726 ,0,0,0}, - {28707,28714,28708 ,11621,11628,11622 ,0,0,0}, {28897,28715,28714 ,11811,11629,11628 ,0,0,0}, - {28856,28716,28898 ,11770,11630,11812 ,0,0,0}, {28858,28760,28627 ,11772,11674,11541 ,0,0,0}, - {28633,28626,28766 ,11547,11540,11680 ,0,0,0}, {28629,28899,28900 ,11543,11813,11814 ,0,0,0}, - {28858,28629,28816 ,11772,11543,11730 ,0,0,0}, {28901,28858,28627 ,11815,11772,11541 ,0,0,0}, - {28622,28900,28902 ,11536,11814,11816 ,0,0,0}, {28858,28899,28629 ,11772,11813,11543 ,0,0,0}, - {28621,28902,28860 ,11535,11816,11774 ,0,0,0}, {28900,28622,28629 ,11814,11536,11543 ,0,0,0}, - {28903,28862,28861 ,11817,11776,11775 ,0,0,0}, {28902,28621,28622 ,11816,11535,11536 ,0,0,0}, - {28904,28863,28903 ,11818,11777,11817 ,0,0,0}, {28860,28859,28621 ,11774,11773,11535 ,0,0,0}, - {28905,28906,28907 ,11819,11820,11821 ,0,0,0}, {28861,28862,28859 ,11775,11776,11773 ,0,0,0}, - {28904,28905,28864 ,11818,11819,11778 ,0,0,0}, {28903,28863,28862 ,11817,11777,11776 ,0,0,0}, - {28905,28908,28865 ,11819,11822,11779 ,0,0,0}, {28904,28864,28863 ,11818,11778,11777 ,0,0,0}, - {28908,28909,28866 ,11822,11823,11780 ,0,0,0}, {28905,28865,28864 ,11819,11779,11778 ,0,0,0}, - {28909,28910,28867 ,11823,11824,11781 ,0,0,0}, {28908,28866,28865 ,11822,11780,11779 ,0,0,0}, - {28910,28911,28868 ,11824,11825,11782 ,0,0,0}, {28909,28867,28866 ,11823,11781,11780 ,0,0,0}, - {28825,28911,28912 ,11739,11825,11826 ,0,0,0}, {28910,28868,28867 ,11824,11782,11781 ,0,0,0}, - {28826,28912,28870 ,11740,11826,11784 ,0,0,0}, {28911,28825,28868 ,11825,11739,11782 ,0,0,0}, - {28913,28914,28915 ,11827,11828,11829 ,0,0,0}, {28912,28826,28825 ,11826,11740,11739 ,0,0,0}, - {28871,28913,28872 ,11785,11827,11786 ,0,0,0}, {28870,28869,28826 ,11784,11783,11740 ,0,0,0}, - {28913,28916,28873 ,11827,11830,11787 ,0,0,0}, {28871,28872,28869 ,11785,11786,11783 ,0,0,0}, - {28916,28917,28874 ,11830,11831,11788 ,0,0,0}, {28913,28873,28872 ,11827,11787,11786 ,0,0,0}, - {28875,28917,28918 ,11789,11831,11832 ,0,0,0}, {28916,28874,28873 ,11830,11788,11787 ,0,0,0}, - {28876,28918,28832 ,11790,11832,11746 ,0,0,0}, {28875,28874,28917 ,11789,11788,11831 ,0,0,0}, - {28919,28920,28921 ,11833,11834,11835 ,0,0,0}, {28918,28876,28875 ,11832,11790,11789 ,0,0,0}, - {28833,28919,28877 ,11747,11833,11791 ,0,0,0}, {28832,28831,28876 ,11746,11745,11790 ,0,0,0}, - {28919,28922,28878 ,11833,11836,11792 ,0,0,0}, {28833,28877,28831 ,11747,11791,11745 ,0,0,0}, - {28922,28923,28879 ,11836,11837,11793 ,0,0,0}, {28919,28878,28877 ,11833,11792,11791 ,0,0,0}, - {28923,28924,28880 ,11837,11838,11794 ,0,0,0}, {28922,28879,28878 ,11836,11793,11792 ,0,0,0}, - {28881,28924,28839 ,11795,11838,11753 ,0,0,0}, {28880,28879,28923 ,11794,11793,11837 ,0,0,0}, - {28925,28926,28927 ,11839,11840,11841 ,0,0,0}, {28924,28881,28880 ,11838,11795,11794 ,0,0,0}, - {28840,28925,28882 ,11754,11839,11796 ,0,0,0}, {28839,28838,28881 ,11753,11752,11795 ,0,0,0}, - {28925,28928,28883 ,11839,11842,11797 ,0,0,0}, {28840,28882,28838 ,11754,11796,11752 ,0,0,0}, - {28928,28929,28884 ,11842,11843,11798 ,0,0,0}, {28925,28883,28882 ,11839,11797,11796 ,0,0,0}, - {28929,28930,28885 ,11843,11844,11799 ,0,0,0}, {28928,28884,28883 ,11842,11798,11797 ,0,0,0}, - {28801,28930,28931 ,11715,11844,11845 ,0,0,0}, {28929,28885,28884 ,11843,11799,11798 ,0,0,0}, - {28799,28931,28887 ,11713,11845,11801 ,0,0,0}, {28930,28801,28885 ,11844,11715,11799 ,0,0,0}, - {28932,28889,28888 ,11846,11803,11802 ,0,0,0}, {28931,28799,28801 ,11845,11713,11715 ,0,0,0}, - {28933,28934,28935 ,11847,11848,11849 ,0,0,0}, {28887,28886,28799 ,11801,11800,11713 ,0,0,0}, - {28932,28933,28890 ,11846,11847,11804 ,0,0,0}, {28888,28889,28886 ,11802,11803,11800 ,0,0,0}, - {28933,28936,28891 ,11847,11850,11805 ,0,0,0}, {28932,28890,28889 ,11846,11804,11803 ,0,0,0}, - {28936,28937,28892 ,11850,11851,11806 ,0,0,0}, {28933,28891,28890 ,11847,11805,11804 ,0,0,0}, - {28937,28938,28893 ,11851,11852,11807 ,0,0,0}, {28936,28892,28891 ,11850,11806,11805 ,0,0,0}, - {28938,28939,28894 ,11852,11853,11808 ,0,0,0}, {28937,28893,28892 ,11851,11807,11806 ,0,0,0}, - {28939,28940,28895 ,11853,11854,11809 ,0,0,0}, {28938,28894,28893 ,11852,11808,11807 ,0,0,0}, - {28940,28724,28896 ,11854,11638,11810 ,0,0,0}, {28939,28895,28894 ,11853,11809,11808 ,0,0,0}, - {28726,28724,28723 ,11640,11638,11637 ,0,0,0}, {28895,28940,28896 ,11809,11854,11810 ,0,0,0}, - {28941,28715,28897 ,11855,11629,11811 ,0,0,0}, {28726,28896,28724 ,11640,11810,11638 ,0,0,0}, - {28942,28715,28941 ,11856,11629,11855 ,0,0,0}, {28943,28898,28715 ,11857,11812,11629 ,0,0,0}, - {28719,28897,28714 ,11633,11811,11628 ,0,0,0}, {28855,28941,28897 ,11769,11855,11811 ,0,0,0}, - {28942,28943,28715 ,11856,11857,11629 ,0,0,0}, {28901,28627,28626 ,11815,11541,11540 ,0,0,0}, - {28630,28632,28815 ,11544,11546,11729 ,0,0,0}, {28899,28944,28945 ,11813,11858,11859 ,0,0,0}, - {28901,28899,28858 ,11815,11813,11772 ,0,0,0}, {28626,28946,28901 ,11540,11860,11815 ,0,0,0}, - {28900,28945,28947 ,11814,11859,11861 ,0,0,0}, {28901,28944,28899 ,11815,11858,11813 ,0,0,0}, - {28902,28947,28948 ,11816,11861,11862 ,0,0,0}, {28899,28945,28900 ,11813,11859,11814 ,0,0,0}, - {28860,28948,28949 ,11774,11862,11863 ,0,0,0}, {28900,28947,28902 ,11814,11861,11816 ,0,0,0}, - {28861,28949,28950 ,11775,11863,11864 ,0,0,0}, {28902,28948,28860 ,11816,11862,11774 ,0,0,0}, - {28903,28950,28951 ,11817,11864,11865 ,0,0,0}, {28860,28949,28861 ,11774,11863,11775 ,0,0,0}, - {28904,28951,28906 ,11818,11865,11820 ,0,0,0}, {28950,28903,28861 ,11864,11817,11775 ,0,0,0}, - {28952,28908,28907 ,11866,11822,11821 ,0,0,0}, {28951,28904,28903 ,11865,11818,11817 ,0,0,0}, - {28953,28954,28952 ,11867,11868,11866 ,0,0,0}, {28906,28905,28904 ,11820,11819,11818 ,0,0,0}, - {28952,28954,28909 ,11866,11868,11823 ,0,0,0}, {28907,28908,28905 ,11821,11822,11819 ,0,0,0}, - {28954,28955,28910 ,11868,11869,11824 ,0,0,0}, {28952,28909,28908 ,11866,11823,11822 ,0,0,0}, - {28911,28955,28956 ,11825,11869,11870 ,0,0,0}, {28954,28910,28909 ,11868,11824,11823 ,0,0,0}, - {28912,28956,28957 ,11826,11870,11871 ,0,0,0}, {28910,28955,28911 ,11824,11869,11825 ,0,0,0}, - {28870,28957,28958 ,11784,11871,11872 ,0,0,0}, {28911,28956,28912 ,11825,11870,11826 ,0,0,0}, - {28871,28958,28914 ,11785,11872,11828 ,0,0,0}, {28957,28870,28912 ,11871,11784,11826 ,0,0,0}, - {28959,28960,28915 ,11873,11874,11829 ,0,0,0}, {28958,28871,28870 ,11872,11785,11784 ,0,0,0}, - {28915,28960,28916 ,11829,11874,11830 ,0,0,0}, {28914,28913,28871 ,11828,11827,11785 ,0,0,0}, - {28960,28961,28917 ,11874,11875,11831 ,0,0,0}, {28915,28916,28913 ,11829,11830,11827 ,0,0,0}, - {28918,28961,28962 ,11832,11875,11876 ,0,0,0}, {28960,28917,28916 ,11874,11831,11830 ,0,0,0}, - {28832,28962,28963 ,11746,11876,11877 ,0,0,0}, {28917,28961,28918 ,11831,11875,11832 ,0,0,0}, - {28833,28963,28920 ,11747,11877,11834 ,0,0,0}, {28962,28832,28918 ,11876,11746,11832 ,0,0,0}, - {28964,28965,28921 ,11878,11879,11835 ,0,0,0}, {28963,28833,28832 ,11877,11747,11746 ,0,0,0}, - {28921,28965,28922 ,11835,11879,11836 ,0,0,0}, {28920,28919,28833 ,11834,11833,11747 ,0,0,0}, - {28965,28966,28923 ,11879,11880,11837 ,0,0,0}, {28921,28922,28919 ,11835,11836,11833 ,0,0,0}, - {28924,28966,28967 ,11838,11880,11881 ,0,0,0}, {28965,28923,28922 ,11879,11837,11836 ,0,0,0}, - {28839,28967,28968 ,11753,11881,11882 ,0,0,0}, {28923,28966,28924 ,11837,11880,11838 ,0,0,0}, - {28840,28968,28926 ,11754,11882,11840 ,0,0,0}, {28967,28839,28924 ,11881,11753,11838 ,0,0,0}, - {28969,28970,28927 ,11883,11884,11841 ,0,0,0}, {28968,28840,28839 ,11882,11754,11753 ,0,0,0}, - {28927,28970,28928 ,11841,11884,11842 ,0,0,0}, {28926,28925,28840 ,11840,11839,11754 ,0,0,0}, - {28970,28971,28929 ,11884,11885,11843 ,0,0,0}, {28927,28928,28925 ,11841,11842,11839 ,0,0,0}, - {28930,28971,28972 ,11844,11885,11886 ,0,0,0}, {28970,28929,28928 ,11884,11843,11842 ,0,0,0}, - {28931,28972,28973 ,11845,11886,11887 ,0,0,0}, {28929,28971,28930 ,11843,11885,11844 ,0,0,0}, - {28887,28973,28974 ,11801,11887,11888 ,0,0,0}, {28930,28972,28931 ,11844,11886,11845 ,0,0,0}, - {28888,28974,28975 ,11802,11888,11889 ,0,0,0}, {28931,28973,28887 ,11845,11887,11801 ,0,0,0}, - {28932,28975,28934 ,11846,11889,11848 ,0,0,0}, {28974,28888,28887 ,11888,11802,11801 ,0,0,0}, - {28976,28936,28935 ,11890,11850,11849 ,0,0,0}, {28975,28932,28888 ,11889,11846,11802 ,0,0,0}, - {28977,28978,28976 ,11891,11892,11890 ,0,0,0}, {28934,28933,28932 ,11848,11847,11846 ,0,0,0}, - {28976,28978,28937 ,11890,11892,11851 ,0,0,0}, {28935,28936,28933 ,11849,11850,11847 ,0,0,0}, - {28978,28979,28938 ,11892,11893,11852 ,0,0,0}, {28976,28937,28936 ,11890,11851,11850 ,0,0,0}, - {28979,28980,28939 ,11893,11894,11853 ,0,0,0}, {28978,28938,28937 ,11892,11852,11851 ,0,0,0}, - {28980,28981,28940 ,11894,11895,11854 ,0,0,0}, {28979,28939,28938 ,11893,11853,11852 ,0,0,0}, - {28724,28981,28725 ,11638,11895,11639 ,0,0,0}, {28980,28940,28939 ,11894,11854,11853 ,0,0,0}, - {28725,28982,28723 ,11639,11896,11637 ,0,0,0}, {28724,28940,28981 ,11638,11854,11895 ,0,0,0}, - {28983,28941,28731 ,11897,11855,11645 ,0,0,0}, {28983,28984,28941 ,11897,11898,11855 ,0,0,0}, - {28727,28855,28897 ,11641,11769,11811 ,0,0,0}, {28982,28731,28855 ,11896,11645,11769 ,0,0,0}, - {28942,28941,28984 ,11856,11855,11898 ,0,0,0}, {28632,28946,28626 ,11546,11860,11540 ,0,0,0}, - {28985,28631,28630 ,11899,11545,11544 ,0,0,0}, {28986,28944,28946 ,11900,11858,11860 ,0,0,0}, - {28946,28944,28901 ,11860,11858,11815 ,0,0,0}, {28946,28857,28986 ,11860,11771,11900 ,0,0,0}, - {28987,28945,28944 ,11901,11859,11858 ,0,0,0}, {28944,28986,28987 ,11858,11900,11901 ,0,0,0}, - {28988,28947,28945 ,11902,11861,11859 ,0,0,0}, {28945,28987,28988 ,11859,11901,11902 ,0,0,0}, - {28989,28948,28947 ,11903,11862,11861 ,0,0,0}, {28947,28988,28989 ,11861,11902,11903 ,0,0,0}, - {28990,28949,28948 ,11904,11863,11862 ,0,0,0}, {28948,28989,28990 ,11862,11903,11904 ,0,0,0}, - {28991,28950,28949 ,11905,11864,11863 ,0,0,0}, {28949,28990,28991 ,11863,11904,11905 ,0,0,0}, - {28992,28951,28950 ,11906,11865,11864 ,0,0,0}, {28950,28991,28992 ,11864,11905,11906 ,0,0,0}, - {28993,28906,28951 ,11907,11820,11865 ,0,0,0}, {28951,28992,28993 ,11865,11906,11907 ,0,0,0}, - {28994,28907,28906 ,11908,11821,11820 ,0,0,0}, {28906,28993,28994 ,11820,11907,11908 ,0,0,0}, - {28995,28952,28907 ,11909,11866,11821 ,0,0,0}, {28994,28995,28907 ,11908,11909,11821 ,0,0,0}, - {28996,28997,28998 ,11910,11911,11912 ,0,0,0}, {28995,28953,28952 ,11909,11867,11866 ,0,0,0}, - {28999,28955,28954 ,11913,11869,11868 ,0,0,0}, {28953,28999,28954 ,11867,11913,11868 ,0,0,0}, - {29000,28956,28955 ,11914,11870,11869 ,0,0,0}, {28955,28999,29000 ,11869,11913,11914 ,0,0,0}, - {29001,28957,28956 ,11915,11871,11870 ,0,0,0}, {28956,29000,29001 ,11870,11914,11915 ,0,0,0}, - {29002,28958,28957 ,11916,11872,11871 ,0,0,0}, {28957,29001,29002 ,11871,11915,11916 ,0,0,0}, - {29003,28914,28958 ,11917,11828,11872 ,0,0,0}, {28958,29002,29003 ,11872,11916,11917 ,0,0,0}, - {29004,28915,28914 ,11918,11829,11828 ,0,0,0}, {29003,29004,28914 ,11917,11918,11828 ,0,0,0}, - {29005,28959,29006 ,11919,11873,11920 ,0,0,0}, {29004,28959,28915 ,11918,11873,11829 ,0,0,0}, - {29005,28961,28960 ,11919,11875,11874 ,0,0,0}, {28959,29005,28960 ,11873,11919,11874 ,0,0,0}, - {29007,28962,28961 ,11921,11876,11875 ,0,0,0}, {28961,29005,29007 ,11875,11919,11921 ,0,0,0}, - {29008,28963,28962 ,11922,11877,11876 ,0,0,0}, {28962,29007,29008 ,11876,11921,11922 ,0,0,0}, - {29009,28920,28963 ,11923,11834,11877 ,0,0,0}, {28963,29008,29009 ,11877,11922,11923 ,0,0,0}, - {29010,28921,28920 ,11924,11835,11834 ,0,0,0}, {29009,29010,28920 ,11923,11924,11834 ,0,0,0}, - {29011,29012,29013 ,11925,11926,11927 ,0,0,0}, {29010,28964,28921 ,11924,11878,11835 ,0,0,0}, - {29014,28966,28965 ,11928,11880,11879 ,0,0,0}, {28964,29014,28965 ,11878,11928,11879 ,0,0,0}, - {29015,28967,28966 ,11929,11881,11880 ,0,0,0}, {28966,29014,29015 ,11880,11928,11929 ,0,0,0}, - {29016,28968,28967 ,11930,11882,11881 ,0,0,0}, {28967,29015,29016 ,11881,11929,11930 ,0,0,0}, - {29017,28926,28968 ,11931,11840,11882 ,0,0,0}, {28968,29016,29017 ,11882,11930,11931 ,0,0,0}, - {29018,28927,28926 ,11932,11841,11840 ,0,0,0}, {29017,29018,28926 ,11931,11932,11840 ,0,0,0}, - {28970,29019,28971 ,11884,11933,11885 ,0,0,0}, {29018,28969,28927 ,11932,11883,11841 ,0,0,0}, - {29020,29021,29019 ,11934,11935,11933 ,0,0,0}, {28969,29019,28970 ,11883,11933,11884 ,0,0,0}, - {29021,28972,28971 ,11935,11886,11885 ,0,0,0}, {28971,29019,29021 ,11885,11933,11935 ,0,0,0}, - {29022,28973,28972 ,11936,11887,11886 ,0,0,0}, {28972,29021,29022 ,11886,11935,11936 ,0,0,0}, - {29023,28974,28973 ,11937,11888,11887 ,0,0,0}, {28973,29022,29023 ,11887,11936,11937 ,0,0,0}, - {29024,28975,28974 ,11938,11889,11888 ,0,0,0}, {28974,29023,29024 ,11888,11937,11938 ,0,0,0}, - {29025,28934,28975 ,11939,11848,11889 ,0,0,0}, {28975,29024,29025 ,11889,11938,11939 ,0,0,0}, - {29026,28935,28934 ,11940,11849,11848 ,0,0,0}, {28934,29025,29026 ,11848,11939,11940 ,0,0,0}, - {29027,28976,28935 ,11941,11890,11849 ,0,0,0}, {29026,29027,28935 ,11940,11941,11849 ,0,0,0}, - {28978,29028,28979 ,11892,11942,11893 ,0,0,0}, {29027,28977,28976 ,11941,11891,11890 ,0,0,0}, - {28979,29029,28980 ,11893,11943,11894 ,0,0,0}, {28977,29028,28978 ,11891,11942,11892 ,0,0,0}, - {28980,29030,28981 ,11894,11944,11895 ,0,0,0}, {29028,29029,28979 ,11942,11943,11893 ,0,0,0}, - {28981,28728,28725 ,11895,11642,11639 ,0,0,0}, {29029,29030,28980 ,11943,11944,11894 ,0,0,0}, - {28733,28732,28729 ,11647,11646,11643 ,0,0,0}, {29030,28728,28981 ,11944,11642,11895 ,0,0,0}, - {28729,28982,28725 ,11643,11896,11639 ,0,0,0}, {28855,28731,28941 ,11769,11645,11855 ,0,0,0}, - {28723,28982,28855 ,11637,11896,11769 ,0,0,0}, {28982,28729,28732 ,11896,11643,11646 ,0,0,0}, - {28983,28731,28730 ,11897,11645,11644 ,0,0,0}, {28631,28857,28632 ,11545,11771,11546 ,0,0,0}, - {28985,28638,28636 ,11899,11552,11550 ,0,0,0}, {28986,28857,29031 ,11900,11771,11945 ,0,0,0}, - {28632,28857,28946 ,11546,11771,11860 ,0,0,0}, {28857,28635,29031 ,11771,11549,11945 ,0,0,0}, - {28987,28986,29032 ,11901,11900,11946 ,0,0,0}, {28986,29031,29032 ,11900,11945,11946 ,0,0,0}, - {28988,28987,29033 ,11902,11901,11947 ,0,0,0}, {28987,29032,29033 ,11901,11946,11947 ,0,0,0}, - {28989,28988,29034 ,11903,11902,11948 ,0,0,0}, {28988,29033,29034 ,11902,11947,11948 ,0,0,0}, - {28990,28989,29035 ,11904,11903,11949 ,0,0,0}, {28989,29034,29035 ,11903,11948,11949 ,0,0,0}, - {28991,28990,29036 ,11905,11904,11950 ,0,0,0}, {28990,29035,29036 ,11904,11949,11950 ,0,0,0}, - {28992,28991,29037 ,11906,11905,11951 ,0,0,0}, {28991,29036,29037 ,11905,11950,11951 ,0,0,0}, - {28993,28992,29038 ,11907,11906,11952 ,0,0,0}, {28992,29037,29038 ,11906,11951,11952 ,0,0,0}, - {28994,28993,29039 ,11908,11907,11953 ,0,0,0}, {28993,29038,29039 ,11907,11952,11953 ,0,0,0}, - {28995,28994,29040 ,11909,11908,11954 ,0,0,0}, {28994,29039,29040 ,11908,11953,11954 ,0,0,0}, - {28953,28995,29041 ,11867,11909,11955 ,0,0,0}, {28995,29040,29041 ,11909,11954,11955 ,0,0,0}, - {28999,28953,28996 ,11913,11867,11910 ,0,0,0}, {29041,28996,28953 ,11955,11910,11867 ,0,0,0}, - {29000,28999,28998 ,11914,11913,11912 ,0,0,0}, {28999,28996,28998 ,11913,11910,11912 ,0,0,0}, - {29001,29000,29042 ,11915,11914,11956 ,0,0,0}, {29000,28998,29042 ,11914,11912,11956 ,0,0,0}, - {29002,29001,29043 ,11916,11915,11957 ,0,0,0}, {29001,29042,29043 ,11915,11956,11957 ,0,0,0}, - {29003,29002,29044 ,11917,11916,11958 ,0,0,0}, {29002,29043,29044 ,11916,11957,11958 ,0,0,0}, - {29004,29003,29045 ,11918,11917,11959 ,0,0,0}, {29003,29044,29045 ,11917,11958,11959 ,0,0,0}, - {28959,29004,29046 ,11873,11918,11960 ,0,0,0}, {29004,29045,29046 ,11918,11959,11960 ,0,0,0}, - {29046,29047,29006 ,11960,11961,11920 ,0,0,0}, {29046,29006,28959 ,11960,11920,11873 ,0,0,0}, - {29007,29005,29048 ,11921,11919,11962 ,0,0,0}, {29005,29006,29048 ,11919,11920,11962 ,0,0,0}, - {29008,29007,29049 ,11922,11921,11963 ,0,0,0}, {29007,29048,29049 ,11921,11962,11963 ,0,0,0}, - {29009,29008,29050 ,11923,11922,11964 ,0,0,0}, {29008,29049,29050 ,11922,11963,11964 ,0,0,0}, - {29010,29009,29051 ,11924,11923,11965 ,0,0,0}, {29009,29050,29051 ,11923,11964,11965 ,0,0,0}, - {28964,29010,29052 ,11878,11924,11966 ,0,0,0}, {29010,29051,29052 ,11924,11965,11966 ,0,0,0}, - {29014,28964,29011 ,11928,11878,11925 ,0,0,0}, {29052,29011,28964 ,11966,11925,11878 ,0,0,0}, - {29015,29014,29013 ,11929,11928,11927 ,0,0,0}, {29014,29011,29013 ,11928,11925,11927 ,0,0,0}, - {29016,29015,29053 ,11930,11929,11967 ,0,0,0}, {29015,29013,29053 ,11929,11927,11967 ,0,0,0}, - {29017,29016,29054 ,11931,11930,11968 ,0,0,0}, {29016,29053,29054 ,11930,11967,11968 ,0,0,0}, - {29018,29017,29055 ,11932,11931,11969 ,0,0,0}, {29017,29054,29055 ,11931,11968,11969 ,0,0,0}, - {28969,29018,29056 ,11883,11932,11970 ,0,0,0}, {29018,29055,29056 ,11932,11969,11970 ,0,0,0}, - {29019,28969,29057 ,11933,11883,11971 ,0,0,0}, {28969,29056,29057 ,11883,11970,11971 ,0,0,0}, - {29020,29057,29058 ,11934,11971,11972 ,0,0,0}, {29057,29020,29019 ,11971,11934,11933 ,0,0,0}, - {29022,29021,29059 ,11936,11935,11973 ,0,0,0}, {29021,29020,29059 ,11935,11934,11973 ,0,0,0}, - {29023,29022,29060 ,11937,11936,11974 ,0,0,0}, {29022,29059,29060 ,11936,11973,11974 ,0,0,0}, - {29024,29023,29061 ,11938,11937,11975 ,0,0,0}, {29023,29060,29061 ,11937,11974,11975 ,0,0,0}, - {29025,29024,29062 ,11939,11938,11976 ,0,0,0}, {29024,29061,29062 ,11938,11975,11976 ,0,0,0}, - {29026,29025,29063 ,11940,11939,11977 ,0,0,0}, {29025,29062,29063 ,11939,11976,11977 ,0,0,0}, - {29027,29026,29064 ,11941,11940,11978 ,0,0,0}, {29026,29063,29064 ,11940,11977,11978 ,0,0,0}, - {28977,29027,29065 ,11891,11941,11979 ,0,0,0}, {29027,29064,29065 ,11941,11978,11979 ,0,0,0}, - {29028,28977,29066 ,11942,11891,11980 ,0,0,0}, {28977,29065,29066 ,11891,11979,11980 ,0,0,0}, - {29029,29028,29067 ,11943,11942,11981 ,0,0,0}, {29028,29066,29067 ,11942,11980,11981 ,0,0,0}, - {29030,29029,29068 ,11944,11943,11982 ,0,0,0}, {29029,29067,29068 ,11943,11981,11982 ,0,0,0}, - {28728,29030,29069 ,11642,11944,11983 ,0,0,0}, {29030,29068,29069 ,11944,11982,11983 ,0,0,0}, - {29070,28729,28728 ,11984,11643,11642 ,0,0,0}, {29070,28728,29069 ,11984,11642,11983 ,0,0,0}, - {28982,28732,28731 ,11896,11646,11645 ,0,0,0}, {29070,28733,28729 ,11984,11647,11643 ,0,0,0}, - {28730,28732,28735 ,11644,11646,11649 ,0,0,0}, {28636,28631,28985 ,11550,11545,11899 ,0,0,0}, - {28637,28634,28636 ,11551,11548,11550 ,0,0,0}, {28634,29071,28635 ,11548,11985,11549 ,0,0,0}, - {28635,29071,29031 ,11549,11985,11945 ,0,0,0}, {29071,29072,29031 ,11985,11986,11945 ,0,0,0}, - {29031,29072,29032 ,11945,11986,11946 ,0,0,0}, {29072,29073,29032 ,11986,11987,11946 ,0,0,0}, - {29032,29073,29033 ,11946,11987,11947 ,0,0,0}, {29073,29074,29033 ,11987,11988,11947 ,0,0,0}, - {29033,29074,29034 ,11947,11988,11948 ,0,0,0}, {29074,29075,29034 ,11988,11989,11948 ,0,0,0}, - {29034,29075,29035 ,11948,11989,11949 ,0,0,0}, {29075,29076,29035 ,11989,11990,11949 ,0,0,0}, - {29035,29076,29036 ,11949,11990,11950 ,0,0,0}, {29076,29077,29036 ,11990,11991,11950 ,0,0,0}, - {29036,29077,29037 ,11950,11991,11951 ,0,0,0}, {29077,29078,29037 ,11991,11992,11951 ,0,0,0}, - {29078,29079,29038 ,11992,11993,11952 ,0,0,0}, {29078,29038,29037 ,11992,11952,11951 ,0,0,0}, - {29079,29080,29039 ,11993,11994,11953 ,0,0,0}, {29079,29039,29038 ,11993,11953,11952 ,0,0,0}, - {29080,29081,29040 ,11994,11995,11954 ,0,0,0}, {29080,29040,29039 ,11994,11954,11953 ,0,0,0}, - {29081,29082,29041 ,11995,11996,11955 ,0,0,0}, {29081,29041,29040 ,11995,11955,11954 ,0,0,0}, - {29082,29083,28996 ,11996,11997,11910 ,0,0,0}, {29082,28996,29041 ,11996,11910,11955 ,0,0,0}, - {28997,28996,29083 ,11911,11910,11997 ,0,0,0}, {28997,29084,28998 ,11911,11998,11912 ,0,0,0}, - {28998,29084,29042 ,11912,11998,11956 ,0,0,0}, {29084,29085,29042 ,11998,11999,11956 ,0,0,0}, - {29042,29085,29043 ,11956,11999,11957 ,0,0,0}, {29085,29086,29043 ,11999,12000,11957 ,0,0,0}, - {29086,29087,29044 ,12000,12001,11958 ,0,0,0}, {29086,29044,29043 ,12000,11958,11957 ,0,0,0}, - {29087,29088,29045 ,12001,12002,11959 ,0,0,0}, {29087,29045,29044 ,12001,11959,11958 ,0,0,0}, - {29088,29047,29046 ,12002,11961,11960 ,0,0,0}, {29088,29046,29045 ,12002,11960,11959 ,0,0,0}, - {29047,29089,29006 ,11961,12003,11920 ,0,0,0}, {29089,29090,29006 ,12003,12004,11920 ,0,0,0}, - {29006,29090,29048 ,11920,12004,11962 ,0,0,0}, {29090,29091,29048 ,12004,12005,11962 ,0,0,0}, - {29048,29091,29049 ,11962,12005,11963 ,0,0,0}, {29091,29092,29049 ,12005,12006,11963 ,0,0,0}, - {29092,29093,29050 ,12006,12007,11964 ,0,0,0}, {29092,29050,29049 ,12006,11964,11963 ,0,0,0}, - {29093,29094,29051 ,12007,12008,11965 ,0,0,0}, {29093,29051,29050 ,12007,11965,11964 ,0,0,0}, - {29094,29095,29052 ,12008,12009,11966 ,0,0,0}, {29094,29052,29051 ,12008,11966,11965 ,0,0,0}, - {29095,29096,29011 ,12009,12010,11925 ,0,0,0}, {29095,29011,29052 ,12009,11925,11966 ,0,0,0}, - {29012,29011,29096 ,11926,11925,12010 ,0,0,0}, {29012,29097,29013 ,11926,12011,11927 ,0,0,0}, - {29013,29097,29053 ,11927,12011,11967 ,0,0,0}, {29097,29098,29053 ,12011,12012,11967 ,0,0,0}, - {29098,29099,29054 ,12012,12013,11968 ,0,0,0}, {29098,29054,29053 ,12012,11968,11967 ,0,0,0}, - {29099,29100,29055 ,12013,12014,11969 ,0,0,0}, {29099,29055,29054 ,12013,11969,11968 ,0,0,0}, - {29100,29101,29056 ,12014,12015,11970 ,0,0,0}, {29100,29056,29055 ,12014,11970,11969 ,0,0,0}, - {29101,29058,29057 ,12015,11972,11971 ,0,0,0}, {29101,29057,29056 ,12015,11971,11970 ,0,0,0}, - {29058,29102,29020 ,11972,12016,11934 ,0,0,0}, {29102,29103,29020 ,12016,12017,11934 ,0,0,0}, - {29020,29103,29059 ,11934,12017,11973 ,0,0,0}, {29103,29104,29059 ,12017,12018,11973 ,0,0,0}, - {29059,29104,29060 ,11973,12018,11974 ,0,0,0}, {29104,29105,29060 ,12018,12019,11974 ,0,0,0}, - {29060,29105,29061 ,11974,12019,11975 ,0,0,0}, {29105,29106,29061 ,12019,12020,11975 ,0,0,0}, - {29106,29107,29062 ,12020,12021,11976 ,0,0,0}, {29106,29062,29061 ,12020,11976,11975 ,0,0,0}, - {29107,29108,29063 ,12021,12022,11977 ,0,0,0}, {29107,29063,29062 ,12021,11977,11976 ,0,0,0}, - {29108,29109,29064 ,12022,12023,11978 ,0,0,0}, {29108,29064,29063 ,12022,11978,11977 ,0,0,0}, - {29109,29110,29065 ,12023,12024,11979 ,0,0,0}, {29109,29065,29064 ,12023,11979,11978 ,0,0,0}, - {29110,29111,29066 ,12024,12025,11980 ,0,0,0}, {29110,29066,29065 ,12024,11980,11979 ,0,0,0}, - {29111,29112,29067 ,12025,12026,11981 ,0,0,0}, {29111,29067,29066 ,12025,11981,11980 ,0,0,0}, - {29112,29113,29068 ,12026,12027,11982 ,0,0,0}, {29112,29068,29067 ,12026,11982,11981 ,0,0,0}, - {29113,29114,29069 ,12027,12028,11983 ,0,0,0}, {29113,29069,29068 ,12027,11983,11982 ,0,0,0}, - {29114,29115,29070 ,12028,12029,11984 ,0,0,0}, {29114,29070,29069 ,12028,11984,11983 ,0,0,0}, - {29116,29070,29115 ,12030,11984,12029 ,0,0,0}, {29070,29116,28733 ,11984,12030,11647 ,0,0,0}, - {28733,29116,28736 ,11647,12030,11650 ,0,0,0}, {29117,29118,29119 ,12031,12032,12033 ,0,0,0}, - {29120,29121,29122 ,12034,12035,12036 ,0,0,0}, {29123,29124,29125 ,12037,12038,12039 ,0,0,0}, - {29126,29127,29123 ,12040,12041,12037 ,0,0,0}, {29128,29129,29130 ,12042,12043,12044 ,0,0,0}, - {29131,29132,29133 ,12045,12046,12047 ,0,0,0}, {29134,29135,29136 ,12048,12049,12050 ,0,0,0}, - {29137,29138,29131 ,12051,12052,12045 ,0,0,0}, {29139,29140,29141 ,12053,12054,12055 ,0,0,0}, - {29141,29136,29142 ,12055,12050,12056 ,0,0,0}, {29143,29139,29144 ,12057,12053,12058 ,0,0,0}, - {29140,29139,29145 ,12054,12053,12059 ,0,0,0}, {29126,29146,29147 ,12040,12060,12061 ,0,0,0}, - {29143,29148,29139 ,12057,12062,12053 ,0,0,0}, {29149,29150,29151 ,12063,12064,12065 ,0,0,0}, - {29150,29152,29119 ,12064,12066,12033 ,0,0,0}, {29153,29154,29151 ,12067,12068,12065 ,0,0,0}, - {29152,29150,29149 ,12066,12064,12063 ,0,0,0}, {29155,29156,29153 ,12069,12070,12067 ,0,0,0}, - {29151,29154,29149 ,12065,12068,12063 ,0,0,0}, {29157,29158,29121 ,12071,12072,12035 ,0,0,0}, - {29159,29160,29161 ,12073,12074,12075 ,0,0,0}, {29157,29162,29158 ,12071,12076,12072 ,0,0,0}, - {29163,29164,29165 ,12077,12078,12079 ,0,0,0}, {29160,29166,29161 ,12074,12080,12075 ,0,0,0}, - {29167,29168,29169 ,12081,12082,12083 ,0,0,0}, {29163,29165,29170 ,12077,12079,12084 ,0,0,0}, - {29171,29172,29173 ,12085,12086,12087 ,0,0,0}, {29172,29171,29174 ,12086,12085,12088 ,0,0,0}, - {29175,29176,29177 ,12089,12090,12091 ,0,0,0}, {29178,29179,29176 ,12092,12093,12090 ,0,0,0}, - {29180,29181,29182 ,12094,12095,12096 ,0,0,0}, {29175,29177,29183 ,12089,12091,12097 ,0,0,0}, - {29184,29185,29186 ,12098,12099,12100 ,0,0,0}, {29180,29182,29187 ,12094,12096,12101 ,0,0,0}, - {29188,29189,29190 ,12102,12103,12104 ,0,0,0}, {29191,29185,29184 ,12105,12099,12098 ,0,0,0}, - {29192,29193,29194 ,12106,12107,12108 ,0,0,0}, {29194,29190,29192 ,12108,12104,12106 ,0,0,0}, - {29195,29196,29197 ,12109,12110,12111 ,0,0,0}, {29198,29193,29199 ,12112,12107,12113 ,0,0,0}, - {29200,29201,29202 ,12114,12115,12116 ,0,0,0}, {29201,29200,29203 ,12115,12114,12117 ,0,0,0}, - {29204,29205,29206 ,12118,12119,12120 ,0,0,0}, {29202,29205,29207 ,12116,12119,12121 ,0,0,0}, - {29208,29209,29210 ,12122,12123,12124 ,0,0,0}, {29211,29212,29213 ,12125,12126,12127 ,0,0,0}, - {29214,29215,29216 ,12128,12129,12130 ,0,0,0}, {29215,29214,29217 ,12129,12128,12131 ,0,0,0}, - {29218,29219,29220 ,12132,12133,12134 ,0,0,0}, {29221,29222,29218 ,12135,12136,12132 ,0,0,0}, - {29219,29218,29222 ,12133,12132,12136 ,0,0,0}, {29219,29222,29208 ,12133,12136,12122 ,0,0,0}, - {29223,29224,29225 ,12137,12138,12139 ,0,0,0}, {29206,29210,29209 ,12120,12124,12123 ,0,0,0}, - {29226,29211,29213 ,12140,12125,12127 ,0,0,0}, {29212,29227,29213 ,12126,12141,12127 ,0,0,0}, - {29228,29229,29211 ,12142,12143,12125 ,0,0,0}, {29211,29230,29212 ,12125,12144,12126 ,0,0,0}, - {29231,29232,29233 ,12145,12146,12147 ,0,0,0}, {28630,29234,29235 ,12148,12149,12150 ,0,0,0}, - {29235,29236,28985 ,12150,12151,12152 ,0,0,0}, {29236,28638,28985 ,12151,12153,12152 ,0,0,0}, - {28639,28638,29237 ,730,12153,12154 ,0,0,0}, {29225,29205,29223 ,12139,12119,12137 ,0,0,0}, - {29216,29221,29218 ,12130,12135,12132 ,0,0,0}, {29206,29209,29204 ,12120,12123,12118 ,0,0,0}, - {28768,29217,28767 ,12155,12131,12156 ,0,0,0}, {29200,29202,29207 ,12114,12116,12121 ,0,0,0}, - {29205,29204,29207 ,12119,12118,12121 ,0,0,0}, {29195,29203,29196 ,12109,12117,12110 ,0,0,0}, - {29201,29203,29195 ,12115,12117,12109 ,0,0,0}, {29195,29238,29201 ,12109,12157,12115 ,0,0,0}, - {29196,29198,29197 ,12110,12112,12111 ,0,0,0}, {29199,29193,29192 ,12113,12107,12106 ,0,0,0}, - {29198,29199,29197 ,12112,12113,12111 ,0,0,0}, {29188,29190,29194 ,12102,12104,12108 ,0,0,0}, - {29184,29186,29239 ,12098,12100,12158 ,0,0,0}, {29240,29191,29241 ,12159,12105,12160 ,0,0,0}, - {29190,29189,29241 ,12104,12103,12160 ,0,0,0}, {29185,29191,29240 ,12099,12105,12159 ,0,0,0}, - {29189,29240,29241 ,12103,12159,12160 ,0,0,0}, {29239,29186,29187 ,12158,12100,12101 ,0,0,0}, - {29242,29184,29239 ,12161,12098,12158 ,0,0,0}, {29187,29182,29239 ,12101,12096,12158 ,0,0,0}, - {29183,29181,29243 ,12097,12095,12162 ,0,0,0}, {29180,29243,29181 ,12094,12162,12095 ,0,0,0}, - {29244,29183,29243 ,12163,12097,12162 ,0,0,0}, {29179,29177,29176 ,12093,12091,12090 ,0,0,0}, - {29175,29183,29244 ,12089,12097,12163 ,0,0,0}, {29178,29245,29179 ,12092,12164,12093 ,0,0,0}, - {29173,29172,29245 ,12087,12086,12164 ,0,0,0}, {29245,29178,29173 ,12164,12092,12087 ,0,0,0}, - {29174,29246,29169 ,12088,12165,12083 ,0,0,0}, {29247,29248,29249 ,12166,12167,12168 ,0,0,0}, - {29169,29246,29250 ,12083,12165,12169 ,0,0,0}, {29246,29174,29171 ,12165,12088,12085 ,0,0,0}, - {29251,29170,29168 ,12170,12084,12082 ,0,0,0}, {29167,29169,29250 ,12081,12083,12169 ,0,0,0}, - {29170,29251,29163 ,12084,12170,12077 ,0,0,0}, {29251,29168,29167 ,12170,12082,12081 ,0,0,0}, - {29162,29252,29253 ,12076,12171,12172 ,0,0,0}, {29164,29166,29254 ,12078,12080,12173 ,0,0,0}, - {29165,29164,29254 ,12079,12078,12173 ,0,0,0}, {29254,29166,29160 ,12173,12080,12074 ,0,0,0}, - {29255,29256,29257 ,12174,12175,12176 ,0,0,0}, {29252,29159,29161 ,12171,12073,12075 ,0,0,0}, - {29119,29152,29117 ,12033,12066,12031 ,0,0,0}, {29162,29159,29252 ,12076,12073,12171 ,0,0,0}, - {29162,29253,29158 ,12076,12172,12072 ,0,0,0}, {29121,29120,29157 ,12035,12034,12071 ,0,0,0}, - {29156,29155,29122 ,12070,12069,12036 ,0,0,0}, {29122,29155,29120 ,12036,12069,12034 ,0,0,0}, - {29258,29155,29153 ,12177,12069,12067 ,0,0,0}, {29156,29154,29153 ,12070,12068,12067 ,0,0,0}, - {29118,29147,29146 ,12032,12061,12060 ,0,0,0}, {29117,29147,29118 ,12031,12061,12032 ,0,0,0}, - {29127,29124,29123 ,12041,12038,12037 ,0,0,0}, {29126,29123,29146 ,12040,12037,12060 ,0,0,0}, - {29127,29259,29124 ,12041,12178,12038 ,0,0,0}, {29130,29260,29134 ,12044,12179,12048 ,0,0,0}, - {29261,29262,29259 ,12180,12181,12178 ,0,0,0}, {29128,29263,29264 ,12042,12182,12183 ,0,0,0}, - {29262,29265,29266 ,12181,12184,12185 ,0,0,0}, {29261,29265,29262 ,12180,12184,12181 ,0,0,0}, - {29262,29124,29259 ,12181,12038,12178 ,0,0,0}, {29266,29267,29268 ,12185,12186,12187 ,0,0,0}, - {29267,29266,29269 ,12186,12185,12188 ,0,0,0}, {29265,29269,29266 ,12184,12188,12185 ,0,0,0}, - {29264,29263,29268 ,12183,12182,12187 ,0,0,0}, {29270,29130,29129 ,12189,12044,12043 ,0,0,0}, - {29266,29268,29263 ,12185,12187,12182 ,0,0,0}, {29135,29134,29271 ,12049,12048,12190 ,0,0,0}, - {29266,29272,29262 ,12185,12191,12181 ,0,0,0}, {29273,29146,29123 ,12192,12060,12037 ,0,0,0}, - {29262,29133,29124 ,12181,12047,12038 ,0,0,0}, {29274,29118,29146 ,12193,12032,12060 ,0,0,0}, - {29125,29124,29133 ,12039,12038,12047 ,0,0,0}, {29275,29119,29118 ,12194,12033,12032 ,0,0,0}, - {29273,29123,29125 ,12192,12037,12039 ,0,0,0}, {29276,29150,29119 ,12195,12064,12033 ,0,0,0}, - {29274,29146,29273 ,12193,12060,12192 ,0,0,0}, {29277,29151,29150 ,12196,12065,12064 ,0,0,0}, - {29275,29118,29274 ,12194,12032,12193 ,0,0,0}, {29278,29153,29151 ,12197,12067,12065 ,0,0,0}, - {29119,29275,29276 ,12033,12194,12195 ,0,0,0}, {29279,29280,29281 ,12198,12199,12200 ,0,0,0}, - {29150,29276,29277 ,12064,12195,12196 ,0,0,0}, {29281,29120,29155 ,12200,12034,12069 ,0,0,0}, - {29151,29277,29278 ,12065,12196,12197 ,0,0,0}, {29282,29157,29120 ,12201,12071,12034 ,0,0,0}, - {29153,29278,29258 ,12067,12197,12177 ,0,0,0}, {29283,29162,29157 ,12202,12076,12071 ,0,0,0}, - {29155,29258,29281 ,12069,12177,12200 ,0,0,0}, {29284,29159,29162 ,12203,12073,12076 ,0,0,0}, - {29120,29281,29282 ,12034,12200,12201 ,0,0,0}, {29285,29160,29159 ,12204,12074,12073 ,0,0,0}, - {29283,29157,29282 ,12202,12071,12201 ,0,0,0}, {29286,29254,29160 ,12205,12173,12074 ,0,0,0}, - {29284,29162,29283 ,12203,12076,12202 ,0,0,0}, {29287,29165,29254 ,12206,12079,12173 ,0,0,0}, - {29159,29284,29285 ,12073,12203,12204 ,0,0,0}, {29256,29170,29165 ,12175,12084,12079 ,0,0,0}, - {29160,29285,29286 ,12074,12204,12205 ,0,0,0}, {29288,29168,29170 ,12207,12082,12084 ,0,0,0}, - {29254,29286,29287 ,12173,12205,12206 ,0,0,0}, {29289,29169,29168 ,12208,12083,12082 ,0,0,0}, - {29165,29287,29256 ,12079,12206,12175 ,0,0,0}, {29290,29174,29169 ,12209,12088,12083 ,0,0,0}, - {29288,29170,29256 ,12207,12084,12175 ,0,0,0}, {29291,29172,29174 ,12210,12086,12088 ,0,0,0}, - {29289,29168,29288 ,12208,12082,12207 ,0,0,0}, {29292,29245,29172 ,12211,12164,12086 ,0,0,0}, - {29169,29289,29290 ,12083,12208,12209 ,0,0,0}, {29179,29245,29247 ,12093,12164,12166 ,0,0,0}, - {29174,29290,29291 ,12088,12209,12210 ,0,0,0}, {29293,29177,29179 ,12212,12091,12093 ,0,0,0}, - {29172,29291,29292 ,12086,12210,12211 ,0,0,0}, {29294,29183,29177 ,12213,12097,12091 ,0,0,0}, - {29245,29292,29247 ,12164,12211,12166 ,0,0,0}, {29295,29181,29183 ,12214,12095,12097 ,0,0,0}, - {29293,29179,29247 ,12212,12093,12166 ,0,0,0}, {29296,29182,29181 ,12215,12096,12095 ,0,0,0}, - {29294,29177,29293 ,12213,12091,12212 ,0,0,0}, {29297,29239,29182 ,12216,12158,12096 ,0,0,0}, - {29183,29294,29295 ,12097,12213,12214 ,0,0,0}, {29298,29299,29300 ,12217,12218,12219 ,0,0,0}, - {29181,29295,29296 ,12095,12214,12215 ,0,0,0}, {29301,29191,29184 ,12220,12105,12098 ,0,0,0}, - {29182,29296,29297 ,12096,12215,12216 ,0,0,0}, {29302,29241,29191 ,12221,12160,12105 ,0,0,0}, - {29239,29297,29242 ,12158,12216,12161 ,0,0,0}, {29303,29190,29241 ,12222,12104,12160 ,0,0,0}, - {29184,29242,29301 ,12098,12161,12220 ,0,0,0}, {29304,29192,29190 ,12223,12106,12104 ,0,0,0}, - {29302,29191,29301 ,12221,12105,12220 ,0,0,0}, {29305,29199,29192 ,12224,12113,12106 ,0,0,0}, - {29303,29241,29302 ,12222,12160,12221 ,0,0,0}, {29306,29197,29199 ,12225,12111,12113 ,0,0,0}, - {29304,29190,29303 ,12223,12104,12222 ,0,0,0}, {29307,29195,29197 ,12226,12109,12111 ,0,0,0}, - {29192,29304,29305 ,12106,12223,12224 ,0,0,0}, {29201,29308,29202 ,12115,12227,12116 ,0,0,0}, - {29199,29305,29306 ,12113,12224,12225 ,0,0,0}, {29223,29309,29224 ,12137,12228,12138 ,0,0,0}, - {29197,29306,29307 ,12111,12225,12226 ,0,0,0}, {29223,29205,29202 ,12137,12119,12116 ,0,0,0}, - {29195,29307,29238 ,12109,12226,12157 ,0,0,0}, {29225,29206,29205 ,12139,12120,12119 ,0,0,0}, - {29201,29238,29308 ,12115,12157,12227 ,0,0,0}, {29210,29206,29310 ,12124,12120,12229 ,0,0,0}, - {29223,29202,29308 ,12137,12116,12227 ,0,0,0}, {29227,29220,29219 ,12141,12134,12133 ,0,0,0}, - {29311,29218,29220 ,12230,12132,12134 ,0,0,0}, {29210,29219,29208 ,12124,12133,12122 ,0,0,0}, - {29310,29206,29225 ,12229,12120,12139 ,0,0,0}, {29227,29212,29220 ,12141,12126,12134 ,0,0,0}, - {29219,29210,29227 ,12133,12124,12141 ,0,0,0}, {29216,29312,29214 ,12130,12231,12128 ,0,0,0}, - {29214,28767,29217 ,12128,12156,12131 ,0,0,0}, {29221,29216,29215 ,12135,12130,12129 ,0,0,0}, - {29216,29311,29312 ,12130,12230,12231 ,0,0,0}, {28769,28767,29214 ,12232,12156,12128 ,0,0,0}, - {29263,29272,29266 ,12182,12191,12185 ,0,0,0}, {29129,29128,29264 ,12043,12042,12183 ,0,0,0}, - {29313,29141,29140 ,12233,12055,12054 ,0,0,0}, {29272,29133,29262 ,12191,12047,12181 ,0,0,0}, - {29272,29263,29314 ,12191,12182,12234 ,0,0,0}, {29125,29132,29315 ,12039,12046,12235 ,0,0,0}, - {29131,29133,29272 ,12045,12047,12191 ,0,0,0}, {29273,29315,29316 ,12192,12235,12236 ,0,0,0}, - {29132,29125,29133 ,12046,12039,12047 ,0,0,0}, {29274,29316,29317 ,12193,12236,12237 ,0,0,0}, - {29315,29273,29125 ,12235,12192,12039 ,0,0,0}, {29275,29317,29318 ,12194,12237,12238 ,0,0,0}, - {29316,29274,29273 ,12236,12193,12192 ,0,0,0}, {29276,29318,29319 ,12195,12238,12239 ,0,0,0}, - {29317,29275,29274 ,12237,12194,12193 ,0,0,0}, {29277,29319,29320 ,12196,12239,12240 ,0,0,0}, - {29318,29276,29275 ,12238,12195,12194 ,0,0,0}, {29278,29320,29321 ,12197,12240,12241 ,0,0,0}, - {29319,29277,29276 ,12239,12196,12195 ,0,0,0}, {29258,29321,29279 ,12177,12241,12198 ,0,0,0}, - {29278,29277,29320 ,12197,12196,12240 ,0,0,0}, {29322,29323,29324 ,12242,12243,12244 ,0,0,0}, - {29258,29278,29321 ,12177,12197,12241 ,0,0,0}, {29282,29280,29322 ,12201,12199,12242 ,0,0,0}, - {29281,29258,29279 ,12200,12177,12198 ,0,0,0}, {29283,29322,29325 ,12202,12242,12245 ,0,0,0}, - {29282,29281,29280 ,12201,12200,12199 ,0,0,0}, {29284,29325,29326 ,12203,12245,12246 ,0,0,0}, - {29322,29283,29282 ,12242,12202,12201 ,0,0,0}, {29285,29326,29327 ,12204,12246,12247 ,0,0,0}, - {29325,29284,29283 ,12245,12203,12202 ,0,0,0}, {29286,29327,29328 ,12205,12247,12248 ,0,0,0}, - {29326,29285,29284 ,12246,12204,12203 ,0,0,0}, {29287,29328,29257 ,12206,12248,12176 ,0,0,0}, - {29286,29285,29327 ,12205,12204,12247 ,0,0,0}, {29329,29330,29331 ,12249,12250,12251 ,0,0,0}, - {29287,29286,29328 ,12206,12205,12248 ,0,0,0}, {29288,29255,29332 ,12207,12174,12252 ,0,0,0}, - {29256,29287,29257 ,12175,12206,12176 ,0,0,0}, {29289,29332,29333 ,12208,12252,12253 ,0,0,0}, - {29255,29288,29256 ,12174,12207,12175 ,0,0,0}, {29290,29333,29334 ,12209,12253,12254 ,0,0,0}, - {29332,29289,29288 ,12252,12208,12207 ,0,0,0}, {29291,29334,29335 ,12210,12254,12255 ,0,0,0}, - {29333,29290,29289 ,12253,12209,12208 ,0,0,0}, {29292,29335,29248 ,12211,12255,12167 ,0,0,0}, - {29291,29290,29334 ,12210,12209,12254 ,0,0,0}, {29336,29337,29338 ,12256,12257,12258 ,0,0,0}, - {29292,29291,29335 ,12211,12210,12255 ,0,0,0}, {29293,29249,29339 ,12212,12168,12259 ,0,0,0}, - {29247,29292,29248 ,12166,12211,12167 ,0,0,0}, {29294,29339,29340 ,12213,12259,12260 ,0,0,0}, - {29293,29247,29249 ,12212,12166,12168 ,0,0,0}, {29295,29340,29341 ,12214,12260,12261 ,0,0,0}, - {29339,29294,29293 ,12259,12213,12212 ,0,0,0}, {29296,29341,29342 ,12215,12261,12262 ,0,0,0}, - {29340,29295,29294 ,12260,12214,12213 ,0,0,0}, {29297,29342,29343 ,12216,12262,12263 ,0,0,0}, - {29341,29296,29295 ,12261,12215,12214 ,0,0,0}, {29242,29343,29344 ,12161,12263,12264 ,0,0,0}, - {29297,29296,29342 ,12216,12215,12262 ,0,0,0}, {29301,29344,29299 ,12220,12264,12218 ,0,0,0}, - {29242,29297,29343 ,12161,12216,12263 ,0,0,0}, {29302,29299,29345 ,12221,12218,12265 ,0,0,0}, - {29301,29242,29344 ,12220,12161,12264 ,0,0,0}, {29303,29345,29346 ,12222,12265,12266 ,0,0,0}, - {29299,29302,29301 ,12218,12221,12220 ,0,0,0}, {29304,29346,29347 ,12223,12266,12267 ,0,0,0}, - {29345,29303,29302 ,12265,12222,12221 ,0,0,0}, {29305,29347,29348 ,12224,12267,12268 ,0,0,0}, - {29346,29304,29303 ,12266,12223,12222 ,0,0,0}, {29306,29348,29349 ,12225,12268,12269 ,0,0,0}, - {29347,29305,29304 ,12267,12224,12223 ,0,0,0}, {29307,29349,29350 ,12226,12269,12270 ,0,0,0}, - {29348,29306,29305 ,12268,12225,12224 ,0,0,0}, {29238,29350,29351 ,12157,12270,12271 ,0,0,0}, - {29349,29307,29306 ,12269,12226,12225 ,0,0,0}, {29308,29351,29309 ,12227,12271,12228 ,0,0,0}, - {29238,29307,29350 ,12157,12226,12270 ,0,0,0}, {29352,29225,29224 ,12272,12139,12138 ,0,0,0}, - {29308,29238,29351 ,12227,12157,12271 ,0,0,0}, {29234,29353,29229 ,12149,12273,12143 ,0,0,0}, - {29223,29308,29309 ,12137,12227,12228 ,0,0,0}, {29352,29213,29310 ,12272,12127,12229 ,0,0,0}, - {29212,29354,29220 ,12126,12274,12134 ,0,0,0}, {29310,29227,29210 ,12229,12141,12124 ,0,0,0}, - {29352,29310,29225 ,12272,12229,12139 ,0,0,0}, {29355,29312,29311 ,12275,12231,12230 ,0,0,0}, - {29310,29213,29227 ,12229,12127,12141 ,0,0,0}, {28770,29312,29355 ,12276,12231,12275 ,0,0,0}, - {29312,28769,29214 ,12231,12232,12128 ,0,0,0}, {29218,29311,29216 ,12132,12230,12130 ,0,0,0}, - {29354,29355,29311 ,12274,12275,12230 ,0,0,0}, {28770,28769,29312 ,12276,12232,12231 ,0,0,0}, - {29314,29263,29128 ,12234,12182,12042 ,0,0,0}, {29260,29130,29270 ,12179,12044,12189 ,0,0,0}, - {29356,29132,29138 ,12277,12046,12052 ,0,0,0}, {29314,29131,29272 ,12234,12045,12191 ,0,0,0}, - {29314,29128,29357 ,12234,12042,12278 ,0,0,0}, {29358,29359,29360 ,12279,12280,12281 ,0,0,0}, - {29137,29131,29314 ,12051,12045,12234 ,0,0,0}, {29356,29358,29315 ,12277,12279,12235 ,0,0,0}, - {29138,29132,29131 ,12052,12046,12045 ,0,0,0}, {29358,29361,29316 ,12279,12282,12236 ,0,0,0}, - {29356,29315,29132 ,12277,12235,12046 ,0,0,0}, {29361,29362,29317 ,12282,12283,12237 ,0,0,0}, - {29358,29316,29315 ,12279,12236,12235 ,0,0,0}, {29362,29363,29318 ,12283,12284,12238 ,0,0,0}, - {29361,29317,29316 ,12282,12237,12236 ,0,0,0}, {29363,29364,29319 ,12284,12285,12239 ,0,0,0}, - {29362,29318,29317 ,12283,12238,12237 ,0,0,0}, {29364,29365,29320 ,12285,12286,12240 ,0,0,0}, - {29363,29319,29318 ,12284,12239,12238 ,0,0,0}, {29365,29366,29321 ,12286,12287,12241 ,0,0,0}, - {29364,29320,29319 ,12285,12240,12239 ,0,0,0}, {29366,29367,29279 ,12287,12288,12198 ,0,0,0}, - {29365,29321,29320 ,12286,12241,12240 ,0,0,0}, {29367,29323,29280 ,12288,12243,12199 ,0,0,0}, - {29279,29321,29366 ,12198,12241,12287 ,0,0,0}, {29368,29369,29370 ,12289,12290,12291 ,0,0,0}, - {29280,29279,29367 ,12199,12198,12288 ,0,0,0}, {29324,29368,29325 ,12244,12289,12245 ,0,0,0}, - {29323,29322,29280 ,12243,12242,12199 ,0,0,0}, {29368,29371,29326 ,12289,12292,12246 ,0,0,0}, - {29324,29325,29322 ,12244,12245,12242 ,0,0,0}, {29371,29372,29327 ,12292,12293,12247 ,0,0,0}, - {29368,29326,29325 ,12289,12246,12245 ,0,0,0}, {29372,29373,29328 ,12293,12294,12248 ,0,0,0}, - {29371,29327,29326 ,12292,12247,12246 ,0,0,0}, {29373,29374,29257 ,12294,12295,12176 ,0,0,0}, - {29372,29328,29327 ,12293,12248,12247 ,0,0,0}, {29255,29374,29375 ,12174,12295,12296 ,0,0,0}, - {29257,29328,29373 ,12176,12248,12294 ,0,0,0}, {29375,29329,29332 ,12296,12249,12252 ,0,0,0}, - {29374,29255,29257 ,12295,12174,12176 ,0,0,0}, {29329,29376,29333 ,12249,12297,12253 ,0,0,0}, - {29375,29332,29255 ,12296,12252,12174 ,0,0,0}, {29376,29377,29334 ,12297,12298,12254 ,0,0,0}, - {29329,29333,29332 ,12249,12253,12252 ,0,0,0}, {29377,29378,29335 ,12298,12299,12255 ,0,0,0}, - {29376,29334,29333 ,12297,12254,12253 ,0,0,0}, {29378,29379,29248 ,12299,12300,12167 ,0,0,0}, - {29377,29335,29334 ,12298,12255,12254 ,0,0,0}, {29379,29380,29249 ,12300,12301,12168 ,0,0,0}, - {29248,29335,29378 ,12167,12255,12299 ,0,0,0}, {29380,29336,29339 ,12301,12256,12259 ,0,0,0}, - {29249,29248,29379 ,12168,12167,12300 ,0,0,0}, {29336,29381,29340 ,12256,12302,12260 ,0,0,0}, - {29380,29339,29249 ,12301,12259,12168 ,0,0,0}, {29381,29382,29341 ,12302,12303,12261 ,0,0,0}, - {29336,29340,29339 ,12256,12260,12259 ,0,0,0}, {29382,29383,29342 ,12303,12304,12262 ,0,0,0}, - {29381,29341,29340 ,12302,12261,12260 ,0,0,0}, {29383,29384,29343 ,12304,12305,12263 ,0,0,0}, - {29382,29342,29341 ,12303,12262,12261 ,0,0,0}, {29384,29300,29344 ,12305,12219,12264 ,0,0,0}, - {29343,29342,29383 ,12263,12262,12304 ,0,0,0}, {29385,29386,29387 ,12306,12307,12308 ,0,0,0}, - {29344,29343,29384 ,12264,12263,12305 ,0,0,0}, {29298,29385,29345 ,12217,12306,12265 ,0,0,0}, - {29300,29299,29344 ,12219,12218,12264 ,0,0,0}, {29385,29388,29346 ,12306,12309,12266 ,0,0,0}, - {29298,29345,29299 ,12217,12265,12218 ,0,0,0}, {29388,29389,29347 ,12309,12310,12267 ,0,0,0}, - {29385,29346,29345 ,12306,12266,12265 ,0,0,0}, {29389,29390,29348 ,12310,12311,12268 ,0,0,0}, - {29388,29347,29346 ,12309,12267,12266 ,0,0,0}, {29390,29391,29349 ,12311,12312,12269 ,0,0,0}, - {29389,29348,29347 ,12310,12268,12267 ,0,0,0}, {29391,29392,29350 ,12312,12313,12270 ,0,0,0}, - {29390,29349,29348 ,12311,12269,12268 ,0,0,0}, {29392,29393,29351 ,12313,12314,12271 ,0,0,0}, - {29391,29350,29349 ,12312,12270,12269 ,0,0,0}, {29393,29394,29309 ,12314,12315,12228 ,0,0,0}, - {29392,29351,29350 ,12313,12271,12270 ,0,0,0}, {29394,29395,29224 ,12315,12316,12138 ,0,0,0}, - {29393,29309,29351 ,12314,12228,12271 ,0,0,0}, {29395,29226,29352 ,12316,12140,12272 ,0,0,0}, - {29224,29309,29394 ,12138,12228,12315 ,0,0,0}, {29396,28766,28628 ,12317,12318,12319 ,0,0,0}, - {29395,29352,29224 ,12316,12272,12138 ,0,0,0}, {29228,29211,29226 ,12142,12125,12140 ,0,0,0}, - {29352,29226,29213 ,12272,12140,12127 ,0,0,0}, {28761,29355,29396 ,12320,12275,12317 ,0,0,0}, - {28761,28772,29355 ,12320,12321,12275 ,0,0,0}, {29220,29354,29311 ,12134,12274,12230 ,0,0,0}, - {29230,29396,29354 ,12144,12317,12274 ,0,0,0}, {28770,29355,28772 ,12276,12275,12321 ,0,0,0}, - {29130,29357,29128 ,12044,12278,12042 ,0,0,0}, {29271,29134,29260 ,12190,12048,12179 ,0,0,0}, - {29137,29397,29398 ,12051,12322,12323 ,0,0,0}, {29357,29137,29314 ,12278,12051,12234 ,0,0,0}, - {29399,29357,29130 ,12324,12278,12044 ,0,0,0}, {29138,29398,29400 ,12052,12323,12325 ,0,0,0}, - {29357,29397,29137 ,12278,12322,12051 ,0,0,0}, {29356,29400,29359 ,12277,12325,12280 ,0,0,0}, - {29398,29138,29137 ,12323,12052,12051 ,0,0,0}, {29401,29361,29360 ,12326,12282,12281 ,0,0,0}, - {29400,29356,29138 ,12325,12277,12052 ,0,0,0}, {29402,29362,29401 ,12327,12283,12326 ,0,0,0}, - {29359,29358,29356 ,12280,12279,12277 ,0,0,0}, {29403,29404,29405 ,12328,12329,12330 ,0,0,0}, - {29360,29361,29358 ,12281,12282,12279 ,0,0,0}, {29402,29403,29363 ,12327,12328,12284 ,0,0,0}, - {29401,29362,29361 ,12326,12283,12282 ,0,0,0}, {29403,29406,29364 ,12328,12331,12285 ,0,0,0}, - {29402,29363,29362 ,12327,12284,12283 ,0,0,0}, {29406,29407,29365 ,12331,12332,12286 ,0,0,0}, - {29403,29364,29363 ,12328,12285,12284 ,0,0,0}, {29407,29408,29366 ,12332,12333,12287 ,0,0,0}, - {29406,29365,29364 ,12331,12286,12285 ,0,0,0}, {29408,29409,29367 ,12333,12334,12288 ,0,0,0}, - {29407,29366,29365 ,12332,12287,12286 ,0,0,0}, {29323,29409,29410 ,12243,12334,12335 ,0,0,0}, - {29408,29367,29366 ,12333,12288,12287 ,0,0,0}, {29324,29410,29369 ,12244,12335,12290 ,0,0,0}, - {29409,29323,29367 ,12334,12243,12288 ,0,0,0}, {29411,29412,29413 ,12336,12337,12338 ,0,0,0}, - {29410,29324,29323 ,12335,12244,12243 ,0,0,0}, {29370,29411,29371 ,12291,12336,12292 ,0,0,0}, - {29369,29368,29324 ,12290,12289,12244 ,0,0,0}, {29411,29414,29372 ,12336,12339,12293 ,0,0,0}, - {29370,29371,29368 ,12291,12292,12289 ,0,0,0}, {29414,29415,29373 ,12339,12340,12294 ,0,0,0}, - {29411,29372,29371 ,12336,12293,12292 ,0,0,0}, {29374,29415,29416 ,12295,12340,12341 ,0,0,0}, - {29414,29373,29372 ,12339,12294,12293 ,0,0,0}, {29375,29416,29330 ,12296,12341,12250 ,0,0,0}, - {29374,29373,29415 ,12295,12294,12340 ,0,0,0}, {29417,29418,29419 ,12342,12343,12344 ,0,0,0}, - {29416,29375,29374 ,12341,12296,12295 ,0,0,0}, {29331,29417,29376 ,12251,12342,12297 ,0,0,0}, - {29330,29329,29375 ,12250,12249,12296 ,0,0,0}, {29417,29420,29377 ,12342,12345,12298 ,0,0,0}, - {29331,29376,29329 ,12251,12297,12249 ,0,0,0}, {29420,29421,29378 ,12345,12346,12299 ,0,0,0}, - {29417,29377,29376 ,12342,12298,12297 ,0,0,0}, {29421,29422,29379 ,12346,12347,12300 ,0,0,0}, - {29420,29378,29377 ,12345,12299,12298 ,0,0,0}, {29380,29422,29337 ,12301,12347,12257 ,0,0,0}, - {29379,29378,29421 ,12300,12299,12346 ,0,0,0}, {29423,29424,29425 ,12348,12349,12350 ,0,0,0}, - {29422,29380,29379 ,12347,12301,12300 ,0,0,0}, {29338,29423,29381 ,12258,12348,12302 ,0,0,0}, - {29337,29336,29380 ,12257,12256,12301 ,0,0,0}, {29423,29426,29382 ,12348,12351,12303 ,0,0,0}, - {29338,29381,29336 ,12258,12302,12256 ,0,0,0}, {29426,29427,29383 ,12351,12352,12304 ,0,0,0}, - {29423,29382,29381 ,12348,12303,12302 ,0,0,0}, {29427,29428,29384 ,12352,12353,12305 ,0,0,0}, - {29426,29383,29382 ,12351,12304,12303 ,0,0,0}, {29300,29428,29429 ,12219,12353,12354 ,0,0,0}, - {29427,29384,29383 ,12352,12305,12304 ,0,0,0}, {29298,29429,29386 ,12217,12354,12307 ,0,0,0}, - {29428,29300,29384 ,12353,12219,12305 ,0,0,0}, {29430,29388,29387 ,12355,12309,12308 ,0,0,0}, - {29429,29298,29300 ,12354,12217,12219 ,0,0,0}, {29431,29432,29433 ,12356,12357,12358 ,0,0,0}, - {29386,29385,29298 ,12307,12306,12217 ,0,0,0}, {29430,29431,29389 ,12355,12356,12310 ,0,0,0}, - {29387,29388,29385 ,12308,12309,12306 ,0,0,0}, {29431,29434,29390 ,12356,12359,12311 ,0,0,0}, - {29430,29389,29388 ,12355,12310,12309 ,0,0,0}, {29434,29435,29391 ,12359,12360,12312 ,0,0,0}, - {29431,29390,29389 ,12356,12311,12310 ,0,0,0}, {29435,29436,29392 ,12360,12361,12313 ,0,0,0}, - {29434,29391,29390 ,12359,12312,12311 ,0,0,0}, {29436,29437,29393 ,12361,12362,12314 ,0,0,0}, - {29435,29392,29391 ,12360,12313,12312 ,0,0,0}, {29437,29438,29394 ,12362,12363,12315 ,0,0,0}, - {29436,29393,29392 ,12361,12314,12313 ,0,0,0}, {29438,29439,29395 ,12363,12364,12316 ,0,0,0}, - {29437,29394,29393 ,12362,12315,12314 ,0,0,0}, {29226,29439,29228 ,12140,12364,12142 ,0,0,0}, - {29395,29394,29438 ,12316,12315,12363 ,0,0,0}, {29233,29228,29439 ,12147,12142,12364 ,0,0,0}, - {29226,29395,29439 ,12140,12316,12364 ,0,0,0}, {29230,29353,29396 ,12144,12273,12317 ,0,0,0}, - {29354,29396,29355 ,12274,12317,12275 ,0,0,0}, {29212,29230,29354 ,12126,12144,12274 ,0,0,0}, - {29229,29353,29230 ,12143,12273,12144 ,0,0,0}, {28761,29396,28628 ,12320,12317,12319 ,0,0,0}, - {29134,29399,29130 ,12048,12324,12044 ,0,0,0}, {29142,29136,29135 ,12056,12050,12049 ,0,0,0}, - {29397,29440,29441 ,12322,12365,12366 ,0,0,0}, {29399,29397,29357 ,12324,12322,12278 ,0,0,0}, - {29134,29442,29399 ,12048,12367,12324 ,0,0,0}, {29398,29441,29443 ,12323,12366,12368 ,0,0,0}, - {29399,29440,29397 ,12324,12365,12322 ,0,0,0}, {29400,29443,29444 ,12325,12368,12369 ,0,0,0}, - {29397,29441,29398 ,12322,12366,12323 ,0,0,0}, {29359,29444,29445 ,12280,12369,12370 ,0,0,0}, - {29398,29443,29400 ,12323,12368,12325 ,0,0,0}, {29360,29445,29446 ,12281,12370,12371 ,0,0,0}, - {29400,29444,29359 ,12325,12369,12280 ,0,0,0}, {29401,29446,29447 ,12326,12371,12372 ,0,0,0}, - {29359,29445,29360 ,12280,12370,12281 ,0,0,0}, {29402,29447,29404 ,12327,12372,12329 ,0,0,0}, - {29446,29401,29360 ,12371,12326,12281 ,0,0,0}, {29448,29406,29405 ,12373,12331,12330 ,0,0,0}, - {29447,29402,29401 ,12372,12327,12326 ,0,0,0}, {29449,29450,29448 ,12374,12375,12373 ,0,0,0}, - {29404,29403,29402 ,12329,12328,12327 ,0,0,0}, {29448,29450,29407 ,12373,12375,12332 ,0,0,0}, - {29405,29406,29403 ,12330,12331,12328 ,0,0,0}, {29450,29451,29408 ,12375,12376,12333 ,0,0,0}, - {29448,29407,29406 ,12373,12332,12331 ,0,0,0}, {29409,29451,29452 ,12334,12376,12377 ,0,0,0}, - {29450,29408,29407 ,12375,12333,12332 ,0,0,0}, {29410,29452,29453 ,12335,12377,12378 ,0,0,0}, - {29408,29451,29409 ,12333,12376,12334 ,0,0,0}, {29369,29453,29454 ,12290,12378,12379 ,0,0,0}, - {29409,29452,29410 ,12334,12377,12335 ,0,0,0}, {29370,29454,29412 ,12291,12379,12337 ,0,0,0}, - {29453,29369,29410 ,12378,12290,12335 ,0,0,0}, {29455,29456,29413 ,12380,12381,12338 ,0,0,0}, - {29454,29370,29369 ,12379,12291,12290 ,0,0,0}, {29413,29456,29414 ,12338,12381,12339 ,0,0,0}, - {29412,29411,29370 ,12337,12336,12291 ,0,0,0}, {29456,29457,29415 ,12381,12382,12340 ,0,0,0}, - {29413,29414,29411 ,12338,12339,12336 ,0,0,0}, {29416,29457,29458 ,12341,12382,12383 ,0,0,0}, - {29456,29415,29414 ,12381,12340,12339 ,0,0,0}, {29330,29458,29459 ,12250,12383,12384 ,0,0,0}, - {29415,29457,29416 ,12340,12382,12341 ,0,0,0}, {29331,29459,29418 ,12251,12384,12343 ,0,0,0}, - {29458,29330,29416 ,12383,12250,12341 ,0,0,0}, {29460,29461,29419 ,12385,12386,12344 ,0,0,0}, - {29459,29331,29330 ,12384,12251,12250 ,0,0,0}, {29419,29461,29420 ,12344,12386,12345 ,0,0,0}, - {29418,29417,29331 ,12343,12342,12251 ,0,0,0}, {29461,29462,29421 ,12386,12387,12346 ,0,0,0}, - {29419,29420,29417 ,12344,12345,12342 ,0,0,0}, {29422,29462,29463 ,12347,12387,12388 ,0,0,0}, - {29461,29421,29420 ,12386,12346,12345 ,0,0,0}, {29337,29463,29464 ,12257,12388,12389 ,0,0,0}, - {29421,29462,29422 ,12346,12387,12347 ,0,0,0}, {29338,29464,29424 ,12258,12389,12349 ,0,0,0}, - {29463,29337,29422 ,12388,12257,12347 ,0,0,0}, {29465,29466,29425 ,12390,12391,12350 ,0,0,0}, - {29464,29338,29337 ,12389,12258,12257 ,0,0,0}, {29425,29466,29426 ,12350,12391,12351 ,0,0,0}, - {29424,29423,29338 ,12349,12348,12258 ,0,0,0}, {29466,29467,29427 ,12391,12392,12352 ,0,0,0}, - {29425,29426,29423 ,12350,12351,12348 ,0,0,0}, {29428,29467,29468 ,12353,12392,12393 ,0,0,0}, - {29466,29427,29426 ,12391,12352,12351 ,0,0,0}, {29429,29468,29469 ,12354,12393,12394 ,0,0,0}, - {29427,29467,29428 ,12352,12392,12353 ,0,0,0}, {29386,29469,29470 ,12307,12394,12395 ,0,0,0}, - {29428,29468,29429 ,12353,12393,12354 ,0,0,0}, {29387,29470,29471 ,12308,12395,12396 ,0,0,0}, - {29429,29469,29386 ,12354,12394,12307 ,0,0,0}, {29430,29471,29432 ,12355,12396,12357 ,0,0,0}, - {29470,29387,29386 ,12395,12308,12307 ,0,0,0}, {29472,29434,29433 ,12397,12359,12358 ,0,0,0}, - {29471,29430,29387 ,12396,12355,12308 ,0,0,0}, {29473,29474,29472 ,12398,12399,12397 ,0,0,0}, - {29432,29431,29430 ,12357,12356,12355 ,0,0,0}, {29472,29474,29435 ,12397,12399,12360 ,0,0,0}, - {29433,29434,29431 ,12358,12359,12356 ,0,0,0}, {29474,29475,29436 ,12399,12400,12361 ,0,0,0}, - {29472,29435,29434 ,12397,12360,12359 ,0,0,0}, {29475,29476,29437 ,12400,12401,12362 ,0,0,0}, - {29474,29436,29435 ,12399,12361,12360 ,0,0,0}, {29476,29477,29438 ,12401,12402,12363 ,0,0,0}, - {29475,29437,29436 ,12400,12362,12361 ,0,0,0}, {29439,29477,29233 ,12364,12402,12147 ,0,0,0}, - {29476,29438,29437 ,12401,12363,12362 ,0,0,0}, {29233,29478,29228 ,12147,12403,12142 ,0,0,0}, - {29438,29477,29439 ,12363,12402,12364 ,0,0,0}, {28633,29353,29234 ,12404,12273,12149 ,0,0,0}, - {29353,28766,29396 ,12273,12318,12317 ,0,0,0}, {29211,29229,29230 ,12125,12143,12144 ,0,0,0}, - {29478,29234,29229 ,12403,12149,12143 ,0,0,0}, {28633,28766,29353 ,12404,12318,12273 ,0,0,0}, - {29136,29442,29134 ,12050,12367,12048 ,0,0,0}, {29479,29141,29142 ,12405,12055,12056 ,0,0,0}, - {29480,29440,29442 ,12406,12365,12367 ,0,0,0}, {29442,29440,29399 ,12367,12365,12324 ,0,0,0}, - {29442,29313,29480 ,12367,12233,12406 ,0,0,0}, {29481,29441,29440 ,12407,12366,12365 ,0,0,0}, - {29440,29480,29481 ,12365,12406,12407 ,0,0,0}, {29482,29443,29441 ,12408,12368,12366 ,0,0,0}, - {29441,29481,29482 ,12366,12407,12408 ,0,0,0}, {29483,29444,29443 ,12409,12369,12368 ,0,0,0}, - {29443,29482,29483 ,12368,12408,12409 ,0,0,0}, {29484,29445,29444 ,12410,12370,12369 ,0,0,0}, - {29444,29483,29484 ,12369,12409,12410 ,0,0,0}, {29485,29446,29445 ,12411,12371,12370 ,0,0,0}, - {29445,29484,29485 ,12370,12410,12411 ,0,0,0}, {29486,29447,29446 ,12412,12372,12371 ,0,0,0}, - {29446,29485,29486 ,12371,12411,12412 ,0,0,0}, {29487,29404,29447 ,12413,12329,12372 ,0,0,0}, - {29447,29486,29487 ,12372,12412,12413 ,0,0,0}, {29488,29405,29404 ,12414,12330,12329 ,0,0,0}, - {29404,29487,29488 ,12329,12413,12414 ,0,0,0}, {29489,29448,29405 ,12415,12373,12330 ,0,0,0}, - {29488,29489,29405 ,12414,12415,12330 ,0,0,0}, {29490,29491,29492 ,12416,12417,12418 ,0,0,0}, - {29489,29449,29448 ,12415,12374,12373 ,0,0,0}, {29493,29451,29450 ,12419,12376,12375 ,0,0,0}, - {29449,29493,29450 ,12374,12419,12375 ,0,0,0}, {29494,29452,29451 ,12420,12377,12376 ,0,0,0}, - {29451,29493,29494 ,12376,12419,12420 ,0,0,0}, {29495,29453,29452 ,12421,12378,12377 ,0,0,0}, - {29452,29494,29495 ,12377,12420,12421 ,0,0,0}, {29496,29454,29453 ,12422,12379,12378 ,0,0,0}, - {29453,29495,29496 ,12378,12421,12422 ,0,0,0}, {29497,29412,29454 ,12423,12337,12379 ,0,0,0}, - {29454,29496,29497 ,12379,12422,12423 ,0,0,0}, {29498,29413,29412 ,12424,12338,12337 ,0,0,0}, - {29497,29498,29412 ,12423,12424,12337 ,0,0,0}, {29499,29455,29500 ,12425,12380,12426 ,0,0,0}, - {29498,29455,29413 ,12424,12380,12338 ,0,0,0}, {29499,29457,29456 ,12425,12382,12381 ,0,0,0}, - {29455,29499,29456 ,12380,12425,12381 ,0,0,0}, {29501,29458,29457 ,12427,12383,12382 ,0,0,0}, - {29457,29499,29501 ,12382,12425,12427 ,0,0,0}, {29502,29459,29458 ,12428,12384,12383 ,0,0,0}, - {29458,29501,29502 ,12383,12427,12428 ,0,0,0}, {29503,29418,29459 ,12429,12343,12384 ,0,0,0}, - {29459,29502,29503 ,12384,12428,12429 ,0,0,0}, {29504,29419,29418 ,12430,12344,12343 ,0,0,0}, - {29503,29504,29418 ,12429,12430,12343 ,0,0,0}, {29505,29506,29507 ,12431,12432,12433 ,0,0,0}, - {29504,29460,29419 ,12430,12385,12344 ,0,0,0}, {29508,29462,29461 ,12434,12387,12386 ,0,0,0}, - {29460,29508,29461 ,12385,12434,12386 ,0,0,0}, {29509,29463,29462 ,12435,12388,12387 ,0,0,0}, - {29462,29508,29509 ,12387,12434,12435 ,0,0,0}, {29510,29464,29463 ,12436,12389,12388 ,0,0,0}, - {29463,29509,29510 ,12388,12435,12436 ,0,0,0}, {29511,29424,29464 ,12437,12349,12389 ,0,0,0}, - {29464,29510,29511 ,12389,12436,12437 ,0,0,0}, {29512,29425,29424 ,12438,12350,12349 ,0,0,0}, - {29511,29512,29424 ,12437,12438,12349 ,0,0,0}, {29466,29513,29467 ,12391,12439,12392 ,0,0,0}, - {29512,29465,29425 ,12438,12390,12350 ,0,0,0}, {29514,29515,29513 ,12440,12441,12439 ,0,0,0}, - {29465,29513,29466 ,12390,12439,12391 ,0,0,0}, {29515,29468,29467 ,12441,12393,12392 ,0,0,0}, - {29467,29513,29515 ,12392,12439,12441 ,0,0,0}, {29516,29469,29468 ,12442,12394,12393 ,0,0,0}, - {29468,29515,29516 ,12393,12441,12442 ,0,0,0}, {29517,29470,29469 ,12443,12395,12394 ,0,0,0}, - {29469,29516,29517 ,12394,12442,12443 ,0,0,0}, {29518,29471,29470 ,12444,12396,12395 ,0,0,0}, - {29470,29517,29518 ,12395,12443,12444 ,0,0,0}, {29519,29432,29471 ,12445,12357,12396 ,0,0,0}, - {29471,29518,29519 ,12396,12444,12445 ,0,0,0}, {29520,29433,29432 ,12446,12358,12357 ,0,0,0}, - {29432,29519,29520 ,12357,12445,12446 ,0,0,0}, {29521,29472,29433 ,12447,12397,12358 ,0,0,0}, - {29520,29521,29433 ,12446,12447,12358 ,0,0,0}, {29474,29522,29475 ,12399,12448,12400 ,0,0,0}, - {29521,29473,29472 ,12447,12398,12397 ,0,0,0}, {29475,29523,29476 ,12400,12449,12401 ,0,0,0}, - {29473,29522,29474 ,12398,12448,12399 ,0,0,0}, {29476,29524,29477 ,12401,12450,12402 ,0,0,0}, - {29522,29523,29475 ,12448,12449,12400 ,0,0,0}, {29477,29231,29233 ,12402,12145,12147 ,0,0,0}, - {29523,29524,29476 ,12449,12450,12401 ,0,0,0}, {29232,29236,29235 ,12146,12151,12150 ,0,0,0}, - {29524,29231,29477 ,12450,12145,12402 ,0,0,0}, {29232,29478,29233 ,12146,12403,12147 ,0,0,0}, - {28815,28633,29234 ,12451,12404,12149 ,0,0,0}, {29228,29478,29229 ,12142,12403,12143 ,0,0,0}, - {29478,29232,29235 ,12403,12146,12150 ,0,0,0}, {28630,28815,29234 ,12148,12451,12149 ,0,0,0}, - {29141,29313,29136 ,12055,12233,12050 ,0,0,0}, {29479,29144,29139 ,12405,12058,12053 ,0,0,0}, - {29480,29313,29525 ,12406,12233,12452 ,0,0,0}, {29136,29313,29442 ,12050,12233,12367 ,0,0,0}, - {29313,29140,29525 ,12233,12054,12452 ,0,0,0}, {29481,29480,29526 ,12407,12406,12453 ,0,0,0}, - {29480,29525,29526 ,12406,12452,12453 ,0,0,0}, {29482,29481,29527 ,12408,12407,12454 ,0,0,0}, - {29481,29526,29527 ,12407,12453,12454 ,0,0,0}, {29483,29482,29528 ,12409,12408,12455 ,0,0,0}, - {29482,29527,29528 ,12408,12454,12455 ,0,0,0}, {29484,29483,29529 ,12410,12409,12456 ,0,0,0}, - {29483,29528,29529 ,12409,12455,12456 ,0,0,0}, {29485,29484,29530 ,12411,12410,12457 ,0,0,0}, - {29484,29529,29530 ,12410,12456,12457 ,0,0,0}, {29486,29485,29531 ,12412,12411,12458 ,0,0,0}, - {29485,29530,29531 ,12411,12457,12458 ,0,0,0}, {29487,29486,29532 ,12413,12412,12459 ,0,0,0}, - {29486,29531,29532 ,12412,12458,12459 ,0,0,0}, {29488,29487,29533 ,12414,12413,12460 ,0,0,0}, - {29487,29532,29533 ,12413,12459,12460 ,0,0,0}, {29489,29488,29534 ,12415,12414,12461 ,0,0,0}, - {29488,29533,29534 ,12414,12460,12461 ,0,0,0}, {29449,29489,29535 ,12374,12415,12462 ,0,0,0}, - {29489,29534,29535 ,12415,12461,12462 ,0,0,0}, {29493,29449,29490 ,12419,12374,12416 ,0,0,0}, - {29535,29490,29449 ,12462,12416,12374 ,0,0,0}, {29494,29493,29492 ,12420,12419,12418 ,0,0,0}, - {29493,29490,29492 ,12419,12416,12418 ,0,0,0}, {29495,29494,29536 ,12421,12420,12463 ,0,0,0}, - {29494,29492,29536 ,12420,12418,12463 ,0,0,0}, {29496,29495,29537 ,12422,12421,12464 ,0,0,0}, - {29495,29536,29537 ,12421,12463,12464 ,0,0,0}, {29497,29496,29538 ,12423,12422,12465 ,0,0,0}, - {29496,29537,29538 ,12422,12464,12465 ,0,0,0}, {29498,29497,29539 ,12424,12423,12466 ,0,0,0}, - {29497,29538,29539 ,12423,12465,12466 ,0,0,0}, {29455,29498,29540 ,12380,12424,12467 ,0,0,0}, - {29498,29539,29540 ,12424,12466,12467 ,0,0,0}, {29540,29541,29500 ,12467,12468,12426 ,0,0,0}, - {29540,29500,29455 ,12467,12426,12380 ,0,0,0}, {29501,29499,29542 ,12427,12425,12469 ,0,0,0}, - {29499,29500,29542 ,12425,12426,12469 ,0,0,0}, {29502,29501,29543 ,12428,12427,12470 ,0,0,0}, - {29501,29542,29543 ,12427,12469,12470 ,0,0,0}, {29503,29502,29544 ,12429,12428,12471 ,0,0,0}, - {29502,29543,29544 ,12428,12470,12471 ,0,0,0}, {29504,29503,29545 ,12430,12429,12472 ,0,0,0}, - {29503,29544,29545 ,12429,12471,12472 ,0,0,0}, {29460,29504,29546 ,12385,12430,12473 ,0,0,0}, - {29504,29545,29546 ,12430,12472,12473 ,0,0,0}, {29508,29460,29505 ,12434,12385,12431 ,0,0,0}, - {29546,29505,29460 ,12473,12431,12385 ,0,0,0}, {29509,29508,29507 ,12435,12434,12433 ,0,0,0}, - {29508,29505,29507 ,12434,12431,12433 ,0,0,0}, {29510,29509,29547 ,12436,12435,12474 ,0,0,0}, - {29509,29507,29547 ,12435,12433,12474 ,0,0,0}, {29511,29510,29548 ,12437,12436,12475 ,0,0,0}, - {29510,29547,29548 ,12436,12474,12475 ,0,0,0}, {29512,29511,29549 ,12438,12437,12476 ,0,0,0}, - {29511,29548,29549 ,12437,12475,12476 ,0,0,0}, {29465,29512,29550 ,12390,12438,12477 ,0,0,0}, - {29512,29549,29550 ,12438,12476,12477 ,0,0,0}, {29513,29465,29551 ,12439,12390,12478 ,0,0,0}, - {29465,29550,29551 ,12390,12477,12478 ,0,0,0}, {29514,29551,29552 ,12440,12478,12479 ,0,0,0}, - {29551,29514,29513 ,12478,12440,12439 ,0,0,0}, {29516,29515,29553 ,12442,12441,12480 ,0,0,0}, - {29515,29514,29553 ,12441,12440,12480 ,0,0,0}, {29517,29516,29554 ,12443,12442,12481 ,0,0,0}, - {29516,29553,29554 ,12442,12480,12481 ,0,0,0}, {29518,29517,29555 ,12444,12443,12482 ,0,0,0}, - {29517,29554,29555 ,12443,12481,12482 ,0,0,0}, {29519,29518,29556 ,12445,12444,12483 ,0,0,0}, - {29518,29555,29556 ,12444,12482,12483 ,0,0,0}, {29520,29519,29557 ,12446,12445,12484 ,0,0,0}, - {29519,29556,29557 ,12445,12483,12484 ,0,0,0}, {29521,29520,29558 ,12447,12446,12485 ,0,0,0}, - {29520,29557,29558 ,12446,12484,12485 ,0,0,0}, {29473,29521,29559 ,12398,12447,12486 ,0,0,0}, - {29521,29558,29559 ,12447,12485,12486 ,0,0,0}, {29522,29473,29560 ,12448,12398,12487 ,0,0,0}, - {29473,29559,29560 ,12398,12486,12487 ,0,0,0}, {29523,29522,29561 ,12449,12448,12488 ,0,0,0}, - {29522,29560,29561 ,12448,12487,12488 ,0,0,0}, {29524,29523,29562 ,12450,12449,12489 ,0,0,0}, - {29523,29561,29562 ,12449,12488,12489 ,0,0,0}, {29231,29524,29563 ,12145,12450,12490 ,0,0,0}, - {29524,29562,29563 ,12450,12489,12490 ,0,0,0}, {29564,29232,29231 ,12491,12146,12145 ,0,0,0}, - {29563,29564,29231 ,12490,12491,12145 ,0,0,0}, {29478,29235,29234 ,12403,12150,12149 ,0,0,0}, - {29564,29236,29232 ,12491,12151,12146 ,0,0,0}, {28630,29235,28985 ,12148,12150,12152 ,0,0,0}, - {29139,29141,29479 ,12053,12055,12405 ,0,0,0}, {29148,29145,29139 ,12062,12059,12053 ,0,0,0}, - {29145,29565,29140 ,12059,12492,12054 ,0,0,0}, {29140,29565,29525 ,12054,12492,12452 ,0,0,0}, - {29565,29566,29525 ,12492,12493,12452 ,0,0,0}, {29525,29566,29526 ,12452,12493,12453 ,0,0,0}, - {29566,29567,29526 ,12493,12494,12453 ,0,0,0}, {29526,29567,29527 ,12453,12494,12454 ,0,0,0}, - {29567,29568,29527 ,12494,12495,12454 ,0,0,0}, {29527,29568,29528 ,12454,12495,12455 ,0,0,0}, - {29568,29569,29528 ,12495,12496,12455 ,0,0,0}, {29528,29569,29529 ,12455,12496,12456 ,0,0,0}, - {29569,29570,29529 ,12496,12497,12456 ,0,0,0}, {29529,29570,29530 ,12456,12497,12457 ,0,0,0}, - {29570,29571,29530 ,12497,12498,12457 ,0,0,0}, {29530,29571,29531 ,12457,12498,12458 ,0,0,0}, - {29571,29572,29531 ,12498,12499,12458 ,0,0,0}, {29572,29573,29532 ,12499,12500,12459 ,0,0,0}, - {29572,29532,29531 ,12499,12459,12458 ,0,0,0}, {29573,29574,29533 ,12500,12501,12460 ,0,0,0}, - {29573,29533,29532 ,12500,12460,12459 ,0,0,0}, {29574,29575,29534 ,12501,12502,12461 ,0,0,0}, - {29574,29534,29533 ,12501,12461,12460 ,0,0,0}, {29575,29576,29535 ,12502,12503,12462 ,0,0,0}, - {29575,29535,29534 ,12502,12462,12461 ,0,0,0}, {29576,29577,29490 ,12503,12504,12416 ,0,0,0}, - {29576,29490,29535 ,12503,12416,12462 ,0,0,0}, {29491,29490,29577 ,12417,12416,12504 ,0,0,0}, - {29491,29578,29492 ,12417,12505,12418 ,0,0,0}, {29492,29578,29536 ,12418,12505,12463 ,0,0,0}, - {29578,29579,29536 ,12505,12506,12463 ,0,0,0}, {29536,29579,29537 ,12463,12506,12464 ,0,0,0}, - {29579,29580,29537 ,12506,12507,12464 ,0,0,0}, {29580,29581,29538 ,12507,12508,12465 ,0,0,0}, - {29580,29538,29537 ,12507,12465,12464 ,0,0,0}, {29581,29582,29539 ,12508,12509,12466 ,0,0,0}, - {29581,29539,29538 ,12508,12466,12465 ,0,0,0}, {29582,29541,29540 ,12509,12468,12467 ,0,0,0}, - {29582,29540,29539 ,12509,12467,12466 ,0,0,0}, {29541,29583,29500 ,12468,12510,12426 ,0,0,0}, - {29583,29584,29500 ,12510,12511,12426 ,0,0,0}, {29500,29584,29542 ,12426,12511,12469 ,0,0,0}, - {29584,29585,29542 ,12511,12512,12469 ,0,0,0}, {29542,29585,29543 ,12469,12512,12470 ,0,0,0}, - {29585,29586,29543 ,12512,12513,12470 ,0,0,0}, {29586,29587,29544 ,12513,12514,12471 ,0,0,0}, - {29586,29544,29543 ,12513,12471,12470 ,0,0,0}, {29587,29588,29545 ,12514,12515,12472 ,0,0,0}, - {29587,29545,29544 ,12514,12472,12471 ,0,0,0}, {29588,29589,29546 ,12515,12516,12473 ,0,0,0}, - {29588,29546,29545 ,12515,12473,12472 ,0,0,0}, {29589,29590,29505 ,12516,12517,12431 ,0,0,0}, - {29589,29505,29546 ,12516,12431,12473 ,0,0,0}, {29506,29505,29590 ,12432,12431,12517 ,0,0,0}, - {29506,29591,29507 ,12432,12518,12433 ,0,0,0}, {29507,29591,29547 ,12433,12518,12474 ,0,0,0}, - {29591,29592,29547 ,12518,12519,12474 ,0,0,0}, {29592,29593,29548 ,12519,12520,12475 ,0,0,0}, - {29592,29548,29547 ,12519,12475,12474 ,0,0,0}, {29593,29594,29549 ,12520,12521,12476 ,0,0,0}, - {29593,29549,29548 ,12520,12476,12475 ,0,0,0}, {29594,29595,29550 ,12521,12522,12477 ,0,0,0}, - {29594,29550,29549 ,12521,12477,12476 ,0,0,0}, {29595,29552,29551 ,12522,12479,12478 ,0,0,0}, - {29595,29551,29550 ,12522,12478,12477 ,0,0,0}, {29552,29596,29514 ,12479,12523,12440 ,0,0,0}, - {29596,29597,29514 ,12523,12524,12440 ,0,0,0}, {29514,29597,29553 ,12440,12524,12480 ,0,0,0}, - {29597,29598,29553 ,12524,12525,12480 ,0,0,0}, {29553,29598,29554 ,12480,12525,12481 ,0,0,0}, - {29598,29599,29554 ,12525,12526,12481 ,0,0,0}, {29554,29599,29555 ,12481,12526,12482 ,0,0,0}, - {29599,29600,29555 ,12526,12527,12482 ,0,0,0}, {29600,29601,29556 ,12527,12528,12483 ,0,0,0}, - {29600,29556,29555 ,12527,12483,12482 ,0,0,0}, {29601,29602,29557 ,12528,12529,12484 ,0,0,0}, - {29601,29557,29556 ,12528,12484,12483 ,0,0,0}, {29602,29603,29558 ,12529,12530,12485 ,0,0,0}, - {29602,29558,29557 ,12529,12485,12484 ,0,0,0}, {29603,29604,29559 ,12530,12531,12486 ,0,0,0}, - {29603,29559,29558 ,12530,12486,12485 ,0,0,0}, {29604,29605,29560 ,12531,12532,12487 ,0,0,0}, - {29604,29560,29559 ,12531,12487,12486 ,0,0,0}, {29605,29606,29561 ,12532,12533,12488 ,0,0,0}, - {29605,29561,29560 ,12532,12488,12487 ,0,0,0}, {29606,29607,29562 ,12533,12534,12489 ,0,0,0}, - {29606,29562,29561 ,12533,12489,12488 ,0,0,0}, {29607,29608,29563 ,12534,12535,12490 ,0,0,0}, - {29607,29563,29562 ,12534,12490,12489 ,0,0,0}, {29608,29609,29564 ,12535,12536,12491 ,0,0,0}, - {29608,29564,29563 ,12535,12491,12490 ,0,0,0}, {29237,29564,29609 ,12154,12491,12536 ,0,0,0}, - {29564,29237,29236 ,12491,12154,12151 ,0,0,0}, {28638,29236,29237 ,12153,12151,12154 ,0,0,0}, - {29610,29611,29581 ,12537,12538,12539 ,0,0,0}, {29581,29580,29610 ,12539,12540,12537 ,0,0,0}, - {29612,29613,29614 ,12541,12542,12543 ,0,0,0}, {29615,29579,29578 ,12544,12545,12546 ,0,0,0}, - {29580,29579,29616 ,12540,12545,12547 ,0,0,0}, {29615,29616,29579 ,12544,12547,12545 ,0,0,0}, - {29491,29577,29617 ,12548,12549,12550 ,0,0,0}, {29618,29491,29617 ,12551,12548,12550 ,0,0,0}, - {29578,29491,29618 ,12546,12548,12551 ,0,0,0}, {29617,29576,29619 ,12550,12552,12553 ,0,0,0}, - {29578,29618,29615 ,12546,12551,12544 ,0,0,0}, {29617,29577,29576 ,12550,12549,12552 ,0,0,0}, - {29616,29610,29580 ,12547,12537,12540 ,0,0,0}, {29620,29575,29574 ,12554,12555,12556 ,0,0,0}, - {29620,29619,29575 ,12554,12553,12555 ,0,0,0}, {29621,29620,29574 ,12557,12554,12556 ,0,0,0}, - {29622,29623,29624 ,12558,12559,12560 ,0,0,0}, {29625,29621,29573 ,12561,12557,12562 ,0,0,0}, - {29572,29625,29573 ,12563,12561,12562 ,0,0,0}, {29626,29572,29571 ,12564,12563,12565 ,0,0,0}, - {29625,29572,29626 ,12561,12563,12564 ,0,0,0}, {29627,29626,29571 ,12566,12564,12565 ,0,0,0}, - {29573,29621,29574 ,12562,12557,12556 ,0,0,0}, {29619,29576,29575 ,12553,12552,12555 ,0,0,0}, - {29628,29569,29629 ,12567,12568,12569 ,0,0,0}, {29570,29628,29627 ,12570,12567,12566 ,0,0,0}, - {29568,29630,29629 ,12571,12572,12569 ,0,0,0}, {29570,29569,29628 ,12570,12568,12567 ,0,0,0}, - {29630,29567,29631 ,12572,12573,12574 ,0,0,0}, {29567,29630,29568 ,12573,12572,12571 ,0,0,0}, - {29631,29566,29632 ,12574,12575,12576 ,0,0,0}, {29569,29568,29629 ,12568,12571,12569 ,0,0,0}, - {29567,29566,29631 ,12573,12575,12574 ,0,0,0}, {29631,29633,29634 ,12574,12577,12578 ,0,0,0}, - {29265,29635,29269 ,12579,12580,12188 ,0,0,0}, {29636,29637,29638 ,12581,12582,12583 ,0,0,0}, - {29635,29639,29269 ,12580,12584,12188 ,0,0,0}, {29640,29641,29642 ,12585,12586,12587 ,0,0,0}, - {29635,29265,29640 ,12580,12579,12585 ,0,0,0}, {29632,29566,29565 ,12576,12575,12588 ,0,0,0}, - {29634,29643,29644 ,12578,12589,12590 ,0,0,0}, {29645,29646,29644 ,12591,12592,12590 ,0,0,0}, - {29644,29643,29647 ,12590,12589,12593 ,0,0,0}, {29565,29145,29648 ,12588,12594,12595 ,0,0,0}, - {29649,29650,29651 ,12596,12597,12598 ,0,0,0}, {29650,29652,29653 ,12597,12599,12600 ,0,0,0}, - {29652,29654,29653 ,12599,12601,12600 ,0,0,0}, {29655,29651,29656 ,12602,12598,12603 ,0,0,0}, - {29657,29656,29143 ,12604,12603,12057 ,0,0,0}, {29145,29656,29648 ,12594,12603,12595 ,0,0,0}, - {29656,29148,29143 ,12603,12605,12057 ,0,0,0}, {29657,29655,29656 ,12604,12602,12603 ,0,0,0}, - {29637,29658,29659 ,12582,12606,12607 ,0,0,0}, {29570,29627,29571 ,12570,12566,12565 ,0,0,0}, - {29611,29582,29581 ,12538,12608,12539 ,0,0,0}, {29541,29582,29660 ,12609,12608,12610 ,0,0,0}, - {29611,29660,29582 ,12538,12610,12608 ,0,0,0}, {29661,29583,29541 ,12611,12612,12609 ,0,0,0}, - {29541,29660,29661 ,12609,12610,12611 ,0,0,0}, {29584,29661,29662 ,12613,12611,12614 ,0,0,0}, - {29661,29584,29583 ,12611,12613,12612 ,0,0,0}, {29663,29585,29662 ,12615,12616,12614 ,0,0,0}, - {29584,29662,29585 ,12613,12614,12616 ,0,0,0}, {29586,29585,29663 ,12617,12616,12615 ,0,0,0}, - {29663,29664,29586 ,12615,12618,12617 ,0,0,0}, {29586,29664,29587 ,12617,12618,12619 ,0,0,0}, - {29587,29664,29665 ,12619,12618,12620 ,0,0,0}, {29666,29667,29668 ,12621,12622,12623 ,0,0,0}, - {29669,29588,29665 ,12624,12625,12620 ,0,0,0}, {29587,29665,29588 ,12619,12620,12625 ,0,0,0}, - {29669,29670,29589 ,12624,12626,12627 ,0,0,0}, {29589,29588,29669 ,12627,12625,12624 ,0,0,0}, - {29506,29590,29670 ,12628,12629,12626 ,0,0,0}, {29670,29590,29589 ,12626,12629,12627 ,0,0,0}, - {29671,29591,29506 ,12630,12631,12628 ,0,0,0}, {29506,29670,29671 ,12628,12626,12630 ,0,0,0}, - {29591,29672,29592 ,12631,12632,12633 ,0,0,0}, {29672,29591,29671 ,12632,12631,12630 ,0,0,0}, - {29593,29592,29673 ,12634,12633,12635 ,0,0,0}, {29672,29673,29592 ,12632,12635,12633 ,0,0,0}, - {29674,29593,29673 ,12636,12634,12635 ,0,0,0}, {29674,29594,29593 ,12636,12637,12634 ,0,0,0}, - {29674,29675,29594 ,12636,12638,12637 ,0,0,0}, {29676,29677,29678 ,12639,12640,12641 ,0,0,0}, - {29595,29675,29679 ,12642,12638,12643 ,0,0,0}, {29675,29595,29594 ,12638,12642,12637 ,0,0,0}, - {29680,29552,29679 ,12644,12645,12643 ,0,0,0}, {29595,29679,29552 ,12642,12643,12645 ,0,0,0}, - {29596,29680,29597 ,12646,12644,12647 ,0,0,0}, {29596,29552,29680 ,12646,12645,12644 ,0,0,0}, - {29598,29597,29681 ,12648,12647,12649 ,0,0,0}, {29680,29681,29597 ,12644,12649,12647 ,0,0,0}, - {29682,29599,29598 ,12650,12651,12648 ,0,0,0}, {29598,29681,29682 ,12648,12649,12650 ,0,0,0}, - {29599,29683,29600 ,12651,12652,12653 ,0,0,0}, {29683,29599,29682 ,12652,12651,12650 ,0,0,0}, - {29601,29600,29684 ,12654,12653,12655 ,0,0,0}, {29683,29684,29600 ,12652,12655,12653 ,0,0,0}, - {29685,29601,29684 ,12656,12654,12655 ,0,0,0}, {29685,29602,29601 ,12656,12657,12654 ,0,0,0}, - {29685,29686,29602 ,12656,12658,12657 ,0,0,0}, {29687,29688,29689 ,12659,12660,12661 ,0,0,0}, - {29603,29686,29688 ,12662,12658,12660 ,0,0,0}, {29686,29603,29602 ,12658,12662,12657 ,0,0,0}, - {29690,29604,29688 ,12663,12664,12660 ,0,0,0}, {29603,29688,29604 ,12662,12660,12664 ,0,0,0}, - {29691,29692,29693 ,12665,12666,12667 ,0,0,0}, {29605,29604,29690 ,12668,12664,12663 ,0,0,0}, - {29694,29695,29696 ,12669,12670,12671 ,0,0,0}, {29697,29698,29699 ,12672,12673,12674 ,0,0,0}, - {29700,29701,29702 ,12675,12676,12677 ,0,0,0}, {29703,29704,29705 ,12678,12679,12680 ,0,0,0}, - {29706,29707,29694 ,12681,12682,12669 ,0,0,0}, {29708,29709,29710 ,12683,12684,12685 ,0,0,0}, - {29711,29712,29707 ,12686,12687,12682 ,0,0,0}, {29708,29703,29709 ,12683,12678,12684 ,0,0,0}, - {29707,29713,29714 ,12682,12688,12689 ,0,0,0}, {29217,28768,29710 ,12690,726,12685 ,0,0,0}, - {29715,29605,29690 ,12691,12668,12663 ,0,0,0}, {29605,29715,29606 ,12668,12691,12692 ,0,0,0}, - {29606,29691,29607 ,12692,12665,12693 ,0,0,0}, {29687,29690,29688 ,12659,12663,12660 ,0,0,0}, - {29716,29717,29608 ,12694,12695,12696 ,0,0,0}, {29691,29716,29607 ,12665,12694,12693 ,0,0,0}, - {29714,29716,29693 ,12689,12694,12667 ,0,0,0}, {29607,29716,29608 ,12693,12694,12696 ,0,0,0}, - {29717,29718,29237 ,12695,12697,12698 ,0,0,0}, {29717,29237,29609 ,12695,12698,12699 ,0,0,0}, - {28639,29237,29719 ,730,12698,12700 ,0,0,0}, {29656,29145,29148 ,12603,12594,12605 ,0,0,0}, - {29649,29651,29655 ,12596,12598,12602 ,0,0,0}, {29659,29658,29720 ,12607,12606,12701 ,0,0,0}, - {29648,29632,29565 ,12595,12576,12588 ,0,0,0}, {29648,29651,29721 ,12595,12598,12702 ,0,0,0}, - {29722,29630,29634 ,12703,12572,12578 ,0,0,0}, {29632,29721,29633 ,12576,12702,12577 ,0,0,0}, - {29723,29629,29722 ,12704,12569,12703 ,0,0,0}, {29633,29631,29632 ,12577,12574,12576 ,0,0,0}, - {29724,29628,29723 ,12705,12567,12704 ,0,0,0}, {29634,29630,29631 ,12578,12572,12574 ,0,0,0}, - {29725,29627,29724 ,12706,12566,12705 ,0,0,0}, {29722,29629,29630 ,12703,12569,12572 ,0,0,0}, - {29726,29626,29725 ,12707,12564,12706 ,0,0,0}, {29723,29628,29629 ,12704,12567,12569 ,0,0,0}, - {29727,29625,29726 ,12708,12561,12707 ,0,0,0}, {29724,29627,29628 ,12705,12566,12567 ,0,0,0}, - {29728,29621,29727 ,12709,12557,12708 ,0,0,0}, {29725,29626,29627 ,12706,12564,12566 ,0,0,0}, - {29728,29729,29620 ,12709,12710,12554 ,0,0,0}, {29625,29626,29726 ,12561,12564,12707 ,0,0,0}, - {29730,29619,29729 ,12711,12553,12710 ,0,0,0}, {29621,29625,29727 ,12557,12561,12708 ,0,0,0}, - {29623,29617,29730 ,12559,12550,12711 ,0,0,0}, {29620,29621,29728 ,12554,12557,12709 ,0,0,0}, - {29731,29618,29623 ,12712,12551,12559 ,0,0,0}, {29619,29620,29729 ,12553,12554,12710 ,0,0,0}, - {29732,29615,29731 ,12713,12544,12712 ,0,0,0}, {29617,29619,29730 ,12550,12553,12711 ,0,0,0}, - {29733,29616,29732 ,12714,12547,12713 ,0,0,0}, {29623,29618,29617 ,12559,12551,12550 ,0,0,0}, - {29734,29610,29733 ,12715,12537,12714 ,0,0,0}, {29731,29615,29618 ,12712,12544,12551 ,0,0,0}, - {29734,29735,29611 ,12715,12716,12538 ,0,0,0}, {29616,29615,29732 ,12547,12544,12713 ,0,0,0}, - {29736,29660,29735 ,12717,12610,12716 ,0,0,0}, {29610,29616,29733 ,12537,12547,12714 ,0,0,0}, - {29737,29661,29736 ,12718,12611,12717 ,0,0,0}, {29611,29610,29734 ,12538,12537,12715 ,0,0,0}, - {29738,29662,29737 ,12719,12614,12718 ,0,0,0}, {29660,29611,29735 ,12610,12538,12716 ,0,0,0}, - {29739,29663,29738 ,12720,12615,12719 ,0,0,0}, {29661,29660,29736 ,12611,12610,12717 ,0,0,0}, - {29740,29664,29739 ,12721,12618,12720 ,0,0,0}, {29737,29662,29661 ,12718,12614,12611 ,0,0,0}, - {29740,29741,29665 ,12721,12722,12620 ,0,0,0}, {29663,29662,29738 ,12615,12614,12719 ,0,0,0}, - {29742,29669,29741 ,12723,12624,12722 ,0,0,0}, {29664,29663,29739 ,12618,12615,12720 ,0,0,0}, - {29666,29670,29742 ,12621,12626,12723 ,0,0,0}, {29665,29664,29740 ,12620,12618,12721 ,0,0,0}, - {29743,29671,29666 ,12724,12630,12621 ,0,0,0}, {29669,29665,29741 ,12624,12620,12722 ,0,0,0}, - {29744,29672,29743 ,12725,12632,12724 ,0,0,0}, {29670,29669,29742 ,12626,12624,12723 ,0,0,0}, - {29745,29673,29744 ,12726,12635,12725 ,0,0,0}, {29666,29671,29670 ,12621,12630,12626 ,0,0,0}, - {29746,29674,29745 ,12727,12636,12726 ,0,0,0}, {29743,29672,29671 ,12724,12632,12630 ,0,0,0}, - {29746,29747,29675 ,12727,12728,12638 ,0,0,0}, {29673,29672,29744 ,12635,12632,12725 ,0,0,0}, - {29748,29679,29747 ,12729,12643,12728 ,0,0,0}, {29674,29673,29745 ,12636,12635,12726 ,0,0,0}, - {29749,29680,29748 ,12730,12644,12729 ,0,0,0}, {29675,29674,29746 ,12638,12636,12727 ,0,0,0}, - {29750,29681,29749 ,12731,12649,12730 ,0,0,0}, {29679,29675,29747 ,12643,12638,12728 ,0,0,0}, - {29751,29682,29750 ,12732,12650,12731 ,0,0,0}, {29748,29680,29679 ,12729,12644,12643 ,0,0,0}, - {29752,29683,29751 ,12733,12652,12732 ,0,0,0}, {29749,29681,29680 ,12730,12649,12644 ,0,0,0}, - {29753,29684,29752 ,12734,12655,12733 ,0,0,0}, {29750,29682,29681 ,12731,12650,12649 ,0,0,0}, - {29754,29685,29753 ,12735,12656,12734 ,0,0,0}, {29751,29683,29682 ,12732,12652,12650 ,0,0,0}, - {29754,29689,29686 ,12735,12661,12658 ,0,0,0}, {29684,29683,29752 ,12655,12652,12733 ,0,0,0}, - {29690,29687,29755 ,12663,12659,12736 ,0,0,0}, {29685,29684,29753 ,12656,12655,12734 ,0,0,0}, - {29711,29693,29699 ,12686,12667,12674 ,0,0,0}, {29686,29685,29754 ,12658,12656,12735 ,0,0,0}, - {29715,29755,29692 ,12691,12736,12666 ,0,0,0}, {29686,29689,29688 ,12658,12661,12660 ,0,0,0}, - {29755,29756,29692 ,12736,12737,12666 ,0,0,0}, {29714,29717,29716 ,12689,12695,12694 ,0,0,0}, - {29715,29691,29606 ,12691,12665,12692 ,0,0,0}, {29755,29715,29690 ,12736,12691,12663 ,0,0,0}, - {29714,29711,29707 ,12689,12686,12682 ,0,0,0}, {29691,29715,29692 ,12665,12691,12666 ,0,0,0}, - {29718,29713,29757 ,12697,12688,12738 ,0,0,0}, {29718,29719,29237 ,12697,12700,12698 ,0,0,0}, - {29608,29717,29609 ,12696,12695,12699 ,0,0,0}, {29718,29717,29713 ,12697,12695,12688 ,0,0,0}, - {29758,29719,29718 ,12739,12700,12697 ,0,0,0}, {29656,29651,29648 ,12603,12598,12595 ,0,0,0}, - {29652,29650,29649 ,12599,12597,12596 ,0,0,0}, {29640,29265,29261 ,12585,12579,12740 ,0,0,0}, - {29648,29721,29632 ,12595,12702,12576 ,0,0,0}, {29759,29721,29650 ,12741,12702,12597 ,0,0,0}, - {29644,29646,29722 ,12590,12592,12703 ,0,0,0}, {29643,29633,29759 ,12589,12577,12741 ,0,0,0}, - {29646,29760,29723 ,12592,12742,12704 ,0,0,0}, {29643,29634,29633 ,12589,12578,12577 ,0,0,0}, - {29760,29761,29724 ,12742,12743,12705 ,0,0,0}, {29644,29722,29634 ,12590,12703,12578 ,0,0,0}, - {29761,29762,29725 ,12743,12744,12706 ,0,0,0}, {29646,29723,29722 ,12592,12704,12703 ,0,0,0}, - {29762,29763,29726 ,12744,12745,12707 ,0,0,0}, {29760,29724,29723 ,12742,12705,12704 ,0,0,0}, - {29763,29764,29727 ,12745,12746,12708 ,0,0,0}, {29761,29725,29724 ,12743,12706,12705 ,0,0,0}, - {29764,29765,29728 ,12746,12747,12709 ,0,0,0}, {29762,29726,29725 ,12744,12707,12706 ,0,0,0}, - {29765,29766,29729 ,12747,12748,12710 ,0,0,0}, {29763,29727,29726 ,12745,12708,12707 ,0,0,0}, - {29766,29624,29730 ,12748,12560,12711 ,0,0,0}, {29728,29727,29764 ,12709,12708,12746 ,0,0,0}, - {29767,29768,29769 ,12749,12750,12751 ,0,0,0}, {29729,29728,29765 ,12710,12709,12747 ,0,0,0}, - {29622,29768,29731 ,12558,12750,12712 ,0,0,0}, {29730,29729,29766 ,12711,12710,12748 ,0,0,0}, - {29768,29767,29732 ,12750,12749,12713 ,0,0,0}, {29623,29730,29624 ,12559,12711,12560 ,0,0,0}, - {29767,29770,29733 ,12749,12752,12714 ,0,0,0}, {29622,29731,29623 ,12558,12712,12559 ,0,0,0}, - {29770,29771,29734 ,12752,12753,12715 ,0,0,0}, {29768,29732,29731 ,12750,12713,12712 ,0,0,0}, - {29771,29772,29735 ,12753,12754,12716 ,0,0,0}, {29767,29733,29732 ,12749,12714,12713 ,0,0,0}, - {29772,29773,29736 ,12754,12755,12717 ,0,0,0}, {29734,29733,29770 ,12715,12714,12752 ,0,0,0}, - {29614,29737,29773 ,12543,12718,12755 ,0,0,0}, {29735,29734,29771 ,12716,12715,12753 ,0,0,0}, - {29614,29613,29738 ,12543,12542,12719 ,0,0,0}, {29736,29735,29772 ,12717,12716,12754 ,0,0,0}, - {29613,29774,29739 ,12542,12756,12720 ,0,0,0}, {29773,29737,29736 ,12755,12718,12717 ,0,0,0}, - {29774,29775,29740 ,12756,12757,12721 ,0,0,0}, {29614,29738,29737 ,12543,12719,12718 ,0,0,0}, - {29775,29776,29741 ,12757,12758,12722 ,0,0,0}, {29613,29739,29738 ,12542,12720,12719 ,0,0,0}, - {29776,29667,29742 ,12758,12622,12723 ,0,0,0}, {29740,29739,29774 ,12721,12720,12756 ,0,0,0}, - {29777,29778,29779 ,12759,12760,12761 ,0,0,0}, {29741,29740,29775 ,12722,12721,12757 ,0,0,0}, - {29668,29780,29743 ,12623,12762,12724 ,0,0,0}, {29742,29741,29776 ,12723,12722,12758 ,0,0,0}, - {29780,29781,29744 ,12762,12763,12725 ,0,0,0}, {29666,29742,29667 ,12621,12723,12622 ,0,0,0}, - {29781,29782,29745 ,12763,12764,12726 ,0,0,0}, {29668,29743,29666 ,12623,12724,12621 ,0,0,0}, - {29782,29783,29746 ,12764,12765,12727 ,0,0,0}, {29780,29744,29743 ,12762,12725,12724 ,0,0,0}, - {29783,29784,29747 ,12765,12766,12728 ,0,0,0}, {29781,29745,29744 ,12763,12726,12725 ,0,0,0}, - {29784,29785,29748 ,12766,12767,12729 ,0,0,0}, {29746,29745,29782 ,12727,12726,12764 ,0,0,0}, - {29785,29676,29749 ,12767,12639,12730 ,0,0,0}, {29747,29746,29783 ,12728,12727,12765 ,0,0,0}, - {29676,29678,29750 ,12639,12641,12731 ,0,0,0}, {29748,29747,29784 ,12729,12728,12766 ,0,0,0}, - {29678,29786,29751 ,12641,12768,12732 ,0,0,0}, {29785,29749,29748 ,12767,12730,12729 ,0,0,0}, - {29786,29787,29752 ,12768,12769,12733 ,0,0,0}, {29676,29750,29749 ,12639,12731,12730 ,0,0,0}, - {29787,29788,29753 ,12769,12770,12734 ,0,0,0}, {29678,29751,29750 ,12641,12732,12731 ,0,0,0}, - {29788,29789,29754 ,12770,12771,12735 ,0,0,0}, {29786,29752,29751 ,12768,12733,12732 ,0,0,0}, - {29789,29790,29689 ,12771,12772,12661 ,0,0,0}, {29787,29753,29752 ,12769,12734,12733 ,0,0,0}, - {29790,29791,29687 ,12772,12773,12659 ,0,0,0}, {29788,29754,29753 ,12770,12735,12734 ,0,0,0}, - {29791,29756,29755 ,12773,12737,12736 ,0,0,0}, {29789,29689,29754 ,12771,12661,12735 ,0,0,0}, - {29756,29699,29692 ,12737,12674,12666 ,0,0,0}, {29687,29689,29790 ,12659,12661,12772 ,0,0,0}, - {29792,29793,29794 ,12774,12775,12776 ,0,0,0}, {29791,29755,29687 ,12773,12736,12659 ,0,0,0}, - {29712,29694,29707 ,12687,12669,12682 ,0,0,0}, {29706,29795,29757 ,12681,12777,12738 ,0,0,0}, - {29691,29693,29716 ,12665,12667,12694 ,0,0,0}, {29699,29693,29692 ,12674,12667,12666 ,0,0,0}, - {29796,29757,29795 ,12778,12738,12777 ,0,0,0}, {29757,29758,29718 ,12738,12739,12697 ,0,0,0}, - {29717,29714,29713 ,12695,12689,12688 ,0,0,0}, {29713,29706,29757 ,12688,12681,12738 ,0,0,0}, - {29796,29758,29757 ,12778,12739,12738 ,0,0,0}, {29650,29721,29651 ,12597,12702,12598 ,0,0,0}, - {29797,29653,29654 ,12779,12600,12601 ,0,0,0}, {29797,29658,29653 ,12779,12606,12600 ,0,0,0}, - {29721,29759,29633 ,12702,12741,12577 ,0,0,0}, {29798,29759,29653 ,12780,12741,12600 ,0,0,0}, - {29646,29799,29760 ,12592,12781,12742 ,0,0,0}, {29647,29643,29798 ,12593,12589,12780 ,0,0,0}, - {29760,29800,29761 ,12742,12782,12743 ,0,0,0}, {29647,29645,29644 ,12593,12591,12590 ,0,0,0}, - {29801,29802,29803 ,12783,12784,12785 ,0,0,0}, {29645,29799,29646 ,12591,12781,12592 ,0,0,0}, - {29762,29761,29804 ,12744,12743,12786 ,0,0,0}, {29799,29800,29760 ,12781,12782,12742 ,0,0,0}, - {29763,29762,29803 ,12745,12744,12785 ,0,0,0}, {29800,29804,29761 ,12782,12786,12743 ,0,0,0}, - {29764,29763,29802 ,12746,12745,12784 ,0,0,0}, {29804,29803,29762 ,12786,12785,12744 ,0,0,0}, - {29765,29764,29805 ,12747,12746,12787 ,0,0,0}, {29803,29802,29763 ,12785,12784,12745 ,0,0,0}, - {29766,29765,29806 ,12748,12747,12788 ,0,0,0}, {29802,29805,29764 ,12784,12787,12746 ,0,0,0}, - {29624,29766,29807 ,12560,12748,12789 ,0,0,0}, {29805,29806,29765 ,12787,12788,12747 ,0,0,0}, - {29622,29624,29808 ,12558,12560,12790 ,0,0,0}, {29806,29807,29766 ,12788,12789,12748 ,0,0,0}, - {29768,29622,29809 ,12750,12558,12791 ,0,0,0}, {29808,29624,29807 ,12790,12560,12789 ,0,0,0}, - {29810,29811,29812 ,12792,12793,12794 ,0,0,0}, {29809,29622,29808 ,12791,12558,12790 ,0,0,0}, - {29770,29767,29813 ,12752,12749,12795 ,0,0,0}, {29809,29769,29768 ,12791,12751,12750 ,0,0,0}, - {29771,29770,29812 ,12753,12752,12794 ,0,0,0}, {29769,29813,29767 ,12751,12795,12749 ,0,0,0}, - {29772,29771,29811 ,12754,12753,12793 ,0,0,0}, {29813,29812,29770 ,12795,12794,12752 ,0,0,0}, - {29773,29772,29814 ,12755,12754,12796 ,0,0,0}, {29812,29811,29771 ,12794,12793,12753 ,0,0,0}, - {29614,29773,29815 ,12543,12755,12797 ,0,0,0}, {29814,29772,29811 ,12796,12754,12793 ,0,0,0}, - {29816,29817,29818 ,12798,12799,12800 ,0,0,0}, {29815,29773,29814 ,12797,12755,12796 ,0,0,0}, - {29774,29613,29819 ,12756,12542,12801 ,0,0,0}, {29815,29612,29614 ,12797,12541,12543 ,0,0,0}, - {29775,29774,29818 ,12757,12756,12800 ,0,0,0}, {29612,29819,29613 ,12541,12801,12542 ,0,0,0}, - {29776,29775,29817 ,12758,12757,12799 ,0,0,0}, {29819,29818,29774 ,12801,12800,12756 ,0,0,0}, - {29667,29776,29820 ,12622,12758,12802 ,0,0,0}, {29818,29817,29775 ,12800,12799,12757 ,0,0,0}, - {29668,29667,29821 ,12623,12622,12803 ,0,0,0}, {29817,29820,29776 ,12799,12802,12758 ,0,0,0}, - {29780,29668,29822 ,12762,12623,12804 ,0,0,0}, {29821,29667,29820 ,12803,12622,12802 ,0,0,0}, - {29781,29780,29823 ,12763,12762,12805 ,0,0,0}, {29822,29668,29821 ,12804,12623,12803 ,0,0,0}, - {29782,29781,29777 ,12764,12763,12759 ,0,0,0}, {29822,29823,29780 ,12804,12805,12762 ,0,0,0}, - {29783,29782,29779 ,12765,12764,12761 ,0,0,0}, {29823,29777,29781 ,12805,12759,12763 ,0,0,0}, - {29784,29783,29824 ,12766,12765,12806 ,0,0,0}, {29777,29779,29782 ,12759,12761,12764 ,0,0,0}, - {29785,29784,29825 ,12767,12766,12807 ,0,0,0}, {29779,29824,29783 ,12761,12806,12765 ,0,0,0}, - {29676,29785,29826 ,12639,12767,12808 ,0,0,0}, {29825,29784,29824 ,12807,12766,12806 ,0,0,0}, - {29827,29828,29829 ,12809,12810,12811 ,0,0,0}, {29826,29785,29825 ,12808,12767,12807 ,0,0,0}, - {29786,29678,29830 ,12768,12641,12812 ,0,0,0}, {29826,29677,29676 ,12808,12640,12639 ,0,0,0}, - {29787,29786,29829 ,12769,12768,12811 ,0,0,0}, {29677,29830,29678 ,12640,12812,12641 ,0,0,0}, - {29788,29787,29828 ,12770,12769,12810 ,0,0,0}, {29830,29829,29786 ,12812,12811,12768 ,0,0,0}, - {29789,29788,29831 ,12771,12770,12813 ,0,0,0}, {29829,29828,29787 ,12811,12810,12769 ,0,0,0}, - {29790,29789,29832 ,12772,12771,12814 ,0,0,0}, {29828,29831,29788 ,12810,12813,12770 ,0,0,0}, - {29791,29790,29833 ,12773,12772,12815 ,0,0,0}, {29831,29832,29789 ,12813,12814,12771 ,0,0,0}, - {29756,29791,29834 ,12737,12773,12816 ,0,0,0}, {29832,29833,29790 ,12814,12815,12772 ,0,0,0}, - {29699,29756,29697 ,12674,12737,12672 ,0,0,0}, {29833,29834,29791 ,12815,12816,12773 ,0,0,0}, - {29711,29699,29698 ,12686,12674,12673 ,0,0,0}, {29834,29697,29756 ,12816,12672,12737 ,0,0,0}, - {29835,29705,29794 ,12817,12680,12776 ,0,0,0}, {29836,29695,29694 ,12818,12670,12669 ,0,0,0}, - {29693,29711,29714 ,12667,12686,12689 ,0,0,0}, {29698,29712,29711 ,12673,12687,12686 ,0,0,0}, - {29837,29795,29793 ,12819,12777,12775 ,0,0,0}, {29837,29838,29795 ,12819,12820,12777 ,0,0,0}, - {29713,29707,29706 ,12688,12682,12681 ,0,0,0}, {29706,29696,29795 ,12681,12671,12777 ,0,0,0}, - {29796,29795,29838 ,12778,12777,12820 ,0,0,0}, {29650,29653,29759 ,12597,12600,12741 ,0,0,0}, - {29720,29658,29797 ,12701,12606,12779 ,0,0,0}, {29647,29839,29645 ,12593,12821,12591 ,0,0,0}, - {29759,29798,29643 ,12741,12780,12589 ,0,0,0}, {29658,29840,29798 ,12606,12822,12780 ,0,0,0}, - {29799,29645,29841 ,12781,12591,12823 ,0,0,0}, {29840,29839,29647 ,12822,12821,12593 ,0,0,0}, - {29800,29799,29842 ,12782,12781,12824 ,0,0,0}, {29645,29839,29841 ,12591,12821,12823 ,0,0,0}, - {29804,29800,29843 ,12786,12782,12825 ,0,0,0}, {29799,29841,29842 ,12781,12823,12824 ,0,0,0}, - {29803,29804,29844 ,12785,12786,12826 ,0,0,0}, {29842,29843,29800 ,12824,12825,12782 ,0,0,0}, - {29845,29805,29802 ,12827,12787,12784 ,0,0,0}, {29843,29844,29804 ,12825,12826,12786 ,0,0,0}, - {29846,29847,29848 ,12828,12829,12830 ,0,0,0}, {29844,29801,29803 ,12826,12783,12785 ,0,0,0}, - {29805,29849,29806 ,12787,12831,12788 ,0,0,0}, {29801,29845,29802 ,12783,12827,12784 ,0,0,0}, - {29806,29847,29807 ,12788,12829,12789 ,0,0,0}, {29845,29849,29805 ,12827,12831,12787 ,0,0,0}, - {29807,29846,29808 ,12789,12828,12790 ,0,0,0}, {29849,29847,29806 ,12831,12829,12788 ,0,0,0}, - {29808,29850,29809 ,12790,12832,12791 ,0,0,0}, {29847,29846,29807 ,12829,12828,12789 ,0,0,0}, - {29809,29851,29769 ,12791,12833,12751 ,0,0,0}, {29846,29850,29808 ,12828,12832,12790 ,0,0,0}, - {29813,29769,29852 ,12795,12751,12834 ,0,0,0}, {29850,29851,29809 ,12832,12833,12791 ,0,0,0}, - {29812,29813,29853 ,12794,12795,12835 ,0,0,0}, {29851,29852,29769 ,12833,12834,12751 ,0,0,0}, - {29854,29855,29856 ,12836,12837,12838 ,0,0,0}, {29852,29853,29813 ,12834,12835,12795 ,0,0,0}, - {29811,29857,29814 ,12793,12839,12796 ,0,0,0}, {29853,29810,29812 ,12835,12792,12794 ,0,0,0}, - {29814,29858,29815 ,12796,12840,12797 ,0,0,0}, {29810,29857,29811 ,12792,12839,12793 ,0,0,0}, - {29815,29859,29612 ,12797,12841,12541 ,0,0,0}, {29857,29858,29814 ,12839,12840,12796 ,0,0,0}, - {29819,29612,29860 ,12801,12541,12842 ,0,0,0}, {29858,29859,29815 ,12840,12841,12797 ,0,0,0}, - {29818,29819,29861 ,12800,12801,12843 ,0,0,0}, {29859,29860,29612 ,12841,12842,12541 ,0,0,0}, - {29862,29863,29864 ,12844,12845,12846 ,0,0,0}, {29860,29861,29819 ,12842,12843,12801 ,0,0,0}, - {29817,29865,29820 ,12799,12847,12802 ,0,0,0}, {29861,29816,29818 ,12843,12798,12800 ,0,0,0}, - {29820,29866,29821 ,12802,12848,12803 ,0,0,0}, {29816,29865,29817 ,12798,12847,12799 ,0,0,0}, - {29821,29867,29822 ,12803,12849,12804 ,0,0,0}, {29865,29866,29820 ,12847,12848,12802 ,0,0,0}, - {29822,29868,29823 ,12804,12850,12805 ,0,0,0}, {29866,29867,29821 ,12848,12849,12803 ,0,0,0}, - {29777,29823,29869 ,12759,12805,12851 ,0,0,0}, {29867,29868,29822 ,12849,12850,12804 ,0,0,0}, - {29870,29871,29872 ,12852,12853,12854 ,0,0,0}, {29868,29869,29823 ,12850,12851,12805 ,0,0,0}, - {29779,29873,29824 ,12761,12855,12806 ,0,0,0}, {29869,29778,29777 ,12851,12760,12759 ,0,0,0}, - {29824,29871,29825 ,12806,12853,12807 ,0,0,0}, {29778,29873,29779 ,12760,12855,12761 ,0,0,0}, - {29825,29870,29826 ,12807,12852,12808 ,0,0,0}, {29873,29871,29824 ,12855,12853,12806 ,0,0,0}, - {29826,29874,29677 ,12808,12856,12640 ,0,0,0}, {29871,29870,29825 ,12853,12852,12807 ,0,0,0}, - {29830,29677,29875 ,12812,12640,12857 ,0,0,0}, {29870,29874,29826 ,12852,12856,12808 ,0,0,0}, - {29829,29830,29876 ,12811,12812,12858 ,0,0,0}, {29874,29875,29677 ,12856,12857,12640 ,0,0,0}, - {29877,29831,29828 ,12859,12813,12810 ,0,0,0}, {29875,29876,29830 ,12857,12858,12812 ,0,0,0}, - {29878,29879,29880 ,12860,12861,12862 ,0,0,0}, {29876,29827,29829 ,12858,12809,12811 ,0,0,0}, - {29831,29881,29832 ,12813,12863,12814 ,0,0,0}, {29827,29877,29828 ,12809,12859,12810 ,0,0,0}, - {29832,29879,29833 ,12814,12861,12815 ,0,0,0}, {29877,29881,29831 ,12859,12863,12813 ,0,0,0}, - {29833,29878,29834 ,12815,12860,12816 ,0,0,0}, {29881,29879,29832 ,12863,12861,12814 ,0,0,0}, - {29834,29882,29697 ,12816,12864,12672 ,0,0,0}, {29879,29878,29833 ,12861,12860,12815 ,0,0,0}, - {29697,29883,29698 ,12672,12865,12673 ,0,0,0}, {29878,29882,29834 ,12860,12864,12816 ,0,0,0}, - {29698,29884,29712 ,12673,12866,12687 ,0,0,0}, {29882,29883,29697 ,12864,12865,12672 ,0,0,0}, - {29712,29836,29694 ,12687,12818,12669 ,0,0,0}, {29884,29698,29883 ,12866,12673,12865 ,0,0,0}, - {29701,29695,29885 ,12676,12670,12867 ,0,0,0}, {29712,29884,29836 ,12687,12866,12818 ,0,0,0}, - {29793,29886,29794 ,12775,12868,12776 ,0,0,0}, {29795,29696,29793 ,12777,12671,12775 ,0,0,0}, - {29706,29694,29696 ,12681,12669,12671 ,0,0,0}, {29696,29886,29793 ,12671,12868,12775 ,0,0,0}, - {29837,29793,29792 ,12819,12775,12774 ,0,0,0}, {29653,29658,29798 ,12600,12606,12780 ,0,0,0}, - {29638,29637,29659 ,12583,12582,12607 ,0,0,0}, {29839,29887,29841 ,12821,12869,12823 ,0,0,0}, - {29798,29840,29647 ,12780,12822,12593 ,0,0,0}, {29637,29888,29840 ,12582,12870,12822 ,0,0,0}, - {29842,29841,29889 ,12824,12823,12871 ,0,0,0}, {29839,29888,29887 ,12821,12870,12869 ,0,0,0}, - {29843,29842,29890 ,12825,12824,12872 ,0,0,0}, {29841,29887,29889 ,12823,12869,12871 ,0,0,0}, - {29844,29843,29891 ,12826,12825,12873 ,0,0,0}, {29842,29889,29890 ,12824,12871,12872 ,0,0,0}, - {29801,29844,29892 ,12783,12826,12874 ,0,0,0}, {29843,29890,29891 ,12825,12872,12873 ,0,0,0}, - {29845,29801,29893 ,12827,12783,12875 ,0,0,0}, {29844,29891,29892 ,12826,12873,12874 ,0,0,0}, - {29849,29845,29894 ,12831,12827,12876 ,0,0,0}, {29801,29892,29893 ,12783,12874,12875 ,0,0,0}, - {29847,29849,29895 ,12829,12831,12877 ,0,0,0}, {29893,29894,29845 ,12875,12876,12827 ,0,0,0}, - {29896,29897,29898 ,12878,12879,12880 ,0,0,0}, {29894,29895,29849 ,12876,12877,12831 ,0,0,0}, - {29846,29899,29850 ,12828,12881,12832 ,0,0,0}, {29895,29848,29847 ,12877,12830,12829 ,0,0,0}, - {29850,29898,29851 ,12832,12880,12833 ,0,0,0}, {29848,29899,29846 ,12830,12881,12828 ,0,0,0}, - {29851,29900,29852 ,12833,12882,12834 ,0,0,0}, {29899,29898,29850 ,12881,12880,12832 ,0,0,0}, - {29853,29852,29901 ,12835,12834,12883 ,0,0,0}, {29898,29900,29851 ,12880,12882,12833 ,0,0,0}, - {29810,29853,29902 ,12792,12835,12884 ,0,0,0}, {29852,29900,29901 ,12834,12882,12883 ,0,0,0}, - {29857,29810,29903 ,12839,12792,12885 ,0,0,0}, {29853,29901,29902 ,12835,12883,12884 ,0,0,0}, - {29858,29857,29904 ,12840,12839,12886 ,0,0,0}, {29902,29903,29810 ,12884,12885,12792 ,0,0,0}, - {29858,29905,29859 ,12840,12887,12841 ,0,0,0}, {29903,29904,29857 ,12885,12886,12839 ,0,0,0}, - {29859,29855,29860 ,12841,12837,12842 ,0,0,0}, {29904,29905,29858 ,12886,12887,12840 ,0,0,0}, - {29861,29860,29906 ,12843,12842,12888 ,0,0,0}, {29905,29855,29859 ,12887,12837,12841 ,0,0,0}, - {29816,29861,29907 ,12798,12843,12889 ,0,0,0}, {29860,29855,29906 ,12842,12837,12888 ,0,0,0}, - {29865,29816,29908 ,12847,12798,12890 ,0,0,0}, {29861,29906,29907 ,12843,12888,12889 ,0,0,0}, - {29866,29865,29909 ,12848,12847,12891 ,0,0,0}, {29907,29908,29816 ,12889,12890,12798 ,0,0,0}, - {29866,29910,29867 ,12848,12892,12849 ,0,0,0}, {29908,29909,29865 ,12890,12891,12847 ,0,0,0}, - {29867,29863,29868 ,12849,12845,12850 ,0,0,0}, {29909,29910,29866 ,12891,12892,12848 ,0,0,0}, - {29869,29868,29911 ,12851,12850,12893 ,0,0,0}, {29910,29863,29867 ,12892,12845,12849 ,0,0,0}, - {29778,29869,29912 ,12760,12851,12894 ,0,0,0}, {29868,29863,29911 ,12850,12845,12893 ,0,0,0}, - {29873,29778,29913 ,12855,12760,12895 ,0,0,0}, {29869,29911,29912 ,12851,12893,12894 ,0,0,0}, - {29871,29873,29914 ,12853,12855,12896 ,0,0,0}, {29912,29913,29778 ,12894,12895,12760 ,0,0,0}, - {29915,29916,29917 ,12897,12898,12899 ,0,0,0}, {29913,29914,29873 ,12895,12896,12855 ,0,0,0}, - {29870,29918,29874 ,12852,12900,12856 ,0,0,0}, {29914,29872,29871 ,12896,12854,12853 ,0,0,0}, - {29874,29917,29875 ,12856,12899,12857 ,0,0,0}, {29872,29918,29870 ,12854,12900,12852 ,0,0,0}, - {29876,29875,29919 ,12858,12857,12901 ,0,0,0}, {29918,29917,29874 ,12900,12899,12856 ,0,0,0}, - {29827,29876,29920 ,12809,12858,12902 ,0,0,0}, {29875,29917,29919 ,12857,12899,12901 ,0,0,0}, - {29877,29827,29921 ,12859,12809,12903 ,0,0,0}, {29876,29919,29920 ,12858,12901,12902 ,0,0,0}, - {29881,29877,29922 ,12863,12859,12904 ,0,0,0}, {29827,29920,29921 ,12809,12902,12903 ,0,0,0}, - {29879,29881,29923 ,12861,12863,12905 ,0,0,0}, {29921,29922,29877 ,12903,12904,12859 ,0,0,0}, - {29924,29882,29878 ,12906,12864,12860 ,0,0,0}, {29922,29923,29881 ,12904,12905,12863 ,0,0,0}, - {29925,29926,29927 ,12907,12908,12909 ,0,0,0}, {29923,29880,29879 ,12905,12862,12861 ,0,0,0}, - {29882,29928,29883 ,12864,12910,12865 ,0,0,0}, {29880,29924,29878 ,12862,12906,12860 ,0,0,0}, - {29883,29927,29884 ,12865,12909,12866 ,0,0,0}, {29924,29928,29882 ,12906,12910,12864 ,0,0,0}, - {29884,29929,29836 ,12866,12911,12818 ,0,0,0}, {29928,29927,29883 ,12910,12909,12865 ,0,0,0}, - {29836,29885,29695 ,12818,12867,12670 ,0,0,0}, {29927,29929,29884 ,12909,12911,12866 ,0,0,0}, - {29695,29701,29886 ,12670,12676,12868 ,0,0,0}, {29836,29929,29885 ,12818,12911,12867 ,0,0,0}, - {29930,29794,29705 ,12912,12776,12680 ,0,0,0}, {29931,29792,29794 ,12913,12774,12776 ,0,0,0}, - {29696,29695,29886 ,12671,12670,12868 ,0,0,0}, {29886,29835,29794 ,12868,12817,12776 ,0,0,0}, - {29930,29931,29794 ,12912,12913,12776 ,0,0,0}, {29658,29637,29840 ,12606,12582,12822 ,0,0,0}, - {29932,29636,29638 ,12914,12581,12583 ,0,0,0}, {29889,29887,29642 ,12871,12869,12587 ,0,0,0}, - {29840,29888,29839 ,12822,12870,12821 ,0,0,0}, {29636,29933,29888 ,12581,12915,12870 ,0,0,0}, - {29890,29889,29934 ,12872,12871,12916 ,0,0,0}, {29887,29933,29642 ,12869,12915,12587 ,0,0,0}, - {29935,29934,29936 ,12917,12916,12918 ,0,0,0}, {29889,29642,29934 ,12871,12587,12916 ,0,0,0}, - {29935,29937,29891 ,12917,12919,12873 ,0,0,0}, {29891,29890,29935 ,12873,12872,12917 ,0,0,0}, - {29937,29938,29892 ,12919,12920,12874 ,0,0,0}, {29892,29891,29937 ,12874,12873,12919 ,0,0,0}, - {29938,29939,29893 ,12920,12921,12875 ,0,0,0}, {29893,29892,29938 ,12875,12874,12920 ,0,0,0}, - {29939,29940,29894 ,12921,12922,12876 ,0,0,0}, {29894,29893,29939 ,12876,12875,12921 ,0,0,0}, - {29940,29941,29895 ,12922,12923,12877 ,0,0,0}, {29895,29894,29940 ,12877,12876,12922 ,0,0,0}, - {29941,29942,29848 ,12923,12924,12830 ,0,0,0}, {29848,29895,29941 ,12830,12877,12923 ,0,0,0}, - {29942,29896,29899 ,12924,12878,12881 ,0,0,0}, {29848,29942,29899 ,12830,12924,12881 ,0,0,0}, - {29252,29943,29944 ,12925,12926,12927 ,0,0,0}, {29899,29896,29898 ,12881,12878,12880 ,0,0,0}, - {29900,29945,29901 ,12882,12928,12883 ,0,0,0}, {29898,29897,29900 ,12880,12879,12882 ,0,0,0}, - {29946,29945,29944 ,12929,12928,12927 ,0,0,0}, {29897,29945,29900 ,12879,12928,12882 ,0,0,0}, - {29946,29947,29902 ,12929,12930,12884 ,0,0,0}, {29902,29901,29946 ,12884,12883,12929 ,0,0,0}, - {29947,29948,29903 ,12930,12931,12885 ,0,0,0}, {29903,29902,29947 ,12885,12884,12930 ,0,0,0}, - {29948,29949,29904 ,12931,12932,12886 ,0,0,0}, {29904,29903,29948 ,12886,12885,12931 ,0,0,0}, - {29949,29856,29905 ,12932,12838,12887 ,0,0,0}, {29904,29949,29905 ,12886,12932,12887 ,0,0,0}, - {29950,29951,29952 ,12933,12934,12935 ,0,0,0}, {29905,29856,29855 ,12887,12838,12837 ,0,0,0}, - {29854,29951,29906 ,12836,12934,12888 ,0,0,0}, {29855,29854,29906 ,12837,12836,12888 ,0,0,0}, - {29951,29953,29907 ,12934,12936,12889 ,0,0,0}, {29907,29906,29951 ,12889,12888,12934 ,0,0,0}, - {29953,29954,29908 ,12936,12937,12890 ,0,0,0}, {29908,29907,29953 ,12890,12889,12936 ,0,0,0}, - {29954,29955,29909 ,12937,12938,12891 ,0,0,0}, {29909,29908,29954 ,12891,12890,12937 ,0,0,0}, - {29955,29864,29910 ,12938,12846,12892 ,0,0,0}, {29909,29955,29910 ,12891,12938,12892 ,0,0,0}, - {29956,29243,29957 ,12939,12940,12941 ,0,0,0}, {29910,29864,29863 ,12892,12846,12845 ,0,0,0}, - {29912,29911,29958 ,12894,12893,12942 ,0,0,0}, {29863,29862,29911 ,12845,12844,12893 ,0,0,0}, - {29959,29958,29956 ,12943,12942,12939 ,0,0,0}, {29911,29862,29958 ,12893,12844,12942 ,0,0,0}, - {29959,29960,29913 ,12943,12944,12895 ,0,0,0}, {29913,29912,29959 ,12895,12894,12943 ,0,0,0}, - {29960,29961,29914 ,12944,12945,12896 ,0,0,0}, {29914,29913,29960 ,12896,12895,12944 ,0,0,0}, - {29961,29962,29872 ,12945,12946,12854 ,0,0,0}, {29872,29914,29961 ,12854,12896,12945 ,0,0,0}, - {29962,29915,29918 ,12946,12897,12900 ,0,0,0}, {29872,29962,29918 ,12854,12946,12900 ,0,0,0}, - {29963,29964,29965 ,12947,12948,12949 ,0,0,0}, {29918,29915,29917 ,12900,12897,12899 ,0,0,0}, - {29916,29964,29919 ,12898,12948,12901 ,0,0,0}, {29917,29916,29919 ,12899,12898,12901 ,0,0,0}, - {29964,29966,29920 ,12948,12950,12902 ,0,0,0}, {29920,29919,29964 ,12902,12901,12948 ,0,0,0}, - {29966,29967,29921 ,12950,12951,12903 ,0,0,0}, {29921,29920,29966 ,12903,12902,12950 ,0,0,0}, - {29967,29968,29922 ,12951,12952,12904 ,0,0,0}, {29922,29921,29967 ,12904,12903,12951 ,0,0,0}, - {29968,29969,29923 ,12952,12953,12905 ,0,0,0}, {29923,29922,29968 ,12905,12904,12952 ,0,0,0}, - {29969,29970,29880 ,12953,12954,12862 ,0,0,0}, {29880,29923,29969 ,12862,12905,12953 ,0,0,0}, - {29970,29971,29924 ,12954,12955,12906 ,0,0,0}, {29924,29880,29970 ,12906,12862,12954 ,0,0,0}, - {29971,29925,29928 ,12955,12907,12910 ,0,0,0}, {29924,29971,29928 ,12906,12955,12910 ,0,0,0}, - {29929,29926,29972 ,12911,12908,12956 ,0,0,0}, {29928,29925,29927 ,12910,12907,12909 ,0,0,0}, - {29702,29701,29885 ,12677,12676,12867 ,0,0,0}, {29927,29926,29929 ,12909,12908,12911 ,0,0,0}, - {29700,29835,29701 ,12675,12817,12676 ,0,0,0}, {29929,29972,29885 ,12911,12956,12867 ,0,0,0}, - {29973,29709,29703 ,12957,12684,12678 ,0,0,0}, {29972,29702,29885 ,12956,12677,12867 ,0,0,0}, - {29700,29974,29975 ,12675,12958,12959 ,0,0,0}, {29976,29930,29705 ,12960,12912,12680 ,0,0,0}, - {29886,29701,29835 ,12868,12676,12817 ,0,0,0}, {29705,29835,29975 ,12680,12817,12959 ,0,0,0}, - {29704,29976,29705 ,12679,12960,12680 ,0,0,0}, {29637,29636,29888 ,12582,12581,12870 ,0,0,0}, - {29932,29639,29635 ,12914,12584,12580 ,0,0,0}, {29933,29635,29640 ,12915,12580,12585 ,0,0,0}, - {29888,29933,29887 ,12870,12915,12869 ,0,0,0}, {29642,29933,29640 ,12587,12915,12585 ,0,0,0}, - {29641,29936,29934 ,12586,12918,12916 ,0,0,0}, {29934,29642,29641 ,12916,12587,12586 ,0,0,0}, - {29936,29977,29935 ,12918,12961,12917 ,0,0,0}, {29978,29937,29977 ,12962,12919,12961 ,0,0,0}, - {29890,29934,29935 ,12872,12916,12917 ,0,0,0}, {29937,29935,29977 ,12919,12917,12961 ,0,0,0}, - {29979,29938,29978 ,12963,12920,12962 ,0,0,0}, {29938,29937,29978 ,12920,12919,12962 ,0,0,0}, - {29980,29939,29979 ,12964,12921,12963 ,0,0,0}, {29939,29938,29979 ,12921,12920,12963 ,0,0,0}, - {29981,29940,29980 ,12965,12922,12964 ,0,0,0}, {29940,29939,29980 ,12922,12921,12964 ,0,0,0}, - {29982,29941,29981 ,12966,12923,12965 ,0,0,0}, {29941,29940,29981 ,12923,12922,12965 ,0,0,0}, - {29983,29942,29982 ,12967,12924,12966 ,0,0,0}, {29942,29941,29982 ,12924,12923,12966 ,0,0,0}, - {29984,29896,29983 ,12968,12878,12967 ,0,0,0}, {29896,29942,29983 ,12878,12924,12967 ,0,0,0}, - {29985,29897,29984 ,12969,12879,12968 ,0,0,0}, {29897,29896,29984 ,12879,12878,12968 ,0,0,0}, - {29944,29945,29985 ,12927,12928,12969 ,0,0,0}, {29897,29985,29945 ,12879,12969,12928 ,0,0,0}, - {29944,29943,29946 ,12927,12926,12929 ,0,0,0}, {29986,29947,29943 ,12970,12930,12926 ,0,0,0}, - {29901,29945,29946 ,12883,12928,12929 ,0,0,0}, {29947,29946,29943 ,12930,12929,12926 ,0,0,0}, - {29987,29948,29986 ,12971,12931,12970 ,0,0,0}, {29948,29947,29986 ,12931,12930,12970 ,0,0,0}, - {29988,29949,29987 ,12972,12932,12971 ,0,0,0}, {29949,29948,29987 ,12932,12931,12971 ,0,0,0}, - {29989,29856,29988 ,12973,12838,12972 ,0,0,0}, {29856,29949,29988 ,12838,12932,12972 ,0,0,0}, - {29952,29854,29989 ,12935,12836,12973 ,0,0,0}, {29854,29856,29989 ,12836,12838,12973 ,0,0,0}, - {29952,29167,29950 ,12935,12974,12933 ,0,0,0}, {29854,29952,29951 ,12836,12935,12934 ,0,0,0}, - {29990,29953,29950 ,12975,12936,12933 ,0,0,0}, {29953,29951,29950 ,12936,12934,12933 ,0,0,0}, - {29991,29954,29990 ,12976,12937,12975 ,0,0,0}, {29954,29953,29990 ,12937,12936,12975 ,0,0,0}, - {29992,29955,29991 ,12977,12938,12976 ,0,0,0}, {29955,29954,29991 ,12938,12937,12976 ,0,0,0}, - {29993,29864,29992 ,12978,12846,12977 ,0,0,0}, {29864,29955,29992 ,12846,12938,12977 ,0,0,0}, - {29994,29862,29993 ,12979,12844,12978 ,0,0,0}, {29862,29864,29993 ,12844,12846,12978 ,0,0,0}, - {29956,29958,29994 ,12939,12942,12979 ,0,0,0}, {29862,29994,29958 ,12844,12979,12942 ,0,0,0}, - {29956,29957,29959 ,12939,12941,12943 ,0,0,0}, {29995,29960,29957 ,12980,12944,12941 ,0,0,0}, - {29912,29958,29959 ,12894,12942,12943 ,0,0,0}, {29960,29959,29957 ,12944,12943,12941 ,0,0,0}, - {29996,29961,29995 ,12981,12945,12980 ,0,0,0}, {29961,29960,29995 ,12945,12944,12980 ,0,0,0}, - {29997,29962,29996 ,12982,12946,12981 ,0,0,0}, {29962,29961,29996 ,12946,12945,12981 ,0,0,0}, - {29998,29915,29997 ,12983,12897,12982 ,0,0,0}, {29915,29962,29997 ,12897,12946,12982 ,0,0,0}, - {29965,29916,29998 ,12949,12898,12983 ,0,0,0}, {29916,29915,29998 ,12898,12897,12983 ,0,0,0}, - {29965,29189,29963 ,12949,12984,12947 ,0,0,0}, {29916,29965,29964 ,12898,12949,12948 ,0,0,0}, - {29999,29966,29963 ,12985,12950,12947 ,0,0,0}, {29966,29964,29963 ,12950,12948,12947 ,0,0,0}, - {30000,29967,29999 ,12986,12951,12985 ,0,0,0}, {29967,29966,29999 ,12951,12950,12985 ,0,0,0}, - {30001,29968,30000 ,12987,12952,12986 ,0,0,0}, {29968,29967,30000 ,12952,12951,12986 ,0,0,0}, - {30002,29969,30001 ,12988,12953,12987 ,0,0,0}, {29969,29968,30001 ,12953,12952,12987 ,0,0,0}, - {30003,29970,30002 ,12989,12954,12988 ,0,0,0}, {29970,29969,30002 ,12954,12953,12988 ,0,0,0}, - {30004,29971,30003 ,12990,12955,12989 ,0,0,0}, {29971,29970,30003 ,12955,12954,12989 ,0,0,0}, - {30005,29925,30004 ,12991,12907,12990 ,0,0,0}, {29925,29971,30004 ,12907,12955,12990 ,0,0,0}, - {30006,29926,30005 ,12992,12908,12991 ,0,0,0}, {29926,29925,30005 ,12908,12907,12991 ,0,0,0}, - {30007,29972,30006 ,12993,12956,12992 ,0,0,0}, {29972,29926,30006 ,12956,12908,12992 ,0,0,0}, - {30008,29702,30007 ,12994,12677,12993 ,0,0,0}, {29702,29972,30007 ,12677,12956,12993 ,0,0,0}, - {30008,29974,29700 ,12994,12958,12675 ,0,0,0}, {29700,29702,30008 ,12675,12677,12994 ,0,0,0}, - {29974,29973,29975 ,12958,12957,12959 ,0,0,0}, {29705,29975,29703 ,12680,12959,12678 ,0,0,0}, - {29835,29700,29975 ,12817,12675,12959 ,0,0,0}, {29973,29703,29975 ,12957,12678,12959 ,0,0,0}, - {29704,29703,29708 ,12679,12678,12683 ,0,0,0}, {29933,29636,29635 ,12915,12581,12580 ,0,0,0}, - {29635,29636,29932 ,12580,12581,12914 ,0,0,0}, {29261,29259,29640 ,12740,12995,12585 ,0,0,0}, - {29640,29259,29641 ,12585,12995,12586 ,0,0,0}, {29259,29127,29641 ,12995,12996,12586 ,0,0,0}, - {29641,29127,29936 ,12586,12996,12918 ,0,0,0}, {29127,29126,29936 ,12996,12997,12918 ,0,0,0}, - {29936,29126,29977 ,12918,12997,12961 ,0,0,0}, {29126,29147,29977 ,12997,12998,12961 ,0,0,0}, - {29977,29147,29978 ,12961,12998,12962 ,0,0,0}, {29147,29117,29978 ,12998,12999,12962 ,0,0,0}, - {29978,29117,29979 ,12962,12999,12963 ,0,0,0}, {29117,29152,29979 ,12999,13000,12963 ,0,0,0}, - {29979,29152,29980 ,12963,13000,12964 ,0,0,0}, {29152,29149,29980 ,13000,13001,12964 ,0,0,0}, - {29980,29149,29981 ,12964,13001,12965 ,0,0,0}, {29149,29154,29981 ,13001,13002,12965 ,0,0,0}, - {29154,29156,29982 ,13002,13003,12966 ,0,0,0}, {29154,29982,29981 ,13002,12966,12965 ,0,0,0}, - {29156,29122,29983 ,13003,13004,12967 ,0,0,0}, {29156,29983,29982 ,13003,12967,12966 ,0,0,0}, - {29122,29121,29984 ,13004,13005,12968 ,0,0,0}, {29122,29984,29983 ,13004,12968,12967 ,0,0,0}, - {29121,29158,29985 ,13005,13006,12969 ,0,0,0}, {29121,29985,29984 ,13005,12969,12968 ,0,0,0}, - {29158,29253,29944 ,13006,13007,12927 ,0,0,0}, {29158,29944,29985 ,13006,12927,12969 ,0,0,0}, - {29252,29944,29253 ,12925,12927,13007 ,0,0,0}, {29252,29161,29943 ,12925,13008,12926 ,0,0,0}, - {29943,29161,29986 ,12926,13008,12970 ,0,0,0}, {29161,29166,29986 ,13008,13009,12970 ,0,0,0}, - {29986,29166,29987 ,12970,13009,12971 ,0,0,0}, {29166,29164,29987 ,13009,13010,12971 ,0,0,0}, - {29164,29163,29988 ,13010,13011,12972 ,0,0,0}, {29164,29988,29987 ,13010,12972,12971 ,0,0,0}, - {29163,29251,29989 ,13011,13012,12973 ,0,0,0}, {29163,29989,29988 ,13011,12973,12972 ,0,0,0}, - {29251,29167,29952 ,13012,12974,12935 ,0,0,0}, {29251,29952,29989 ,13012,12935,12973 ,0,0,0}, - {29167,29250,29950 ,12974,13013,12933 ,0,0,0}, {29250,29246,29950 ,13013,13014,12933 ,0,0,0}, - {29950,29246,29990 ,12933,13014,12975 ,0,0,0}, {29246,29171,29990 ,13014,13015,12975 ,0,0,0}, - {29990,29171,29991 ,12975,13015,12976 ,0,0,0}, {29171,29173,29991 ,13015,13016,12976 ,0,0,0}, - {29173,29178,29992 ,13016,13017,12977 ,0,0,0}, {29173,29992,29991 ,13016,12977,12976 ,0,0,0}, - {29178,29176,29993 ,13017,13018,12978 ,0,0,0}, {29178,29993,29992 ,13017,12978,12977 ,0,0,0}, - {29176,29175,29994 ,13018,13019,12979 ,0,0,0}, {29176,29994,29993 ,13018,12979,12978 ,0,0,0}, - {29175,29244,29956 ,13019,13020,12939 ,0,0,0}, {29175,29956,29994 ,13019,12939,12979 ,0,0,0}, - {29243,29956,29244 ,12940,12939,13020 ,0,0,0}, {29243,29180,29957 ,12940,13021,12941 ,0,0,0}, - {29957,29180,29995 ,12941,13021,12980 ,0,0,0}, {29180,29187,29995 ,13021,13022,12980 ,0,0,0}, - {29187,29186,29996 ,13022,13023,12981 ,0,0,0}, {29187,29996,29995 ,13022,12981,12980 ,0,0,0}, - {29186,29185,29997 ,13023,13024,12982 ,0,0,0}, {29186,29997,29996 ,13023,12982,12981 ,0,0,0}, - {29185,29240,29998 ,13024,13025,12983 ,0,0,0}, {29185,29998,29997 ,13024,12983,12982 ,0,0,0}, - {29240,29189,29965 ,13025,12984,12949 ,0,0,0}, {29240,29965,29998 ,13025,12949,12983 ,0,0,0}, - {29189,29188,29963 ,12984,13026,12947 ,0,0,0}, {29188,29194,29963 ,13026,13027,12947 ,0,0,0}, - {29963,29194,29999 ,12947,13027,12985 ,0,0,0}, {29194,29193,29999 ,13027,13028,12985 ,0,0,0}, - {29999,29193,30000 ,12985,13028,12986 ,0,0,0}, {29193,29198,30000 ,13028,13029,12986 ,0,0,0}, - {30000,29198,30001 ,12986,13029,12987 ,0,0,0}, {29198,29196,30001 ,13029,13030,12987 ,0,0,0}, - {29196,29203,30002 ,13030,13031,12988 ,0,0,0}, {29196,30002,30001 ,13030,12988,12987 ,0,0,0}, - {29203,29200,30003 ,13031,13032,12989 ,0,0,0}, {29203,30003,30002 ,13031,12989,12988 ,0,0,0}, - {29200,29207,30004 ,13032,13033,12990 ,0,0,0}, {29200,30004,30003 ,13032,12990,12989 ,0,0,0}, - {29207,29204,30005 ,13033,13034,12991 ,0,0,0}, {29207,30005,30004 ,13033,12991,12990 ,0,0,0}, - {29204,29209,30006 ,13034,13035,12992 ,0,0,0}, {29204,30006,30005 ,13034,12992,12991 ,0,0,0}, - {29209,29208,30007 ,13035,13036,12993 ,0,0,0}, {29209,30007,30006 ,13035,12993,12992 ,0,0,0}, - {29208,29222,30008 ,13036,13037,12994 ,0,0,0}, {29208,30008,30007 ,13036,12994,12993 ,0,0,0}, - {29222,29221,29974 ,13037,13038,12958 ,0,0,0}, {29222,29974,30008 ,13037,12958,12994 ,0,0,0}, - {29221,29215,29973 ,13038,13039,12957 ,0,0,0}, {29221,29973,29974 ,13038,12957,12958 ,0,0,0}, - {29215,29217,29709 ,13039,12690,12684 ,0,0,0}, {29215,29709,29973 ,13039,12684,12957 ,0,0,0}, - {29710,29709,29217 ,12685,12684,12690 ,0,0,0}, {30009,30010,30011 ,13040,13041,13042 ,0,0,0}, - {30012,29086,29085 ,13043,13044,13045 ,0,0,0}, {30012,30013,29086 ,13043,13046,13044 ,0,0,0}, - {30014,29084,30015 ,13047,13048,13049 ,0,0,0}, {29085,30014,30012 ,13045,13047,13043 ,0,0,0}, - {30014,29085,29084 ,13047,13045,13048 ,0,0,0}, {29082,30016,29083 ,13050,13051,13052 ,0,0,0}, - {28997,29083,30016 ,13053,13052,13051 ,0,0,0}, {28997,30016,30015 ,13053,13051,13049 ,0,0,0}, - {29082,29081,30017 ,13050,13054,13055 ,0,0,0}, {28997,30015,29084 ,13053,13049,13048 ,0,0,0}, - {30016,29082,30017 ,13051,13050,13055 ,0,0,0}, {29087,29086,30013 ,13056,13044,13046 ,0,0,0}, - {30018,29080,30019 ,13057,13058,13059 ,0,0,0}, {30018,29081,29080 ,13057,13054,13058 ,0,0,0}, - {30020,30021,30022 ,13060,13061,13062 ,0,0,0}, {30023,30019,29079 ,13063,13059,13064 ,0,0,0}, - {29080,29079,30019 ,13058,13064,13059 ,0,0,0}, {30024,30023,29078 ,13065,13063,13066 ,0,0,0}, - {30024,29077,30025 ,13065,13067,13068 ,0,0,0}, {29078,29077,30024 ,13066,13067,13065 ,0,0,0}, - {30025,29077,29076 ,13068,13067,13069 ,0,0,0}, {29079,29078,30023 ,13064,13066,13063 ,0,0,0}, - {30017,29081,30018 ,13055,13054,13057 ,0,0,0}, {29075,29074,30026 ,13070,13071,13072 ,0,0,0}, - {29075,30027,29076 ,13070,13073,13069 ,0,0,0}, {29073,30028,29074 ,13074,13075,13071 ,0,0,0}, - {29075,30026,30027 ,13070,13072,13073 ,0,0,0}, {29073,29072,30029 ,13074,13076,13077 ,0,0,0}, - {30029,30028,29073 ,13077,13075,13074 ,0,0,0}, {29710,28768,28765 ,13078,11682,13079 ,0,0,0}, - {29074,30028,30026 ,13071,13075,13072 ,0,0,0}, {30029,29072,30030 ,13077,13076,13080 ,0,0,0}, - {30031,29710,28765 ,13081,13078,13079 ,0,0,0}, {30032,30033,30029 ,13082,13083,13077 ,0,0,0}, - {30034,30035,30036 ,13084,13085,13086 ,0,0,0}, {30037,30038,30039 ,13087,13088,13089 ,0,0,0}, - {30040,30041,29930 ,13090,13091,13092 ,0,0,0}, {30040,29704,30042 ,13090,13093,13094 ,0,0,0}, - {30030,29072,29071 ,13080,13076,13095 ,0,0,0}, {30031,28765,30036 ,13081,13079,13086 ,0,0,0}, - {30033,30043,30039 ,13083,13096,13089 ,0,0,0}, {29931,30041,30044 ,13097,13091,13098 ,0,0,0}, - {30045,29758,30046 ,13099,13100,13101 ,0,0,0}, {28634,30047,29071 ,13102,13103,13095 ,0,0,0}, - {30048,29837,30044 ,13104,13105,13098 ,0,0,0}, {29838,29837,30048 ,13106,13105,13104 ,0,0,0}, - {29931,30044,29792 ,13097,13098,13107 ,0,0,0}, {28639,29719,28637 ,11553,13108,13109 ,0,0,0}, - {28634,30045,30047 ,13102,13099,13103 ,0,0,0}, {29758,30045,29719 ,13100,13099,13108 ,0,0,0}, - {30045,28637,29719 ,13099,13109,13108 ,0,0,0}, {30043,30049,30039 ,13096,13110,13089 ,0,0,0}, - {30027,30025,29076 ,13073,13068,13069 ,0,0,0}, {30050,29087,30013 ,13111,13056,13046 ,0,0,0}, - {29088,30050,30051 ,13112,13111,13113 ,0,0,0}, {30050,29088,29087 ,13111,13112,13056 ,0,0,0}, - {30052,29047,30051 ,13114,13115,13113 ,0,0,0}, {29088,30051,29047 ,13112,13113,13115 ,0,0,0}, - {29089,30052,29090 ,13116,13114,13117 ,0,0,0}, {29089,29047,30052 ,13116,13115,13114 ,0,0,0}, - {29091,29090,30053 ,13118,13117,13119 ,0,0,0}, {30052,30053,29090 ,13114,13119,13117 ,0,0,0}, - {30054,29092,29091 ,13120,13121,13118 ,0,0,0}, {29091,30053,30054 ,13118,13119,13120 ,0,0,0}, - {30054,30055,29092 ,13120,13122,13121 ,0,0,0}, {29092,30055,29093 ,13121,13122,13123 ,0,0,0}, - {29093,30055,30056 ,13123,13122,13124 ,0,0,0}, {30057,30058,30059 ,13125,13126,13127 ,0,0,0}, - {30060,29094,30056 ,13128,13129,13124 ,0,0,0}, {29093,30056,29094 ,13123,13124,13129 ,0,0,0}, - {30060,30061,29095 ,13128,13130,13131 ,0,0,0}, {29095,29094,30060 ,13131,13129,13128 ,0,0,0}, - {29012,29096,30061 ,13132,13133,13130 ,0,0,0}, {30061,29096,29095 ,13130,13133,13131 ,0,0,0}, - {30062,29097,29012 ,13134,13135,13132 ,0,0,0}, {29012,30061,30062 ,13132,13130,13134 ,0,0,0}, - {29097,30063,29098 ,13135,13136,13137 ,0,0,0}, {30063,29097,30062 ,13136,13135,13134 ,0,0,0}, - {29099,29098,30064 ,13138,13137,13139 ,0,0,0}, {30063,30064,29098 ,13136,13139,13137 ,0,0,0}, - {30065,29099,30064 ,13140,13138,13139 ,0,0,0}, {30065,29100,29099 ,13140,13141,13138 ,0,0,0}, - {30065,30066,29100 ,13140,13142,13141 ,0,0,0}, {30067,30068,30069 ,13143,13144,13145 ,0,0,0}, - {29101,30066,30070 ,13146,13142,13147 ,0,0,0}, {30066,29101,29100 ,13142,13146,13141 ,0,0,0}, - {30071,29058,30070 ,13148,13149,13147 ,0,0,0}, {29101,30070,29058 ,13146,13147,13149 ,0,0,0}, - {29102,30071,29103 ,13150,13148,13151 ,0,0,0}, {29102,29058,30071 ,13150,13149,13148 ,0,0,0}, - {29104,29103,30072 ,13152,13151,13153 ,0,0,0}, {30071,30072,29103 ,13148,13153,13151 ,0,0,0}, - {30073,29105,29104 ,13154,13155,13152 ,0,0,0}, {29104,30072,30073 ,13152,13153,13154 ,0,0,0}, - {29105,30074,29106 ,13155,13156,13157 ,0,0,0}, {30074,29105,30073 ,13156,13155,13154 ,0,0,0}, - {29107,29106,30075 ,13158,13157,13159 ,0,0,0}, {30074,30075,29106 ,13156,13159,13157 ,0,0,0}, - {30076,29107,30075 ,13160,13158,13159 ,0,0,0}, {30076,29108,29107 ,13160,13161,13158 ,0,0,0}, - {30076,30077,29108 ,13160,13162,13161 ,0,0,0}, {30078,30079,30080 ,13163,13164,13165 ,0,0,0}, - {29109,30077,30079 ,13166,13162,13164 ,0,0,0}, {30077,29109,29108 ,13162,13166,13161 ,0,0,0}, - {30081,29110,30079 ,13167,13168,13164 ,0,0,0}, {29109,30079,29110 ,13166,13164,13168 ,0,0,0}, - {30082,30083,30084 ,13169,13170,13171 ,0,0,0}, {29111,29110,30081 ,13172,13168,13167 ,0,0,0}, - {30085,30086,30087 ,13173,13174,13175 ,0,0,0}, {30088,30089,30090 ,13176,13177,13178 ,0,0,0}, - {30091,30085,30092 ,13179,13173,13180 ,0,0,0}, {30093,30094,30095 ,13181,13182,13183 ,0,0,0}, - {30096,30097,30098 ,13184,13185,13186 ,0,0,0}, {30093,30099,30100 ,13181,13187,13188 ,0,0,0}, - {30101,30102,30103 ,13189,13190,13191 ,0,0,0}, {30100,30099,30104 ,13188,13187,13192 ,0,0,0}, - {29112,29111,30105 ,13193,13172,13194 ,0,0,0}, {28702,30104,30099 ,11616,13192,13187 ,0,0,0}, - {30106,30107,30108 ,13195,13196,13197 ,0,0,0}, {29111,30081,30105 ,13172,13167,13194 ,0,0,0}, - {29112,30090,29113 ,13193,13178,13198 ,0,0,0}, {30078,30081,30079 ,13163,13167,13164 ,0,0,0}, - {29114,29113,30107 ,13199,13198,13196 ,0,0,0}, {30090,30107,29113 ,13178,13196,13198 ,0,0,0}, - {29115,30106,29116 ,13200,13195,13201 ,0,0,0}, {29114,30107,30106 ,13199,13196,13195 ,0,0,0}, - {29116,30109,28736 ,13201,13202,11650 ,0,0,0}, {30106,30109,29116 ,13195,13202,13201 ,0,0,0}, - {28637,30045,28634 ,13109,13099,13102 ,0,0,0}, {29796,30046,29758 ,13203,13101,13100 ,0,0,0}, - {29796,30048,30046 ,13203,13104,13101 ,0,0,0}, {30047,30030,29071 ,13103,13080,13095 ,0,0,0}, - {30047,30046,30110 ,13103,13101,13204 ,0,0,0}, {30111,30028,30033 ,13205,13075,13083 ,0,0,0}, - {30030,30110,30032 ,13080,13204,13082 ,0,0,0}, {30112,30026,30111 ,13206,13072,13205 ,0,0,0}, - {30032,30029,30030 ,13082,13077,13080 ,0,0,0}, {30113,30027,30112 ,13207,13073,13206 ,0,0,0}, - {30033,30028,30029 ,13083,13075,13077 ,0,0,0}, {30114,30025,30113 ,13208,13068,13207 ,0,0,0}, - {30111,30026,30028 ,13205,13072,13075 ,0,0,0}, {30115,30024,30114 ,13209,13065,13208 ,0,0,0}, - {30112,30027,30026 ,13206,13073,13072 ,0,0,0}, {30116,30023,30115 ,13210,13063,13209 ,0,0,0}, - {30113,30025,30027 ,13207,13068,13073 ,0,0,0}, {30117,30019,30116 ,13211,13059,13210 ,0,0,0}, - {30114,30024,30025 ,13208,13065,13068 ,0,0,0}, {30117,30118,30018 ,13211,13212,13057 ,0,0,0}, - {30023,30024,30115 ,13063,13065,13209 ,0,0,0}, {30119,30017,30118 ,13213,13055,13212 ,0,0,0}, - {30019,30023,30116 ,13059,13063,13210 ,0,0,0}, {30020,30016,30119 ,13060,13051,13213 ,0,0,0}, - {30018,30019,30117 ,13057,13059,13211 ,0,0,0}, {30120,30015,30020 ,13214,13049,13060 ,0,0,0}, - {30017,30018,30118 ,13055,13057,13212 ,0,0,0}, {30121,30014,30120 ,13215,13047,13214 ,0,0,0}, - {30016,30017,30119 ,13051,13055,13213 ,0,0,0}, {30122,30012,30121 ,13216,13043,13215 ,0,0,0}, - {30020,30015,30016 ,13060,13049,13051 ,0,0,0}, {30123,30013,30122 ,13217,13046,13216 ,0,0,0}, - {30120,30014,30015 ,13214,13047,13049 ,0,0,0}, {30123,30124,30050 ,13217,13218,13111 ,0,0,0}, - {30012,30014,30121 ,13043,13047,13215 ,0,0,0}, {30125,30051,30124 ,13219,13113,13218 ,0,0,0}, - {30013,30012,30122 ,13046,13043,13216 ,0,0,0}, {30126,30052,30125 ,13220,13114,13219 ,0,0,0}, - {30050,30013,30123 ,13111,13046,13217 ,0,0,0}, {30127,30053,30126 ,13221,13119,13220 ,0,0,0}, - {30051,30050,30124 ,13113,13111,13218 ,0,0,0}, {30128,30054,30127 ,13222,13120,13221 ,0,0,0}, - {30052,30051,30125 ,13114,13113,13219 ,0,0,0}, {30129,30055,30128 ,13223,13122,13222 ,0,0,0}, - {30126,30053,30052 ,13220,13119,13114 ,0,0,0}, {30129,30130,30056 ,13223,13224,13124 ,0,0,0}, - {30054,30053,30127 ,13120,13119,13221 ,0,0,0}, {30131,30060,30130 ,13225,13128,13224 ,0,0,0}, - {30055,30054,30128 ,13122,13120,13222 ,0,0,0}, {30057,30061,30131 ,13125,13130,13225 ,0,0,0}, - {30056,30055,30129 ,13124,13122,13223 ,0,0,0}, {30132,30062,30057 ,13226,13134,13125 ,0,0,0}, - {30060,30056,30130 ,13128,13124,13224 ,0,0,0}, {30133,30063,30132 ,13227,13136,13226 ,0,0,0}, - {30061,30060,30131 ,13130,13128,13225 ,0,0,0}, {30134,30064,30133 ,13228,13139,13227 ,0,0,0}, - {30057,30062,30061 ,13125,13134,13130 ,0,0,0}, {30135,30065,30134 ,13229,13140,13228 ,0,0,0}, - {30132,30063,30062 ,13226,13136,13134 ,0,0,0}, {30135,30136,30066 ,13229,13230,13142 ,0,0,0}, - {30064,30063,30133 ,13139,13136,13227 ,0,0,0}, {30137,30070,30136 ,13231,13147,13230 ,0,0,0}, - {30065,30064,30134 ,13140,13139,13228 ,0,0,0}, {30138,30071,30137 ,13232,13148,13231 ,0,0,0}, - {30066,30065,30135 ,13142,13140,13229 ,0,0,0}, {30139,30072,30138 ,13233,13153,13232 ,0,0,0}, - {30070,30066,30136 ,13147,13142,13230 ,0,0,0}, {30140,30073,30139 ,13234,13154,13233 ,0,0,0}, - {30137,30071,30070 ,13231,13148,13147 ,0,0,0}, {30141,30074,30140 ,13235,13156,13234 ,0,0,0}, - {30138,30072,30071 ,13232,13153,13148 ,0,0,0}, {30142,30075,30141 ,13236,13159,13235 ,0,0,0}, - {30139,30073,30072 ,13233,13154,13153 ,0,0,0}, {30143,30076,30142 ,13237,13160,13236 ,0,0,0}, - {30140,30074,30073 ,13234,13156,13154 ,0,0,0}, {30143,30080,30077 ,13237,13165,13162 ,0,0,0}, - {30075,30074,30141 ,13159,13156,13235 ,0,0,0}, {30081,30078,30144 ,13167,13163,13238 ,0,0,0}, - {30076,30075,30142 ,13160,13159,13236 ,0,0,0}, {30098,30089,30102 ,13186,13177,13190 ,0,0,0}, - {30077,30076,30143 ,13162,13160,13237 ,0,0,0}, {30088,30105,30144 ,13176,13194,13238 ,0,0,0}, - {30079,30077,30080 ,13164,13162,13165 ,0,0,0}, {30088,30144,30145 ,13176,13238,13239 ,0,0,0}, - {30097,30108,30098 ,13185,13197,13186 ,0,0,0}, {30105,30090,29112 ,13194,13178,13193 ,0,0,0}, - {30105,30081,30144 ,13194,13167,13238 ,0,0,0}, {30146,30109,30147 ,13240,13202,13241 ,0,0,0}, - {30105,30088,30090 ,13194,13176,13178 ,0,0,0}, {30108,30107,30089 ,13197,13196,13177 ,0,0,0}, - {30148,30149,30109 ,13242,13243,13202 ,0,0,0}, {29114,30106,29115 ,13199,13195,13200 ,0,0,0}, - {30106,30147,30109 ,13195,13241,13202 ,0,0,0}, {28736,30109,30149 ,11650,13202,13243 ,0,0,0}, - {30045,30046,30047 ,13099,13101,13103 ,0,0,0}, {29838,30048,29796 ,13106,13104,13203 ,0,0,0}, - {29930,29976,30040 ,13092,13244,13090 ,0,0,0}, {30047,30110,30030 ,13103,13204,13080 ,0,0,0}, - {30110,30048,30150 ,13204,13104,13245 ,0,0,0}, {30039,30038,30111 ,13089,13088,13205 ,0,0,0}, - {30043,30032,30150 ,13096,13082,13245 ,0,0,0}, {30038,30151,30112 ,13088,13246,13206 ,0,0,0}, - {30043,30033,30032 ,13096,13083,13082 ,0,0,0}, {30151,30152,30113 ,13246,13247,13207 ,0,0,0}, - {30039,30111,30033 ,13089,13205,13083 ,0,0,0}, {30152,30153,30114 ,13247,13248,13208 ,0,0,0}, - {30038,30112,30111 ,13088,13206,13205 ,0,0,0}, {30153,30154,30115 ,13248,13249,13209 ,0,0,0}, - {30151,30113,30112 ,13246,13207,13206 ,0,0,0}, {30154,30155,30116 ,13249,13250,13210 ,0,0,0}, - {30152,30114,30113 ,13247,13208,13207 ,0,0,0}, {30155,30156,30117 ,13250,13251,13211 ,0,0,0}, - {30153,30115,30114 ,13248,13209,13208 ,0,0,0}, {30156,30157,30118 ,13251,13252,13212 ,0,0,0}, - {30154,30116,30115 ,13249,13210,13209 ,0,0,0}, {30157,30021,30119 ,13252,13061,13213 ,0,0,0}, - {30117,30116,30155 ,13211,13210,13250 ,0,0,0}, {30158,30159,30160 ,13253,13254,13255 ,0,0,0}, - {30118,30117,30156 ,13212,13211,13251 ,0,0,0}, {30022,30159,30120 ,13062,13254,13214 ,0,0,0}, - {30119,30118,30157 ,13213,13212,13252 ,0,0,0}, {30159,30158,30121 ,13254,13253,13215 ,0,0,0}, - {30020,30119,30021 ,13060,13213,13061 ,0,0,0}, {30158,30161,30122 ,13253,13256,13216 ,0,0,0}, - {30022,30120,30020 ,13062,13214,13060 ,0,0,0}, {30161,30162,30123 ,13256,13257,13217 ,0,0,0}, - {30159,30121,30120 ,13254,13215,13214 ,0,0,0}, {30162,30163,30124 ,13257,13258,13218 ,0,0,0}, - {30158,30122,30121 ,13253,13216,13215 ,0,0,0}, {30163,30164,30125 ,13258,13259,13219 ,0,0,0}, - {30123,30122,30161 ,13217,13216,13256 ,0,0,0}, {30010,30126,30164 ,13041,13220,13259 ,0,0,0}, - {30124,30123,30162 ,13218,13217,13257 ,0,0,0}, {30010,30009,30127 ,13041,13040,13221 ,0,0,0}, - {30125,30124,30163 ,13219,13218,13258 ,0,0,0}, {30009,30165,30128 ,13040,13260,13222 ,0,0,0}, - {30164,30126,30125 ,13259,13220,13219 ,0,0,0}, {30165,30166,30129 ,13260,13261,13223 ,0,0,0}, - {30010,30127,30126 ,13041,13221,13220 ,0,0,0}, {30166,30167,30130 ,13261,13262,13224 ,0,0,0}, - {30009,30128,30127 ,13040,13222,13221 ,0,0,0}, {30167,30058,30131 ,13262,13126,13225 ,0,0,0}, - {30129,30128,30165 ,13223,13222,13260 ,0,0,0}, {30168,30169,30170 ,13263,13264,13265 ,0,0,0}, - {30130,30129,30166 ,13224,13223,13261 ,0,0,0}, {30059,30171,30132 ,13127,13266,13226 ,0,0,0}, - {30131,30130,30167 ,13225,13224,13262 ,0,0,0}, {30171,30172,30133 ,13266,13267,13227 ,0,0,0}, - {30057,30131,30058 ,13125,13225,13126 ,0,0,0}, {30172,30173,30134 ,13267,13268,13228 ,0,0,0}, - {30059,30132,30057 ,13127,13226,13125 ,0,0,0}, {30173,30174,30135 ,13268,13269,13229 ,0,0,0}, - {30171,30133,30132 ,13266,13227,13226 ,0,0,0}, {30174,30175,30136 ,13269,13270,13230 ,0,0,0}, - {30172,30134,30133 ,13267,13228,13227 ,0,0,0}, {30175,30176,30137 ,13270,13271,13231 ,0,0,0}, - {30135,30134,30173 ,13229,13228,13268 ,0,0,0}, {30176,30067,30138 ,13271,13143,13232 ,0,0,0}, - {30136,30135,30174 ,13230,13229,13269 ,0,0,0}, {30067,30069,30139 ,13143,13145,13233 ,0,0,0}, - {30137,30136,30175 ,13231,13230,13270 ,0,0,0}, {30069,30177,30140 ,13145,13272,13234 ,0,0,0}, - {30176,30138,30137 ,13271,13232,13231 ,0,0,0}, {30177,30178,30141 ,13272,13273,13235 ,0,0,0}, - {30067,30139,30138 ,13143,13233,13232 ,0,0,0}, {30178,30179,30142 ,13273,13274,13236 ,0,0,0}, - {30069,30140,30139 ,13145,13234,13233 ,0,0,0}, {30179,30180,30143 ,13274,13275,13237 ,0,0,0}, - {30177,30141,30140 ,13272,13235,13234 ,0,0,0}, {30180,30181,30080 ,13275,13276,13165 ,0,0,0}, - {30178,30142,30141 ,13273,13236,13235 ,0,0,0}, {30181,30182,30078 ,13276,13277,13163 ,0,0,0}, - {30179,30143,30142 ,13274,13237,13236 ,0,0,0}, {30182,30145,30144 ,13277,13239,13238 ,0,0,0}, - {30180,30080,30143 ,13275,13165,13237 ,0,0,0}, {30145,30102,30088 ,13239,13190,13176 ,0,0,0}, - {30078,30080,30181 ,13163,13165,13276 ,0,0,0}, {30183,30097,30184 ,13278,13185,13279 ,0,0,0}, - {30078,30182,30144 ,13163,13277,13238 ,0,0,0}, {30108,30097,30147 ,13197,13185,13241 ,0,0,0}, - {30096,30184,30097 ,13184,13279,13185 ,0,0,0}, {30090,30089,30107 ,13178,13177,13196 ,0,0,0}, - {30102,30089,30088 ,13190,13177,13176 ,0,0,0}, {30185,30146,30082 ,13280,13240,13169 ,0,0,0}, - {30146,30148,30109 ,13240,13242,13202 ,0,0,0}, {30106,30108,30147 ,13195,13197,13241 ,0,0,0}, - {30146,30147,30183 ,13240,13241,13278 ,0,0,0}, {30185,30148,30146 ,13280,13242,13240 ,0,0,0}, - {30046,30048,30110 ,13101,13104,13204 ,0,0,0}, {29792,30044,29837 ,13107,13098,13105 ,0,0,0}, - {28763,30036,28765 ,13281,13086,13079 ,0,0,0}, {30110,30150,30032 ,13204,13245,13082 ,0,0,0}, - {30150,30044,30186 ,13245,13098,13282 ,0,0,0}, {30038,30187,30151 ,13088,13283,13246 ,0,0,0}, - {30049,30043,30186 ,13110,13096,13282 ,0,0,0}, {30151,30188,30152 ,13246,13284,13247 ,0,0,0}, - {30049,30037,30039 ,13110,13087,13089 ,0,0,0}, {30189,30190,30191 ,13285,13286,13287 ,0,0,0}, - {30037,30187,30038 ,13087,13283,13088 ,0,0,0}, {30153,30152,30192 ,13248,13247,13288 ,0,0,0}, - {30187,30188,30151 ,13283,13284,13246 ,0,0,0}, {30154,30153,30191 ,13249,13248,13287 ,0,0,0}, - {30188,30192,30152 ,13284,13288,13247 ,0,0,0}, {30155,30154,30190 ,13250,13249,13286 ,0,0,0}, - {30192,30191,30153 ,13288,13287,13248 ,0,0,0}, {30156,30155,30193 ,13251,13250,13289 ,0,0,0}, - {30191,30190,30154 ,13287,13286,13249 ,0,0,0}, {30157,30156,30194 ,13252,13251,13290 ,0,0,0}, - {30190,30193,30155 ,13286,13289,13250 ,0,0,0}, {30021,30157,30195 ,13061,13252,13291 ,0,0,0}, - {30193,30194,30156 ,13289,13290,13251 ,0,0,0}, {30022,30021,30196 ,13062,13061,13292 ,0,0,0}, - {30194,30195,30157 ,13290,13291,13252 ,0,0,0}, {30159,30022,30197 ,13254,13062,13293 ,0,0,0}, - {30196,30021,30195 ,13292,13061,13291 ,0,0,0}, {30198,30199,30200 ,13294,13295,13296 ,0,0,0}, - {30197,30022,30196 ,13293,13062,13292 ,0,0,0}, {30161,30158,30201 ,13256,13253,13297 ,0,0,0}, - {30197,30160,30159 ,13293,13255,13254 ,0,0,0}, {30162,30161,30200 ,13257,13256,13296 ,0,0,0}, - {30160,30201,30158 ,13255,13297,13253 ,0,0,0}, {30163,30162,30199 ,13258,13257,13295 ,0,0,0}, - {30201,30200,30161 ,13297,13296,13256 ,0,0,0}, {30164,30163,30202 ,13259,13258,13298 ,0,0,0}, - {30200,30199,30162 ,13296,13295,13257 ,0,0,0}, {30010,30164,30203 ,13041,13259,13299 ,0,0,0}, - {30202,30163,30199 ,13298,13258,13295 ,0,0,0}, {30204,30205,30206 ,13300,13301,13302 ,0,0,0}, - {30203,30164,30202 ,13299,13259,13298 ,0,0,0}, {30165,30009,30207 ,13260,13040,13303 ,0,0,0}, - {30203,30011,30010 ,13299,13042,13041 ,0,0,0}, {30166,30165,30206 ,13261,13260,13302 ,0,0,0}, - {30011,30207,30009 ,13042,13303,13040 ,0,0,0}, {30167,30166,30205 ,13262,13261,13301 ,0,0,0}, - {30207,30206,30165 ,13303,13302,13260 ,0,0,0}, {30058,30167,30208 ,13126,13262,13304 ,0,0,0}, - {30206,30205,30166 ,13302,13301,13261 ,0,0,0}, {30059,30058,30209 ,13127,13126,13305 ,0,0,0}, - {30205,30208,30167 ,13301,13304,13262 ,0,0,0}, {30171,30059,30210 ,13266,13127,13306 ,0,0,0}, - {30209,30058,30208 ,13305,13126,13304 ,0,0,0}, {30172,30171,30211 ,13267,13266,13307 ,0,0,0}, - {30210,30059,30209 ,13306,13127,13305 ,0,0,0}, {30173,30172,30168 ,13268,13267,13263 ,0,0,0}, - {30210,30211,30171 ,13306,13307,13266 ,0,0,0}, {30174,30173,30170 ,13269,13268,13265 ,0,0,0}, - {30211,30168,30172 ,13307,13263,13267 ,0,0,0}, {30175,30174,30212 ,13270,13269,13308 ,0,0,0}, - {30168,30170,30173 ,13263,13265,13268 ,0,0,0}, {30176,30175,30213 ,13271,13270,13309 ,0,0,0}, - {30170,30212,30174 ,13265,13308,13269 ,0,0,0}, {30067,30176,30214 ,13143,13271,13310 ,0,0,0}, - {30213,30175,30212 ,13309,13270,13308 ,0,0,0}, {30215,30216,30217 ,13311,13312,13313 ,0,0,0}, - {30214,30176,30213 ,13310,13271,13309 ,0,0,0}, {30177,30069,30218 ,13272,13145,13314 ,0,0,0}, - {30214,30068,30067 ,13310,13144,13143 ,0,0,0}, {30178,30177,30217 ,13273,13272,13313 ,0,0,0}, - {30068,30218,30069 ,13144,13314,13145 ,0,0,0}, {30179,30178,30216 ,13274,13273,13312 ,0,0,0}, - {30218,30217,30177 ,13314,13313,13272 ,0,0,0}, {30180,30179,30219 ,13275,13274,13315 ,0,0,0}, - {30217,30216,30178 ,13313,13312,13273 ,0,0,0}, {30181,30180,30220 ,13276,13275,13316 ,0,0,0}, - {30216,30219,30179 ,13312,13315,13274 ,0,0,0}, {30182,30181,30221 ,13277,13276,13317 ,0,0,0}, - {30219,30220,30180 ,13315,13316,13275 ,0,0,0}, {30145,30182,30222 ,13239,13277,13318 ,0,0,0}, - {30220,30221,30181 ,13316,13317,13276 ,0,0,0}, {30102,30145,30103 ,13190,13239,13191 ,0,0,0}, - {30221,30222,30182 ,13317,13318,13277 ,0,0,0}, {30098,30102,30101 ,13186,13190,13189 ,0,0,0}, - {30222,30103,30145 ,13318,13191,13239 ,0,0,0}, {30083,30184,30086 ,13170,13279,13174 ,0,0,0}, - {30184,30223,30086 ,13279,13319,13174 ,0,0,0}, {30089,30098,30108 ,13177,13186,13197 ,0,0,0}, - {30101,30096,30098 ,13189,13184,13186 ,0,0,0}, {30224,30082,30084 ,13320,13169,13171 ,0,0,0}, - {30146,30183,30082 ,13240,13278,13169 ,0,0,0}, {30147,30097,30183 ,13241,13185,13278 ,0,0,0}, - {30183,30083,30082 ,13278,13170,13169 ,0,0,0}, {30185,30082,30224 ,13280,13169,13320 ,0,0,0}, - {30044,30150,30048 ,13098,13245,13104 ,0,0,0}, {29930,30041,29931 ,13092,13091,13097 ,0,0,0}, - {30049,30225,30037 ,13110,13321,13087 ,0,0,0}, {30150,30186,30043 ,13245,13282,13096 ,0,0,0}, - {30041,30226,30186 ,13091,13322,13282 ,0,0,0}, {30187,30037,30227 ,13283,13087,13323 ,0,0,0}, - {30226,30225,30049 ,13322,13321,13110 ,0,0,0}, {30188,30187,30228 ,13284,13283,13324 ,0,0,0}, - {30037,30225,30227 ,13087,13321,13323 ,0,0,0}, {30192,30188,30229 ,13288,13284,13325 ,0,0,0}, - {30187,30227,30228 ,13283,13323,13324 ,0,0,0}, {30191,30192,30230 ,13287,13288,13326 ,0,0,0}, - {30228,30229,30188 ,13324,13325,13284 ,0,0,0}, {30231,30193,30190 ,13327,13289,13286 ,0,0,0}, - {30229,30230,30192 ,13325,13326,13288 ,0,0,0}, {30232,30233,30234 ,13328,13329,13330 ,0,0,0}, - {30230,30189,30191 ,13326,13285,13287 ,0,0,0}, {30193,30235,30194 ,13289,13331,13290 ,0,0,0}, - {30189,30231,30190 ,13285,13327,13286 ,0,0,0}, {30194,30233,30195 ,13290,13329,13291 ,0,0,0}, - {30231,30235,30193 ,13327,13331,13289 ,0,0,0}, {30195,30232,30196 ,13291,13328,13292 ,0,0,0}, - {30235,30233,30194 ,13331,13329,13290 ,0,0,0}, {30196,30236,30197 ,13292,13332,13293 ,0,0,0}, - {30233,30232,30195 ,13329,13328,13291 ,0,0,0}, {30197,30237,30160 ,13293,13333,13255 ,0,0,0}, - {30232,30236,30196 ,13328,13332,13292 ,0,0,0}, {30201,30160,30238 ,13297,13255,13334 ,0,0,0}, - {30236,30237,30197 ,13332,13333,13293 ,0,0,0}, {30200,30201,30239 ,13296,13297,13335 ,0,0,0}, - {30237,30238,30160 ,13333,13334,13255 ,0,0,0}, {30240,30241,30242 ,13336,13337,13338 ,0,0,0}, - {30238,30239,30201 ,13334,13335,13297 ,0,0,0}, {30199,30243,30202 ,13295,13339,13298 ,0,0,0}, - {30239,30198,30200 ,13335,13294,13296 ,0,0,0}, {30202,30244,30203 ,13298,13340,13299 ,0,0,0}, - {30198,30243,30199 ,13294,13339,13295 ,0,0,0}, {30203,30245,30011 ,13299,13341,13042 ,0,0,0}, - {30243,30244,30202 ,13339,13340,13298 ,0,0,0}, {30207,30011,30246 ,13303,13042,13342 ,0,0,0}, - {30244,30245,30203 ,13340,13341,13299 ,0,0,0}, {30206,30207,30247 ,13302,13303,13343 ,0,0,0}, - {30245,30246,30011 ,13341,13342,13042 ,0,0,0}, {30248,30249,30250 ,13344,13345,13346 ,0,0,0}, - {30246,30247,30207 ,13342,13343,13303 ,0,0,0}, {30205,30251,30208 ,13301,13347,13304 ,0,0,0}, - {30247,30204,30206 ,13343,13300,13302 ,0,0,0}, {30208,30252,30209 ,13304,13348,13305 ,0,0,0}, - {30204,30251,30205 ,13300,13347,13301 ,0,0,0}, {30209,30253,30210 ,13305,13349,13306 ,0,0,0}, - {30251,30252,30208 ,13347,13348,13304 ,0,0,0}, {30210,30254,30211 ,13306,13350,13307 ,0,0,0}, - {30252,30253,30209 ,13348,13349,13305 ,0,0,0}, {30168,30211,30255 ,13263,13307,13351 ,0,0,0}, - {30253,30254,30210 ,13349,13350,13306 ,0,0,0}, {30256,30257,30258 ,13352,13353,13354 ,0,0,0}, - {30254,30255,30211 ,13350,13351,13307 ,0,0,0}, {30170,30259,30212 ,13265,13355,13308 ,0,0,0}, - {30255,30169,30168 ,13351,13264,13263 ,0,0,0}, {30212,30257,30213 ,13308,13353,13309 ,0,0,0}, - {30169,30259,30170 ,13264,13355,13265 ,0,0,0}, {30213,30256,30214 ,13309,13352,13310 ,0,0,0}, - {30259,30257,30212 ,13355,13353,13308 ,0,0,0}, {30214,30260,30068 ,13310,13356,13144 ,0,0,0}, - {30257,30256,30213 ,13353,13352,13309 ,0,0,0}, {30218,30068,30261 ,13314,13144,13357 ,0,0,0}, - {30256,30260,30214 ,13352,13356,13310 ,0,0,0}, {30217,30218,30262 ,13313,13314,13358 ,0,0,0}, - {30260,30261,30068 ,13356,13357,13144 ,0,0,0}, {30263,30219,30216 ,13359,13315,13312 ,0,0,0}, - {30261,30262,30218 ,13357,13358,13314 ,0,0,0}, {30264,30265,30266 ,13360,13361,13362 ,0,0,0}, - {30262,30215,30217 ,13358,13311,13313 ,0,0,0}, {30219,30267,30220 ,13315,13363,13316 ,0,0,0}, - {30215,30263,30216 ,13311,13359,13312 ,0,0,0}, {30220,30265,30221 ,13316,13361,13317 ,0,0,0}, - {30263,30267,30219 ,13359,13363,13315 ,0,0,0}, {30221,30264,30222 ,13317,13360,13318 ,0,0,0}, - {30267,30265,30220 ,13363,13361,13316 ,0,0,0}, {30222,30268,30103 ,13318,13364,13191 ,0,0,0}, - {30265,30264,30221 ,13361,13360,13317 ,0,0,0}, {30103,30269,30101 ,13191,13365,13189 ,0,0,0}, - {30264,30268,30222 ,13360,13364,13318 ,0,0,0}, {30101,30270,30096 ,13189,13366,13184 ,0,0,0}, - {30268,30269,30103 ,13364,13365,13191 ,0,0,0}, {30096,30223,30184 ,13184,13319,13279 ,0,0,0}, - {30270,30101,30269 ,13366,13189,13365 ,0,0,0}, {30271,30272,30084 ,13367,13368,13171 ,0,0,0}, - {30096,30270,30223 ,13184,13366,13319 ,0,0,0}, {30273,30084,30272 ,13369,13171,13368 ,0,0,0}, - {30274,30224,30084 ,13370,13320,13171 ,0,0,0}, {30183,30184,30083 ,13278,13279,13170 ,0,0,0}, - {30083,30271,30084 ,13170,13367,13171 ,0,0,0}, {30273,30274,30084 ,13369,13370,13171 ,0,0,0}, - {30041,30186,30044 ,13091,13282,13098 ,0,0,0}, {29704,30040,29976 ,13093,13090,13244 ,0,0,0}, - {30225,30275,30227 ,13321,13371,13323 ,0,0,0}, {30186,30226,30049 ,13282,13322,13110 ,0,0,0}, - {30040,30276,30226 ,13090,13372,13322 ,0,0,0}, {30228,30227,30277 ,13324,13323,13373 ,0,0,0}, - {30225,30276,30275 ,13321,13372,13371 ,0,0,0}, {30229,30228,30278 ,13325,13324,13374 ,0,0,0}, - {30227,30275,30277 ,13323,13371,13373 ,0,0,0}, {30230,30229,30279 ,13326,13325,13375 ,0,0,0}, - {30228,30277,30278 ,13324,13373,13374 ,0,0,0}, {30189,30230,30280 ,13285,13326,13376 ,0,0,0}, - {30229,30278,30279 ,13325,13374,13375 ,0,0,0}, {30231,30189,30281 ,13327,13285,13377 ,0,0,0}, - {30230,30279,30280 ,13326,13375,13376 ,0,0,0}, {30235,30231,30282 ,13331,13327,13378 ,0,0,0}, - {30189,30280,30281 ,13285,13376,13377 ,0,0,0}, {30233,30235,30283 ,13329,13331,13379 ,0,0,0}, - {30281,30282,30231 ,13377,13378,13327 ,0,0,0}, {30284,30285,30286 ,13380,13381,13382 ,0,0,0}, - {30282,30283,30235 ,13378,13379,13331 ,0,0,0}, {30232,30287,30236 ,13328,13383,13332 ,0,0,0}, - {30283,30234,30233 ,13379,13330,13329 ,0,0,0}, {30236,30286,30237 ,13332,13382,13333 ,0,0,0}, - {30234,30287,30232 ,13330,13383,13328 ,0,0,0}, {30237,30288,30238 ,13333,13384,13334 ,0,0,0}, - {30287,30286,30236 ,13383,13382,13332 ,0,0,0}, {30239,30238,30289 ,13335,13334,13385 ,0,0,0}, - {30286,30288,30237 ,13382,13384,13333 ,0,0,0}, {30198,30239,30290 ,13294,13335,13386 ,0,0,0}, - {30238,30288,30289 ,13334,13384,13385 ,0,0,0}, {30243,30198,30291 ,13339,13294,13387 ,0,0,0}, - {30239,30289,30290 ,13335,13385,13386 ,0,0,0}, {30244,30243,30292 ,13340,13339,13388 ,0,0,0}, - {30290,30291,30198 ,13386,13387,13294 ,0,0,0}, {30244,30293,30245 ,13340,13389,13341 ,0,0,0}, - {30291,30292,30243 ,13387,13388,13339 ,0,0,0}, {30245,30241,30246 ,13341,13337,13342 ,0,0,0}, - {30292,30293,30244 ,13388,13389,13340 ,0,0,0}, {30247,30246,30294 ,13343,13342,13390 ,0,0,0}, - {30293,30241,30245 ,13389,13337,13341 ,0,0,0}, {30204,30247,30295 ,13300,13343,13391 ,0,0,0}, - {30246,30241,30294 ,13342,13337,13390 ,0,0,0}, {30251,30204,30296 ,13347,13300,13392 ,0,0,0}, - {30247,30294,30295 ,13343,13390,13391 ,0,0,0}, {30252,30251,30297 ,13348,13347,13393 ,0,0,0}, - {30295,30296,30204 ,13391,13392,13300 ,0,0,0}, {30252,30298,30253 ,13348,13394,13349 ,0,0,0}, - {30296,30297,30251 ,13392,13393,13347 ,0,0,0}, {30253,30249,30254 ,13349,13345,13350 ,0,0,0}, - {30297,30298,30252 ,13393,13394,13348 ,0,0,0}, {30255,30254,30299 ,13351,13350,13395 ,0,0,0}, - {30298,30249,30253 ,13394,13345,13349 ,0,0,0}, {30169,30255,30300 ,13264,13351,13396 ,0,0,0}, - {30254,30249,30299 ,13350,13345,13395 ,0,0,0}, {30259,30169,30301 ,13355,13264,13397 ,0,0,0}, - {30255,30299,30300 ,13351,13395,13396 ,0,0,0}, {30257,30259,30302 ,13353,13355,13398 ,0,0,0}, - {30300,30301,30169 ,13396,13397,13264 ,0,0,0}, {30303,30304,30305 ,13399,13400,13401 ,0,0,0}, - {30301,30302,30259 ,13397,13398,13355 ,0,0,0}, {30256,30306,30260 ,13352,13402,13356 ,0,0,0}, - {30302,30258,30257 ,13398,13354,13353 ,0,0,0}, {30260,30305,30261 ,13356,13401,13357 ,0,0,0}, - {30258,30306,30256 ,13354,13402,13352 ,0,0,0}, {30262,30261,30307 ,13358,13357,13403 ,0,0,0}, - {30306,30305,30260 ,13402,13401,13356 ,0,0,0}, {30215,30262,30308 ,13311,13358,13404 ,0,0,0}, - {30261,30305,30307 ,13357,13401,13403 ,0,0,0}, {30263,30215,30309 ,13359,13311,13405 ,0,0,0}, - {30262,30307,30308 ,13358,13403,13404 ,0,0,0}, {30267,30263,30310 ,13363,13359,13406 ,0,0,0}, - {30215,30308,30309 ,13311,13404,13405 ,0,0,0}, {30265,30267,30311 ,13361,13363,13407 ,0,0,0}, - {30309,30310,30263 ,13405,13406,13359 ,0,0,0}, {30312,30268,30264 ,13408,13364,13360 ,0,0,0}, - {30310,30311,30267 ,13406,13407,13363 ,0,0,0}, {30313,30314,30315 ,13409,13410,13411 ,0,0,0}, - {30311,30266,30265 ,13407,13362,13361 ,0,0,0}, {30268,30316,30269 ,13364,13412,13365 ,0,0,0}, - {30266,30312,30264 ,13362,13408,13360 ,0,0,0}, {30269,30315,30270 ,13365,13411,13366 ,0,0,0}, - {30312,30316,30268 ,13408,13412,13364 ,0,0,0}, {30270,30317,30223 ,13366,13413,13319 ,0,0,0}, - {30316,30315,30269 ,13412,13411,13365 ,0,0,0}, {30223,30087,30086 ,13319,13175,13174 ,0,0,0}, - {30315,30317,30270 ,13411,13413,13366 ,0,0,0}, {30086,30085,30271 ,13174,13173,13367 ,0,0,0}, - {30087,30223,30317 ,13175,13319,13413 ,0,0,0}, {30272,30318,30095 ,13368,13414,13183 ,0,0,0}, - {30319,30320,30272 ,13415,13416,13368 ,0,0,0}, {30083,30086,30271 ,13170,13174,13367 ,0,0,0}, - {30271,30318,30272 ,13367,13414,13368 ,0,0,0}, {30273,30272,30320 ,13369,13368,13416 ,0,0,0}, - {30041,30040,30226 ,13091,13090,13322 ,0,0,0}, {29708,30042,29704 ,13417,13094,13093 ,0,0,0}, - {30277,30275,30035 ,13373,13371,13085 ,0,0,0}, {30226,30276,30225 ,13322,13372,13321 ,0,0,0}, - {30042,30321,30276 ,13094,13418,13372 ,0,0,0}, {30278,30277,30322 ,13374,13373,13419 ,0,0,0}, - {30275,30321,30035 ,13371,13418,13085 ,0,0,0}, {30323,30322,30324 ,13420,13419,13421 ,0,0,0}, - {30277,30035,30322 ,13373,13085,13419 ,0,0,0}, {30323,30325,30279 ,13420,13422,13375 ,0,0,0}, - {30279,30278,30323 ,13375,13374,13420 ,0,0,0}, {30325,30326,30280 ,13422,13423,13376 ,0,0,0}, - {30280,30279,30325 ,13376,13375,13422 ,0,0,0}, {30326,30327,30281 ,13423,13424,13377 ,0,0,0}, - {30281,30280,30326 ,13377,13376,13423 ,0,0,0}, {30327,30328,30282 ,13424,13425,13378 ,0,0,0}, - {30282,30281,30327 ,13378,13377,13424 ,0,0,0}, {30328,30329,30283 ,13425,13426,13379 ,0,0,0}, - {30283,30282,30328 ,13379,13378,13425 ,0,0,0}, {30329,30330,30234 ,13426,13427,13330 ,0,0,0}, - {30234,30283,30329 ,13330,13379,13426 ,0,0,0}, {30330,30284,30287 ,13427,13380,13383 ,0,0,0}, - {30234,30330,30287 ,13330,13427,13383 ,0,0,0}, {28751,30331,30332 ,13428,13429,13430 ,0,0,0}, - {30287,30284,30286 ,13383,13380,13382 ,0,0,0}, {30288,30333,30289 ,13384,13431,13385 ,0,0,0}, - {30286,30285,30288 ,13382,13381,13384 ,0,0,0}, {30334,30333,30332 ,13432,13431,13430 ,0,0,0}, - {30285,30333,30288 ,13381,13431,13384 ,0,0,0}, {30334,30335,30290 ,13432,13433,13386 ,0,0,0}, - {30290,30289,30334 ,13386,13385,13432 ,0,0,0}, {30335,30336,30291 ,13433,13434,13387 ,0,0,0}, - {30291,30290,30335 ,13387,13386,13433 ,0,0,0}, {30336,30337,30292 ,13434,13435,13388 ,0,0,0}, - {30292,30291,30336 ,13388,13387,13434 ,0,0,0}, {30337,30242,30293 ,13435,13338,13389 ,0,0,0}, - {30292,30337,30293 ,13388,13435,13389 ,0,0,0}, {30338,30339,30340 ,13436,13437,13438 ,0,0,0}, - {30293,30242,30241 ,13389,13338,13337 ,0,0,0}, {30240,30339,30294 ,13336,13437,13390 ,0,0,0}, - {30241,30240,30294 ,13337,13336,13390 ,0,0,0}, {30339,30341,30295 ,13437,13439,13391 ,0,0,0}, - {30295,30294,30339 ,13391,13390,13437 ,0,0,0}, {30341,30342,30296 ,13439,13440,13392 ,0,0,0}, - {30296,30295,30341 ,13392,13391,13439 ,0,0,0}, {30342,30343,30297 ,13440,13441,13393 ,0,0,0}, - {30297,30296,30342 ,13393,13392,13440 ,0,0,0}, {30343,30250,30298 ,13441,13346,13394 ,0,0,0}, - {30297,30343,30298 ,13393,13441,13394 ,0,0,0}, {30344,28742,30345 ,13442,13443,13444 ,0,0,0}, - {30298,30250,30249 ,13394,13346,13345 ,0,0,0}, {30300,30299,30346 ,13396,13395,13445 ,0,0,0}, - {30249,30248,30299 ,13345,13344,13395 ,0,0,0}, {30347,30346,30344 ,13446,13445,13442 ,0,0,0}, - {30299,30248,30346 ,13395,13344,13445 ,0,0,0}, {30347,30348,30301 ,13446,13447,13397 ,0,0,0}, - {30301,30300,30347 ,13397,13396,13446 ,0,0,0}, {30348,30349,30302 ,13447,13448,13398 ,0,0,0}, - {30302,30301,30348 ,13398,13397,13447 ,0,0,0}, {30349,30350,30258 ,13448,13449,13354 ,0,0,0}, - {30258,30302,30349 ,13354,13398,13448 ,0,0,0}, {30350,30303,30306 ,13449,13399,13402 ,0,0,0}, - {30258,30350,30306 ,13354,13449,13402 ,0,0,0}, {30351,30352,30353 ,13450,13451,13452 ,0,0,0}, - {30306,30303,30305 ,13402,13399,13401 ,0,0,0}, {30304,30352,30307 ,13400,13451,13403 ,0,0,0}, - {30305,30304,30307 ,13401,13400,13403 ,0,0,0}, {30352,30354,30308 ,13451,13453,13404 ,0,0,0}, - {30308,30307,30352 ,13404,13403,13451 ,0,0,0}, {30354,30355,30309 ,13453,13454,13405 ,0,0,0}, - {30309,30308,30354 ,13405,13404,13453 ,0,0,0}, {30355,30356,30310 ,13454,13455,13406 ,0,0,0}, - {30310,30309,30355 ,13406,13405,13454 ,0,0,0}, {30356,30357,30311 ,13455,13456,13407 ,0,0,0}, - {30311,30310,30356 ,13407,13406,13455 ,0,0,0}, {30357,30358,30266 ,13456,13457,13362 ,0,0,0}, - {30266,30311,30357 ,13362,13407,13456 ,0,0,0}, {30358,30359,30312 ,13457,13458,13408 ,0,0,0}, - {30312,30266,30358 ,13408,13362,13457 ,0,0,0}, {30359,30313,30316 ,13458,13409,13412 ,0,0,0}, - {30312,30359,30316 ,13408,13458,13412 ,0,0,0}, {30317,30314,30360 ,13413,13410,13459 ,0,0,0}, - {30316,30313,30315 ,13412,13409,13411 ,0,0,0}, {30092,30085,30087 ,13180,13173,13175 ,0,0,0}, - {30315,30314,30317 ,13411,13410,13413 ,0,0,0}, {30091,30318,30085 ,13179,13414,13173 ,0,0,0}, - {30317,30360,30087 ,13413,13459,13175 ,0,0,0}, {30099,30093,30361 ,13187,13181,13460 ,0,0,0}, - {30360,30092,30087 ,13459,13180,13175 ,0,0,0}, {30091,30362,30363 ,13179,13461,13462 ,0,0,0}, - {30095,30319,30272 ,13183,13415,13368 ,0,0,0}, {30271,30085,30318 ,13367,13173,13414 ,0,0,0}, - {30095,30318,30363 ,13183,13414,13462 ,0,0,0}, {30094,30319,30095 ,13182,13415,13183 ,0,0,0}, - {30040,30042,30276 ,13090,13094,13372 ,0,0,0}, {29708,29710,30031 ,13417,13078,13081 ,0,0,0}, - {30321,30031,30036 ,13418,13081,13086 ,0,0,0}, {30276,30321,30275 ,13372,13418,13371 ,0,0,0}, - {30035,30321,30036 ,13085,13418,13086 ,0,0,0}, {30034,30324,30322 ,13084,13421,13419 ,0,0,0}, - {30322,30035,30034 ,13419,13085,13084 ,0,0,0}, {30324,30364,30323 ,13421,13463,13420 ,0,0,0}, - {30365,30325,30364 ,13464,13422,13463 ,0,0,0}, {30278,30322,30323 ,13374,13419,13420 ,0,0,0}, - {30325,30323,30364 ,13422,13420,13463 ,0,0,0}, {30366,30326,30365 ,13465,13423,13464 ,0,0,0}, - {30326,30325,30365 ,13423,13422,13464 ,0,0,0}, {30367,30327,30366 ,13466,13424,13465 ,0,0,0}, - {30327,30326,30366 ,13424,13423,13465 ,0,0,0}, {30368,30328,30367 ,13467,13425,13466 ,0,0,0}, - {30328,30327,30367 ,13425,13424,13466 ,0,0,0}, {30369,30329,30368 ,13468,13426,13467 ,0,0,0}, - {30329,30328,30368 ,13426,13425,13467 ,0,0,0}, {30370,30330,30369 ,13469,13427,13468 ,0,0,0}, - {30330,30329,30369 ,13427,13426,13468 ,0,0,0}, {30371,30284,30370 ,13470,13380,13469 ,0,0,0}, - {30284,30330,30370 ,13380,13427,13469 ,0,0,0}, {30372,30285,30371 ,13471,13381,13470 ,0,0,0}, - {30285,30284,30371 ,13381,13380,13470 ,0,0,0}, {30332,30333,30372 ,13430,13431,13471 ,0,0,0}, - {30285,30372,30333 ,13381,13471,13431 ,0,0,0}, {30332,30331,30334 ,13430,13429,13432 ,0,0,0}, - {30373,30335,30331 ,13472,13433,13429 ,0,0,0}, {30289,30333,30334 ,13385,13431,13432 ,0,0,0}, - {30335,30334,30331 ,13433,13432,13429 ,0,0,0}, {30374,30336,30373 ,13473,13434,13472 ,0,0,0}, - {30336,30335,30373 ,13434,13433,13472 ,0,0,0}, {30375,30337,30374 ,13474,13435,13473 ,0,0,0}, - {30337,30336,30374 ,13435,13434,13473 ,0,0,0}, {30376,30242,30375 ,13475,13338,13474 ,0,0,0}, - {30242,30337,30375 ,13338,13435,13474 ,0,0,0}, {30340,30240,30376 ,13438,13336,13475 ,0,0,0}, - {30240,30242,30376 ,13336,13338,13475 ,0,0,0}, {30340,28659,30338 ,13438,13476,13436 ,0,0,0}, - {30240,30340,30339 ,13336,13438,13437 ,0,0,0}, {30377,30341,30338 ,13477,13439,13436 ,0,0,0}, - {30341,30339,30338 ,13439,13437,13436 ,0,0,0}, {30378,30342,30377 ,13478,13440,13477 ,0,0,0}, - {30342,30341,30377 ,13440,13439,13477 ,0,0,0}, {30379,30343,30378 ,13479,13441,13478 ,0,0,0}, - {30343,30342,30378 ,13441,13440,13478 ,0,0,0}, {30380,30250,30379 ,13480,13346,13479 ,0,0,0}, - {30250,30343,30379 ,13346,13441,13479 ,0,0,0}, {30381,30248,30380 ,13481,13344,13480 ,0,0,0}, - {30248,30250,30380 ,13344,13346,13480 ,0,0,0}, {30344,30346,30381 ,13442,13445,13481 ,0,0,0}, - {30248,30381,30346 ,13344,13481,13445 ,0,0,0}, {30344,30345,30347 ,13442,13444,13446 ,0,0,0}, - {30382,30348,30345 ,13482,13447,13444 ,0,0,0}, {30300,30346,30347 ,13396,13445,13446 ,0,0,0}, - {30348,30347,30345 ,13447,13446,13444 ,0,0,0}, {30383,30349,30382 ,13483,13448,13482 ,0,0,0}, - {30349,30348,30382 ,13448,13447,13482 ,0,0,0}, {30384,30350,30383 ,13484,13449,13483 ,0,0,0}, - {30350,30349,30383 ,13449,13448,13483 ,0,0,0}, {30385,30303,30384 ,13485,13399,13484 ,0,0,0}, - {30303,30350,30384 ,13399,13449,13484 ,0,0,0}, {30353,30304,30385 ,13452,13400,13485 ,0,0,0}, - {30304,30303,30385 ,13400,13399,13485 ,0,0,0}, {30353,28681,30351 ,13452,13486,13450 ,0,0,0}, - {30304,30353,30352 ,13400,13452,13451 ,0,0,0}, {30386,30354,30351 ,13487,13453,13450 ,0,0,0}, - {30354,30352,30351 ,13453,13451,13450 ,0,0,0}, {30387,30355,30386 ,13488,13454,13487 ,0,0,0}, - {30355,30354,30386 ,13454,13453,13487 ,0,0,0}, {30388,30356,30387 ,13489,13455,13488 ,0,0,0}, - {30356,30355,30387 ,13455,13454,13488 ,0,0,0}, {30389,30357,30388 ,13490,13456,13489 ,0,0,0}, - {30357,30356,30388 ,13456,13455,13489 ,0,0,0}, {30390,30358,30389 ,13491,13457,13490 ,0,0,0}, - {30358,30357,30389 ,13457,13456,13490 ,0,0,0}, {30391,30359,30390 ,13492,13458,13491 ,0,0,0}, - {30359,30358,30390 ,13458,13457,13491 ,0,0,0}, {30392,30313,30391 ,13493,13409,13492 ,0,0,0}, - {30313,30359,30391 ,13409,13458,13492 ,0,0,0}, {30393,30314,30392 ,13494,13410,13493 ,0,0,0}, - {30314,30313,30392 ,13410,13409,13493 ,0,0,0}, {30394,30360,30393 ,13495,13459,13494 ,0,0,0}, - {30360,30314,30393 ,13459,13410,13494 ,0,0,0}, {30395,30092,30394 ,13496,13180,13495 ,0,0,0}, - {30092,30360,30394 ,13180,13459,13495 ,0,0,0}, {30395,30362,30091 ,13496,13461,13179 ,0,0,0}, - {30091,30092,30395 ,13179,13180,13496 ,0,0,0}, {30362,30361,30363 ,13461,13460,13462 ,0,0,0}, - {30095,30363,30093 ,13183,13462,13181 ,0,0,0}, {30318,30091,30363 ,13414,13179,13462 ,0,0,0}, - {30361,30093,30363 ,13460,13181,13462 ,0,0,0}, {30094,30093,30100 ,13182,13181,13188 ,0,0,0}, - {30321,30042,30031 ,13418,13094,13081 ,0,0,0}, {30031,30042,29708 ,13081,13094,13417 ,0,0,0}, - {28763,28759,30036 ,13281,13497,13086 ,0,0,0}, {30036,28759,30034 ,13086,13497,13084 ,0,0,0}, - {28759,28758,30034 ,13497,13498,13084 ,0,0,0}, {30034,28758,30324 ,13084,13498,13421 ,0,0,0}, - {28758,28757,30324 ,13498,13499,13421 ,0,0,0}, {30324,28757,30364 ,13421,13499,13463 ,0,0,0}, - {28757,28620,30364 ,13499,13500,13463 ,0,0,0}, {30364,28620,30365 ,13463,13500,13464 ,0,0,0}, - {28620,28610,30365 ,13500,13501,13464 ,0,0,0}, {30365,28610,30366 ,13464,13501,13465 ,0,0,0}, - {28610,28643,30366 ,13501,13502,13465 ,0,0,0}, {30366,28643,30367 ,13465,13502,13466 ,0,0,0}, - {28643,28640,30367 ,13502,13503,13466 ,0,0,0}, {30367,28640,30368 ,13466,13503,13467 ,0,0,0}, - {28640,28645,30368 ,13503,13504,13467 ,0,0,0}, {28645,28648,30369 ,13504,13505,13468 ,0,0,0}, - {28645,30369,30368 ,13504,13468,13467 ,0,0,0}, {28648,28615,30370 ,13505,13506,13469 ,0,0,0}, - {28648,30370,30369 ,13505,13469,13468 ,0,0,0}, {28615,28614,30371 ,13506,13507,13470 ,0,0,0}, - {28615,30371,30370 ,13506,13470,13469 ,0,0,0}, {28614,28650,30372 ,13507,13508,13471 ,0,0,0}, - {28614,30372,30371 ,13507,13471,13470 ,0,0,0}, {28650,28752,30332 ,13508,13509,13430 ,0,0,0}, - {28650,30332,30372 ,13508,13430,13471 ,0,0,0}, {28751,30332,28752 ,13428,13430,13509 ,0,0,0}, - {28751,28653,30331 ,13428,13510,13429 ,0,0,0}, {30331,28653,30373 ,13429,13510,13472 ,0,0,0}, - {28653,28658,30373 ,13510,13511,13472 ,0,0,0}, {30373,28658,30374 ,13472,13511,13473 ,0,0,0}, - {28658,28656,30374 ,13511,13512,13473 ,0,0,0}, {28656,28655,30375 ,13512,13513,13474 ,0,0,0}, - {28656,30375,30374 ,13512,13474,13473 ,0,0,0}, {28655,28750,30376 ,13513,13514,13475 ,0,0,0}, - {28655,30376,30375 ,13513,13475,13474 ,0,0,0}, {28750,28659,30340 ,13514,13476,13438 ,0,0,0}, - {28750,30340,30376 ,13514,13438,13475 ,0,0,0}, {28659,28749,30338 ,13476,13515,13436 ,0,0,0}, - {28749,28745,30338 ,13515,13516,13436 ,0,0,0}, {30338,28745,30377 ,13436,13516,13477 ,0,0,0}, - {28745,28663,30377 ,13516,13517,13477 ,0,0,0}, {30377,28663,30378 ,13477,13517,13478 ,0,0,0}, - {28663,28665,30378 ,13517,13518,13478 ,0,0,0}, {28665,28670,30379 ,13518,13519,13479 ,0,0,0}, - {28665,30379,30378 ,13518,13479,13478 ,0,0,0}, {28670,28668,30380 ,13519,13520,13480 ,0,0,0}, - {28670,30380,30379 ,13519,13480,13479 ,0,0,0}, {28668,28667,30381 ,13520,13521,13481 ,0,0,0}, - {28668,30381,30380 ,13520,13481,13480 ,0,0,0}, {28667,28743,30344 ,13521,13522,13442 ,0,0,0}, - {28667,30344,30381 ,13521,13442,13481 ,0,0,0}, {28742,30344,28743 ,13443,13442,13522 ,0,0,0}, - {28742,28672,30345 ,13443,13523,13444 ,0,0,0}, {30345,28672,30382 ,13444,13523,13482 ,0,0,0}, - {28672,28679,30382 ,13523,13524,13482 ,0,0,0}, {28679,28678,30383 ,13524,13525,13483 ,0,0,0}, - {28679,30383,30382 ,13524,13483,13482 ,0,0,0}, {28678,28677,30384 ,13525,13526,13484 ,0,0,0}, - {28678,30384,30383 ,13525,13484,13483 ,0,0,0}, {28677,28739,30385 ,13526,13527,13485 ,0,0,0}, - {28677,30385,30384 ,13526,13485,13484 ,0,0,0}, {28739,28681,30353 ,13527,13486,13452 ,0,0,0}, - {28739,30353,30385 ,13527,13452,13485 ,0,0,0}, {28681,28680,30351 ,13486,13528,13450 ,0,0,0}, - {28680,28686,30351 ,13528,13529,13450 ,0,0,0}, {30351,28686,30386 ,13450,13529,13487 ,0,0,0}, - {28686,28685,30386 ,13529,13530,13487 ,0,0,0}, {30386,28685,30387 ,13487,13530,13488 ,0,0,0}, - {28685,28690,30387 ,13530,13531,13488 ,0,0,0}, {30387,28690,30388 ,13488,13531,13489 ,0,0,0}, - {28690,28688,30388 ,13531,13532,13489 ,0,0,0}, {28688,28696,30389 ,13532,13533,13490 ,0,0,0}, - {28688,30389,30388 ,13532,13490,13489 ,0,0,0}, {28696,28692,30390 ,13533,13534,13491 ,0,0,0}, - {28696,30390,30389 ,13533,13491,13490 ,0,0,0}, {28692,28694,30391 ,13534,13535,13492 ,0,0,0}, - {28692,30391,30390 ,13534,13492,13491 ,0,0,0}, {28694,28697,30392 ,13535,13536,13493 ,0,0,0}, - {28694,30392,30391 ,13535,13493,13492 ,0,0,0}, {28697,28699,30393 ,13536,13537,13494 ,0,0,0}, - {28697,30393,30392 ,13536,13494,13493 ,0,0,0}, {28699,28704,30394 ,13537,13538,13495 ,0,0,0}, - {28699,30394,30393 ,13537,13495,13494 ,0,0,0}, {28704,28710,30395 ,13538,13539,13496 ,0,0,0}, - {28704,30395,30394 ,13538,13496,13495 ,0,0,0}, {28710,28711,30362 ,13539,13540,13461 ,0,0,0}, - {28710,30362,30395 ,13539,13461,13496 ,0,0,0}, {28711,28709,30361 ,13540,13541,13460 ,0,0,0}, - {28711,30361,30362 ,13540,13460,13461 ,0,0,0}, {28709,28703,30099 ,13541,13542,13187 ,0,0,0}, - {28709,30099,30361 ,13541,13187,13460 ,0,0,0}, {30099,28703,28702 ,13187,13542,11616 ,0,0,0}, - {29932,29638,29659 ,13543,13543,13543 ,0,0,0}, {29268,29655,29264 ,13543,13543,13543 ,0,0,0}, - {29654,29659,29720 ,13543,13543,13543 ,0,0,0}, {29932,29659,29639 ,13543,13543,13543 ,0,0,0}, - {29654,29720,29797 ,13543,13543,13543 ,0,0,0}, {29639,29654,29269 ,13543,13543,13543 ,0,0,0}, - {29659,29654,29639 ,13543,13543,13543 ,0,0,0}, {29129,29264,29655 ,13543,13543,13543 ,0,0,0}, - {29268,29652,29649 ,13543,13543,13543 ,0,0,0}, {29135,29144,29479 ,13543,13543,13543 ,0,0,0}, - {29270,29129,29655 ,13543,13543,13543 ,0,0,0}, {29271,29270,29135 ,13543,13543,13543 ,0,0,0}, - {29270,29271,29260 ,13543,13543,13543 ,0,0,0}, {29142,29135,29479 ,13543,13543,13543 ,0,0,0}, - {29143,29144,29270 ,13543,13543,13543 ,0,0,0}, {29144,29135,29270 ,13543,13543,13543 ,0,0,0}, - {29657,29270,29655 ,13543,13543,13543 ,0,0,0}, {29657,29143,29270 ,13543,13543,13543 ,0,0,0}, - {29655,29268,29649 ,13543,13543,13543 ,0,0,0}, {29652,29268,29654 ,13543,13543,13543 ,0,0,0}, - {29269,29654,29267 ,13543,13543,13543 ,0,0,0}, {29268,29267,29654 ,13543,13543,13543 ,0,0,0}, - {30319,30094,30100 ,13544,13544,13544 ,0,0,0}, {30148,30185,28898 ,13544,13544,13544 ,0,0,0}, - {30104,30320,30100 ,13544,13544,13544 ,0,0,0}, {30224,30274,28814 ,13544,13544,13544 ,0,0,0}, - {30273,30320,30274 ,13544,13544,13544 ,0,0,0}, {30320,30104,28702 ,13544,13544,13544 ,0,0,0}, - {30319,30100,30320 ,13544,13544,13544 ,0,0,0}, {28814,30274,30320 ,13544,13544,13544 ,0,0,0}, - {30320,28702,28814 ,13544,13544,13544 ,0,0,0}, {28813,30224,28814 ,13544,13544,13544 ,0,0,0}, - {28813,28856,30224 ,13544,13544,13544 ,0,0,0}, {30185,30224,28898 ,13544,13544,13544 ,0,0,0}, - {28856,28898,30224 ,13544,13544,13544 ,0,0,0}, {30149,30148,28898 ,13544,13544,13544 ,0,0,0}, - {28942,28984,28943 ,13544,13544,13544 ,0,0,0}, {28943,30149,28898 ,13544,13544,13544 ,0,0,0}, - {30149,28943,28984 ,13544,13544,13544 ,0,0,0}, {28735,28983,28730 ,13544,13544,13544 ,0,0,0}, - {30149,28984,28736 ,13544,13544,13544 ,0,0,0}, {28984,28735,28734 ,13544,13544,13544 ,0,0,0}, - {28735,28984,28983 ,13544,13544,13544 ,0,0,0}, {28984,28734,28736 ,13544,13544,13544 ,0,0,0} -// M3abstandhalter20mm.prt - , {30396,30397,30398 ,17250,17251,17252 ,0,0,0}, {30398,30399,30400 ,17252,17253,17254 ,0,0,0}, - {30399,30401,30400 ,17253,17255,17254 ,0,0,0}, {30398,30400,30396 ,17252,17254,17250 ,0,0,0}, - {30402,30403,30404 ,17256,17257,17258 ,0,0,0}, {30404,30403,30401 ,17258,17257,17255 ,0,0,0}, - {30402,30405,30406 ,17256,17259,17260 ,0,0,0}, {30406,30403,30402 ,17260,17257,17256 ,0,0,0}, - {30406,30405,30407 ,17260,17259,17261 ,0,0,0}, {30407,30405,30408 ,17261,17259,17262 ,0,0,0}, - {30408,30409,30410 ,17262,17263,17264 ,0,0,0}, {30407,30408,30410 ,17261,17262,17264 ,0,0,0}, - {30401,30399,30404 ,17255,17253,17258 ,0,0,0}, {140,30411,30412 ,17265,82,17266 ,0,0,0}, - {140,30412,30409 ,17265,17266,17263 ,0,0,0}, {30409,30412,30410 ,17263,17266,17264 ,0,0,0}, - {30396,30413,30397 ,17250,17267,17251 ,0,0,0}, {30414,30413,30415 ,17268,17267,17269 ,0,0,0}, - {30413,30414,30397 ,17267,17268,17251 ,0,0,0}, {30416,30417,30415 ,17270,17271,17269 ,0,0,0}, - {30414,30415,30417 ,17268,17269,17271 ,0,0,0}, {30416,30418,30419 ,17270,17272,17273 ,0,0,0}, - {30419,30417,30416 ,17273,17271,17270 ,0,0,0}, {30420,30418,30421 ,17274,17272,17275 ,0,0,0}, - {30418,30420,30419 ,17272,17274,17273 ,0,0,0}, {30422,30423,30421 ,17276,17277,17275 ,0,0,0}, - {30420,30421,30423 ,17274,17275,17277 ,0,0,0}, {30422,30424,30425 ,17276,17278,17279 ,0,0,0}, - {30425,30423,30422 ,17279,17277,17276 ,0,0,0}, {126,30424,30426 ,17280,17278,17281 ,0,0,0}, - {30424,126,30425 ,17278,17280,17279 ,0,0,0}, {30422,30421,30427 ,17282,17283,17284 ,0,0,0}, - {30427,30424,30422 ,17284,17285,17282 ,0,0,0}, {30427,30426,30424 ,17284,17286,17285 ,0,0,0}, - {30427,30418,30416 ,17284,17287,17288 ,0,0,0}, {30421,30418,30427 ,17283,17287,17284 ,0,0,0}, - {30427,30415,30413 ,17284,17289,17290 ,0,0,0}, {30416,30415,30427 ,17288,17289,17284 ,0,0,0}, - {30413,30396,30427 ,17290,17291,17284 ,0,0,0}, {30401,30427,30400 ,17292,17284,17293 ,0,0,0}, - {30427,30396,30400 ,17284,17291,17293 ,0,0,0}, {30406,30427,30403 ,17294,17284,17295 ,0,0,0}, - {30427,30401,30403 ,17284,17292,17295 ,0,0,0}, {30410,30427,30407 ,17296,17284,17297 ,0,0,0}, - {30427,30406,30407 ,17284,17294,17297 ,0,0,0}, {30411,30427,30412 ,17298,17284,17299 ,0,0,0}, - {30427,30410,30412 ,17284,17296,17299 ,0,0,0}, {30428,30429,30430 ,17300,17301,17302 ,0,0,0}, - {30431,30432,30433 ,324,17303,17304 ,0,0,0}, {30434,30429,30435 ,17305,17301,17306 ,0,0,0}, - {30429,30434,30430 ,17301,17305,17302 ,0,0,0}, {30434,30435,30436 ,17305,17306,17307 ,0,0,0}, - {30437,30438,30436 ,17308,17309,17307 ,0,0,0}, {30436,30435,30437 ,17307,17306,17308 ,0,0,0}, - {30439,30438,30437 ,17310,17309,17308 ,0,0,0}, {30439,30440,30438 ,17310,82,17309 ,0,0,0}, - {30441,30428,30430 ,17311,17300,17302 ,0,0,0}, {30442,30443,30441 ,17312,17313,17311 ,0,0,0}, - {30428,30441,30443 ,17300,17311,17313 ,0,0,0}, {30444,30445,30443 ,17314,17315,17313 ,0,0,0}, - {30443,30442,30444 ,17313,17312,17314 ,0,0,0}, {30445,30446,30447 ,17315,17316,17317 ,0,0,0}, - {30446,30445,30444 ,17316,17315,17314 ,0,0,0}, {30431,30447,30448 ,324,17317,17318 ,0,0,0}, - {30446,30448,30447 ,17316,17318,17317 ,0,0,0}, {30449,30450,30451 ,17319,17320,17321 ,0,0,0}, - {30431,30448,30432 ,324,17318,17303 ,0,0,0}, {30452,30453,30454 ,17322,17323,17324 ,0,0,0}, - {30453,30449,30455 ,17323,17319,17325 ,0,0,0}, {30456,30457,30458 ,17326,17327,17328 ,0,0,0}, - {30459,30460,30457 ,17329,17330,17327 ,0,0,0}, {30461,30462,30463 ,17331,17332,17333 ,0,0,0}, - {30456,30463,30462 ,17326,17333,17332 ,0,0,0}, {30461,30464,30465 ,17331,4726,17334 ,0,0,0}, - {30465,30462,30461 ,17334,17332,17331 ,0,0,0}, {30460,30458,30457 ,17330,17328,17327 ,0,0,0}, - {30456,30458,30463 ,17326,17328,17333 ,0,0,0}, {30459,30453,30452 ,17329,17323,17322 ,0,0,0}, - {30459,30452,30460 ,17329,17322,17330 ,0,0,0}, {30449,30451,30455 ,17319,17321,17325 ,0,0,0}, - {30454,30453,30455 ,17324,17323,17325 ,0,0,0}, {30433,30450,30431 ,17304,17320,324 ,0,0,0}, - {30451,30450,30433 ,17321,17320,17304 ,0,0,0}, {30466,30467,30468 ,21,17335,17336 ,0,0,0}, - {30468,30469,30470 ,17336,17337,17338 ,0,0,0}, {30469,30471,30470 ,17337,17339,17338 ,0,0,0}, - {30468,30470,30466 ,17336,17338,21 ,0,0,0}, {30472,30473,30474 ,17340,17341,17342 ,0,0,0}, - {30474,30473,30471 ,17342,17341,17339 ,0,0,0}, {30472,30475,30476 ,17340,17343,17344 ,0,0,0}, - {30476,30473,30472 ,17344,17341,17340 ,0,0,0}, {30476,30475,30477 ,17344,17343,17345 ,0,0,0}, - {30477,30475,30478 ,17345,17343,17346 ,0,0,0}, {30478,30479,30480 ,17346,17347,17348 ,0,0,0}, - {30477,30478,30480 ,17345,17346,17348 ,0,0,0}, {30471,30469,30474 ,17339,17337,17342 ,0,0,0}, - {30481,30482,30483 ,8320,82,17349 ,0,0,0}, {30481,30483,30479 ,8320,17349,17347 ,0,0,0}, - {30479,30483,30480 ,17347,17349,17348 ,0,0,0}, {30466,30484,30467 ,21,17350,17335 ,0,0,0}, - {30485,30484,30486 ,17351,17350,17352 ,0,0,0}, {30484,30485,30467 ,17350,17351,17335 ,0,0,0}, - {30487,30488,30486 ,17353,17354,17352 ,0,0,0}, {30485,30486,30488 ,17351,17352,17354 ,0,0,0}, - {30487,30489,30490 ,17353,17355,17356 ,0,0,0}, {30490,30488,30487 ,17356,17354,17353 ,0,0,0}, - {30491,30489,30492 ,17357,17355,17358 ,0,0,0}, {30489,30491,30490 ,17355,17357,17356 ,0,0,0}, - {30493,30494,30492 ,17359,17360,17358 ,0,0,0}, {30491,30492,30494 ,17357,17358,17360 ,0,0,0}, - {30493,30495,30496 ,17359,17361,17362 ,0,0,0}, {30496,30494,30493 ,17362,17360,17359 ,0,0,0}, - {30497,30495,30498 ,126,17361,17363 ,0,0,0}, {30495,30497,30496 ,17361,126,17362 ,0,0,0}, - {30493,30492,30499 ,17364,17365,17366 ,0,0,0}, {30499,30495,30493 ,17366,17367,17364 ,0,0,0}, - {30499,30498,30495 ,17366,17368,17367 ,0,0,0}, {30499,30489,30487 ,17366,17369,17370 ,0,0,0}, - {30492,30489,30499 ,17365,17369,17366 ,0,0,0}, {30499,30486,30484 ,17366,17371,17372 ,0,0,0}, - {30487,30486,30499 ,17370,17371,17366 ,0,0,0}, {30484,30466,30499 ,17372,17373,17366 ,0,0,0}, - {30471,30499,30470 ,17374,17366,17375 ,0,0,0}, {30499,30466,30470 ,17366,17373,17375 ,0,0,0}, - {30476,30499,30473 ,17376,17366,17377 ,0,0,0}, {30499,30471,30473 ,17366,17374,17377 ,0,0,0}, - {30480,30499,30477 ,17378,17366,17379 ,0,0,0}, {30499,30476,30477 ,17366,17376,17379 ,0,0,0}, - {30482,30499,30483 ,17380,17366,17381 ,0,0,0}, {30499,30480,30483 ,17366,17378,17381 ,0,0,0}, - {30500,30501,30502 ,17382,17383,17384 ,0,0,0}, {30503,30504,30505 ,21,7309,17385 ,0,0,0}, - {30506,30501,30507 ,17386,17383,17387 ,0,0,0}, {30501,30506,30502 ,17383,17386,17384 ,0,0,0}, - {30506,30507,30508 ,17386,17387,17388 ,0,0,0}, {30509,30510,30508 ,17389,17390,17388 ,0,0,0}, - {30508,30507,30509 ,17388,17387,17389 ,0,0,0}, {30511,30510,30509 ,17391,17390,17389 ,0,0,0}, - {30511,30512,30510 ,17391,17392,17390 ,0,0,0}, {30513,30500,30502 ,17393,17382,17384 ,0,0,0}, - {30514,30515,30513 ,17394,17395,17393 ,0,0,0}, {30500,30513,30515 ,17382,17393,17395 ,0,0,0}, - {30516,30517,30515 ,17396,17397,17395 ,0,0,0}, {30515,30514,30516 ,17395,17394,17396 ,0,0,0}, - {30517,30518,30519 ,17397,17398,17399 ,0,0,0}, {30518,30517,30516 ,17398,17397,17396 ,0,0,0}, - {30503,30519,30520 ,21,17399,17400 ,0,0,0}, {30518,30520,30519 ,17398,17400,17399 ,0,0,0}, - {30521,30522,30523 ,17401,17402,17403 ,0,0,0}, {30503,30520,30504 ,21,17400,7309 ,0,0,0}, - {30524,30525,30526 ,17404,17405,17406 ,0,0,0}, {30525,30521,30527 ,17405,17401,17407 ,0,0,0}, - {30528,30529,30530 ,17408,17409,17410 ,0,0,0}, {30531,30532,30529 ,17411,17412,17409 ,0,0,0}, - {30533,30534,30535 ,17413,17414,17415 ,0,0,0}, {30528,30535,30534 ,17408,17415,17414 ,0,0,0}, - {30533,30536,30537 ,17413,126,17416 ,0,0,0}, {30537,30534,30533 ,17416,17414,17413 ,0,0,0}, - {30532,30530,30529 ,17412,17410,17409 ,0,0,0}, {30528,30530,30535 ,17408,17410,17415 ,0,0,0}, - {30531,30525,30524 ,17411,17405,17404 ,0,0,0}, {30531,30524,30532 ,17411,17404,17412 ,0,0,0}, - {30521,30523,30527 ,17401,17403,17407 ,0,0,0}, {30526,30525,30527 ,17406,17405,17407 ,0,0,0}, - {30505,30522,30503 ,17385,17402,21 ,0,0,0}, {30523,30522,30505 ,17403,17402,17385 ,0,0,0}, - {30538,30429,30539 ,17417,17417,17417 ,0,0,0}, {30540,30541,30429 ,17417,17417,17417 ,0,0,0}, - {30429,30541,30539 ,17417,17417,17417 ,0,0,0}, {30538,30539,30542 ,17417,17417,17417 ,0,0,0}, - {30543,30544,30432 ,730,730,730 ,0,0,0}, {30545,30455,30546 ,730,730,730 ,0,0,0}, - {30547,126,30440 ,730,730,730 ,0,0,0}, {30548,30423,30425 ,730,730,730 ,0,0,0}, - {30549,30436,30550 ,730,730,730 ,0,0,0}, {30434,30549,30551 ,730,730,730 ,0,0,0}, - {30551,30430,30434 ,730,730,730 ,0,0,0}, {30552,30441,30551 ,730,730,730 ,0,0,0}, - {30436,30549,30434 ,730,730,730 ,0,0,0}, {30438,126,30550 ,730,730,730 ,0,0,0}, - {30438,30550,30436 ,730,730,730 ,0,0,0}, {30552,30553,30442 ,730,730,730 ,0,0,0}, - {30438,30440,126 ,730,730,730 ,0,0,0}, {30444,30554,30446 ,730,730,730 ,0,0,0}, - {30442,30553,30444 ,730,730,730 ,0,0,0}, {30555,30419,30420 ,730,730,730 ,0,0,0}, - {30417,30419,30556 ,730,730,730 ,0,0,0}, {30432,30544,30433 ,730,730,730 ,0,0,0}, - {30557,30414,30558 ,730,730,730 ,0,0,0}, {30559,30397,30414 ,730,730,730 ,0,0,0}, - {30451,30433,30546 ,730,730,730 ,0,0,0}, {30560,30561,30545 ,730,730,730 ,0,0,0}, - {30398,30562,30399 ,730,730,730 ,0,0,0}, {30397,30563,30398 ,730,730,730 ,0,0,0}, - {30460,30452,30561 ,730,730,730 ,0,0,0}, {30561,30454,30455 ,730,730,730 ,0,0,0}, - {30404,30564,30565 ,730,730,730 ,0,0,0}, {30564,30399,30566 ,730,730,730 ,0,0,0}, - {30567,30458,30568 ,730,730,730 ,0,0,0}, {30569,30405,30402 ,730,730,730 ,0,0,0}, - {30402,30404,30565 ,730,730,730 ,0,0,0}, {30408,30570,30571 ,730,730,730 ,0,0,0}, - {140,30464,30461 ,730,730,730 ,0,0,0}, {30409,30572,140 ,730,730,730 ,0,0,0}, - {30409,30408,30571 ,730,730,730 ,0,0,0}, {30573,30461,30463 ,730,730,730 ,0,0,0}, - {30574,30570,30405 ,730,730,730 ,0,0,0}, {30463,30567,30573 ,730,730,730 ,0,0,0}, - {30554,30543,30448 ,730,730,730 ,0,0,0}, {30420,30423,30575 ,730,730,730 ,0,0,0}, - {30397,30559,30563 ,730,730,730 ,0,0,0}, {30551,30441,30430 ,730,730,730 ,0,0,0}, - {30552,30442,30441 ,730,730,730 ,0,0,0}, {30554,30444,30553 ,730,730,730 ,0,0,0}, - {30554,30448,30446 ,730,730,730 ,0,0,0}, {30543,30432,30448 ,730,730,730 ,0,0,0}, - {30546,30433,30544 ,730,730,730 ,0,0,0}, {30546,30455,30451 ,730,730,730 ,0,0,0}, - {30561,30455,30545 ,730,730,730 ,0,0,0}, {30561,30568,30458 ,730,730,730 ,0,0,0}, - {30458,30460,30561 ,730,730,730 ,0,0,0}, {30567,30463,30458 ,730,730,730 ,0,0,0}, - {140,30461,30573 ,730,730,730 ,0,0,0}, {140,30572,30464 ,730,730,730 ,0,0,0}, - {30409,30571,30572 ,730,730,730 ,0,0,0}, {30405,30570,30408 ,730,730,730 ,0,0,0}, - {30405,30569,30574 ,730,730,730 ,0,0,0}, {30402,30565,30569 ,730,730,730 ,0,0,0}, - {30399,30564,30404 ,730,730,730 ,0,0,0}, {30399,30562,30566 ,730,730,730 ,0,0,0}, - {30398,30563,30562 ,730,730,730 ,0,0,0}, {30557,30559,30414 ,730,730,730 ,0,0,0}, - {30417,30558,30414 ,730,730,730 ,0,0,0}, {30419,30555,30556 ,730,730,730 ,0,0,0}, - {30417,30556,30558 ,730,730,730 ,0,0,0}, {30420,30576,30555 ,730,730,730 ,0,0,0}, - {30575,30423,30548 ,730,730,730 ,0,0,0}, {30576,30420,30575 ,730,730,730 ,0,0,0}, - {30548,30425,30547 ,730,730,730 ,0,0,0}, {126,30547,30425 ,730,730,730 ,0,0,0}, - {30454,30561,30452 ,730,730,730 ,0,0,0}, {30560,30568,30561 ,730,730,730 ,0,0,0}, - {30577,30578,30529 ,17418,17419,17419 ,0,0,0}, {30578,30579,30580 ,17419,2197,2197 ,0,0,0}, - {30580,30529,30578 ,2197,17419,17419 ,0,0,0}, {30529,30581,30577 ,17419,17418,17418 ,0,0,0}, - {30582,30583,30501 ,1398,17420,17420 ,0,0,0}, {30583,30538,30542 ,17420,1398,1398 ,0,0,0}, - {30542,30501,30583 ,1398,17420,17420 ,0,0,0}, {30501,30584,30582 ,17420,1398,1398 ,0,0,0}, - {30503,30579,30585 ,17421,1814,17422 ,0,0,0}, {30582,30584,30585 ,17423,17423,17422 ,0,0,0}, - {30584,30503,30585 ,17423,17421,17422 ,0,0,0}, {30503,30580,30579 ,17421,17424,1814 ,0,0,0}, - {30431,30586,30540 ,17425,17425,17425 ,0,0,0}, {30431,30587,30588 ,17425,17426,17426 ,0,0,0}, - {30431,30588,30586 ,17425,17426,17425 ,0,0,0}, {30586,30541,30540 ,17425,17425,17425 ,0,0,0}, - {30589,30490,30590 ,726,7626,7754 ,0,0,0}, {30591,30479,30592 ,7626,7627,7626 ,0,0,0}, - {30485,30488,30593 ,7625,7627,7755 ,0,0,0}, {30485,30594,30595 ,7625,17427,7249 ,0,0,0}, - {30595,30596,30467 ,7249,17428,7626 ,0,0,0}, {30467,30596,30468 ,7626,17428,7625 ,0,0,0}, - {30488,30490,30589 ,7627,7626,726 ,0,0,0}, {30597,30598,30469 ,7264,17429,7626 ,0,0,0}, - {30469,30468,30599 ,7626,7625,17430 ,0,0,0}, {30600,30474,30598 ,17431,7625,17429 ,0,0,0}, - {30491,30601,30590 ,7626,7754,7754 ,0,0,0}, {30497,30512,30602 ,7626,7626,7626 ,0,0,0}, - {30472,30603,30475 ,7758,7754,7627 ,0,0,0}, {30479,30478,30592 ,7627,7626,7626 ,0,0,0}, - {30604,30510,30497 ,726,7626,7626 ,0,0,0}, {30516,30514,30605 ,7626,726,7626 ,0,0,0}, - {30605,30506,30606 ,7626,726,726 ,0,0,0}, {30607,30505,30608 ,7628,726,726 ,0,0,0}, - {30609,30518,30516 ,7626,7628,7626 ,0,0,0}, {30523,30607,30527 ,7626,7628,726 ,0,0,0}, - {30610,30526,30611 ,7626,7626,726 ,0,0,0}, {30612,30530,30613 ,7626,726,7626 ,0,0,0}, - {30524,30610,30613 ,726,7626,7626 ,0,0,0}, {30608,30504,30614 ,726,7628,7626 ,0,0,0}, - {30612,30615,30535 ,7626,7626,726 ,0,0,0}, {30609,30614,30520 ,7626,7626,7626 ,0,0,0}, - {30536,30481,30591 ,7626,7626,7626 ,0,0,0}, {30481,30536,30533 ,7626,7626,7626 ,0,0,0}, - {30508,30616,30506 ,726,726,726 ,0,0,0}, {30617,30516,30605 ,726,7626,7626 ,0,0,0}, - {30618,30592,30478 ,8135,7626,7626 ,0,0,0}, {30508,30604,30616 ,726,726,726 ,0,0,0}, - {30475,30618,30478 ,7627,8135,7626 ,0,0,0}, {30619,30496,30602 ,7626,7626,7626 ,0,0,0}, - {30505,30504,30608 ,726,7628,726 ,0,0,0}, {30494,30496,30619 ,7626,7626,7626 ,0,0,0}, - {30474,30600,30472 ,7625,17431,7758 ,0,0,0}, {30620,30491,30494 ,7758,7626,7626 ,0,0,0}, - {30479,30591,30481 ,7627,7626,7626 ,0,0,0}, {30502,30605,30513 ,726,7626,726 ,0,0,0}, - {30475,30603,30621 ,7627,7754,7627 ,0,0,0}, {30621,30618,30475 ,7627,8135,7627 ,0,0,0}, - {30472,30600,30603 ,7758,17431,7754 ,0,0,0}, {30469,30598,30474 ,7626,17429,7625 ,0,0,0}, - {30469,30599,30597 ,7626,17430,7264 ,0,0,0}, {30468,30596,30599 ,7625,17428,17430 ,0,0,0}, - {30485,30595,30467 ,7625,7249,7626 ,0,0,0}, {30485,30593,30594 ,7625,7755,17427 ,0,0,0}, - {30488,30589,30593 ,7627,726,7755 ,0,0,0}, {30491,30590,30490 ,7626,7754,7626 ,0,0,0}, - {30491,30620,30601 ,7626,7758,7754 ,0,0,0}, {30494,30619,30620 ,7626,7626,7758 ,0,0,0}, - {30497,30602,30496 ,7626,7626,7626 ,0,0,0}, {30497,30510,30512 ,7626,7626,7626 ,0,0,0}, - {30604,30508,30510 ,726,726,7626 ,0,0,0}, {30606,30506,30616 ,726,726,726 ,0,0,0}, - {30502,30506,30605 ,726,726,7626 ,0,0,0}, {30514,30513,30605 ,726,726,7626 ,0,0,0}, - {30609,30516,30617 ,7626,7626,726 ,0,0,0}, {30609,30520,30518 ,7626,7626,7628 ,0,0,0}, - {30614,30504,30520 ,7626,7628,7626 ,0,0,0}, {30523,30505,30607 ,7626,726,7628 ,0,0,0}, - {30611,30527,30607 ,726,726,7628 ,0,0,0}, {30610,30524,30526 ,7626,726,7626 ,0,0,0}, - {30611,30526,30527 ,726,7626,726 ,0,0,0}, {30613,30532,30524 ,7626,726,726 ,0,0,0}, - {30530,30612,30535 ,726,7626,726 ,0,0,0}, {30532,30613,30530 ,726,7626,726 ,0,0,0}, - {30535,30615,30533 ,726,7626,7626 ,0,0,0}, {30481,30533,30615 ,7626,7626,7626 ,0,0,0}, - {30606,30622,30605 ,726,7626,7626 ,0,0,0}, {30605,30622,30617 ,7626,7626,726 ,0,0,0}, - {30587,30457,30623 ,17432,17433,17433 ,0,0,0}, {30577,30581,30457 ,17434,17434,17433 ,0,0,0}, - {30457,30581,30623 ,17433,17434,17433 ,0,0,0}, {30587,30623,30588 ,17432,17433,17432 ,0,0,0}, - {30602,30511,30624 ,17435,17436,17437 ,0,0,0}, {30590,30601,30625 ,17438,17439,17440 ,0,0,0}, - {30626,30620,30619 ,17441,17442,17443 ,0,0,0}, {30627,30586,30595 ,17444,17445,17446 ,0,0,0}, - {30628,30629,30593 ,17447,17448,17449 ,0,0,0}, {30630,30598,30631 ,17450,17451,17452 ,0,0,0}, - {30597,30599,30632 ,17453,17454,17455 ,0,0,0}, {30603,30630,30633 ,17456,17450,17457 ,0,0,0}, - {30623,30618,30621 ,17458,17459,17460 ,0,0,0}, {30621,30633,30623 ,17460,17457,17458 ,0,0,0}, - {30618,30634,30592 ,17459,17461,17462 ,0,0,0}, {30634,30618,30623 ,17461,17459,17458 ,0,0,0}, - {30634,30635,30592 ,17461,17463,17462 ,0,0,0}, {30537,30591,30635 ,17416,17464,17463 ,0,0,0}, - {30592,30635,30591 ,17462,17463,17464 ,0,0,0}, {30536,30591,30537 ,126,17464,17416 ,0,0,0}, - {30603,30600,30630 ,17456,17465,17450 ,0,0,0}, {30621,30603,30633 ,17460,17456,17457 ,0,0,0}, - {30598,30597,30631 ,17451,17453,17452 ,0,0,0}, {30600,30598,30630 ,17465,17451,17450 ,0,0,0}, - {30632,30599,30586 ,17455,17454,17445 ,0,0,0}, {30631,30597,30632 ,17452,17453,17455 ,0,0,0}, - {30595,30586,30596 ,17446,17445,17466 ,0,0,0}, {30586,30599,30596 ,17445,17454,17466 ,0,0,0}, - {30629,30627,30594 ,17448,17444,17467 ,0,0,0}, {30627,30595,30594 ,17444,17446,17467 ,0,0,0}, - {30589,30628,30593 ,17468,17447,17449 ,0,0,0}, {30593,30629,30594 ,17449,17448,17467 ,0,0,0}, - {30628,30590,30625 ,17447,17438,17440 ,0,0,0}, {30590,30628,30589 ,17438,17447,17468 ,0,0,0}, - {30601,30620,30539 ,17439,17442,17469 ,0,0,0}, {30601,30539,30625 ,17439,17469,17440 ,0,0,0}, - {30626,30619,30624 ,17441,17443,17437 ,0,0,0}, {30539,30620,30626 ,17469,17442,17441 ,0,0,0}, - {30511,30602,30512 ,17436,17435,17392 ,0,0,0}, {30624,30619,30602 ,17437,17443,17435 ,0,0,0}, - {30534,30581,30528 ,726,726,7658 ,0,0,0}, {30581,30529,30528 ,726,7658,7658 ,0,0,0}, - {30537,30581,30534 ,7918,726,726 ,0,0,0}, {30634,30581,30635 ,7661,726,7918 ,0,0,0}, - {30581,30537,30635 ,726,7918,7918 ,0,0,0}, {30623,30581,30634 ,7658,726,7661 ,0,0,0}, - {30628,30541,30629 ,726,17470,17471 ,0,0,0}, {30629,30541,30627 ,17471,17470,17472 ,0,0,0}, - {30541,30586,30627 ,17470,17470,17472 ,0,0,0}, {30541,30625,30539 ,17470,726,726 ,0,0,0}, - {30541,30628,30625 ,17470,726,726 ,0,0,0}, {30500,30584,30501 ,726,726,726 ,0,0,0}, - {30517,30584,30515 ,726,726,726 ,0,0,0}, {30584,30500,30515 ,726,726,726 ,0,0,0}, - {30503,30584,30519 ,726,726,726 ,0,0,0}, {30584,30517,30519 ,726,726,726 ,0,0,0}, - {30580,30522,30521 ,7660,726,17473 ,0,0,0}, {30503,30522,30580 ,726,726,7660 ,0,0,0}, - {30580,30531,30529 ,7660,17474,726 ,0,0,0}, {30580,30525,30531 ,7660,726,17474 ,0,0,0}, - {30521,30525,30580 ,17473,726,7660 ,0,0,0}, {30623,30633,30588 ,726,726,726 ,0,0,0}, - {30631,30588,30630 ,7659,726,7659 ,0,0,0}, {30633,30630,30588 ,726,7659,726 ,0,0,0}, - {30632,30586,30588 ,726,726,726 ,0,0,0}, {30632,30588,30631 ,726,726,7659 ,0,0,0}, - {30626,30542,30539 ,726,726,726 ,0,0,0}, {30542,30626,30624 ,726,726,726 ,0,0,0}, - {30509,30542,30511 ,726,726,726 ,0,0,0}, {30542,30624,30511 ,726,726,726 ,0,0,0}, - {30501,30542,30507 ,726,726,726 ,0,0,0}, {30542,30509,30507 ,726,726,726 ,0,0,0}, - {30636,30637,30499 ,17475,17476,17477 ,0,0,0}, {30499,30638,30636 ,17477,17478,17475 ,0,0,0}, - {30499,30482,30638 ,17477,17479,17478 ,0,0,0}, {30499,30639,30640 ,17477,17480,17481 ,0,0,0}, - {30637,30639,30499 ,17476,17480,17477 ,0,0,0}, {30499,30641,30642 ,17477,17482,17483 ,0,0,0}, - {30640,30641,30499 ,17481,17482,17477 ,0,0,0}, {30642,30643,30499 ,17483,17484,17477 ,0,0,0}, - {30644,30499,30645 ,17485,17477,17486 ,0,0,0}, {30499,30643,30645 ,17477,17484,17486 ,0,0,0}, - {30646,30499,30647 ,17487,17477,17488 ,0,0,0}, {30499,30644,30647 ,17477,17485,17488 ,0,0,0}, - {30648,30499,30649 ,17489,17477,17490 ,0,0,0}, {30499,30646,30649 ,17477,17487,17490 ,0,0,0}, - {30498,30499,30648 ,17491,17477,17489 ,0,0,0}, {30481,30615,30638 ,17492,17493,17494 ,0,0,0}, - {30640,30639,30610 ,17495,17496,17497 ,0,0,0}, {30637,30636,30612 ,17498,17499,17500 ,0,0,0}, - {30642,30608,30643 ,17501,17502,17503 ,0,0,0}, {30611,30607,30641 ,17504,17505,17506 ,0,0,0}, - {30609,30617,30644 ,17507,17508,17509 ,0,0,0}, {30609,30645,30614 ,17507,17510,17511 ,0,0,0}, - {30622,30606,30646 ,17512,17513,17514 ,0,0,0}, {30646,30647,30622 ,17514,17515,17512 ,0,0,0}, - {30649,30606,30616 ,17516,17513,17517 ,0,0,0}, {30606,30649,30646 ,17513,17516,17514 ,0,0,0}, - {30604,30648,30616 ,17518,17519,17517 ,0,0,0}, {30649,30616,30648 ,17516,17517,17519 ,0,0,0}, - {30604,30497,30498 ,17518,17520,17521 ,0,0,0}, {30498,30648,30604 ,17521,17519,17518 ,0,0,0}, - {30608,30642,30607 ,17502,17501,17505 ,0,0,0}, {30617,30647,30644 ,17508,17515,17509 ,0,0,0}, - {30622,30647,30617 ,17512,17515,17508 ,0,0,0}, {30610,30639,30613 ,17497,17496,17522 ,0,0,0}, - {30614,30645,30643 ,17511,17510,17503 ,0,0,0}, {30609,30644,30645 ,17507,17509,17510 ,0,0,0}, - {30608,30614,30643 ,17502,17511,17503 ,0,0,0}, {30641,30607,30642 ,17506,17505,17501 ,0,0,0}, - {30640,30610,30611 ,17495,17497,17504 ,0,0,0}, {30611,30641,30640 ,17504,17506,17495 ,0,0,0}, - {30636,30615,30612 ,17499,17493,17500 ,0,0,0}, {30613,30637,30612 ,17522,17498,17500 ,0,0,0}, - {30639,30637,30613 ,17496,17498,17522 ,0,0,0}, {30481,30638,30482 ,17492,17494,81 ,0,0,0}, - {30615,30636,30638 ,17493,17499,17494 ,0,0,0}, {30547,30439,30650 ,17523,17310,17524 ,0,0,0}, - {30555,30576,30651 ,17525,17526,17527 ,0,0,0}, {30652,30575,30548 ,17528,17529,17530 ,0,0,0}, - {30653,30585,30559 ,17531,17532,17533 ,0,0,0}, {30654,30655,30558 ,17534,17535,17536 ,0,0,0}, - {30656,30564,30657 ,17537,17538,17539 ,0,0,0}, {30566,30562,30658 ,17540,17541,17542 ,0,0,0}, - {30569,30656,30659 ,17543,17537,17544 ,0,0,0}, {30578,30570,30574 ,17545,17546,17547 ,0,0,0}, - {30574,30659,30578 ,17547,17544,17545 ,0,0,0}, {30570,30660,30571 ,17546,17548,17549 ,0,0,0}, - {30660,30570,30578 ,17548,17546,17545 ,0,0,0}, {30660,30661,30571 ,17548,17550,17549 ,0,0,0}, - {30465,30572,30661 ,17551,17552,17550 ,0,0,0}, {30571,30661,30572 ,17549,17550,17552 ,0,0,0}, - {30464,30572,30465 ,17553,17552,17551 ,0,0,0}, {30569,30565,30656 ,17543,17554,17537 ,0,0,0}, - {30574,30569,30659 ,17547,17543,17544 ,0,0,0}, {30564,30566,30657 ,17538,17540,17539 ,0,0,0}, - {30565,30564,30656 ,17554,17538,17537 ,0,0,0}, {30658,30562,30585 ,17542,17541,17532 ,0,0,0}, - {30657,30566,30658 ,17539,17540,17542 ,0,0,0}, {30559,30585,30563 ,17533,17532,17555 ,0,0,0}, - {30585,30562,30563 ,17532,17541,17555 ,0,0,0}, {30655,30653,30557 ,17535,17531,17556 ,0,0,0}, - {30653,30559,30557 ,17531,17533,17556 ,0,0,0}, {30556,30654,30558 ,17557,17534,17536 ,0,0,0}, - {30558,30655,30557 ,17536,17535,17556 ,0,0,0}, {30654,30555,30651 ,17534,17525,17527 ,0,0,0}, - {30555,30654,30556 ,17525,17534,17557 ,0,0,0}, {30576,30575,30583 ,17526,17529,17558 ,0,0,0}, - {30576,30583,30651 ,17526,17558,17527 ,0,0,0}, {30652,30548,30650 ,17528,17530,17524 ,0,0,0}, - {30583,30575,30652 ,17558,17529,17528 ,0,0,0}, {30439,30547,30440 ,17310,17523,82 ,0,0,0}, - {30650,30548,30547 ,17524,17530,17523 ,0,0,0}, {30582,30654,30651 ,730,17559,730 ,0,0,0}, - {30653,30582,30585 ,730,730,730 ,0,0,0}, {30654,30582,30655 ,17559,730,17559 ,0,0,0}, - {30582,30653,30655 ,730,730,17559 ,0,0,0}, {30651,30583,30582 ,730,17560,730 ,0,0,0}, - {30456,30577,30457 ,7433,17559,7433 ,0,0,0}, {30577,30661,30660 ,17559,17559,17560 ,0,0,0}, - {30577,30456,30462 ,17559,7433,730 ,0,0,0}, {30661,30577,30465 ,17559,17559,17561 ,0,0,0}, - {30577,30462,30465 ,17559,730,17561 ,0,0,0}, {30660,30578,30577 ,17560,7433,17559 ,0,0,0}, - {30443,30540,30428 ,7017,730,730 ,0,0,0}, {30540,30429,30428 ,730,11466,730 ,0,0,0}, - {30447,30540,30445 ,7534,730,17562 ,0,0,0}, {30540,30443,30445 ,730,7017,17562 ,0,0,0}, - {30431,30540,30447 ,17563,730,7534 ,0,0,0}, {30657,30579,30656 ,730,17560,17559 ,0,0,0}, - {30659,30656,30579 ,17559,17559,17560 ,0,0,0}, {30578,30659,30579 ,17561,17559,17560 ,0,0,0}, - {30658,30585,30579 ,17564,730,17560 ,0,0,0}, {30658,30579,30657 ,17564,17560,730 ,0,0,0}, - {30450,30449,30587 ,17561,730,17565 ,0,0,0}, {30431,30450,30587 ,17566,17561,17565 ,0,0,0}, - {30453,30459,30587 ,730,730,17565 ,0,0,0}, {30453,30587,30449 ,730,17565,730 ,0,0,0}, - {30457,30587,30459 ,730,17565,730 ,0,0,0}, {30583,30652,30538 ,730,730,730 ,0,0,0}, - {30538,30650,30439 ,730,730,730 ,0,0,0}, {30538,30652,30650 ,730,730,730 ,0,0,0}, - {30439,30437,30538 ,730,730,730 ,0,0,0}, {30538,30435,30429 ,730,730,730 ,0,0,0}, - {30437,30435,30538 ,730,730,730 ,0,0,0}, {30662,30663,30427 ,17567,17568,17569 ,0,0,0}, - {30427,30664,30662 ,17569,17570,17567 ,0,0,0}, {30427,30411,30664 ,17569,17571,17570 ,0,0,0}, - {30427,30665,30666 ,17569,17572,17573 ,0,0,0}, {30663,30665,30427 ,17568,17572,17569 ,0,0,0}, - {30427,30667,30668 ,17569,17574,17575 ,0,0,0}, {30666,30667,30427 ,17573,17574,17569 ,0,0,0}, - {30668,30669,30427 ,17575,17576,17569 ,0,0,0}, {30670,30427,30671 ,17577,17569,17578 ,0,0,0}, - {30427,30669,30671 ,17569,17576,17578 ,0,0,0}, {30672,30427,30673 ,17579,17569,17580 ,0,0,0}, - {30427,30670,30673 ,17569,17577,17580 ,0,0,0}, {30674,30427,30675 ,17581,17569,17582 ,0,0,0}, - {30427,30672,30675 ,17569,17579,17582 ,0,0,0}, {30426,30427,30674 ,17583,17569,17581 ,0,0,0}, - {140,30573,30664 ,2602,17584,17585 ,0,0,0}, {30666,30665,30560 ,17586,17587,17588 ,0,0,0}, - {30663,30662,30567 ,17589,17590,17591 ,0,0,0}, {30668,30544,30669 ,17592,17593,17594 ,0,0,0}, - {30545,30546,30667 ,17595,17596,17597 ,0,0,0}, {30554,30553,30670 ,17598,17599,17600 ,0,0,0}, - {30554,30671,30543 ,17598,17601,17602 ,0,0,0}, {30552,30551,30672 ,17603,17604,17605 ,0,0,0}, - {30672,30673,30552 ,17605,17606,17603 ,0,0,0}, {30675,30551,30549 ,17607,17604,17608 ,0,0,0}, - {30551,30675,30672 ,17604,17607,17605 ,0,0,0}, {30550,30674,30549 ,17609,17610,17608 ,0,0,0}, - {30675,30549,30674 ,17607,17608,17610 ,0,0,0}, {30550,126,30426 ,17609,17611,17612 ,0,0,0}, - {30426,30674,30550 ,17612,17610,17609 ,0,0,0}, {30544,30668,30546 ,17593,17592,17596 ,0,0,0}, - {30553,30673,30670 ,17599,17606,17600 ,0,0,0}, {30552,30673,30553 ,17603,17606,17599 ,0,0,0}, - {30560,30665,30568 ,17588,17587,17613 ,0,0,0}, {30543,30671,30669 ,17602,17601,17594 ,0,0,0}, - {30554,30670,30671 ,17598,17600,17601 ,0,0,0}, {30544,30543,30669 ,17593,17602,17594 ,0,0,0}, - {30667,30546,30668 ,17597,17596,17592 ,0,0,0}, {30666,30560,30545 ,17586,17588,17595 ,0,0,0}, - {30545,30667,30666 ,17595,17597,17586 ,0,0,0}, {30662,30573,30567 ,17590,17584,17591 ,0,0,0}, - {30568,30663,30567 ,17613,17589,17591 ,0,0,0}, {30665,30663,30568 ,17587,17589,17613 ,0,0,0}, - {140,30664,30411 ,2602,17585,82 ,0,0,0}, {30573,30662,30664 ,17584,17590,17585 ,0,0,0} -// M3abstandhalter20mm.prt - , {30676,30677,30678 ,17614,17615,17616 ,0,0,0}, {30678,30679,30680 ,17616,17617,17618 ,0,0,0}, - {30679,30681,30680 ,17617,17619,17618 ,0,0,0}, {30678,30680,30676 ,17616,17618,17614 ,0,0,0}, - {30682,30683,30684 ,17620,17621,17622 ,0,0,0}, {30684,30683,30681 ,17622,17621,17619 ,0,0,0}, - {30682,30685,30686 ,17620,17623,17624 ,0,0,0}, {30686,30683,30682 ,17624,17621,17620 ,0,0,0}, - {30686,30685,30687 ,17624,17623,17625 ,0,0,0}, {30687,30685,30688 ,17625,17623,17626 ,0,0,0}, - {30688,30689,30690 ,17626,17627,17628 ,0,0,0}, {30687,30688,30690 ,17625,17626,17628 ,0,0,0}, - {30681,30679,30684 ,17619,17617,17622 ,0,0,0}, {30691,30692,30693 ,17629,17629,17630 ,0,0,0}, - {30691,30693,30689 ,17629,17630,17627 ,0,0,0}, {30689,30693,30690 ,17627,17630,17628 ,0,0,0}, - {30676,30694,30677 ,17614,17631,17615 ,0,0,0}, {30695,30694,30696 ,17632,17631,17633 ,0,0,0}, - {30694,30695,30677 ,17631,17632,17615 ,0,0,0}, {30697,30698,30696 ,17634,17635,17633 ,0,0,0}, - {30695,30696,30698 ,17632,17633,17635 ,0,0,0}, {30697,30699,30700 ,17634,17636,17637 ,0,0,0}, - {30700,30698,30697 ,17637,17635,17634 ,0,0,0}, {30701,30699,30702 ,17638,17636,17639 ,0,0,0}, - {30699,30701,30700 ,17636,17638,17637 ,0,0,0}, {30703,30704,30702 ,17640,17641,17639 ,0,0,0}, - {30701,30702,30704 ,17638,17639,17641 ,0,0,0}, {30703,30705,30706 ,17640,17642,17643 ,0,0,0}, - {30706,30704,30703 ,17643,17641,17640 ,0,0,0}, {30707,30705,30708 ,17644,17642,17644 ,0,0,0}, - {30705,30707,30706 ,17642,17644,17643 ,0,0,0}, {30703,30702,30709 ,17645,17646,17647 ,0,0,0}, - {30709,30705,30703 ,17647,17648,17645 ,0,0,0}, {30709,30708,30705 ,17647,17649,17648 ,0,0,0}, - {30709,30699,30697 ,17647,17650,17651 ,0,0,0}, {30702,30699,30709 ,17646,17650,17647 ,0,0,0}, - {30709,30696,30694 ,17647,17652,17653 ,0,0,0}, {30697,30696,30709 ,17651,17652,17647 ,0,0,0}, - {30694,30676,30709 ,17653,17654,17647 ,0,0,0}, {30681,30709,30680 ,17655,17647,17656 ,0,0,0}, - {30709,30676,30680 ,17647,17654,17656 ,0,0,0}, {30686,30709,30683 ,17657,17647,17658 ,0,0,0}, - {30709,30681,30683 ,17647,17655,17658 ,0,0,0}, {30690,30709,30687 ,17659,17647,17660 ,0,0,0}, - {30709,30686,30687 ,17647,17657,17660 ,0,0,0}, {30692,30709,30693 ,17647,17647,17661 ,0,0,0}, - {30709,30690,30693 ,17647,17659,17661 ,0,0,0}, {30710,30711,30712 ,17662,17663,17664 ,0,0,0}, - {30713,30714,30715 ,17665,17665,17666 ,0,0,0}, {30716,30711,30717 ,17667,17663,17668 ,0,0,0}, - {30711,30716,30712 ,17663,17667,17664 ,0,0,0}, {30716,30717,30718 ,17667,17668,17669 ,0,0,0}, - {30719,30720,30718 ,17670,17671,17669 ,0,0,0}, {30718,30717,30719 ,17669,17668,17670 ,0,0,0}, - {30721,30720,30719 ,17629,17671,17670 ,0,0,0}, {30721,30722,30720 ,17629,17629,17671 ,0,0,0}, - {30723,30710,30712 ,17672,17662,17664 ,0,0,0}, {30724,30725,30723 ,17673,17674,17672 ,0,0,0}, - {30710,30723,30725 ,17662,17672,17674 ,0,0,0}, {30726,30727,30725 ,17675,17676,17674 ,0,0,0}, - {30725,30724,30726 ,17674,17673,17675 ,0,0,0}, {30727,30728,30729 ,17676,17677,17678 ,0,0,0}, - {30728,30727,30726 ,17677,17676,17675 ,0,0,0}, {30713,30729,30730 ,17665,17678,17679 ,0,0,0}, - {30728,30730,30729 ,17677,17679,17678 ,0,0,0}, {30731,30732,30733 ,17680,17681,17682 ,0,0,0}, - {30713,30730,30714 ,17665,17679,17665 ,0,0,0}, {30734,30735,30736 ,17683,17684,17685 ,0,0,0}, - {30735,30731,30737 ,17684,17680,17686 ,0,0,0}, {30738,30739,30740 ,17687,17688,17689 ,0,0,0}, - {30741,30742,30739 ,17690,17691,17688 ,0,0,0}, {30743,30744,30745 ,17692,17693,17694 ,0,0,0}, - {30738,30745,30744 ,17687,17694,17693 ,0,0,0}, {30743,30746,30747 ,17692,17644,17644 ,0,0,0}, - {30747,30744,30743 ,17644,17693,17692 ,0,0,0}, {30742,30740,30739 ,17691,17689,17688 ,0,0,0}, - {30738,30740,30745 ,17687,17689,17694 ,0,0,0}, {30741,30735,30734 ,17690,17684,17683 ,0,0,0}, - {30741,30734,30742 ,17690,17683,17691 ,0,0,0}, {30731,30733,30737 ,17680,17682,17686 ,0,0,0}, - {30736,30735,30737 ,17685,17684,17686 ,0,0,0}, {30715,30732,30713 ,17666,17681,17665 ,0,0,0}, - {30733,30732,30715 ,17682,17681,17666 ,0,0,0}, {30748,30749,30750 ,17695,17696,17697 ,0,0,0}, - {30750,30751,30752 ,17697,17698,17699 ,0,0,0}, {30751,30753,30752 ,17698,17700,17699 ,0,0,0}, - {30750,30752,30748 ,17697,17699,17695 ,0,0,0}, {30754,30755,30756 ,17701,17702,17703 ,0,0,0}, - {30756,30755,30753 ,17703,17702,17700 ,0,0,0}, {30754,30757,30758 ,17701,17704,17705 ,0,0,0}, - {30758,30755,30754 ,17705,17702,17701 ,0,0,0}, {30758,30757,30759 ,17705,17704,17706 ,0,0,0}, - {30759,30757,30760 ,17706,17704,17707 ,0,0,0}, {30760,30761,30762 ,17707,17708,17709 ,0,0,0}, - {30759,30760,30762 ,17706,17707,17709 ,0,0,0}, {30753,30751,30756 ,17700,17698,17703 ,0,0,0}, - {30763,30764,30765 ,17629,17629,17710 ,0,0,0}, {30763,30765,30761 ,17629,17710,17708 ,0,0,0}, - {30761,30765,30762 ,17708,17710,17709 ,0,0,0}, {30748,30766,30749 ,17695,17711,17696 ,0,0,0}, - {30767,30766,30768 ,17712,17711,17713 ,0,0,0}, {30766,30767,30749 ,17711,17712,17696 ,0,0,0}, - {30769,30770,30768 ,17714,17715,17713 ,0,0,0}, {30767,30768,30770 ,17712,17713,17715 ,0,0,0}, - {30769,30771,30772 ,17714,17716,17717 ,0,0,0}, {30772,30770,30769 ,17717,17715,17714 ,0,0,0}, - {30773,30771,30774 ,17718,17716,17719 ,0,0,0}, {30771,30773,30772 ,17716,17718,17717 ,0,0,0}, - {30775,30776,30774 ,17720,17721,17719 ,0,0,0}, {30773,30774,30776 ,17718,17719,17721 ,0,0,0}, - {30775,30777,30778 ,17720,17722,17723 ,0,0,0}, {30778,30776,30775 ,17723,17721,17720 ,0,0,0}, - {30779,30777,30780 ,17644,17722,17644 ,0,0,0}, {30777,30779,30778 ,17722,17644,17723 ,0,0,0}, - {30775,30774,30781 ,17724,17725,17726 ,0,0,0}, {30781,30777,30775 ,17726,17727,17724 ,0,0,0}, - {30781,30780,30777 ,17726,17728,17727 ,0,0,0}, {30781,30771,30769 ,17726,17729,17730 ,0,0,0}, - {30774,30771,30781 ,17725,17729,17726 ,0,0,0}, {30781,30768,30766 ,17726,17731,17732 ,0,0,0}, - {30769,30768,30781 ,17730,17731,17726 ,0,0,0}, {30766,30748,30781 ,17732,17733,17726 ,0,0,0}, - {30753,30781,30752 ,17734,17726,17735 ,0,0,0}, {30781,30748,30752 ,17726,17733,17735 ,0,0,0}, - {30758,30781,30755 ,17736,17726,17737 ,0,0,0}, {30781,30753,30755 ,17726,17734,17737 ,0,0,0}, - {30762,30781,30759 ,17738,17726,17739 ,0,0,0}, {30781,30758,30759 ,17726,17736,17739 ,0,0,0}, - {30764,30781,30765 ,17726,17726,17740 ,0,0,0}, {30781,30762,30765 ,17726,17738,17740 ,0,0,0}, - {30782,30783,30784 ,17741,17742,17743 ,0,0,0}, {30785,30786,30787 ,17695,17695,17744 ,0,0,0}, - {30788,30783,30789 ,17745,17742,17746 ,0,0,0}, {30783,30788,30784 ,17742,17745,17743 ,0,0,0}, - {30788,30789,30790 ,17745,17746,17747 ,0,0,0}, {30791,30792,30790 ,17748,17749,17747 ,0,0,0}, - {30790,30789,30791 ,17747,17746,17748 ,0,0,0}, {30793,30792,30791 ,17629,17749,17748 ,0,0,0}, - {30793,30794,30792 ,17629,17629,17749 ,0,0,0}, {30795,30782,30784 ,17750,17741,17743 ,0,0,0}, - {30796,30797,30795 ,17751,17752,17750 ,0,0,0}, {30782,30795,30797 ,17741,17750,17752 ,0,0,0}, - {30798,30799,30797 ,17753,17754,17752 ,0,0,0}, {30797,30796,30798 ,17752,17751,17753 ,0,0,0}, - {30799,30800,30801 ,17754,17755,17756 ,0,0,0}, {30800,30799,30798 ,17755,17754,17753 ,0,0,0}, - {30785,30801,30802 ,17695,17756,17757 ,0,0,0}, {30800,30802,30801 ,17755,17757,17756 ,0,0,0}, - {30803,30804,30805 ,17758,17759,17760 ,0,0,0}, {30785,30802,30786 ,17695,17757,17695 ,0,0,0}, - {30806,30807,30808 ,17761,17762,17763 ,0,0,0}, {30807,30803,30809 ,17762,17758,17764 ,0,0,0}, - {30810,30811,30812 ,17765,17766,17767 ,0,0,0}, {30813,30814,30811 ,17768,17769,17766 ,0,0,0}, - {30815,30816,30817 ,17770,17771,17772 ,0,0,0}, {30810,30817,30816 ,17765,17772,17771 ,0,0,0}, - {30815,30818,30819 ,17770,17644,17644 ,0,0,0}, {30819,30816,30815 ,17644,17771,17770 ,0,0,0}, - {30814,30812,30811 ,17769,17767,17766 ,0,0,0}, {30810,30812,30817 ,17765,17767,17772 ,0,0,0}, - {30813,30807,30806 ,17768,17762,17761 ,0,0,0}, {30813,30806,30814 ,17768,17761,17769 ,0,0,0}, - {30803,30805,30809 ,17758,17760,17764 ,0,0,0}, {30808,30807,30809 ,17763,17762,17764 ,0,0,0}, - {30787,30804,30785 ,17744,17759,17695 ,0,0,0}, {30805,30804,30787 ,17760,17759,17744 ,0,0,0}, - {30820,30711,30821 ,17773,17773,17773 ,0,0,0}, {30822,30823,30711 ,17773,17773,17773 ,0,0,0}, - {30711,30823,30821 ,17773,17773,17773 ,0,0,0}, {30820,30821,30824 ,17773,17773,17773 ,0,0,0}, - {30825,30826,30714 ,730,730,730 ,0,0,0}, {30827,30737,30828 ,730,730,730 ,0,0,0}, - {30829,30707,30722 ,730,730,730 ,0,0,0}, {30830,30704,30706 ,730,730,730 ,0,0,0}, - {30831,30718,30832 ,730,730,730 ,0,0,0}, {30716,30831,30833 ,730,730,730 ,0,0,0}, - {30833,30712,30716 ,730,730,730 ,0,0,0}, {30834,30723,30833 ,730,730,730 ,0,0,0}, - {30718,30831,30716 ,730,730,730 ,0,0,0}, {30720,30707,30832 ,730,730,730 ,0,0,0}, - {30720,30832,30718 ,730,730,730 ,0,0,0}, {30834,30835,30724 ,730,730,730 ,0,0,0}, - {30720,30722,30707 ,730,730,730 ,0,0,0}, {30726,30836,30728 ,730,730,730 ,0,0,0}, - {30724,30835,30726 ,730,730,730 ,0,0,0}, {30837,30700,30701 ,730,730,730 ,0,0,0}, - {30698,30700,30838 ,730,730,730 ,0,0,0}, {30714,30826,30715 ,730,730,730 ,0,0,0}, - {30839,30695,30840 ,730,730,730 ,0,0,0}, {30841,30677,30695 ,730,730,730 ,0,0,0}, - {30733,30715,30828 ,730,730,730 ,0,0,0}, {30842,30843,30827 ,730,730,730 ,0,0,0}, - {30678,30844,30679 ,730,730,730 ,0,0,0}, {30677,30845,30678 ,730,730,730 ,0,0,0}, - {30742,30734,30843 ,730,730,730 ,0,0,0}, {30843,30736,30737 ,730,730,730 ,0,0,0}, - {30684,30846,30847 ,730,730,730 ,0,0,0}, {30846,30679,30848 ,730,730,730 ,0,0,0}, - {30849,30740,30850 ,730,730,730 ,0,0,0}, {30851,30685,30682 ,730,730,730 ,0,0,0}, - {30682,30684,30847 ,730,730,730 ,0,0,0}, {30688,30852,30853 ,730,730,730 ,0,0,0}, - {30691,30746,30743 ,730,730,730 ,0,0,0}, {30689,30854,30691 ,730,730,730 ,0,0,0}, - {30689,30688,30853 ,730,730,730 ,0,0,0}, {30855,30743,30745 ,730,730,730 ,0,0,0}, - {30856,30852,30685 ,730,730,730 ,0,0,0}, {30745,30849,30855 ,730,730,730 ,0,0,0}, - {30836,30825,30730 ,730,730,730 ,0,0,0}, {30701,30704,30857 ,730,730,730 ,0,0,0}, - {30677,30841,30845 ,730,730,730 ,0,0,0}, {30833,30723,30712 ,730,730,730 ,0,0,0}, - {30834,30724,30723 ,730,730,730 ,0,0,0}, {30836,30726,30835 ,730,730,730 ,0,0,0}, - {30836,30730,30728 ,730,730,730 ,0,0,0}, {30825,30714,30730 ,730,730,730 ,0,0,0}, - {30828,30715,30826 ,730,730,730 ,0,0,0}, {30828,30737,30733 ,730,730,730 ,0,0,0}, - {30843,30737,30827 ,730,730,730 ,0,0,0}, {30843,30850,30740 ,730,730,730 ,0,0,0}, - {30740,30742,30843 ,730,730,730 ,0,0,0}, {30849,30745,30740 ,730,730,730 ,0,0,0}, - {30691,30743,30855 ,730,730,730 ,0,0,0}, {30691,30854,30746 ,730,730,730 ,0,0,0}, - {30689,30853,30854 ,730,730,730 ,0,0,0}, {30685,30852,30688 ,730,730,730 ,0,0,0}, - {30685,30851,30856 ,730,730,730 ,0,0,0}, {30682,30847,30851 ,730,730,730 ,0,0,0}, - {30679,30846,30684 ,730,730,730 ,0,0,0}, {30679,30844,30848 ,730,730,730 ,0,0,0}, - {30678,30845,30844 ,730,730,730 ,0,0,0}, {30839,30841,30695 ,730,730,730 ,0,0,0}, - {30698,30840,30695 ,730,730,730 ,0,0,0}, {30700,30837,30838 ,730,730,730 ,0,0,0}, - {30698,30838,30840 ,730,730,730 ,0,0,0}, {30701,30858,30837 ,730,730,730 ,0,0,0}, - {30857,30704,30830 ,730,730,730 ,0,0,0}, {30858,30701,30857 ,730,730,730 ,0,0,0}, - {30830,30706,30829 ,730,730,730 ,0,0,0}, {30707,30829,30706 ,730,730,730 ,0,0,0}, - {30736,30843,30734 ,730,730,730 ,0,0,0}, {30842,30850,30843 ,730,730,730 ,0,0,0}, - {30859,30860,30811 ,17774,17775,17775 ,0,0,0}, {30860,30861,30862 ,17775,17776,17776 ,0,0,0}, - {30862,30811,30860 ,17776,17775,17775 ,0,0,0}, {30811,30863,30859 ,17775,17774,17774 ,0,0,0}, - {30864,30865,30783 ,17777,17778,17778 ,0,0,0}, {30865,30820,30824 ,17778,17777,17777 ,0,0,0}, - {30824,30783,30865 ,17777,17778,17778 ,0,0,0}, {30783,30866,30864 ,17778,17777,17777 ,0,0,0}, - {30785,30861,30867 ,17779,17695,17779 ,0,0,0}, {30864,30866,30867 ,17780,17780,17779 ,0,0,0}, - {30866,30785,30867 ,17780,17779,17779 ,0,0,0}, {30785,30862,30861 ,17779,17781,17695 ,0,0,0}, - {30713,30868,30822 ,17782,17782,17782 ,0,0,0}, {30713,30869,30870 ,17782,17665,17665 ,0,0,0}, - {30713,30870,30868 ,17782,17665,17782 ,0,0,0}, {30868,30823,30822 ,17782,17782,17782 ,0,0,0}, - {30871,30772,30872 ,726,17783,17784 ,0,0,0}, {30873,30761,30874 ,17783,17785,17783 ,0,0,0}, - {30767,30770,30875 ,17786,17785,17787 ,0,0,0}, {30767,30876,30877 ,17786,17788,17789 ,0,0,0}, - {30877,30878,30749 ,17789,17790,17783 ,0,0,0}, {30749,30878,30750 ,17783,17790,17786 ,0,0,0}, - {30770,30772,30871 ,17785,17783,726 ,0,0,0}, {30879,30880,30751 ,17791,17792,17783 ,0,0,0}, - {30751,30750,30881 ,17783,17786,17793 ,0,0,0}, {30882,30756,30880 ,17794,17786,17792 ,0,0,0}, - {30773,30883,30872 ,17783,17784,17784 ,0,0,0}, {30779,30794,30884 ,17783,17783,17783 ,0,0,0}, - {30754,30885,30757 ,17795,17784,17785 ,0,0,0}, {30761,30760,30874 ,17785,17783,17783 ,0,0,0}, - {30886,30792,30779 ,726,17783,17783 ,0,0,0}, {30798,30796,30887 ,17783,726,17783 ,0,0,0}, - {30887,30788,30888 ,17783,726,726 ,0,0,0}, {30889,30787,30890 ,17796,726,726 ,0,0,0}, - {30891,30800,30798 ,17783,17796,17783 ,0,0,0}, {30805,30889,30809 ,17783,17796,726 ,0,0,0}, - {30892,30808,30893 ,17783,17783,726 ,0,0,0}, {30894,30812,30895 ,17783,726,17783 ,0,0,0}, - {30806,30892,30895 ,726,17783,17783 ,0,0,0}, {30890,30786,30896 ,726,17796,17783 ,0,0,0}, - {30894,30897,30817 ,17783,17783,726 ,0,0,0}, {30891,30896,30802 ,17783,17783,17783 ,0,0,0}, - {30818,30763,30873 ,17783,17783,17783 ,0,0,0}, {30763,30818,30815 ,17783,17783,17783 ,0,0,0}, - {30790,30898,30788 ,726,726,726 ,0,0,0}, {30899,30798,30887 ,726,17783,17783 ,0,0,0}, - {30900,30874,30760 ,17797,17783,17783 ,0,0,0}, {30790,30886,30898 ,726,726,726 ,0,0,0}, - {30757,30900,30760 ,17785,17797,17783 ,0,0,0}, {30901,30778,30884 ,17783,17783,17783 ,0,0,0}, - {30787,30786,30890 ,726,17796,726 ,0,0,0}, {30776,30778,30901 ,17783,17783,17783 ,0,0,0}, - {30756,30882,30754 ,17786,17794,17795 ,0,0,0}, {30902,30773,30776 ,17795,17783,17783 ,0,0,0}, - {30761,30873,30763 ,17785,17783,17783 ,0,0,0}, {30784,30887,30795 ,726,17783,726 ,0,0,0}, - {30757,30885,30903 ,17785,17784,17785 ,0,0,0}, {30903,30900,30757 ,17785,17797,17785 ,0,0,0}, - {30754,30882,30885 ,17795,17794,17784 ,0,0,0}, {30751,30880,30756 ,17783,17792,17786 ,0,0,0}, - {30751,30881,30879 ,17783,17793,17791 ,0,0,0}, {30750,30878,30881 ,17786,17790,17793 ,0,0,0}, - {30767,30877,30749 ,17786,17789,17783 ,0,0,0}, {30767,30875,30876 ,17786,17787,17788 ,0,0,0}, - {30770,30871,30875 ,17785,726,17787 ,0,0,0}, {30773,30872,30772 ,17783,17784,17783 ,0,0,0}, - {30773,30902,30883 ,17783,17795,17784 ,0,0,0}, {30776,30901,30902 ,17783,17783,17795 ,0,0,0}, - {30779,30884,30778 ,17783,17783,17783 ,0,0,0}, {30779,30792,30794 ,17783,17783,17783 ,0,0,0}, - {30886,30790,30792 ,726,726,17783 ,0,0,0}, {30888,30788,30898 ,726,726,726 ,0,0,0}, - {30784,30788,30887 ,726,726,17783 ,0,0,0}, {30796,30795,30887 ,726,726,17783 ,0,0,0}, - {30891,30798,30899 ,17783,17783,726 ,0,0,0}, {30891,30802,30800 ,17783,17783,17796 ,0,0,0}, - {30896,30786,30802 ,17783,17796,17783 ,0,0,0}, {30805,30787,30889 ,17783,726,17796 ,0,0,0}, - {30893,30809,30889 ,726,726,17796 ,0,0,0}, {30892,30806,30808 ,17783,726,17783 ,0,0,0}, - {30893,30808,30809 ,726,17783,726 ,0,0,0}, {30895,30814,30806 ,17783,726,726 ,0,0,0}, - {30812,30894,30817 ,726,17783,726 ,0,0,0}, {30814,30895,30812 ,726,17783,726 ,0,0,0}, - {30817,30897,30815 ,726,17783,17783 ,0,0,0}, {30763,30815,30897 ,17783,17783,17783 ,0,0,0}, - {30888,30904,30887 ,726,17783,17783 ,0,0,0}, {30887,30904,30899 ,17783,17783,726 ,0,0,0}, - {30869,30739,30905 ,17798,17799,17799 ,0,0,0}, {30859,30863,30739 ,17800,17800,17799 ,0,0,0}, - {30739,30863,30905 ,17799,17800,17799 ,0,0,0}, {30869,30905,30870 ,17798,17799,17798 ,0,0,0}, - {30884,30793,30906 ,17801,17629,17802 ,0,0,0}, {30872,30883,30907 ,17803,17804,17805 ,0,0,0}, - {30908,30902,30901 ,17806,17807,17808 ,0,0,0}, {30909,30868,30877 ,17809,17810,17811 ,0,0,0}, - {30910,30911,30875 ,17812,17813,17814 ,0,0,0}, {30912,30880,30913 ,17815,17816,17817 ,0,0,0}, - {30879,30881,30914 ,17818,17819,17820 ,0,0,0}, {30885,30912,30915 ,17821,17815,17822 ,0,0,0}, - {30905,30900,30903 ,17823,17824,17825 ,0,0,0}, {30903,30915,30905 ,17825,17822,17823 ,0,0,0}, - {30900,30916,30874 ,17824,17826,17827 ,0,0,0}, {30916,30900,30905 ,17826,17824,17823 ,0,0,0}, - {30916,30917,30874 ,17826,17828,17827 ,0,0,0}, {30819,30873,30917 ,17644,17829,17828 ,0,0,0}, - {30874,30917,30873 ,17827,17828,17829 ,0,0,0}, {30818,30873,30819 ,17644,17829,17644 ,0,0,0}, - {30885,30882,30912 ,17821,17830,17815 ,0,0,0}, {30903,30885,30915 ,17825,17821,17822 ,0,0,0}, - {30880,30879,30913 ,17816,17818,17817 ,0,0,0}, {30882,30880,30912 ,17830,17816,17815 ,0,0,0}, - {30914,30881,30868 ,17820,17819,17810 ,0,0,0}, {30913,30879,30914 ,17817,17818,17820 ,0,0,0}, - {30877,30868,30878 ,17811,17810,17665 ,0,0,0}, {30868,30881,30878 ,17810,17819,17665 ,0,0,0}, - {30911,30909,30876 ,17813,17809,17831 ,0,0,0}, {30909,30877,30876 ,17809,17811,17831 ,0,0,0}, - {30871,30910,30875 ,17832,17812,17814 ,0,0,0}, {30875,30911,30876 ,17814,17813,17831 ,0,0,0}, - {30910,30872,30907 ,17812,17803,17805 ,0,0,0}, {30872,30910,30871 ,17803,17812,17832 ,0,0,0}, - {30883,30902,30821 ,17804,17807,17833 ,0,0,0}, {30883,30821,30907 ,17804,17833,17805 ,0,0,0}, - {30908,30901,30906 ,17806,17808,17802 ,0,0,0}, {30821,30902,30908 ,17833,17807,17806 ,0,0,0}, - {30793,30884,30794 ,17629,17801,17629 ,0,0,0}, {30906,30901,30884 ,17802,17808,17801 ,0,0,0}, - {30816,30863,30810 ,726,726,17834 ,0,0,0}, {30863,30811,30810 ,726,17834,17834 ,0,0,0}, - {30819,30863,30816 ,17835,726,726 ,0,0,0}, {30916,30863,30917 ,17836,726,17835 ,0,0,0}, - {30863,30819,30917 ,726,17835,17835 ,0,0,0}, {30905,30863,30916 ,17834,726,17836 ,0,0,0}, - {30910,30823,30911 ,726,17837,17838 ,0,0,0}, {30911,30823,30909 ,17838,17837,17839 ,0,0,0}, - {30823,30868,30909 ,17837,17837,17839 ,0,0,0}, {30823,30907,30821 ,17837,726,726 ,0,0,0}, - {30823,30910,30907 ,17837,726,726 ,0,0,0}, {30782,30866,30783 ,726,726,726 ,0,0,0}, - {30799,30866,30797 ,726,726,726 ,0,0,0}, {30866,30782,30797 ,726,726,726 ,0,0,0}, - {30785,30866,30801 ,726,726,726 ,0,0,0}, {30866,30799,30801 ,726,726,726 ,0,0,0}, - {30862,30804,30803 ,17840,726,17841 ,0,0,0}, {30785,30804,30862 ,726,726,17840 ,0,0,0}, - {30862,30813,30811 ,17840,17842,726 ,0,0,0}, {30862,30807,30813 ,17840,726,17842 ,0,0,0}, - {30803,30807,30862 ,17841,726,17840 ,0,0,0}, {30905,30915,30870 ,726,726,726 ,0,0,0}, - {30913,30870,30912 ,17843,726,17843 ,0,0,0}, {30915,30912,30870 ,726,17843,726 ,0,0,0}, - {30914,30868,30870 ,726,726,726 ,0,0,0}, {30914,30870,30913 ,726,726,17843 ,0,0,0}, - {30908,30824,30821 ,726,726,726 ,0,0,0}, {30824,30908,30906 ,726,726,726 ,0,0,0}, - {30791,30824,30793 ,726,726,726 ,0,0,0}, {30824,30906,30793 ,726,726,726 ,0,0,0}, - {30783,30824,30789 ,726,726,726 ,0,0,0}, {30824,30791,30789 ,726,726,726 ,0,0,0}, - {30918,30919,30781 ,17844,17845,17728 ,0,0,0}, {30781,30920,30918 ,17728,17846,17844 ,0,0,0}, - {30781,30764,30920 ,17728,17726,17846 ,0,0,0}, {30781,30921,30922 ,17728,17847,17848 ,0,0,0}, - {30919,30921,30781 ,17845,17847,17728 ,0,0,0}, {30781,30923,30924 ,17728,17849,17850 ,0,0,0}, - {30922,30923,30781 ,17848,17849,17728 ,0,0,0}, {30924,30925,30781 ,17850,17851,17728 ,0,0,0}, - {30926,30781,30927 ,17852,17728,17853 ,0,0,0}, {30781,30925,30927 ,17728,17851,17853 ,0,0,0}, - {30928,30781,30929 ,17854,17728,17855 ,0,0,0}, {30781,30926,30929 ,17728,17852,17855 ,0,0,0}, - {30930,30781,30931 ,17856,17728,17857 ,0,0,0}, {30781,30928,30931 ,17728,17854,17857 ,0,0,0}, - {30780,30781,30930 ,17728,17728,17856 ,0,0,0}, {30763,30897,30920 ,17629,17858,17859 ,0,0,0}, - {30922,30921,30892 ,17860,17861,17862 ,0,0,0}, {30919,30918,30894 ,17863,17864,17865 ,0,0,0}, - {30924,30890,30925 ,17866,17867,17868 ,0,0,0}, {30893,30889,30923 ,17869,17870,17871 ,0,0,0}, - {30891,30899,30926 ,17872,17873,17874 ,0,0,0}, {30891,30927,30896 ,17872,17875,17876 ,0,0,0}, - {30904,30888,30928 ,17877,17878,17879 ,0,0,0}, {30928,30929,30904 ,17879,17880,17877 ,0,0,0}, - {30931,30888,30898 ,17881,17878,17882 ,0,0,0}, {30888,30931,30928 ,17878,17881,17879 ,0,0,0}, - {30886,30930,30898 ,17883,17884,17882 ,0,0,0}, {30931,30898,30930 ,17881,17882,17884 ,0,0,0}, - {30886,30779,30780 ,17883,17644,17644 ,0,0,0}, {30780,30930,30886 ,17644,17884,17883 ,0,0,0}, - {30890,30924,30889 ,17867,17866,17870 ,0,0,0}, {30899,30929,30926 ,17873,17880,17874 ,0,0,0}, - {30904,30929,30899 ,17877,17880,17873 ,0,0,0}, {30892,30921,30895 ,17862,17861,17885 ,0,0,0}, - {30896,30927,30925 ,17876,17875,17868 ,0,0,0}, {30891,30926,30927 ,17872,17874,17875 ,0,0,0}, - {30890,30896,30925 ,17867,17876,17868 ,0,0,0}, {30923,30889,30924 ,17871,17870,17866 ,0,0,0}, - {30922,30892,30893 ,17860,17862,17869 ,0,0,0}, {30893,30923,30922 ,17869,17871,17860 ,0,0,0}, - {30918,30897,30894 ,17864,17858,17865 ,0,0,0}, {30895,30919,30894 ,17885,17863,17865 ,0,0,0}, - {30921,30919,30895 ,17861,17863,17885 ,0,0,0}, {30763,30920,30764 ,17629,17859,17629 ,0,0,0}, - {30897,30918,30920 ,17858,17864,17859 ,0,0,0}, {30829,30721,30932 ,17886,17629,17887 ,0,0,0}, - {30837,30858,30933 ,17888,17889,17890 ,0,0,0}, {30934,30857,30830 ,17891,17892,17893 ,0,0,0}, - {30935,30867,30841 ,17894,17895,17896 ,0,0,0}, {30936,30937,30840 ,17897,17898,17899 ,0,0,0}, - {30938,30846,30939 ,17900,17901,17902 ,0,0,0}, {30848,30844,30940 ,17903,17904,17905 ,0,0,0}, - {30851,30938,30941 ,17906,17900,17907 ,0,0,0}, {30860,30852,30856 ,17908,17909,17910 ,0,0,0}, - {30856,30941,30860 ,17910,17907,17908 ,0,0,0}, {30852,30942,30853 ,17909,17911,17912 ,0,0,0}, - {30942,30852,30860 ,17911,17909,17908 ,0,0,0}, {30942,30943,30853 ,17911,17913,17912 ,0,0,0}, - {30747,30854,30943 ,17644,17914,17913 ,0,0,0}, {30853,30943,30854 ,17912,17913,17914 ,0,0,0}, - {30746,30854,30747 ,17644,17914,17644 ,0,0,0}, {30851,30847,30938 ,17906,17915,17900 ,0,0,0}, - {30856,30851,30941 ,17910,17906,17907 ,0,0,0}, {30846,30848,30939 ,17901,17903,17902 ,0,0,0}, - {30847,30846,30938 ,17915,17901,17900 ,0,0,0}, {30940,30844,30867 ,17905,17904,17895 ,0,0,0}, - {30939,30848,30940 ,17902,17903,17905 ,0,0,0}, {30841,30867,30845 ,17896,17895,17695 ,0,0,0}, - {30867,30844,30845 ,17895,17904,17695 ,0,0,0}, {30937,30935,30839 ,17898,17894,17916 ,0,0,0}, - {30935,30841,30839 ,17894,17896,17916 ,0,0,0}, {30838,30936,30840 ,17917,17897,17899 ,0,0,0}, - {30840,30937,30839 ,17899,17898,17916 ,0,0,0}, {30936,30837,30933 ,17897,17888,17890 ,0,0,0}, - {30837,30936,30838 ,17888,17897,17917 ,0,0,0}, {30858,30857,30865 ,17889,17892,17918 ,0,0,0}, - {30858,30865,30933 ,17889,17918,17890 ,0,0,0}, {30934,30830,30932 ,17891,17893,17887 ,0,0,0}, - {30865,30857,30934 ,17918,17892,17891 ,0,0,0}, {30721,30829,30722 ,17629,17886,17629 ,0,0,0}, - {30932,30830,30829 ,17887,17893,17886 ,0,0,0}, {30864,30936,30933 ,730,17919,730 ,0,0,0}, - {30935,30864,30867 ,730,730,730 ,0,0,0}, {30936,30864,30937 ,17919,730,17919 ,0,0,0}, - {30864,30935,30937 ,730,730,17919 ,0,0,0}, {30933,30865,30864 ,730,17920,730 ,0,0,0}, - {30738,30859,30739 ,17921,17919,17921 ,0,0,0}, {30859,30943,30942 ,17919,17919,17920 ,0,0,0}, - {30859,30738,30744 ,17919,17921,730 ,0,0,0}, {30943,30859,30747 ,17919,17919,17922 ,0,0,0}, - {30859,30744,30747 ,17919,730,17922 ,0,0,0}, {30942,30860,30859 ,17920,17921,17919 ,0,0,0}, - {30725,30822,30710 ,17923,730,730 ,0,0,0}, {30822,30711,30710 ,730,17924,730 ,0,0,0}, - {30729,30822,30727 ,17925,730,17926 ,0,0,0}, {30822,30725,30727 ,730,17923,17926 ,0,0,0}, - {30713,30822,30729 ,17927,730,17925 ,0,0,0}, {30939,30861,30938 ,730,17920,17919 ,0,0,0}, - {30941,30938,30861 ,17919,17919,17920 ,0,0,0}, {30860,30941,30861 ,17922,17919,17920 ,0,0,0}, - {30940,30867,30861 ,17928,730,17920 ,0,0,0}, {30940,30861,30939 ,17928,17920,730 ,0,0,0}, - {30732,30731,30869 ,17922,730,17929 ,0,0,0}, {30713,30732,30869 ,17930,17922,17929 ,0,0,0}, - {30735,30741,30869 ,730,730,17929 ,0,0,0}, {30735,30869,30731 ,730,17929,730 ,0,0,0}, - {30739,30869,30741 ,730,17929,730 ,0,0,0}, {30865,30934,30820 ,730,730,730 ,0,0,0}, - {30820,30932,30721 ,730,730,730 ,0,0,0}, {30820,30934,30932 ,730,730,730 ,0,0,0}, - {30721,30719,30820 ,730,730,730 ,0,0,0}, {30820,30717,30711 ,730,730,730 ,0,0,0}, - {30719,30717,30820 ,730,730,730 ,0,0,0}, {30944,30945,30709 ,17931,17932,17649 ,0,0,0}, - {30709,30946,30944 ,17649,17933,17931 ,0,0,0}, {30709,30692,30946 ,17649,17647,17933 ,0,0,0}, - {30709,30947,30948 ,17649,17934,17935 ,0,0,0}, {30945,30947,30709 ,17932,17934,17649 ,0,0,0}, - {30709,30949,30950 ,17649,17936,17937 ,0,0,0}, {30948,30949,30709 ,17935,17936,17649 ,0,0,0}, - {30950,30951,30709 ,17937,17938,17649 ,0,0,0}, {30952,30709,30953 ,17939,17649,17940 ,0,0,0}, - {30709,30951,30953 ,17649,17938,17940 ,0,0,0}, {30954,30709,30955 ,17941,17649,17942 ,0,0,0}, - {30709,30952,30955 ,17649,17939,17942 ,0,0,0}, {30956,30709,30957 ,17943,17649,17944 ,0,0,0}, - {30709,30954,30957 ,17649,17941,17944 ,0,0,0}, {30708,30709,30956 ,17649,17649,17943 ,0,0,0}, - {30691,30855,30946 ,17629,17945,17946 ,0,0,0}, {30948,30947,30842 ,17947,17948,17949 ,0,0,0}, - {30945,30944,30849 ,17950,17951,17952 ,0,0,0}, {30950,30826,30951 ,17953,17954,17955 ,0,0,0}, - {30827,30828,30949 ,17956,17957,17958 ,0,0,0}, {30836,30835,30952 ,17959,17960,17961 ,0,0,0}, - {30836,30953,30825 ,17959,17962,17963 ,0,0,0}, {30834,30833,30954 ,17964,17965,17966 ,0,0,0}, - {30954,30955,30834 ,17966,17967,17964 ,0,0,0}, {30957,30833,30831 ,17968,17965,17969 ,0,0,0}, - {30833,30957,30954 ,17965,17968,17966 ,0,0,0}, {30832,30956,30831 ,17970,17971,17969 ,0,0,0}, - {30957,30831,30956 ,17968,17969,17971 ,0,0,0}, {30832,30707,30708 ,17970,17644,17644 ,0,0,0}, - {30708,30956,30832 ,17644,17971,17970 ,0,0,0}, {30826,30950,30828 ,17954,17953,17957 ,0,0,0}, - {30835,30955,30952 ,17960,17967,17961 ,0,0,0}, {30834,30955,30835 ,17964,17967,17960 ,0,0,0}, - {30842,30947,30850 ,17949,17948,17972 ,0,0,0}, {30825,30953,30951 ,17963,17962,17955 ,0,0,0}, - {30836,30952,30953 ,17959,17961,17962 ,0,0,0}, {30826,30825,30951 ,17954,17963,17955 ,0,0,0}, - {30949,30828,30950 ,17958,17957,17953 ,0,0,0}, {30948,30842,30827 ,17947,17949,17956 ,0,0,0}, - {30827,30949,30948 ,17956,17958,17947 ,0,0,0}, {30944,30855,30849 ,17951,17945,17952 ,0,0,0}, - {30850,30945,30849 ,17972,17950,17952 ,0,0,0}, {30947,30945,30850 ,17948,17950,17972 ,0,0,0}, - {30691,30946,30692 ,17629,17946,17629 ,0,0,0}, {30855,30944,30946 ,17945,17951,17946 ,0,0,0} -// M3abstandhalter20mm.prt - , {30958,30959,30960 ,17973,17974,17975 ,0,0,0}, {30960,30961,30962 ,17975,17976,17977 ,0,0,0}, - {30961,30963,30962 ,17976,17978,17977 ,0,0,0}, {30960,30962,30958 ,17975,17977,17973 ,0,0,0}, - {30964,30965,30966 ,17979,17980,17981 ,0,0,0}, {30966,30965,30963 ,17981,17980,17978 ,0,0,0}, - {30964,30967,30968 ,17979,17982,17983 ,0,0,0}, {30968,30965,30964 ,17983,17980,17979 ,0,0,0}, - {30968,30967,30969 ,17983,17982,17984 ,0,0,0}, {30969,30967,30970 ,17984,17982,17985 ,0,0,0}, - {30970,30971,30972 ,17985,17986,17987 ,0,0,0}, {30969,30970,30972 ,17984,17985,17987 ,0,0,0}, - {30963,30961,30966 ,17978,17976,17981 ,0,0,0}, {228,30973,30974 ,7498,126,17988 ,0,0,0}, - {228,30974,30971 ,7498,17988,17986 ,0,0,0}, {30971,30974,30972 ,17986,17988,17987 ,0,0,0}, - {30958,30975,30959 ,17973,17989,17974 ,0,0,0}, {30976,30975,30977 ,17990,17989,17991 ,0,0,0}, - {30975,30976,30959 ,17989,17990,17974 ,0,0,0}, {30978,30979,30977 ,17992,17993,17991 ,0,0,0}, - {30976,30977,30979 ,17990,17991,17993 ,0,0,0}, {30978,30980,30981 ,17992,17994,17995 ,0,0,0}, - {30981,30979,30978 ,17995,17993,17992 ,0,0,0}, {30982,30980,30983 ,17996,17994,17997 ,0,0,0}, - {30980,30982,30981 ,17994,17996,17995 ,0,0,0}, {30984,30985,30983 ,17998,17999,17997 ,0,0,0}, - {30982,30983,30985 ,17996,17997,17999 ,0,0,0}, {30984,30986,30987 ,17998,18000,18001 ,0,0,0}, - {30987,30985,30984 ,18001,17999,17998 ,0,0,0}, {242,30986,30988 ,18002,18000,18003 ,0,0,0}, - {30986,242,30987 ,18000,18002,18001 ,0,0,0}, {30984,30983,30989 ,18004,18005,18006 ,0,0,0}, - {30989,30986,30984 ,18006,18007,18004 ,0,0,0}, {30989,30988,30986 ,18006,18008,18007 ,0,0,0}, - {30989,30980,30978 ,18006,18009,18010 ,0,0,0}, {30983,30980,30989 ,18005,18009,18006 ,0,0,0}, - {30989,30977,30975 ,18006,18011,18012 ,0,0,0}, {30978,30977,30989 ,18010,18011,18006 ,0,0,0}, - {30975,30958,30989 ,18012,18013,18006 ,0,0,0}, {30963,30989,30962 ,18014,18006,18015 ,0,0,0}, - {30989,30958,30962 ,18006,18013,18015 ,0,0,0}, {30968,30989,30965 ,18016,18006,18017 ,0,0,0}, - {30989,30963,30965 ,18006,18014,18017 ,0,0,0}, {30972,30989,30969 ,18018,18006,18019 ,0,0,0}, - {30989,30968,30969 ,18006,18016,18019 ,0,0,0}, {30973,30989,30974 ,18020,18006,18021 ,0,0,0}, - {30989,30972,30974 ,18006,18018,18021 ,0,0,0}, {30990,30991,30992 ,18022,18023,17547 ,0,0,0}, - {30993,30994,30995 ,21,7309,17533 ,0,0,0}, {30996,30991,30997 ,17546,18023,18024 ,0,0,0}, - {30991,30996,30992 ,18023,17546,17547 ,0,0,0}, {30996,30997,30998 ,17546,18024,17549 ,0,0,0}, - {30999,31000,30998 ,18025,17552,17549 ,0,0,0}, {30998,30997,30999 ,17549,18024,18025 ,0,0,0}, - {31001,31000,30999 ,18026,17552,18025 ,0,0,0}, {31001,31002,31000 ,18026,126,17552 ,0,0,0}, - {31003,30990,30992 ,17543,18022,17547 ,0,0,0}, {31004,31005,31003 ,17554,18027,17543 ,0,0,0}, - {30990,31003,31005 ,18022,17543,18027 ,0,0,0}, {31006,31007,31005 ,17538,18028,18027 ,0,0,0}, - {31005,31004,31006 ,18027,17554,17538 ,0,0,0}, {31007,31008,31009 ,18028,17540,18029 ,0,0,0}, - {31008,31007,31006 ,17540,18028,17538 ,0,0,0}, {30993,31009,31010 ,21,18029,17541 ,0,0,0}, - {31008,31010,31009 ,17540,17541,18029 ,0,0,0}, {31011,31012,31013 ,18030,18031,17556 ,0,0,0}, - {30993,31010,30994 ,21,17541,7309 ,0,0,0}, {31014,31015,31016 ,17525,18032,17557 ,0,0,0}, - {31015,31011,31017 ,18032,18030,17536 ,0,0,0}, {31018,31019,31020 ,18033,18034,17529 ,0,0,0}, - {31021,31022,31019 ,18035,17526,18034 ,0,0,0}, {31023,31024,31025 ,17523,18036,17530 ,0,0,0}, - {31018,31025,31024 ,18033,17530,18036 ,0,0,0}, {31023,31026,31027 ,17523,18037,18038 ,0,0,0}, - {31027,31024,31023 ,18038,18036,17523 ,0,0,0}, {31022,31020,31019 ,17526,17529,18034 ,0,0,0}, - {31018,31020,31025 ,18033,17529,17530 ,0,0,0}, {31021,31015,31014 ,18035,18032,17525 ,0,0,0}, - {31021,31014,31022 ,18035,17525,17526 ,0,0,0}, {31011,31013,31017 ,18030,17556,17536 ,0,0,0}, - {31016,31015,31017 ,17557,18032,17536 ,0,0,0}, {30995,31012,30993 ,17533,18031,21 ,0,0,0}, - {31013,31012,30995 ,17556,18031,17533 ,0,0,0}, {31028,31029,31030 ,324,18039,18040 ,0,0,0}, - {31030,31031,31032 ,18040,18041,18042 ,0,0,0}, {31031,31033,31032 ,18041,18043,18042 ,0,0,0}, - {31030,31032,31028 ,18040,18042,324 ,0,0,0}, {31034,31035,31036 ,18044,18045,18046 ,0,0,0}, - {31036,31035,31033 ,18046,18045,18043 ,0,0,0}, {31034,31037,31038 ,18044,18047,18048 ,0,0,0}, - {31038,31035,31034 ,18048,18045,18044 ,0,0,0}, {31038,31037,31039 ,18048,18047,18049 ,0,0,0}, - {31039,31037,31040 ,18049,18047,18050 ,0,0,0}, {31040,31041,31042 ,18050,18051,18052 ,0,0,0}, - {31039,31040,31042 ,18049,18050,18052 ,0,0,0}, {31033,31031,31036 ,18043,18041,18046 ,0,0,0}, - {31043,31044,31045 ,18053,126,18054 ,0,0,0}, {31043,31045,31041 ,18053,18054,18051 ,0,0,0}, - {31041,31045,31042 ,18051,18054,18052 ,0,0,0}, {31028,31046,31029 ,324,18055,18039 ,0,0,0}, - {31047,31046,31048 ,18056,18055,18057 ,0,0,0}, {31046,31047,31029 ,18055,18056,18039 ,0,0,0}, - {31049,31050,31048 ,18058,18059,18057 ,0,0,0}, {31047,31048,31050 ,18056,18057,18059 ,0,0,0}, - {31049,31051,31052 ,18058,18060,18061 ,0,0,0}, {31052,31050,31049 ,18061,18059,18058 ,0,0,0}, - {31053,31051,31054 ,18062,18060,18063 ,0,0,0}, {31051,31053,31052 ,18060,18062,18061 ,0,0,0}, - {31055,31056,31054 ,18064,18065,18063 ,0,0,0}, {31053,31054,31056 ,18062,18063,18065 ,0,0,0}, - {31055,31057,31058 ,18064,18066,18067 ,0,0,0}, {31058,31056,31055 ,18067,18065,18064 ,0,0,0}, - {31059,31057,31060 ,82,18066,18068 ,0,0,0}, {31057,31059,31058 ,18066,82,18067 ,0,0,0}, - {31055,31054,31061 ,18069,18070,18071 ,0,0,0}, {31061,31057,31055 ,18071,18072,18069 ,0,0,0}, - {31061,31060,31057 ,18071,18073,18072 ,0,0,0}, {31061,31051,31049 ,18071,18074,18075 ,0,0,0}, - {31054,31051,31061 ,18070,18074,18071 ,0,0,0}, {31061,31048,31046 ,18071,18076,18077 ,0,0,0}, - {31049,31048,31061 ,18075,18076,18071 ,0,0,0}, {31046,31028,31061 ,18077,18078,18071 ,0,0,0}, - {31033,31061,31032 ,18079,18071,18080 ,0,0,0}, {31061,31028,31032 ,18071,18078,18080 ,0,0,0}, - {31038,31061,31035 ,18081,18071,18082 ,0,0,0}, {31061,31033,31035 ,18071,18079,18082 ,0,0,0}, - {31042,31061,31039 ,18083,18071,18084 ,0,0,0}, {31061,31038,31039 ,18071,18081,18084 ,0,0,0}, - {31044,31061,31045 ,18085,18071,18086 ,0,0,0}, {31061,31042,31045 ,18071,18083,18086 ,0,0,0}, - {31062,31063,31064 ,18087,18088,17460 ,0,0,0}, {31065,31066,31067 ,324,17303,17446 ,0,0,0}, - {31068,31063,31069 ,17459,18088,18089 ,0,0,0}, {31063,31068,31064 ,18088,17459,17460 ,0,0,0}, - {31068,31069,31070 ,17459,18089,17462 ,0,0,0}, {31071,31072,31070 ,18090,17464,17462 ,0,0,0}, - {31070,31069,31071 ,17462,18089,18090 ,0,0,0}, {31073,31072,31071 ,18091,17464,18090 ,0,0,0}, - {31073,31074,31072 ,18091,18092,17464 ,0,0,0}, {31075,31062,31064 ,17456,18087,17460 ,0,0,0}, - {31076,31077,31075 ,17465,18093,17456 ,0,0,0}, {31062,31075,31077 ,18087,17456,18093 ,0,0,0}, - {31078,31079,31077 ,17451,18094,18093 ,0,0,0}, {31077,31076,31078 ,18093,17465,17451 ,0,0,0}, - {31079,31080,31081 ,18094,17453,18095 ,0,0,0}, {31080,31079,31078 ,17453,18094,17451 ,0,0,0}, - {31065,31081,31082 ,324,18095,17454 ,0,0,0}, {31080,31082,31081 ,17453,17454,18095 ,0,0,0}, - {31083,31084,31085 ,18096,18097,17467 ,0,0,0}, {31065,31082,31066 ,324,17454,17303 ,0,0,0}, - {31086,31087,31088 ,17438,18098,17468 ,0,0,0}, {31087,31083,31089 ,18098,18096,17449 ,0,0,0}, - {31090,31091,31092 ,18099,18100,17442 ,0,0,0}, {31093,31094,31091 ,18101,17439,18100 ,0,0,0}, - {31095,31096,31097 ,17435,18102,17443 ,0,0,0}, {31090,31097,31096 ,18099,17443,18102 ,0,0,0}, - {31095,31098,31099 ,17435,82,18103 ,0,0,0}, {31099,31096,31095 ,18103,18102,17435 ,0,0,0}, - {31094,31092,31091 ,17439,17442,18100 ,0,0,0}, {31090,31092,31097 ,18099,17442,17443 ,0,0,0}, - {31093,31087,31086 ,18101,18098,17438 ,0,0,0}, {31093,31086,31094 ,18101,17438,17439 ,0,0,0}, - {31083,31085,31089 ,18096,17467,17449 ,0,0,0}, {31088,31087,31089 ,17468,18098,17449 ,0,0,0}, - {31067,31084,31065 ,17446,18097,324 ,0,0,0}, {31085,31084,31067 ,17467,18097,17446 ,0,0,0}, - {31100,30991,31101 ,18104,18104,18104 ,0,0,0}, {31102,31103,30991 ,18104,18104,18104 ,0,0,0}, - {30991,31103,31101 ,18104,18104,18104 ,0,0,0}, {31100,31101,31104 ,18104,18104,18104 ,0,0,0}, - {31105,31106,30994 ,730,730,730 ,0,0,0}, {31107,31017,31108 ,730,730,730 ,0,0,0}, - {31109,242,31002 ,730,730,730 ,0,0,0}, {31110,30985,30987 ,730,730,730 ,0,0,0}, - {31111,30998,31112 ,730,730,730 ,0,0,0}, {30996,31111,31113 ,730,730,730 ,0,0,0}, - {31113,30992,30996 ,730,730,730 ,0,0,0}, {31114,31003,31113 ,730,730,730 ,0,0,0}, - {30998,31111,30996 ,730,730,730 ,0,0,0}, {31000,242,31112 ,730,730,730 ,0,0,0}, - {31000,31112,30998 ,730,730,730 ,0,0,0}, {31114,31115,31004 ,730,730,730 ,0,0,0}, - {31000,31002,242 ,730,730,730 ,0,0,0}, {31006,31116,31008 ,730,730,730 ,0,0,0}, - {31004,31115,31006 ,730,730,730 ,0,0,0}, {31117,30981,30982 ,730,730,730 ,0,0,0}, - {30979,30981,31118 ,730,730,730 ,0,0,0}, {30994,31106,30995 ,730,730,730 ,0,0,0}, - {31119,30976,31120 ,730,730,730 ,0,0,0}, {31121,30959,30976 ,730,730,730 ,0,0,0}, - {31013,30995,31108 ,730,730,730 ,0,0,0}, {31122,31123,31107 ,730,730,730 ,0,0,0}, - {30960,31124,30961 ,730,730,730 ,0,0,0}, {30959,31125,30960 ,730,730,730 ,0,0,0}, - {31022,31014,31123 ,730,730,730 ,0,0,0}, {31123,31016,31017 ,730,730,730 ,0,0,0}, - {30966,31126,31127 ,730,730,730 ,0,0,0}, {31126,30961,31128 ,730,730,730 ,0,0,0}, - {31129,31020,31130 ,730,730,730 ,0,0,0}, {31131,30967,30964 ,730,730,730 ,0,0,0}, - {30964,30966,31127 ,730,730,730 ,0,0,0}, {30970,31132,31133 ,730,730,730 ,0,0,0}, - {228,31026,31023 ,730,730,730 ,0,0,0}, {30971,31134,228 ,730,730,730 ,0,0,0}, - {30971,30970,31133 ,730,730,730 ,0,0,0}, {31135,31023,31025 ,730,730,730 ,0,0,0}, - {31136,31132,30967 ,730,730,730 ,0,0,0}, {31025,31129,31135 ,730,730,730 ,0,0,0}, - {31116,31105,31010 ,730,730,730 ,0,0,0}, {30982,30985,31137 ,730,730,730 ,0,0,0}, - {30959,31121,31125 ,730,730,730 ,0,0,0}, {31113,31003,30992 ,730,730,730 ,0,0,0}, - {31114,31004,31003 ,730,730,730 ,0,0,0}, {31116,31006,31115 ,730,730,730 ,0,0,0}, - {31116,31010,31008 ,730,730,730 ,0,0,0}, {31105,30994,31010 ,730,730,730 ,0,0,0}, - {31108,30995,31106 ,730,730,730 ,0,0,0}, {31108,31017,31013 ,730,730,730 ,0,0,0}, - {31123,31017,31107 ,730,730,730 ,0,0,0}, {31123,31130,31020 ,730,730,730 ,0,0,0}, - {31020,31022,31123 ,730,730,730 ,0,0,0}, {31129,31025,31020 ,730,730,730 ,0,0,0}, - {228,31023,31135 ,730,730,730 ,0,0,0}, {228,31134,31026 ,730,730,730 ,0,0,0}, - {30971,31133,31134 ,730,730,730 ,0,0,0}, {30967,31132,30970 ,730,730,730 ,0,0,0}, - {30967,31131,31136 ,730,730,730 ,0,0,0}, {30964,31127,31131 ,730,730,730 ,0,0,0}, - {30961,31126,30966 ,730,730,730 ,0,0,0}, {30961,31124,31128 ,730,730,730 ,0,0,0}, - {30960,31125,31124 ,730,730,730 ,0,0,0}, {31119,31121,30976 ,730,730,730 ,0,0,0}, - {30979,31120,30976 ,730,730,730 ,0,0,0}, {30981,31117,31118 ,730,730,730 ,0,0,0}, - {30979,31118,31120 ,730,730,730 ,0,0,0}, {30982,31138,31117 ,730,730,730 ,0,0,0}, - {31137,30985,31110 ,730,730,730 ,0,0,0}, {31138,30982,31137 ,730,730,730 ,0,0,0}, - {31110,30987,31109 ,730,730,730 ,0,0,0}, {242,31109,30987 ,730,730,730 ,0,0,0}, - {31016,31123,31014 ,730,730,730 ,0,0,0}, {31122,31130,31123 ,730,730,730 ,0,0,0}, - {31139,31140,31091 ,18105,18106,18106 ,0,0,0}, {31140,31141,31142 ,18106,1433,1433 ,0,0,0}, - {31142,31091,31140 ,1433,18106,18106 ,0,0,0}, {31091,31143,31139 ,18106,18105,18105 ,0,0,0}, - {31144,31145,31063 ,2162,18107,18107 ,0,0,0}, {31145,31100,31104 ,18107,2162,2162 ,0,0,0}, - {31104,31063,31145 ,2162,18107,18107 ,0,0,0}, {31063,31146,31144 ,18107,2162,2162 ,0,0,0}, - {31065,31141,31147 ,18108,1077,18109 ,0,0,0}, {31144,31146,31147 ,18110,18110,18109 ,0,0,0}, - {31146,31065,31147 ,18110,18108,18109 ,0,0,0}, {31065,31142,31141 ,18108,18111,1077 ,0,0,0}, - {30993,31148,31102 ,18112,18112,18112 ,0,0,0}, {30993,31149,31150 ,18112,18113,18113 ,0,0,0}, - {30993,31150,31148 ,18112,18113,18112 ,0,0,0}, {31148,31103,31102 ,18112,18112,18112 ,0,0,0}, - {31151,31052,31152 ,726,7628,8135 ,0,0,0}, {31153,31041,31154 ,7628,7625,7628 ,0,0,0}, - {31047,31050,31155 ,7627,7625,7761 ,0,0,0}, {31047,31156,31157 ,7627,18114,7253 ,0,0,0}, - {31157,31158,31029 ,7253,18115,7628 ,0,0,0}, {31029,31158,31030 ,7628,18115,7627 ,0,0,0}, - {31050,31052,31151 ,7625,7628,726 ,0,0,0}, {31159,31160,31031 ,8017,18116,7628 ,0,0,0}, - {31031,31030,31161 ,7628,7627,18117 ,0,0,0}, {31162,31036,31160 ,7756,7627,18116 ,0,0,0}, - {31053,31163,31152 ,7628,8135,8135 ,0,0,0}, {31059,31074,31164 ,7628,7628,7628 ,0,0,0}, - {31034,31165,31037 ,7880,8135,7625 ,0,0,0}, {31041,31040,31154 ,7625,7628,7628 ,0,0,0}, - {31166,31072,31059 ,726,7628,7628 ,0,0,0}, {31078,31076,31167 ,7628,726,7628 ,0,0,0}, - {31167,31068,31168 ,7628,726,726 ,0,0,0}, {31169,31067,31170 ,7626,726,726 ,0,0,0}, - {31171,31080,31078 ,7628,7626,7628 ,0,0,0}, {31085,31169,31089 ,7628,7626,726 ,0,0,0}, - {31172,31088,31173 ,7628,7628,726 ,0,0,0}, {31174,31092,31175 ,7628,726,7628 ,0,0,0}, - {31086,31172,31175 ,726,7628,7628 ,0,0,0}, {31170,31066,31176 ,726,7626,7628 ,0,0,0}, - {31174,31177,31097 ,7628,7628,726 ,0,0,0}, {31171,31176,31082 ,7628,7628,7628 ,0,0,0}, - {31098,31043,31153 ,7628,7628,7628 ,0,0,0}, {31043,31098,31095 ,7628,7628,7628 ,0,0,0}, - {31070,31178,31068 ,726,726,726 ,0,0,0}, {31179,31078,31167 ,726,7628,7628 ,0,0,0}, - {31180,31154,31040 ,7754,7628,7628 ,0,0,0}, {31070,31166,31178 ,726,726,726 ,0,0,0}, - {31037,31180,31040 ,7625,7754,7628 ,0,0,0}, {31181,31058,31164 ,7628,7628,7628 ,0,0,0}, - {31067,31066,31170 ,726,7626,726 ,0,0,0}, {31056,31058,31181 ,7628,7628,7628 ,0,0,0}, - {31036,31162,31034 ,7627,7756,7880 ,0,0,0}, {31182,31053,31056 ,7880,7628,7628 ,0,0,0}, - {31041,31153,31043 ,7625,7628,7628 ,0,0,0}, {31064,31167,31075 ,726,7628,726 ,0,0,0}, - {31037,31165,31183 ,7625,8135,7625 ,0,0,0}, {31183,31180,31037 ,7625,7754,7625 ,0,0,0}, - {31034,31162,31165 ,7880,7756,8135 ,0,0,0}, {31031,31160,31036 ,7628,18116,7627 ,0,0,0}, - {31031,31161,31159 ,7628,18117,8017 ,0,0,0}, {31030,31158,31161 ,7627,18115,18117 ,0,0,0}, - {31047,31157,31029 ,7627,7253,7628 ,0,0,0}, {31047,31155,31156 ,7627,7761,18114 ,0,0,0}, - {31050,31151,31155 ,7625,726,7761 ,0,0,0}, {31053,31152,31052 ,7628,8135,7628 ,0,0,0}, - {31053,31182,31163 ,7628,7880,8135 ,0,0,0}, {31056,31181,31182 ,7628,7628,7880 ,0,0,0}, - {31059,31164,31058 ,7628,7628,7628 ,0,0,0}, {31059,31072,31074 ,7628,7628,7628 ,0,0,0}, - {31166,31070,31072 ,726,726,7628 ,0,0,0}, {31168,31068,31178 ,726,726,726 ,0,0,0}, - {31064,31068,31167 ,726,726,7628 ,0,0,0}, {31076,31075,31167 ,726,726,7628 ,0,0,0}, - {31171,31078,31179 ,7628,7628,726 ,0,0,0}, {31171,31082,31080 ,7628,7628,7626 ,0,0,0}, - {31176,31066,31082 ,7628,7626,7628 ,0,0,0}, {31085,31067,31169 ,7628,726,7626 ,0,0,0}, - {31173,31089,31169 ,726,726,7626 ,0,0,0}, {31172,31086,31088 ,7628,726,7628 ,0,0,0}, - {31173,31088,31089 ,726,7628,726 ,0,0,0}, {31175,31094,31086 ,7628,726,726 ,0,0,0}, - {31092,31174,31097 ,726,7628,726 ,0,0,0}, {31094,31175,31092 ,726,7628,726 ,0,0,0}, - {31097,31177,31095 ,726,7628,7628 ,0,0,0}, {31043,31095,31177 ,7628,7628,7628 ,0,0,0}, - {31168,31184,31167 ,726,7628,7628 ,0,0,0}, {31167,31184,31179 ,7628,7628,726 ,0,0,0}, - {31149,31019,31185 ,18118,18119,18119 ,0,0,0}, {31139,31143,31019 ,18120,18120,18119 ,0,0,0}, - {31019,31143,31185 ,18119,18120,18119 ,0,0,0}, {31149,31185,31150 ,18118,18119,18118 ,0,0,0}, - {31164,31073,31186 ,17413,18121,18122 ,0,0,0}, {31152,31163,31187 ,17404,17412,18123 ,0,0,0}, - {31188,31182,31181 ,18124,17410,17415 ,0,0,0}, {31189,31148,31157 ,18125,18126,17385 ,0,0,0}, - {31190,31191,31155 ,18127,18128,17407 ,0,0,0}, {31192,31160,31193 ,18129,17396,18130 ,0,0,0}, - {31159,31161,31194 ,17398,17400,18131 ,0,0,0}, {31165,31192,31195 ,17393,18129,18132 ,0,0,0}, - {31185,31180,31183 ,18133,17386,17384 ,0,0,0}, {31183,31195,31185 ,17384,18132,18133 ,0,0,0}, - {31180,31196,31154 ,17386,18134,17388 ,0,0,0}, {31196,31180,31185 ,18134,17386,18133 ,0,0,0}, - {31196,31197,31154 ,18134,18135,17388 ,0,0,0}, {31099,31153,31197 ,18103,17390,18135 ,0,0,0}, - {31154,31197,31153 ,17388,18135,17390 ,0,0,0}, {31098,31153,31099 ,82,17390,18103 ,0,0,0}, - {31165,31162,31192 ,17393,17394,18129 ,0,0,0}, {31183,31165,31195 ,17384,17393,18132 ,0,0,0}, - {31160,31159,31193 ,17396,17398,18130 ,0,0,0}, {31162,31160,31192 ,17394,17396,18129 ,0,0,0}, - {31194,31161,31148 ,18131,17400,18126 ,0,0,0}, {31193,31159,31194 ,18130,17398,18131 ,0,0,0}, - {31157,31148,31158 ,17385,18126,18136 ,0,0,0}, {31148,31161,31158 ,18126,17400,18136 ,0,0,0}, - {31191,31189,31156 ,18128,18125,17403 ,0,0,0}, {31189,31157,31156 ,18125,17385,17403 ,0,0,0}, - {31151,31190,31155 ,17406,18127,17407 ,0,0,0}, {31155,31191,31156 ,17407,18128,17403 ,0,0,0}, - {31190,31152,31187 ,18127,17404,18123 ,0,0,0}, {31152,31190,31151 ,17404,18127,17406 ,0,0,0}, - {31163,31182,31101 ,17412,17410,18137 ,0,0,0}, {31163,31101,31187 ,17412,18137,18123 ,0,0,0}, - {31188,31181,31186 ,18124,17415,18122 ,0,0,0}, {31101,31182,31188 ,18137,17410,18124 ,0,0,0}, - {31073,31164,31074 ,18121,17413,18092 ,0,0,0}, {31186,31181,31164 ,18122,17415,17413 ,0,0,0}, - {31096,31143,31090 ,726,726,7661 ,0,0,0}, {31143,31091,31090 ,726,7661,7661 ,0,0,0}, - {31099,31143,31096 ,18138,726,726 ,0,0,0}, {31196,31143,31197 ,7658,726,18138 ,0,0,0}, - {31143,31099,31197 ,726,18138,18138 ,0,0,0}, {31185,31143,31196 ,7661,726,7658 ,0,0,0}, - {31190,31103,31191 ,726,17471,17470 ,0,0,0}, {31191,31103,31189 ,17470,17471,18139 ,0,0,0}, - {31103,31148,31189 ,17471,17471,18139 ,0,0,0}, {31103,31187,31101 ,17471,726,726 ,0,0,0}, - {31103,31190,31187 ,17471,726,726 ,0,0,0}, {31062,31146,31063 ,726,726,726 ,0,0,0}, - {31079,31146,31077 ,726,726,726 ,0,0,0}, {31146,31062,31077 ,726,726,726 ,0,0,0}, - {31065,31146,31081 ,726,726,726 ,0,0,0}, {31146,31079,31081 ,726,726,726 ,0,0,0}, - {31142,31084,31083 ,7659,726,18140 ,0,0,0}, {31065,31084,31142 ,726,726,7659 ,0,0,0}, - {31142,31093,31091 ,7659,18141,726 ,0,0,0}, {31142,31087,31093 ,7659,726,18141 ,0,0,0}, - {31083,31087,31142 ,18140,726,7659 ,0,0,0}, {31185,31195,31150 ,726,726,726 ,0,0,0}, - {31193,31150,31192 ,7660,726,7660 ,0,0,0}, {31195,31192,31150 ,726,7660,726 ,0,0,0}, - {31194,31148,31150 ,726,726,726 ,0,0,0}, {31194,31150,31193 ,726,726,7660 ,0,0,0}, - {31188,31104,31101 ,726,726,726 ,0,0,0}, {31104,31188,31186 ,726,726,726 ,0,0,0}, - {31071,31104,31073 ,726,726,726 ,0,0,0}, {31104,31186,31073 ,726,726,726 ,0,0,0}, - {31063,31104,31069 ,726,726,726 ,0,0,0}, {31104,31071,31069 ,726,726,726 ,0,0,0}, - {31198,31199,31061 ,18142,18143,18144 ,0,0,0}, {31061,31200,31198 ,18144,18145,18142 ,0,0,0}, - {31061,31044,31200 ,18144,18146,18145 ,0,0,0}, {31061,31201,31202 ,18144,18147,18148 ,0,0,0}, - {31199,31201,31061 ,18143,18147,18144 ,0,0,0}, {31061,31203,31204 ,18144,18149,18150 ,0,0,0}, - {31202,31203,31061 ,18148,18149,18144 ,0,0,0}, {31204,31205,31061 ,18150,18151,18144 ,0,0,0}, - {31206,31061,31207 ,18152,18144,18153 ,0,0,0}, {31061,31205,31207 ,18144,18151,18153 ,0,0,0}, - {31208,31061,31209 ,18154,18144,18155 ,0,0,0}, {31061,31206,31209 ,18144,18152,18155 ,0,0,0}, - {31210,31061,31211 ,18156,18144,18157 ,0,0,0}, {31061,31208,31211 ,18144,18154,18157 ,0,0,0}, - {31060,31061,31210 ,18158,18144,18156 ,0,0,0}, {31043,31177,31200 ,18159,18160,18161 ,0,0,0}, - {31202,31201,31172 ,18162,18163,18164 ,0,0,0}, {31199,31198,31174 ,18165,18166,18167 ,0,0,0}, - {31204,31170,31205 ,18168,18169,18170 ,0,0,0}, {31173,31169,31203 ,18171,18172,18173 ,0,0,0}, - {31171,31179,31206 ,18174,18175,18176 ,0,0,0}, {31171,31207,31176 ,18174,18177,18178 ,0,0,0}, - {31184,31168,31208 ,18179,18180,18181 ,0,0,0}, {31208,31209,31184 ,18181,18182,18179 ,0,0,0}, - {31211,31168,31178 ,18183,18180,18184 ,0,0,0}, {31168,31211,31208 ,18180,18183,18181 ,0,0,0}, - {31166,31210,31178 ,18185,18186,18184 ,0,0,0}, {31211,31178,31210 ,18183,18184,18186 ,0,0,0}, - {31166,31059,31060 ,18185,18187,18188 ,0,0,0}, {31060,31210,31166 ,18188,18186,18185 ,0,0,0}, - {31170,31204,31169 ,18169,18168,18172 ,0,0,0}, {31179,31209,31206 ,18175,18182,18176 ,0,0,0}, - {31184,31209,31179 ,18179,18182,18175 ,0,0,0}, {31172,31201,31175 ,18164,18163,18189 ,0,0,0}, - {31176,31207,31205 ,18178,18177,18170 ,0,0,0}, {31171,31206,31207 ,18174,18176,18177 ,0,0,0}, - {31170,31176,31205 ,18169,18178,18170 ,0,0,0}, {31203,31169,31204 ,18173,18172,18168 ,0,0,0}, - {31202,31172,31173 ,18162,18164,18171 ,0,0,0}, {31173,31203,31202 ,18171,18173,18162 ,0,0,0}, - {31198,31177,31174 ,18166,18160,18167 ,0,0,0}, {31175,31199,31174 ,18189,18165,18167 ,0,0,0}, - {31201,31199,31175 ,18163,18165,18189 ,0,0,0}, {31043,31200,31044 ,18159,18161,35 ,0,0,0}, - {31177,31198,31200 ,18160,18166,18161 ,0,0,0}, {31109,31001,31212 ,17331,18026,18190 ,0,0,0}, - {31117,31138,31213 ,17322,17330,18191 ,0,0,0}, {31214,31137,31110 ,18192,17328,17333 ,0,0,0}, - {31215,31147,31121 ,18193,18194,17304 ,0,0,0}, {31216,31217,31120 ,18195,18196,17325 ,0,0,0}, - {31218,31126,31219 ,18197,17314,18198 ,0,0,0}, {31128,31124,31220 ,17316,17318,18199 ,0,0,0}, - {31131,31218,31221 ,17311,18197,18200 ,0,0,0}, {31140,31132,31136 ,18201,17305,17302 ,0,0,0}, - {31136,31221,31140 ,17302,18200,18201 ,0,0,0}, {31132,31222,31133 ,17305,18202,17307 ,0,0,0}, - {31222,31132,31140 ,18202,17305,18201 ,0,0,0}, {31222,31223,31133 ,18202,18203,17307 ,0,0,0}, - {31027,31134,31223 ,18204,17309,18203 ,0,0,0}, {31133,31223,31134 ,17307,18203,17309 ,0,0,0}, - {31026,31134,31027 ,18205,17309,18204 ,0,0,0}, {31131,31127,31218 ,17311,17312,18197 ,0,0,0}, - {31136,31131,31221 ,17302,17311,18200 ,0,0,0}, {31126,31128,31219 ,17314,17316,18198 ,0,0,0}, - {31127,31126,31218 ,17312,17314,18197 ,0,0,0}, {31220,31124,31147 ,18199,17318,18194 ,0,0,0}, - {31219,31128,31220 ,18198,17316,18199 ,0,0,0}, {31121,31147,31125 ,17304,18194,10001 ,0,0,0}, - {31147,31124,31125 ,18194,17318,10001 ,0,0,0}, {31217,31215,31119 ,18196,18193,17321 ,0,0,0}, - {31215,31121,31119 ,18193,17304,17321 ,0,0,0}, {31118,31216,31120 ,17324,18195,17325 ,0,0,0}, - {31120,31217,31119 ,17325,18196,17321 ,0,0,0}, {31216,31117,31213 ,18195,17322,18191 ,0,0,0}, - {31117,31216,31118 ,17322,18195,17324 ,0,0,0}, {31138,31137,31145 ,17330,17328,18206 ,0,0,0}, - {31138,31145,31213 ,17330,18206,18191 ,0,0,0}, {31214,31110,31212 ,18192,17333,18190 ,0,0,0}, - {31145,31137,31214 ,18206,17328,18192 ,0,0,0}, {31001,31109,31002 ,18026,17331,126 ,0,0,0}, - {31212,31110,31109 ,18190,17333,17331 ,0,0,0}, {31144,31216,31213 ,730,17561,730 ,0,0,0}, - {31215,31144,31147 ,730,730,730 ,0,0,0}, {31216,31144,31217 ,17561,730,17561 ,0,0,0}, - {31144,31215,31217 ,730,730,17561 ,0,0,0}, {31213,31145,31144 ,730,7433,730 ,0,0,0}, - {31018,31139,31019 ,7376,17561,7376 ,0,0,0}, {31139,31223,31222 ,17561,17561,7433 ,0,0,0}, - {31139,31018,31024 ,17561,7376,730 ,0,0,0}, {31223,31139,31027 ,17561,17561,18207 ,0,0,0}, - {31139,31024,31027 ,17561,730,18207 ,0,0,0}, {31222,31140,31139 ,7433,7376,17561 ,0,0,0}, - {31005,31102,30990 ,7015,730,730 ,0,0,0}, {31102,30991,30990 ,730,11465,730 ,0,0,0}, - {31009,31102,31007 ,7532,730,7016 ,0,0,0}, {31102,31005,31007 ,730,7015,7016 ,0,0,0}, - {30993,31102,31009 ,18208,730,7532 ,0,0,0}, {31219,31141,31218 ,730,7433,17561 ,0,0,0}, - {31221,31218,31141 ,17561,17561,7433 ,0,0,0}, {31140,31221,31141 ,18207,17561,7433 ,0,0,0}, - {31220,31147,31141 ,18209,730,7433 ,0,0,0}, {31220,31141,31219 ,18209,7433,730 ,0,0,0}, - {31012,31011,31149 ,18207,730,9877 ,0,0,0}, {30993,31012,31149 ,18210,18207,9877 ,0,0,0}, - {31015,31021,31149 ,730,730,9877 ,0,0,0}, {31015,31149,31011 ,730,9877,730 ,0,0,0}, - {31019,31149,31021 ,730,9877,730 ,0,0,0}, {31145,31214,31100 ,730,730,730 ,0,0,0}, - {31100,31212,31001 ,730,730,730 ,0,0,0}, {31100,31214,31212 ,730,730,730 ,0,0,0}, - {31001,30999,31100 ,730,730,730 ,0,0,0}, {31100,30997,30991 ,730,730,730 ,0,0,0}, - {30999,30997,31100 ,730,730,730 ,0,0,0}, {31224,31225,30989 ,18211,18212,18213 ,0,0,0}, - {30989,31226,31224 ,18213,18214,18211 ,0,0,0}, {30989,30973,31226 ,18213,18215,18214 ,0,0,0}, - {30989,31227,31228 ,18213,18216,18217 ,0,0,0}, {31225,31227,30989 ,18212,18216,18213 ,0,0,0}, - {30989,31229,31230 ,18213,18218,18219 ,0,0,0}, {31228,31229,30989 ,18217,18218,18213 ,0,0,0}, - {31230,31231,30989 ,18219,18220,18213 ,0,0,0}, {31232,30989,31233 ,18221,18213,18222 ,0,0,0}, - {30989,31231,31233 ,18213,18220,18222 ,0,0,0}, {31234,30989,31235 ,18223,18213,18224 ,0,0,0}, - {30989,31232,31235 ,18213,18221,18224 ,0,0,0}, {31236,30989,31237 ,18225,18213,18226 ,0,0,0}, - {30989,31234,31237 ,18213,18223,18226 ,0,0,0}, {30988,30989,31236 ,18227,18213,18225 ,0,0,0}, - {228,31135,31226 ,3345,18228,18229 ,0,0,0}, {31228,31227,31122 ,18230,18231,18232 ,0,0,0}, - {31225,31224,31129 ,18233,18234,18235 ,0,0,0}, {31230,31106,31231 ,18236,18237,18238 ,0,0,0}, - {31107,31108,31229 ,18239,18240,18241 ,0,0,0}, {31116,31115,31232 ,18242,18243,18244 ,0,0,0}, - {31116,31233,31105 ,18242,18245,18246 ,0,0,0}, {31114,31113,31234 ,18247,18248,18249 ,0,0,0}, - {31234,31235,31114 ,18249,18250,18247 ,0,0,0}, {31237,31113,31111 ,18251,18248,18252 ,0,0,0}, - {31113,31237,31234 ,18248,18251,18249 ,0,0,0}, {31112,31236,31111 ,18253,18254,18252 ,0,0,0}, - {31237,31111,31236 ,18251,18252,18254 ,0,0,0}, {31112,242,30988 ,18253,18255,18256 ,0,0,0}, - {30988,31236,31112 ,18256,18254,18253 ,0,0,0}, {31106,31230,31108 ,18237,18236,18240 ,0,0,0}, - {31115,31235,31232 ,18243,18250,18244 ,0,0,0}, {31114,31235,31115 ,18247,18250,18243 ,0,0,0}, - {31122,31227,31130 ,18232,18231,18257 ,0,0,0}, {31105,31233,31231 ,18246,18245,18238 ,0,0,0}, - {31116,31232,31233 ,18242,18244,18245 ,0,0,0}, {31106,31105,31231 ,18237,18246,18238 ,0,0,0}, - {31229,31108,31230 ,18241,18240,18236 ,0,0,0}, {31228,31122,31107 ,18230,18232,18239 ,0,0,0}, - {31107,31229,31228 ,18239,18241,18230 ,0,0,0}, {31224,31135,31129 ,18234,18228,18235 ,0,0,0}, - {31130,31225,31129 ,18257,18233,18235 ,0,0,0}, {31227,31225,31130 ,18231,18233,18257 ,0,0,0}, - {228,31226,30973 ,3345,18229,126 ,0,0,0}, {31135,31224,31226 ,18228,18234,18229 ,0,0,0} -// M3abstandhalter20mm.prt - , {31238,31239,31240 ,17973,17974,17975 ,0,0,0}, {31240,31241,31242 ,17975,17976,17977 ,0,0,0}, - {31241,31243,31242 ,17976,17978,17977 ,0,0,0}, {31240,31242,31238 ,17975,17977,17973 ,0,0,0}, - {31244,31245,31246 ,17979,17980,17981 ,0,0,0}, {31246,31245,31243 ,17981,17980,17978 ,0,0,0}, - {31244,31247,31248 ,17979,17982,17983 ,0,0,0}, {31248,31245,31244 ,17983,17980,17979 ,0,0,0}, - {31248,31247,31249 ,17983,17982,17984 ,0,0,0}, {31249,31247,31250 ,17984,17982,17985 ,0,0,0}, - {31250,31251,31252 ,17985,17986,17987 ,0,0,0}, {31249,31250,31252 ,17984,17985,17987 ,0,0,0}, - {31243,31241,31246 ,17978,17976,17981 ,0,0,0}, {160,31253,31254 ,7498,126,17988 ,0,0,0}, - {160,31254,31251 ,7498,17988,17986 ,0,0,0}, {31251,31254,31252 ,17986,17988,17987 ,0,0,0}, - {31238,31255,31239 ,17973,17989,17974 ,0,0,0}, {31256,31255,31257 ,17990,17989,17991 ,0,0,0}, - {31255,31256,31239 ,17989,17990,17974 ,0,0,0}, {31258,31259,31257 ,17992,17993,17991 ,0,0,0}, - {31256,31257,31259 ,17990,17991,17993 ,0,0,0}, {31258,31260,31261 ,17992,17994,17995 ,0,0,0}, - {31261,31259,31258 ,17995,17993,17992 ,0,0,0}, {31262,31260,31263 ,17996,17994,17997 ,0,0,0}, - {31260,31262,31261 ,17994,17996,17995 ,0,0,0}, {31264,31265,31263 ,17998,17999,17997 ,0,0,0}, - {31262,31263,31265 ,17996,17997,17999 ,0,0,0}, {31264,31266,31267 ,17998,18000,18001 ,0,0,0}, - {31267,31265,31264 ,18001,17999,17998 ,0,0,0}, {174,31266,31268 ,18002,18000,18003 ,0,0,0}, - {31266,174,31267 ,18000,18002,18001 ,0,0,0}, {31264,31263,31269 ,18004,18005,18006 ,0,0,0}, - {31269,31266,31264 ,18006,18007,18004 ,0,0,0}, {31269,31268,31266 ,18006,18008,18007 ,0,0,0}, - {31269,31260,31258 ,18006,18009,18010 ,0,0,0}, {31263,31260,31269 ,18005,18009,18006 ,0,0,0}, - {31269,31257,31255 ,18006,18011,18012 ,0,0,0}, {31258,31257,31269 ,18010,18011,18006 ,0,0,0}, - {31255,31238,31269 ,18012,18013,18006 ,0,0,0}, {31243,31269,31242 ,18014,18006,18015 ,0,0,0}, - {31269,31238,31242 ,18006,18013,18015 ,0,0,0}, {31248,31269,31245 ,18016,18006,18017 ,0,0,0}, - {31269,31243,31245 ,18006,18014,18017 ,0,0,0}, {31252,31269,31249 ,18018,18006,18019 ,0,0,0}, - {31269,31248,31249 ,18006,18016,18019 ,0,0,0}, {31253,31269,31254 ,18020,18006,18021 ,0,0,0}, - {31269,31252,31254 ,18006,18018,18021 ,0,0,0}, {31270,31271,31272 ,18022,18023,17547 ,0,0,0}, - {31273,31274,31275 ,21,7309,17533 ,0,0,0}, {31276,31271,31277 ,17546,18023,18024 ,0,0,0}, - {31271,31276,31272 ,18023,17546,17547 ,0,0,0}, {31276,31277,31278 ,17546,18024,17549 ,0,0,0}, - {31279,31280,31278 ,18025,17552,17549 ,0,0,0}, {31278,31277,31279 ,17549,18024,18025 ,0,0,0}, - {31281,31280,31279 ,18026,17552,18025 ,0,0,0}, {31281,31282,31280 ,18026,126,17552 ,0,0,0}, - {31283,31270,31272 ,17543,18022,17547 ,0,0,0}, {31284,31285,31283 ,17554,18027,17543 ,0,0,0}, - {31270,31283,31285 ,18022,17543,18027 ,0,0,0}, {31286,31287,31285 ,17538,18028,18027 ,0,0,0}, - {31285,31284,31286 ,18027,17554,17538 ,0,0,0}, {31287,31288,31289 ,18028,17540,18029 ,0,0,0}, - {31288,31287,31286 ,17540,18028,17538 ,0,0,0}, {31273,31289,31290 ,21,18029,17541 ,0,0,0}, - {31288,31290,31289 ,17540,17541,18029 ,0,0,0}, {31291,31292,31293 ,18030,18031,17556 ,0,0,0}, - {31273,31290,31274 ,21,17541,7309 ,0,0,0}, {31294,31295,31296 ,17525,18032,17557 ,0,0,0}, - {31295,31291,31297 ,18032,18030,17536 ,0,0,0}, {31298,31299,31300 ,18033,18034,17529 ,0,0,0}, - {31301,31302,31299 ,18035,17526,18034 ,0,0,0}, {31303,31304,31305 ,17523,18036,17530 ,0,0,0}, - {31298,31305,31304 ,18033,17530,18036 ,0,0,0}, {31303,31306,31307 ,17523,18037,18038 ,0,0,0}, - {31307,31304,31303 ,18038,18036,17523 ,0,0,0}, {31302,31300,31299 ,17526,17529,18034 ,0,0,0}, - {31298,31300,31305 ,18033,17529,17530 ,0,0,0}, {31301,31295,31294 ,18035,18032,17525 ,0,0,0}, - {31301,31294,31302 ,18035,17525,17526 ,0,0,0}, {31291,31293,31297 ,18030,17556,17536 ,0,0,0}, - {31296,31295,31297 ,17557,18032,17536 ,0,0,0}, {31275,31292,31273 ,17533,18031,21 ,0,0,0}, - {31293,31292,31275 ,17556,18031,17533 ,0,0,0}, {31308,31309,31310 ,324,18039,18040 ,0,0,0}, - {31310,31311,31312 ,18040,18041,18042 ,0,0,0}, {31311,31313,31312 ,18041,18043,18042 ,0,0,0}, - {31310,31312,31308 ,18040,18042,324 ,0,0,0}, {31314,31315,31316 ,18044,18045,18046 ,0,0,0}, - {31316,31315,31313 ,18046,18045,18043 ,0,0,0}, {31314,31317,31318 ,18044,18047,18048 ,0,0,0}, - {31318,31315,31314 ,18048,18045,18044 ,0,0,0}, {31318,31317,31319 ,18048,18047,18049 ,0,0,0}, - {31319,31317,31320 ,18049,18047,18050 ,0,0,0}, {31320,31321,31322 ,18050,18051,18052 ,0,0,0}, - {31319,31320,31322 ,18049,18050,18052 ,0,0,0}, {31313,31311,31316 ,18043,18041,18046 ,0,0,0}, - {31323,31324,31325 ,18053,126,18054 ,0,0,0}, {31323,31325,31321 ,18053,18054,18051 ,0,0,0}, - {31321,31325,31322 ,18051,18054,18052 ,0,0,0}, {31308,31326,31309 ,324,18055,18039 ,0,0,0}, - {31327,31326,31328 ,18056,18055,18057 ,0,0,0}, {31326,31327,31309 ,18055,18056,18039 ,0,0,0}, - {31329,31330,31328 ,18058,18059,18057 ,0,0,0}, {31327,31328,31330 ,18056,18057,18059 ,0,0,0}, - {31329,31331,31332 ,18058,18060,18061 ,0,0,0}, {31332,31330,31329 ,18061,18059,18058 ,0,0,0}, - {31333,31331,31334 ,18062,18060,18063 ,0,0,0}, {31331,31333,31332 ,18060,18062,18061 ,0,0,0}, - {31335,31336,31334 ,18064,18065,18063 ,0,0,0}, {31333,31334,31336 ,18062,18063,18065 ,0,0,0}, - {31335,31337,31338 ,18064,18066,18067 ,0,0,0}, {31338,31336,31335 ,18067,18065,18064 ,0,0,0}, - {31339,31337,31340 ,82,18066,18068 ,0,0,0}, {31337,31339,31338 ,18066,82,18067 ,0,0,0}, - {31335,31334,31341 ,18069,18070,18071 ,0,0,0}, {31341,31337,31335 ,18071,18072,18069 ,0,0,0}, - {31341,31340,31337 ,18071,18073,18072 ,0,0,0}, {31341,31331,31329 ,18071,18074,18075 ,0,0,0}, - {31334,31331,31341 ,18070,18074,18071 ,0,0,0}, {31341,31328,31326 ,18071,18076,18077 ,0,0,0}, - {31329,31328,31341 ,18075,18076,18071 ,0,0,0}, {31326,31308,31341 ,18077,18078,18071 ,0,0,0}, - {31313,31341,31312 ,18079,18071,18080 ,0,0,0}, {31341,31308,31312 ,18071,18078,18080 ,0,0,0}, - {31318,31341,31315 ,18081,18071,18082 ,0,0,0}, {31341,31313,31315 ,18071,18079,18082 ,0,0,0}, - {31322,31341,31319 ,18083,18071,18084 ,0,0,0}, {31341,31318,31319 ,18071,18081,18084 ,0,0,0}, - {31324,31341,31325 ,18085,18071,18086 ,0,0,0}, {31341,31322,31325 ,18071,18083,18086 ,0,0,0}, - {31342,31343,31344 ,18087,18088,17460 ,0,0,0}, {31345,31346,31347 ,324,17303,17446 ,0,0,0}, - {31348,31343,31349 ,17459,18088,18089 ,0,0,0}, {31343,31348,31344 ,18088,17459,17460 ,0,0,0}, - {31348,31349,31350 ,17459,18089,17462 ,0,0,0}, {31351,31352,31350 ,18090,17464,17462 ,0,0,0}, - {31350,31349,31351 ,17462,18089,18090 ,0,0,0}, {31353,31352,31351 ,18091,17464,18090 ,0,0,0}, - {31353,31354,31352 ,18091,18092,17464 ,0,0,0}, {31355,31342,31344 ,17456,18087,17460 ,0,0,0}, - {31356,31357,31355 ,17465,18093,17456 ,0,0,0}, {31342,31355,31357 ,18087,17456,18093 ,0,0,0}, - {31358,31359,31357 ,17451,18094,18093 ,0,0,0}, {31357,31356,31358 ,18093,17465,17451 ,0,0,0}, - {31359,31360,31361 ,18094,17453,18095 ,0,0,0}, {31360,31359,31358 ,17453,18094,17451 ,0,0,0}, - {31345,31361,31362 ,324,18095,17454 ,0,0,0}, {31360,31362,31361 ,17453,17454,18095 ,0,0,0}, - {31363,31364,31365 ,18096,18097,17467 ,0,0,0}, {31345,31362,31346 ,324,17454,17303 ,0,0,0}, - {31366,31367,31368 ,17438,18098,17468 ,0,0,0}, {31367,31363,31369 ,18098,18096,17449 ,0,0,0}, - {31370,31371,31372 ,18099,18100,17442 ,0,0,0}, {31373,31374,31371 ,18101,17439,18100 ,0,0,0}, - {31375,31376,31377 ,17435,18102,17443 ,0,0,0}, {31370,31377,31376 ,18099,17443,18102 ,0,0,0}, - {31375,31378,31379 ,17435,82,18103 ,0,0,0}, {31379,31376,31375 ,18103,18102,17435 ,0,0,0}, - {31374,31372,31371 ,17439,17442,18100 ,0,0,0}, {31370,31372,31377 ,18099,17442,17443 ,0,0,0}, - {31373,31367,31366 ,18101,18098,17438 ,0,0,0}, {31373,31366,31374 ,18101,17438,17439 ,0,0,0}, - {31363,31365,31369 ,18096,17467,17449 ,0,0,0}, {31368,31367,31369 ,17468,18098,17449 ,0,0,0}, - {31347,31364,31345 ,17446,18097,324 ,0,0,0}, {31365,31364,31347 ,17467,18097,17446 ,0,0,0}, - {31380,31271,31381 ,18104,18104,18104 ,0,0,0}, {31382,31383,31271 ,18104,18104,18104 ,0,0,0}, - {31271,31383,31381 ,18104,18104,18104 ,0,0,0}, {31380,31381,31384 ,18104,18104,18104 ,0,0,0}, - {31385,31386,31274 ,730,730,730 ,0,0,0}, {31387,31297,31388 ,730,730,730 ,0,0,0}, - {31389,174,31282 ,730,730,730 ,0,0,0}, {31390,31265,31267 ,730,730,730 ,0,0,0}, - {31391,31278,31392 ,730,730,730 ,0,0,0}, {31276,31391,31393 ,730,730,730 ,0,0,0}, - {31393,31272,31276 ,730,730,730 ,0,0,0}, {31394,31283,31393 ,730,730,730 ,0,0,0}, - {31278,31391,31276 ,730,730,730 ,0,0,0}, {31280,174,31392 ,730,730,730 ,0,0,0}, - {31280,31392,31278 ,730,730,730 ,0,0,0}, {31394,31395,31284 ,730,730,730 ,0,0,0}, - {31280,31282,174 ,730,730,730 ,0,0,0}, {31286,31396,31288 ,730,730,730 ,0,0,0}, - {31284,31395,31286 ,730,730,730 ,0,0,0}, {31397,31261,31262 ,730,730,730 ,0,0,0}, - {31259,31261,31398 ,730,730,730 ,0,0,0}, {31274,31386,31275 ,730,730,730 ,0,0,0}, - {31399,31256,31400 ,730,730,730 ,0,0,0}, {31401,31239,31256 ,730,730,730 ,0,0,0}, - {31293,31275,31388 ,730,730,730 ,0,0,0}, {31402,31403,31387 ,730,730,730 ,0,0,0}, - {31240,31404,31241 ,730,730,730 ,0,0,0}, {31239,31405,31240 ,730,730,730 ,0,0,0}, - {31302,31294,31403 ,730,730,730 ,0,0,0}, {31403,31296,31297 ,730,730,730 ,0,0,0}, - {31246,31406,31407 ,730,730,730 ,0,0,0}, {31406,31241,31408 ,730,730,730 ,0,0,0}, - {31409,31300,31410 ,730,730,730 ,0,0,0}, {31411,31247,31244 ,730,730,730 ,0,0,0}, - {31244,31246,31407 ,730,730,730 ,0,0,0}, {31250,31412,31413 ,730,730,730 ,0,0,0}, - {160,31306,31303 ,730,730,730 ,0,0,0}, {31251,31414,160 ,730,730,730 ,0,0,0}, - {31251,31250,31413 ,730,730,730 ,0,0,0}, {31415,31303,31305 ,730,730,730 ,0,0,0}, - {31416,31412,31247 ,730,730,730 ,0,0,0}, {31305,31409,31415 ,730,730,730 ,0,0,0}, - {31396,31385,31290 ,730,730,730 ,0,0,0}, {31262,31265,31417 ,730,730,730 ,0,0,0}, - {31239,31401,31405 ,730,730,730 ,0,0,0}, {31393,31283,31272 ,730,730,730 ,0,0,0}, - {31394,31284,31283 ,730,730,730 ,0,0,0}, {31396,31286,31395 ,730,730,730 ,0,0,0}, - {31396,31290,31288 ,730,730,730 ,0,0,0}, {31385,31274,31290 ,730,730,730 ,0,0,0}, - {31388,31275,31386 ,730,730,730 ,0,0,0}, {31388,31297,31293 ,730,730,730 ,0,0,0}, - {31403,31297,31387 ,730,730,730 ,0,0,0}, {31403,31410,31300 ,730,730,730 ,0,0,0}, - {31300,31302,31403 ,730,730,730 ,0,0,0}, {31409,31305,31300 ,730,730,730 ,0,0,0}, - {160,31303,31415 ,730,730,730 ,0,0,0}, {160,31414,31306 ,730,730,730 ,0,0,0}, - {31251,31413,31414 ,730,730,730 ,0,0,0}, {31247,31412,31250 ,730,730,730 ,0,0,0}, - {31247,31411,31416 ,730,730,730 ,0,0,0}, {31244,31407,31411 ,730,730,730 ,0,0,0}, - {31241,31406,31246 ,730,730,730 ,0,0,0}, {31241,31404,31408 ,730,730,730 ,0,0,0}, - {31240,31405,31404 ,730,730,730 ,0,0,0}, {31399,31401,31256 ,730,730,730 ,0,0,0}, - {31259,31400,31256 ,730,730,730 ,0,0,0}, {31261,31397,31398 ,730,730,730 ,0,0,0}, - {31259,31398,31400 ,730,730,730 ,0,0,0}, {31262,31418,31397 ,730,730,730 ,0,0,0}, - {31417,31265,31390 ,730,730,730 ,0,0,0}, {31418,31262,31417 ,730,730,730 ,0,0,0}, - {31390,31267,31389 ,730,730,730 ,0,0,0}, {174,31389,31267 ,730,730,730 ,0,0,0}, - {31296,31403,31294 ,730,730,730 ,0,0,0}, {31402,31410,31403 ,730,730,730 ,0,0,0}, - {31419,31420,31371 ,18105,18106,18106 ,0,0,0}, {31420,31421,31422 ,18106,1433,1433 ,0,0,0}, - {31422,31371,31420 ,1433,18106,18106 ,0,0,0}, {31371,31423,31419 ,18106,18105,18105 ,0,0,0}, - {31424,31425,31343 ,2162,18107,18107 ,0,0,0}, {31425,31380,31384 ,18107,2162,2162 ,0,0,0}, - {31384,31343,31425 ,2162,18107,18107 ,0,0,0}, {31343,31426,31424 ,18107,2162,2162 ,0,0,0}, - {31345,31421,31427 ,18108,1077,18109 ,0,0,0}, {31424,31426,31427 ,18110,18110,18109 ,0,0,0}, - {31426,31345,31427 ,18110,18108,18109 ,0,0,0}, {31345,31422,31421 ,18108,18111,1077 ,0,0,0}, - {31273,31428,31382 ,18112,18112,18112 ,0,0,0}, {31273,31429,31430 ,18112,18113,18113 ,0,0,0}, - {31273,31430,31428 ,18112,18113,18112 ,0,0,0}, {31428,31383,31382 ,18112,18112,18112 ,0,0,0}, - {31431,31332,31432 ,726,7628,8135 ,0,0,0}, {31433,31321,31434 ,7628,7625,7628 ,0,0,0}, - {31327,31330,31435 ,7627,7625,7761 ,0,0,0}, {31327,31436,31437 ,7627,18114,7253 ,0,0,0}, - {31437,31438,31309 ,7253,18115,7628 ,0,0,0}, {31309,31438,31310 ,7628,18115,7627 ,0,0,0}, - {31330,31332,31431 ,7625,7628,726 ,0,0,0}, {31439,31440,31311 ,8017,18116,7628 ,0,0,0}, - {31311,31310,31441 ,7628,7627,18117 ,0,0,0}, {31442,31316,31440 ,7756,7627,18116 ,0,0,0}, - {31333,31443,31432 ,7628,8135,8135 ,0,0,0}, {31339,31354,31444 ,7628,7628,7628 ,0,0,0}, - {31314,31445,31317 ,7880,8135,7625 ,0,0,0}, {31321,31320,31434 ,7625,7628,7628 ,0,0,0}, - {31446,31352,31339 ,726,7628,7628 ,0,0,0}, {31358,31356,31447 ,7628,726,7628 ,0,0,0}, - {31447,31348,31448 ,7628,726,726 ,0,0,0}, {31449,31347,31450 ,7626,726,726 ,0,0,0}, - {31451,31360,31358 ,7628,7626,7628 ,0,0,0}, {31365,31449,31369 ,7628,7626,726 ,0,0,0}, - {31452,31368,31453 ,7628,7628,726 ,0,0,0}, {31454,31372,31455 ,7628,726,7628 ,0,0,0}, - {31366,31452,31455 ,726,7628,7628 ,0,0,0}, {31450,31346,31456 ,726,7626,7628 ,0,0,0}, - {31454,31457,31377 ,7628,7628,726 ,0,0,0}, {31451,31456,31362 ,7628,7628,7628 ,0,0,0}, - {31378,31323,31433 ,7628,7628,7628 ,0,0,0}, {31323,31378,31375 ,7628,7628,7628 ,0,0,0}, - {31350,31458,31348 ,726,726,726 ,0,0,0}, {31459,31358,31447 ,726,7628,7628 ,0,0,0}, - {31460,31434,31320 ,7754,7628,7628 ,0,0,0}, {31350,31446,31458 ,726,726,726 ,0,0,0}, - {31317,31460,31320 ,7625,7754,7628 ,0,0,0}, {31461,31338,31444 ,7628,7628,7628 ,0,0,0}, - {31347,31346,31450 ,726,7626,726 ,0,0,0}, {31336,31338,31461 ,7628,7628,7628 ,0,0,0}, - {31316,31442,31314 ,7627,7756,7880 ,0,0,0}, {31462,31333,31336 ,7880,7628,7628 ,0,0,0}, - {31321,31433,31323 ,7625,7628,7628 ,0,0,0}, {31344,31447,31355 ,726,7628,726 ,0,0,0}, - {31317,31445,31463 ,7625,8135,7625 ,0,0,0}, {31463,31460,31317 ,7625,7754,7625 ,0,0,0}, - {31314,31442,31445 ,7880,7756,8135 ,0,0,0}, {31311,31440,31316 ,7628,18116,7627 ,0,0,0}, - {31311,31441,31439 ,7628,18117,8017 ,0,0,0}, {31310,31438,31441 ,7627,18115,18117 ,0,0,0}, - {31327,31437,31309 ,7627,7253,7628 ,0,0,0}, {31327,31435,31436 ,7627,7761,18114 ,0,0,0}, - {31330,31431,31435 ,7625,726,7761 ,0,0,0}, {31333,31432,31332 ,7628,8135,7628 ,0,0,0}, - {31333,31462,31443 ,7628,7880,8135 ,0,0,0}, {31336,31461,31462 ,7628,7628,7880 ,0,0,0}, - {31339,31444,31338 ,7628,7628,7628 ,0,0,0}, {31339,31352,31354 ,7628,7628,7628 ,0,0,0}, - {31446,31350,31352 ,726,726,7628 ,0,0,0}, {31448,31348,31458 ,726,726,726 ,0,0,0}, - {31344,31348,31447 ,726,726,7628 ,0,0,0}, {31356,31355,31447 ,726,726,7628 ,0,0,0}, - {31451,31358,31459 ,7628,7628,726 ,0,0,0}, {31451,31362,31360 ,7628,7628,7626 ,0,0,0}, - {31456,31346,31362 ,7628,7626,7628 ,0,0,0}, {31365,31347,31449 ,7628,726,7626 ,0,0,0}, - {31453,31369,31449 ,726,726,7626 ,0,0,0}, {31452,31366,31368 ,7628,726,7628 ,0,0,0}, - {31453,31368,31369 ,726,7628,726 ,0,0,0}, {31455,31374,31366 ,7628,726,726 ,0,0,0}, - {31372,31454,31377 ,726,7628,726 ,0,0,0}, {31374,31455,31372 ,726,7628,726 ,0,0,0}, - {31377,31457,31375 ,726,7628,7628 ,0,0,0}, {31323,31375,31457 ,7628,7628,7628 ,0,0,0}, - {31448,31464,31447 ,726,7628,7628 ,0,0,0}, {31447,31464,31459 ,7628,7628,726 ,0,0,0}, - {31429,31299,31465 ,18118,18119,18119 ,0,0,0}, {31419,31423,31299 ,18120,18120,18119 ,0,0,0}, - {31299,31423,31465 ,18119,18120,18119 ,0,0,0}, {31429,31465,31430 ,18118,18119,18118 ,0,0,0}, - {31444,31353,31466 ,17413,18121,18122 ,0,0,0}, {31432,31443,31467 ,17404,17412,18123 ,0,0,0}, - {31468,31462,31461 ,18124,17410,17415 ,0,0,0}, {31469,31428,31437 ,18125,18126,17385 ,0,0,0}, - {31470,31471,31435 ,18127,18128,17407 ,0,0,0}, {31472,31440,31473 ,18129,17396,18130 ,0,0,0}, - {31439,31441,31474 ,17398,17400,18131 ,0,0,0}, {31445,31472,31475 ,17393,18129,18132 ,0,0,0}, - {31465,31460,31463 ,18133,17386,17384 ,0,0,0}, {31463,31475,31465 ,17384,18132,18133 ,0,0,0}, - {31460,31476,31434 ,17386,18134,17388 ,0,0,0}, {31476,31460,31465 ,18134,17386,18133 ,0,0,0}, - {31476,31477,31434 ,18134,18135,17388 ,0,0,0}, {31379,31433,31477 ,18103,17390,18135 ,0,0,0}, - {31434,31477,31433 ,17388,18135,17390 ,0,0,0}, {31378,31433,31379 ,82,17390,18103 ,0,0,0}, - {31445,31442,31472 ,17393,17394,18129 ,0,0,0}, {31463,31445,31475 ,17384,17393,18132 ,0,0,0}, - {31440,31439,31473 ,17396,17398,18130 ,0,0,0}, {31442,31440,31472 ,17394,17396,18129 ,0,0,0}, - {31474,31441,31428 ,18131,17400,18126 ,0,0,0}, {31473,31439,31474 ,18130,17398,18131 ,0,0,0}, - {31437,31428,31438 ,17385,18126,18136 ,0,0,0}, {31428,31441,31438 ,18126,17400,18136 ,0,0,0}, - {31471,31469,31436 ,18128,18125,17403 ,0,0,0}, {31469,31437,31436 ,18125,17385,17403 ,0,0,0}, - {31431,31470,31435 ,17406,18127,17407 ,0,0,0}, {31435,31471,31436 ,17407,18128,17403 ,0,0,0}, - {31470,31432,31467 ,18127,17404,18123 ,0,0,0}, {31432,31470,31431 ,17404,18127,17406 ,0,0,0}, - {31443,31462,31381 ,17412,17410,18137 ,0,0,0}, {31443,31381,31467 ,17412,18137,18123 ,0,0,0}, - {31468,31461,31466 ,18124,17415,18122 ,0,0,0}, {31381,31462,31468 ,18137,17410,18124 ,0,0,0}, - {31353,31444,31354 ,18121,17413,18092 ,0,0,0}, {31466,31461,31444 ,18122,17415,17413 ,0,0,0}, - {31376,31423,31370 ,726,726,7661 ,0,0,0}, {31423,31371,31370 ,726,7661,7661 ,0,0,0}, - {31379,31423,31376 ,18138,726,726 ,0,0,0}, {31476,31423,31477 ,7658,726,18138 ,0,0,0}, - {31423,31379,31477 ,726,18138,18138 ,0,0,0}, {31465,31423,31476 ,7661,726,7658 ,0,0,0}, - {31470,31383,31471 ,726,17471,17470 ,0,0,0}, {31471,31383,31469 ,17470,17471,18139 ,0,0,0}, - {31383,31428,31469 ,17471,17471,18139 ,0,0,0}, {31383,31467,31381 ,17471,726,726 ,0,0,0}, - {31383,31470,31467 ,17471,726,726 ,0,0,0}, {31342,31426,31343 ,726,726,726 ,0,0,0}, - {31359,31426,31357 ,726,726,726 ,0,0,0}, {31426,31342,31357 ,726,726,726 ,0,0,0}, - {31345,31426,31361 ,726,726,726 ,0,0,0}, {31426,31359,31361 ,726,726,726 ,0,0,0}, - {31422,31364,31363 ,7659,726,18140 ,0,0,0}, {31345,31364,31422 ,726,726,7659 ,0,0,0}, - {31422,31373,31371 ,7659,18141,726 ,0,0,0}, {31422,31367,31373 ,7659,726,18141 ,0,0,0}, - {31363,31367,31422 ,18140,726,7659 ,0,0,0}, {31465,31475,31430 ,726,726,726 ,0,0,0}, - {31473,31430,31472 ,7660,726,7660 ,0,0,0}, {31475,31472,31430 ,726,7660,726 ,0,0,0}, - {31474,31428,31430 ,726,726,726 ,0,0,0}, {31474,31430,31473 ,726,726,7660 ,0,0,0}, - {31468,31384,31381 ,726,726,726 ,0,0,0}, {31384,31468,31466 ,726,726,726 ,0,0,0}, - {31351,31384,31353 ,726,726,726 ,0,0,0}, {31384,31466,31353 ,726,726,726 ,0,0,0}, - {31343,31384,31349 ,726,726,726 ,0,0,0}, {31384,31351,31349 ,726,726,726 ,0,0,0}, - {31478,31479,31341 ,18142,18143,18144 ,0,0,0}, {31341,31480,31478 ,18144,18145,18142 ,0,0,0}, - {31341,31324,31480 ,18144,18146,18145 ,0,0,0}, {31341,31481,31482 ,18144,18147,18148 ,0,0,0}, - {31479,31481,31341 ,18143,18147,18144 ,0,0,0}, {31341,31483,31484 ,18144,18149,18150 ,0,0,0}, - {31482,31483,31341 ,18148,18149,18144 ,0,0,0}, {31484,31485,31341 ,18150,18151,18144 ,0,0,0}, - {31486,31341,31487 ,18152,18144,18153 ,0,0,0}, {31341,31485,31487 ,18144,18151,18153 ,0,0,0}, - {31488,31341,31489 ,18154,18144,18155 ,0,0,0}, {31341,31486,31489 ,18144,18152,18155 ,0,0,0}, - {31490,31341,31491 ,18156,18144,18157 ,0,0,0}, {31341,31488,31491 ,18144,18154,18157 ,0,0,0}, - {31340,31341,31490 ,18158,18144,18156 ,0,0,0}, {31323,31457,31480 ,18159,18160,18161 ,0,0,0}, - {31482,31481,31452 ,18162,18163,18164 ,0,0,0}, {31479,31478,31454 ,18165,18166,18167 ,0,0,0}, - {31484,31450,31485 ,18168,18169,18170 ,0,0,0}, {31453,31449,31483 ,18171,18172,18173 ,0,0,0}, - {31451,31459,31486 ,18174,18175,18176 ,0,0,0}, {31451,31487,31456 ,18174,18177,18178 ,0,0,0}, - {31464,31448,31488 ,18179,18180,18181 ,0,0,0}, {31488,31489,31464 ,18181,18182,18179 ,0,0,0}, - {31491,31448,31458 ,18183,18180,18184 ,0,0,0}, {31448,31491,31488 ,18180,18183,18181 ,0,0,0}, - {31446,31490,31458 ,18185,18186,18184 ,0,0,0}, {31491,31458,31490 ,18183,18184,18186 ,0,0,0}, - {31446,31339,31340 ,18185,18187,18188 ,0,0,0}, {31340,31490,31446 ,18188,18186,18185 ,0,0,0}, - {31450,31484,31449 ,18169,18168,18172 ,0,0,0}, {31459,31489,31486 ,18175,18182,18176 ,0,0,0}, - {31464,31489,31459 ,18179,18182,18175 ,0,0,0}, {31452,31481,31455 ,18164,18163,18189 ,0,0,0}, - {31456,31487,31485 ,18178,18177,18170 ,0,0,0}, {31451,31486,31487 ,18174,18176,18177 ,0,0,0}, - {31450,31456,31485 ,18169,18178,18170 ,0,0,0}, {31483,31449,31484 ,18173,18172,18168 ,0,0,0}, - {31482,31452,31453 ,18162,18164,18171 ,0,0,0}, {31453,31483,31482 ,18171,18173,18162 ,0,0,0}, - {31478,31457,31454 ,18166,18160,18167 ,0,0,0}, {31455,31479,31454 ,18189,18165,18167 ,0,0,0}, - {31481,31479,31455 ,18163,18165,18189 ,0,0,0}, {31323,31480,31324 ,18159,18161,35 ,0,0,0}, - {31457,31478,31480 ,18160,18166,18161 ,0,0,0}, {31389,31281,31492 ,17331,18026,18190 ,0,0,0}, - {31397,31418,31493 ,17322,17330,18191 ,0,0,0}, {31494,31417,31390 ,18192,17328,17333 ,0,0,0}, - {31495,31427,31401 ,18193,18194,17304 ,0,0,0}, {31496,31497,31400 ,18195,18196,17325 ,0,0,0}, - {31498,31406,31499 ,18197,17314,18198 ,0,0,0}, {31408,31404,31500 ,17316,17318,18199 ,0,0,0}, - {31411,31498,31501 ,17311,18197,18200 ,0,0,0}, {31420,31412,31416 ,18201,17305,17302 ,0,0,0}, - {31416,31501,31420 ,17302,18200,18201 ,0,0,0}, {31412,31502,31413 ,17305,18202,17307 ,0,0,0}, - {31502,31412,31420 ,18202,17305,18201 ,0,0,0}, {31502,31503,31413 ,18202,18203,17307 ,0,0,0}, - {31307,31414,31503 ,18204,17309,18203 ,0,0,0}, {31413,31503,31414 ,17307,18203,17309 ,0,0,0}, - {31306,31414,31307 ,18205,17309,18204 ,0,0,0}, {31411,31407,31498 ,17311,17312,18197 ,0,0,0}, - {31416,31411,31501 ,17302,17311,18200 ,0,0,0}, {31406,31408,31499 ,17314,17316,18198 ,0,0,0}, - {31407,31406,31498 ,17312,17314,18197 ,0,0,0}, {31500,31404,31427 ,18199,17318,18194 ,0,0,0}, - {31499,31408,31500 ,18198,17316,18199 ,0,0,0}, {31401,31427,31405 ,17304,18194,10001 ,0,0,0}, - {31427,31404,31405 ,18194,17318,10001 ,0,0,0}, {31497,31495,31399 ,18196,18193,17321 ,0,0,0}, - {31495,31401,31399 ,18193,17304,17321 ,0,0,0}, {31398,31496,31400 ,17324,18195,17325 ,0,0,0}, - {31400,31497,31399 ,17325,18196,17321 ,0,0,0}, {31496,31397,31493 ,18195,17322,18191 ,0,0,0}, - {31397,31496,31398 ,17322,18195,17324 ,0,0,0}, {31418,31417,31425 ,17330,17328,18206 ,0,0,0}, - {31418,31425,31493 ,17330,18206,18191 ,0,0,0}, {31494,31390,31492 ,18192,17333,18190 ,0,0,0}, - {31425,31417,31494 ,18206,17328,18192 ,0,0,0}, {31281,31389,31282 ,18026,17331,126 ,0,0,0}, - {31492,31390,31389 ,18190,17333,17331 ,0,0,0}, {31424,31496,31493 ,730,17561,730 ,0,0,0}, - {31495,31424,31427 ,730,730,730 ,0,0,0}, {31496,31424,31497 ,17561,730,17561 ,0,0,0}, - {31424,31495,31497 ,730,730,17561 ,0,0,0}, {31493,31425,31424 ,730,7433,730 ,0,0,0}, - {31298,31419,31299 ,7376,17561,7376 ,0,0,0}, {31419,31503,31502 ,17561,17561,7433 ,0,0,0}, - {31419,31298,31304 ,17561,7376,730 ,0,0,0}, {31503,31419,31307 ,17561,17561,18207 ,0,0,0}, - {31419,31304,31307 ,17561,730,18207 ,0,0,0}, {31502,31420,31419 ,7433,7376,17561 ,0,0,0}, - {31285,31382,31270 ,7015,730,730 ,0,0,0}, {31382,31271,31270 ,730,11465,730 ,0,0,0}, - {31289,31382,31287 ,7532,730,7016 ,0,0,0}, {31382,31285,31287 ,730,7015,7016 ,0,0,0}, - {31273,31382,31289 ,18208,730,7532 ,0,0,0}, {31499,31421,31498 ,730,7433,17561 ,0,0,0}, - {31501,31498,31421 ,17561,17561,7433 ,0,0,0}, {31420,31501,31421 ,18207,17561,7433 ,0,0,0}, - {31500,31427,31421 ,18209,730,7433 ,0,0,0}, {31500,31421,31499 ,18209,7433,730 ,0,0,0}, - {31292,31291,31429 ,18207,730,9877 ,0,0,0}, {31273,31292,31429 ,18210,18207,9877 ,0,0,0}, - {31295,31301,31429 ,730,730,9877 ,0,0,0}, {31295,31429,31291 ,730,9877,730 ,0,0,0}, - {31299,31429,31301 ,730,9877,730 ,0,0,0}, {31425,31494,31380 ,730,730,730 ,0,0,0}, - {31380,31492,31281 ,730,730,730 ,0,0,0}, {31380,31494,31492 ,730,730,730 ,0,0,0}, - {31281,31279,31380 ,730,730,730 ,0,0,0}, {31380,31277,31271 ,730,730,730 ,0,0,0}, - {31279,31277,31380 ,730,730,730 ,0,0,0}, {31504,31505,31269 ,18211,18212,18213 ,0,0,0}, - {31269,31506,31504 ,18213,18214,18211 ,0,0,0}, {31269,31253,31506 ,18213,18215,18214 ,0,0,0}, - {31269,31507,31508 ,18213,18216,18217 ,0,0,0}, {31505,31507,31269 ,18212,18216,18213 ,0,0,0}, - {31269,31509,31510 ,18213,18218,18219 ,0,0,0}, {31508,31509,31269 ,18217,18218,18213 ,0,0,0}, - {31510,31511,31269 ,18219,18220,18213 ,0,0,0}, {31512,31269,31513 ,18221,18213,18222 ,0,0,0}, - {31269,31511,31513 ,18213,18220,18222 ,0,0,0}, {31514,31269,31515 ,18223,18213,18224 ,0,0,0}, - {31269,31512,31515 ,18213,18221,18224 ,0,0,0}, {31516,31269,31517 ,18225,18213,18226 ,0,0,0}, - {31269,31514,31517 ,18213,18223,18226 ,0,0,0}, {31268,31269,31516 ,18227,18213,18225 ,0,0,0}, - {160,31415,31506 ,3345,18228,18229 ,0,0,0}, {31508,31507,31402 ,18230,18231,18232 ,0,0,0}, - {31505,31504,31409 ,18233,18234,18235 ,0,0,0}, {31510,31386,31511 ,18236,18237,18238 ,0,0,0}, - {31387,31388,31509 ,18239,18240,18241 ,0,0,0}, {31396,31395,31512 ,18242,18243,18244 ,0,0,0}, - {31396,31513,31385 ,18242,18245,18246 ,0,0,0}, {31394,31393,31514 ,18247,18248,18249 ,0,0,0}, - {31514,31515,31394 ,18249,18250,18247 ,0,0,0}, {31517,31393,31391 ,18251,18248,18252 ,0,0,0}, - {31393,31517,31514 ,18248,18251,18249 ,0,0,0}, {31392,31516,31391 ,18253,18254,18252 ,0,0,0}, - {31517,31391,31516 ,18251,18252,18254 ,0,0,0}, {31392,174,31268 ,18253,18255,18256 ,0,0,0}, - {31268,31516,31392 ,18256,18254,18253 ,0,0,0}, {31386,31510,31388 ,18237,18236,18240 ,0,0,0}, - {31395,31515,31512 ,18243,18250,18244 ,0,0,0}, {31394,31515,31395 ,18247,18250,18243 ,0,0,0}, - {31402,31507,31410 ,18232,18231,18257 ,0,0,0}, {31385,31513,31511 ,18246,18245,18238 ,0,0,0}, - {31396,31512,31513 ,18242,18244,18245 ,0,0,0}, {31386,31385,31511 ,18237,18246,18238 ,0,0,0}, - {31509,31388,31510 ,18241,18240,18236 ,0,0,0}, {31508,31402,31387 ,18230,18232,18239 ,0,0,0}, - {31387,31509,31508 ,18239,18241,18230 ,0,0,0}, {31504,31415,31409 ,18234,18228,18235 ,0,0,0}, - {31410,31505,31409 ,18257,18233,18235 ,0,0,0}, {31507,31505,31410 ,18231,18233,18257 ,0,0,0}, - {160,31506,31253 ,3345,18229,126 ,0,0,0}, {31415,31504,31506 ,18228,18234,18229 ,0,0,0} -// Battery3.prt - , {31518,31519,31520 ,0,1,0 ,0,0,0}, {31521,31522,31523 ,2,2,3 ,0,0,0}, - {31521,31520,31522 ,2,0,2 ,0,0,0}, {31523,31522,31524 ,3,2,3 ,0,0,0}, - {31520,31521,31518 ,0,2,0 ,0,0,0}, {31525,31519,31518 ,1,1,0 ,0,0,0}, - {31526,31525,31527 ,4,1,4 ,0,0,0}, {31525,31526,31519 ,1,4,1 ,0,0,0}, - {31528,31529,31530 ,5,6,5 ,0,0,0}, {31531,31532,31533 ,7,7,8 ,0,0,0}, - {31531,31530,31532 ,7,5,7 ,0,0,0}, {31533,31532,31534 ,8,7,8 ,0,0,0}, - {31530,31531,31528 ,5,7,5 ,0,0,0}, {31535,31529,31528 ,9,6,5 ,0,0,0}, - {31536,31535,31537 ,10,9,11 ,0,0,0}, {31535,31536,31529 ,9,10,6 ,0,0,0}, - {31538,31539,31540 ,12,13,12 ,0,0,0}, {31541,31542,31543 ,14,14,15 ,0,0,0}, - {31541,31540,31542 ,14,12,14 ,0,0,0}, {31543,31542,31544 ,15,14,15 ,0,0,0}, - {31540,31541,31538 ,12,14,12 ,0,0,0}, {31545,31539,31538 ,13,13,12 ,0,0,0}, - {31546,31545,31547 ,16,13,16 ,0,0,0}, {31545,31546,31539 ,13,16,13 ,0,0,0}, - {31548,31549,31550 ,17,18,17 ,0,0,0}, {31551,31552,31553 ,19,19,20 ,0,0,0}, - {31551,31550,31552 ,19,17,19 ,0,0,0}, {31553,31552,31554 ,20,19,20 ,0,0,0}, - {31550,31551,31548 ,17,19,17 ,0,0,0}, {31555,31549,31548 ,18,18,17 ,0,0,0}, - {31556,31555,31557 ,21,18,21 ,0,0,0}, {31555,31556,31549 ,18,21,18 ,0,0,0}, - {31558,31559,31560 ,22,23,24 ,0,0,0}, {31561,31562,31563 ,25,26,27 ,0,0,0}, - {31564,31558,31560 ,28,22,24 ,0,0,0}, {31563,31562,31564 ,27,26,28 ,0,0,0}, - {31562,31561,31565 ,26,25,29 ,0,0,0}, {31560,31563,31564 ,24,27,28 ,0,0,0}, - {31566,31567,31568 ,30,31,32 ,0,0,0}, {31567,31569,31568 ,31,33,32 ,0,0,0}, - {31565,31570,31566 ,29,34,30 ,0,0,0}, {31567,31566,31570 ,31,30,34 ,0,0,0}, - {31571,31572,31573 ,35,36,37 ,0,0,0}, {31574,31575,31569 ,38,39,33 ,0,0,0}, - {31572,31575,31574 ,36,39,38 ,0,0,0}, {31572,31574,31573 ,36,38,37 ,0,0,0}, - {31573,31576,31571 ,37,40,35 ,0,0,0}, {31568,31569,31575 ,32,33,39 ,0,0,0}, - {31565,31561,31570 ,29,25,34 ,0,0,0}, {31558,31577,31559 ,22,41,23 ,0,0,0}, - {31578,31577,31579 ,42,41,43 ,0,0,0}, {31577,31578,31559 ,41,42,23 ,0,0,0}, - {31580,31581,31579 ,44,45,43 ,0,0,0}, {31578,31579,31581 ,42,43,45 ,0,0,0}, - {31580,31582,31583 ,44,46,47 ,0,0,0}, {31583,31581,31580 ,47,45,44 ,0,0,0}, - {31584,31582,31585 ,48,46,49 ,0,0,0}, {31582,31584,31583 ,46,48,47 ,0,0,0}, - {31586,31587,31585 ,50,51,49 ,0,0,0}, {31584,31585,31587 ,48,49,51 ,0,0,0}, - {31586,31588,31589 ,50,52,53 ,0,0,0}, {31589,31587,31586 ,53,51,50 ,0,0,0}, - {31590,31588,31591 ,54,52,54 ,0,0,0}, {31588,31590,31589 ,52,54,53 ,0,0,0}, - {31592,31593,31594 ,22,55,24 ,0,0,0}, {31595,31596,31597 ,56,57,58 ,0,0,0}, - {31598,31592,31594 ,59,22,24 ,0,0,0}, {31597,31596,31598 ,58,57,59 ,0,0,0}, - {31596,31595,31599 ,57,56,60 ,0,0,0}, {31594,31597,31598 ,24,58,59 ,0,0,0}, - {31600,31601,31602 ,61,62,63 ,0,0,0}, {31601,31603,31602 ,62,64,63 ,0,0,0}, - {31599,31604,31600 ,60,65,61 ,0,0,0}, {31601,31600,31604 ,62,61,65 ,0,0,0}, - {31605,31606,31607 ,66,67,68 ,0,0,0}, {31608,31609,31603 ,69,70,64 ,0,0,0}, - {31606,31609,31608 ,67,70,69 ,0,0,0}, {31606,31608,31607 ,67,69,68 ,0,0,0}, - {31607,31610,31605 ,68,66,66 ,0,0,0}, {31602,31603,31609 ,63,64,70 ,0,0,0}, - {31599,31595,31604 ,60,56,65 ,0,0,0}, {31592,31611,31593 ,22,71,55 ,0,0,0}, - {31612,31611,31613 ,72,71,43 ,0,0,0}, {31611,31612,31593 ,71,72,55 ,0,0,0}, - {31614,31615,31613 ,73,74,43 ,0,0,0}, {31612,31613,31615 ,72,43,74 ,0,0,0}, - {31614,31616,31617 ,73,46,75 ,0,0,0}, {31617,31615,31614 ,75,74,73 ,0,0,0}, - {31618,31616,31619 ,76,46,77 ,0,0,0}, {31616,31618,31617 ,46,76,75 ,0,0,0}, - {31620,31621,31619 ,50,78,77 ,0,0,0}, {31618,31619,31621 ,76,77,78 ,0,0,0}, - {31620,31622,31623 ,50,79,80 ,0,0,0}, {31623,31621,31620 ,80,78,50 ,0,0,0}, - {31624,31622,31625 ,81,79,82 ,0,0,0}, {31622,31624,31623 ,79,81,80 ,0,0,0}, - {31626,31627,31628 ,83,84,85 ,0,0,0}, {31629,31630,31631 ,86,87,88 ,0,0,0}, - {31632,31626,31628 ,89,83,85 ,0,0,0}, {31631,31630,31632 ,88,87,89 ,0,0,0}, - {31630,31629,31633 ,87,86,90 ,0,0,0}, {31628,31631,31632 ,85,88,89 ,0,0,0}, - {31634,31635,31636 ,91,92,93 ,0,0,0}, {31635,31637,31636 ,92,94,93 ,0,0,0}, - {31633,31638,31634 ,90,95,91 ,0,0,0}, {31635,31634,31638 ,92,91,95 ,0,0,0}, - {30497,31639,31640 ,96,97,98 ,0,0,0}, {31641,31642,31637 ,99,100,94 ,0,0,0}, - {31639,31642,31641 ,97,100,99 ,0,0,0}, {31639,31641,31640 ,97,99,98 ,0,0,0}, - {31640,31643,30497 ,98,101,96 ,0,0,0}, {31636,31637,31642 ,93,94,100 ,0,0,0}, - {31633,31629,31638 ,90,86,95 ,0,0,0}, {31626,31644,31627 ,83,102,84 ,0,0,0}, - {31645,31644,31646 ,103,102,104 ,0,0,0}, {31644,31645,31627 ,102,103,84 ,0,0,0}, - {31647,31648,31646 ,105,106,104 ,0,0,0}, {31645,31646,31648 ,103,104,106 ,0,0,0}, - {31647,31649,31650 ,105,107,108 ,0,0,0}, {31650,31648,31647 ,108,106,105 ,0,0,0}, - {31651,31649,31652 ,109,107,110 ,0,0,0}, {31649,31651,31650 ,107,109,108 ,0,0,0}, - {31653,31654,31652 ,111,112,110 ,0,0,0}, {31651,31652,31654 ,109,110,112 ,0,0,0}, - {31653,31655,31656 ,111,113,114 ,0,0,0}, {31656,31654,31653 ,114,112,111 ,0,0,0}, - {31657,31655,30481 ,54,113,54 ,0,0,0}, {31655,31657,31656 ,113,54,114 ,0,0,0}, - {31658,31659,31660 ,83,115,85 ,0,0,0}, {31661,31662,31663 ,116,117,118 ,0,0,0}, - {31664,31658,31660 ,119,83,85 ,0,0,0}, {31663,31662,31664 ,118,117,119 ,0,0,0}, - {31662,31661,31665 ,117,116,120 ,0,0,0}, {31660,31663,31664 ,85,118,119 ,0,0,0}, - {31666,31667,31668 ,121,122,123 ,0,0,0}, {31667,31669,31668 ,122,124,123 ,0,0,0}, - {31665,31670,31666 ,120,125,121 ,0,0,0}, {31667,31666,31670 ,122,121,125 ,0,0,0}, - {31323,31671,31672 ,126,127,128 ,0,0,0}, {31673,31674,31669 ,129,130,124 ,0,0,0}, - {31671,31674,31673 ,127,130,129 ,0,0,0}, {31671,31673,31672 ,127,129,128 ,0,0,0}, - {31672,31675,31323 ,128,35,126 ,0,0,0}, {31668,31669,31674 ,123,124,130 ,0,0,0}, - {31665,31661,31670 ,120,116,125 ,0,0,0}, {31658,31676,31659 ,83,131,115 ,0,0,0}, - {31677,31676,31678 ,132,131,133 ,0,0,0}, {31676,31677,31659 ,131,132,115 ,0,0,0}, - {31679,31680,31678 ,134,74,133 ,0,0,0}, {31677,31678,31680 ,132,133,74 ,0,0,0}, - {31679,31681,31682 ,134,135,108 ,0,0,0}, {31682,31680,31679 ,108,74,134 ,0,0,0}, - {31683,31681,31684 ,136,135,137 ,0,0,0}, {31681,31683,31682 ,135,136,108 ,0,0,0}, - {31685,31686,31684 ,138,139,137 ,0,0,0}, {31683,31684,31686 ,136,137,139 ,0,0,0}, - {31685,31687,31688 ,138,79,80 ,0,0,0}, {31688,31686,31685 ,80,139,138 ,0,0,0}, - {31689,31687,31339 ,140,79,140 ,0,0,0}, {31687,31689,31688 ,79,140,80 ,0,0,0}, - {31690,31691,31692 ,141,142,143 ,0,0,0}, {31693,31694,31695 ,144,145,146 ,0,0,0}, - {31696,31690,31692 ,147,141,143 ,0,0,0}, {31695,31694,31696 ,146,145,147 ,0,0,0}, - {31694,31693,31697 ,145,144,148 ,0,0,0}, {31692,31695,31696 ,143,146,147 ,0,0,0}, - {31698,31699,31700 ,149,150,151 ,0,0,0}, {31699,31701,31700 ,150,152,151 ,0,0,0}, - {31697,31702,31698 ,148,153,149 ,0,0,0}, {31699,31698,31702 ,150,149,153 ,0,0,0}, - {31703,31704,31705 ,126,154,155 ,0,0,0}, {31706,31707,31701 ,156,157,152 ,0,0,0}, - {31704,31707,31706 ,154,157,156 ,0,0,0}, {31704,31706,31705 ,154,156,155 ,0,0,0}, - {31705,31708,31703 ,155,35,126 ,0,0,0}, {31700,31701,31707 ,151,152,157 ,0,0,0}, - {31697,31693,31702 ,148,144,153 ,0,0,0}, {31690,31709,31691 ,141,158,142 ,0,0,0}, - {31710,31709,31711 ,159,158,160 ,0,0,0}, {31709,31710,31691 ,158,159,142 ,0,0,0}, - {31712,31713,31711 ,161,162,160 ,0,0,0}, {31710,31711,31713 ,159,160,162 ,0,0,0}, - {31712,31714,31715 ,161,163,164 ,0,0,0}, {31715,31713,31712 ,164,162,161 ,0,0,0}, - {31716,31714,31717 ,165,163,166 ,0,0,0}, {31714,31716,31715 ,163,165,164 ,0,0,0}, - {31718,31719,31717 ,167,168,166 ,0,0,0}, {31716,31717,31719 ,165,166,168 ,0,0,0}, - {31718,31720,31721 ,167,169,170 ,0,0,0}, {31721,31719,31718 ,170,168,167 ,0,0,0}, - {31722,31720,31723 ,140,169,140 ,0,0,0}, {31720,31722,31721 ,169,140,170 ,0,0,0}, - {31724,31725,31726 ,171,172,173 ,0,0,0}, {31727,31728,31729 ,174,175,176 ,0,0,0}, - {31730,31724,31726 ,177,171,173 ,0,0,0}, {31729,31728,31730 ,176,175,177 ,0,0,0}, - {31728,31727,31731 ,175,174,178 ,0,0,0}, {31726,31729,31730 ,173,176,177 ,0,0,0}, - {31732,31733,31734 ,179,180,181 ,0,0,0}, {31733,31735,31734 ,180,182,181 ,0,0,0}, - {31731,31736,31732 ,178,183,179 ,0,0,0}, {31733,31732,31736 ,180,179,183 ,0,0,0}, - {31043,31737,31738 ,35,184,185 ,0,0,0}, {31739,31740,31735 ,186,187,182 ,0,0,0}, - {31737,31740,31739 ,184,187,186 ,0,0,0}, {31737,31739,31738 ,184,186,185 ,0,0,0}, - {31738,31741,31043 ,185,40,35 ,0,0,0}, {31734,31735,31740 ,181,182,187 ,0,0,0}, - {31731,31727,31736 ,178,174,183 ,0,0,0}, {31724,31742,31725 ,171,188,172 ,0,0,0}, - {31743,31742,31744 ,189,188,104 ,0,0,0}, {31742,31743,31725 ,188,189,172 ,0,0,0}, - {31745,31746,31744 ,190,45,104 ,0,0,0}, {31743,31744,31746 ,189,104,45 ,0,0,0}, - {31745,31747,31748 ,190,191,192 ,0,0,0}, {31748,31746,31745 ,192,45,190 ,0,0,0}, - {31749,31747,31750 ,193,191,194 ,0,0,0}, {31747,31749,31748 ,191,193,192 ,0,0,0}, - {31751,31752,31750 ,111,195,194 ,0,0,0}, {31749,31750,31752 ,193,194,195 ,0,0,0}, - {31751,31753,31754 ,111,52,53 ,0,0,0}, {31754,31752,31751 ,53,195,111 ,0,0,0}, - {31755,31753,31059 ,54,52,54 ,0,0,0}, {31753,31755,31754 ,52,54,53 ,0,0,0}, - {31756,31757,31758 ,196,197,197 ,0,0,0}, {31759,31760,31761 ,198,196,198 ,0,0,0}, - {31760,31756,31758 ,196,196,197 ,0,0,0}, {31759,31761,31762 ,198,198,199 ,0,0,0}, - {31763,31764,31765 ,200,82,200 ,0,0,0}, {31762,31761,31766 ,199,198,199 ,0,0,0}, - {31766,31765,31762 ,199,200,199 ,0,0,0}, {31765,31766,31763 ,200,199,200 ,0,0,0}, - {31764,31763,31767 ,82,200,201 ,0,0,0}, {31760,31759,31756 ,196,198,196 ,0,0,0}, - {31768,31758,31757 ,202,197,197 ,0,0,0}, {31769,31768,31770 ,203,202,202 ,0,0,0}, - {31757,31770,31768 ,197,202,202 ,0,0,0}, {31771,31772,31769 ,203,204,203 ,0,0,0}, - {31769,31770,31771 ,203,202,203 ,0,0,0}, {31772,31773,31774 ,204,204,205 ,0,0,0}, - {31773,31772,31771 ,204,204,203 ,0,0,0}, {31773,31775,31774 ,204,205,205 ,0,0,0}, - {31776,31777,31778 ,206,207,208 ,0,0,0}, {31779,31776,31780 ,209,206,210 ,0,0,0}, - {31776,31779,31777 ,206,209,207 ,0,0,0}, {31781,31782,31780 ,211,212,210 ,0,0,0}, - {31779,31780,31782 ,209,210,212 ,0,0,0}, {31781,31783,31784 ,211,213,214 ,0,0,0}, - {31784,31782,31781 ,214,212,211 ,0,0,0}, {31785,31783,31786 ,215,213,216 ,0,0,0}, - {31783,31785,31784 ,213,215,214 ,0,0,0}, {31787,31788,31786 ,217,218,216 ,0,0,0}, - {31785,31786,31788 ,215,216,218 ,0,0,0}, {31787,31789,31790 ,217,219,220 ,0,0,0}, - {31790,31788,31787 ,220,218,217 ,0,0,0}, {31791,31790,31789 ,221,220,219 ,0,0,0}, - {31791,31792,31790 ,221,221,220 ,0,0,0}, {31776,31778,31793 ,206,208,222 ,0,0,0}, - {31794,31795,31778 ,223,224,208 ,0,0,0}, {31793,31778,31795 ,222,208,224 ,0,0,0}, - {31794,31796,31797 ,223,225,226 ,0,0,0}, {31797,31795,31794 ,226,224,223 ,0,0,0}, - {31798,31796,31799 ,227,225,228 ,0,0,0}, {31796,31798,31797 ,225,227,226 ,0,0,0}, - {31800,31801,31799 ,229,230,228 ,0,0,0}, {31798,31799,31801 ,227,228,230 ,0,0,0}, - {31800,31802,31803 ,229,231,232 ,0,0,0}, {31803,31801,31800 ,232,230,229 ,0,0,0}, - {31804,31802,31805 ,233,231,234 ,0,0,0}, {31802,31804,31803 ,231,233,232 ,0,0,0}, - {31805,31806,31804 ,234,235,233 ,0,0,0}, {31804,31806,31807 ,233,235,235 ,0,0,0}, - {31808,31809,31810 ,236,237,238 ,0,0,0}, {31811,31812,31808 ,239,240,236 ,0,0,0}, - {31808,31810,31811 ,236,238,239 ,0,0,0}, {31812,31813,31814 ,240,241,242 ,0,0,0}, - {31813,31812,31811 ,241,240,239 ,0,0,0}, {31815,31814,31816 ,243,242,244 ,0,0,0}, - {31813,31816,31814 ,241,244,242 ,0,0,0}, {31817,31818,31815 ,245,246,243 ,0,0,0}, - {31815,31816,31817 ,243,244,245 ,0,0,0}, {31819,31818,31817 ,247,246,245 ,0,0,0}, - {31819,31820,31818 ,247,126,246 ,0,0,0}, {31810,31809,31821 ,238,237,248 ,0,0,0}, - {31821,31822,31823 ,248,249,250 ,0,0,0}, {31822,31821,31809 ,249,248,237 ,0,0,0}, - {31824,31823,31825 ,251,250,252 ,0,0,0}, {31822,31825,31823 ,249,252,250 ,0,0,0}, - {31826,31827,31824 ,253,254,251 ,0,0,0}, {31824,31825,31826 ,251,252,253 ,0,0,0}, - {31827,31828,31829 ,254,255,256 ,0,0,0}, {31828,31827,31826 ,255,254,253 ,0,0,0}, - {31828,31830,31829 ,255,257,256 ,0,0,0}, {31829,31830,31831 ,256,257,257 ,0,0,0}, - {31832,31833,31834 ,258,259,260 ,0,0,0}, {31835,31832,31836 ,261,258,262 ,0,0,0}, - {31832,31835,31833 ,258,261,259 ,0,0,0}, {31837,31838,31836 ,263,264,262 ,0,0,0}, - {31835,31836,31838 ,261,262,264 ,0,0,0}, {31837,31839,31840 ,263,265,266 ,0,0,0}, - {31840,31838,31837 ,266,264,263 ,0,0,0}, {31841,31839,31842 ,267,265,268 ,0,0,0}, - {31839,31841,31840 ,265,267,266 ,0,0,0}, {31843,31844,31842 ,269,270,268 ,0,0,0}, - {31841,31842,31844 ,267,268,270 ,0,0,0}, {31843,31845,31846 ,269,271,272 ,0,0,0}, - {31846,31844,31843 ,272,270,269 ,0,0,0}, {31847,31846,31845 ,273,272,271 ,0,0,0}, - {31847,31848,31846 ,273,273,272 ,0,0,0}, {31832,31834,31849 ,258,260,274 ,0,0,0}, - {31850,31851,31834 ,275,276,260 ,0,0,0}, {31849,31834,31851 ,274,260,276 ,0,0,0}, - {31850,31852,31853 ,275,277,278 ,0,0,0}, {31853,31851,31850 ,278,276,275 ,0,0,0}, - {31854,31852,31855 ,279,277,280 ,0,0,0}, {31852,31854,31853 ,277,279,278 ,0,0,0}, - {31856,31857,31855 ,281,282,280 ,0,0,0}, {31854,31855,31857 ,279,280,282 ,0,0,0}, - {31856,31858,31859 ,281,283,284 ,0,0,0}, {31859,31857,31856 ,284,282,281 ,0,0,0}, - {31860,31858,31861 ,285,283,286 ,0,0,0}, {31858,31860,31859 ,283,285,284 ,0,0,0}, - {31861,31862,31860 ,286,257,285 ,0,0,0}, {31860,31862,31863 ,285,257,257 ,0,0,0}, - {31864,31865,31866 ,287,288,288 ,0,0,0}, {31867,31868,31869 ,289,287,289 ,0,0,0}, - {31868,31864,31866 ,287,287,288 ,0,0,0}, {31867,31869,31870 ,289,289,290 ,0,0,0}, - {31871,31872,31873 ,291,82,291 ,0,0,0}, {31870,31869,31874 ,290,289,290 ,0,0,0}, - {31874,31873,31870 ,290,291,290 ,0,0,0}, {31873,31874,31871 ,291,290,291 ,0,0,0}, - {31872,31871,31875 ,82,291,292 ,0,0,0}, {31868,31867,31864 ,287,289,287 ,0,0,0}, - {31876,31866,31865 ,293,288,288 ,0,0,0}, {31877,31876,31878 ,203,293,293 ,0,0,0}, - {31865,31878,31876 ,288,293,293 ,0,0,0}, {31879,31880,31877 ,203,294,203 ,0,0,0}, - {31877,31878,31879 ,203,293,203 ,0,0,0}, {31880,31881,31882 ,294,294,205 ,0,0,0}, - {31881,31880,31879 ,294,294,203 ,0,0,0}, {31881,31883,31882 ,294,205,205 ,0,0,0}, - {31884,31885,31886 ,295,296,295 ,0,0,0}, {31887,31885,31888 ,296,296,297 ,0,0,0}, - {31885,31887,31886 ,296,296,295 ,0,0,0}, {31889,31890,31888 ,298,297,297 ,0,0,0}, - {31887,31888,31890 ,296,297,297 ,0,0,0}, {31889,31891,31892 ,298,299,298 ,0,0,0}, - {31892,31890,31889 ,298,297,298 ,0,0,0}, {31891,31893,31892 ,299,300,298 ,0,0,0}, - {31894,31884,31886 ,301,295,295 ,0,0,0}, {31895,31896,31894 ,302,301,301 ,0,0,0}, - {31884,31894,31896 ,295,301,301 ,0,0,0}, {31895,31897,31898 ,302,303,302 ,0,0,0}, - {31898,31896,31895 ,302,301,302 ,0,0,0}, {31899,31897,31900 ,303,303,304 ,0,0,0}, - {31897,31899,31898 ,303,303,302 ,0,0,0}, {31899,31900,31901 ,303,304,304 ,0,0,0}, - {31902,31903,31904 ,305,306,305 ,0,0,0}, {31905,31903,31906 ,306,306,307 ,0,0,0}, - {31903,31905,31904 ,306,306,305 ,0,0,0}, {31907,31908,31906 ,308,307,307 ,0,0,0}, - {31905,31906,31908 ,306,307,307 ,0,0,0}, {31907,31909,31910 ,308,309,308 ,0,0,0}, - {31910,31908,31907 ,308,307,308 ,0,0,0}, {31909,31911,31910 ,309,310,308 ,0,0,0}, - {31912,31902,31904 ,311,305,305 ,0,0,0}, {31913,31914,31912 ,312,311,311 ,0,0,0}, - {31902,31912,31914 ,305,311,311 ,0,0,0}, {31913,31915,31916 ,312,313,312 ,0,0,0}, - {31916,31914,31913 ,312,311,312 ,0,0,0}, {31917,31915,31918 ,313,313,314 ,0,0,0}, - {31915,31917,31916 ,313,313,312 ,0,0,0}, {31917,31918,31919 ,313,314,314 ,0,0,0}, - {31920,31911,31909 ,315,309,309 ,0,0,0}, {31921,31922,31923 ,316,317,317 ,0,0,0}, - {31924,31925,31926 ,318,318,315 ,0,0,0}, {31927,31928,31929 ,319,319,320 ,0,0,0}, - {31930,31931,31932 ,316,321,321 ,0,0,0}, {31933,31934,31929 ,322,320,320 ,0,0,0}, - {31927,31929,31934 ,319,320,320 ,0,0,0}, {31935,31934,31933 ,323,320,322 ,0,0,0}, - {31931,31928,31932 ,321,319,321 ,0,0,0}, {31932,31928,31927 ,321,319,319 ,0,0,0}, - {31930,31922,31921 ,316,317,316 ,0,0,0}, {31930,31921,31931 ,316,316,321 ,0,0,0}, - {31923,31925,31924 ,317,318,318 ,0,0,0}, {31922,31925,31923 ,317,318,317 ,0,0,0}, - {31920,31926,31911 ,315,315,309 ,0,0,0}, {31924,31926,31920 ,318,315,315 ,0,0,0}, - {31936,31937,31938 ,324,324,324 ,0,0,0}, {31936,31938,31939 ,324,324,324 ,0,0,0}, - {31940,31941,31942 ,325,326,325 ,0,0,0}, {31943,31944,31940 ,327,327,325 ,0,0,0}, - {31940,31942,31943 ,325,325,327 ,0,0,0}, {31944,31945,31946 ,327,328,329 ,0,0,0}, - {31945,31944,31943 ,328,327,327 ,0,0,0}, {31947,31946,31948 ,330,329,331 ,0,0,0}, - {31945,31948,31946 ,328,331,329 ,0,0,0}, {31949,31950,31947 ,332,332,330 ,0,0,0}, - {31947,31948,31949 ,330,331,332 ,0,0,0}, {31950,31951,31952 ,332,333,334 ,0,0,0}, - {31951,31950,31949 ,333,332,332 ,0,0,0}, {31953,31952,31954 ,335,334,335 ,0,0,0}, - {31951,31954,31952 ,333,335,334 ,0,0,0}, {31955,31956,31953 ,336,336,335 ,0,0,0}, - {31953,31954,31955 ,335,335,336 ,0,0,0}, {31942,31941,31957 ,325,326,337 ,0,0,0}, - {31958,31957,31959 ,338,337,339 ,0,0,0}, {31941,31959,31957 ,326,339,337 ,0,0,0}, - {31960,31961,31958 ,340,341,338 ,0,0,0}, {31958,31959,31960 ,338,339,340 ,0,0,0}, - {31961,31962,31963 ,341,342,343 ,0,0,0}, {31962,31961,31960 ,342,341,340 ,0,0,0}, - {31964,31963,31965 ,344,343,345 ,0,0,0}, {31962,31965,31963 ,342,345,343 ,0,0,0}, - {31966,31967,31964 ,346,347,344 ,0,0,0}, {31964,31965,31966 ,344,345,346 ,0,0,0}, - {31967,31968,31969 ,347,348,349 ,0,0,0}, {31968,31967,31966 ,348,347,346 ,0,0,0}, - {31968,31546,31969 ,348,16,349 ,0,0,0}, {31969,31546,31547 ,349,16,350 ,0,0,0}, - {31970,31893,31891 ,351,299,299 ,0,0,0}, {31971,31972,31973 ,352,353,353 ,0,0,0}, - {31974,31975,31976 ,354,354,351 ,0,0,0}, {31977,31978,31979 ,355,355,356 ,0,0,0}, - {31980,31981,31982 ,352,357,357 ,0,0,0}, {31983,31984,31979 ,358,356,356 ,0,0,0}, - {31977,31979,31984 ,355,356,356 ,0,0,0}, {31985,31984,31983 ,359,356,358 ,0,0,0}, - {31981,31978,31982 ,357,355,357 ,0,0,0}, {31982,31978,31977 ,357,355,355 ,0,0,0}, - {31980,31972,31971 ,352,353,352 ,0,0,0}, {31980,31971,31981 ,352,352,357 ,0,0,0}, - {31973,31975,31974 ,353,354,354 ,0,0,0}, {31972,31975,31973 ,353,354,353 ,0,0,0}, - {31970,31976,31893 ,351,351,299 ,0,0,0}, {31974,31976,31970 ,354,351,351 ,0,0,0}, - {31986,31987,31988 ,360,324,360 ,0,0,0}, {31987,31986,31989 ,324,360,324 ,0,0,0}, - {31990,31991,31992 ,361,362,361 ,0,0,0}, {31993,31994,31990 ,363,363,361 ,0,0,0}, - {31990,31992,31993 ,361,361,363 ,0,0,0}, {31994,31995,31996 ,363,364,365 ,0,0,0}, - {31995,31994,31993 ,364,363,363 ,0,0,0}, {31997,31996,31998 ,366,365,367 ,0,0,0}, - {31995,31998,31996 ,364,367,365 ,0,0,0}, {31999,32000,31997 ,368,369,366 ,0,0,0}, - {31997,31998,31999 ,366,367,368 ,0,0,0}, {32000,32001,32002 ,369,370,370 ,0,0,0}, - {32001,32000,31999 ,370,369,368 ,0,0,0}, {32003,32002,32004 ,371,370,371 ,0,0,0}, - {32001,32004,32002 ,370,371,370 ,0,0,0}, {32005,32006,32003 ,372,372,371 ,0,0,0}, - {32003,32004,32005 ,371,371,372 ,0,0,0}, {31992,31991,32007 ,361,362,373 ,0,0,0}, - {32008,32007,32009 ,374,373,375 ,0,0,0}, {31991,32009,32007 ,362,375,373 ,0,0,0}, - {32010,32011,32008 ,376,377,374 ,0,0,0}, {32008,32009,32010 ,374,375,376 ,0,0,0}, - {32011,32012,32013 ,377,378,379 ,0,0,0}, {32012,32011,32010 ,378,377,376 ,0,0,0}, - {32014,32013,32015 ,380,379,381 ,0,0,0}, {32012,32015,32013 ,378,381,379 ,0,0,0}, - {32016,32017,32014 ,382,383,380 ,0,0,0}, {32014,32015,32016 ,380,381,382 ,0,0,0}, - {32017,32018,32019 ,383,384,385 ,0,0,0}, {32018,32017,32016 ,384,383,382 ,0,0,0}, - {32018,31526,32019 ,384,4,385 ,0,0,0}, {32019,31526,31527 ,385,4,386 ,0,0,0}, - {31875,32020,32021 ,387,388,388 ,0,0,0}, {32022,32023,32024 ,389,389,390 ,0,0,0}, - {32025,32026,32027 ,390,391,391 ,0,0,0}, {32028,32029,32030 ,392,393,392 ,0,0,0}, - {32031,32032,32033 ,394,394,393 ,0,0,0}, {32034,32035,32030 ,395,395,392 ,0,0,0}, - {32028,32030,32035 ,392,392,395 ,0,0,0}, {32034,32036,32037 ,395,396,396 ,0,0,0}, - {32037,32035,32034 ,396,395,395 ,0,0,0}, {32028,32033,32029 ,392,393,393 ,0,0,0}, - {32027,32026,32020 ,391,391,388 ,0,0,0}, {32033,32032,32029 ,393,394,393 ,0,0,0}, - {32031,32022,32032 ,394,389,394 ,0,0,0}, {32023,32025,32024 ,389,390,390 ,0,0,0}, - {32031,32023,32022 ,394,389,389 ,0,0,0}, {32024,32025,32027 ,390,390,391 ,0,0,0}, - {31875,32021,31872 ,387,388,397 ,0,0,0}, {32020,32026,32021 ,388,391,388 ,0,0,0}, - {32038,32039,32040 ,398,399,400 ,0,0,0}, {32041,32040,32042 ,401,400,402 ,0,0,0}, - {32039,32042,32040 ,399,402,400 ,0,0,0}, {32042,32043,32044 ,402,403,404 ,0,0,0}, - {32044,32041,32042 ,404,401,402 ,0,0,0}, {32045,32043,32046 ,405,403,406 ,0,0,0}, - {32043,32045,32044 ,403,405,404 ,0,0,0}, {32047,32048,32046 ,407,408,406 ,0,0,0}, - {32045,32046,32048 ,405,406,408 ,0,0,0}, {32047,32049,32050 ,407,409,410 ,0,0,0}, - {32050,32048,32047 ,410,408,407 ,0,0,0}, {32051,32049,32052 ,411,409,412 ,0,0,0}, - {32049,32051,32050 ,409,411,410 ,0,0,0}, {32053,32051,32054 ,413,411,414 ,0,0,0}, - {32052,32054,32051 ,412,414,411 ,0,0,0}, {32055,32056,32053 ,415,416,413 ,0,0,0}, - {32053,32054,32055 ,413,414,415 ,0,0,0}, {32057,32055,32058 ,417,415,418 ,0,0,0}, - {32055,32057,32056 ,415,417,416 ,0,0,0}, {32059,32060,32058 ,419,420,418 ,0,0,0}, - {32057,32058,32060 ,417,418,420 ,0,0,0}, {32059,32061,32062 ,419,421,422 ,0,0,0}, - {32062,32060,32059 ,422,420,419 ,0,0,0}, {32063,32061,32064 ,423,421,424 ,0,0,0}, - {32061,32063,32062 ,421,423,422 ,0,0,0}, {32065,32066,32064 ,425,426,424 ,0,0,0}, - {32063,32064,32066 ,423,424,426 ,0,0,0}, {32067,32068,32066 ,427,427,426 ,0,0,0}, - {32066,32065,32067 ,426,425,427 ,0,0,0}, {32039,32038,32069 ,399,398,428 ,0,0,0}, - {32069,32070,32071 ,428,429,430 ,0,0,0}, {32070,32069,32038 ,429,428,398 ,0,0,0}, - {32072,32073,32070 ,431,432,429 ,0,0,0}, {32071,32070,32073 ,430,429,432 ,0,0,0}, - {32072,32074,32075 ,431,433,434 ,0,0,0}, {32075,32073,32072 ,434,432,431 ,0,0,0}, - {32076,32074,32077 ,435,433,436 ,0,0,0}, {32074,32076,32075 ,433,435,434 ,0,0,0}, - {32078,32079,32077 ,437,438,436 ,0,0,0}, {32076,32077,32079 ,435,436,438 ,0,0,0}, - {32078,32080,32081 ,437,439,440 ,0,0,0}, {32081,32079,32078 ,440,438,437 ,0,0,0}, - {32081,32082,32083 ,440,441,442 ,0,0,0}, {32082,32081,32080 ,441,440,439 ,0,0,0}, - {32084,32083,32085 ,443,442,444 ,0,0,0}, {32082,32085,32083 ,441,444,442 ,0,0,0}, - {32085,32086,32087 ,444,445,446 ,0,0,0}, {32087,32084,32085 ,446,443,444 ,0,0,0}, - {32088,32086,32089 ,447,445,448 ,0,0,0}, {32086,32088,32087 ,445,447,446 ,0,0,0}, - {32090,32091,32089 ,449,450,448 ,0,0,0}, {32088,32089,32091 ,447,448,450 ,0,0,0}, - {32090,32092,32093 ,449,451,452 ,0,0,0}, {32093,32091,32090 ,452,450,449 ,0,0,0}, - {32094,32092,32095 ,453,451,454 ,0,0,0}, {32092,32094,32093 ,451,453,452 ,0,0,0}, - {32095,32096,32094 ,454,455,453 ,0,0,0}, {32094,32096,32097 ,453,455,456 ,0,0,0}, - {32098,32099,32100 ,457,458,459 ,0,0,0}, {32098,32100,32101 ,457,459,460 ,0,0,0}, - {32102,31848,31847 ,461,273,273 ,0,0,0}, {32103,32104,32105 ,462,463,464 ,0,0,0}, - {32106,32107,32108 ,465,466,467 ,0,0,0}, {32109,32110,32111 ,468,469,470 ,0,0,0}, - {32112,32113,32114 ,471,472,473 ,0,0,0}, {32115,32116,32117 ,474,475,476 ,0,0,0}, - {32118,32119,32120 ,477,478,479 ,0,0,0}, {32121,32122,32123 ,480,481,482 ,0,0,0}, - {32121,32124,32116 ,480,483,475 ,0,0,0}, {32125,32122,32126 ,484,481,485 ,0,0,0}, - {32122,32125,32123 ,481,484,482 ,0,0,0}, {32127,32128,32126 ,486,487,485 ,0,0,0}, - {32125,32126,32128 ,484,485,487 ,0,0,0}, {32129,32130,32128 ,488,488,487 ,0,0,0}, - {32128,32127,32129 ,487,486,488 ,0,0,0}, {32117,32116,32124 ,476,475,483 ,0,0,0}, - {32121,32123,32124 ,480,482,483 ,0,0,0}, {32118,32115,32119 ,477,474,478 ,0,0,0}, - {32115,32117,32119 ,474,476,478 ,0,0,0}, {32111,32118,32109 ,470,477,468 ,0,0,0}, - {32118,32120,32109 ,477,479,468 ,0,0,0}, {32114,32113,32110 ,473,472,469 ,0,0,0}, - {32114,32110,32109 ,473,469,468 ,0,0,0}, {32112,32104,32103 ,471,463,462 ,0,0,0}, - {32112,32103,32113 ,471,462,472 ,0,0,0}, {32105,32107,32106 ,464,466,465 ,0,0,0}, - {32104,32107,32105 ,463,466,464 ,0,0,0}, {32102,32108,32131 ,461,467,489 ,0,0,0}, - {32106,32108,32102 ,465,467,461 ,0,0,0}, {31848,32102,32131 ,273,461,489 ,0,0,0}, - {32132,32133,32134 ,490,491,492 ,0,0,0}, {32135,32136,32133 ,493,494,491 ,0,0,0}, - {32137,32138,32139 ,495,496,497 ,0,0,0}, {32137,32132,32134 ,495,490,492 ,0,0,0}, - {32140,32141,32142 ,498,499,500 ,0,0,0}, {32139,32132,32137 ,497,490,495 ,0,0,0}, - {32138,32142,32141 ,496,500,499 ,0,0,0}, {32143,32140,32142 ,501,498,500 ,0,0,0}, - {32139,32138,32141 ,497,496,499 ,0,0,0}, {32144,32145,32146 ,502,503,504 ,0,0,0}, - {32147,32144,32146 ,505,502,504 ,0,0,0}, {32148,32143,32145 ,506,501,503 ,0,0,0}, - {32145,32144,32148 ,503,502,506 ,0,0,0}, {32146,32149,32147 ,504,507,505 ,0,0,0}, - {32143,32148,32140 ,501,506,498 ,0,0,0}, {32147,32149,32150 ,505,507,508 ,0,0,0}, - {32134,32133,32136 ,492,491,494 ,0,0,0}, {32151,32150,32149 ,508,508,507 ,0,0,0}, - {32135,32152,32153 ,493,509,510 ,0,0,0}, {32153,32136,32135 ,510,494,493 ,0,0,0}, - {32154,32152,32155 ,511,509,512 ,0,0,0}, {32152,32154,32153 ,509,511,510 ,0,0,0}, - {32156,32157,32155 ,513,514,512 ,0,0,0}, {32154,32155,32157 ,511,512,514 ,0,0,0}, - {32156,32158,32159 ,513,515,516 ,0,0,0}, {32159,32157,32156 ,516,514,513 ,0,0,0}, - {32160,32158,32161 ,517,515,518 ,0,0,0}, {32158,32160,32159 ,515,517,516 ,0,0,0}, - {32162,32163,32161 ,519,520,518 ,0,0,0}, {32160,32161,32163 ,517,518,520 ,0,0,0}, - {32162,32164,32165 ,519,521,522 ,0,0,0}, {32165,32163,32162 ,522,520,519 ,0,0,0}, - {32166,32164,32167 ,523,521,524 ,0,0,0}, {32164,32166,32165 ,521,523,522 ,0,0,0}, - {32166,32167,32168 ,523,524,525 ,0,0,0}, {32168,32167,32169 ,525,524,525 ,0,0,0}, - {32170,31820,31819 ,526,527,247 ,0,0,0}, {32171,32172,32173 ,528,529,530 ,0,0,0}, - {32174,32175,32176 ,531,532,533 ,0,0,0}, {32177,32178,32179 ,534,535,536 ,0,0,0}, - {32180,32181,32182 ,537,538,539 ,0,0,0}, {32183,32184,32185 ,540,541,542 ,0,0,0}, - {32186,32183,32179 ,543,540,536 ,0,0,0}, {32187,32185,32188 ,544,542,545 ,0,0,0}, - {32184,32188,32185 ,541,545,542 ,0,0,0}, {32189,32190,32187 ,546,546,544 ,0,0,0}, - {32187,32188,32189 ,544,545,546 ,0,0,0}, {32178,32186,32179 ,535,543,536 ,0,0,0}, - {32186,32184,32183 ,543,541,540 ,0,0,0}, {32182,32181,32177 ,539,538,534 ,0,0,0}, - {32181,32178,32177 ,538,535,534 ,0,0,0}, {32171,32173,32180 ,528,530,537 ,0,0,0}, - {32171,32180,32182 ,528,537,539 ,0,0,0}, {32172,32175,32174 ,529,532,531 ,0,0,0}, - {32172,32174,32173 ,529,531,530 ,0,0,0}, {32176,32191,32170 ,533,547,526 ,0,0,0}, - {32175,32191,32176 ,532,547,533 ,0,0,0}, {31820,32170,32191 ,527,526,547 ,0,0,0}, - {32192,32193,32194 ,548,549,550 ,0,0,0}, {32195,32196,32193 ,551,552,549 ,0,0,0}, - {32197,32198,32199 ,553,554,555 ,0,0,0}, {32197,32192,32194 ,553,548,550 ,0,0,0}, - {32200,32201,32202 ,556,557,558 ,0,0,0}, {32199,32192,32197 ,555,548,553 ,0,0,0}, - {32198,32202,32201 ,554,558,557 ,0,0,0}, {32203,32200,32202 ,559,556,558 ,0,0,0}, - {32199,32198,32201 ,555,554,557 ,0,0,0}, {32204,32205,32206 ,560,561,562 ,0,0,0}, - {32207,32204,32206 ,563,560,562 ,0,0,0}, {32208,32203,32205 ,564,559,561 ,0,0,0}, - {32205,32204,32208 ,561,560,564 ,0,0,0}, {32206,32209,32207 ,562,565,563 ,0,0,0}, - {32203,32208,32200 ,559,564,556 ,0,0,0}, {32207,32209,32210 ,563,565,508 ,0,0,0}, - {32194,32193,32196 ,550,549,552 ,0,0,0}, {32211,32210,32209 ,508,508,565 ,0,0,0}, - {32195,32212,32213 ,551,566,567 ,0,0,0}, {32213,32196,32195 ,567,552,551 ,0,0,0}, - {32214,32212,32215 ,568,566,569 ,0,0,0}, {32212,32214,32213 ,566,568,567 ,0,0,0}, - {32216,32217,32215 ,570,571,569 ,0,0,0}, {32214,32215,32217 ,568,569,571 ,0,0,0}, - {32216,32218,32219 ,570,572,573 ,0,0,0}, {32219,32217,32216 ,573,571,570 ,0,0,0}, - {32220,32218,32221 ,574,572,575 ,0,0,0}, {32218,32220,32219 ,572,574,573 ,0,0,0}, - {32222,32223,32221 ,576,577,575 ,0,0,0}, {32220,32221,32223 ,574,575,577 ,0,0,0}, - {32222,32224,32225 ,576,578,579 ,0,0,0}, {32225,32223,32222 ,579,577,576 ,0,0,0}, - {32226,32224,32227 ,580,578,581 ,0,0,0}, {32224,32226,32225 ,578,580,579 ,0,0,0}, - {32226,32227,32228 ,580,581,525 ,0,0,0}, {32228,32227,32229 ,525,581,525 ,0,0,0}, - {32230,31792,31791 ,582,221,221 ,0,0,0}, {32231,32232,32233 ,583,584,585 ,0,0,0}, - {32234,32235,32236 ,586,587,588 ,0,0,0}, {32237,32238,32239 ,589,590,591 ,0,0,0}, - {32240,32241,32242 ,592,593,594 ,0,0,0}, {32243,32244,32245 ,595,596,597 ,0,0,0}, - {32246,32247,32248 ,598,599,600 ,0,0,0}, {32249,32250,32251 ,601,602,603 ,0,0,0}, - {32249,32252,32244 ,601,604,596 ,0,0,0}, {32253,32250,32254 ,605,602,606 ,0,0,0}, - {32250,32253,32251 ,602,605,603 ,0,0,0}, {32255,32256,32254 ,607,608,606 ,0,0,0}, - {32253,32254,32256 ,605,606,608 ,0,0,0}, {32257,32258,32256 ,546,546,608 ,0,0,0}, - {32256,32255,32257 ,608,607,546 ,0,0,0}, {32245,32244,32252 ,597,596,604 ,0,0,0}, - {32249,32251,32252 ,601,603,604 ,0,0,0}, {32246,32243,32247 ,598,595,599 ,0,0,0}, - {32243,32245,32247 ,595,597,599 ,0,0,0}, {32239,32246,32237 ,591,598,589 ,0,0,0}, - {32246,32248,32237 ,598,600,589 ,0,0,0}, {32242,32241,32238 ,594,593,590 ,0,0,0}, - {32242,32238,32237 ,594,590,589 ,0,0,0}, {32240,32232,32231 ,592,584,583 ,0,0,0}, - {32240,32231,32241 ,592,583,593 ,0,0,0}, {32233,32235,32234 ,585,587,586 ,0,0,0}, - {32232,32235,32233 ,584,587,585 ,0,0,0}, {32230,32236,32259 ,582,588,609 ,0,0,0}, - {32234,32236,32230 ,586,588,582 ,0,0,0}, {31792,32230,32259 ,221,582,609 ,0,0,0}, - {32260,32261,32262 ,610,611,610 ,0,0,0}, {32261,32260,32263 ,611,610,611 ,0,0,0}, - {32264,32265,32266 ,612,613,614 ,0,0,0}, {32267,32266,32268 ,615,614,616 ,0,0,0}, - {32265,32268,32266 ,613,616,614 ,0,0,0}, {32268,32269,32270 ,616,617,618 ,0,0,0}, - {32270,32267,32268 ,618,615,616 ,0,0,0}, {32271,32269,32272 ,619,617,620 ,0,0,0}, - {32269,32271,32270 ,617,619,618 ,0,0,0}, {32273,32274,32272 ,621,622,620 ,0,0,0}, - {32271,32272,32274 ,619,620,622 ,0,0,0}, {32273,32275,32276 ,621,623,624 ,0,0,0}, - {32276,32274,32273 ,624,622,621 ,0,0,0}, {32277,32275,32278 ,625,623,626 ,0,0,0}, - {32275,32277,32276 ,623,625,624 ,0,0,0}, {32279,32277,32280 ,627,625,628 ,0,0,0}, - {32278,32280,32277 ,626,628,625 ,0,0,0}, {32281,32282,32279 ,629,630,627 ,0,0,0}, - {32279,32280,32281 ,627,628,629 ,0,0,0}, {32283,32281,32284 ,631,629,632 ,0,0,0}, - {32281,32283,32282 ,629,631,630 ,0,0,0}, {32285,32286,32284 ,633,634,632 ,0,0,0}, - {32283,32284,32286 ,631,632,634 ,0,0,0}, {32285,32287,32288 ,633,635,636 ,0,0,0}, - {32288,32286,32285 ,636,634,633 ,0,0,0}, {32289,32287,32290 ,637,635,638 ,0,0,0}, - {32287,32289,32288 ,635,637,636 ,0,0,0}, {32291,32292,32290 ,639,640,638 ,0,0,0}, - {32289,32290,32292 ,637,638,640 ,0,0,0}, {32293,32294,32292 ,641,641,640 ,0,0,0}, - {32292,32291,32293 ,640,639,641 ,0,0,0}, {32265,32264,32295 ,613,612,642 ,0,0,0}, - {32295,32296,32297 ,642,643,644 ,0,0,0}, {32296,32295,32264 ,643,642,612 ,0,0,0}, - {32298,32299,32296 ,645,646,643 ,0,0,0}, {32297,32296,32299 ,644,643,646 ,0,0,0}, - {32298,32300,32301 ,645,647,648 ,0,0,0}, {32301,32299,32298 ,648,646,645 ,0,0,0}, - {32302,32300,32303 ,649,647,650 ,0,0,0}, {32300,32302,32301 ,647,649,648 ,0,0,0}, - {32304,32305,32303 ,651,652,650 ,0,0,0}, {32302,32303,32305 ,649,650,652 ,0,0,0}, - {32304,32306,32307 ,651,653,654 ,0,0,0}, {32307,32305,32304 ,654,652,651 ,0,0,0}, - {32307,32308,32309 ,654,655,656 ,0,0,0}, {32308,32307,32306 ,655,654,653 ,0,0,0}, - {32310,32309,32311 ,657,656,658 ,0,0,0}, {32308,32311,32309 ,655,658,656 ,0,0,0}, - {32311,32312,32313 ,658,659,660 ,0,0,0}, {32313,32310,32311 ,660,657,658 ,0,0,0}, - {32314,32312,32315 ,661,659,662 ,0,0,0}, {32312,32314,32313 ,659,661,660 ,0,0,0}, - {32316,32317,32315 ,663,664,662 ,0,0,0}, {32314,32315,32317 ,661,662,664 ,0,0,0}, - {32316,32318,32319 ,663,665,666 ,0,0,0}, {32319,32317,32316 ,666,664,663 ,0,0,0}, - {32320,32318,32321 ,667,665,668 ,0,0,0}, {32318,32320,32319 ,665,667,666 ,0,0,0}, - {32321,32322,32320 ,668,669,667 ,0,0,0}, {32320,32322,32323 ,667,669,670 ,0,0,0}, - {31767,32324,32325 ,671,672,672 ,0,0,0}, {32326,32327,32328 ,673,674,675 ,0,0,0}, - {32329,32330,32331 ,675,676,676 ,0,0,0}, {32332,32333,32334 ,677,678,677 ,0,0,0}, - {32335,32336,32337 ,679,679,678 ,0,0,0}, {32338,32339,32334 ,680,680,677 ,0,0,0}, - {32332,32334,32339 ,677,677,680 ,0,0,0}, {32338,32340,32341 ,680,396,396 ,0,0,0}, - {32341,32339,32338 ,396,680,680 ,0,0,0}, {32332,32337,32333 ,677,678,678 ,0,0,0}, - {32331,32330,32324 ,676,676,672 ,0,0,0}, {32337,32336,32333 ,678,679,678 ,0,0,0}, - {32335,32326,32336 ,679,673,679 ,0,0,0}, {32327,32329,32328 ,674,675,675 ,0,0,0}, - {32335,32327,32326 ,679,674,673 ,0,0,0}, {32328,32329,32331 ,675,675,676 ,0,0,0}, - {31767,32325,31764 ,671,672,681 ,0,0,0}, {32324,32330,32325 ,672,676,672 ,0,0,0}, - {31536,31537,32342 ,21,21,21 ,0,0,0}, {31536,32342,32343 ,21,21,21 ,0,0,0}, - {32344,32345,32346 ,682,683,684 ,0,0,0}, {32347,32348,32346 ,685,686,684 ,0,0,0}, - {32344,32346,32348 ,682,684,686 ,0,0,0}, {32347,32349,32350 ,685,687,688 ,0,0,0}, - {32350,32348,32347 ,688,686,685 ,0,0,0}, {32351,32349,32352 ,689,687,690 ,0,0,0}, - {32349,32351,32350 ,687,689,688 ,0,0,0}, {32353,32354,32352 ,691,692,690 ,0,0,0}, - {32351,32352,32354 ,689,690,692 ,0,0,0}, {32353,32355,32356 ,691,693,694 ,0,0,0}, - {32356,32354,32353 ,694,692,691 ,0,0,0}, {32357,32355,32358 ,695,693,696 ,0,0,0}, - {32355,32357,32356 ,693,695,694 ,0,0,0}, {32359,32360,32358 ,697,698,696 ,0,0,0}, - {32357,32358,32360 ,695,696,698 ,0,0,0}, {32359,32361,32362 ,697,699,700 ,0,0,0}, - {32362,32360,32359 ,700,698,697 ,0,0,0}, {32363,32361,32364 ,701,699,702 ,0,0,0}, - {32361,32363,32362 ,699,701,700 ,0,0,0}, {32365,32366,32364 ,641,703,702 ,0,0,0}, - {32363,32364,32366 ,701,702,703 ,0,0,0}, {32367,32366,32365 ,641,703,641 ,0,0,0}, - {32368,32345,32344 ,704,683,682 ,0,0,0}, {32369,32368,32370 ,705,704,706 ,0,0,0}, - {32368,32369,32345 ,704,705,683 ,0,0,0}, {32371,32372,32370 ,707,708,706 ,0,0,0}, - {32369,32370,32372 ,705,706,708 ,0,0,0}, {32371,32373,32374 ,707,709,710 ,0,0,0}, - {32374,32372,32371 ,710,708,707 ,0,0,0}, {32375,32373,32376 ,711,709,712 ,0,0,0}, - {32373,32375,32374 ,709,711,710 ,0,0,0}, {32377,32378,32376 ,713,714,712 ,0,0,0}, - {32375,32376,32378 ,711,712,714 ,0,0,0}, {32377,32379,32380 ,713,715,716 ,0,0,0}, - {32380,32378,32377 ,716,714,713 ,0,0,0}, {32381,32379,32382 ,717,715,718 ,0,0,0}, - {32379,32381,32380 ,715,717,716 ,0,0,0}, {32383,32384,32382 ,719,720,718 ,0,0,0}, - {32381,32382,32384 ,717,718,720 ,0,0,0}, {32383,32385,32386 ,719,721,722 ,0,0,0}, - {32386,32384,32383 ,722,720,719 ,0,0,0}, {32387,32385,32388 ,723,721,456 ,0,0,0}, - {32385,32387,32386 ,721,723,722 ,0,0,0}, {32387,32388,32389 ,723,456,724 ,0,0,0}, - {31556,31557,32390 ,21,725,725 ,0,0,0}, {31556,32390,32391 ,21,725,21 ,0,0,0}, - {31824,31559,31823 ,726,726,726 ,0,0,0}, {31610,32348,32392 ,727,727,726 ,0,0,0}, - {32184,32186,32393 ,726,726,726 ,0,0,0}, {32368,32344,31610 ,727,727,727 ,0,0,0}, - {31607,32368,31610 ,726,727,727 ,0,0,0}, {31574,32394,32395 ,726,726,726 ,0,0,0}, - {31766,31970,31763 ,726,726,726 ,0,0,0}, {32370,31607,31608 ,726,726,726 ,0,0,0}, - {32373,31603,31601 ,727,726,726 ,0,0,0}, {32396,32392,32350 ,726,726,726 ,0,0,0}, - {32397,32398,32399 ,726,726,726 ,0,0,0}, {32286,32400,32401 ,727,727,727 ,0,0,0}, - {32057,32402,32403 ,726,726,727 ,0,0,0}, {32396,32351,32404 ,726,726,726 ,0,0,0}, - {32405,32277,32406 ,726,726,726 ,0,0,0}, {32276,32405,32407 ,727,726,726 ,0,0,0}, - {32354,32408,32404 ,727,726,726 ,0,0,0}, {31601,31604,32376 ,726,727,726 ,0,0,0}, - {32409,31708,32271 ,726,727,726 ,0,0,0}, {32315,32312,31710 ,726,726,726 ,0,0,0}, - {32410,32408,32356 ,727,726,726 ,0,0,0}, {31595,32377,31604 ,727,726,727 ,0,0,0}, - {32411,32360,32412 ,727,727,727 ,0,0,0}, {32411,32410,32357 ,727,727,727 ,0,0,0}, - {32413,32412,32363 ,726,727,726 ,0,0,0}, {32362,32412,32360 ,726,727,727 ,0,0,0}, - {32414,32367,32415 ,727,726,726 ,0,0,0}, {32414,32413,32366 ,727,726,726 ,0,0,0}, - {32415,32416,32417 ,726,726,726 ,0,0,0}, {32418,32419,31624 ,726,726,727 ,0,0,0}, - {32382,31597,32383 ,726,727,726 ,0,0,0}, {32420,32421,32418 ,727,727,726 ,0,0,0}, - {32422,32416,32423 ,727,726,726 ,0,0,0}, {31617,31618,32424 ,727,726,726 ,0,0,0}, - {32030,31919,32034 ,726,726,726 ,0,0,0}, {32425,32426,32036 ,727,726,726 ,0,0,0}, - {32419,32427,32428 ,726,726,727 ,0,0,0}, {32022,31903,31902 ,726,726,727 ,0,0,0}, - {32429,32110,32430 ,726,726,728 ,0,0,0}, {32020,31875,31909 ,727,726,727 ,0,0,0}, - {32430,32113,32103 ,728,726,726 ,0,0,0}, {31645,31854,31627 ,728,726,726 ,0,0,0}, - {31648,31851,31853 ,726,728,726 ,0,0,0}, {31860,31631,31628 ,726,726,726 ,0,0,0}, - {32431,32432,32116 ,726,726,726 ,0,0,0}, {31631,31863,31629 ,726,726,726 ,0,0,0}, - {31871,31874,31924 ,726,726,727 ,0,0,0}, {32433,31641,31637 ,726,726,726 ,0,0,0}, - {31643,31640,32434 ,726,726,726 ,0,0,0}, {32435,32436,32101 ,727,726,726 ,0,0,0}, - {32164,31953,31956 ,726,726,726 ,0,0,0}, {32437,32096,31677 ,726,726,726 ,0,0,0}, - {32438,32439,32440 ,727,727,726 ,0,0,0}, {31660,32095,32092 ,726,727,726 ,0,0,0}, - {32441,32442,32068 ,727,726,727 ,0,0,0}, {32443,32062,32444 ,726,726,727 ,0,0,0}, - {31670,32085,31667 ,727,726,726 ,0,0,0}, {32445,32045,32048 ,727,726,726 ,0,0,0}, - {32038,32446,32447 ,727,726,726 ,0,0,0}, {31675,31672,32074 ,727,726,726 ,0,0,0}, - {31675,32072,32070 ,727,726,727 ,0,0,0}, {31673,32077,31672 ,726,727,726 ,0,0,0}, - {32078,31673,31669 ,727,726,726 ,0,0,0}, {32447,32070,32038 ,726,727,727 ,0,0,0}, - {32448,32446,32040 ,726,726,726 ,0,0,0}, {31667,32082,32080 ,726,727,726 ,0,0,0}, - {32041,32449,32448 ,727,726,726 ,0,0,0}, {32445,32449,32044 ,727,726,727 ,0,0,0}, - {31661,32086,31670 ,727,726,727 ,0,0,0}, {32050,32450,32451 ,726,727,727 ,0,0,0}, - {32451,32445,32048 ,727,727,726 ,0,0,0}, {32403,32452,32053 ,727,726,727 ,0,0,0}, - {32051,32452,32450 ,726,726,727 ,0,0,0}, {32453,32068,32442 ,727,727,726 ,0,0,0}, - {32063,32454,32444 ,726,726,727 ,0,0,0}, {32066,32068,32454 ,726,727,726 ,0,0,0}, - {32454,32068,32453 ,726,727,727 ,0,0,0}, {32060,32443,32402 ,726,726,726 ,0,0,0}, - {32063,32066,32454 ,726,726,726 ,0,0,0}, {31689,32442,32441 ,727,726,727 ,0,0,0}, - {32439,32455,31683 ,727,726,726 ,0,0,0}, {31689,32441,32456 ,727,727,726 ,0,0,0}, - {31683,31686,32439 ,726,727,727 ,0,0,0}, {32455,31682,31683 ,726,727,726 ,0,0,0}, - {32438,32440,32457 ,727,726,726 ,0,0,0}, {32458,32438,32457 ,726,727,726 ,0,0,0}, - {32459,32460,32101 ,726,726,726 ,0,0,0}, {32101,32458,32457 ,726,726,726 ,0,0,0}, - {32460,31882,32458 ,726,726,726 ,0,0,0}, {32101,32391,32461 ,726,727,726 ,0,0,0}, - {32162,31952,31953 ,726,726,726 ,0,0,0}, {32462,32100,32463 ,726,726,726 ,0,0,0}, - {32167,31956,32464 ,726,726,726 ,0,0,0}, {32105,32465,32103 ,726,726,726 ,0,0,0}, - {32465,32105,32466 ,726,726,726 ,0,0,0}, {31839,31656,31842 ,726,726,726 ,0,0,0}, - {32467,31845,32468 ,726,726,726 ,0,0,0}, {32468,31843,31657 ,726,726,726 ,0,0,0}, - {32469,31847,32467 ,726,726,726 ,0,0,0}, {31847,32469,32102 ,726,726,726 ,0,0,0}, - {31845,31843,32468 ,726,726,726 ,0,0,0}, {32106,32102,32469 ,726,726,726 ,0,0,0}, - {31845,32467,31847 ,726,726,726 ,0,0,0}, {31657,31843,31842 ,726,726,726 ,0,0,0}, - {32106,32469,32466 ,726,726,726 ,0,0,0}, {31654,31656,31837 ,726,726,726 ,0,0,0}, - {32431,32118,32470 ,726,729,726 ,0,0,0}, {31836,31832,31651 ,726,726,726 ,0,0,0}, - {31857,31628,31627 ,726,726,726 ,0,0,0}, {32431,32115,32118 ,726,726,729 ,0,0,0}, - {31629,32471,31638 ,726,728,726 ,0,0,0}, {32432,32472,32121 ,726,726,726 ,0,0,0}, - {32433,32473,31641 ,726,726,726 ,0,0,0}, {32471,32433,31635 ,728,726,726 ,0,0,0}, - {31866,31876,31928 ,727,727,727 ,0,0,0}, {31928,31931,31866 ,727,727,727 ,0,0,0}, - {31868,31866,31931 ,726,727,727 ,0,0,0}, {32474,32176,32170 ,726,726,726 ,0,0,0}, - {31931,31921,31868 ,727,726,726 ,0,0,0}, {32027,32020,31907 ,726,727,726 ,0,0,0}, - {31920,31871,31924 ,727,726,727 ,0,0,0}, {31921,31923,31869 ,726,726,727 ,0,0,0}, - {31933,31877,31880 ,726,726,726 ,0,0,0}, {32126,32122,32475 ,726,726,726 ,0,0,0}, - {31875,31871,31920 ,726,726,727 ,0,0,0}, {31947,32158,32156 ,726,726,726 ,0,0,0}, - {32476,32477,32129 ,726,726,726 ,0,0,0}, {32475,32122,32472 ,726,726,726 ,0,0,0}, - {31923,31874,31869 ,726,726,727 ,0,0,0}, {31869,31868,31921 ,727,726,726 ,0,0,0}, - {31946,31947,32156 ,726,726,726 ,0,0,0}, {32127,32476,32129 ,726,726,726 ,0,0,0}, - {32473,32478,32479 ,726,726,726 ,0,0,0}, {31640,31641,32434 ,726,726,726 ,0,0,0}, - {32480,31554,32169 ,726,726,726 ,0,0,0}, {32478,32462,32463 ,726,726,726 ,0,0,0}, - {32478,32463,32479 ,726,726,726 ,0,0,0}, {32158,31950,32161 ,726,726,726 ,0,0,0}, - {31929,31928,31876 ,726,727,727 ,0,0,0}, {32140,31965,32141 ,726,728,728 ,0,0,0}, - {32141,31962,32139 ,728,728,726 ,0,0,0}, {32027,31906,32024 ,726,726,726 ,0,0,0}, - {31941,32133,31959 ,726,726,728 ,0,0,0}, {32024,31906,31903 ,726,726,726 ,0,0,0}, - {32022,32024,31903 ,726,726,726 ,0,0,0}, {31914,32029,32032 ,727,726,726 ,0,0,0}, - {31902,32032,32022 ,727,726,726 ,0,0,0}, {32006,32481,32227 ,726,726,726 ,0,0,0}, - {32032,31902,31914 ,726,727,727 ,0,0,0}, {32482,32483,31534 ,726,726,726 ,0,0,0}, - {32484,32485,32486 ,726,726,726 ,0,0,0}, {32487,32486,31544 ,726,726,726 ,0,0,0}, - {32488,32188,32489 ,726,726,726 ,0,0,0}, {32485,32484,32490 ,726,726,726 ,0,0,0}, - {31817,31590,31819 ,726,726,726 ,0,0,0}, {31569,32394,31574 ,726,726,726 ,0,0,0}, - {32491,32492,32174 ,726,726,726 ,0,0,0}, {32474,32170,31590 ,726,726,726 ,0,0,0}, - {32174,32176,32491 ,726,726,726 ,0,0,0}, {32474,32491,32176 ,726,726,726 ,0,0,0}, - {32493,32173,32492 ,726,726,726 ,0,0,0}, {32173,32174,32492 ,726,726,726 ,0,0,0}, - {32493,32494,32180 ,726,726,726 ,0,0,0}, {32170,31819,31590 ,726,726,726 ,0,0,0}, - {31589,31816,31587 ,726,726,726 ,0,0,0}, {32494,32495,32181 ,726,728,726 ,0,0,0}, - {31581,31821,31578 ,726,726,728 ,0,0,0}, {31811,31584,31813 ,726,726,726 ,0,0,0}, - {31563,31831,31561 ,726,726,726 ,0,0,0}, {31560,31827,31829 ,726,726,726 ,0,0,0}, - {32241,32496,32497 ,726,726,726 ,0,0,0}, {32394,31567,32498 ,726,726,728 ,0,0,0}, - {32498,31570,31561 ,728,726,726 ,0,0,0}, {32393,32489,32184 ,726,726,726 ,0,0,0}, - {31530,32499,31532 ,726,726,726 ,0,0,0}, {32189,32500,32501 ,726,726,726 ,0,0,0}, - {32502,32503,32504 ,727,727,726 ,0,0,0}, {31997,32218,32216 ,726,726,726 ,0,0,0}, - {31937,32505,31529 ,726,726,726 ,0,0,0}, {32227,32481,32229 ,726,726,726 ,0,0,0}, - {31534,32483,32506 ,726,726,726 ,0,0,0}, {32221,32002,32222 ,726,726,726 ,0,0,0}, - {31774,32507,32508 ,726,726,727 ,0,0,0}, {31758,31971,31760 ,727,727,726 ,0,0,0}, - {31768,31981,31758 ,727,727,727 ,0,0,0}, {31767,31763,31891 ,726,726,727 ,0,0,0}, - {31760,31971,31973 ,726,727,726 ,0,0,0}, {31885,32331,31888 ,726,726,727 ,0,0,0}, - {32193,31991,32195 ,726,726,726 ,0,0,0}, {32326,31884,31896 ,726,726,727 ,0,0,0}, - {31722,32509,32510 ,727,726,726 ,0,0,0}, {32511,32260,32512 ,726,726,726 ,0,0,0}, - {31899,32334,32333 ,726,726,726 ,0,0,0}, {31901,32513,32338 ,726,726,726 ,0,0,0}, - {32397,32399,32514 ,726,726,728 ,0,0,0}, {32515,32516,32263 ,726,726,726 ,0,0,0}, - {32398,32517,32399 ,726,726,726 ,0,0,0}, {32254,32250,32518 ,726,728,726 ,0,0,0}, - {31741,32519,32520 ,726,726,726 ,0,0,0}, {31798,31727,31797 ,726,726,726 ,0,0,0}, - {31807,32519,31738 ,726,726,726 ,0,0,0}, {32521,32520,32517 ,726,726,726 ,0,0,0}, - {31787,31749,31789 ,726,726,726 ,0,0,0}, {31793,31795,31729 ,726,726,726 ,0,0,0}, - {32231,32233,32496 ,726,726,726 ,0,0,0}, {32234,31755,32233 ,726,726,726 ,0,0,0}, - {32522,32238,32497 ,726,728,726 ,0,0,0}, {32241,32497,32238 ,726,726,728 ,0,0,0}, - {32239,32238,32522 ,726,728,726 ,0,0,0}, {32496,32241,32231 ,726,726,726 ,0,0,0}, - {32496,32233,31755 ,726,726,726 ,0,0,0}, {32522,32523,32239 ,726,726,726 ,0,0,0}, - {32524,32243,32523 ,726,726,726 ,0,0,0}, {32523,32246,32239 ,726,726,726 ,0,0,0}, - {32524,32525,32244 ,726,728,726 ,0,0,0}, {32234,32230,31754 ,726,726,726 ,0,0,0}, - {31781,31743,31783 ,726,728,726 ,0,0,0}, {31791,31789,31752 ,726,726,726 ,0,0,0}, - {31726,31776,31793 ,726,726,726 ,0,0,0}, {31743,31780,31725 ,728,726,726 ,0,0,0}, - {31798,31736,31727 ,726,726,726 ,0,0,0}, {31803,31735,31733 ,726,726,726 ,0,0,0}, - {31735,31807,31739 ,726,726,726 ,0,0,0}, {32526,32518,32250 ,726,726,728 ,0,0,0}, - {31801,31733,31736 ,726,726,726 ,0,0,0}, {32527,32255,32518 ,726,726,726 ,0,0,0}, - {32398,32528,32517 ,726,726,726 ,0,0,0}, {32529,32530,32531 ,726,726,726 ,0,0,0}, - {31524,31522,32210 ,726,726,726 ,0,0,0}, {31526,32207,31519 ,726,726,726 ,0,0,0}, - {32311,31692,31691 ,726,726,727 ,0,0,0}, {32532,32294,32533 ,727,726,726 ,0,0,0}, - {31898,32336,31896 ,727,726,727 ,0,0,0}, {32534,32514,32263 ,726,728,726 ,0,0,0}, - {32514,32534,32397 ,728,726,726 ,0,0,0}, {32263,31524,32534 ,726,726,726 ,0,0,0}, - {32292,32535,32289 ,726,726,726 ,0,0,0}, {32303,31702,31693 ,726,727,727 ,0,0,0}, - {32271,31708,32270 ,726,727,726 ,0,0,0}, {32282,32536,32406 ,726,727,726 ,0,0,0}, - {32267,32270,31705 ,726,726,726 ,0,0,0}, {32409,32274,32407 ,726,726,726 ,0,0,0}, - {31705,31706,32266 ,726,726,726 ,0,0,0}, {32296,31701,31699 ,726,726,726 ,0,0,0}, - {31699,32298,32296 ,726,726,726 ,0,0,0}, {32282,32406,32279 ,726,726,726 ,0,0,0}, - {31702,32300,31699 ,727,727,726 ,0,0,0}, {32536,32283,32401 ,727,726,727 ,0,0,0}, - {31693,31695,32304 ,727,727,726 ,0,0,0}, {32400,32288,32535 ,727,726,726 ,0,0,0}, - {32308,32306,31692 ,726,726,726 ,0,0,0}, {32537,32538,32533 ,726,726,726 ,0,0,0}, - {31715,32316,31713 ,727,727,726 ,0,0,0}, {32539,32540,32541 ,726,726,727 ,0,0,0}, - {32542,32537,32540 ,727,726,726 ,0,0,0}, {32543,32541,32544 ,726,727,727 ,0,0,0}, - {32544,32541,32540 ,727,727,726 ,0,0,0}, {32326,31896,32336 ,726,727,726 ,0,0,0}, - {32510,32541,32543 ,726,727,726 ,0,0,0}, {31719,31721,32322 ,727,726,727 ,0,0,0}, - {31898,31899,32333 ,727,726,726 ,0,0,0}, {31722,32510,32545 ,727,726,726 ,0,0,0}, - {32544,32546,32543 ,727,727,726 ,0,0,0}, {32509,32541,32510 ,726,727,726 ,0,0,0}, - {32340,32547,32511 ,726,726,726 ,0,0,0}, {32546,32511,32512 ,727,726,726 ,0,0,0}, - {32546,32512,32543 ,727,726,726 ,0,0,0}, {31898,32333,32336 ,727,726,726 ,0,0,0}, - {31884,32328,31885 ,726,726,726 ,0,0,0}, {32331,31885,32328 ,726,726,726 ,0,0,0}, - {32328,31884,32326 ,726,726,726 ,0,0,0}, {31889,31767,31891 ,727,726,727 ,0,0,0}, - {31888,32324,31889 ,727,727,727 ,0,0,0}, {31763,31970,31891 ,726,726,727 ,0,0,0}, - {32012,32201,32015 ,726,728,726 ,0,0,0}, {31974,31970,31766 ,726,726,726 ,0,0,0}, - {31973,31974,31761 ,726,726,727 ,0,0,0}, {31761,31974,31766 ,727,726,726 ,0,0,0}, - {31973,31761,31760 ,726,727,726 ,0,0,0}, {32503,32502,32548 ,727,727,727 ,0,0,0}, - {31769,31978,31768 ,726,726,727 ,0,0,0}, {31758,31981,31971 ,727,727,727 ,0,0,0}, - {32549,32550,32428 ,727,727,727 ,0,0,0}, {31916,32029,31914 ,726,726,727 ,0,0,0}, - {32030,31917,31919 ,726,726,726 ,0,0,0}, {31916,32030,32029 ,726,726,726 ,0,0,0}, - {31919,32425,32034 ,726,727,726 ,0,0,0}, {32551,32552,32036 ,726,726,726 ,0,0,0}, - {32428,31624,32419 ,727,727,726 ,0,0,0}, {32553,32418,32421 ,727,726,727 ,0,0,0}, - {32418,32553,32419 ,726,727,726 ,0,0,0}, {32423,32421,32420 ,726,727,727 ,0,0,0}, - {31612,32554,32388 ,726,726,726 ,0,0,0}, {32101,32100,31556 ,726,726,726 ,0,0,0}, - {32555,32169,32167 ,726,726,726 ,0,0,0}, {31880,31882,32556 ,726,726,726 ,0,0,0}, - {32101,31556,32391 ,726,726,727 ,0,0,0}, {31880,32557,31933 ,726,726,726 ,0,0,0}, - {32101,32461,32435 ,726,726,727 ,0,0,0}, {32458,32101,32460 ,726,726,726 ,0,0,0}, - {32436,32459,32101 ,726,726,726 ,0,0,0}, {32558,32556,31882 ,726,726,726 ,0,0,0}, - {32460,32558,31882 ,726,726,726 ,0,0,0}, {32556,32557,31880 ,726,726,726 ,0,0,0}, - {31929,31877,31933 ,726,726,726 ,0,0,0}, {31929,31876,31877 ,726,727,726 ,0,0,0}, - {32156,32155,31946 ,726,726,726 ,0,0,0}, {32155,32152,31944 ,726,726,726 ,0,0,0}, - {32152,32135,31940 ,726,726,726 ,0,0,0}, {32135,32133,31941 ,726,726,726 ,0,0,0}, - {32132,31959,32133 ,726,728,726 ,0,0,0}, {31923,31924,31874 ,726,727,726 ,0,0,0}, - {31946,32155,31944 ,726,726,726 ,0,0,0}, {31920,31909,31875 ,727,727,726 ,0,0,0}, - {31940,31944,32152 ,726,726,726 ,0,0,0}, {31960,32132,32139 ,726,726,726 ,0,0,0}, - {31909,31907,32020 ,727,726,727 ,0,0,0}, {31940,32135,31941 ,726,726,726 ,0,0,0}, - {32148,31966,32140 ,726,726,726 ,0,0,0}, {31907,31906,32027 ,726,726,726 ,0,0,0}, - {31959,32132,31960 ,728,726,726 ,0,0,0}, {31546,31968,32144 ,726,726,726 ,0,0,0}, - {31965,31962,32141 ,728,728,728 ,0,0,0}, {32147,32150,31539 ,726,726,726 ,0,0,0}, - {31966,31965,32140 ,726,728,726 ,0,0,0}, {31540,32150,31542 ,726,726,726 ,0,0,0}, - {31968,31966,32148 ,726,726,726 ,0,0,0}, {32419,32553,32559 ,726,727,726 ,0,0,0}, - {31916,31917,32030 ,726,726,726 ,0,0,0}, {32552,32559,32553 ,726,726,727 ,0,0,0}, - {32551,32036,32426 ,726,726,726 ,0,0,0}, {32425,32036,32034 ,727,726,726 ,0,0,0}, - {32552,32551,32559 ,726,726,726 ,0,0,0}, {32560,32548,32427 ,726,727,726 ,0,0,0}, - {32502,32504,32343 ,727,726,727 ,0,0,0}, {32419,32560,32427 ,726,726,726 ,0,0,0}, - {31623,32561,31621 ,726,727,727 ,0,0,0}, {32504,31938,32343 ,726,727,727 ,0,0,0}, - {32562,32563,31774 ,726,726,726 ,0,0,0}, {32000,32221,32218 ,726,726,726 ,0,0,0}, - {32224,32222,32003 ,726,726,728 ,0,0,0}, {31544,32564,32487 ,726,726,726 ,0,0,0}, - {31546,32144,32147 ,726,726,726 ,0,0,0}, {32229,32506,32483 ,726,726,726 ,0,0,0}, - {32490,32484,32565 ,726,726,726 ,0,0,0}, {32564,31544,31542 ,726,726,726 ,0,0,0}, - {32564,31542,32150 ,726,726,726 ,0,0,0}, {31540,31539,32150 ,726,726,726 ,0,0,0}, - {31539,31546,32147 ,726,726,726 ,0,0,0}, {31968,32148,32144 ,726,726,726 ,0,0,0}, - {31962,31960,32139 ,728,726,726 ,0,0,0}, {31950,31952,32161 ,726,726,726 ,0,0,0}, - {31947,31950,32158 ,726,726,726 ,0,0,0}, {32162,31953,32164 ,726,726,726 ,0,0,0}, - {32161,31952,32162 ,726,726,726 ,0,0,0}, {32164,31956,32167 ,726,726,726 ,0,0,0}, - {32464,32555,32167 ,726,726,726 ,0,0,0}, {32555,32480,32169 ,726,726,726 ,0,0,0}, - {32462,32169,31554 ,726,726,726 ,0,0,0}, {31552,32100,31554 ,726,726,726 ,0,0,0}, - {32462,31554,32100 ,726,726,726 ,0,0,0}, {31549,32100,31550 ,726,726,726 ,0,0,0}, - {32100,31552,31550 ,726,726,726 ,0,0,0}, {31556,32100,31549 ,726,726,726 ,0,0,0}, - {31997,32216,31996 ,726,726,726 ,0,0,0}, {31938,31937,31536 ,727,726,726 ,0,0,0}, - {31769,31983,31979 ,726,726,726 ,0,0,0}, {31938,31536,32343 ,727,726,727 ,0,0,0}, - {31983,31772,32563 ,726,726,726 ,0,0,0}, {32503,32548,32560 ,727,727,726 ,0,0,0}, - {31623,32428,32550 ,726,727,727 ,0,0,0}, {32549,32508,32507 ,727,727,726 ,0,0,0}, - {32549,32507,32550 ,727,726,727 ,0,0,0}, {32508,32562,31774 ,727,726,726 ,0,0,0}, - {32563,31772,31774 ,726,726,726 ,0,0,0}, {31983,31769,31772 ,726,726,726 ,0,0,0}, - {31978,31769,31979 ,726,726,726 ,0,0,0}, {31978,31981,31768 ,726,727,727 ,0,0,0}, - {32215,31994,31996 ,726,726,726 ,0,0,0}, {32212,31990,31994 ,726,726,726 ,0,0,0}, - {32195,31991,31990 ,726,726,726 ,0,0,0}, {32193,32009,31991 ,726,729,726 ,0,0,0}, - {32216,32215,31996 ,726,726,726 ,0,0,0}, {32192,32010,32009 ,726,726,729 ,0,0,0}, - {32215,32212,31994 ,726,726,726 ,0,0,0}, {32199,32012,32010 ,726,726,726 ,0,0,0}, - {31889,32324,31767 ,727,727,726 ,0,0,0}, {32212,32195,31990 ,726,726,726 ,0,0,0}, - {32200,32016,32015 ,726,726,726 ,0,0,0}, {31888,32331,32324 ,727,726,727 ,0,0,0}, - {32193,32192,32009 ,726,726,729 ,0,0,0}, {32018,32016,32208 ,726,726,726 ,0,0,0}, - {32192,32199,32010 ,726,726,726 ,0,0,0}, {32207,31526,32204 ,726,726,726 ,0,0,0}, - {32015,32201,32200 ,726,728,726 ,0,0,0}, {31987,32263,32260 ,727,726,726 ,0,0,0}, - {32200,32208,32016 ,726,726,726 ,0,0,0}, {32338,32566,32340 ,726,726,726 ,0,0,0}, - {31901,32334,31899 ,726,726,726 ,0,0,0}, {32513,32567,32338 ,726,727,726 ,0,0,0}, - {32334,31901,32338 ,726,726,726 ,0,0,0}, {32567,32566,32338 ,727,726,726 ,0,0,0}, - {32511,32547,32260 ,726,726,726 ,0,0,0}, {32566,32547,32340 ,726,726,726 ,0,0,0}, - {32568,32260,32569 ,726,726,727 ,0,0,0}, {32260,32547,32569 ,726,726,727 ,0,0,0}, - {32570,32260,32571 ,726,726,726 ,0,0,0}, {32260,32568,32571 ,726,726,726 ,0,0,0}, - {32260,32570,31987 ,726,726,727 ,0,0,0}, {31989,32263,31987 ,726,726,727 ,0,0,0}, - {31520,32207,32210 ,726,726,726 ,0,0,0}, {32263,32572,32515 ,726,726,726 ,0,0,0}, - {32263,31989,32572 ,726,726,726 ,0,0,0}, {31524,32210,32534 ,726,726,726 ,0,0,0}, - {32516,31524,32263 ,726,726,726 ,0,0,0}, {31522,31520,32210 ,726,726,726 ,0,0,0}, - {31520,31519,32207 ,726,726,726 ,0,0,0}, {32018,32204,31526 ,726,726,726 ,0,0,0}, - {32018,32208,32204 ,726,726,726 ,0,0,0}, {32012,32199,32201 ,726,726,728 ,0,0,0}, - {32000,32002,32221 ,726,726,726 ,0,0,0}, {31997,32000,32218 ,726,726,726 ,0,0,0}, - {32002,32003,32222 ,726,728,726 ,0,0,0}, {32003,32006,32224 ,728,726,726 ,0,0,0}, - {32227,32224,32006 ,726,726,726 ,0,0,0}, {32573,32229,32481 ,726,726,726 ,0,0,0}, - {32487,32484,32486 ,726,726,726 ,0,0,0}, {32573,32506,32229 ,726,726,726 ,0,0,0}, - {31576,31532,32574 ,726,726,726 ,0,0,0}, {32499,31530,32505 ,726,726,726 ,0,0,0}, - {32574,31532,32499 ,726,726,726 ,0,0,0}, {31937,31529,31536 ,726,726,726 ,0,0,0}, - {32505,31530,31529 ,726,726,726 ,0,0,0}, {32526,32249,32525 ,726,726,728 ,0,0,0}, - {31748,31786,31746 ,726,726,726 ,0,0,0}, {31729,31795,31727 ,726,726,726 ,0,0,0}, - {32243,32246,32523 ,726,726,726 ,0,0,0}, {32244,32243,32524 ,726,726,726 ,0,0,0}, - {32249,32244,32525 ,726,726,728 ,0,0,0}, {32250,32249,32526 ,728,726,726 ,0,0,0}, - {32257,32255,32527 ,726,726,726 ,0,0,0}, {32255,32254,32518 ,726,726,726 ,0,0,0}, - {32530,32529,32528 ,726,726,726 ,0,0,0}, {32257,32575,32531 ,726,726,726 ,0,0,0}, - {32575,32257,32527 ,726,726,726 ,0,0,0}, {32576,32529,32531 ,726,726,726 ,0,0,0}, - {32575,32576,32531 ,726,726,726 ,0,0,0}, {32528,32398,32530 ,726,726,726 ,0,0,0}, - {32517,32520,32399 ,726,726,726 ,0,0,0}, {31741,32520,32521 ,726,726,726 ,0,0,0}, - {31738,32519,31741 ,726,726,726 ,0,0,0}, {31739,31807,31738 ,726,726,726 ,0,0,0}, - {31803,31804,31735 ,726,726,726 ,0,0,0}, {31807,31735,31804 ,726,726,726 ,0,0,0}, - {31801,31803,31733 ,726,726,726 ,0,0,0}, {31798,31801,31736 ,726,726,726 ,0,0,0}, - {31795,31797,31727 ,726,726,726 ,0,0,0}, {31793,31729,31726 ,726,726,726 ,0,0,0}, - {31776,31726,31725 ,726,726,726 ,0,0,0}, {31781,31780,31743 ,726,726,728 ,0,0,0}, - {31780,31776,31725 ,726,726,726 ,0,0,0}, {31746,31783,31743 ,726,726,728 ,0,0,0}, - {31748,31787,31786 ,726,726,726 ,0,0,0}, {31746,31786,31783 ,726,726,726 ,0,0,0}, - {31749,31752,31789 ,726,726,726 ,0,0,0}, {31748,31749,31787 ,726,726,726 ,0,0,0}, - {31791,31752,32230 ,726,726,726 ,0,0,0}, {32234,31754,31755 ,726,726,726 ,0,0,0}, - {32230,31752,31754 ,726,726,726 ,0,0,0}, {32535,32292,32532 ,726,726,727 ,0,0,0}, - {31716,32318,31715 ,726,727,727 ,0,0,0}, {31692,32306,31695 ,726,726,727 ,0,0,0}, - {32542,32540,32539 ,727,726,726 ,0,0,0}, {32538,32537,32542 ,726,726,727 ,0,0,0}, - {32294,32537,32533 ,726,726,726 ,0,0,0}, {32292,32294,32532 ,726,726,727 ,0,0,0}, - {32288,32289,32535 ,726,726,726 ,0,0,0}, {32286,32288,32400 ,727,726,727 ,0,0,0}, - {32283,32286,32401 ,726,727,727 ,0,0,0}, {32282,32283,32536 ,726,726,727 ,0,0,0}, - {32277,32279,32406 ,726,726,726 ,0,0,0}, {32276,32277,32405 ,727,726,726 ,0,0,0}, - {32274,32276,32407 ,726,727,726 ,0,0,0}, {32271,32274,32409 ,726,726,726 ,0,0,0}, - {32270,31708,31705 ,726,727,726 ,0,0,0}, {32266,32267,31705 ,726,726,726 ,0,0,0}, - {32264,32266,31706 ,727,726,726 ,0,0,0}, {32296,32264,31701 ,726,727,726 ,0,0,0}, - {32264,31706,31701 ,727,726,726 ,0,0,0}, {32300,32298,31699 ,727,726,726 ,0,0,0}, - {32303,32300,31702 ,726,727,727 ,0,0,0}, {32304,32303,31693 ,726,726,727 ,0,0,0}, - {32306,32304,31695 ,726,726,727 ,0,0,0}, {32311,32308,31692 ,726,726,726 ,0,0,0}, - {32312,32311,31691 ,726,726,727 ,0,0,0}, {31713,32315,31710 ,726,726,726 ,0,0,0}, - {31710,32312,31691 ,726,726,727 ,0,0,0}, {31715,32318,32316 ,727,727,727 ,0,0,0}, - {31713,32316,32315 ,726,727,726 ,0,0,0}, {31716,32321,32318 ,726,726,727 ,0,0,0}, - {31719,32322,31716 ,727,727,726 ,0,0,0}, {32321,31716,32322 ,726,726,727 ,0,0,0}, - {32322,31721,32545 ,727,726,726 ,0,0,0}, {31722,32545,31721 ,727,726,726 ,0,0,0}, - {31661,31663,32089 ,727,727,726 ,0,0,0}, {32057,32403,32056 ,726,727,727 ,0,0,0}, - {31660,32090,31663 ,726,727,727 ,0,0,0}, {32062,32063,32444 ,726,726,727 ,0,0,0}, - {32060,32062,32443 ,726,726,726 ,0,0,0}, {32057,32060,32402 ,726,726,726 ,0,0,0}, - {32053,32056,32403 ,727,727,727 ,0,0,0}, {32051,32053,32452 ,726,727,726 ,0,0,0}, - {32050,32051,32450 ,726,726,727 ,0,0,0}, {32048,32050,32451 ,726,726,727 ,0,0,0}, - {32044,32045,32445 ,727,726,727 ,0,0,0}, {32041,32044,32449 ,727,727,726 ,0,0,0}, - {32040,32041,32448 ,726,727,726 ,0,0,0}, {32038,32040,32446 ,727,726,726 ,0,0,0}, - {32070,32447,31675 ,727,726,727 ,0,0,0}, {32074,32072,31675 ,726,726,727 ,0,0,0}, - {32077,32074,31672 ,727,726,726 ,0,0,0}, {32078,32077,31673 ,727,727,726 ,0,0,0}, - {32080,31669,31667 ,726,726,726 ,0,0,0}, {32078,31669,32080 ,727,726,726 ,0,0,0}, - {32085,32082,31667 ,726,727,726 ,0,0,0}, {32086,32085,31670 ,726,726,727 ,0,0,0}, - {32089,32086,31661 ,726,726,727 ,0,0,0}, {32090,32089,31663 ,727,726,727 ,0,0,0}, - {31659,32095,31660 ,727,727,726 ,0,0,0}, {32092,32090,31660 ,726,727,726 ,0,0,0}, - {32096,31659,31677 ,726,727,726 ,0,0,0}, {31659,32096,32095 ,727,726,727 ,0,0,0}, - {31677,31680,32437 ,726,726,726 ,0,0,0}, {32455,32437,31682 ,726,726,727 ,0,0,0}, - {31680,31682,32437 ,726,727,726 ,0,0,0}, {32439,31686,32440 ,727,727,726 ,0,0,0}, - {31688,32456,31686 ,726,726,727 ,0,0,0}, {32440,31686,32456 ,726,727,726 ,0,0,0}, - {31689,32456,31688 ,727,726,726 ,0,0,0}, {32429,32470,32111 ,726,726,726 ,0,0,0}, - {31650,31832,31849 ,726,726,728 ,0,0,0}, {31859,31860,31628 ,728,726,726 ,0,0,0}, - {32105,32106,32466 ,726,726,726 ,0,0,0}, {32103,32465,32430 ,726,726,728 ,0,0,0}, - {32110,32113,32430 ,726,726,728 ,0,0,0}, {32111,32110,32429 ,726,726,726 ,0,0,0}, - {32118,32111,32470 ,729,726,726 ,0,0,0}, {32116,32115,32431 ,726,726,726 ,0,0,0}, - {32121,32116,32432 ,726,726,726 ,0,0,0}, {32122,32121,32472 ,726,726,726 ,0,0,0}, - {32476,32127,32126 ,726,726,726 ,0,0,0}, {32126,32475,32476 ,726,726,726 ,0,0,0}, - {32129,32577,32578 ,726,726,726 ,0,0,0}, {32577,32129,32477 ,726,726,726 ,0,0,0}, - {32578,31643,32434 ,726,726,726 ,0,0,0}, {32577,31643,32578 ,726,726,726 ,0,0,0}, - {31641,32473,32479 ,726,726,726 ,0,0,0}, {31641,32479,32434 ,726,726,726 ,0,0,0}, - {31635,32433,31637 ,726,726,726 ,0,0,0}, {31638,32471,31635 ,726,728,726 ,0,0,0}, - {31863,32471,31629 ,726,728,726 ,0,0,0}, {31860,31863,31631 ,726,726,726 ,0,0,0}, - {31854,31857,31627 ,726,726,726 ,0,0,0}, {31857,31859,31628 ,726,728,726 ,0,0,0}, - {31853,31854,31645 ,726,726,728 ,0,0,0}, {31648,31849,31851 ,726,728,728 ,0,0,0}, - {31648,31853,31645 ,726,726,728 ,0,0,0}, {31650,31651,31832 ,726,726,726 ,0,0,0}, - {31648,31650,31849 ,726,726,728 ,0,0,0}, {31651,31654,31836 ,726,726,726 ,0,0,0}, - {31837,31656,31839 ,726,726,726 ,0,0,0}, {31836,31654,31837 ,726,726,726 ,0,0,0}, - {31842,31656,31657 ,726,726,726 ,0,0,0}, {32385,32383,31594 ,726,726,726 ,0,0,0}, - {32379,31595,32382 ,727,727,726 ,0,0,0}, {32422,32423,32579 ,727,726,726 ,0,0,0}, - {32579,32423,32420 ,726,726,727 ,0,0,0}, {32417,32416,32422 ,726,726,727 ,0,0,0}, - {32367,32416,32415 ,726,726,726 ,0,0,0}, {32366,32367,32414 ,726,726,727 ,0,0,0}, - {32363,32366,32413 ,726,726,726 ,0,0,0}, {32362,32363,32412 ,726,726,727 ,0,0,0}, - {32357,32360,32411 ,727,727,727 ,0,0,0}, {32356,32357,32410 ,726,727,727 ,0,0,0}, - {32354,32356,32408 ,727,726,726 ,0,0,0}, {32351,32354,32404 ,726,727,726 ,0,0,0}, - {32350,32351,32396 ,726,726,726 ,0,0,0}, {32348,32350,32392 ,727,726,726 ,0,0,0}, - {32344,32348,31610 ,727,727,727 ,0,0,0}, {32370,32368,31607 ,726,727,726 ,0,0,0}, - {32371,32370,31608 ,726,726,726 ,0,0,0}, {32373,32371,31603 ,727,726,726 ,0,0,0}, - {32371,31608,31603 ,726,726,726 ,0,0,0}, {32376,32373,31601 ,726,727,726 ,0,0,0}, - {32377,32376,31604 ,726,726,727 ,0,0,0}, {32379,32377,31595 ,727,726,727 ,0,0,0}, - {31597,32382,31595 ,727,726,727 ,0,0,0}, {31593,32385,31594 ,727,726,726 ,0,0,0}, - {31594,32383,31597 ,726,726,727 ,0,0,0}, {32388,31593,31612 ,726,727,726 ,0,0,0}, - {31593,32388,32385 ,727,726,726 ,0,0,0}, {31612,31615,32554 ,726,726,726 ,0,0,0}, - {32424,32554,31617 ,726,726,727 ,0,0,0}, {31615,31617,32554 ,726,727,726 ,0,0,0}, - {32424,31618,32561 ,726,726,727 ,0,0,0}, {32561,31623,32550 ,727,726,727 ,0,0,0}, - {32561,31618,31621 ,727,726,727 ,0,0,0}, {32428,31623,31624 ,727,726,727 ,0,0,0}, - {32495,32186,32178 ,728,726,726 ,0,0,0}, {31583,31810,31581 ,726,726,726 ,0,0,0}, - {31829,31563,31560 ,726,726,726 ,0,0,0}, {32180,32173,32493 ,726,726,726 ,0,0,0}, - {32181,32180,32494 ,726,726,726 ,0,0,0}, {32178,32181,32495 ,726,726,728 ,0,0,0}, - {32393,32186,32495 ,726,726,728 ,0,0,0}, {32188,32184,32489 ,726,726,726 ,0,0,0}, - {32488,32500,32189 ,726,726,726 ,0,0,0}, {32189,32188,32488 ,726,726,726 ,0,0,0}, - {32580,32501,32500 ,726,726,726 ,0,0,0}, {31573,31534,31532 ,726,726,726 ,0,0,0}, - {32501,32581,32565 ,726,726,726 ,0,0,0}, {32581,32501,32580 ,726,726,726 ,0,0,0}, - {31573,31532,31576 ,726,726,726 ,0,0,0}, {32581,32490,32565 ,726,726,726 ,0,0,0}, - {31576,32574,31544 ,726,726,726 ,0,0,0}, {31576,31544,32486 ,726,726,726 ,0,0,0}, - {31573,32482,31534 ,726,726,726 ,0,0,0}, {31573,31574,32395 ,726,726,726 ,0,0,0}, - {31573,32395,32482 ,726,726,726 ,0,0,0}, {31567,32394,31569 ,726,726,726 ,0,0,0}, - {31570,32498,31567 ,726,728,726 ,0,0,0}, {31831,32498,31561 ,726,728,726 ,0,0,0}, - {31829,31831,31563 ,726,726,726 ,0,0,0}, {31827,31560,31559 ,726,726,726 ,0,0,0}, - {31578,31823,31559 ,728,726,726 ,0,0,0}, {31824,31827,31559 ,726,726,726 ,0,0,0}, - {31581,31810,31821 ,726,726,726 ,0,0,0}, {31578,31821,31823 ,728,726,726 ,0,0,0}, - {31583,31811,31810 ,726,726,726 ,0,0,0}, {31584,31587,31813 ,726,726,726 ,0,0,0}, - {31583,31584,31811 ,726,726,726 ,0,0,0}, {31816,31589,31817 ,726,726,726 ,0,0,0}, - {31813,31587,31816 ,726,726,726 ,0,0,0}, {31590,31817,31589 ,726,726,726 ,0,0,0}, - {32582,31883,32583 ,730,730,730 ,0,0,0}, {31779,31744,31742 ,730,730,730 ,0,0,0}, - {31606,32372,31609 ,730,730,730 ,0,0,0}, {32584,32585,32586 ,730,730,730 ,0,0,0}, - {32587,32253,32256 ,730,730,730 ,0,0,0}, {31972,31759,31975 ,730,730,730 ,0,0,0}, - {31995,32214,32217 ,730,730,730 ,0,0,0}, {31775,32588,32589 ,730,730,730 ,0,0,0}, - {32590,32591,32592 ,730,730,730 ,0,0,0}, {32588,31775,32593 ,730,730,730 ,0,0,0}, - {32594,32595,31622 ,730,730,730 ,0,0,0}, {32361,32596,32597 ,730,730,730 ,0,0,0}, - {32594,31620,31619 ,730,730,730 ,0,0,0}, {31602,32374,32375 ,730,730,730 ,0,0,0}, - {31599,31600,32378 ,730,730,730 ,0,0,0}, {32598,32599,32355 ,730,730,730 ,0,0,0}, - {31611,32389,31613 ,730,730,730 ,0,0,0}, {32346,32345,31605 ,730,730,730 ,0,0,0}, - {32347,32600,32349 ,730,730,730 ,0,0,0}, {31592,32386,32387 ,730,730,730 ,0,0,0}, - {32601,32602,31616 ,730,730,730 ,0,0,0}, {31674,31671,32076 ,730,730,730 ,0,0,0}, - {31598,31596,32384 ,730,730,730 ,0,0,0}, {32039,32069,32603 ,730,730,730 ,0,0,0}, - {32387,32389,31611 ,730,730,730 ,0,0,0}, {31599,32380,31596 ,730,730,730 ,0,0,0}, - {31658,32094,31676 ,730,730,730 ,0,0,0}, {32604,32605,32047 ,730,730,730 ,0,0,0}, - {32345,32369,31605 ,730,730,730 ,0,0,0}, {32601,31614,31613 ,730,730,730 ,0,0,0}, - {32605,32606,32049 ,730,730,730 ,0,0,0}, {31666,32081,32083 ,730,730,730 ,0,0,0}, - {32346,31605,32607 ,730,730,730 ,0,0,0}, {32602,32594,31619 ,730,730,730 ,0,0,0}, - {32310,31709,31690 ,730,730,730 ,0,0,0}, {32314,31712,31711 ,730,730,730 ,0,0,0}, - {32352,32349,32608 ,730,730,730 ,0,0,0}, {32349,32600,32608 ,730,730,730 ,0,0,0}, - {32609,32598,32353 ,730,730,730 ,0,0,0}, {32596,32361,32359 ,730,730,730 ,0,0,0}, - {32599,32596,32358 ,730,730,730 ,0,0,0}, {32364,32597,32610 ,730,730,730 ,0,0,0}, - {32611,32612,32613 ,730,730,730 ,0,0,0}, {31775,31773,32593 ,730,730,730 ,0,0,0}, - {32614,32615,32595 ,730,730,730 ,0,0,0}, {31773,31771,31985 ,730,730,730 ,0,0,0}, - {32616,32617,32618 ,730,730,730 ,0,0,0}, {32619,32620,32621 ,730,730,730 ,0,0,0}, - {31756,31759,31972 ,730,730,730 ,0,0,0}, {31893,31976,31765 ,730,730,730 ,0,0,0}, - {32223,32225,32004 ,730,730,730 ,0,0,0}, {32202,32198,32013 ,730,730,730 ,0,0,0}, - {32584,32622,32623 ,730,730,730 ,0,0,0}, {32624,32587,32256 ,730,730,730 ,0,0,0}, - {32625,32626,32252 ,730,730,730 ,0,0,0}, {32627,32240,32242 ,730,730,730 ,0,0,0}, - {32245,32626,32628 ,730,730,730 ,0,0,0}, {31753,31751,32259 ,730,730,730 ,0,0,0}, - {32237,32629,32630 ,730,730,730 ,0,0,0}, {32631,32632,32633 ,730,730,730 ,0,0,0}, - {32634,32635,32636 ,730,730,730 ,0,0,0}, {32019,32206,32205 ,730,730,730 ,0,0,0}, - {32633,32261,32631 ,730,730,730 ,0,0,0}, {32637,32638,32639 ,730,730,730 ,0,0,0}, - {32640,32262,32641 ,730,730,730 ,0,0,0}, {32642,32287,32643 ,730,730,730 ,0,0,0}, - {32291,32644,32293 ,730,730,730 ,0,0,0}, {32645,32646,32281 ,730,730,730 ,0,0,0}, - {31717,32323,31718 ,730,730,730 ,0,0,0}, {32647,32278,32275 ,730,730,730 ,0,0,0}, - {31707,31704,32265 ,730,730,730 ,0,0,0}, {31694,32302,32305 ,730,730,730 ,0,0,0}, - {32648,32637,32639 ,730,730,730 ,0,0,0}, {32647,32275,32649 ,730,730,730 ,0,0,0}, - {32272,31703,32650 ,730,730,730 ,0,0,0}, {31720,32323,32651 ,730,730,730 ,0,0,0}, - {32317,31714,31712 ,730,730,730 ,0,0,0}, {31690,31696,32307 ,730,730,730 ,0,0,0}, - {32299,31698,32297 ,730,730,730 ,0,0,0}, {32301,32302,31697 ,730,730,730 ,0,0,0}, - {31709,32313,31711 ,730,730,730 ,0,0,0}, {31700,32295,32297 ,730,730,730 ,0,0,0}, - {31703,32272,32269 ,730,730,730 ,0,0,0}, {32268,31704,32269 ,730,730,730 ,0,0,0}, - {32320,32323,31717 ,730,730,730 ,0,0,0}, {31717,31714,32319 ,730,730,730 ,0,0,0}, - {31723,32651,32652 ,730,730,730 ,0,0,0}, {32649,32275,32273 ,730,730,730 ,0,0,0}, - {32652,32648,32653 ,730,730,730 ,0,0,0}, {31730,31728,31794 ,730,730,730 ,0,0,0}, - {31709,32310,32313 ,730,730,730 ,0,0,0}, {32647,32645,32278 ,730,730,730 ,0,0,0}, - {32654,32284,32646 ,730,730,730 ,0,0,0}, {32287,32642,32290 ,730,730,730 ,0,0,0}, - {32643,32285,32654 ,730,730,730 ,0,0,0}, {32644,32655,32293 ,730,730,730 ,0,0,0}, - {32648,32639,32656 ,730,730,730 ,0,0,0}, {32657,32656,32658 ,730,730,730 ,0,0,0}, - {32638,32637,32659 ,730,730,730 ,0,0,0}, {32660,32638,32659 ,730,730,730 ,0,0,0}, - {32661,32662,32262 ,730,730,730 ,0,0,0}, {32262,32660,32659 ,730,730,730 ,0,0,0}, - {32662,32341,32660 ,730,730,730 ,0,0,0}, {31900,32339,32663 ,730,730,730 ,0,0,0}, - {32205,32017,32019 ,730,730,730 ,0,0,0}, {31525,32209,31527 ,730,730,730 ,0,0,0}, - {32664,31059,32235 ,730,730,730 ,0,0,0}, {31806,31740,31737 ,730,730,730 ,0,0,0}, - {31745,31784,31785 ,730,730,730 ,0,0,0}, {31750,31747,31788 ,730,730,730 ,0,0,0}, - {31796,31728,31799 ,730,730,730 ,0,0,0}, {31732,31800,31731 ,730,730,730 ,0,0,0}, - {31779,31742,31777 ,730,730,730 ,0,0,0}, {31724,31778,31777 ,730,730,730 ,0,0,0}, - {31784,31744,31782 ,730,730,730 ,0,0,0}, {31751,31792,32259 ,730,730,730 ,0,0,0}, - {31745,31785,31747 ,730,730,730 ,0,0,0}, {32251,32587,32625 ,730,730,730 ,0,0,0}, - {32624,32258,32586 ,730,730,730 ,0,0,0}, {32247,32629,32248 ,730,730,730 ,0,0,0}, - {32628,32247,32245 ,730,730,730 ,0,0,0}, {32240,32664,32232 ,730,730,730 ,0,0,0}, - {32242,32630,32627 ,730,730,730 ,0,0,0}, {31790,31751,31750 ,730,730,730 ,0,0,0}, - {31753,32236,31059 ,730,730,730 ,0,0,0}, {31897,31895,32337 ,730,730,730 ,0,0,0}, - {32197,32008,32011 ,730,730,730 ,0,0,0}, {31998,32217,32219 ,730,730,730 ,0,0,0}, - {31762,31975,31759 ,730,730,730 ,0,0,0}, {31992,32213,31993 ,730,730,730 ,0,0,0}, - {32149,31547,31545 ,730,730,730 ,0,0,0}, {32213,32214,31993 ,730,730,730 ,0,0,0}, - {31992,32196,32213 ,730,730,730 ,0,0,0}, {32194,32008,32197 ,730,730,730 ,0,0,0}, - {32202,32013,32014 ,730,730,730 ,0,0,0}, {32203,32202,32014 ,730,730,730 ,0,0,0}, - {32634,32665,32666 ,730,730,730 ,0,0,0}, {32667,31043,32635 ,730,730,730 ,0,0,0}, - {32634,32666,32635 ,730,730,730 ,0,0,0}, {32203,32017,32205 ,730,730,730 ,0,0,0}, - {32636,32635,31043 ,730,730,730 ,0,0,0}, {32666,32632,32631 ,730,730,730 ,0,0,0}, - {32632,32666,32665 ,730,730,730 ,0,0,0}, {32211,31521,31523 ,730,730,730 ,0,0,0}, - {32014,32017,32203 ,730,730,730 ,0,0,0}, {32198,32011,32013 ,730,730,730 ,0,0,0}, - {32197,32011,32198 ,730,730,730 ,0,0,0}, {32196,32007,32194 ,730,730,730 ,0,0,0}, - {31886,32329,32327 ,730,730,730 ,0,0,0}, {32330,31887,31890 ,730,730,730 ,0,0,0}, - {31765,31976,31762 ,730,730,730 ,0,0,0}, {32668,32228,32669 ,730,730,730 ,0,0,0}, - {32225,32226,32005 ,730,730,730 ,0,0,0}, {31936,31535,32670 ,730,730,730 ,0,0,0}, - {32149,32146,31547 ,730,730,730 ,0,0,0}, {32671,32226,32228 ,730,730,730 ,0,0,0}, - {32151,31545,31538 ,730,730,730 ,0,0,0}, {32672,31543,32673 ,730,730,730 ,0,0,0}, - {31582,31580,31808 ,730,730,730 ,0,0,0}, {31558,31828,31826 ,730,730,730 ,0,0,0}, - {31588,31586,31815 ,730,730,730 ,0,0,0}, {32674,31591,32191 ,730,730,730 ,0,0,0}, - {32675,32182,32676 ,730,730,730 ,0,0,0}, {31825,31577,31826 ,730,730,730 ,0,0,0}, - {32677,32678,32187 ,730,730,730 ,0,0,0}, {32679,32680,32681 ,730,730,730 ,0,0,0}, - {31814,31586,31585 ,730,730,730 ,0,0,0}, {31579,31809,31580 ,730,730,730 ,0,0,0}, - {32172,32682,32683 ,730,730,730 ,0,0,0}, {31820,31591,31818 ,730,730,730 ,0,0,0}, - {32684,32676,32177 ,730,730,730 ,0,0,0}, {32685,32679,32686 ,730,730,730 ,0,0,0}, - {32687,32185,32678 ,730,730,730 ,0,0,0}, {32684,32183,32687 ,730,730,730 ,0,0,0}, - {32190,32681,32677 ,730,730,730 ,0,0,0}, {32183,32684,32179 ,730,730,730 ,0,0,0}, - {32674,32175,32683 ,730,730,730 ,0,0,0}, {32682,32171,32675 ,730,730,730 ,0,0,0}, - {31873,31926,31925 ,730,730,730 ,0,0,0}, {31582,31812,31585 ,730,730,730 ,0,0,0}, - {31591,31588,31818 ,730,730,730 ,0,0,0}, {31822,31579,31577 ,730,730,730 ,0,0,0}, - {32145,32143,31967 ,730,730,730 ,0,0,0}, {32138,32137,31961 ,730,730,730 ,0,0,0}, - {31964,32143,32142 ,730,730,730 ,0,0,0}, {31967,32143,31964 ,730,730,730 ,0,0,0}, - {32145,31969,32146 ,730,730,730 ,0,0,0}, {32688,31830,31562 ,730,730,730 ,0,0,0}, - {32689,32672,32673 ,730,730,730 ,0,0,0}, {31963,31964,32142 ,730,730,730 ,0,0,0}, - {31969,32145,31967 ,730,730,730 ,0,0,0}, {31571,31543,32690 ,730,730,730 ,0,0,0}, - {32691,31566,31568 ,730,730,730 ,0,0,0}, {31545,32151,32149 ,730,730,730 ,0,0,0}, - {31538,31541,32151 ,730,730,730 ,0,0,0}, {31543,31571,32673 ,730,730,730 ,0,0,0}, - {31547,32146,31969 ,730,730,730 ,0,0,0}, {32692,32693,32037 ,730,730,730 ,0,0,0}, - {32142,32138,31963 ,730,730,730 ,0,0,0}, {31963,32138,31961 ,730,730,730 ,0,0,0}, - {32031,31912,31904 ,730,730,730 ,0,0,0}, {31961,32137,31958 ,730,730,730 ,0,0,0}, - {31905,32025,32023 ,730,730,730 ,0,0,0}, {31957,31958,32134 ,730,730,730 ,0,0,0}, - {31943,31942,32153 ,730,730,730 ,0,0,0}, {32136,31942,31957 ,730,730,730 ,0,0,0}, - {32157,31948,31945 ,730,730,730 ,0,0,0}, {31945,31943,32154 ,730,730,730 ,0,0,0}, - {31932,31864,31930 ,730,730,730 ,0,0,0}, {31867,31870,31922 ,730,730,730 ,0,0,0}, - {31878,31934,31879 ,730,730,730 ,0,0,0}, {31935,32694,31881 ,730,730,730 ,0,0,0}, - {32695,31642,32696 ,730,730,730 ,0,0,0}, {32166,32697,31955 ,730,730,730 ,0,0,0}, - {31626,31861,31858 ,730,730,730 ,0,0,0}, {31649,31833,31652 ,730,730,730 ,0,0,0}, - {31626,31856,31644 ,730,730,730 ,0,0,0}, {32125,32128,32698 ,730,730,730 ,0,0,0}, - {32699,32109,32700 ,730,730,730 ,0,0,0}, {32701,32702,32124 ,730,730,730 ,0,0,0}, - {32108,32703,32704 ,730,730,730 ,0,0,0}, {31840,31841,31655 ,730,730,730 ,0,0,0}, - {32128,32130,32698 ,730,730,730 ,0,0,0}, {31652,31835,31653 ,730,730,730 ,0,0,0}, - {32123,32705,32701 ,730,730,730 ,0,0,0}, {32706,31846,32707 ,730,730,730 ,0,0,0}, - {32114,32708,32112 ,730,730,730 ,0,0,0}, {32117,32709,32119 ,730,730,730 ,0,0,0}, - {32700,32120,32709 ,730,730,730 ,0,0,0}, {32708,32114,32699 ,730,730,730 ,0,0,0}, - {32107,32710,32703 ,730,730,730 ,0,0,0}, {32710,32104,32708 ,730,730,730 ,0,0,0}, - {32124,32702,32117 ,730,730,730 ,0,0,0}, {32704,32707,31848 ,730,730,730 ,0,0,0}, - {32108,32704,32131 ,730,730,730 ,0,0,0}, {30481,31655,31841 ,730,730,730 ,0,0,0}, - {32706,30481,31844 ,730,730,730 ,0,0,0}, {32130,32711,32712 ,730,730,730 ,0,0,0}, - {32712,32698,32130 ,730,730,730 ,0,0,0}, {31834,31833,31649 ,730,730,730 ,0,0,0}, - {31653,31838,31655 ,730,730,730 ,0,0,0}, {31647,31646,31852 ,730,730,730 ,0,0,0}, - {31834,31647,31850 ,730,730,730 ,0,0,0}, {30497,32713,32714 ,730,730,730 ,0,0,0}, - {31855,31646,31644 ,730,730,730 ,0,0,0}, {31636,31642,32695 ,730,730,730 ,0,0,0}, - {31862,31630,32715 ,730,730,730 ,0,0,0}, {31878,31927,31934 ,730,730,730 ,0,0,0}, - {31634,31636,32695 ,730,730,730 ,0,0,0}, {32716,32717,32696 ,730,730,730 ,0,0,0}, - {32717,32716,32718 ,730,730,730 ,0,0,0}, {31548,31551,32099 ,730,730,730 ,0,0,0}, - {32099,32719,32718 ,730,730,730 ,0,0,0}, {32717,32718,32719 ,730,730,730 ,0,0,0}, - {32719,32099,31553 ,730,730,730 ,0,0,0}, {32168,31553,32720 ,730,730,730 ,0,0,0}, - {32052,32721,32054 ,730,730,730 ,0,0,0}, {32094,31658,32093 ,730,730,730 ,0,0,0}, - {32722,32058,32723 ,730,730,730 ,0,0,0}, {32054,32723,32055 ,730,730,730 ,0,0,0}, - {32606,32721,32052 ,730,730,730 ,0,0,0}, {32042,32724,32725 ,730,730,730 ,0,0,0}, - {32604,32046,32043 ,730,730,730 ,0,0,0}, {32071,31323,32726 ,730,730,730 ,0,0,0}, - {32603,32724,32039 ,730,730,730 ,0,0,0}, {32727,31679,31678 ,730,730,730 ,0,0,0}, - {32073,32075,31323 ,730,730,730 ,0,0,0}, {32091,31658,31664 ,730,730,730 ,0,0,0}, - {32087,32088,31662 ,730,730,730 ,0,0,0}, {32097,31678,31676 ,730,730,730 ,0,0,0}, - {32087,31665,32084 ,730,730,730 ,0,0,0}, {31681,32727,32728 ,730,730,730 ,0,0,0}, - {32079,31668,31674 ,730,730,730 ,0,0,0}, {31323,32071,32073 ,730,730,730 ,0,0,0}, - {32729,31684,32728 ,730,730,730 ,0,0,0}, {31685,31684,32729 ,730,730,730 ,0,0,0}, - {32042,32039,32724 ,730,730,730 ,0,0,0}, {32064,32061,32730 ,730,730,730 ,0,0,0}, - {32731,32059,32722 ,730,730,730 ,0,0,0}, {32064,32732,32065 ,730,730,730 ,0,0,0}, - {32730,32061,32731 ,730,730,730 ,0,0,0}, {32065,32732,32067 ,730,730,730 ,0,0,0}, - {31687,32733,31339 ,730,730,730 ,0,0,0}, {32729,32734,32735 ,730,730,730 ,0,0,0}, - {31687,31685,32733 ,730,730,730 ,0,0,0}, {32736,32734,32582 ,730,730,730 ,0,0,0}, - {32734,32736,32735 ,730,730,730 ,0,0,0}, {31865,31932,31927 ,730,730,730 ,0,0,0}, - {32736,32582,32098 ,730,730,730 ,0,0,0}, {31932,31865,31864 ,730,730,730 ,0,0,0}, - {31878,31865,31927 ,730,730,730 ,0,0,0}, {31864,31867,31930 ,730,730,730 ,0,0,0}, - {31922,31870,31925 ,730,730,730 ,0,0,0}, {31930,31867,31922 ,730,730,730 ,0,0,0}, - {31948,32159,31949 ,730,730,730 ,0,0,0}, {31942,32136,32153 ,730,730,730 ,0,0,0}, - {31911,31926,32737 ,730,730,730 ,0,0,0}, {31911,32737,31872 ,730,730,730 ,0,0,0}, - {31872,32021,31911 ,730,730,730 ,0,0,0}, {32026,31908,31910 ,730,730,730 ,0,0,0}, - {31951,31949,32160 ,730,730,730 ,0,0,0}, {31925,31870,31873 ,730,730,730 ,0,0,0}, - {32153,32154,31943 ,730,730,730 ,0,0,0}, {31951,32163,31954 ,730,730,730 ,0,0,0}, - {32154,32157,31945 ,730,730,730 ,0,0,0}, {32166,31955,32165 ,730,730,730 ,0,0,0}, - {32157,32159,31948 ,730,730,730 ,0,0,0}, {31557,32098,32390 ,730,730,730 ,0,0,0}, - {32160,32163,31951 ,730,730,730 ,0,0,0}, {31883,32738,32739 ,730,730,730 ,0,0,0}, - {31935,31879,31934 ,730,730,730 ,0,0,0}, {32694,32738,31881 ,730,730,730 ,0,0,0}, - {31879,31935,31881 ,730,730,730 ,0,0,0}, {31881,32738,31883 ,730,730,730 ,0,0,0}, - {32582,32583,32098 ,730,730,730 ,0,0,0}, {32739,32583,31883 ,730,730,730 ,0,0,0}, - {32740,32098,32741 ,730,730,730 ,0,0,0}, {32098,32583,32741 ,730,730,730 ,0,0,0}, - {32742,32098,32743 ,730,730,730 ,0,0,0}, {32098,32740,32743 ,730,730,730 ,0,0,0}, - {32098,32742,32390 ,730,730,730 ,0,0,0}, {32744,32166,32168 ,730,730,730 ,0,0,0}, - {32098,31557,32099 ,730,730,730 ,0,0,0}, {32099,31555,31548 ,730,730,730 ,0,0,0}, - {32099,31557,31555 ,730,730,730 ,0,0,0}, {31553,32168,32719 ,730,730,730 ,0,0,0}, - {31551,31553,32099 ,730,730,730 ,0,0,0}, {32720,32744,32168 ,730,730,730 ,0,0,0}, - {32744,32697,32166 ,730,730,730 ,0,0,0}, {31954,32165,31955 ,730,730,730 ,0,0,0}, - {32165,31954,32163 ,730,730,730 ,0,0,0}, {31949,32159,32160 ,730,730,730 ,0,0,0}, - {31957,32134,32136 ,730,730,730 ,0,0,0}, {31958,32137,32134 ,730,730,730 ,0,0,0}, - {32031,31904,32023 ,730,730,730 ,0,0,0}, {31911,32021,31910 ,730,730,730 ,0,0,0}, - {32033,31913,31912 ,730,730,730 ,0,0,0}, {31908,32026,32025 ,730,730,730 ,0,0,0}, - {31918,31915,32028 ,730,730,730 ,0,0,0}, {32023,31904,31905 ,730,730,730 ,0,0,0}, - {32037,32745,32746 ,730,730,730 ,0,0,0}, {32033,31912,32031 ,730,730,730 ,0,0,0}, - {31533,31572,31531 ,730,730,730 ,0,0,0}, {31913,32033,32028 ,730,730,730 ,0,0,0}, - {32690,31531,31571 ,730,730,730 ,0,0,0}, {32672,32747,31543 ,730,730,730 ,0,0,0}, - {32151,31541,32747 ,730,730,730 ,0,0,0}, {31543,32747,31541 ,730,730,730 ,0,0,0}, - {31535,31528,32670 ,730,730,730 ,0,0,0}, {32748,31531,32690 ,730,730,730 ,0,0,0}, - {32749,31572,31533 ,730,730,730 ,0,0,0}, {31936,31537,31535 ,730,730,730 ,0,0,0}, - {32750,32749,31533 ,730,730,730 ,0,0,0}, {32217,31998,31995 ,730,730,730 ,0,0,0}, - {31757,31982,31770 ,730,730,730 ,0,0,0}, {32751,32752,32613 ,730,730,730 ,0,0,0}, - {31984,31771,31977 ,730,730,730 ,0,0,0}, {31918,32035,32746 ,730,730,730 ,0,0,0}, - {32589,32753,31775 ,730,730,730 ,0,0,0}, {32621,32612,32611 ,730,730,730 ,0,0,0}, - {32752,32693,32692 ,730,730,730 ,0,0,0}, {32752,32692,32613 ,730,730,730 ,0,0,0}, - {32693,32745,32037 ,730,730,730 ,0,0,0}, {32746,32035,32037 ,730,730,730 ,0,0,0}, - {31918,32028,32035 ,730,730,730 ,0,0,0}, {31913,32028,31915 ,730,730,730 ,0,0,0}, - {32025,31905,31908 ,730,730,730 ,0,0,0}, {32021,32026,31910 ,730,730,730 ,0,0,0}, - {31765,31764,31893 ,730,730,730 ,0,0,0}, {31764,32325,31892 ,730,730,730 ,0,0,0}, - {32219,32220,31999 ,730,730,730 ,0,0,0}, {31976,31975,31762 ,730,730,730 ,0,0,0}, - {31995,31993,32214 ,730,730,730 ,0,0,0}, {32001,32220,32223 ,730,730,730 ,0,0,0}, - {31757,31756,31980 ,730,730,730 ,0,0,0}, {31972,31980,31756 ,730,730,730 ,0,0,0}, - {31998,32219,31999 ,730,730,730 ,0,0,0}, {31982,31977,31770 ,730,730,730 ,0,0,0}, - {32001,32223,32004 ,730,730,730 ,0,0,0}, {31984,31985,31771 ,730,730,730 ,0,0,0}, - {31770,31977,31771 ,730,730,730 ,0,0,0}, {31939,32342,31537 ,730,730,730 ,0,0,0}, - {32754,32617,32751 ,730,730,730 ,0,0,0}, {32751,32615,32754 ,730,730,730 ,0,0,0}, - {31985,32593,31773 ,730,730,730 ,0,0,0}, {32621,32611,32619 ,730,730,730 ,0,0,0}, - {32753,32614,32595 ,730,730,730 ,0,0,0}, {32589,32614,32753 ,730,730,730 ,0,0,0}, - {32618,32617,32754 ,730,730,730 ,0,0,0}, {32616,32755,32756 ,730,730,730 ,0,0,0}, - {32755,32616,32618 ,730,730,730 ,0,0,0}, {32756,32342,31939 ,730,730,730 ,0,0,0}, - {32755,32342,32756 ,730,730,730 ,0,0,0}, {31936,31939,31537 ,730,730,730 ,0,0,0}, - {31528,31531,32748 ,730,730,730 ,0,0,0}, {31528,32748,32670 ,730,730,730 ,0,0,0}, - {32757,31572,32749 ,730,730,730 ,0,0,0}, {32750,31533,32669 ,730,730,730 ,0,0,0}, - {32750,32669,32228 ,730,730,730 ,0,0,0}, {32668,32671,32228 ,730,730,730 ,0,0,0}, - {32671,32005,32226 ,730,730,730 ,0,0,0}, {32225,32005,32004 ,730,730,730 ,0,0,0}, - {32001,31999,32220 ,730,730,730 ,0,0,0}, {31992,32007,32196 ,730,730,730 ,0,0,0}, - {32007,32008,32194 ,730,730,730 ,0,0,0}, {32327,31894,31886 ,730,730,730 ,0,0,0}, - {31893,31764,31892 ,730,730,730 ,0,0,0}, {31894,32335,31895 ,730,730,730 ,0,0,0}, - {32325,32330,31890 ,730,730,730 ,0,0,0}, {32332,32339,31900 ,730,730,730 ,0,0,0}, - {31886,31887,32329 ,730,730,730 ,0,0,0}, {32327,32335,31894 ,730,730,730 ,0,0,0}, - {32337,31895,32335 ,730,730,730 ,0,0,0}, {32209,32206,31527 ,730,730,730 ,0,0,0}, - {32206,32019,31527 ,730,730,730 ,0,0,0}, {31518,32211,32209 ,730,730,730 ,0,0,0}, - {31518,32209,31525 ,730,730,730 ,0,0,0}, {31523,32633,32211 ,730,730,730 ,0,0,0}, - {31518,31521,32211 ,730,730,730 ,0,0,0}, {32261,32633,31523 ,730,730,730 ,0,0,0}, - {32758,32261,32759 ,730,730,730 ,0,0,0}, {32261,31523,32759 ,730,730,730 ,0,0,0}, - {32261,32758,32760 ,730,730,730 ,0,0,0}, {32261,31986,31988 ,730,730,730 ,0,0,0}, - {32261,32760,31986 ,730,730,730 ,0,0,0}, {32761,32339,32762 ,730,730,730 ,0,0,0}, - {32261,31988,32262 ,730,730,730 ,0,0,0}, {32262,32763,32641 ,730,730,730 ,0,0,0}, - {32262,31988,32763 ,730,730,730 ,0,0,0}, {32660,32262,32662 ,730,730,730 ,0,0,0}, - {32640,32661,32262 ,730,730,730 ,0,0,0}, {32341,32762,32339 ,730,730,730 ,0,0,0}, - {32662,32762,32341 ,730,730,730 ,0,0,0}, {32761,32663,32339 ,730,730,730 ,0,0,0}, - {31897,32332,31900 ,730,730,730 ,0,0,0}, {31897,32337,32332 ,730,730,730 ,0,0,0}, - {31887,32330,32329 ,730,730,730 ,0,0,0}, {31890,31892,32325 ,730,730,730 ,0,0,0}, - {32665,32634,32764 ,730,730,730 ,0,0,0}, {31802,31732,31734 ,730,730,730 ,0,0,0}, - {32623,32622,32764 ,730,730,730 ,0,0,0}, {32622,32665,32764 ,730,730,730 ,0,0,0}, - {32585,32584,32623 ,730,730,730 ,0,0,0}, {32258,32584,32586 ,730,730,730 ,0,0,0}, - {32256,32258,32624 ,730,730,730 ,0,0,0}, {32251,32253,32587 ,730,730,730 ,0,0,0}, - {32252,32251,32625 ,730,730,730 ,0,0,0}, {32245,32252,32626 ,730,730,730 ,0,0,0}, - {32247,32628,32629 ,730,730,730 ,0,0,0}, {32237,32248,32629 ,730,730,730 ,0,0,0}, - {32242,32237,32630 ,730,730,730 ,0,0,0}, {32240,32627,32664 ,730,730,730 ,0,0,0}, - {32235,32232,32664 ,730,730,730 ,0,0,0}, {32236,32235,31059 ,730,730,730 ,0,0,0}, - {32259,32236,31753 ,730,730,730 ,0,0,0}, {31790,31792,31751 ,730,730,730 ,0,0,0}, - {31788,31790,31750 ,730,730,730 ,0,0,0}, {31785,31788,31747 ,730,730,730 ,0,0,0}, - {31784,31745,31744 ,730,730,730 ,0,0,0}, {31779,31782,31744 ,730,730,730 ,0,0,0}, - {31777,31742,31724 ,730,730,730 ,0,0,0}, {31778,31724,31730 ,730,730,730 ,0,0,0}, - {31796,31794,31728 ,730,730,730 ,0,0,0}, {31794,31778,31730 ,730,730,730 ,0,0,0}, - {31731,31799,31728 ,730,730,730 ,0,0,0}, {31732,31802,31800 ,730,730,730 ,0,0,0}, - {31731,31800,31799 ,730,730,730 ,0,0,0}, {31734,31805,31802 ,730,730,730 ,0,0,0}, - {31740,31806,31734 ,730,730,730 ,0,0,0}, {31805,31734,31806 ,730,730,730 ,0,0,0}, - {31806,31737,32667 ,730,730,730 ,0,0,0}, {31043,32667,31737 ,730,730,730 ,0,0,0}, - {32650,32649,32273 ,730,730,730 ,0,0,0}, {32273,32272,32650 ,730,730,730 ,0,0,0}, - {32281,32280,32645 ,730,730,730 ,0,0,0}, {32278,32645,32280 ,730,730,730 ,0,0,0}, - {32284,32281,32646 ,730,730,730 ,0,0,0}, {32285,32284,32654 ,730,730,730 ,0,0,0}, - {32287,32285,32643 ,730,730,730 ,0,0,0}, {32642,32644,32291 ,730,730,730 ,0,0,0}, - {32291,32290,32642 ,730,730,730 ,0,0,0}, {32656,32765,32658 ,730,730,730 ,0,0,0}, - {32765,32655,32766 ,730,730,730 ,0,0,0}, {32655,32765,32293 ,730,730,730 ,0,0,0}, - {32766,32658,32765 ,730,730,730 ,0,0,0}, {32656,32657,32648 ,730,730,730 ,0,0,0}, - {32648,32652,32637 ,730,730,730 ,0,0,0}, {31723,32652,32653 ,730,730,730 ,0,0,0}, - {31720,32651,31723 ,730,730,730 ,0,0,0}, {31718,32323,31720 ,730,730,730 ,0,0,0}, - {32319,32320,31717 ,730,730,730 ,0,0,0}, {32317,32319,31714 ,730,730,730 ,0,0,0}, - {32314,32317,31712 ,730,730,730 ,0,0,0}, {32313,32314,31711 ,730,730,730 ,0,0,0}, - {32310,31690,32309 ,730,730,730 ,0,0,0}, {32305,32307,31696 ,730,730,730 ,0,0,0}, - {32307,32309,31690 ,730,730,730 ,0,0,0}, {31697,32302,31694 ,730,730,730 ,0,0,0}, - {31694,32305,31696 ,730,730,730 ,0,0,0}, {31698,32301,31697 ,730,730,730 ,0,0,0}, - {31698,31700,32297 ,730,730,730 ,0,0,0}, {31698,32299,32301 ,730,730,730 ,0,0,0}, - {31700,31707,32295 ,730,730,730 ,0,0,0}, {32265,31704,32268 ,730,730,730 ,0,0,0}, - {32295,31707,32265 ,730,730,730 ,0,0,0}, {32269,31704,31703 ,730,730,730 ,0,0,0}, - {32726,32603,32069 ,730,730,730 ,0,0,0}, {32726,32069,32071 ,730,730,730 ,0,0,0}, - {32043,32725,32604 ,730,730,730 ,0,0,0}, {32042,32725,32043 ,730,730,730 ,0,0,0}, - {32047,32046,32604 ,730,730,730 ,0,0,0}, {32049,32047,32605 ,730,730,730 ,0,0,0}, - {32052,32049,32606 ,730,730,730 ,0,0,0}, {32054,32721,32723 ,730,730,730 ,0,0,0}, - {32058,32055,32723 ,730,730,730 ,0,0,0}, {32059,32058,32722 ,730,730,730 ,0,0,0}, - {32061,32059,32731 ,730,730,730 ,0,0,0}, {32733,31685,32735 ,730,730,730 ,0,0,0}, - {32064,32730,32732 ,730,730,730 ,0,0,0}, {32767,32067,32732 ,730,730,730 ,0,0,0}, - {32067,32768,32769 ,730,730,730 ,0,0,0}, {32768,32067,32767 ,730,730,730 ,0,0,0}, - {32769,31339,32733 ,730,730,730 ,0,0,0}, {32768,31339,32769 ,730,730,730 ,0,0,0}, - {31685,32729,32735 ,730,730,730 ,0,0,0}, {31681,32728,31684 ,730,730,730 ,0,0,0}, - {31679,32727,31681 ,730,730,730 ,0,0,0}, {32097,32727,31678 ,730,730,730 ,0,0,0}, - {32094,32097,31676 ,730,730,730 ,0,0,0}, {32091,32093,31658 ,730,730,730 ,0,0,0}, - {32088,32091,31664 ,730,730,730 ,0,0,0}, {31665,32087,31662 ,730,730,730 ,0,0,0}, - {31662,32088,31664 ,730,730,730 ,0,0,0}, {31666,32084,31665 ,730,730,730 ,0,0,0}, - {31666,31668,32081 ,730,730,730 ,0,0,0}, {31666,32083,32084 ,730,730,730 ,0,0,0}, - {32079,31674,32076 ,730,730,730 ,0,0,0}, {32081,31668,32079 ,730,730,730 ,0,0,0}, - {32076,31671,32075 ,730,730,730 ,0,0,0}, {31323,32075,31671 ,730,730,730 ,0,0,0}, - {32713,32711,32130 ,730,730,730 ,0,0,0}, {30497,32711,32713 ,730,730,730 ,0,0,0}, - {32123,32125,32705 ,730,730,730 ,0,0,0}, {32125,32698,32705 ,730,730,730 ,0,0,0}, - {32124,32123,32701 ,730,730,730 ,0,0,0}, {32117,32702,32709 ,730,730,730 ,0,0,0}, - {32120,32119,32709 ,730,730,730 ,0,0,0}, {32109,32120,32700 ,730,730,730 ,0,0,0}, - {32114,32109,32699 ,730,730,730 ,0,0,0}, {32104,32112,32708 ,730,730,730 ,0,0,0}, - {32107,32104,32710 ,730,730,730 ,0,0,0}, {32108,32107,32703 ,730,730,730 ,0,0,0}, - {31848,32131,32704 ,730,730,730 ,0,0,0}, {31846,31848,32707 ,730,730,730 ,0,0,0}, - {31844,31846,32706 ,730,730,730 ,0,0,0}, {31841,31844,30481 ,730,730,730 ,0,0,0}, - {31838,31840,31655 ,730,730,730 ,0,0,0}, {31835,31838,31653 ,730,730,730 ,0,0,0}, - {31833,31835,31652 ,730,730,730 ,0,0,0}, {31834,31649,31647 ,730,730,730 ,0,0,0}, - {31852,31850,31647 ,730,730,730 ,0,0,0}, {31855,31852,31646 ,730,730,730 ,0,0,0}, - {31856,31855,31644 ,730,730,730 ,0,0,0}, {31632,31861,31626 ,730,730,730 ,0,0,0}, - {31858,31856,31626 ,730,730,730 ,0,0,0}, {31862,31632,31630 ,730,730,730 ,0,0,0}, - {31632,31862,31861 ,730,730,730 ,0,0,0}, {31630,31633,32715 ,730,730,730 ,0,0,0}, - {32695,32715,31634 ,730,730,730 ,0,0,0}, {31633,31634,32715 ,730,730,730 ,0,0,0}, - {32696,31642,32716 ,730,730,730 ,0,0,0}, {31639,32714,31642 ,730,730,730 ,0,0,0}, - {32716,31642,32714 ,730,730,730 ,0,0,0}, {30497,32714,31639 ,730,730,730 ,0,0,0}, - {32607,32600,32347 ,730,730,730 ,0,0,0}, {32607,32347,32346 ,730,730,730 ,0,0,0}, - {32353,32352,32609 ,730,730,730 ,0,0,0}, {32352,32608,32609 ,730,730,730 ,0,0,0}, - {32355,32353,32598 ,730,730,730 ,0,0,0}, {32358,32355,32599 ,730,730,730 ,0,0,0}, - {32359,32358,32596 ,730,730,730 ,0,0,0}, {32364,32361,32597 ,730,730,730 ,0,0,0}, - {32610,32591,32365 ,730,730,730 ,0,0,0}, {32365,32364,32610 ,730,730,730 ,0,0,0}, - {31622,32615,31625 ,730,730,730 ,0,0,0}, {32770,32590,32592 ,730,730,730 ,0,0,0}, - {32591,32590,32365 ,730,730,730 ,0,0,0}, {32619,32770,32620 ,730,730,730 ,0,0,0}, - {32770,32619,32590 ,730,730,730 ,0,0,0}, {32615,32751,31625 ,730,730,730 ,0,0,0}, - {32612,31625,32751 ,730,730,730 ,0,0,0}, {32612,32751,32613 ,730,730,730 ,0,0,0}, - {31622,32595,32615 ,730,730,730 ,0,0,0}, {31622,31620,32594 ,730,730,730 ,0,0,0}, - {31616,32602,31619 ,730,730,730 ,0,0,0}, {31614,32601,31616 ,730,730,730 ,0,0,0}, - {32389,32601,31613 ,730,730,730 ,0,0,0}, {32387,31611,31592 ,730,730,730 ,0,0,0}, - {32386,31592,31598 ,730,730,730 ,0,0,0}, {32381,32384,31596 ,730,730,730 ,0,0,0}, - {32384,32386,31598 ,730,730,730 ,0,0,0}, {31599,32378,32380 ,730,730,730 ,0,0,0}, - {31596,32380,32381 ,730,730,730 ,0,0,0}, {31600,32375,32378 ,730,730,730 ,0,0,0}, - {31602,31609,32374 ,730,730,730 ,0,0,0}, {31600,31602,32375 ,730,730,730 ,0,0,0}, - {32372,31606,32369 ,730,730,730 ,0,0,0}, {32374,31609,32372 ,730,730,730 ,0,0,0}, - {31605,32369,31606 ,730,730,730 ,0,0,0}, {32771,32689,32772 ,730,730,730 ,0,0,0}, - {32689,32673,32772 ,730,730,730 ,0,0,0}, {32685,32686,32771 ,730,730,730 ,0,0,0}, - {32686,32689,32771 ,730,730,730 ,0,0,0}, {32680,32679,32685 ,730,730,730 ,0,0,0}, - {32190,32679,32681 ,730,730,730 ,0,0,0}, {32187,32190,32677 ,730,730,730 ,0,0,0}, - {32185,32187,32678 ,730,730,730 ,0,0,0}, {32183,32185,32687 ,730,730,730 ,0,0,0}, - {32177,32179,32684 ,730,730,730 ,0,0,0}, {32182,32177,32676 ,730,730,730 ,0,0,0}, - {32171,32182,32675 ,730,730,730 ,0,0,0}, {32172,32171,32682 ,730,730,730 ,0,0,0}, - {32175,32172,32683 ,730,730,730 ,0,0,0}, {32191,32175,32674 ,730,730,730 ,0,0,0}, - {31820,32191,31591 ,730,730,730 ,0,0,0}, {31815,31818,31588 ,730,730,730 ,0,0,0}, - {31814,31815,31586 ,730,730,730 ,0,0,0}, {31812,31814,31585 ,730,730,730 ,0,0,0}, - {31808,31812,31582 ,730,730,730 ,0,0,0}, {31809,31808,31580 ,730,730,730 ,0,0,0}, - {31822,31809,31579 ,730,730,730 ,0,0,0}, {31825,31822,31577 ,730,730,730 ,0,0,0}, - {31564,31828,31558 ,730,730,730 ,0,0,0}, {31558,31826,31577 ,730,730,730 ,0,0,0}, - {31830,31564,31562 ,730,730,730 ,0,0,0}, {31564,31830,31828 ,730,730,730 ,0,0,0}, - {31562,31565,32688 ,730,730,730 ,0,0,0}, {32691,32688,31566 ,730,730,730 ,0,0,0}, - {31565,31566,32688 ,730,730,730 ,0,0,0}, {31568,31575,32691 ,730,730,730 ,0,0,0}, - {31572,32757,31575 ,730,730,730 ,0,0,0}, {32691,31575,32757 ,730,730,730 ,0,0,0}, - {31571,31531,31572 ,730,730,730 ,0,0,0}, {31980,31982,31757 ,730,730,730 ,0,0,0}, - {31926,31873,32737 ,730,730,730 ,0,0,0}, {31873,31872,32737 ,730,730,730 ,0,0,0}, - {31741,32521,32636 ,731,732,733 ,0,0,0}, {32529,32623,32528 ,734,735,736 ,0,0,0}, - {32764,32634,32517 ,737,738,739 ,0,0,0}, {32624,32527,32587 ,740,741,742 ,0,0,0}, - {32576,32575,32586 ,743,744,745 ,0,0,0}, {32525,32628,32626 ,746,747,748 ,0,0,0}, - {32526,32625,32518 ,749,750,751 ,0,0,0}, {32523,32630,32629 ,752,753,754 ,0,0,0}, - {32629,32628,32524 ,754,747,755 ,0,0,0}, {32630,32522,32627 ,753,756,757 ,0,0,0}, - {32522,32630,32523 ,756,753,752 ,0,0,0}, {32664,32627,32497 ,758,757,759 ,0,0,0}, - {32522,32497,32627 ,756,759,757 ,0,0,0}, {32496,31059,32664 ,760,761,758 ,0,0,0}, - {32664,32497,32496 ,758,759,760 ,0,0,0}, {31755,31059,32496 ,761,761,760 ,0,0,0}, - {32526,32525,32626 ,749,746,748 ,0,0,0}, {32628,32525,32524 ,747,746,755 ,0,0,0}, - {32523,32629,32524 ,752,754,755 ,0,0,0}, {32526,32626,32625 ,749,748,750 ,0,0,0}, - {32518,32625,32587 ,751,750,742 ,0,0,0}, {32527,32624,32575 ,741,740,744 ,0,0,0}, - {32527,32518,32587 ,741,751,742 ,0,0,0}, {32576,32586,32585 ,743,745,762 ,0,0,0}, - {32586,32575,32624 ,745,744,740 ,0,0,0}, {32585,32623,32529 ,762,735,734 ,0,0,0}, - {32585,32529,32576 ,762,734,743 ,0,0,0}, {32517,32528,32764 ,739,736,737 ,0,0,0}, - {32623,32764,32528 ,735,737,736 ,0,0,0}, {32634,32521,32517 ,738,732,739 ,0,0,0}, - {31741,32636,31043 ,731,733,35 ,0,0,0}, {32521,32634,32636 ,732,738,733 ,0,0,0}, - {31708,32409,32650 ,763,764,765 ,0,0,0}, {32406,32645,32405 ,766,767,768 ,0,0,0}, - {32647,32649,32407 ,769,770,771 ,0,0,0}, {32643,32400,32642 ,772,773,774 ,0,0,0}, - {32536,32401,32654 ,775,776,777 ,0,0,0}, {32533,32766,32655 ,778,779,780 ,0,0,0}, - {32532,32644,32535 ,781,782,783 ,0,0,0}, {32542,32657,32658 ,784,785,786 ,0,0,0}, - {32658,32766,32538 ,786,779,787 ,0,0,0}, {32657,32539,32648 ,785,788,789 ,0,0,0}, - {32539,32657,32542 ,788,785,784 ,0,0,0}, {32653,32648,32541 ,790,789,791 ,0,0,0}, - {32539,32541,32648 ,788,791,789 ,0,0,0}, {32509,31723,32653 ,792,793,790 ,0,0,0}, - {32653,32541,32509 ,790,791,792 ,0,0,0}, {31722,31723,32509 ,793,793,792 ,0,0,0}, - {32532,32533,32655 ,781,778,780 ,0,0,0}, {32766,32533,32538 ,779,778,787 ,0,0,0}, - {32542,32658,32538 ,784,786,787 ,0,0,0}, {32532,32655,32644 ,781,780,782 ,0,0,0}, - {32535,32644,32642 ,783,782,774 ,0,0,0}, {32400,32643,32401 ,773,772,776 ,0,0,0}, - {32400,32535,32642 ,773,783,774 ,0,0,0}, {32536,32654,32646 ,775,777,794 ,0,0,0}, - {32654,32401,32643 ,777,776,772 ,0,0,0}, {32646,32645,32406 ,794,767,766 ,0,0,0}, - {32646,32406,32536 ,794,766,775 ,0,0,0}, {32407,32405,32647 ,771,768,769 ,0,0,0}, - {32645,32647,32405 ,767,769,768 ,0,0,0}, {32649,32409,32407 ,770,764,771 ,0,0,0}, - {31708,32650,31703 ,763,765,126 ,0,0,0}, {32409,32649,32650 ,764,770,765 ,0,0,0}, - {31675,32447,32726 ,763,795,796 ,0,0,0}, {32449,32725,32448 ,797,798,799 ,0,0,0}, - {32724,32603,32446 ,800,801,802 ,0,0,0}, {32606,32450,32721 ,803,804,805 ,0,0,0}, - {32445,32451,32605 ,806,807,808 ,0,0,0}, {32402,32731,32722 ,809,810,811 ,0,0,0}, - {32403,32723,32452 ,812,813,814 ,0,0,0}, {32444,32732,32730 ,815,816,817 ,0,0,0}, - {32730,32731,32443 ,817,810,818 ,0,0,0}, {32732,32454,32767 ,816,819,820 ,0,0,0}, - {32454,32732,32444 ,819,816,815 ,0,0,0}, {32768,32767,32453 ,821,820,822 ,0,0,0}, - {32454,32453,32767 ,819,822,820 ,0,0,0}, {32442,31339,32768 ,823,793,821 ,0,0,0}, - {32768,32453,32442 ,821,822,823 ,0,0,0}, {31689,31339,32442 ,793,793,823 ,0,0,0}, - {32403,32402,32722 ,812,809,811 ,0,0,0}, {32731,32402,32443 ,810,809,818 ,0,0,0}, - {32444,32730,32443 ,815,817,818 ,0,0,0}, {32403,32722,32723 ,812,811,813 ,0,0,0}, - {32452,32723,32721 ,814,813,805 ,0,0,0}, {32450,32606,32451 ,804,803,807 ,0,0,0}, - {32450,32452,32721 ,804,814,805 ,0,0,0}, {32445,32605,32604 ,806,808,824 ,0,0,0}, - {32605,32451,32606 ,808,807,803 ,0,0,0}, {32604,32725,32449 ,824,798,797 ,0,0,0}, - {32604,32449,32445 ,824,797,806 ,0,0,0}, {32446,32448,32724 ,802,799,800 ,0,0,0}, - {32725,32724,32448 ,798,800,799 ,0,0,0}, {32603,32447,32446 ,801,795,802 ,0,0,0}, - {31675,32726,31323 ,763,796,126 ,0,0,0}, {32447,32603,32726 ,795,801,796 ,0,0,0}, - {31643,32577,32711 ,731,795,796 ,0,0,0}, {32475,32705,32476 ,825,826,799 ,0,0,0}, - {32698,32712,32477 ,827,828,829 ,0,0,0}, {32709,32431,32700 ,830,831,805 ,0,0,0}, - {32472,32432,32702 ,832,833,834 ,0,0,0}, {32430,32710,32708 ,835,836,837 ,0,0,0}, - {32429,32699,32470 ,838,839,814 ,0,0,0}, {32466,32704,32703 ,840,841,842 ,0,0,0}, - {32703,32710,32465 ,842,836,843 ,0,0,0}, {32704,32469,32707 ,841,844,845 ,0,0,0}, - {32469,32704,32466 ,844,841,840 ,0,0,0}, {32706,32707,32467 ,846,845,847 ,0,0,0}, - {32469,32467,32707 ,844,847,845 ,0,0,0}, {32468,30481,32706 ,848,761,846 ,0,0,0}, - {32706,32467,32468 ,846,847,848 ,0,0,0}, {31657,30481,32468 ,761,761,848 ,0,0,0}, - {32429,32430,32708 ,838,835,837 ,0,0,0}, {32710,32430,32465 ,836,835,843 ,0,0,0}, - {32466,32703,32465 ,840,842,843 ,0,0,0}, {32429,32708,32699 ,838,837,839 ,0,0,0}, - {32470,32699,32700 ,814,839,805 ,0,0,0}, {32431,32709,32432 ,831,830,833 ,0,0,0}, - {32431,32470,32700 ,831,814,805 ,0,0,0}, {32472,32702,32701 ,832,834,849 ,0,0,0}, - {32702,32432,32709 ,834,833,830 ,0,0,0}, {32701,32705,32475 ,849,826,825 ,0,0,0}, - {32701,32475,32472 ,849,825,832 ,0,0,0}, {32477,32476,32698 ,829,799,827 ,0,0,0}, - {32705,32698,32476 ,826,827,799 ,0,0,0}, {32712,32577,32477 ,828,795,829 ,0,0,0}, - {31643,32711,30497 ,731,796,35 ,0,0,0}, {32577,32712,32711 ,795,828,796 ,0,0,0}, - {31610,32392,32607 ,850,851,852 ,0,0,0}, {32408,32609,32404 ,853,854,855 ,0,0,0}, - {32608,32600,32396 ,856,801,857 ,0,0,0}, {32596,32412,32597 ,830,858,859 ,0,0,0}, - {32410,32411,32599 ,860,861,862 ,0,0,0}, {32415,32592,32591 ,863,864,865 ,0,0,0}, - {32414,32610,32413 ,866,867,868 ,0,0,0}, {32422,32620,32770 ,869,870,871 ,0,0,0}, - {32770,32592,32417 ,871,864,872 ,0,0,0}, {32620,32579,32621 ,870,873,874 ,0,0,0}, - {32579,32620,32422 ,873,870,869 ,0,0,0}, {32612,32621,32420 ,875,874,876 ,0,0,0}, - {32579,32420,32621 ,873,876,874 ,0,0,0}, {32418,31625,32612 ,877,82,875 ,0,0,0}, - {32612,32420,32418 ,875,876,877 ,0,0,0}, {31624,31625,32418 ,878,82,877 ,0,0,0}, - {32414,32415,32591 ,866,863,865 ,0,0,0}, {32592,32415,32417 ,864,863,872 ,0,0,0}, - {32422,32770,32417 ,869,871,872 ,0,0,0}, {32414,32591,32610 ,866,865,867 ,0,0,0}, - {32413,32610,32597 ,868,867,859 ,0,0,0}, {32412,32596,32411 ,858,830,861 ,0,0,0}, - {32412,32413,32597 ,858,868,859 ,0,0,0}, {32410,32599,32598 ,860,862,879 ,0,0,0}, - {32599,32411,32596 ,862,861,830 ,0,0,0}, {32598,32609,32408 ,879,854,853 ,0,0,0}, - {32598,32408,32410 ,879,853,860 ,0,0,0}, {32396,32404,32608 ,857,855,856 ,0,0,0}, - {32609,32608,32404 ,854,856,855 ,0,0,0}, {32600,32392,32396 ,801,851,857 ,0,0,0}, - {31610,32607,31605 ,850,852,850 ,0,0,0}, {32392,32600,32607 ,851,801,852 ,0,0,0}, - {31576,32486,32673 ,731,851,880 ,0,0,0}, {32581,32685,32490 ,881,882,855 ,0,0,0}, - {32771,32772,32485 ,856,801,857 ,0,0,0}, {32677,32488,32678 ,883,884,859 ,0,0,0}, - {32580,32500,32681 ,860,885,834 ,0,0,0}, {32495,32676,32684 ,886,887,888 ,0,0,0}, - {32393,32687,32489 ,889,890,868 ,0,0,0}, {32493,32682,32675 ,891,892,893 ,0,0,0}, - {32675,32676,32494 ,893,887,894 ,0,0,0}, {32682,32492,32683 ,892,895,896 ,0,0,0}, - {32492,32682,32493 ,895,892,891 ,0,0,0}, {32674,32683,32491 ,897,896,898 ,0,0,0}, - {32492,32491,32683 ,895,898,896 ,0,0,0}, {32474,31591,32674 ,899,761,897 ,0,0,0}, - {32674,32491,32474 ,897,898,899 ,0,0,0}, {31590,31591,32474 ,761,761,899 ,0,0,0}, - {32393,32495,32684 ,889,886,888 ,0,0,0}, {32676,32495,32494 ,887,886,894 ,0,0,0}, - {32493,32675,32494 ,891,893,894 ,0,0,0}, {32393,32684,32687 ,889,888,890 ,0,0,0}, - {32489,32687,32678 ,868,890,859 ,0,0,0}, {32488,32677,32500 ,884,883,885 ,0,0,0}, - {32488,32489,32678 ,884,868,859 ,0,0,0}, {32580,32681,32680 ,860,834,849 ,0,0,0}, - {32681,32500,32677 ,834,885,883 ,0,0,0}, {32680,32685,32581 ,849,882,881 ,0,0,0}, - {32680,32581,32580 ,849,881,860 ,0,0,0}, {32485,32490,32771 ,857,855,856 ,0,0,0}, - {32685,32771,32490 ,882,856,855 ,0,0,0}, {32772,32486,32485 ,801,851,857 ,0,0,0}, - {31576,32673,31571 ,731,880,35 ,0,0,0}, {32486,32772,32673 ,851,801,880 ,0,0,0}, - {31554,32480,32720 ,20,900,900 ,0,0,0}, {32464,31955,32697 ,901,336,901 ,0,0,0}, - {32697,32744,32555 ,901,902,902 ,0,0,0}, {31956,31955,32464 ,336,336,901 ,0,0,0}, - {32480,32744,32720 ,900,902,900 ,0,0,0}, {32744,32480,32555 ,902,900,902 ,0,0,0}, - {32464,32697,32555 ,901,901,902 ,0,0,0}, {32720,31553,31554 ,900,20,20 ,0,0,0}, - {32741,32583,32460 ,903,904,905 ,0,0,0}, {32459,32436,32740 ,906,907,908 ,0,0,0}, - {32459,32740,32741 ,906,908,903 ,0,0,0}, {32459,32741,32460 ,906,903,905 ,0,0,0}, - {32742,32743,32435 ,909,910,911 ,0,0,0}, {32743,32436,32435 ,910,907,911 ,0,0,0}, - {32740,32436,32743 ,908,907,910 ,0,0,0}, {32461,32391,32390 ,912,21,21 ,0,0,0}, - {32461,32390,32742 ,912,21,909 ,0,0,0}, {32435,32461,32742 ,911,912,909 ,0,0,0}, - {32460,32583,32558 ,905,904,913 ,0,0,0}, {32556,32558,32739 ,914,913,915 ,0,0,0}, - {32583,32739,32558 ,904,915,913 ,0,0,0}, {32738,32557,32556 ,916,917,914 ,0,0,0}, - {32556,32739,32738 ,914,915,916 ,0,0,0}, {32557,32694,31933 ,917,918,322 ,0,0,0}, - {32694,32557,32738 ,918,917,916 ,0,0,0}, {32694,31935,31933 ,918,322,322 ,0,0,0}, - {31544,32574,32690 ,15,919,920 ,0,0,0}, {32505,31936,32670 ,921,922,921 ,0,0,0}, - {32670,32748,32499 ,921,923,923 ,0,0,0}, {31937,31936,32505 ,924,922,921 ,0,0,0}, - {32574,32748,32690 ,919,923,920 ,0,0,0}, {32748,32574,32499 ,923,919,923 ,0,0,0}, - {32505,32670,32499 ,921,921,923 ,0,0,0}, {32690,31543,31544 ,920,15,15 ,0,0,0}, - {31534,32506,32669 ,8,925,925 ,0,0,0}, {32481,32005,32671 ,926,372,926 ,0,0,0}, - {32671,32668,32573 ,926,927,927 ,0,0,0}, {32006,32005,32481 ,372,372,926 ,0,0,0}, - {32506,32668,32669 ,925,927,925 ,0,0,0}, {32668,32506,32573 ,927,925,927 ,0,0,0}, - {32481,32671,32573 ,926,926,927 ,0,0,0}, {32669,31533,31534 ,925,8,8 ,0,0,0}, - {32752,32751,32419 ,928,929,930 ,0,0,0}, {32752,32559,32693 ,928,931,932 ,0,0,0}, - {32559,32752,32419 ,931,928,930 ,0,0,0}, {32426,32745,32551 ,933,934,935 ,0,0,0}, - {32551,32745,32693 ,935,934,932 ,0,0,0}, {31918,32746,32425 ,314,936,937 ,0,0,0}, - {32425,31919,31918 ,937,314,314 ,0,0,0}, {32425,32746,32426 ,937,936,933 ,0,0,0}, - {32426,32746,32745 ,933,936,934 ,0,0,0}, {32693,32559,32551 ,932,931,935 ,0,0,0}, - {32419,32751,32560 ,930,929,938 ,0,0,0}, {32503,32560,32617 ,939,938,940 ,0,0,0}, - {32751,32617,32560 ,929,940,938 ,0,0,0}, {32616,32504,32503 ,941,942,939 ,0,0,0}, - {32503,32617,32616 ,939,940,941 ,0,0,0}, {32504,32756,31938 ,942,943,944 ,0,0,0}, - {32756,32504,32616 ,943,942,941 ,0,0,0}, {32756,31939,31938 ,943,324,944 ,0,0,0}, - {32615,32614,32549 ,945,946,947 ,0,0,0}, {32615,32428,32754 ,945,948,949 ,0,0,0}, - {32428,32615,32549 ,948,945,947 ,0,0,0}, {32548,32618,32427 ,950,951,952 ,0,0,0}, - {32427,32618,32754 ,952,951,949 ,0,0,0}, {32342,32755,32502 ,953,954,955 ,0,0,0}, - {32502,32343,32342 ,955,21,953 ,0,0,0}, {32502,32755,32548 ,955,954,950 ,0,0,0}, - {32548,32755,32618 ,950,954,951 ,0,0,0}, {32754,32428,32427 ,949,948,952 ,0,0,0}, - {32549,32614,32508 ,947,946,956 ,0,0,0}, {32562,32508,32589 ,957,956,958 ,0,0,0}, - {32614,32589,32508 ,946,958,956 ,0,0,0}, {32588,32563,32562 ,959,960,957 ,0,0,0}, - {32562,32589,32588 ,957,958,959 ,0,0,0}, {32563,32593,31983 ,960,961,358 ,0,0,0}, - {32593,32563,32588 ,961,960,959 ,0,0,0}, {32593,31985,31983 ,961,358,358 ,0,0,0}, - {32662,32661,32569 ,962,963,964 ,0,0,0}, {32547,32566,32762 ,965,966,967 ,0,0,0}, - {32547,32762,32662 ,965,967,962 ,0,0,0}, {32547,32662,32569 ,965,962,964 ,0,0,0}, - {32663,32761,32567 ,968,969,970 ,0,0,0}, {32761,32566,32567 ,969,966,970 ,0,0,0}, - {32762,32566,32761 ,967,966,969 ,0,0,0}, {32513,31901,31900 ,971,304,304 ,0,0,0}, - {32513,31900,32663 ,971,304,968 ,0,0,0}, {32567,32513,32663 ,970,971,968 ,0,0,0}, - {32569,32661,32568 ,964,963,972 ,0,0,0}, {32571,32568,32640 ,973,972,974 ,0,0,0}, - {32661,32640,32568 ,963,974,972 ,0,0,0}, {32641,32570,32571 ,975,976,973 ,0,0,0}, - {32571,32640,32641 ,973,974,975 ,0,0,0}, {32570,32763,31987 ,976,977,324 ,0,0,0}, - {32763,32570,32641 ,977,976,975 ,0,0,0}, {32763,31988,31987 ,977,978,324 ,0,0,0}, - {31524,32516,32759 ,3,979,979 ,0,0,0}, {32572,31986,32760 ,980,324,980 ,0,0,0}, - {32760,32758,32515 ,980,981,981 ,0,0,0}, {31989,31986,32572 ,982,324,980 ,0,0,0}, - {32516,32758,32759 ,979,981,979 ,0,0,0}, {32758,32516,32515 ,981,979,981 ,0,0,0}, - {32572,32760,32515 ,980,980,981 ,0,0,0}, {32759,31523,31524 ,979,3,3 ,0,0,0}, - {32666,32399,32635 ,983,983,984 ,0,0,0}, {32520,32519,32667 ,984,985,986 ,0,0,0}, - {32635,32520,32667 ,984,984,986 ,0,0,0}, {32519,31807,31806 ,985,235,235 ,0,0,0}, - {32667,32519,31806 ,986,985,235 ,0,0,0}, {32635,32399,32520 ,984,983,984 ,0,0,0}, - {32514,32399,32666 ,987,983,983 ,0,0,0}, {32514,32631,32263 ,987,987,988 ,0,0,0}, - {32631,32514,32666 ,987,987,983 ,0,0,0}, {32631,32261,32263 ,987,988,988 ,0,0,0}, - {32530,32398,32665 ,989,990,990 ,0,0,0}, {32397,32633,32632 ,991,992,991 ,0,0,0}, - {32665,32398,32632 ,990,990,991 ,0,0,0}, {32210,32211,32534 ,508,508,992 ,0,0,0}, - {32633,32397,32534 ,992,991,992 ,0,0,0}, {32534,32211,32633 ,992,508,992 ,0,0,0}, - {32397,32632,32398 ,991,991,990 ,0,0,0}, {32665,32622,32530 ,990,989,989 ,0,0,0}, - {32622,32584,32531 ,989,993,994 ,0,0,0}, {32531,32530,32622 ,994,989,989 ,0,0,0}, - {32257,32584,32258 ,546,993,546 ,0,0,0}, {32584,32257,32531 ,993,546,994 ,0,0,0}, - {32482,32395,32757 ,995,996,996 ,0,0,0}, {32394,32688,32691 ,997,998,997 ,0,0,0}, - {32757,32395,32691 ,996,996,997 ,0,0,0}, {31831,31830,32498 ,257,257,998 ,0,0,0}, - {32688,32394,32498 ,998,997,998 ,0,0,0}, {32498,31830,32688 ,998,257,998 ,0,0,0}, - {32394,32691,32395 ,997,997,996 ,0,0,0}, {32757,32749,32482 ,996,995,995 ,0,0,0}, - {32749,32750,32483 ,995,999,999 ,0,0,0}, {32483,32482,32749 ,999,995,995 ,0,0,0}, - {32229,32750,32228 ,525,999,525 ,0,0,0}, {32750,32229,32483 ,999,525,999 ,0,0,0}, - {32565,32484,32689 ,1000,1001,1001 ,0,0,0}, {32487,32747,32672 ,1002,1003,1004 ,0,0,0}, - {32689,32484,32672 ,1001,1001,1004 ,0,0,0}, {32150,32151,32564 ,508,508,1003 ,0,0,0}, - {32747,32487,32564 ,1003,1002,1003 ,0,0,0}, {32564,32151,32747 ,1003,508,1003 ,0,0,0}, - {32487,32672,32484 ,1002,1004,1001 ,0,0,0}, {32689,32686,32565 ,1001,1000,1000 ,0,0,0}, - {32686,32679,32501 ,1000,1005,1005 ,0,0,0}, {32501,32565,32686 ,1005,1000,1000 ,0,0,0}, - {32189,32679,32190 ,546,1005,546 ,0,0,0}, {32679,32189,32501 ,1005,546,1005 ,0,0,0}, - {32478,32473,32696 ,1006,1007,1007 ,0,0,0}, {32433,32715,32695 ,1008,1009,1008 ,0,0,0}, - {32696,32473,32695 ,1007,1007,1008 ,0,0,0}, {31863,31862,32471 ,257,257,1009 ,0,0,0}, - {32715,32433,32471 ,1009,1008,1009 ,0,0,0}, {32471,31862,32715 ,1009,257,1009 ,0,0,0}, - {32433,32695,32473 ,1008,1008,1007 ,0,0,0}, {32696,32717,32478 ,1007,1006,1006 ,0,0,0}, - {32717,32719,32462 ,1006,1010,1010 ,0,0,0}, {32462,32478,32717 ,1010,1006,1006 ,0,0,0}, - {32169,32719,32168 ,525,1010,525 ,0,0,0}, {32719,32169,32462 ,1010,525,1010 ,0,0,0}, - {32714,32434,32716 ,1011,1011,1012 ,0,0,0}, {32479,32463,32718 ,1012,1013,1013 ,0,0,0}, - {32716,32479,32718 ,1012,1012,1013 ,0,0,0}, {32463,32100,32099 ,1013,324,324 ,0,0,0}, - {32718,32463,32099 ,1013,1013,324 ,0,0,0}, {32716,32434,32479 ,1012,1011,1012 ,0,0,0}, - {32578,32434,32714 ,1014,1011,1011 ,0,0,0}, {32578,32713,32129 ,1014,1014,488 ,0,0,0}, - {32713,32578,32714 ,1014,1014,1011 ,0,0,0}, {32713,32130,32129 ,1014,488,488 ,0,0,0}, - {32735,32440,32733 ,1015,1015,1016 ,0,0,0}, {32456,32441,32769 ,1016,1017,1017 ,0,0,0}, - {32733,32456,32769 ,1016,1016,1017 ,0,0,0}, {32441,32068,32067 ,1017,427,427 ,0,0,0}, - {32769,32441,32067 ,1017,1017,427 ,0,0,0}, {32733,32440,32456 ,1016,1015,1016 ,0,0,0}, - {32457,32440,32735 ,1018,1015,1015 ,0,0,0}, {32457,32736,32101 ,1018,1018,1019 ,0,0,0}, - {32736,32457,32735 ,1018,1018,1015 ,0,0,0}, {32736,32098,32101 ,1018,324,1019 ,0,0,0}, - {32455,32439,32729 ,1020,1021,1021 ,0,0,0}, {32438,32582,32734 ,1022,1023,1022 ,0,0,0}, - {32729,32439,32734 ,1021,1021,1022 ,0,0,0}, {31882,31883,32458 ,205,205,1023 ,0,0,0}, - {32582,32438,32458 ,1023,1022,1023 ,0,0,0}, {32458,31883,32582 ,1023,205,1023 ,0,0,0}, - {32438,32734,32439 ,1022,1022,1021 ,0,0,0}, {32729,32728,32455 ,1021,1020,1020 ,0,0,0}, - {32728,32727,32437 ,1020,1024,1024 ,0,0,0}, {32437,32455,32728 ,1024,1020,1020 ,0,0,0}, - {32096,32727,32097 ,456,1024,456 ,0,0,0}, {32727,32096,32437 ,1024,456,1024 ,0,0,0}, - {32553,32421,32611 ,1025,1026,1026 ,0,0,0}, {32423,32590,32619 ,1027,1028,1027 ,0,0,0}, - {32611,32421,32619 ,1026,1026,1027 ,0,0,0}, {32367,32365,32416 ,641,641,1028 ,0,0,0}, - {32590,32423,32416 ,1028,1027,1028 ,0,0,0}, {32416,32365,32590 ,1028,641,1028 ,0,0,0}, - {32423,32619,32421 ,1027,1027,1026 ,0,0,0}, {32611,32613,32553 ,1026,1025,1025 ,0,0,0}, - {32613,32692,32552 ,1025,1029,1029 ,0,0,0}, {32552,32553,32613 ,1029,1025,1025 ,0,0,0}, - {32036,32692,32037 ,396,1029,396 ,0,0,0}, {32692,32036,32552 ,1029,396,1029 ,0,0,0}, - {32424,32561,32594 ,1030,1031,1031 ,0,0,0}, {32550,32753,32595 ,1032,1033,1032 ,0,0,0}, - {32594,32561,32595 ,1031,1031,1032 ,0,0,0}, {31774,31775,32507 ,205,205,1033 ,0,0,0}, - {32753,32550,32507 ,1033,1032,1033 ,0,0,0}, {32507,31775,32753 ,1033,205,1033 ,0,0,0}, - {32550,32595,32561 ,1032,1032,1031 ,0,0,0}, {32594,32602,32424 ,1031,1030,1030 ,0,0,0}, - {32602,32601,32554 ,1030,1034,1034 ,0,0,0}, {32554,32424,32602 ,1034,1030,1030 ,0,0,0}, - {32388,32601,32389 ,456,1034,456 ,0,0,0}, {32601,32388,32554 ,1034,456,1034 ,0,0,0}, - {32546,32544,32639 ,1035,1036,1036 ,0,0,0}, {32540,32765,32656 ,1037,1038,1037 ,0,0,0}, - {32639,32544,32656 ,1036,1036,1037 ,0,0,0}, {32294,32293,32537 ,641,641,1038 ,0,0,0}, - {32765,32540,32537 ,1038,1037,1038 ,0,0,0}, {32537,32293,32765 ,1038,641,1038 ,0,0,0}, - {32540,32656,32544 ,1037,1037,1036 ,0,0,0}, {32639,32638,32546 ,1036,1035,1035 ,0,0,0}, - {32638,32660,32511 ,1035,1039,1040 ,0,0,0}, {32511,32546,32638 ,1040,1035,1035 ,0,0,0}, - {32340,32660,32341 ,396,1039,396 ,0,0,0}, {32660,32340,32511 ,1039,396,1040 ,0,0,0}, - {32652,32510,32637 ,1041,1041,1042 ,0,0,0}, {32543,32512,32659 ,1042,1043,1044 ,0,0,0}, - {32637,32543,32659 ,1042,1042,1044 ,0,0,0}, {32512,32260,32262 ,1043,1045,1045 ,0,0,0}, - {32659,32512,32262 ,1044,1043,1045 ,0,0,0}, {32637,32510,32543 ,1042,1041,1042 ,0,0,0}, - {32545,32510,32652 ,1046,1041,1041 ,0,0,0}, {32545,32651,32322 ,1046,1046,670 ,0,0,0}, - {32651,32545,32652 ,1046,1046,1041 ,0,0,0}, {32651,32323,32322 ,1046,670,670 ,0,0,0} -// M3abstandhalter10mm.prt - , {32773,32452,32774 ,18258,18259,18260 ,0,0,0}, {32775,32776,32777 ,18261,18262,18263 ,0,0,0}, - {32774,32452,32777 ,18260,18259,18263 ,0,0,0}, {32776,32775,32778 ,18262,18261,18264 ,0,0,0}, - {32778,32779,32776 ,18264,18265,18262 ,0,0,0}, {32779,32780,32781 ,18265,18266,18267 ,0,0,0}, - {32778,32780,32779 ,18264,18266,18265 ,0,0,0}, {32775,32777,32452 ,18261,18263,18259 ,0,0,0}, - {32782,32783,32784 ,18268,18269,18270 ,0,0,0}, {32783,32781,32784 ,18269,18267,18270 ,0,0,0}, - {32782,32785,32786 ,18268,18271,18272 ,0,0,0}, {32786,32783,32782 ,18272,18269,18268 ,0,0,0}, - {32785,32787,32788 ,18271,18273,18274 ,0,0,0}, {32785,32788,32786 ,18271,18274,18272 ,0,0,0}, - {32780,32784,32781 ,18266,18270,18267 ,0,0,0}, {32789,32788,32787 ,18275,18274,18273 ,0,0,0}, - {32790,31675,32791 ,18276,18277,126 ,0,0,0}, {32790,32791,32789 ,18276,126,18275 ,0,0,0}, - {32787,32790,32789 ,18273,18276,18275 ,0,0,0}, {32773,32774,32792 ,18258,18260,18278 ,0,0,0}, - {32792,32793,32794 ,18278,18279,18280 ,0,0,0}, {32794,32773,32792 ,18280,18258,18278 ,0,0,0}, - {32795,32793,32796 ,18281,18279,18282 ,0,0,0}, {32793,32795,32794 ,18279,18281,18280 ,0,0,0}, - {32797,32798,32796 ,18283,18284,18282 ,0,0,0}, {32795,32796,32798 ,18281,18282,18284 ,0,0,0}, - {32797,32799,32800 ,18283,18285,18286 ,0,0,0}, {32800,32798,32797 ,18286,18284,18283 ,0,0,0}, - {32801,32799,32802 ,18287,18285,18288 ,0,0,0}, {32799,32801,32800 ,18285,18287,18286 ,0,0,0}, - {32803,32804,32802 ,18289,18290,18288 ,0,0,0}, {32801,32802,32804 ,18287,18288,18290 ,0,0,0}, - {32803,32805,32806 ,18289,18291,18292 ,0,0,0}, {32806,32804,32803 ,18292,18290,18289 ,0,0,0}, - {31689,32805,32807 ,18293,18291,18003 ,0,0,0}, {32805,31689,32806 ,18291,18293,18292 ,0,0,0}, - {32808,32809,32810 ,18294,18295,18296 ,0,0,0}, {32811,32812,32813 ,18297,21,18298 ,0,0,0}, - {32814,32808,32815 ,18299,18294,18300 ,0,0,0}, {32808,32814,32809 ,18294,18299,18295 ,0,0,0}, - {32814,32815,32816 ,18299,18300,18301 ,0,0,0}, {32817,32818,32816 ,18302,18303,18301 ,0,0,0}, - {32816,32815,32817 ,18301,18300,18302 ,0,0,0}, {32818,32819,32820 ,18303,18304,126 ,0,0,0}, - {32819,32818,32817 ,18304,18303,18302 ,0,0,0}, {32819,32821,32820 ,18304,3135,126 ,0,0,0}, - {32808,32810,32822 ,18294,18296,18305 ,0,0,0}, {32823,32822,32824 ,18306,18305,18307 ,0,0,0}, - {32810,32824,32822 ,18296,18307,18305 ,0,0,0}, {32825,32823,32826 ,18308,18306,18309 ,0,0,0}, - {32823,32824,32826 ,18306,18307,18309 ,0,0,0}, {32825,32827,32828 ,18308,18310,18311 ,0,0,0}, - {32828,32823,32825 ,18311,18306,18308 ,0,0,0}, {32829,32827,32830 ,18312,18310,18313 ,0,0,0}, - {32827,32829,32828 ,18310,18312,18311 ,0,0,0}, {32812,32829,32813 ,21,18312,18298 ,0,0,0}, - {32830,32813,32829 ,18313,18298,18312 ,0,0,0}, {32831,32832,32833 ,18314,18315,18316 ,0,0,0}, - {32811,32834,32833 ,18297,18317,18316 ,0,0,0}, {32835,32836,32837 ,18318,18319,18320 ,0,0,0}, - {32836,32832,32838 ,18319,18315,18321 ,0,0,0}, {32839,32840,32841 ,18322,18323,18324 ,0,0,0}, - {32842,32843,32839 ,18325,18326,18322 ,0,0,0}, {32844,32845,32846 ,18327,18328,18329 ,0,0,0}, - {32845,32844,32847 ,18328,18327,18330 ,0,0,0}, {32848,32849,32846 ,18037,18331,18329 ,0,0,0}, - {32844,32846,32849 ,18327,18329,18331 ,0,0,0}, {32850,32849,32848 ,18038,18331,18037 ,0,0,0}, - {32841,32847,32839 ,18324,18330,18322 ,0,0,0}, {32841,32845,32847 ,18324,18328,18330 ,0,0,0}, - {32836,32835,32842 ,18319,18318,18325 ,0,0,0}, {32839,32843,32840 ,18322,18326,18323 ,0,0,0}, - {32842,32835,32843 ,18325,18318,18326 ,0,0,0}, {32832,32831,32838 ,18315,18314,18321 ,0,0,0}, - {32837,32836,32838 ,18320,18319,18321 ,0,0,0}, {32833,32812,32811 ,18316,21,18297 ,0,0,0}, - {32831,32833,32834 ,18314,18316,18317 ,0,0,0}, {32851,32852,32853 ,18332,1077,18332 ,0,0,0}, - {32854,32855,32853 ,18333,18333,18332 ,0,0,0}, {32855,32851,32853 ,18333,18332,18332 ,0,0,0}, - {32851,32856,32852 ,18332,18334,1077 ,0,0,0}, {32857,32858,32859 ,18335,18336,324 ,0,0,0}, - {32860,32861,32862 ,18337,18338,18339 ,0,0,0}, {32859,32858,32862 ,324,18336,18339 ,0,0,0}, - {32861,32860,32863 ,18338,18337,18340 ,0,0,0}, {32863,32864,32861 ,18340,18341,18338 ,0,0,0}, - {32864,32865,32866 ,18341,18342,18343 ,0,0,0}, {32863,32865,32864 ,18340,18342,18341 ,0,0,0}, - {32860,32862,32858 ,18337,18339,18336 ,0,0,0}, {32867,32868,32869 ,18344,18345,18346 ,0,0,0}, - {32868,32866,32869 ,18345,18343,18346 ,0,0,0}, {32867,32870,32871 ,18344,18347,18348 ,0,0,0}, - {32871,32868,32867 ,18348,18345,18344 ,0,0,0}, {32870,32872,32873 ,18347,18349,18350 ,0,0,0}, - {32870,32873,32871 ,18347,18350,18348 ,0,0,0}, {32865,32869,32866 ,18342,18346,18343 ,0,0,0}, - {32874,32873,32872 ,18351,18350,18349 ,0,0,0}, {32875,32876,32877 ,18352,18353,126 ,0,0,0}, - {32875,32877,32874 ,18352,126,18351 ,0,0,0}, {32872,32875,32874 ,18349,18352,18351 ,0,0,0}, - {32857,32859,32878 ,18335,324,18354 ,0,0,0}, {32878,32879,32880 ,18354,18355,18356 ,0,0,0}, - {32880,32857,32878 ,18356,18335,18354 ,0,0,0}, {32881,32879,32882 ,18357,18355,18358 ,0,0,0}, - {32879,32881,32880 ,18355,18357,18356 ,0,0,0}, {32883,32884,32882 ,18359,18360,18358 ,0,0,0}, - {32881,32882,32884 ,18357,18358,18360 ,0,0,0}, {32883,32885,32886 ,18359,18361,18362 ,0,0,0}, - {32886,32884,32883 ,18362,18360,18359 ,0,0,0}, {32887,32885,32888 ,18363,18361,18364 ,0,0,0}, - {32885,32887,32886 ,18361,18363,18362 ,0,0,0}, {32889,32890,32888 ,18365,18366,18364 ,0,0,0}, - {32887,32888,32890 ,18363,18364,18366 ,0,0,0}, {32889,32891,32892 ,18365,18367,18368 ,0,0,0}, - {32892,32890,32889 ,18368,18366,18365 ,0,0,0}, {32893,32891,32894 ,18369,18367,18188 ,0,0,0}, - {32891,32893,32892 ,18367,18369,18368 ,0,0,0}, {32895,32896,32897 ,18370,18371,18372 ,0,0,0}, - {32898,32851,32899 ,18373,324,18374 ,0,0,0}, {32900,32895,32901 ,18375,18370,18376 ,0,0,0}, - {32895,32900,32896 ,18370,18375,18371 ,0,0,0}, {32900,32901,32902 ,18375,18376,18377 ,0,0,0}, - {32903,32904,32902 ,18378,18379,18377 ,0,0,0}, {32902,32901,32903 ,18377,18376,18378 ,0,0,0}, - {32904,32905,32906 ,18379,18380,18092 ,0,0,0}, {32905,32904,32903 ,18380,18379,18378 ,0,0,0}, - {32905,32907,32906 ,18380,18381,18092 ,0,0,0}, {32895,32897,32908 ,18370,18372,18382 ,0,0,0}, - {32909,32908,32910 ,18383,18382,18384 ,0,0,0}, {32897,32910,32908 ,18372,18384,18382 ,0,0,0}, - {32911,32909,32912 ,18385,18383,18386 ,0,0,0}, {32909,32910,32912 ,18383,18384,18386 ,0,0,0}, - {32911,32913,32914 ,18385,18387,18388 ,0,0,0}, {32914,32909,32911 ,18388,18383,18385 ,0,0,0}, - {32915,32913,32916 ,18389,18387,18390 ,0,0,0}, {32913,32915,32914 ,18387,18389,18388 ,0,0,0}, - {32851,32915,32899 ,324,18389,18374 ,0,0,0}, {32916,32899,32915 ,18390,18374,18389 ,0,0,0}, - {32917,32918,32919 ,18391,18392,18393 ,0,0,0}, {32898,32920,32919 ,18373,18394,18393 ,0,0,0}, - {32921,32922,32923 ,18395,18396,18397 ,0,0,0}, {32922,32918,32924 ,18396,18392,18398 ,0,0,0}, - {32925,32926,32927 ,18399,18400,18401 ,0,0,0}, {32928,32929,32925 ,18402,18403,18399 ,0,0,0}, - {32930,32931,32932 ,18404,18405,18406 ,0,0,0}, {32931,32930,32933 ,18405,18404,18407 ,0,0,0}, - {32934,32935,32932 ,82,18408,18406 ,0,0,0}, {32930,32932,32935 ,18404,18406,18408 ,0,0,0}, - {32936,32935,32934 ,18103,18408,82 ,0,0,0}, {32927,32933,32925 ,18401,18407,18399 ,0,0,0}, - {32927,32931,32933 ,18401,18405,18407 ,0,0,0}, {32922,32921,32928 ,18396,18395,18402 ,0,0,0}, - {32925,32929,32926 ,18399,18403,18400 ,0,0,0}, {32928,32921,32929 ,18402,18395,18403 ,0,0,0}, - {32918,32917,32924 ,18392,18391,18398 ,0,0,0}, {32923,32922,32924 ,18397,18396,18398 ,0,0,0}, - {32919,32851,32898 ,18393,324,18373 ,0,0,0}, {32917,32919,32920 ,18391,18393,18394 ,0,0,0}, - {32937,32808,32938 ,2197,2197,2197 ,0,0,0}, {32939,32940,32808 ,2197,2197,2197 ,0,0,0}, - {32940,32938,32808 ,2197,2197,2197 ,0,0,0}, {32938,32941,32937 ,2197,2197,2197 ,0,0,0}, - {32942,32943,32845 ,730,730,730 ,0,0,0}, {32798,32944,32945 ,730,730,730 ,0,0,0}, - {32946,32947,32835 ,730,730,730 ,0,0,0}, {32843,32947,32840 ,730,730,730 ,0,0,0}, - {32811,32948,32834 ,730,730,730 ,0,0,0}, {32834,32949,32831 ,730,730,730 ,0,0,0}, - {32950,32837,32838 ,730,730,730 ,0,0,0}, {32830,32951,32813 ,730,730,730 ,0,0,0}, - {32827,32952,32830 ,730,730,730 ,0,0,0}, {32953,32952,32825 ,730,730,730 ,0,0,0}, - {32825,32826,32953 ,730,730,730 ,0,0,0}, {32814,32816,32954 ,730,730,730 ,0,0,0}, - {32955,32826,32824 ,730,730,730 ,0,0,0}, {32809,32956,32957 ,730,730,730 ,0,0,0}, - {32958,32816,32818 ,730,730,730 ,0,0,0}, {31689,32818,32820 ,730,730,730 ,0,0,0}, - {31689,32959,32806 ,730,730,730 ,0,0,0}, {32960,32801,32961 ,730,730,730 ,0,0,0}, - {32804,32806,32962 ,730,730,730 ,0,0,0}, {32804,32962,32961 ,730,730,730 ,0,0,0}, - {32960,32963,32800 ,730,730,730 ,0,0,0}, {32798,32800,32944 ,730,730,730 ,0,0,0}, - {32810,32957,32824 ,730,730,730 ,0,0,0}, {32795,32945,32964 ,730,730,730 ,0,0,0}, - {32773,32794,32965 ,730,730,730 ,0,0,0}, {32773,32966,32452 ,730,730,730 ,0,0,0}, - {32966,32967,32452 ,730,730,730 ,0,0,0}, {32794,32964,32968 ,730,730,730 ,0,0,0}, - {32969,32775,32967 ,730,730,730 ,0,0,0}, {32778,32969,32970 ,730,730,730 ,0,0,0}, - {32971,32780,32972 ,730,730,730 ,0,0,0}, {32780,32778,32972 ,730,730,730 ,0,0,0}, - {32784,32971,32973 ,730,730,730 ,0,0,0}, {32974,32787,32785 ,730,730,730 ,0,0,0}, - {32975,32782,32973 ,730,730,730 ,0,0,0}, {32974,32785,32976 ,730,730,730 ,0,0,0}, - {32948,32811,31660 ,730,730,730 ,0,0,0}, {32790,32787,32977 ,730,730,730 ,0,0,0}, - {32974,32977,32787 ,730,730,730 ,0,0,0}, {32790,32978,31675 ,730,730,730 ,0,0,0}, - {32978,32790,32977 ,730,730,730 ,0,0,0}, {31675,32848,32846 ,730,730,730 ,0,0,0}, - {32978,32848,31675 ,730,730,730 ,0,0,0}, {32979,32942,32841 ,730,730,730 ,0,0,0}, - {31660,32811,32813 ,730,730,730 ,0,0,0}, {32975,32976,32782 ,730,730,730 ,0,0,0}, - {32976,32785,32782 ,730,730,730 ,0,0,0}, {32784,32973,32782 ,730,730,730 ,0,0,0}, - {32780,32971,32784 ,730,730,730 ,0,0,0}, {32970,32972,32778 ,730,730,730 ,0,0,0}, - {32775,32969,32778 ,730,730,730 ,0,0,0}, {32452,32967,32775 ,730,730,730 ,0,0,0}, - {32965,32966,32773 ,730,730,730 ,0,0,0}, {32968,32965,32794 ,730,730,730 ,0,0,0}, - {32795,32964,32794 ,730,730,730 ,0,0,0}, {32798,32945,32795 ,730,730,730 ,0,0,0}, - {32963,32944,32800 ,730,730,730 ,0,0,0}, {32801,32960,32800 ,730,730,730 ,0,0,0}, - {32804,32961,32801 ,730,730,730 ,0,0,0}, {32959,32962,32806 ,730,730,730 ,0,0,0}, - {32820,32959,31689 ,730,730,730 ,0,0,0}, {32958,32818,31689 ,730,730,730 ,0,0,0}, - {32954,32816,32958 ,730,730,730 ,0,0,0}, {32809,32814,32956 ,730,730,730 ,0,0,0}, - {32814,32954,32956 ,730,730,730 ,0,0,0}, {32810,32809,32957 ,730,730,730 ,0,0,0}, - {32955,32824,32957 ,730,730,730 ,0,0,0}, {32953,32826,32955 ,730,730,730 ,0,0,0}, - {32827,32825,32952 ,730,730,730 ,0,0,0}, {32951,32830,32952 ,730,730,730 ,0,0,0}, - {31660,32813,32951 ,730,730,730 ,0,0,0}, {32834,32948,32949 ,730,730,730 ,0,0,0}, - {32838,32831,32949 ,730,730,730 ,0,0,0}, {32946,32837,32950 ,730,730,730 ,0,0,0}, - {32950,32838,32949 ,730,730,730 ,0,0,0}, {32947,32843,32835 ,730,730,730 ,0,0,0}, - {32946,32835,32837 ,730,730,730 ,0,0,0}, {32947,32979,32840 ,730,730,730 ,0,0,0}, - {32841,32942,32845 ,730,730,730 ,0,0,0}, {32840,32979,32841 ,730,730,730 ,0,0,0}, - {32845,32943,32846 ,730,730,730 ,0,0,0}, {31675,32846,32943 ,730,730,730 ,0,0,0}, - {32980,32981,32925 ,18409,18410,18410 ,0,0,0}, {32981,32852,32856 ,18410,1433,1433 ,0,0,0}, - {32925,32981,32856 ,18410,18410,1433 ,0,0,0}, {32925,32982,32980 ,18410,18409,18409 ,0,0,0}, - {32854,32983,32895 ,2162,18411,18411 ,0,0,0}, {32983,32937,32941 ,18411,2162,2162 ,0,0,0}, - {32895,32983,32941 ,18411,18411,2162 ,0,0,0}, {32895,32855,32854 ,18411,2162,2162 ,0,0,0}, - {31675,32943,32984 ,18353,18412,18413 ,0,0,0}, {32947,32985,32979 ,18414,18415,18416 ,0,0,0}, - {32986,32987,32942 ,18417,18418,18419 ,0,0,0}, {32988,32949,32989 ,18420,18421,18422 ,0,0,0}, - {32946,32950,32990 ,18423,18239,18424 ,0,0,0}, {32951,32991,32992 ,18425,18426,18427 ,0,0,0}, - {32992,32993,31660 ,18427,324,18428 ,0,0,0}, {32955,32994,32953 ,18429,18430,18431 ,0,0,0}, - {32995,32952,32953 ,18432,18433,18431 ,0,0,0}, {32957,32996,32997 ,18434,18435,18436 ,0,0,0}, - {32997,32955,32957 ,18436,18429,18434 ,0,0,0}, {32996,32956,32998 ,18435,18437,18438 ,0,0,0}, - {32956,32996,32957 ,18437,18435,18434 ,0,0,0}, {32999,32998,32954 ,18439,18438,18440 ,0,0,0}, - {32956,32954,32998 ,18437,18440,18438 ,0,0,0}, {32958,32807,32999 ,18441,18256,18439 ,0,0,0}, - {32999,32954,32958 ,18439,18440,18441 ,0,0,0}, {31689,32807,32958 ,18002,18256,18441 ,0,0,0}, - {32997,32994,32955 ,18436,18430,18429 ,0,0,0}, {32995,32953,32994 ,18432,18431,18430 ,0,0,0}, - {32995,32991,32952 ,18432,18426,18433 ,0,0,0}, {32989,32948,32993 ,18422,18442,324 ,0,0,0}, - {32951,32992,31660 ,18425,18427,18428 ,0,0,0}, {32952,32991,32951 ,18433,18426,18425 ,0,0,0}, - {32993,32948,31660 ,324,18442,18428 ,0,0,0}, {32948,32989,32949 ,18442,18422,18421 ,0,0,0}, - {32990,32950,32988 ,18424,18239,18420 ,0,0,0}, {32950,32949,32988 ,18239,18421,18420 ,0,0,0}, - {32946,33000,32947 ,18423,18443,18414 ,0,0,0}, {33000,32946,32990 ,18443,18423,18424 ,0,0,0}, - {32986,32979,32985 ,18417,18416,18415 ,0,0,0}, {33000,32985,32947 ,18443,18415,18414 ,0,0,0}, - {32942,32987,32943 ,18419,18418,18412 ,0,0,0}, {32979,32986,32942 ,18416,18417,18419 ,0,0,0}, - {31675,32984,32791 ,18353,18413,3345 ,0,0,0}, {32943,32987,32984 ,18412,18418,18413 ,0,0,0}, - {32812,33001,32939 ,18444,18444,18113 ,0,0,0}, {32812,33002,33003 ,18444,18113,18113 ,0,0,0}, - {32812,33003,33001 ,18444,18113,18444 ,0,0,0}, {33001,32940,32939 ,18444,18113,18113 ,0,0,0}, - {32890,32892,33004 ,7758,7880,7627 ,0,0,0}, {32898,32899,33005 ,726,726,7627 ,0,0,0}, - {32884,33006,33007 ,726,18445,7755 ,0,0,0}, {33008,32886,33009 ,8017,7627,7627 ,0,0,0}, - {33010,32857,33011 ,18446,7758,18447 ,0,0,0}, {33011,32880,33012 ,18447,7264,7249 ,0,0,0}, - {33013,32863,33014 ,18448,7627,18449 ,0,0,0}, {33007,33015,32881 ,7755,8018,7755 ,0,0,0}, - {32860,33016,33014 ,7761,18450,18449 ,0,0,0}, {33017,32865,32863 ,18451,726,7627 ,0,0,0}, - {32865,33017,33018 ,726,18451,726 ,0,0,0}, {32858,33010,33016 ,7755,18446,18450 ,0,0,0}, - {33019,32869,33018 ,7264,7627,726 ,0,0,0}, {32867,33020,32870 ,7758,7264,7880 ,0,0,0}, - {33021,33022,32872 ,726,7880,7627 ,0,0,0}, {33023,32900,33024 ,726,7627,726 ,0,0,0}, - {33025,32911,32912 ,726,7627,7627 ,0,0,0}, {33022,33026,32875 ,7880,7627,7880 ,0,0,0}, - {32876,32932,33027 ,7627,7627,726 ,0,0,0}, {32931,33028,33027 ,7627,7627,726 ,0,0,0}, - {32929,33029,32926 ,7625,7627,7627 ,0,0,0}, {32927,32926,33030 ,726,7627,726 ,0,0,0}, - {32910,33031,32912 ,7627,726,7627 ,0,0,0}, {33028,32931,32927 ,7627,7627,726 ,0,0,0}, - {33032,32923,32924 ,7627,726,726 ,0,0,0}, {32921,32923,33033 ,7627,726,7627 ,0,0,0}, - {32898,33005,33034 ,726,7627,726 ,0,0,0}, {33034,33035,32920 ,726,7627,7627 ,0,0,0}, - {33036,32916,32913 ,7627,726,726 ,0,0,0}, {33035,32924,32917 ,7627,726,726 ,0,0,0}, - {33036,32911,33025 ,7627,7627,726 ,0,0,0}, {32916,33037,32899 ,726,726,726 ,0,0,0}, - {33029,32921,33033 ,7627,7627,7627 ,0,0,0}, {32910,32897,33038 ,7627,7625,726 ,0,0,0}, - {33023,32896,32900 ,726,726,7627 ,0,0,0}, {33024,32900,32902 ,726,7627,726 ,0,0,0}, - {32896,33023,33038 ,726,726,726 ,0,0,0}, {33026,32934,32876 ,7627,7627,7627 ,0,0,0}, - {33039,32902,32904 ,726,726,7627 ,0,0,0}, {32902,33039,33024 ,726,726,726 ,0,0,0}, - {32893,32904,32906 ,7627,7627,7627 ,0,0,0}, {32893,33039,32904 ,7627,726,7627 ,0,0,0}, - {32906,33040,32893 ,7627,7758,7627 ,0,0,0}, {33041,33009,32887 ,7758,7627,7758 ,0,0,0}, - {33019,33042,32867 ,7264,7761,7758 ,0,0,0}, {33010,32858,32857 ,18446,7755,7758 ,0,0,0}, - {32897,32896,33038 ,7625,726,726 ,0,0,0}, {33031,32910,33038 ,726,7627,726 ,0,0,0}, - {33025,32912,33031 ,726,7627,726 ,0,0,0}, {32913,32911,33036 ,726,7627,7627 ,0,0,0}, - {33037,32916,33036 ,726,726,7627 ,0,0,0}, {33005,32899,33037 ,7627,726,726 ,0,0,0}, - {32920,32898,33034 ,7627,726,726 ,0,0,0}, {32917,32920,33035 ,726,7627,7627 ,0,0,0}, - {33032,32924,33035 ,7627,726,7627 ,0,0,0}, {33033,32923,33032 ,7627,726,7627 ,0,0,0}, - {32929,32921,33029 ,7625,7627,7627 ,0,0,0}, {33030,32926,33029 ,726,7627,7627 ,0,0,0}, - {33028,32927,33030 ,7627,726,726 ,0,0,0}, {32932,32931,33027 ,7627,7627,726 ,0,0,0}, - {32934,32932,32876 ,7627,7627,7627 ,0,0,0}, {32875,33026,32876 ,7880,7627,7627 ,0,0,0}, - {32872,33022,32875 ,7627,7880,7880 ,0,0,0}, {33020,33021,32870 ,7264,726,7880 ,0,0,0}, - {33021,32872,32870 ,726,7627,7880 ,0,0,0}, {33042,33020,32867 ,7761,7264,7758 ,0,0,0}, - {32869,33019,32867 ,7627,7264,7758 ,0,0,0}, {32865,33018,32869 ,726,726,7627 ,0,0,0}, - {33013,33017,32863 ,18448,18451,7627 ,0,0,0}, {32860,33014,32863 ,7761,18449,7627 ,0,0,0}, - {32858,33016,32860 ,7755,18450,7761 ,0,0,0}, {33011,32857,32880 ,18447,7758,7264 ,0,0,0}, - {33015,33012,32880 ,8018,7249,7264 ,0,0,0}, {32884,33007,32881 ,726,7755,7755 ,0,0,0}, - {32881,33015,32880 ,7755,8018,7264 ,0,0,0}, {32886,33006,32884 ,7627,18445,726 ,0,0,0}, - {32886,32887,33009 ,7627,7758,7627 ,0,0,0}, {32886,33008,33006 ,7627,8017,18445 ,0,0,0}, - {32887,32890,33041 ,7758,7758,7758 ,0,0,0}, {33004,32892,33040 ,7627,7880,7758 ,0,0,0}, - {33041,32890,33004 ,7758,7758,7627 ,0,0,0}, {32893,33040,32892 ,7627,7758,7880 ,0,0,0}, - {33002,32839,33043 ,1398,18452,18452 ,0,0,0}, {32980,32982,32839 ,18453,18453,18452 ,0,0,0}, - {32982,33043,32839 ,18453,18452,18452 ,0,0,0}, {33043,33003,33002 ,18452,1398,1398 ,0,0,0}, - {33044,32906,32907 ,18454,18092,18121 ,0,0,0}, {33009,33041,32938 ,18455,18456,18457 ,0,0,0}, - {33045,33004,33046 ,18458,18459,18460 ,0,0,0}, {33008,33047,33006 ,18461,18462,18463 ,0,0,0}, - {33048,33001,33010 ,18464,7309,18465 ,0,0,0}, {33049,33012,33015 ,18466,18467,18468 ,0,0,0}, - {33018,33017,33050 ,18469,18470,18471 ,0,0,0}, {33013,33014,33051 ,18472,18473,18474 ,0,0,0}, - {33019,33052,33042 ,18475,18476,18477 ,0,0,0}, {33043,33021,33020 ,18478,18479,18480 ,0,0,0}, - {33042,33043,33020 ,18477,18478,18480 ,0,0,0}, {33021,33053,33022 ,18479,18481,18482 ,0,0,0}, - {33053,33021,33043 ,18481,18479,18478 ,0,0,0}, {33053,33054,33022 ,18481,18483,18482 ,0,0,0}, - {33055,33026,33054 ,18484,18485,18483 ,0,0,0}, {33022,33054,33026 ,18482,18483,18485 ,0,0,0}, - {33055,32936,32934 ,18484,18486,82 ,0,0,0}, {32934,33026,33055 ,82,18485,18484 ,0,0,0}, - {33050,33052,33019 ,18471,18476,18475 ,0,0,0}, {33042,33052,33043 ,18477,18476,18478 ,0,0,0}, - {33017,33056,33050 ,18470,18487,18471 ,0,0,0}, {33019,33018,33050 ,18475,18469,18471 ,0,0,0}, - {33051,33056,33013 ,18474,18487,18472 ,0,0,0}, {33017,33013,33056 ,18470,18472,18487 ,0,0,0}, - {33051,33016,33001 ,18474,18488,7309 ,0,0,0}, {33014,33016,33051 ,18473,18488,18474 ,0,0,0}, - {33048,33010,33011 ,18464,18465,18489 ,0,0,0}, {33001,33016,33010 ,7309,18488,18465 ,0,0,0}, - {33012,33049,33048 ,18467,18466,18464 ,0,0,0}, {33048,33011,33012 ,18464,18489,18467 ,0,0,0}, - {33007,33057,33015 ,18490,18491,18468 ,0,0,0}, {33057,33049,33015 ,18491,18466,18468 ,0,0,0}, - {33057,33006,33047 ,18491,18463,18462 ,0,0,0}, {33006,33057,33007 ,18463,18491,18490 ,0,0,0}, - {33008,33009,32938 ,18461,18455,18457 ,0,0,0}, {33008,32938,33047 ,18461,18457,18462 ,0,0,0}, - {33041,33004,33045 ,18456,18459,18458 ,0,0,0}, {33041,33045,32938 ,18456,18458,18457 ,0,0,0}, - {33046,33040,33044 ,18460,18492,18454 ,0,0,0}, {33004,33040,33046 ,18459,18492,18460 ,0,0,0}, - {32906,33044,33040 ,18092,18454,18492 ,0,0,0}, {32930,32982,32933 ,7792,726,7658 ,0,0,0}, - {32982,32925,32933 ,726,726,7658 ,0,0,0}, {32936,32982,32935 ,7664,726,7662 ,0,0,0}, - {32982,32930,32935 ,726,7792,7662 ,0,0,0}, {33054,32982,33055 ,7662,726,5488 ,0,0,0}, - {32982,32936,33055 ,726,7664,5488 ,0,0,0}, {33043,32982,33053 ,726,726,726 ,0,0,0}, - {32982,33054,33053 ,726,7662,726 ,0,0,0}, {33057,32940,33049 ,726,726,17470 ,0,0,0}, - {33049,32940,33048 ,17470,726,7628 ,0,0,0}, {32940,33001,33048 ,726,726,7628 ,0,0,0}, - {32940,33047,32938 ,726,726,726 ,0,0,0}, {32940,33057,33047 ,726,726,726 ,0,0,0}, - {32908,32855,32895 ,726,726,726 ,0,0,0}, {32914,32855,32909 ,7661,726,7659 ,0,0,0}, - {32855,32908,32909 ,726,726,7659 ,0,0,0}, {32851,32855,32915 ,7661,726,7661 ,0,0,0}, - {32855,32914,32915 ,726,7661,7661 ,0,0,0}, {32856,32919,32918 ,7660,7660,7660 ,0,0,0}, - {32851,32919,32856 ,726,7660,7660 ,0,0,0}, {32856,32928,32925 ,7660,726,726 ,0,0,0}, - {32856,32922,32928 ,7660,7658,726 ,0,0,0}, {32918,32922,32856 ,7660,7658,7660 ,0,0,0}, - {33043,33052,33003 ,726,726,726 ,0,0,0}, {33056,33003,33050 ,726,726,7661 ,0,0,0}, - {33052,33050,33003 ,726,7661,726 ,0,0,0}, {33051,33001,33003 ,726,726,726 ,0,0,0}, - {33051,33003,33056 ,726,726,726 ,0,0,0}, {33045,32941,32938 ,726,726,726 ,0,0,0}, - {33044,32941,33046 ,726,726,726 ,0,0,0}, {32941,33045,33046 ,726,726,726 ,0,0,0}, - {32905,32941,32907 ,726,726,726 ,0,0,0}, {32941,33044,32907 ,726,726,726 ,0,0,0}, - {32901,32941,32903 ,726,726,7660 ,0,0,0}, {32941,32905,32903 ,726,726,7660 ,0,0,0}, - {32895,32941,32901 ,726,726,726 ,0,0,0}, {32891,32889,33058 ,726,726,7583 ,0,0,0}, - {33059,33060,33061 ,726,726,726 ,0,0,0}, {33062,33059,32894 ,726,726,726 ,0,0,0}, - {33058,33063,32891 ,7583,7583,726 ,0,0,0}, {33064,33065,33061 ,726,726,726 ,0,0,0}, - {33066,33067,33060 ,726,726,726 ,0,0,0}, {33064,33061,33067 ,726,726,726 ,0,0,0}, - {33060,33067,33061 ,726,726,726 ,0,0,0}, {33061,33068,33059 ,726,726,726 ,0,0,0}, - {32891,33062,32894 ,726,726,726 ,0,0,0}, {32894,33059,33068 ,726,726,726 ,0,0,0}, - {33058,32889,32888 ,7583,726,726 ,0,0,0}, {32891,33063,33062 ,726,7583,726 ,0,0,0}, - {33069,32888,32885 ,7583,726,726 ,0,0,0}, {32888,33069,33058 ,726,7583,7583 ,0,0,0}, - {32885,33070,33071 ,726,726,726 ,0,0,0}, {33069,32885,33071 ,7583,726,726 ,0,0,0}, - {32883,33070,32885 ,726,726,726 ,0,0,0}, {33070,32882,33072 ,726,726,726 ,0,0,0}, - {32882,33070,32883 ,726,726,726 ,0,0,0}, {32882,32879,33072 ,726,726,726 ,0,0,0}, - {33073,32879,33074 ,726,726,5489 ,0,0,0}, {33073,33072,32879 ,726,726,726 ,0,0,0}, - {33074,32878,32859 ,5489,7583,726 ,0,0,0}, {32879,32878,33074 ,726,7583,5489 ,0,0,0}, - {32862,32877,32859 ,7583,7583,726 ,0,0,0}, {33074,32859,32877 ,5489,726,7583 ,0,0,0}, - {32866,32873,32861 ,7583,7583,726 ,0,0,0}, {32861,32864,32866 ,726,726,7583 ,0,0,0}, - {32873,32868,32871 ,7583,7583,726 ,0,0,0}, {32873,32862,32861 ,7583,7583,726 ,0,0,0}, - {32873,32874,32862 ,7583,5489,7583 ,0,0,0}, {32873,32866,32868 ,7583,7583,7583 ,0,0,0}, - {32862,32874,32877 ,7583,5489,7583 ,0,0,0}, {32876,33027,33074 ,35,18493,18494 ,0,0,0}, - {33029,33070,33030 ,18495,18496,18497 ,0,0,0}, {33072,33073,33028 ,18498,18499,18500 ,0,0,0}, - {33058,33035,33063 ,18501,18502,18503 ,0,0,0}, {33033,33032,33069 ,18504,18505,18506 ,0,0,0}, - {33037,33060,33059 ,18507,18508,18509 ,0,0,0}, {33059,33062,33005 ,18509,18510,18511 ,0,0,0}, - {33031,33067,33025 ,18512,18513,18514 ,0,0,0}, {33066,33036,33025 ,18515,18516,18514 ,0,0,0}, - {33038,33065,33064 ,18517,18518,18519 ,0,0,0}, {33064,33031,33038 ,18519,18512,18517 ,0,0,0}, - {33065,33023,33061 ,18518,18520,18521 ,0,0,0}, {33023,33065,33038 ,18520,18518,18517 ,0,0,0}, - {33068,33061,33024 ,18522,18521,18523 ,0,0,0}, {33023,33024,33061 ,18520,18523,18521 ,0,0,0}, - {33039,32894,33068 ,18524,18188,18522 ,0,0,0}, {33068,33024,33039 ,18522,18523,18524 ,0,0,0}, - {32893,32894,33039 ,18188,18188,18524 ,0,0,0}, {33064,33067,33031 ,18519,18513,18512 ,0,0,0}, - {33066,33025,33067 ,18515,18514,18513 ,0,0,0}, {33066,33060,33036 ,18515,18508,18516 ,0,0,0}, - {33063,33034,33062 ,18503,18525,18510 ,0,0,0}, {33037,33059,33005 ,18507,18509,18511 ,0,0,0}, - {33036,33060,33037 ,18516,18508,18507 ,0,0,0}, {33062,33034,33005 ,18510,18525,18511 ,0,0,0}, - {33034,33063,33035 ,18525,18503,18502 ,0,0,0}, {33069,33032,33058 ,18506,18505,18501 ,0,0,0}, - {33032,33035,33058 ,18505,18502,18501 ,0,0,0}, {33033,33071,33029 ,18504,18526,18495 ,0,0,0}, - {33071,33033,33069 ,18526,18504,18506 ,0,0,0}, {33072,33030,33070 ,18498,18497,18496 ,0,0,0}, - {33071,33070,33029 ,18526,18496,18495 ,0,0,0}, {33028,33073,33027 ,18500,18499,18493 ,0,0,0}, - {33030,33072,33028 ,18497,18498,18500 ,0,0,0}, {32876,33074,32877 ,35,18494,763 ,0,0,0}, - {33027,33073,33074 ,18493,18499,18494 ,0,0,0}, {33075,32820,32821 ,18527,126,18026 ,0,0,0}, - {32960,32961,32983 ,18528,18529,18530 ,0,0,0}, {33076,32962,33077 ,18531,18532,18533 ,0,0,0}, - {32963,33078,32944 ,18534,18535,18536 ,0,0,0}, {33079,32853,32966 ,18537,10001,18538 ,0,0,0}, - {33080,32968,32964 ,18539,18540,18541 ,0,0,0}, {32971,32972,33081 ,18542,18543,18544 ,0,0,0}, - {32970,32969,33082 ,18545,18546,18547 ,0,0,0}, {32973,33083,32975 ,18548,18549,18550 ,0,0,0}, - {32981,32974,32976 ,18551,18552,18553 ,0,0,0}, {32975,32981,32976 ,18550,18551,18553 ,0,0,0}, - {32974,33084,32977 ,18552,18554,18555 ,0,0,0}, {33084,32974,32981 ,18554,18552,18551 ,0,0,0}, - {33084,33085,32977 ,18554,18556,18555 ,0,0,0}, {33086,32978,33085 ,18557,18558,18556 ,0,0,0}, - {32977,33085,32978 ,18555,18556,18558 ,0,0,0}, {33086,32850,32848 ,18557,5000,18205 ,0,0,0}, - {32848,32978,33086 ,18205,18558,18557 ,0,0,0}, {33081,33083,32973 ,18544,18549,18548 ,0,0,0}, - {32975,33083,32981 ,18550,18549,18551 ,0,0,0}, {32972,33087,33081 ,18543,18559,18544 ,0,0,0}, - {32973,32971,33081 ,18548,18542,18544 ,0,0,0}, {33082,33087,32970 ,18547,18559,18545 ,0,0,0}, - {32972,32970,33087 ,18543,18545,18559 ,0,0,0}, {33082,32967,32853 ,18547,18560,10001 ,0,0,0}, - {32969,32967,33082 ,18546,18560,18547 ,0,0,0}, {33079,32966,32965 ,18537,18538,18561 ,0,0,0}, - {32853,32967,32966 ,10001,18560,18538 ,0,0,0}, {32968,33080,33079 ,18540,18539,18537 ,0,0,0}, - {33079,32965,32968 ,18537,18561,18540 ,0,0,0}, {32945,33088,32964 ,18562,18563,18541 ,0,0,0}, - {33088,33080,32964 ,18563,18539,18541 ,0,0,0}, {33088,32944,33078 ,18563,18536,18535 ,0,0,0}, - {32944,33088,32945 ,18536,18563,18562 ,0,0,0}, {32963,32960,32983 ,18534,18528,18530 ,0,0,0}, - {32963,32983,33078 ,18534,18530,18535 ,0,0,0}, {32961,32962,33076 ,18529,18532,18531 ,0,0,0}, - {32961,33076,32983 ,18529,18531,18530 ,0,0,0}, {33077,32959,33075 ,18533,18564,18527 ,0,0,0}, - {32962,32959,33077 ,18532,18564,18533 ,0,0,0}, {32820,33075,32959 ,126,18527,18564 ,0,0,0}, - {32854,33088,33078 ,17561,17561,730 ,0,0,0}, {33079,32854,32853 ,730,17561,730 ,0,0,0}, - {33088,32854,33080 ,17561,17561,730 ,0,0,0}, {32854,33079,33080 ,17561,730,730 ,0,0,0}, - {33078,32983,32854 ,730,7376,17561 ,0,0,0}, {32847,32980,32839 ,18207,730,730 ,0,0,0}, - {32980,33086,33085 ,730,730,730 ,0,0,0}, {32849,32980,32844 ,17561,730,7433 ,0,0,0}, - {32980,32847,32844 ,730,18207,7433 ,0,0,0}, {33086,32980,32850 ,730,730,17561 ,0,0,0}, - {32980,32849,32850 ,730,17561,17561 ,0,0,0}, {33085,33084,32980 ,730,7433,730 ,0,0,0}, - {33084,32981,32980 ,7433,730,730 ,0,0,0}, {32823,32939,32822 ,7017,730,730 ,0,0,0}, - {32939,32808,32822 ,730,11465,730 ,0,0,0}, {32829,32939,32828 ,18565,730,730 ,0,0,0}, - {32939,32823,32828 ,730,7017,730 ,0,0,0}, {32812,32939,32829 ,18566,730,18565 ,0,0,0}, - {33087,32852,33081 ,730,7376,17561 ,0,0,0}, {33083,33081,32852 ,730,17561,7376 ,0,0,0}, - {32981,33083,32852 ,730,730,7376 ,0,0,0}, {33082,32853,32852 ,7376,730,7376 ,0,0,0}, - {33082,32852,33087 ,7376,7376,730 ,0,0,0}, {32833,32832,33002 ,18207,18207,9877 ,0,0,0}, - {32812,32833,33002 ,18567,18207,9877 ,0,0,0}, {32836,32842,33002 ,730,9878,9877 ,0,0,0}, - {32836,33002,32832 ,730,9877,18207 ,0,0,0}, {32839,33002,32842 ,730,9877,9878 ,0,0,0}, - {32983,33076,32937 ,730,730,730 ,0,0,0}, {32937,33075,32821 ,730,730,9877 ,0,0,0}, - {33075,32937,33077 ,730,730,730 ,0,0,0}, {32937,33076,33077 ,730,730,730 ,0,0,0}, - {32821,32819,32937 ,9877,730,730 ,0,0,0}, {32937,32817,32815 ,730,9878,730 ,0,0,0}, - {32819,32817,32937 ,730,9878,730 ,0,0,0}, {32815,32808,32937 ,730,730,730 ,0,0,0}, - {32984,32987,32793 ,730,730,9878 ,0,0,0}, {32777,32776,32788 ,730,730,730 ,0,0,0}, - {32774,32777,32791 ,9875,730,730 ,0,0,0}, {32793,32792,32984 ,9878,730,730 ,0,0,0}, - {32783,32786,32788 ,730,730,730 ,0,0,0}, {32779,32781,32776 ,730,730,730 ,0,0,0}, - {32783,32788,32781 ,730,730,730 ,0,0,0}, {32776,32781,32788 ,730,730,730 ,0,0,0}, - {32788,32789,32777 ,730,730,730 ,0,0,0}, {32984,32774,32791 ,730,9875,730 ,0,0,0}, - {32791,32777,32789 ,730,730,730 ,0,0,0}, {32793,32987,32986 ,9878,730,730 ,0,0,0}, - {32984,32792,32774 ,730,730,9875 ,0,0,0}, {32796,32986,32985 ,9878,730,730 ,0,0,0}, - {32986,32796,32793 ,730,9878,9878 ,0,0,0}, {32985,32799,32797 ,730,730,730 ,0,0,0}, - {32796,32985,32797 ,9878,730,730 ,0,0,0}, {33000,32799,32985 ,730,730,730 ,0,0,0}, - {32799,32990,32802 ,730,9875,9878 ,0,0,0}, {32990,32799,33000 ,9875,730,730 ,0,0,0}, - {32990,32988,32802 ,9875,730,9878 ,0,0,0}, {32803,32988,32805 ,9878,730,730 ,0,0,0}, - {32803,32802,32988 ,9878,9878,730 ,0,0,0}, {32805,32989,32993 ,730,9875,9875 ,0,0,0}, - {32988,32989,32805 ,730,9875,730 ,0,0,0}, {32992,32807,32993 ,730,9878,9875 ,0,0,0}, - {32805,32993,32807 ,730,9875,9878 ,0,0,0}, {32994,32998,32991 ,9878,9878,730 ,0,0,0}, - {32991,32995,32994 ,730,9878,9878 ,0,0,0}, {32998,32997,32996 ,9878,9878,9877 ,0,0,0}, - {32998,32992,32991 ,9878,730,730 ,0,0,0}, {32998,32999,32992 ,9878,730,730 ,0,0,0}, - {32998,32994,32997 ,9878,9878,9878 ,0,0,0}, {32992,32999,32807 ,730,730,9878 ,0,0,0} -// M3abstandhalter10mm.prt - , {33089,32518,33090 ,18258,18259,18260 ,0,0,0}, {33091,33092,33093 ,18261,18262,18263 ,0,0,0}, - {33090,32518,33093 ,18260,18259,18263 ,0,0,0}, {33092,33091,33094 ,18262,18261,18264 ,0,0,0}, - {33094,33095,33092 ,18264,18265,18262 ,0,0,0}, {33095,33096,33097 ,18265,18266,18267 ,0,0,0}, - {33094,33096,33095 ,18264,18266,18265 ,0,0,0}, {33091,33093,32518 ,18261,18263,18259 ,0,0,0}, - {33098,33099,33100 ,18268,18269,18270 ,0,0,0}, {33099,33097,33100 ,18269,18267,18270 ,0,0,0}, - {33098,33101,33102 ,18268,18271,18272 ,0,0,0}, {33102,33099,33098 ,18272,18269,18268 ,0,0,0}, - {33101,33103,33104 ,18271,18273,18274 ,0,0,0}, {33101,33104,33102 ,18271,18274,18272 ,0,0,0}, - {33096,33100,33097 ,18266,18270,18267 ,0,0,0}, {33105,33104,33103 ,18275,18274,18273 ,0,0,0}, - {33106,31741,33107 ,18276,18277,126 ,0,0,0}, {33106,33107,33105 ,18276,126,18275 ,0,0,0}, - {33103,33106,33105 ,18273,18276,18275 ,0,0,0}, {33089,33090,33108 ,18258,18260,18278 ,0,0,0}, - {33108,33109,33110 ,18278,18279,18280 ,0,0,0}, {33110,33089,33108 ,18280,18258,18278 ,0,0,0}, - {33111,33109,33112 ,18281,18279,18282 ,0,0,0}, {33109,33111,33110 ,18279,18281,18280 ,0,0,0}, - {33113,33114,33112 ,18283,18284,18282 ,0,0,0}, {33111,33112,33114 ,18281,18282,18284 ,0,0,0}, - {33113,33115,33116 ,18283,18285,18286 ,0,0,0}, {33116,33114,33113 ,18286,18284,18283 ,0,0,0}, - {33117,33115,33118 ,18287,18285,18288 ,0,0,0}, {33115,33117,33116 ,18285,18287,18286 ,0,0,0}, - {33119,33120,33118 ,18289,18290,18288 ,0,0,0}, {33117,33118,33120 ,18287,18288,18290 ,0,0,0}, - {33119,33121,33122 ,18289,18291,18292 ,0,0,0}, {33122,33120,33119 ,18292,18290,18289 ,0,0,0}, - {31755,33121,33123 ,18293,18291,18003 ,0,0,0}, {33121,31755,33122 ,18291,18293,18292 ,0,0,0}, - {33124,33125,33126 ,18294,18295,18296 ,0,0,0}, {33127,33128,33129 ,18297,21,18298 ,0,0,0}, - {33130,33124,33131 ,18299,18294,18300 ,0,0,0}, {33124,33130,33125 ,18294,18299,18295 ,0,0,0}, - {33130,33131,33132 ,18299,18300,18301 ,0,0,0}, {33133,33134,33132 ,18302,18303,18301 ,0,0,0}, - {33132,33131,33133 ,18301,18300,18302 ,0,0,0}, {33134,33135,33136 ,18303,18304,126 ,0,0,0}, - {33135,33134,33133 ,18304,18303,18302 ,0,0,0}, {33135,33137,33136 ,18304,3135,126 ,0,0,0}, - {33124,33126,33138 ,18294,18296,18305 ,0,0,0}, {33139,33138,33140 ,18306,18305,18307 ,0,0,0}, - {33126,33140,33138 ,18296,18307,18305 ,0,0,0}, {33141,33139,33142 ,18308,18306,18309 ,0,0,0}, - {33139,33140,33142 ,18306,18307,18309 ,0,0,0}, {33141,33143,33144 ,18308,18310,18311 ,0,0,0}, - {33144,33139,33141 ,18311,18306,18308 ,0,0,0}, {33145,33143,33146 ,18312,18310,18313 ,0,0,0}, - {33143,33145,33144 ,18310,18312,18311 ,0,0,0}, {33128,33145,33129 ,21,18312,18298 ,0,0,0}, - {33146,33129,33145 ,18313,18298,18312 ,0,0,0}, {33147,33148,33149 ,18314,18315,18316 ,0,0,0}, - {33127,33150,33149 ,18297,18317,18316 ,0,0,0}, {33151,33152,33153 ,18318,18319,18320 ,0,0,0}, - {33152,33148,33154 ,18319,18315,18321 ,0,0,0}, {33155,33156,33157 ,18322,18323,18324 ,0,0,0}, - {33158,33159,33155 ,18325,18326,18322 ,0,0,0}, {33160,33161,33162 ,18327,18328,18329 ,0,0,0}, - {33161,33160,33163 ,18328,18327,18330 ,0,0,0}, {33164,33165,33162 ,18037,18331,18329 ,0,0,0}, - {33160,33162,33165 ,18327,18329,18331 ,0,0,0}, {33166,33165,33164 ,18038,18331,18037 ,0,0,0}, - {33157,33163,33155 ,18324,18330,18322 ,0,0,0}, {33157,33161,33163 ,18324,18328,18330 ,0,0,0}, - {33152,33151,33158 ,18319,18318,18325 ,0,0,0}, {33155,33159,33156 ,18322,18326,18323 ,0,0,0}, - {33158,33151,33159 ,18325,18318,18326 ,0,0,0}, {33148,33147,33154 ,18315,18314,18321 ,0,0,0}, - {33153,33152,33154 ,18320,18319,18321 ,0,0,0}, {33149,33128,33127 ,18316,21,18297 ,0,0,0}, - {33147,33149,33150 ,18314,18316,18317 ,0,0,0}, {33167,33168,33169 ,18332,1077,18332 ,0,0,0}, - {33170,33171,33169 ,18333,18333,18332 ,0,0,0}, {33171,33167,33169 ,18333,18332,18332 ,0,0,0}, - {33167,33172,33168 ,18332,18334,1077 ,0,0,0}, {33173,33174,33175 ,18335,18336,324 ,0,0,0}, - {33176,33177,33178 ,18337,18338,18339 ,0,0,0}, {33175,33174,33178 ,324,18336,18339 ,0,0,0}, - {33177,33176,33179 ,18338,18337,18340 ,0,0,0}, {33179,33180,33177 ,18340,18341,18338 ,0,0,0}, - {33180,33181,33182 ,18341,18342,18343 ,0,0,0}, {33179,33181,33180 ,18340,18342,18341 ,0,0,0}, - {33176,33178,33174 ,18337,18339,18336 ,0,0,0}, {33183,33184,33185 ,18344,18345,18346 ,0,0,0}, - {33184,33182,33185 ,18345,18343,18346 ,0,0,0}, {33183,33186,33187 ,18344,18347,18348 ,0,0,0}, - {33187,33184,33183 ,18348,18345,18344 ,0,0,0}, {33186,33188,33189 ,18347,18349,18350 ,0,0,0}, - {33186,33189,33187 ,18347,18350,18348 ,0,0,0}, {33181,33185,33182 ,18342,18346,18343 ,0,0,0}, - {33190,33189,33188 ,18351,18350,18349 ,0,0,0}, {33191,33192,33193 ,18352,18353,126 ,0,0,0}, - {33191,33193,33190 ,18352,126,18351 ,0,0,0}, {33188,33191,33190 ,18349,18352,18351 ,0,0,0}, - {33173,33175,33194 ,18335,324,18354 ,0,0,0}, {33194,33195,33196 ,18354,18355,18356 ,0,0,0}, - {33196,33173,33194 ,18356,18335,18354 ,0,0,0}, {33197,33195,33198 ,18357,18355,18358 ,0,0,0}, - {33195,33197,33196 ,18355,18357,18356 ,0,0,0}, {33199,33200,33198 ,18359,18360,18358 ,0,0,0}, - {33197,33198,33200 ,18357,18358,18360 ,0,0,0}, {33199,33201,33202 ,18359,18361,18362 ,0,0,0}, - {33202,33200,33199 ,18362,18360,18359 ,0,0,0}, {33203,33201,33204 ,18363,18361,18364 ,0,0,0}, - {33201,33203,33202 ,18361,18363,18362 ,0,0,0}, {33205,33206,33204 ,18365,18366,18364 ,0,0,0}, - {33203,33204,33206 ,18363,18364,18366 ,0,0,0}, {33205,33207,33208 ,18365,18367,18368 ,0,0,0}, - {33208,33206,33205 ,18368,18366,18365 ,0,0,0}, {33209,33207,33210 ,18369,18367,18188 ,0,0,0}, - {33207,33209,33208 ,18367,18369,18368 ,0,0,0}, {33211,33212,33213 ,18370,18371,18372 ,0,0,0}, - {33214,33167,33215 ,18373,324,18374 ,0,0,0}, {33216,33211,33217 ,18375,18370,18376 ,0,0,0}, - {33211,33216,33212 ,18370,18375,18371 ,0,0,0}, {33216,33217,33218 ,18375,18376,18377 ,0,0,0}, - {33219,33220,33218 ,18378,18379,18377 ,0,0,0}, {33218,33217,33219 ,18377,18376,18378 ,0,0,0}, - {33220,33221,33222 ,18379,18380,18092 ,0,0,0}, {33221,33220,33219 ,18380,18379,18378 ,0,0,0}, - {33221,33223,33222 ,18380,18381,18092 ,0,0,0}, {33211,33213,33224 ,18370,18372,18382 ,0,0,0}, - {33225,33224,33226 ,18383,18382,18384 ,0,0,0}, {33213,33226,33224 ,18372,18384,18382 ,0,0,0}, - {33227,33225,33228 ,18385,18383,18386 ,0,0,0}, {33225,33226,33228 ,18383,18384,18386 ,0,0,0}, - {33227,33229,33230 ,18385,18387,18388 ,0,0,0}, {33230,33225,33227 ,18388,18383,18385 ,0,0,0}, - {33231,33229,33232 ,18389,18387,18390 ,0,0,0}, {33229,33231,33230 ,18387,18389,18388 ,0,0,0}, - {33167,33231,33215 ,324,18389,18374 ,0,0,0}, {33232,33215,33231 ,18390,18374,18389 ,0,0,0}, - {33233,33234,33235 ,18391,18392,18393 ,0,0,0}, {33214,33236,33235 ,18373,18394,18393 ,0,0,0}, - {33237,33238,33239 ,18395,18396,18397 ,0,0,0}, {33238,33234,33240 ,18396,18392,18398 ,0,0,0}, - {33241,33242,33243 ,18399,18400,18401 ,0,0,0}, {33244,33245,33241 ,18402,18403,18399 ,0,0,0}, - {33246,33247,33248 ,18404,18405,18406 ,0,0,0}, {33247,33246,33249 ,18405,18404,18407 ,0,0,0}, - {33250,33251,33248 ,82,18408,18406 ,0,0,0}, {33246,33248,33251 ,18404,18406,18408 ,0,0,0}, - {33252,33251,33250 ,18103,18408,82 ,0,0,0}, {33243,33249,33241 ,18401,18407,18399 ,0,0,0}, - {33243,33247,33249 ,18401,18405,18407 ,0,0,0}, {33238,33237,33244 ,18396,18395,18402 ,0,0,0}, - {33241,33245,33242 ,18399,18403,18400 ,0,0,0}, {33244,33237,33245 ,18402,18395,18403 ,0,0,0}, - {33234,33233,33240 ,18392,18391,18398 ,0,0,0}, {33239,33238,33240 ,18397,18396,18398 ,0,0,0}, - {33235,33167,33214 ,18393,324,18373 ,0,0,0}, {33233,33235,33236 ,18391,18393,18394 ,0,0,0}, - {33253,33124,33254 ,2197,2197,2197 ,0,0,0}, {33255,33256,33124 ,2197,2197,2197 ,0,0,0}, - {33256,33254,33124 ,2197,2197,2197 ,0,0,0}, {33254,33257,33253 ,2197,2197,2197 ,0,0,0}, - {33258,33259,33161 ,730,730,730 ,0,0,0}, {33114,33260,33261 ,730,730,730 ,0,0,0}, - {33262,33263,33151 ,730,730,730 ,0,0,0}, {33159,33263,33156 ,730,730,730 ,0,0,0}, - {33127,33264,33150 ,730,730,730 ,0,0,0}, {33150,33265,33147 ,730,730,730 ,0,0,0}, - {33266,33153,33154 ,730,730,730 ,0,0,0}, {33146,33267,33129 ,730,730,730 ,0,0,0}, - {33143,33268,33146 ,730,730,730 ,0,0,0}, {33269,33268,33141 ,730,730,730 ,0,0,0}, - {33141,33142,33269 ,730,730,730 ,0,0,0}, {33130,33132,33270 ,730,730,730 ,0,0,0}, - {33271,33142,33140 ,730,730,730 ,0,0,0}, {33125,33272,33273 ,730,730,730 ,0,0,0}, - {33274,33132,33134 ,730,730,730 ,0,0,0}, {31755,33134,33136 ,730,730,730 ,0,0,0}, - {31755,33275,33122 ,730,730,730 ,0,0,0}, {33276,33117,33277 ,730,730,730 ,0,0,0}, - {33120,33122,33278 ,730,730,730 ,0,0,0}, {33120,33278,33277 ,730,730,730 ,0,0,0}, - {33276,33279,33116 ,730,730,730 ,0,0,0}, {33114,33116,33260 ,730,730,730 ,0,0,0}, - {33126,33273,33140 ,730,730,730 ,0,0,0}, {33111,33261,33280 ,730,730,730 ,0,0,0}, - {33089,33110,33281 ,730,730,730 ,0,0,0}, {33089,33282,32518 ,730,730,730 ,0,0,0}, - {33282,33283,32518 ,730,730,730 ,0,0,0}, {33110,33280,33284 ,730,730,730 ,0,0,0}, - {33285,33091,33283 ,730,730,730 ,0,0,0}, {33094,33285,33286 ,730,730,730 ,0,0,0}, - {33287,33096,33288 ,730,730,730 ,0,0,0}, {33096,33094,33288 ,730,730,730 ,0,0,0}, - {33100,33287,33289 ,730,730,730 ,0,0,0}, {33290,33103,33101 ,730,730,730 ,0,0,0}, - {33291,33098,33289 ,730,730,730 ,0,0,0}, {33290,33101,33292 ,730,730,730 ,0,0,0}, - {33264,33127,31726 ,730,730,730 ,0,0,0}, {33106,33103,33293 ,730,730,730 ,0,0,0}, - {33290,33293,33103 ,730,730,730 ,0,0,0}, {33106,33294,31741 ,730,730,730 ,0,0,0}, - {33294,33106,33293 ,730,730,730 ,0,0,0}, {31741,33164,33162 ,730,730,730 ,0,0,0}, - {33294,33164,31741 ,730,730,730 ,0,0,0}, {33295,33258,33157 ,730,730,730 ,0,0,0}, - {31726,33127,33129 ,730,730,730 ,0,0,0}, {33291,33292,33098 ,730,730,730 ,0,0,0}, - {33292,33101,33098 ,730,730,730 ,0,0,0}, {33100,33289,33098 ,730,730,730 ,0,0,0}, - {33096,33287,33100 ,730,730,730 ,0,0,0}, {33286,33288,33094 ,730,730,730 ,0,0,0}, - {33091,33285,33094 ,730,730,730 ,0,0,0}, {32518,33283,33091 ,730,730,730 ,0,0,0}, - {33281,33282,33089 ,730,730,730 ,0,0,0}, {33284,33281,33110 ,730,730,730 ,0,0,0}, - {33111,33280,33110 ,730,730,730 ,0,0,0}, {33114,33261,33111 ,730,730,730 ,0,0,0}, - {33279,33260,33116 ,730,730,730 ,0,0,0}, {33117,33276,33116 ,730,730,730 ,0,0,0}, - {33120,33277,33117 ,730,730,730 ,0,0,0}, {33275,33278,33122 ,730,730,730 ,0,0,0}, - {33136,33275,31755 ,730,730,730 ,0,0,0}, {33274,33134,31755 ,730,730,730 ,0,0,0}, - {33270,33132,33274 ,730,730,730 ,0,0,0}, {33125,33130,33272 ,730,730,730 ,0,0,0}, - {33130,33270,33272 ,730,730,730 ,0,0,0}, {33126,33125,33273 ,730,730,730 ,0,0,0}, - {33271,33140,33273 ,730,730,730 ,0,0,0}, {33269,33142,33271 ,730,730,730 ,0,0,0}, - {33143,33141,33268 ,730,730,730 ,0,0,0}, {33267,33146,33268 ,730,730,730 ,0,0,0}, - {31726,33129,33267 ,730,730,730 ,0,0,0}, {33150,33264,33265 ,730,730,730 ,0,0,0}, - {33154,33147,33265 ,730,730,730 ,0,0,0}, {33262,33153,33266 ,730,730,730 ,0,0,0}, - {33266,33154,33265 ,730,730,730 ,0,0,0}, {33263,33159,33151 ,730,730,730 ,0,0,0}, - {33262,33151,33153 ,730,730,730 ,0,0,0}, {33263,33295,33156 ,730,730,730 ,0,0,0}, - {33157,33258,33161 ,730,730,730 ,0,0,0}, {33156,33295,33157 ,730,730,730 ,0,0,0}, - {33161,33259,33162 ,730,730,730 ,0,0,0}, {31741,33162,33259 ,730,730,730 ,0,0,0}, - {33296,33297,33241 ,18409,18410,18410 ,0,0,0}, {33297,33168,33172 ,18410,1433,1433 ,0,0,0}, - {33241,33297,33172 ,18410,18410,1433 ,0,0,0}, {33241,33298,33296 ,18410,18409,18409 ,0,0,0}, - {33170,33299,33211 ,2162,18411,18411 ,0,0,0}, {33299,33253,33257 ,18411,2162,2162 ,0,0,0}, - {33211,33299,33257 ,18411,18411,2162 ,0,0,0}, {33211,33171,33170 ,18411,2162,2162 ,0,0,0}, - {31741,33259,33300 ,18353,18412,18413 ,0,0,0}, {33263,33301,33295 ,18414,18415,18416 ,0,0,0}, - {33302,33303,33258 ,18417,18418,18419 ,0,0,0}, {33304,33265,33305 ,18420,18421,18422 ,0,0,0}, - {33262,33266,33306 ,18423,18239,18424 ,0,0,0}, {33267,33307,33308 ,18425,18426,18427 ,0,0,0}, - {33308,33309,31726 ,18427,324,18428 ,0,0,0}, {33271,33310,33269 ,18429,18430,18431 ,0,0,0}, - {33311,33268,33269 ,18432,18433,18431 ,0,0,0}, {33273,33312,33313 ,18434,18435,18436 ,0,0,0}, - {33313,33271,33273 ,18436,18429,18434 ,0,0,0}, {33312,33272,33314 ,18435,18437,18438 ,0,0,0}, - {33272,33312,33273 ,18437,18435,18434 ,0,0,0}, {33315,33314,33270 ,18439,18438,18440 ,0,0,0}, - {33272,33270,33314 ,18437,18440,18438 ,0,0,0}, {33274,33123,33315 ,18441,18256,18439 ,0,0,0}, - {33315,33270,33274 ,18439,18440,18441 ,0,0,0}, {31755,33123,33274 ,18002,18256,18441 ,0,0,0}, - {33313,33310,33271 ,18436,18430,18429 ,0,0,0}, {33311,33269,33310 ,18432,18431,18430 ,0,0,0}, - {33311,33307,33268 ,18432,18426,18433 ,0,0,0}, {33305,33264,33309 ,18422,18442,324 ,0,0,0}, - {33267,33308,31726 ,18425,18427,18428 ,0,0,0}, {33268,33307,33267 ,18433,18426,18425 ,0,0,0}, - {33309,33264,31726 ,324,18442,18428 ,0,0,0}, {33264,33305,33265 ,18442,18422,18421 ,0,0,0}, - {33306,33266,33304 ,18424,18239,18420 ,0,0,0}, {33266,33265,33304 ,18239,18421,18420 ,0,0,0}, - {33262,33316,33263 ,18423,18443,18414 ,0,0,0}, {33316,33262,33306 ,18443,18423,18424 ,0,0,0}, - {33302,33295,33301 ,18417,18416,18415 ,0,0,0}, {33316,33301,33263 ,18443,18415,18414 ,0,0,0}, - {33258,33303,33259 ,18419,18418,18412 ,0,0,0}, {33295,33302,33258 ,18416,18417,18419 ,0,0,0}, - {31741,33300,33107 ,18353,18413,3345 ,0,0,0}, {33259,33303,33300 ,18412,18418,18413 ,0,0,0}, - {33128,33317,33255 ,18444,18444,18113 ,0,0,0}, {33128,33318,33319 ,18444,18113,18113 ,0,0,0}, - {33128,33319,33317 ,18444,18113,18444 ,0,0,0}, {33317,33256,33255 ,18444,18113,18113 ,0,0,0}, - {33206,33208,33320 ,7758,7880,7627 ,0,0,0}, {33214,33215,33321 ,726,726,7627 ,0,0,0}, - {33200,33322,33323 ,726,18445,7755 ,0,0,0}, {33324,33202,33325 ,8017,7627,7627 ,0,0,0}, - {33326,33173,33327 ,18446,7758,18447 ,0,0,0}, {33327,33196,33328 ,18447,7264,7249 ,0,0,0}, - {33329,33179,33330 ,18448,7627,18449 ,0,0,0}, {33323,33331,33197 ,7755,8018,7755 ,0,0,0}, - {33176,33332,33330 ,7761,18450,18449 ,0,0,0}, {33333,33181,33179 ,18451,726,7627 ,0,0,0}, - {33181,33333,33334 ,726,18451,726 ,0,0,0}, {33174,33326,33332 ,7755,18446,18450 ,0,0,0}, - {33335,33185,33334 ,7264,7627,726 ,0,0,0}, {33183,33336,33186 ,7758,7264,7880 ,0,0,0}, - {33337,33338,33188 ,726,7880,7627 ,0,0,0}, {33339,33216,33340 ,726,7627,726 ,0,0,0}, - {33341,33227,33228 ,726,7627,7627 ,0,0,0}, {33338,33342,33191 ,7880,7627,7880 ,0,0,0}, - {33192,33248,33343 ,7627,7627,726 ,0,0,0}, {33247,33344,33343 ,7627,7627,726 ,0,0,0}, - {33245,33345,33242 ,7625,7627,7627 ,0,0,0}, {33243,33242,33346 ,726,7627,726 ,0,0,0}, - {33226,33347,33228 ,7627,726,7627 ,0,0,0}, {33344,33247,33243 ,7627,7627,726 ,0,0,0}, - {33348,33239,33240 ,7627,726,726 ,0,0,0}, {33237,33239,33349 ,7627,726,7627 ,0,0,0}, - {33214,33321,33350 ,726,7627,726 ,0,0,0}, {33350,33351,33236 ,726,7627,7627 ,0,0,0}, - {33352,33232,33229 ,7627,726,726 ,0,0,0}, {33351,33240,33233 ,7627,726,726 ,0,0,0}, - {33352,33227,33341 ,7627,7627,726 ,0,0,0}, {33232,33353,33215 ,726,726,726 ,0,0,0}, - {33345,33237,33349 ,7627,7627,7627 ,0,0,0}, {33226,33213,33354 ,7627,7625,726 ,0,0,0}, - {33339,33212,33216 ,726,726,7627 ,0,0,0}, {33340,33216,33218 ,726,7627,726 ,0,0,0}, - {33212,33339,33354 ,726,726,726 ,0,0,0}, {33342,33250,33192 ,7627,7627,7627 ,0,0,0}, - {33355,33218,33220 ,726,726,7627 ,0,0,0}, {33218,33355,33340 ,726,726,726 ,0,0,0}, - {33209,33220,33222 ,7627,7627,7627 ,0,0,0}, {33209,33355,33220 ,7627,726,7627 ,0,0,0}, - {33222,33356,33209 ,7627,7758,7627 ,0,0,0}, {33357,33325,33203 ,7758,7627,7758 ,0,0,0}, - {33335,33358,33183 ,7264,7761,7758 ,0,0,0}, {33326,33174,33173 ,18446,7755,7758 ,0,0,0}, - {33213,33212,33354 ,7625,726,726 ,0,0,0}, {33347,33226,33354 ,726,7627,726 ,0,0,0}, - {33341,33228,33347 ,726,7627,726 ,0,0,0}, {33229,33227,33352 ,726,7627,7627 ,0,0,0}, - {33353,33232,33352 ,726,726,7627 ,0,0,0}, {33321,33215,33353 ,7627,726,726 ,0,0,0}, - {33236,33214,33350 ,7627,726,726 ,0,0,0}, {33233,33236,33351 ,726,7627,7627 ,0,0,0}, - {33348,33240,33351 ,7627,726,7627 ,0,0,0}, {33349,33239,33348 ,7627,726,7627 ,0,0,0}, - {33245,33237,33345 ,7625,7627,7627 ,0,0,0}, {33346,33242,33345 ,726,7627,7627 ,0,0,0}, - {33344,33243,33346 ,7627,726,726 ,0,0,0}, {33248,33247,33343 ,7627,7627,726 ,0,0,0}, - {33250,33248,33192 ,7627,7627,7627 ,0,0,0}, {33191,33342,33192 ,7880,7627,7627 ,0,0,0}, - {33188,33338,33191 ,7627,7880,7880 ,0,0,0}, {33336,33337,33186 ,7264,726,7880 ,0,0,0}, - {33337,33188,33186 ,726,7627,7880 ,0,0,0}, {33358,33336,33183 ,7761,7264,7758 ,0,0,0}, - {33185,33335,33183 ,7627,7264,7758 ,0,0,0}, {33181,33334,33185 ,726,726,7627 ,0,0,0}, - {33329,33333,33179 ,18448,18451,7627 ,0,0,0}, {33176,33330,33179 ,7761,18449,7627 ,0,0,0}, - {33174,33332,33176 ,7755,18450,7761 ,0,0,0}, {33327,33173,33196 ,18447,7758,7264 ,0,0,0}, - {33331,33328,33196 ,8018,7249,7264 ,0,0,0}, {33200,33323,33197 ,726,7755,7755 ,0,0,0}, - {33197,33331,33196 ,7755,8018,7264 ,0,0,0}, {33202,33322,33200 ,7627,18445,726 ,0,0,0}, - {33202,33203,33325 ,7627,7758,7627 ,0,0,0}, {33202,33324,33322 ,7627,8017,18445 ,0,0,0}, - {33203,33206,33357 ,7758,7758,7758 ,0,0,0}, {33320,33208,33356 ,7627,7880,7758 ,0,0,0}, - {33357,33206,33320 ,7758,7758,7627 ,0,0,0}, {33209,33356,33208 ,7627,7758,7880 ,0,0,0}, - {33318,33155,33359 ,1398,18452,18452 ,0,0,0}, {33296,33298,33155 ,18453,18453,18452 ,0,0,0}, - {33298,33359,33155 ,18453,18452,18452 ,0,0,0}, {33359,33319,33318 ,18452,1398,1398 ,0,0,0}, - {33360,33222,33223 ,18454,18092,18121 ,0,0,0}, {33325,33357,33254 ,18455,18456,18457 ,0,0,0}, - {33361,33320,33362 ,18458,18459,18460 ,0,0,0}, {33324,33363,33322 ,18461,18462,18463 ,0,0,0}, - {33364,33317,33326 ,18464,7309,18465 ,0,0,0}, {33365,33328,33331 ,18466,18467,18468 ,0,0,0}, - {33334,33333,33366 ,18469,18470,18471 ,0,0,0}, {33329,33330,33367 ,18472,18473,18474 ,0,0,0}, - {33335,33368,33358 ,18475,18476,18477 ,0,0,0}, {33359,33337,33336 ,18478,18479,18480 ,0,0,0}, - {33358,33359,33336 ,18477,18478,18480 ,0,0,0}, {33337,33369,33338 ,18479,18481,18482 ,0,0,0}, - {33369,33337,33359 ,18481,18479,18478 ,0,0,0}, {33369,33370,33338 ,18481,18483,18482 ,0,0,0}, - {33371,33342,33370 ,18484,18485,18483 ,0,0,0}, {33338,33370,33342 ,18482,18483,18485 ,0,0,0}, - {33371,33252,33250 ,18484,18486,82 ,0,0,0}, {33250,33342,33371 ,82,18485,18484 ,0,0,0}, - {33366,33368,33335 ,18471,18476,18475 ,0,0,0}, {33358,33368,33359 ,18477,18476,18478 ,0,0,0}, - {33333,33372,33366 ,18470,18487,18471 ,0,0,0}, {33335,33334,33366 ,18475,18469,18471 ,0,0,0}, - {33367,33372,33329 ,18474,18487,18472 ,0,0,0}, {33333,33329,33372 ,18470,18472,18487 ,0,0,0}, - {33367,33332,33317 ,18474,18488,7309 ,0,0,0}, {33330,33332,33367 ,18473,18488,18474 ,0,0,0}, - {33364,33326,33327 ,18464,18465,18489 ,0,0,0}, {33317,33332,33326 ,7309,18488,18465 ,0,0,0}, - {33328,33365,33364 ,18467,18466,18464 ,0,0,0}, {33364,33327,33328 ,18464,18489,18467 ,0,0,0}, - {33323,33373,33331 ,18490,18491,18468 ,0,0,0}, {33373,33365,33331 ,18491,18466,18468 ,0,0,0}, - {33373,33322,33363 ,18491,18463,18462 ,0,0,0}, {33322,33373,33323 ,18463,18491,18490 ,0,0,0}, - {33324,33325,33254 ,18461,18455,18457 ,0,0,0}, {33324,33254,33363 ,18461,18457,18462 ,0,0,0}, - {33357,33320,33361 ,18456,18459,18458 ,0,0,0}, {33357,33361,33254 ,18456,18458,18457 ,0,0,0}, - {33362,33356,33360 ,18460,18492,18454 ,0,0,0}, {33320,33356,33362 ,18459,18492,18460 ,0,0,0}, - {33222,33360,33356 ,18092,18454,18492 ,0,0,0}, {33246,33298,33249 ,7792,726,7658 ,0,0,0}, - {33298,33241,33249 ,726,726,7658 ,0,0,0}, {33252,33298,33251 ,7664,726,7662 ,0,0,0}, - {33298,33246,33251 ,726,7792,7662 ,0,0,0}, {33370,33298,33371 ,7662,726,5488 ,0,0,0}, - {33298,33252,33371 ,726,7664,5488 ,0,0,0}, {33359,33298,33369 ,726,726,726 ,0,0,0}, - {33298,33370,33369 ,726,7662,726 ,0,0,0}, {33373,33256,33365 ,726,726,17470 ,0,0,0}, - {33365,33256,33364 ,17470,726,7628 ,0,0,0}, {33256,33317,33364 ,726,726,7628 ,0,0,0}, - {33256,33363,33254 ,726,726,726 ,0,0,0}, {33256,33373,33363 ,726,726,726 ,0,0,0}, - {33224,33171,33211 ,726,726,726 ,0,0,0}, {33230,33171,33225 ,7661,726,7659 ,0,0,0}, - {33171,33224,33225 ,726,726,7659 ,0,0,0}, {33167,33171,33231 ,7661,726,7661 ,0,0,0}, - {33171,33230,33231 ,726,7661,7661 ,0,0,0}, {33172,33235,33234 ,7660,7660,7660 ,0,0,0}, - {33167,33235,33172 ,726,7660,7660 ,0,0,0}, {33172,33244,33241 ,7660,726,726 ,0,0,0}, - {33172,33238,33244 ,7660,7658,726 ,0,0,0}, {33234,33238,33172 ,7660,7658,7660 ,0,0,0}, - {33359,33368,33319 ,726,726,726 ,0,0,0}, {33372,33319,33366 ,726,726,7661 ,0,0,0}, - {33368,33366,33319 ,726,7661,726 ,0,0,0}, {33367,33317,33319 ,726,726,726 ,0,0,0}, - {33367,33319,33372 ,726,726,726 ,0,0,0}, {33361,33257,33254 ,726,726,726 ,0,0,0}, - {33360,33257,33362 ,726,726,726 ,0,0,0}, {33257,33361,33362 ,726,726,726 ,0,0,0}, - {33221,33257,33223 ,726,726,726 ,0,0,0}, {33257,33360,33223 ,726,726,726 ,0,0,0}, - {33217,33257,33219 ,726,726,7660 ,0,0,0}, {33257,33221,33219 ,726,726,7660 ,0,0,0}, - {33211,33257,33217 ,726,726,726 ,0,0,0}, {33207,33205,33374 ,726,726,7583 ,0,0,0}, - {33375,33376,33377 ,726,726,726 ,0,0,0}, {33378,33375,33210 ,726,726,726 ,0,0,0}, - {33374,33379,33207 ,7583,7583,726 ,0,0,0}, {33380,33381,33377 ,726,726,726 ,0,0,0}, - {33382,33383,33376 ,726,726,726 ,0,0,0}, {33380,33377,33383 ,726,726,726 ,0,0,0}, - {33376,33383,33377 ,726,726,726 ,0,0,0}, {33377,33384,33375 ,726,726,726 ,0,0,0}, - {33207,33378,33210 ,726,726,726 ,0,0,0}, {33210,33375,33384 ,726,726,726 ,0,0,0}, - {33374,33205,33204 ,7583,726,726 ,0,0,0}, {33207,33379,33378 ,726,7583,726 ,0,0,0}, - {33385,33204,33201 ,7583,726,726 ,0,0,0}, {33204,33385,33374 ,726,7583,7583 ,0,0,0}, - {33201,33386,33387 ,726,726,726 ,0,0,0}, {33385,33201,33387 ,7583,726,726 ,0,0,0}, - {33199,33386,33201 ,726,726,726 ,0,0,0}, {33386,33198,33388 ,726,726,726 ,0,0,0}, - {33198,33386,33199 ,726,726,726 ,0,0,0}, {33198,33195,33388 ,726,726,726 ,0,0,0}, - {33389,33195,33390 ,726,726,5489 ,0,0,0}, {33389,33388,33195 ,726,726,726 ,0,0,0}, - {33390,33194,33175 ,5489,7583,726 ,0,0,0}, {33195,33194,33390 ,726,7583,5489 ,0,0,0}, - {33178,33193,33175 ,7583,7583,726 ,0,0,0}, {33390,33175,33193 ,5489,726,7583 ,0,0,0}, - {33182,33189,33177 ,7583,7583,726 ,0,0,0}, {33177,33180,33182 ,726,726,7583 ,0,0,0}, - {33189,33184,33187 ,7583,7583,726 ,0,0,0}, {33189,33178,33177 ,7583,7583,726 ,0,0,0}, - {33189,33190,33178 ,7583,5489,7583 ,0,0,0}, {33189,33182,33184 ,7583,7583,7583 ,0,0,0}, - {33178,33190,33193 ,7583,5489,7583 ,0,0,0}, {33192,33343,33390 ,35,18493,18494 ,0,0,0}, - {33345,33386,33346 ,18495,18496,18497 ,0,0,0}, {33388,33389,33344 ,18498,18499,18500 ,0,0,0}, - {33374,33351,33379 ,18501,18502,18503 ,0,0,0}, {33349,33348,33385 ,18504,18505,18506 ,0,0,0}, - {33353,33376,33375 ,18507,18508,18509 ,0,0,0}, {33375,33378,33321 ,18509,18510,18511 ,0,0,0}, - {33347,33383,33341 ,18512,18513,18514 ,0,0,0}, {33382,33352,33341 ,18515,18516,18514 ,0,0,0}, - {33354,33381,33380 ,18517,18518,18519 ,0,0,0}, {33380,33347,33354 ,18519,18512,18517 ,0,0,0}, - {33381,33339,33377 ,18518,18520,18521 ,0,0,0}, {33339,33381,33354 ,18520,18518,18517 ,0,0,0}, - {33384,33377,33340 ,18522,18521,18523 ,0,0,0}, {33339,33340,33377 ,18520,18523,18521 ,0,0,0}, - {33355,33210,33384 ,18524,18188,18522 ,0,0,0}, {33384,33340,33355 ,18522,18523,18524 ,0,0,0}, - {33209,33210,33355 ,18188,18188,18524 ,0,0,0}, {33380,33383,33347 ,18519,18513,18512 ,0,0,0}, - {33382,33341,33383 ,18515,18514,18513 ,0,0,0}, {33382,33376,33352 ,18515,18508,18516 ,0,0,0}, - {33379,33350,33378 ,18503,18525,18510 ,0,0,0}, {33353,33375,33321 ,18507,18509,18511 ,0,0,0}, - {33352,33376,33353 ,18516,18508,18507 ,0,0,0}, {33378,33350,33321 ,18510,18525,18511 ,0,0,0}, - {33350,33379,33351 ,18525,18503,18502 ,0,0,0}, {33385,33348,33374 ,18506,18505,18501 ,0,0,0}, - {33348,33351,33374 ,18505,18502,18501 ,0,0,0}, {33349,33387,33345 ,18504,18526,18495 ,0,0,0}, - {33387,33349,33385 ,18526,18504,18506 ,0,0,0}, {33388,33346,33386 ,18498,18497,18496 ,0,0,0}, - {33387,33386,33345 ,18526,18496,18495 ,0,0,0}, {33344,33389,33343 ,18500,18499,18493 ,0,0,0}, - {33346,33388,33344 ,18497,18498,18500 ,0,0,0}, {33192,33390,33193 ,35,18494,763 ,0,0,0}, - {33343,33389,33390 ,18493,18499,18494 ,0,0,0}, {33391,33136,33137 ,18527,126,18026 ,0,0,0}, - {33276,33277,33299 ,18528,18529,18530 ,0,0,0}, {33392,33278,33393 ,18531,18532,18533 ,0,0,0}, - {33279,33394,33260 ,18534,18535,18536 ,0,0,0}, {33395,33169,33282 ,18537,10001,18538 ,0,0,0}, - {33396,33284,33280 ,18539,18540,18541 ,0,0,0}, {33287,33288,33397 ,18542,18543,18544 ,0,0,0}, - {33286,33285,33398 ,18545,18546,18547 ,0,0,0}, {33289,33399,33291 ,18548,18549,18550 ,0,0,0}, - {33297,33290,33292 ,18551,18552,18553 ,0,0,0}, {33291,33297,33292 ,18550,18551,18553 ,0,0,0}, - {33290,33400,33293 ,18552,18554,18555 ,0,0,0}, {33400,33290,33297 ,18554,18552,18551 ,0,0,0}, - {33400,33401,33293 ,18554,18556,18555 ,0,0,0}, {33402,33294,33401 ,18557,18558,18556 ,0,0,0}, - {33293,33401,33294 ,18555,18556,18558 ,0,0,0}, {33402,33166,33164 ,18557,5000,18205 ,0,0,0}, - {33164,33294,33402 ,18205,18558,18557 ,0,0,0}, {33397,33399,33289 ,18544,18549,18548 ,0,0,0}, - {33291,33399,33297 ,18550,18549,18551 ,0,0,0}, {33288,33403,33397 ,18543,18559,18544 ,0,0,0}, - {33289,33287,33397 ,18548,18542,18544 ,0,0,0}, {33398,33403,33286 ,18547,18559,18545 ,0,0,0}, - {33288,33286,33403 ,18543,18545,18559 ,0,0,0}, {33398,33283,33169 ,18547,18560,10001 ,0,0,0}, - {33285,33283,33398 ,18546,18560,18547 ,0,0,0}, {33395,33282,33281 ,18537,18538,18561 ,0,0,0}, - {33169,33283,33282 ,10001,18560,18538 ,0,0,0}, {33284,33396,33395 ,18540,18539,18537 ,0,0,0}, - {33395,33281,33284 ,18537,18561,18540 ,0,0,0}, {33261,33404,33280 ,18562,18563,18541 ,0,0,0}, - {33404,33396,33280 ,18563,18539,18541 ,0,0,0}, {33404,33260,33394 ,18563,18536,18535 ,0,0,0}, - {33260,33404,33261 ,18536,18563,18562 ,0,0,0}, {33279,33276,33299 ,18534,18528,18530 ,0,0,0}, - {33279,33299,33394 ,18534,18530,18535 ,0,0,0}, {33277,33278,33392 ,18529,18532,18531 ,0,0,0}, - {33277,33392,33299 ,18529,18531,18530 ,0,0,0}, {33393,33275,33391 ,18533,18564,18527 ,0,0,0}, - {33278,33275,33393 ,18532,18564,18533 ,0,0,0}, {33136,33391,33275 ,126,18527,18564 ,0,0,0}, - {33170,33404,33394 ,17561,17561,730 ,0,0,0}, {33395,33170,33169 ,730,17561,730 ,0,0,0}, - {33404,33170,33396 ,17561,17561,730 ,0,0,0}, {33170,33395,33396 ,17561,730,730 ,0,0,0}, - {33394,33299,33170 ,730,7376,17561 ,0,0,0}, {33163,33296,33155 ,18207,730,730 ,0,0,0}, - {33296,33402,33401 ,730,730,730 ,0,0,0}, {33165,33296,33160 ,17561,730,7433 ,0,0,0}, - {33296,33163,33160 ,730,18207,7433 ,0,0,0}, {33402,33296,33166 ,730,730,17561 ,0,0,0}, - {33296,33165,33166 ,730,17561,17561 ,0,0,0}, {33401,33400,33296 ,730,7433,730 ,0,0,0}, - {33400,33297,33296 ,7433,730,730 ,0,0,0}, {33139,33255,33138 ,7017,730,730 ,0,0,0}, - {33255,33124,33138 ,730,11465,730 ,0,0,0}, {33145,33255,33144 ,18565,730,730 ,0,0,0}, - {33255,33139,33144 ,730,7017,730 ,0,0,0}, {33128,33255,33145 ,18566,730,18565 ,0,0,0}, - {33403,33168,33397 ,730,7376,17561 ,0,0,0}, {33399,33397,33168 ,730,17561,7376 ,0,0,0}, - {33297,33399,33168 ,730,730,7376 ,0,0,0}, {33398,33169,33168 ,7376,730,7376 ,0,0,0}, - {33398,33168,33403 ,7376,7376,730 ,0,0,0}, {33149,33148,33318 ,18207,18207,9877 ,0,0,0}, - {33128,33149,33318 ,18567,18207,9877 ,0,0,0}, {33152,33158,33318 ,730,9878,9877 ,0,0,0}, - {33152,33318,33148 ,730,9877,18207 ,0,0,0}, {33155,33318,33158 ,730,9877,9878 ,0,0,0}, - {33299,33392,33253 ,730,730,730 ,0,0,0}, {33253,33391,33137 ,730,730,9877 ,0,0,0}, - {33391,33253,33393 ,730,730,730 ,0,0,0}, {33253,33392,33393 ,730,730,730 ,0,0,0}, - {33137,33135,33253 ,9877,730,730 ,0,0,0}, {33253,33133,33131 ,730,9878,730 ,0,0,0}, - {33135,33133,33253 ,730,9878,730 ,0,0,0}, {33131,33124,33253 ,730,730,730 ,0,0,0}, - {33300,33303,33109 ,730,730,9878 ,0,0,0}, {33093,33092,33104 ,730,730,730 ,0,0,0}, - {33090,33093,33107 ,9875,730,730 ,0,0,0}, {33109,33108,33300 ,9878,730,730 ,0,0,0}, - {33099,33102,33104 ,730,730,730 ,0,0,0}, {33095,33097,33092 ,730,730,730 ,0,0,0}, - {33099,33104,33097 ,730,730,730 ,0,0,0}, {33092,33097,33104 ,730,730,730 ,0,0,0}, - {33104,33105,33093 ,730,730,730 ,0,0,0}, {33300,33090,33107 ,730,9875,730 ,0,0,0}, - {33107,33093,33105 ,730,730,730 ,0,0,0}, {33109,33303,33302 ,9878,730,730 ,0,0,0}, - {33300,33108,33090 ,730,730,9875 ,0,0,0}, {33112,33302,33301 ,9878,730,730 ,0,0,0}, - {33302,33112,33109 ,730,9878,9878 ,0,0,0}, {33301,33115,33113 ,730,730,730 ,0,0,0}, - {33112,33301,33113 ,9878,730,730 ,0,0,0}, {33316,33115,33301 ,730,730,730 ,0,0,0}, - {33115,33306,33118 ,730,9875,9878 ,0,0,0}, {33306,33115,33316 ,9875,730,730 ,0,0,0}, - {33306,33304,33118 ,9875,730,9878 ,0,0,0}, {33119,33304,33121 ,9878,730,730 ,0,0,0}, - {33119,33118,33304 ,9878,9878,730 ,0,0,0}, {33121,33305,33309 ,730,9875,9875 ,0,0,0}, - {33304,33305,33121 ,730,9875,730 ,0,0,0}, {33308,33123,33309 ,730,9878,9875 ,0,0,0}, - {33121,33309,33123 ,730,9875,9878 ,0,0,0}, {33310,33314,33307 ,9878,9878,730 ,0,0,0}, - {33307,33311,33310 ,730,9878,9878 ,0,0,0}, {33314,33313,33312 ,9878,9878,9877 ,0,0,0}, - {33314,33308,33307 ,9878,730,730 ,0,0,0}, {33314,33315,33308 ,9878,730,730 ,0,0,0}, - {33314,33310,33313 ,9878,9878,9878 ,0,0,0}, {33308,33315,33123 ,730,730,9878 ,0,0,0} -// M3abstandhalter10mm.prt - , {33405,32470,33406 ,18258,18259,18260 ,0,0,0}, {33407,33408,33409 ,18261,18262,18263 ,0,0,0}, - {33406,32470,33409 ,18260,18259,18263 ,0,0,0}, {33408,33407,33410 ,18262,18261,18264 ,0,0,0}, - {33410,33411,33408 ,18264,18265,18262 ,0,0,0}, {33411,33412,33413 ,18265,18266,18267 ,0,0,0}, - {33410,33412,33411 ,18264,18266,18265 ,0,0,0}, {33407,33409,32470 ,18261,18263,18259 ,0,0,0}, - {33414,33415,33416 ,18268,18269,18270 ,0,0,0}, {33415,33413,33416 ,18269,18267,18270 ,0,0,0}, - {33414,33417,33418 ,18268,18271,18272 ,0,0,0}, {33418,33415,33414 ,18272,18269,18268 ,0,0,0}, - {33417,33419,33420 ,18271,18273,18274 ,0,0,0}, {33417,33420,33418 ,18271,18274,18272 ,0,0,0}, - {33412,33416,33413 ,18266,18270,18267 ,0,0,0}, {33421,33420,33419 ,18275,18274,18273 ,0,0,0}, - {33422,31643,33423 ,18276,18277,126 ,0,0,0}, {33422,33423,33421 ,18276,126,18275 ,0,0,0}, - {33419,33422,33421 ,18273,18276,18275 ,0,0,0}, {33405,33406,33424 ,18258,18260,18278 ,0,0,0}, - {33424,33425,33426 ,18278,18279,18280 ,0,0,0}, {33426,33405,33424 ,18280,18258,18278 ,0,0,0}, - {33427,33425,33428 ,18281,18279,18282 ,0,0,0}, {33425,33427,33426 ,18279,18281,18280 ,0,0,0}, - {33429,33430,33428 ,18283,18284,18282 ,0,0,0}, {33427,33428,33430 ,18281,18282,18284 ,0,0,0}, - {33429,33431,33432 ,18283,18285,18286 ,0,0,0}, {33432,33430,33429 ,18286,18284,18283 ,0,0,0}, - {33433,33431,33434 ,18287,18285,18288 ,0,0,0}, {33431,33433,33432 ,18285,18287,18286 ,0,0,0}, - {33435,33436,33434 ,18289,18290,18288 ,0,0,0}, {33433,33434,33436 ,18287,18288,18290 ,0,0,0}, - {33435,33437,33438 ,18289,18291,18292 ,0,0,0}, {33438,33436,33435 ,18292,18290,18289 ,0,0,0}, - {31657,33437,33439 ,18293,18291,18003 ,0,0,0}, {33437,31657,33438 ,18291,18293,18292 ,0,0,0}, - {33440,33441,33442 ,18294,18295,18296 ,0,0,0}, {33443,33444,33445 ,18297,21,18298 ,0,0,0}, - {33446,33440,33447 ,18299,18294,18300 ,0,0,0}, {33440,33446,33441 ,18294,18299,18295 ,0,0,0}, - {33446,33447,33448 ,18299,18300,18301 ,0,0,0}, {33449,33450,33448 ,18302,18303,18301 ,0,0,0}, - {33448,33447,33449 ,18301,18300,18302 ,0,0,0}, {33450,33451,33452 ,18303,18304,126 ,0,0,0}, - {33451,33450,33449 ,18304,18303,18302 ,0,0,0}, {33451,33453,33452 ,18304,3135,126 ,0,0,0}, - {33440,33442,33454 ,18294,18296,18305 ,0,0,0}, {33455,33454,33456 ,18306,18305,18307 ,0,0,0}, - {33442,33456,33454 ,18296,18307,18305 ,0,0,0}, {33457,33455,33458 ,18308,18306,18309 ,0,0,0}, - {33455,33456,33458 ,18306,18307,18309 ,0,0,0}, {33457,33459,33460 ,18308,18310,18311 ,0,0,0}, - {33460,33455,33457 ,18311,18306,18308 ,0,0,0}, {33461,33459,33462 ,18312,18310,18313 ,0,0,0}, - {33459,33461,33460 ,18310,18312,18311 ,0,0,0}, {33444,33461,33445 ,21,18312,18298 ,0,0,0}, - {33462,33445,33461 ,18313,18298,18312 ,0,0,0}, {33463,33464,33465 ,18314,18315,18316 ,0,0,0}, - {33443,33466,33465 ,18297,18317,18316 ,0,0,0}, {33467,33468,33469 ,18318,18319,18320 ,0,0,0}, - {33468,33464,33470 ,18319,18315,18321 ,0,0,0}, {33471,33472,33473 ,18322,18323,18324 ,0,0,0}, - {33474,33475,33471 ,18325,18326,18322 ,0,0,0}, {33476,33477,33478 ,18327,18328,18329 ,0,0,0}, - {33477,33476,33479 ,18328,18327,18330 ,0,0,0}, {33480,33481,33478 ,18037,18331,18329 ,0,0,0}, - {33476,33478,33481 ,18327,18329,18331 ,0,0,0}, {33482,33481,33480 ,18038,18331,18037 ,0,0,0}, - {33473,33479,33471 ,18324,18330,18322 ,0,0,0}, {33473,33477,33479 ,18324,18328,18330 ,0,0,0}, - {33468,33467,33474 ,18319,18318,18325 ,0,0,0}, {33471,33475,33472 ,18322,18326,18323 ,0,0,0}, - {33474,33467,33475 ,18325,18318,18326 ,0,0,0}, {33464,33463,33470 ,18315,18314,18321 ,0,0,0}, - {33469,33468,33470 ,18320,18319,18321 ,0,0,0}, {33465,33444,33443 ,18316,21,18297 ,0,0,0}, - {33463,33465,33466 ,18314,18316,18317 ,0,0,0}, {33483,33484,33485 ,18332,1077,18332 ,0,0,0}, - {33486,33487,33485 ,18333,18333,18332 ,0,0,0}, {33487,33483,33485 ,18333,18332,18332 ,0,0,0}, - {33483,33488,33484 ,18332,18334,1077 ,0,0,0}, {33489,33490,33491 ,18335,18336,324 ,0,0,0}, - {33492,33493,33494 ,18337,18338,18339 ,0,0,0}, {33491,33490,33494 ,324,18336,18339 ,0,0,0}, - {33493,33492,33495 ,18338,18337,18340 ,0,0,0}, {33495,33496,33493 ,18340,18341,18338 ,0,0,0}, - {33496,33497,33498 ,18341,18342,18343 ,0,0,0}, {33495,33497,33496 ,18340,18342,18341 ,0,0,0}, - {33492,33494,33490 ,18337,18339,18336 ,0,0,0}, {33499,33500,33501 ,18344,18345,18346 ,0,0,0}, - {33500,33498,33501 ,18345,18343,18346 ,0,0,0}, {33499,33502,33503 ,18344,18347,18348 ,0,0,0}, - {33503,33500,33499 ,18348,18345,18344 ,0,0,0}, {33502,33504,33505 ,18347,18349,18350 ,0,0,0}, - {33502,33505,33503 ,18347,18350,18348 ,0,0,0}, {33497,33501,33498 ,18342,18346,18343 ,0,0,0}, - {33506,33505,33504 ,18351,18350,18349 ,0,0,0}, {33507,33508,33509 ,18352,18353,126 ,0,0,0}, - {33507,33509,33506 ,18352,126,18351 ,0,0,0}, {33504,33507,33506 ,18349,18352,18351 ,0,0,0}, - {33489,33491,33510 ,18335,324,18354 ,0,0,0}, {33510,33511,33512 ,18354,18355,18356 ,0,0,0}, - {33512,33489,33510 ,18356,18335,18354 ,0,0,0}, {33513,33511,33514 ,18357,18355,18358 ,0,0,0}, - {33511,33513,33512 ,18355,18357,18356 ,0,0,0}, {33515,33516,33514 ,18359,18360,18358 ,0,0,0}, - {33513,33514,33516 ,18357,18358,18360 ,0,0,0}, {33515,33517,33518 ,18359,18361,18362 ,0,0,0}, - {33518,33516,33515 ,18362,18360,18359 ,0,0,0}, {33519,33517,33520 ,18363,18361,18364 ,0,0,0}, - {33517,33519,33518 ,18361,18363,18362 ,0,0,0}, {33521,33522,33520 ,18365,18366,18364 ,0,0,0}, - {33519,33520,33522 ,18363,18364,18366 ,0,0,0}, {33521,33523,33524 ,18365,18367,18368 ,0,0,0}, - {33524,33522,33521 ,18368,18366,18365 ,0,0,0}, {33525,33523,33526 ,18369,18367,18188 ,0,0,0}, - {33523,33525,33524 ,18367,18369,18368 ,0,0,0}, {33527,33528,33529 ,18370,18371,18372 ,0,0,0}, - {33530,33483,33531 ,18373,324,18374 ,0,0,0}, {33532,33527,33533 ,18375,18370,18376 ,0,0,0}, - {33527,33532,33528 ,18370,18375,18371 ,0,0,0}, {33532,33533,33534 ,18375,18376,18377 ,0,0,0}, - {33535,33536,33534 ,18378,18379,18377 ,0,0,0}, {33534,33533,33535 ,18377,18376,18378 ,0,0,0}, - {33536,33537,33538 ,18379,18380,18092 ,0,0,0}, {33537,33536,33535 ,18380,18379,18378 ,0,0,0}, - {33537,33539,33538 ,18380,18381,18092 ,0,0,0}, {33527,33529,33540 ,18370,18372,18382 ,0,0,0}, - {33541,33540,33542 ,18383,18382,18384 ,0,0,0}, {33529,33542,33540 ,18372,18384,18382 ,0,0,0}, - {33543,33541,33544 ,18385,18383,18386 ,0,0,0}, {33541,33542,33544 ,18383,18384,18386 ,0,0,0}, - {33543,33545,33546 ,18385,18387,18388 ,0,0,0}, {33546,33541,33543 ,18388,18383,18385 ,0,0,0}, - {33547,33545,33548 ,18389,18387,18390 ,0,0,0}, {33545,33547,33546 ,18387,18389,18388 ,0,0,0}, - {33483,33547,33531 ,324,18389,18374 ,0,0,0}, {33548,33531,33547 ,18390,18374,18389 ,0,0,0}, - {33549,33550,33551 ,18391,18392,18393 ,0,0,0}, {33530,33552,33551 ,18373,18394,18393 ,0,0,0}, - {33553,33554,33555 ,18395,18396,18397 ,0,0,0}, {33554,33550,33556 ,18396,18392,18398 ,0,0,0}, - {33557,33558,33559 ,18399,18400,18401 ,0,0,0}, {33560,33561,33557 ,18402,18403,18399 ,0,0,0}, - {33562,33563,33564 ,18404,18405,18406 ,0,0,0}, {33563,33562,33565 ,18405,18404,18407 ,0,0,0}, - {33566,33567,33564 ,82,18408,18406 ,0,0,0}, {33562,33564,33567 ,18404,18406,18408 ,0,0,0}, - {33568,33567,33566 ,18103,18408,82 ,0,0,0}, {33559,33565,33557 ,18401,18407,18399 ,0,0,0}, - {33559,33563,33565 ,18401,18405,18407 ,0,0,0}, {33554,33553,33560 ,18396,18395,18402 ,0,0,0}, - {33557,33561,33558 ,18399,18403,18400 ,0,0,0}, {33560,33553,33561 ,18402,18395,18403 ,0,0,0}, - {33550,33549,33556 ,18392,18391,18398 ,0,0,0}, {33555,33554,33556 ,18397,18396,18398 ,0,0,0}, - {33551,33483,33530 ,18393,324,18373 ,0,0,0}, {33549,33551,33552 ,18391,18393,18394 ,0,0,0}, - {33569,33440,33570 ,2197,2197,2197 ,0,0,0}, {33571,33572,33440 ,2197,2197,2197 ,0,0,0}, - {33572,33570,33440 ,2197,2197,2197 ,0,0,0}, {33570,33573,33569 ,2197,2197,2197 ,0,0,0}, - {33574,33575,33477 ,730,730,730 ,0,0,0}, {33430,33576,33577 ,730,730,730 ,0,0,0}, - {33578,33579,33467 ,730,730,730 ,0,0,0}, {33475,33579,33472 ,730,730,730 ,0,0,0}, - {33443,33580,33466 ,730,730,730 ,0,0,0}, {33466,33581,33463 ,730,730,730 ,0,0,0}, - {33582,33469,33470 ,730,730,730 ,0,0,0}, {33462,33583,33445 ,730,730,730 ,0,0,0}, - {33459,33584,33462 ,730,730,730 ,0,0,0}, {33585,33584,33457 ,730,730,730 ,0,0,0}, - {33457,33458,33585 ,730,730,730 ,0,0,0}, {33446,33448,33586 ,730,730,730 ,0,0,0}, - {33587,33458,33456 ,730,730,730 ,0,0,0}, {33441,33588,33589 ,730,730,730 ,0,0,0}, - {33590,33448,33450 ,730,730,730 ,0,0,0}, {31657,33450,33452 ,730,730,730 ,0,0,0}, - {31657,33591,33438 ,730,730,730 ,0,0,0}, {33592,33433,33593 ,730,730,730 ,0,0,0}, - {33436,33438,33594 ,730,730,730 ,0,0,0}, {33436,33594,33593 ,730,730,730 ,0,0,0}, - {33592,33595,33432 ,730,730,730 ,0,0,0}, {33430,33432,33576 ,730,730,730 ,0,0,0}, - {33442,33589,33456 ,730,730,730 ,0,0,0}, {33427,33577,33596 ,730,730,730 ,0,0,0}, - {33405,33426,33597 ,730,730,730 ,0,0,0}, {33405,33598,32470 ,730,730,730 ,0,0,0}, - {33598,33599,32470 ,730,730,730 ,0,0,0}, {33426,33596,33600 ,730,730,730 ,0,0,0}, - {33601,33407,33599 ,730,730,730 ,0,0,0}, {33410,33601,33602 ,730,730,730 ,0,0,0}, - {33603,33412,33604 ,730,730,730 ,0,0,0}, {33412,33410,33604 ,730,730,730 ,0,0,0}, - {33416,33603,33605 ,730,730,730 ,0,0,0}, {33606,33419,33417 ,730,730,730 ,0,0,0}, - {33607,33414,33605 ,730,730,730 ,0,0,0}, {33606,33417,33608 ,730,730,730 ,0,0,0}, - {33580,33443,31628 ,730,730,730 ,0,0,0}, {33422,33419,33609 ,730,730,730 ,0,0,0}, - {33606,33609,33419 ,730,730,730 ,0,0,0}, {33422,33610,31643 ,730,730,730 ,0,0,0}, - {33610,33422,33609 ,730,730,730 ,0,0,0}, {31643,33480,33478 ,730,730,730 ,0,0,0}, - {33610,33480,31643 ,730,730,730 ,0,0,0}, {33611,33574,33473 ,730,730,730 ,0,0,0}, - {31628,33443,33445 ,730,730,730 ,0,0,0}, {33607,33608,33414 ,730,730,730 ,0,0,0}, - {33608,33417,33414 ,730,730,730 ,0,0,0}, {33416,33605,33414 ,730,730,730 ,0,0,0}, - {33412,33603,33416 ,730,730,730 ,0,0,0}, {33602,33604,33410 ,730,730,730 ,0,0,0}, - {33407,33601,33410 ,730,730,730 ,0,0,0}, {32470,33599,33407 ,730,730,730 ,0,0,0}, - {33597,33598,33405 ,730,730,730 ,0,0,0}, {33600,33597,33426 ,730,730,730 ,0,0,0}, - {33427,33596,33426 ,730,730,730 ,0,0,0}, {33430,33577,33427 ,730,730,730 ,0,0,0}, - {33595,33576,33432 ,730,730,730 ,0,0,0}, {33433,33592,33432 ,730,730,730 ,0,0,0}, - {33436,33593,33433 ,730,730,730 ,0,0,0}, {33591,33594,33438 ,730,730,730 ,0,0,0}, - {33452,33591,31657 ,730,730,730 ,0,0,0}, {33590,33450,31657 ,730,730,730 ,0,0,0}, - {33586,33448,33590 ,730,730,730 ,0,0,0}, {33441,33446,33588 ,730,730,730 ,0,0,0}, - {33446,33586,33588 ,730,730,730 ,0,0,0}, {33442,33441,33589 ,730,730,730 ,0,0,0}, - {33587,33456,33589 ,730,730,730 ,0,0,0}, {33585,33458,33587 ,730,730,730 ,0,0,0}, - {33459,33457,33584 ,730,730,730 ,0,0,0}, {33583,33462,33584 ,730,730,730 ,0,0,0}, - {31628,33445,33583 ,730,730,730 ,0,0,0}, {33466,33580,33581 ,730,730,730 ,0,0,0}, - {33470,33463,33581 ,730,730,730 ,0,0,0}, {33578,33469,33582 ,730,730,730 ,0,0,0}, - {33582,33470,33581 ,730,730,730 ,0,0,0}, {33579,33475,33467 ,730,730,730 ,0,0,0}, - {33578,33467,33469 ,730,730,730 ,0,0,0}, {33579,33611,33472 ,730,730,730 ,0,0,0}, - {33473,33574,33477 ,730,730,730 ,0,0,0}, {33472,33611,33473 ,730,730,730 ,0,0,0}, - {33477,33575,33478 ,730,730,730 ,0,0,0}, {31643,33478,33575 ,730,730,730 ,0,0,0}, - {33612,33613,33557 ,18409,18410,18410 ,0,0,0}, {33613,33484,33488 ,18410,1433,1433 ,0,0,0}, - {33557,33613,33488 ,18410,18410,1433 ,0,0,0}, {33557,33614,33612 ,18410,18409,18409 ,0,0,0}, - {33486,33615,33527 ,2162,18411,18411 ,0,0,0}, {33615,33569,33573 ,18411,2162,2162 ,0,0,0}, - {33527,33615,33573 ,18411,18411,2162 ,0,0,0}, {33527,33487,33486 ,18411,2162,2162 ,0,0,0}, - {31643,33575,33616 ,18353,18412,18413 ,0,0,0}, {33579,33617,33611 ,18414,18415,18416 ,0,0,0}, - {33618,33619,33574 ,18417,18418,18419 ,0,0,0}, {33620,33581,33621 ,18420,18421,18422 ,0,0,0}, - {33578,33582,33622 ,18423,18239,18424 ,0,0,0}, {33583,33623,33624 ,18425,18426,18427 ,0,0,0}, - {33624,33625,31628 ,18427,324,18428 ,0,0,0}, {33587,33626,33585 ,18429,18430,18431 ,0,0,0}, - {33627,33584,33585 ,18432,18433,18431 ,0,0,0}, {33589,33628,33629 ,18434,18435,18436 ,0,0,0}, - {33629,33587,33589 ,18436,18429,18434 ,0,0,0}, {33628,33588,33630 ,18435,18437,18438 ,0,0,0}, - {33588,33628,33589 ,18437,18435,18434 ,0,0,0}, {33631,33630,33586 ,18439,18438,18440 ,0,0,0}, - {33588,33586,33630 ,18437,18440,18438 ,0,0,0}, {33590,33439,33631 ,18441,18256,18439 ,0,0,0}, - {33631,33586,33590 ,18439,18440,18441 ,0,0,0}, {31657,33439,33590 ,18002,18256,18441 ,0,0,0}, - {33629,33626,33587 ,18436,18430,18429 ,0,0,0}, {33627,33585,33626 ,18432,18431,18430 ,0,0,0}, - {33627,33623,33584 ,18432,18426,18433 ,0,0,0}, {33621,33580,33625 ,18422,18442,324 ,0,0,0}, - {33583,33624,31628 ,18425,18427,18428 ,0,0,0}, {33584,33623,33583 ,18433,18426,18425 ,0,0,0}, - {33625,33580,31628 ,324,18442,18428 ,0,0,0}, {33580,33621,33581 ,18442,18422,18421 ,0,0,0}, - {33622,33582,33620 ,18424,18239,18420 ,0,0,0}, {33582,33581,33620 ,18239,18421,18420 ,0,0,0}, - {33578,33632,33579 ,18423,18443,18414 ,0,0,0}, {33632,33578,33622 ,18443,18423,18424 ,0,0,0}, - {33618,33611,33617 ,18417,18416,18415 ,0,0,0}, {33632,33617,33579 ,18443,18415,18414 ,0,0,0}, - {33574,33619,33575 ,18419,18418,18412 ,0,0,0}, {33611,33618,33574 ,18416,18417,18419 ,0,0,0}, - {31643,33616,33423 ,18353,18413,3345 ,0,0,0}, {33575,33619,33616 ,18412,18418,18413 ,0,0,0}, - {33444,33633,33571 ,18444,18444,18113 ,0,0,0}, {33444,33634,33635 ,18444,18113,18113 ,0,0,0}, - {33444,33635,33633 ,18444,18113,18444 ,0,0,0}, {33633,33572,33571 ,18444,18113,18113 ,0,0,0}, - {33522,33524,33636 ,7758,7880,7627 ,0,0,0}, {33530,33531,33637 ,726,726,7627 ,0,0,0}, - {33516,33638,33639 ,726,18445,7755 ,0,0,0}, {33640,33518,33641 ,8017,7627,7627 ,0,0,0}, - {33642,33489,33643 ,18446,7758,18447 ,0,0,0}, {33643,33512,33644 ,18447,7264,7249 ,0,0,0}, - {33645,33495,33646 ,18448,7627,18449 ,0,0,0}, {33639,33647,33513 ,7755,8018,7755 ,0,0,0}, - {33492,33648,33646 ,7761,18450,18449 ,0,0,0}, {33649,33497,33495 ,18451,726,7627 ,0,0,0}, - {33497,33649,33650 ,726,18451,726 ,0,0,0}, {33490,33642,33648 ,7755,18446,18450 ,0,0,0}, - {33651,33501,33650 ,7264,7627,726 ,0,0,0}, {33499,33652,33502 ,7758,7264,7880 ,0,0,0}, - {33653,33654,33504 ,726,7880,7627 ,0,0,0}, {33655,33532,33656 ,726,7627,726 ,0,0,0}, - {33657,33543,33544 ,726,7627,7627 ,0,0,0}, {33654,33658,33507 ,7880,7627,7880 ,0,0,0}, - {33508,33564,33659 ,7627,7627,726 ,0,0,0}, {33563,33660,33659 ,7627,7627,726 ,0,0,0}, - {33561,33661,33558 ,7625,7627,7627 ,0,0,0}, {33559,33558,33662 ,726,7627,726 ,0,0,0}, - {33542,33663,33544 ,7627,726,7627 ,0,0,0}, {33660,33563,33559 ,7627,7627,726 ,0,0,0}, - {33664,33555,33556 ,7627,726,726 ,0,0,0}, {33553,33555,33665 ,7627,726,7627 ,0,0,0}, - {33530,33637,33666 ,726,7627,726 ,0,0,0}, {33666,33667,33552 ,726,7627,7627 ,0,0,0}, - {33668,33548,33545 ,7627,726,726 ,0,0,0}, {33667,33556,33549 ,7627,726,726 ,0,0,0}, - {33668,33543,33657 ,7627,7627,726 ,0,0,0}, {33548,33669,33531 ,726,726,726 ,0,0,0}, - {33661,33553,33665 ,7627,7627,7627 ,0,0,0}, {33542,33529,33670 ,7627,7625,726 ,0,0,0}, - {33655,33528,33532 ,726,726,7627 ,0,0,0}, {33656,33532,33534 ,726,7627,726 ,0,0,0}, - {33528,33655,33670 ,726,726,726 ,0,0,0}, {33658,33566,33508 ,7627,7627,7627 ,0,0,0}, - {33671,33534,33536 ,726,726,7627 ,0,0,0}, {33534,33671,33656 ,726,726,726 ,0,0,0}, - {33525,33536,33538 ,7627,7627,7627 ,0,0,0}, {33525,33671,33536 ,7627,726,7627 ,0,0,0}, - {33538,33672,33525 ,7627,7758,7627 ,0,0,0}, {33673,33641,33519 ,7758,7627,7758 ,0,0,0}, - {33651,33674,33499 ,7264,7761,7758 ,0,0,0}, {33642,33490,33489 ,18446,7755,7758 ,0,0,0}, - {33529,33528,33670 ,7625,726,726 ,0,0,0}, {33663,33542,33670 ,726,7627,726 ,0,0,0}, - {33657,33544,33663 ,726,7627,726 ,0,0,0}, {33545,33543,33668 ,726,7627,7627 ,0,0,0}, - {33669,33548,33668 ,726,726,7627 ,0,0,0}, {33637,33531,33669 ,7627,726,726 ,0,0,0}, - {33552,33530,33666 ,7627,726,726 ,0,0,0}, {33549,33552,33667 ,726,7627,7627 ,0,0,0}, - {33664,33556,33667 ,7627,726,7627 ,0,0,0}, {33665,33555,33664 ,7627,726,7627 ,0,0,0}, - {33561,33553,33661 ,7625,7627,7627 ,0,0,0}, {33662,33558,33661 ,726,7627,7627 ,0,0,0}, - {33660,33559,33662 ,7627,726,726 ,0,0,0}, {33564,33563,33659 ,7627,7627,726 ,0,0,0}, - {33566,33564,33508 ,7627,7627,7627 ,0,0,0}, {33507,33658,33508 ,7880,7627,7627 ,0,0,0}, - {33504,33654,33507 ,7627,7880,7880 ,0,0,0}, {33652,33653,33502 ,7264,726,7880 ,0,0,0}, - {33653,33504,33502 ,726,7627,7880 ,0,0,0}, {33674,33652,33499 ,7761,7264,7758 ,0,0,0}, - {33501,33651,33499 ,7627,7264,7758 ,0,0,0}, {33497,33650,33501 ,726,726,7627 ,0,0,0}, - {33645,33649,33495 ,18448,18451,7627 ,0,0,0}, {33492,33646,33495 ,7761,18449,7627 ,0,0,0}, - {33490,33648,33492 ,7755,18450,7761 ,0,0,0}, {33643,33489,33512 ,18447,7758,7264 ,0,0,0}, - {33647,33644,33512 ,8018,7249,7264 ,0,0,0}, {33516,33639,33513 ,726,7755,7755 ,0,0,0}, - {33513,33647,33512 ,7755,8018,7264 ,0,0,0}, {33518,33638,33516 ,7627,18445,726 ,0,0,0}, - {33518,33519,33641 ,7627,7758,7627 ,0,0,0}, {33518,33640,33638 ,7627,8017,18445 ,0,0,0}, - {33519,33522,33673 ,7758,7758,7758 ,0,0,0}, {33636,33524,33672 ,7627,7880,7758 ,0,0,0}, - {33673,33522,33636 ,7758,7758,7627 ,0,0,0}, {33525,33672,33524 ,7627,7758,7880 ,0,0,0}, - {33634,33471,33675 ,1398,18452,18452 ,0,0,0}, {33612,33614,33471 ,18453,18453,18452 ,0,0,0}, - {33614,33675,33471 ,18453,18452,18452 ,0,0,0}, {33675,33635,33634 ,18452,1398,1398 ,0,0,0}, - {33676,33538,33539 ,18454,18092,18121 ,0,0,0}, {33641,33673,33570 ,18455,18456,18457 ,0,0,0}, - {33677,33636,33678 ,18458,18459,18460 ,0,0,0}, {33640,33679,33638 ,18461,18462,18463 ,0,0,0}, - {33680,33633,33642 ,18464,7309,18465 ,0,0,0}, {33681,33644,33647 ,18466,18467,18468 ,0,0,0}, - {33650,33649,33682 ,18469,18470,18471 ,0,0,0}, {33645,33646,33683 ,18472,18473,18474 ,0,0,0}, - {33651,33684,33674 ,18475,18476,18477 ,0,0,0}, {33675,33653,33652 ,18478,18479,18480 ,0,0,0}, - {33674,33675,33652 ,18477,18478,18480 ,0,0,0}, {33653,33685,33654 ,18479,18481,18482 ,0,0,0}, - {33685,33653,33675 ,18481,18479,18478 ,0,0,0}, {33685,33686,33654 ,18481,18483,18482 ,0,0,0}, - {33687,33658,33686 ,18484,18485,18483 ,0,0,0}, {33654,33686,33658 ,18482,18483,18485 ,0,0,0}, - {33687,33568,33566 ,18484,18486,82 ,0,0,0}, {33566,33658,33687 ,82,18485,18484 ,0,0,0}, - {33682,33684,33651 ,18471,18476,18475 ,0,0,0}, {33674,33684,33675 ,18477,18476,18478 ,0,0,0}, - {33649,33688,33682 ,18470,18487,18471 ,0,0,0}, {33651,33650,33682 ,18475,18469,18471 ,0,0,0}, - {33683,33688,33645 ,18474,18487,18472 ,0,0,0}, {33649,33645,33688 ,18470,18472,18487 ,0,0,0}, - {33683,33648,33633 ,18474,18488,7309 ,0,0,0}, {33646,33648,33683 ,18473,18488,18474 ,0,0,0}, - {33680,33642,33643 ,18464,18465,18489 ,0,0,0}, {33633,33648,33642 ,7309,18488,18465 ,0,0,0}, - {33644,33681,33680 ,18467,18466,18464 ,0,0,0}, {33680,33643,33644 ,18464,18489,18467 ,0,0,0}, - {33639,33689,33647 ,18490,18491,18468 ,0,0,0}, {33689,33681,33647 ,18491,18466,18468 ,0,0,0}, - {33689,33638,33679 ,18491,18463,18462 ,0,0,0}, {33638,33689,33639 ,18463,18491,18490 ,0,0,0}, - {33640,33641,33570 ,18461,18455,18457 ,0,0,0}, {33640,33570,33679 ,18461,18457,18462 ,0,0,0}, - {33673,33636,33677 ,18456,18459,18458 ,0,0,0}, {33673,33677,33570 ,18456,18458,18457 ,0,0,0}, - {33678,33672,33676 ,18460,18492,18454 ,0,0,0}, {33636,33672,33678 ,18459,18492,18460 ,0,0,0}, - {33538,33676,33672 ,18092,18454,18492 ,0,0,0}, {33562,33614,33565 ,7792,726,7658 ,0,0,0}, - {33614,33557,33565 ,726,726,7658 ,0,0,0}, {33568,33614,33567 ,7664,726,7662 ,0,0,0}, - {33614,33562,33567 ,726,7792,7662 ,0,0,0}, {33686,33614,33687 ,7662,726,5488 ,0,0,0}, - {33614,33568,33687 ,726,7664,5488 ,0,0,0}, {33675,33614,33685 ,726,726,726 ,0,0,0}, - {33614,33686,33685 ,726,7662,726 ,0,0,0}, {33689,33572,33681 ,726,726,17470 ,0,0,0}, - {33681,33572,33680 ,17470,726,7628 ,0,0,0}, {33572,33633,33680 ,726,726,7628 ,0,0,0}, - {33572,33679,33570 ,726,726,726 ,0,0,0}, {33572,33689,33679 ,726,726,726 ,0,0,0}, - {33540,33487,33527 ,726,726,726 ,0,0,0}, {33546,33487,33541 ,7661,726,7659 ,0,0,0}, - {33487,33540,33541 ,726,726,7659 ,0,0,0}, {33483,33487,33547 ,7661,726,7661 ,0,0,0}, - {33487,33546,33547 ,726,7661,7661 ,0,0,0}, {33488,33551,33550 ,7660,7660,7660 ,0,0,0}, - {33483,33551,33488 ,726,7660,7660 ,0,0,0}, {33488,33560,33557 ,7660,726,726 ,0,0,0}, - {33488,33554,33560 ,7660,7658,726 ,0,0,0}, {33550,33554,33488 ,7660,7658,7660 ,0,0,0}, - {33675,33684,33635 ,726,726,726 ,0,0,0}, {33688,33635,33682 ,726,726,7661 ,0,0,0}, - {33684,33682,33635 ,726,7661,726 ,0,0,0}, {33683,33633,33635 ,726,726,726 ,0,0,0}, - {33683,33635,33688 ,726,726,726 ,0,0,0}, {33677,33573,33570 ,726,726,726 ,0,0,0}, - {33676,33573,33678 ,726,726,726 ,0,0,0}, {33573,33677,33678 ,726,726,726 ,0,0,0}, - {33537,33573,33539 ,726,726,726 ,0,0,0}, {33573,33676,33539 ,726,726,726 ,0,0,0}, - {33533,33573,33535 ,726,726,7660 ,0,0,0}, {33573,33537,33535 ,726,726,7660 ,0,0,0}, - {33527,33573,33533 ,726,726,726 ,0,0,0}, {33523,33521,33690 ,726,726,7583 ,0,0,0}, - {33691,33692,33693 ,726,726,726 ,0,0,0}, {33694,33691,33526 ,726,726,726 ,0,0,0}, - {33690,33695,33523 ,7583,7583,726 ,0,0,0}, {33696,33697,33693 ,726,726,726 ,0,0,0}, - {33698,33699,33692 ,726,726,726 ,0,0,0}, {33696,33693,33699 ,726,726,726 ,0,0,0}, - {33692,33699,33693 ,726,726,726 ,0,0,0}, {33693,33700,33691 ,726,726,726 ,0,0,0}, - {33523,33694,33526 ,726,726,726 ,0,0,0}, {33526,33691,33700 ,726,726,726 ,0,0,0}, - {33690,33521,33520 ,7583,726,726 ,0,0,0}, {33523,33695,33694 ,726,7583,726 ,0,0,0}, - {33701,33520,33517 ,7583,726,726 ,0,0,0}, {33520,33701,33690 ,726,7583,7583 ,0,0,0}, - {33517,33702,33703 ,726,726,726 ,0,0,0}, {33701,33517,33703 ,7583,726,726 ,0,0,0}, - {33515,33702,33517 ,726,726,726 ,0,0,0}, {33702,33514,33704 ,726,726,726 ,0,0,0}, - {33514,33702,33515 ,726,726,726 ,0,0,0}, {33514,33511,33704 ,726,726,726 ,0,0,0}, - {33705,33511,33706 ,726,726,5489 ,0,0,0}, {33705,33704,33511 ,726,726,726 ,0,0,0}, - {33706,33510,33491 ,5489,7583,726 ,0,0,0}, {33511,33510,33706 ,726,7583,5489 ,0,0,0}, - {33494,33509,33491 ,7583,7583,726 ,0,0,0}, {33706,33491,33509 ,5489,726,7583 ,0,0,0}, - {33498,33505,33493 ,7583,7583,726 ,0,0,0}, {33493,33496,33498 ,726,726,7583 ,0,0,0}, - {33505,33500,33503 ,7583,7583,726 ,0,0,0}, {33505,33494,33493 ,7583,7583,726 ,0,0,0}, - {33505,33506,33494 ,7583,5489,7583 ,0,0,0}, {33505,33498,33500 ,7583,7583,7583 ,0,0,0}, - {33494,33506,33509 ,7583,5489,7583 ,0,0,0}, {33508,33659,33706 ,35,18493,18494 ,0,0,0}, - {33661,33702,33662 ,18495,18496,18497 ,0,0,0}, {33704,33705,33660 ,18498,18499,18500 ,0,0,0}, - {33690,33667,33695 ,18501,18502,18503 ,0,0,0}, {33665,33664,33701 ,18504,18505,18506 ,0,0,0}, - {33669,33692,33691 ,18507,18508,18509 ,0,0,0}, {33691,33694,33637 ,18509,18510,18511 ,0,0,0}, - {33663,33699,33657 ,18512,18513,18514 ,0,0,0}, {33698,33668,33657 ,18515,18516,18514 ,0,0,0}, - {33670,33697,33696 ,18517,18518,18519 ,0,0,0}, {33696,33663,33670 ,18519,18512,18517 ,0,0,0}, - {33697,33655,33693 ,18518,18520,18521 ,0,0,0}, {33655,33697,33670 ,18520,18518,18517 ,0,0,0}, - {33700,33693,33656 ,18522,18521,18523 ,0,0,0}, {33655,33656,33693 ,18520,18523,18521 ,0,0,0}, - {33671,33526,33700 ,18524,18188,18522 ,0,0,0}, {33700,33656,33671 ,18522,18523,18524 ,0,0,0}, - {33525,33526,33671 ,18188,18188,18524 ,0,0,0}, {33696,33699,33663 ,18519,18513,18512 ,0,0,0}, - {33698,33657,33699 ,18515,18514,18513 ,0,0,0}, {33698,33692,33668 ,18515,18508,18516 ,0,0,0}, - {33695,33666,33694 ,18503,18525,18510 ,0,0,0}, {33669,33691,33637 ,18507,18509,18511 ,0,0,0}, - {33668,33692,33669 ,18516,18508,18507 ,0,0,0}, {33694,33666,33637 ,18510,18525,18511 ,0,0,0}, - {33666,33695,33667 ,18525,18503,18502 ,0,0,0}, {33701,33664,33690 ,18506,18505,18501 ,0,0,0}, - {33664,33667,33690 ,18505,18502,18501 ,0,0,0}, {33665,33703,33661 ,18504,18526,18495 ,0,0,0}, - {33703,33665,33701 ,18526,18504,18506 ,0,0,0}, {33704,33662,33702 ,18498,18497,18496 ,0,0,0}, - {33703,33702,33661 ,18526,18496,18495 ,0,0,0}, {33660,33705,33659 ,18500,18499,18493 ,0,0,0}, - {33662,33704,33660 ,18497,18498,18500 ,0,0,0}, {33508,33706,33509 ,35,18494,763 ,0,0,0}, - {33659,33705,33706 ,18493,18499,18494 ,0,0,0}, {33707,33452,33453 ,18527,126,18026 ,0,0,0}, - {33592,33593,33615 ,18528,18529,18530 ,0,0,0}, {33708,33594,33709 ,18531,18532,18533 ,0,0,0}, - {33595,33710,33576 ,18534,18535,18536 ,0,0,0}, {33711,33485,33598 ,18537,10001,18538 ,0,0,0}, - {33712,33600,33596 ,18539,18540,18541 ,0,0,0}, {33603,33604,33713 ,18542,18543,18544 ,0,0,0}, - {33602,33601,33714 ,18545,18546,18547 ,0,0,0}, {33605,33715,33607 ,18548,18549,18550 ,0,0,0}, - {33613,33606,33608 ,18551,18552,18553 ,0,0,0}, {33607,33613,33608 ,18550,18551,18553 ,0,0,0}, - {33606,33716,33609 ,18552,18554,18555 ,0,0,0}, {33716,33606,33613 ,18554,18552,18551 ,0,0,0}, - {33716,33717,33609 ,18554,18556,18555 ,0,0,0}, {33718,33610,33717 ,18557,18558,18556 ,0,0,0}, - {33609,33717,33610 ,18555,18556,18558 ,0,0,0}, {33718,33482,33480 ,18557,5000,18205 ,0,0,0}, - {33480,33610,33718 ,18205,18558,18557 ,0,0,0}, {33713,33715,33605 ,18544,18549,18548 ,0,0,0}, - {33607,33715,33613 ,18550,18549,18551 ,0,0,0}, {33604,33719,33713 ,18543,18559,18544 ,0,0,0}, - {33605,33603,33713 ,18548,18542,18544 ,0,0,0}, {33714,33719,33602 ,18547,18559,18545 ,0,0,0}, - {33604,33602,33719 ,18543,18545,18559 ,0,0,0}, {33714,33599,33485 ,18547,18560,10001 ,0,0,0}, - {33601,33599,33714 ,18546,18560,18547 ,0,0,0}, {33711,33598,33597 ,18537,18538,18561 ,0,0,0}, - {33485,33599,33598 ,10001,18560,18538 ,0,0,0}, {33600,33712,33711 ,18540,18539,18537 ,0,0,0}, - {33711,33597,33600 ,18537,18561,18540 ,0,0,0}, {33577,33720,33596 ,18562,18563,18541 ,0,0,0}, - {33720,33712,33596 ,18563,18539,18541 ,0,0,0}, {33720,33576,33710 ,18563,18536,18535 ,0,0,0}, - {33576,33720,33577 ,18536,18563,18562 ,0,0,0}, {33595,33592,33615 ,18534,18528,18530 ,0,0,0}, - {33595,33615,33710 ,18534,18530,18535 ,0,0,0}, {33593,33594,33708 ,18529,18532,18531 ,0,0,0}, - {33593,33708,33615 ,18529,18531,18530 ,0,0,0}, {33709,33591,33707 ,18533,18564,18527 ,0,0,0}, - {33594,33591,33709 ,18532,18564,18533 ,0,0,0}, {33452,33707,33591 ,126,18527,18564 ,0,0,0}, - {33486,33720,33710 ,17561,17561,730 ,0,0,0}, {33711,33486,33485 ,730,17561,730 ,0,0,0}, - {33720,33486,33712 ,17561,17561,730 ,0,0,0}, {33486,33711,33712 ,17561,730,730 ,0,0,0}, - {33710,33615,33486 ,730,7376,17561 ,0,0,0}, {33479,33612,33471 ,18207,730,730 ,0,0,0}, - {33612,33718,33717 ,730,730,730 ,0,0,0}, {33481,33612,33476 ,17561,730,7433 ,0,0,0}, - {33612,33479,33476 ,730,18207,7433 ,0,0,0}, {33718,33612,33482 ,730,730,17561 ,0,0,0}, - {33612,33481,33482 ,730,17561,17561 ,0,0,0}, {33717,33716,33612 ,730,7433,730 ,0,0,0}, - {33716,33613,33612 ,7433,730,730 ,0,0,0}, {33455,33571,33454 ,7017,730,730 ,0,0,0}, - {33571,33440,33454 ,730,11465,730 ,0,0,0}, {33461,33571,33460 ,18565,730,730 ,0,0,0}, - {33571,33455,33460 ,730,7017,730 ,0,0,0}, {33444,33571,33461 ,18566,730,18565 ,0,0,0}, - {33719,33484,33713 ,730,7376,17561 ,0,0,0}, {33715,33713,33484 ,730,17561,7376 ,0,0,0}, - {33613,33715,33484 ,730,730,7376 ,0,0,0}, {33714,33485,33484 ,7376,730,7376 ,0,0,0}, - {33714,33484,33719 ,7376,7376,730 ,0,0,0}, {33465,33464,33634 ,18207,18207,9877 ,0,0,0}, - {33444,33465,33634 ,18567,18207,9877 ,0,0,0}, {33468,33474,33634 ,730,9878,9877 ,0,0,0}, - {33468,33634,33464 ,730,9877,18207 ,0,0,0}, {33471,33634,33474 ,730,9877,9878 ,0,0,0}, - {33615,33708,33569 ,730,730,730 ,0,0,0}, {33569,33707,33453 ,730,730,9877 ,0,0,0}, - {33707,33569,33709 ,730,730,730 ,0,0,0}, {33569,33708,33709 ,730,730,730 ,0,0,0}, - {33453,33451,33569 ,9877,730,730 ,0,0,0}, {33569,33449,33447 ,730,9878,730 ,0,0,0}, - {33451,33449,33569 ,730,9878,730 ,0,0,0}, {33447,33440,33569 ,730,730,730 ,0,0,0}, - {33616,33619,33425 ,730,730,9878 ,0,0,0}, {33409,33408,33420 ,730,730,730 ,0,0,0}, - {33406,33409,33423 ,9875,730,730 ,0,0,0}, {33425,33424,33616 ,9878,730,730 ,0,0,0}, - {33415,33418,33420 ,730,730,730 ,0,0,0}, {33411,33413,33408 ,730,730,730 ,0,0,0}, - {33415,33420,33413 ,730,730,730 ,0,0,0}, {33408,33413,33420 ,730,730,730 ,0,0,0}, - {33420,33421,33409 ,730,730,730 ,0,0,0}, {33616,33406,33423 ,730,9875,730 ,0,0,0}, - {33423,33409,33421 ,730,730,730 ,0,0,0}, {33425,33619,33618 ,9878,730,730 ,0,0,0}, - {33616,33424,33406 ,730,730,9875 ,0,0,0}, {33428,33618,33617 ,9878,730,730 ,0,0,0}, - {33618,33428,33425 ,730,9878,9878 ,0,0,0}, {33617,33431,33429 ,730,730,730 ,0,0,0}, - {33428,33617,33429 ,9878,730,730 ,0,0,0}, {33632,33431,33617 ,730,730,730 ,0,0,0}, - {33431,33622,33434 ,730,9875,9878 ,0,0,0}, {33622,33431,33632 ,9875,730,730 ,0,0,0}, - {33622,33620,33434 ,9875,730,9878 ,0,0,0}, {33435,33620,33437 ,9878,730,730 ,0,0,0}, - {33435,33434,33620 ,9878,9878,730 ,0,0,0}, {33437,33621,33625 ,730,9875,9875 ,0,0,0}, - {33620,33621,33437 ,730,9875,730 ,0,0,0}, {33624,33439,33625 ,730,9878,9875 ,0,0,0}, - {33437,33625,33439 ,730,9875,9878 ,0,0,0}, {33626,33630,33623 ,9878,9878,730 ,0,0,0}, - {33623,33627,33626 ,730,9878,9878 ,0,0,0}, {33630,33629,33628 ,9878,9878,9877 ,0,0,0}, - {33630,33624,33623 ,9878,730,730 ,0,0,0}, {33630,33631,33624 ,9878,730,730 ,0,0,0}, - {33630,33626,33629 ,9878,9878,9878 ,0,0,0}, {33624,33631,33439 ,730,730,9878 ,0,0,0} -// M3abstandhalter10mm.prt - , {33721,32535,33722 ,18258,18259,18260 ,0,0,0}, {33723,33724,33725 ,18261,18262,18263 ,0,0,0}, - {33722,32535,33725 ,18260,18259,18263 ,0,0,0}, {33724,33723,33726 ,18262,18261,18264 ,0,0,0}, - {33726,33727,33724 ,18264,18265,18262 ,0,0,0}, {33727,33728,33729 ,18265,18266,18267 ,0,0,0}, - {33726,33728,33727 ,18264,18266,18265 ,0,0,0}, {33723,33725,32535 ,18261,18263,18259 ,0,0,0}, - {33730,33731,33732 ,18268,18269,18270 ,0,0,0}, {33731,33729,33732 ,18269,18267,18270 ,0,0,0}, - {33730,33733,33734 ,18268,18271,18272 ,0,0,0}, {33734,33731,33730 ,18272,18269,18268 ,0,0,0}, - {33733,33735,33736 ,18271,18273,18274 ,0,0,0}, {33733,33736,33734 ,18271,18274,18272 ,0,0,0}, - {33728,33732,33729 ,18266,18270,18267 ,0,0,0}, {33737,33736,33735 ,18275,18274,18273 ,0,0,0}, - {33738,31708,33739 ,18276,18277,126 ,0,0,0}, {33738,33739,33737 ,18276,126,18275 ,0,0,0}, - {33735,33738,33737 ,18273,18276,18275 ,0,0,0}, {33721,33722,33740 ,18258,18260,18278 ,0,0,0}, - {33740,33741,33742 ,18278,18279,18280 ,0,0,0}, {33742,33721,33740 ,18280,18258,18278 ,0,0,0}, - {33743,33741,33744 ,18281,18279,18282 ,0,0,0}, {33741,33743,33742 ,18279,18281,18280 ,0,0,0}, - {33745,33746,33744 ,18283,18284,18282 ,0,0,0}, {33743,33744,33746 ,18281,18282,18284 ,0,0,0}, - {33745,33747,33748 ,18283,18285,18286 ,0,0,0}, {33748,33746,33745 ,18286,18284,18283 ,0,0,0}, - {33749,33747,33750 ,18287,18285,18288 ,0,0,0}, {33747,33749,33748 ,18285,18287,18286 ,0,0,0}, - {33751,33752,33750 ,18289,18290,18288 ,0,0,0}, {33749,33750,33752 ,18287,18288,18290 ,0,0,0}, - {33751,33753,33754 ,18289,18291,18292 ,0,0,0}, {33754,33752,33751 ,18292,18290,18289 ,0,0,0}, - {31722,33753,33755 ,18293,18291,18003 ,0,0,0}, {33753,31722,33754 ,18291,18293,18292 ,0,0,0}, - {33756,33757,33758 ,18294,18295,18296 ,0,0,0}, {33759,33760,33761 ,18297,21,18298 ,0,0,0}, - {33762,33756,33763 ,18299,18294,18300 ,0,0,0}, {33756,33762,33757 ,18294,18299,18295 ,0,0,0}, - {33762,33763,33764 ,18299,18300,18301 ,0,0,0}, {33765,33766,33764 ,18302,18303,18301 ,0,0,0}, - {33764,33763,33765 ,18301,18300,18302 ,0,0,0}, {33766,33767,33768 ,18303,18304,126 ,0,0,0}, - {33767,33766,33765 ,18304,18303,18302 ,0,0,0}, {33767,33769,33768 ,18304,3135,126 ,0,0,0}, - {33756,33758,33770 ,18294,18296,18305 ,0,0,0}, {33771,33770,33772 ,18306,18305,18307 ,0,0,0}, - {33758,33772,33770 ,18296,18307,18305 ,0,0,0}, {33773,33771,33774 ,18308,18306,18309 ,0,0,0}, - {33771,33772,33774 ,18306,18307,18309 ,0,0,0}, {33773,33775,33776 ,18308,18310,18311 ,0,0,0}, - {33776,33771,33773 ,18311,18306,18308 ,0,0,0}, {33777,33775,33778 ,18312,18310,18313 ,0,0,0}, - {33775,33777,33776 ,18310,18312,18311 ,0,0,0}, {33760,33777,33761 ,21,18312,18298 ,0,0,0}, - {33778,33761,33777 ,18313,18298,18312 ,0,0,0}, {33779,33780,33781 ,18314,18315,18316 ,0,0,0}, - {33759,33782,33781 ,18297,18317,18316 ,0,0,0}, {33783,33784,33785 ,18318,18319,18320 ,0,0,0}, - {33784,33780,33786 ,18319,18315,18321 ,0,0,0}, {33787,33788,33789 ,18322,18323,18324 ,0,0,0}, - {33790,33791,33787 ,18325,18326,18322 ,0,0,0}, {33792,33793,33794 ,18327,18328,18329 ,0,0,0}, - {33793,33792,33795 ,18328,18327,18330 ,0,0,0}, {33796,33797,33794 ,18037,18331,18329 ,0,0,0}, - {33792,33794,33797 ,18327,18329,18331 ,0,0,0}, {33798,33797,33796 ,18038,18331,18037 ,0,0,0}, - {33789,33795,33787 ,18324,18330,18322 ,0,0,0}, {33789,33793,33795 ,18324,18328,18330 ,0,0,0}, - {33784,33783,33790 ,18319,18318,18325 ,0,0,0}, {33787,33791,33788 ,18322,18326,18323 ,0,0,0}, - {33790,33783,33791 ,18325,18318,18326 ,0,0,0}, {33780,33779,33786 ,18315,18314,18321 ,0,0,0}, - {33785,33784,33786 ,18320,18319,18321 ,0,0,0}, {33781,33760,33759 ,18316,21,18297 ,0,0,0}, - {33779,33781,33782 ,18314,18316,18317 ,0,0,0}, {33799,33800,33801 ,18332,1077,18332 ,0,0,0}, - {33802,33803,33801 ,18333,18333,18332 ,0,0,0}, {33803,33799,33801 ,18333,18332,18332 ,0,0,0}, - {33799,33804,33800 ,18332,18334,1077 ,0,0,0}, {33805,33806,33807 ,18335,18336,324 ,0,0,0}, - {33808,33809,33810 ,18337,18338,18339 ,0,0,0}, {33807,33806,33810 ,324,18336,18339 ,0,0,0}, - {33809,33808,33811 ,18338,18337,18340 ,0,0,0}, {33811,33812,33809 ,18340,18341,18338 ,0,0,0}, - {33812,33813,33814 ,18341,18342,18343 ,0,0,0}, {33811,33813,33812 ,18340,18342,18341 ,0,0,0}, - {33808,33810,33806 ,18337,18339,18336 ,0,0,0}, {33815,33816,33817 ,18344,18345,18346 ,0,0,0}, - {33816,33814,33817 ,18345,18343,18346 ,0,0,0}, {33815,33818,33819 ,18344,18347,18348 ,0,0,0}, - {33819,33816,33815 ,18348,18345,18344 ,0,0,0}, {33818,33820,33821 ,18347,18349,18350 ,0,0,0}, - {33818,33821,33819 ,18347,18350,18348 ,0,0,0}, {33813,33817,33814 ,18342,18346,18343 ,0,0,0}, - {33822,33821,33820 ,18351,18350,18349 ,0,0,0}, {33823,33824,33825 ,18352,18353,126 ,0,0,0}, - {33823,33825,33822 ,18352,126,18351 ,0,0,0}, {33820,33823,33822 ,18349,18352,18351 ,0,0,0}, - {33805,33807,33826 ,18335,324,18354 ,0,0,0}, {33826,33827,33828 ,18354,18355,18356 ,0,0,0}, - {33828,33805,33826 ,18356,18335,18354 ,0,0,0}, {33829,33827,33830 ,18357,18355,18358 ,0,0,0}, - {33827,33829,33828 ,18355,18357,18356 ,0,0,0}, {33831,33832,33830 ,18359,18360,18358 ,0,0,0}, - {33829,33830,33832 ,18357,18358,18360 ,0,0,0}, {33831,33833,33834 ,18359,18361,18362 ,0,0,0}, - {33834,33832,33831 ,18362,18360,18359 ,0,0,0}, {33835,33833,33836 ,18363,18361,18364 ,0,0,0}, - {33833,33835,33834 ,18361,18363,18362 ,0,0,0}, {33837,33838,33836 ,18365,18366,18364 ,0,0,0}, - {33835,33836,33838 ,18363,18364,18366 ,0,0,0}, {33837,33839,33840 ,18365,18367,18368 ,0,0,0}, - {33840,33838,33837 ,18368,18366,18365 ,0,0,0}, {33841,33839,33842 ,18369,18367,18188 ,0,0,0}, - {33839,33841,33840 ,18367,18369,18368 ,0,0,0}, {33843,33844,33845 ,18370,18371,18372 ,0,0,0}, - {33846,33799,33847 ,18373,324,18374 ,0,0,0}, {33848,33843,33849 ,18375,18370,18376 ,0,0,0}, - {33843,33848,33844 ,18370,18375,18371 ,0,0,0}, {33848,33849,33850 ,18375,18376,18377 ,0,0,0}, - {33851,33852,33850 ,18378,18379,18377 ,0,0,0}, {33850,33849,33851 ,18377,18376,18378 ,0,0,0}, - {33852,33853,33854 ,18379,18380,18092 ,0,0,0}, {33853,33852,33851 ,18380,18379,18378 ,0,0,0}, - {33853,33855,33854 ,18380,18381,18092 ,0,0,0}, {33843,33845,33856 ,18370,18372,18382 ,0,0,0}, - {33857,33856,33858 ,18383,18382,18384 ,0,0,0}, {33845,33858,33856 ,18372,18384,18382 ,0,0,0}, - {33859,33857,33860 ,18385,18383,18386 ,0,0,0}, {33857,33858,33860 ,18383,18384,18386 ,0,0,0}, - {33859,33861,33862 ,18385,18387,18388 ,0,0,0}, {33862,33857,33859 ,18388,18383,18385 ,0,0,0}, - {33863,33861,33864 ,18389,18387,18390 ,0,0,0}, {33861,33863,33862 ,18387,18389,18388 ,0,0,0}, - {33799,33863,33847 ,324,18389,18374 ,0,0,0}, {33864,33847,33863 ,18390,18374,18389 ,0,0,0}, - {33865,33866,33867 ,18391,18392,18393 ,0,0,0}, {33846,33868,33867 ,18373,18394,18393 ,0,0,0}, - {33869,33870,33871 ,18395,18396,18397 ,0,0,0}, {33870,33866,33872 ,18396,18392,18398 ,0,0,0}, - {33873,33874,33875 ,18399,18400,18401 ,0,0,0}, {33876,33877,33873 ,18402,18403,18399 ,0,0,0}, - {33878,33879,33880 ,18404,18405,18406 ,0,0,0}, {33879,33878,33881 ,18405,18404,18407 ,0,0,0}, - {33882,33883,33880 ,82,18408,18406 ,0,0,0}, {33878,33880,33883 ,18404,18406,18408 ,0,0,0}, - {33884,33883,33882 ,18103,18408,82 ,0,0,0}, {33875,33881,33873 ,18401,18407,18399 ,0,0,0}, - {33875,33879,33881 ,18401,18405,18407 ,0,0,0}, {33870,33869,33876 ,18396,18395,18402 ,0,0,0}, - {33873,33877,33874 ,18399,18403,18400 ,0,0,0}, {33876,33869,33877 ,18402,18395,18403 ,0,0,0}, - {33866,33865,33872 ,18392,18391,18398 ,0,0,0}, {33871,33870,33872 ,18397,18396,18398 ,0,0,0}, - {33867,33799,33846 ,18393,324,18373 ,0,0,0}, {33865,33867,33868 ,18391,18393,18394 ,0,0,0}, - {33885,33756,33886 ,2197,2197,2197 ,0,0,0}, {33887,33888,33756 ,2197,2197,2197 ,0,0,0}, - {33888,33886,33756 ,2197,2197,2197 ,0,0,0}, {33886,33889,33885 ,2197,2197,2197 ,0,0,0}, - {33890,33891,33793 ,730,730,730 ,0,0,0}, {33746,33892,33893 ,730,730,730 ,0,0,0}, - {33894,33895,33783 ,730,730,730 ,0,0,0}, {33791,33895,33788 ,730,730,730 ,0,0,0}, - {33759,33896,33782 ,730,730,730 ,0,0,0}, {33782,33897,33779 ,730,730,730 ,0,0,0}, - {33898,33785,33786 ,730,730,730 ,0,0,0}, {33778,33899,33761 ,730,730,730 ,0,0,0}, - {33775,33900,33778 ,730,730,730 ,0,0,0}, {33901,33900,33773 ,730,730,730 ,0,0,0}, - {33773,33774,33901 ,730,730,730 ,0,0,0}, {33762,33764,33902 ,730,730,730 ,0,0,0}, - {33903,33774,33772 ,730,730,730 ,0,0,0}, {33757,33904,33905 ,730,730,730 ,0,0,0}, - {33906,33764,33766 ,730,730,730 ,0,0,0}, {31722,33766,33768 ,730,730,730 ,0,0,0}, - {31722,33907,33754 ,730,730,730 ,0,0,0}, {33908,33749,33909 ,730,730,730 ,0,0,0}, - {33752,33754,33910 ,730,730,730 ,0,0,0}, {33752,33910,33909 ,730,730,730 ,0,0,0}, - {33908,33911,33748 ,730,730,730 ,0,0,0}, {33746,33748,33892 ,730,730,730 ,0,0,0}, - {33758,33905,33772 ,730,730,730 ,0,0,0}, {33743,33893,33912 ,730,730,730 ,0,0,0}, - {33721,33742,33913 ,730,730,730 ,0,0,0}, {33721,33914,32535 ,730,730,730 ,0,0,0}, - {33914,33915,32535 ,730,730,730 ,0,0,0}, {33742,33912,33916 ,730,730,730 ,0,0,0}, - {33917,33723,33915 ,730,730,730 ,0,0,0}, {33726,33917,33918 ,730,730,730 ,0,0,0}, - {33919,33728,33920 ,730,730,730 ,0,0,0}, {33728,33726,33920 ,730,730,730 ,0,0,0}, - {33732,33919,33921 ,730,730,730 ,0,0,0}, {33922,33735,33733 ,730,730,730 ,0,0,0}, - {33923,33730,33921 ,730,730,730 ,0,0,0}, {33922,33733,33924 ,730,730,730 ,0,0,0}, - {33896,33759,31692 ,730,730,730 ,0,0,0}, {33738,33735,33925 ,730,730,730 ,0,0,0}, - {33922,33925,33735 ,730,730,730 ,0,0,0}, {33738,33926,31708 ,730,730,730 ,0,0,0}, - {33926,33738,33925 ,730,730,730 ,0,0,0}, {31708,33796,33794 ,730,730,730 ,0,0,0}, - {33926,33796,31708 ,730,730,730 ,0,0,0}, {33927,33890,33789 ,730,730,730 ,0,0,0}, - {31692,33759,33761 ,730,730,730 ,0,0,0}, {33923,33924,33730 ,730,730,730 ,0,0,0}, - {33924,33733,33730 ,730,730,730 ,0,0,0}, {33732,33921,33730 ,730,730,730 ,0,0,0}, - {33728,33919,33732 ,730,730,730 ,0,0,0}, {33918,33920,33726 ,730,730,730 ,0,0,0}, - {33723,33917,33726 ,730,730,730 ,0,0,0}, {32535,33915,33723 ,730,730,730 ,0,0,0}, - {33913,33914,33721 ,730,730,730 ,0,0,0}, {33916,33913,33742 ,730,730,730 ,0,0,0}, - {33743,33912,33742 ,730,730,730 ,0,0,0}, {33746,33893,33743 ,730,730,730 ,0,0,0}, - {33911,33892,33748 ,730,730,730 ,0,0,0}, {33749,33908,33748 ,730,730,730 ,0,0,0}, - {33752,33909,33749 ,730,730,730 ,0,0,0}, {33907,33910,33754 ,730,730,730 ,0,0,0}, - {33768,33907,31722 ,730,730,730 ,0,0,0}, {33906,33766,31722 ,730,730,730 ,0,0,0}, - {33902,33764,33906 ,730,730,730 ,0,0,0}, {33757,33762,33904 ,730,730,730 ,0,0,0}, - {33762,33902,33904 ,730,730,730 ,0,0,0}, {33758,33757,33905 ,730,730,730 ,0,0,0}, - {33903,33772,33905 ,730,730,730 ,0,0,0}, {33901,33774,33903 ,730,730,730 ,0,0,0}, - {33775,33773,33900 ,730,730,730 ,0,0,0}, {33899,33778,33900 ,730,730,730 ,0,0,0}, - {31692,33761,33899 ,730,730,730 ,0,0,0}, {33782,33896,33897 ,730,730,730 ,0,0,0}, - {33786,33779,33897 ,730,730,730 ,0,0,0}, {33894,33785,33898 ,730,730,730 ,0,0,0}, - {33898,33786,33897 ,730,730,730 ,0,0,0}, {33895,33791,33783 ,730,730,730 ,0,0,0}, - {33894,33783,33785 ,730,730,730 ,0,0,0}, {33895,33927,33788 ,730,730,730 ,0,0,0}, - {33789,33890,33793 ,730,730,730 ,0,0,0}, {33788,33927,33789 ,730,730,730 ,0,0,0}, - {33793,33891,33794 ,730,730,730 ,0,0,0}, {31708,33794,33891 ,730,730,730 ,0,0,0}, - {33928,33929,33873 ,18409,18410,18410 ,0,0,0}, {33929,33800,33804 ,18410,1433,1433 ,0,0,0}, - {33873,33929,33804 ,18410,18410,1433 ,0,0,0}, {33873,33930,33928 ,18410,18409,18409 ,0,0,0}, - {33802,33931,33843 ,2162,18411,18411 ,0,0,0}, {33931,33885,33889 ,18411,2162,2162 ,0,0,0}, - {33843,33931,33889 ,18411,18411,2162 ,0,0,0}, {33843,33803,33802 ,18411,2162,2162 ,0,0,0}, - {31708,33891,33932 ,18353,18412,18413 ,0,0,0}, {33895,33933,33927 ,18414,18415,18416 ,0,0,0}, - {33934,33935,33890 ,18417,18418,18419 ,0,0,0}, {33936,33897,33937 ,18420,18421,18422 ,0,0,0}, - {33894,33898,33938 ,18423,18239,18424 ,0,0,0}, {33899,33939,33940 ,18425,18426,18427 ,0,0,0}, - {33940,33941,31692 ,18427,324,18428 ,0,0,0}, {33903,33942,33901 ,18429,18430,18431 ,0,0,0}, - {33943,33900,33901 ,18432,18433,18431 ,0,0,0}, {33905,33944,33945 ,18434,18435,18436 ,0,0,0}, - {33945,33903,33905 ,18436,18429,18434 ,0,0,0}, {33944,33904,33946 ,18435,18437,18438 ,0,0,0}, - {33904,33944,33905 ,18437,18435,18434 ,0,0,0}, {33947,33946,33902 ,18439,18438,18440 ,0,0,0}, - {33904,33902,33946 ,18437,18440,18438 ,0,0,0}, {33906,33755,33947 ,18441,18256,18439 ,0,0,0}, - {33947,33902,33906 ,18439,18440,18441 ,0,0,0}, {31722,33755,33906 ,18002,18256,18441 ,0,0,0}, - {33945,33942,33903 ,18436,18430,18429 ,0,0,0}, {33943,33901,33942 ,18432,18431,18430 ,0,0,0}, - {33943,33939,33900 ,18432,18426,18433 ,0,0,0}, {33937,33896,33941 ,18422,18442,324 ,0,0,0}, - {33899,33940,31692 ,18425,18427,18428 ,0,0,0}, {33900,33939,33899 ,18433,18426,18425 ,0,0,0}, - {33941,33896,31692 ,324,18442,18428 ,0,0,0}, {33896,33937,33897 ,18442,18422,18421 ,0,0,0}, - {33938,33898,33936 ,18424,18239,18420 ,0,0,0}, {33898,33897,33936 ,18239,18421,18420 ,0,0,0}, - {33894,33948,33895 ,18423,18443,18414 ,0,0,0}, {33948,33894,33938 ,18443,18423,18424 ,0,0,0}, - {33934,33927,33933 ,18417,18416,18415 ,0,0,0}, {33948,33933,33895 ,18443,18415,18414 ,0,0,0}, - {33890,33935,33891 ,18419,18418,18412 ,0,0,0}, {33927,33934,33890 ,18416,18417,18419 ,0,0,0}, - {31708,33932,33739 ,18353,18413,3345 ,0,0,0}, {33891,33935,33932 ,18412,18418,18413 ,0,0,0}, - {33760,33949,33887 ,18444,18444,18113 ,0,0,0}, {33760,33950,33951 ,18444,18113,18113 ,0,0,0}, - {33760,33951,33949 ,18444,18113,18444 ,0,0,0}, {33949,33888,33887 ,18444,18113,18113 ,0,0,0}, - {33838,33840,33952 ,7758,7880,7627 ,0,0,0}, {33846,33847,33953 ,726,726,7627 ,0,0,0}, - {33832,33954,33955 ,726,18445,7755 ,0,0,0}, {33956,33834,33957 ,8017,7627,7627 ,0,0,0}, - {33958,33805,33959 ,18446,7758,18447 ,0,0,0}, {33959,33828,33960 ,18447,7264,7249 ,0,0,0}, - {33961,33811,33962 ,18448,7627,18449 ,0,0,0}, {33955,33963,33829 ,7755,8018,7755 ,0,0,0}, - {33808,33964,33962 ,7761,18450,18449 ,0,0,0}, {33965,33813,33811 ,18451,726,7627 ,0,0,0}, - {33813,33965,33966 ,726,18451,726 ,0,0,0}, {33806,33958,33964 ,7755,18446,18450 ,0,0,0}, - {33967,33817,33966 ,7264,7627,726 ,0,0,0}, {33815,33968,33818 ,7758,7264,7880 ,0,0,0}, - {33969,33970,33820 ,726,7880,7627 ,0,0,0}, {33971,33848,33972 ,726,7627,726 ,0,0,0}, - {33973,33859,33860 ,726,7627,7627 ,0,0,0}, {33970,33974,33823 ,7880,7627,7880 ,0,0,0}, - {33824,33880,33975 ,7627,7627,726 ,0,0,0}, {33879,33976,33975 ,7627,7627,726 ,0,0,0}, - {33877,33977,33874 ,7625,7627,7627 ,0,0,0}, {33875,33874,33978 ,726,7627,726 ,0,0,0}, - {33858,33979,33860 ,7627,726,7627 ,0,0,0}, {33976,33879,33875 ,7627,7627,726 ,0,0,0}, - {33980,33871,33872 ,7627,726,726 ,0,0,0}, {33869,33871,33981 ,7627,726,7627 ,0,0,0}, - {33846,33953,33982 ,726,7627,726 ,0,0,0}, {33982,33983,33868 ,726,7627,7627 ,0,0,0}, - {33984,33864,33861 ,7627,726,726 ,0,0,0}, {33983,33872,33865 ,7627,726,726 ,0,0,0}, - {33984,33859,33973 ,7627,7627,726 ,0,0,0}, {33864,33985,33847 ,726,726,726 ,0,0,0}, - {33977,33869,33981 ,7627,7627,7627 ,0,0,0}, {33858,33845,33986 ,7627,7625,726 ,0,0,0}, - {33971,33844,33848 ,726,726,7627 ,0,0,0}, {33972,33848,33850 ,726,7627,726 ,0,0,0}, - {33844,33971,33986 ,726,726,726 ,0,0,0}, {33974,33882,33824 ,7627,7627,7627 ,0,0,0}, - {33987,33850,33852 ,726,726,7627 ,0,0,0}, {33850,33987,33972 ,726,726,726 ,0,0,0}, - {33841,33852,33854 ,7627,7627,7627 ,0,0,0}, {33841,33987,33852 ,7627,726,7627 ,0,0,0}, - {33854,33988,33841 ,7627,7758,7627 ,0,0,0}, {33989,33957,33835 ,7758,7627,7758 ,0,0,0}, - {33967,33990,33815 ,7264,7761,7758 ,0,0,0}, {33958,33806,33805 ,18446,7755,7758 ,0,0,0}, - {33845,33844,33986 ,7625,726,726 ,0,0,0}, {33979,33858,33986 ,726,7627,726 ,0,0,0}, - {33973,33860,33979 ,726,7627,726 ,0,0,0}, {33861,33859,33984 ,726,7627,7627 ,0,0,0}, - {33985,33864,33984 ,726,726,7627 ,0,0,0}, {33953,33847,33985 ,7627,726,726 ,0,0,0}, - {33868,33846,33982 ,7627,726,726 ,0,0,0}, {33865,33868,33983 ,726,7627,7627 ,0,0,0}, - {33980,33872,33983 ,7627,726,7627 ,0,0,0}, {33981,33871,33980 ,7627,726,7627 ,0,0,0}, - {33877,33869,33977 ,7625,7627,7627 ,0,0,0}, {33978,33874,33977 ,726,7627,7627 ,0,0,0}, - {33976,33875,33978 ,7627,726,726 ,0,0,0}, {33880,33879,33975 ,7627,7627,726 ,0,0,0}, - {33882,33880,33824 ,7627,7627,7627 ,0,0,0}, {33823,33974,33824 ,7880,7627,7627 ,0,0,0}, - {33820,33970,33823 ,7627,7880,7880 ,0,0,0}, {33968,33969,33818 ,7264,726,7880 ,0,0,0}, - {33969,33820,33818 ,726,7627,7880 ,0,0,0}, {33990,33968,33815 ,7761,7264,7758 ,0,0,0}, - {33817,33967,33815 ,7627,7264,7758 ,0,0,0}, {33813,33966,33817 ,726,726,7627 ,0,0,0}, - {33961,33965,33811 ,18448,18451,7627 ,0,0,0}, {33808,33962,33811 ,7761,18449,7627 ,0,0,0}, - {33806,33964,33808 ,7755,18450,7761 ,0,0,0}, {33959,33805,33828 ,18447,7758,7264 ,0,0,0}, - {33963,33960,33828 ,8018,7249,7264 ,0,0,0}, {33832,33955,33829 ,726,7755,7755 ,0,0,0}, - {33829,33963,33828 ,7755,8018,7264 ,0,0,0}, {33834,33954,33832 ,7627,18445,726 ,0,0,0}, - {33834,33835,33957 ,7627,7758,7627 ,0,0,0}, {33834,33956,33954 ,7627,8017,18445 ,0,0,0}, - {33835,33838,33989 ,7758,7758,7758 ,0,0,0}, {33952,33840,33988 ,7627,7880,7758 ,0,0,0}, - {33989,33838,33952 ,7758,7758,7627 ,0,0,0}, {33841,33988,33840 ,7627,7758,7880 ,0,0,0}, - {33950,33787,33991 ,1398,18452,18452 ,0,0,0}, {33928,33930,33787 ,18453,18453,18452 ,0,0,0}, - {33930,33991,33787 ,18453,18452,18452 ,0,0,0}, {33991,33951,33950 ,18452,1398,1398 ,0,0,0}, - {33992,33854,33855 ,18454,18092,18121 ,0,0,0}, {33957,33989,33886 ,18455,18456,18457 ,0,0,0}, - {33993,33952,33994 ,18458,18459,18460 ,0,0,0}, {33956,33995,33954 ,18461,18462,18463 ,0,0,0}, - {33996,33949,33958 ,18464,7309,18465 ,0,0,0}, {33997,33960,33963 ,18466,18467,18468 ,0,0,0}, - {33966,33965,33998 ,18469,18470,18471 ,0,0,0}, {33961,33962,33999 ,18472,18473,18474 ,0,0,0}, - {33967,34000,33990 ,18475,18476,18477 ,0,0,0}, {33991,33969,33968 ,18478,18479,18480 ,0,0,0}, - {33990,33991,33968 ,18477,18478,18480 ,0,0,0}, {33969,34001,33970 ,18479,18481,18482 ,0,0,0}, - {34001,33969,33991 ,18481,18479,18478 ,0,0,0}, {34001,34002,33970 ,18481,18483,18482 ,0,0,0}, - {34003,33974,34002 ,18484,18485,18483 ,0,0,0}, {33970,34002,33974 ,18482,18483,18485 ,0,0,0}, - {34003,33884,33882 ,18484,18486,82 ,0,0,0}, {33882,33974,34003 ,82,18485,18484 ,0,0,0}, - {33998,34000,33967 ,18471,18476,18475 ,0,0,0}, {33990,34000,33991 ,18477,18476,18478 ,0,0,0}, - {33965,34004,33998 ,18470,18487,18471 ,0,0,0}, {33967,33966,33998 ,18475,18469,18471 ,0,0,0}, - {33999,34004,33961 ,18474,18487,18472 ,0,0,0}, {33965,33961,34004 ,18470,18472,18487 ,0,0,0}, - {33999,33964,33949 ,18474,18488,7309 ,0,0,0}, {33962,33964,33999 ,18473,18488,18474 ,0,0,0}, - {33996,33958,33959 ,18464,18465,18489 ,0,0,0}, {33949,33964,33958 ,7309,18488,18465 ,0,0,0}, - {33960,33997,33996 ,18467,18466,18464 ,0,0,0}, {33996,33959,33960 ,18464,18489,18467 ,0,0,0}, - {33955,34005,33963 ,18490,18491,18468 ,0,0,0}, {34005,33997,33963 ,18491,18466,18468 ,0,0,0}, - {34005,33954,33995 ,18491,18463,18462 ,0,0,0}, {33954,34005,33955 ,18463,18491,18490 ,0,0,0}, - {33956,33957,33886 ,18461,18455,18457 ,0,0,0}, {33956,33886,33995 ,18461,18457,18462 ,0,0,0}, - {33989,33952,33993 ,18456,18459,18458 ,0,0,0}, {33989,33993,33886 ,18456,18458,18457 ,0,0,0}, - {33994,33988,33992 ,18460,18492,18454 ,0,0,0}, {33952,33988,33994 ,18459,18492,18460 ,0,0,0}, - {33854,33992,33988 ,18092,18454,18492 ,0,0,0}, {33878,33930,33881 ,7792,726,7658 ,0,0,0}, - {33930,33873,33881 ,726,726,7658 ,0,0,0}, {33884,33930,33883 ,7664,726,7662 ,0,0,0}, - {33930,33878,33883 ,726,7792,7662 ,0,0,0}, {34002,33930,34003 ,7662,726,5488 ,0,0,0}, - {33930,33884,34003 ,726,7664,5488 ,0,0,0}, {33991,33930,34001 ,726,726,726 ,0,0,0}, - {33930,34002,34001 ,726,7662,726 ,0,0,0}, {34005,33888,33997 ,726,726,17470 ,0,0,0}, - {33997,33888,33996 ,17470,726,7628 ,0,0,0}, {33888,33949,33996 ,726,726,7628 ,0,0,0}, - {33888,33995,33886 ,726,726,726 ,0,0,0}, {33888,34005,33995 ,726,726,726 ,0,0,0}, - {33856,33803,33843 ,726,726,726 ,0,0,0}, {33862,33803,33857 ,7661,726,7659 ,0,0,0}, - {33803,33856,33857 ,726,726,7659 ,0,0,0}, {33799,33803,33863 ,7661,726,7661 ,0,0,0}, - {33803,33862,33863 ,726,7661,7661 ,0,0,0}, {33804,33867,33866 ,7660,7660,7660 ,0,0,0}, - {33799,33867,33804 ,726,7660,7660 ,0,0,0}, {33804,33876,33873 ,7660,726,726 ,0,0,0}, - {33804,33870,33876 ,7660,7658,726 ,0,0,0}, {33866,33870,33804 ,7660,7658,7660 ,0,0,0}, - {33991,34000,33951 ,726,726,726 ,0,0,0}, {34004,33951,33998 ,726,726,7661 ,0,0,0}, - {34000,33998,33951 ,726,7661,726 ,0,0,0}, {33999,33949,33951 ,726,726,726 ,0,0,0}, - {33999,33951,34004 ,726,726,726 ,0,0,0}, {33993,33889,33886 ,726,726,726 ,0,0,0}, - {33992,33889,33994 ,726,726,726 ,0,0,0}, {33889,33993,33994 ,726,726,726 ,0,0,0}, - {33853,33889,33855 ,726,726,726 ,0,0,0}, {33889,33992,33855 ,726,726,726 ,0,0,0}, - {33849,33889,33851 ,726,726,7660 ,0,0,0}, {33889,33853,33851 ,726,726,7660 ,0,0,0}, - {33843,33889,33849 ,726,726,726 ,0,0,0}, {33839,33837,34006 ,726,726,7583 ,0,0,0}, - {34007,34008,34009 ,726,726,726 ,0,0,0}, {34010,34007,33842 ,726,726,726 ,0,0,0}, - {34006,34011,33839 ,7583,7583,726 ,0,0,0}, {34012,34013,34009 ,726,726,726 ,0,0,0}, - {34014,34015,34008 ,726,726,726 ,0,0,0}, {34012,34009,34015 ,726,726,726 ,0,0,0}, - {34008,34015,34009 ,726,726,726 ,0,0,0}, {34009,34016,34007 ,726,726,726 ,0,0,0}, - {33839,34010,33842 ,726,726,726 ,0,0,0}, {33842,34007,34016 ,726,726,726 ,0,0,0}, - {34006,33837,33836 ,7583,726,726 ,0,0,0}, {33839,34011,34010 ,726,7583,726 ,0,0,0}, - {34017,33836,33833 ,7583,726,726 ,0,0,0}, {33836,34017,34006 ,726,7583,7583 ,0,0,0}, - {33833,34018,34019 ,726,726,726 ,0,0,0}, {34017,33833,34019 ,7583,726,726 ,0,0,0}, - {33831,34018,33833 ,726,726,726 ,0,0,0}, {34018,33830,34020 ,726,726,726 ,0,0,0}, - {33830,34018,33831 ,726,726,726 ,0,0,0}, {33830,33827,34020 ,726,726,726 ,0,0,0}, - {34021,33827,34022 ,726,726,5489 ,0,0,0}, {34021,34020,33827 ,726,726,726 ,0,0,0}, - {34022,33826,33807 ,5489,7583,726 ,0,0,0}, {33827,33826,34022 ,726,7583,5489 ,0,0,0}, - {33810,33825,33807 ,7583,7583,726 ,0,0,0}, {34022,33807,33825 ,5489,726,7583 ,0,0,0}, - {33814,33821,33809 ,7583,7583,726 ,0,0,0}, {33809,33812,33814 ,726,726,7583 ,0,0,0}, - {33821,33816,33819 ,7583,7583,726 ,0,0,0}, {33821,33810,33809 ,7583,7583,726 ,0,0,0}, - {33821,33822,33810 ,7583,5489,7583 ,0,0,0}, {33821,33814,33816 ,7583,7583,7583 ,0,0,0}, - {33810,33822,33825 ,7583,5489,7583 ,0,0,0}, {33824,33975,34022 ,35,18493,18494 ,0,0,0}, - {33977,34018,33978 ,18495,18496,18497 ,0,0,0}, {34020,34021,33976 ,18498,18499,18500 ,0,0,0}, - {34006,33983,34011 ,18501,18502,18503 ,0,0,0}, {33981,33980,34017 ,18504,18505,18506 ,0,0,0}, - {33985,34008,34007 ,18507,18508,18509 ,0,0,0}, {34007,34010,33953 ,18509,18510,18511 ,0,0,0}, - {33979,34015,33973 ,18512,18513,18514 ,0,0,0}, {34014,33984,33973 ,18515,18516,18514 ,0,0,0}, - {33986,34013,34012 ,18517,18518,18519 ,0,0,0}, {34012,33979,33986 ,18519,18512,18517 ,0,0,0}, - {34013,33971,34009 ,18518,18520,18521 ,0,0,0}, {33971,34013,33986 ,18520,18518,18517 ,0,0,0}, - {34016,34009,33972 ,18522,18521,18523 ,0,0,0}, {33971,33972,34009 ,18520,18523,18521 ,0,0,0}, - {33987,33842,34016 ,18524,18188,18522 ,0,0,0}, {34016,33972,33987 ,18522,18523,18524 ,0,0,0}, - {33841,33842,33987 ,18188,18188,18524 ,0,0,0}, {34012,34015,33979 ,18519,18513,18512 ,0,0,0}, - {34014,33973,34015 ,18515,18514,18513 ,0,0,0}, {34014,34008,33984 ,18515,18508,18516 ,0,0,0}, - {34011,33982,34010 ,18503,18525,18510 ,0,0,0}, {33985,34007,33953 ,18507,18509,18511 ,0,0,0}, - {33984,34008,33985 ,18516,18508,18507 ,0,0,0}, {34010,33982,33953 ,18510,18525,18511 ,0,0,0}, - {33982,34011,33983 ,18525,18503,18502 ,0,0,0}, {34017,33980,34006 ,18506,18505,18501 ,0,0,0}, - {33980,33983,34006 ,18505,18502,18501 ,0,0,0}, {33981,34019,33977 ,18504,18526,18495 ,0,0,0}, - {34019,33981,34017 ,18526,18504,18506 ,0,0,0}, {34020,33978,34018 ,18498,18497,18496 ,0,0,0}, - {34019,34018,33977 ,18526,18496,18495 ,0,0,0}, {33976,34021,33975 ,18500,18499,18493 ,0,0,0}, - {33978,34020,33976 ,18497,18498,18500 ,0,0,0}, {33824,34022,33825 ,35,18494,763 ,0,0,0}, - {33975,34021,34022 ,18493,18499,18494 ,0,0,0}, {34023,33768,33769 ,18527,126,18026 ,0,0,0}, - {33908,33909,33931 ,18528,18529,18530 ,0,0,0}, {34024,33910,34025 ,18531,18532,18533 ,0,0,0}, - {33911,34026,33892 ,18534,18535,18536 ,0,0,0}, {34027,33801,33914 ,18537,10001,18538 ,0,0,0}, - {34028,33916,33912 ,18539,18540,18541 ,0,0,0}, {33919,33920,34029 ,18542,18543,18544 ,0,0,0}, - {33918,33917,34030 ,18545,18546,18547 ,0,0,0}, {33921,34031,33923 ,18548,18549,18550 ,0,0,0}, - {33929,33922,33924 ,18551,18552,18553 ,0,0,0}, {33923,33929,33924 ,18550,18551,18553 ,0,0,0}, - {33922,34032,33925 ,18552,18554,18555 ,0,0,0}, {34032,33922,33929 ,18554,18552,18551 ,0,0,0}, - {34032,34033,33925 ,18554,18556,18555 ,0,0,0}, {34034,33926,34033 ,18557,18558,18556 ,0,0,0}, - {33925,34033,33926 ,18555,18556,18558 ,0,0,0}, {34034,33798,33796 ,18557,5000,18205 ,0,0,0}, - {33796,33926,34034 ,18205,18558,18557 ,0,0,0}, {34029,34031,33921 ,18544,18549,18548 ,0,0,0}, - {33923,34031,33929 ,18550,18549,18551 ,0,0,0}, {33920,34035,34029 ,18543,18559,18544 ,0,0,0}, - {33921,33919,34029 ,18548,18542,18544 ,0,0,0}, {34030,34035,33918 ,18547,18559,18545 ,0,0,0}, - {33920,33918,34035 ,18543,18545,18559 ,0,0,0}, {34030,33915,33801 ,18547,18560,10001 ,0,0,0}, - {33917,33915,34030 ,18546,18560,18547 ,0,0,0}, {34027,33914,33913 ,18537,18538,18561 ,0,0,0}, - {33801,33915,33914 ,10001,18560,18538 ,0,0,0}, {33916,34028,34027 ,18540,18539,18537 ,0,0,0}, - {34027,33913,33916 ,18537,18561,18540 ,0,0,0}, {33893,34036,33912 ,18562,18563,18541 ,0,0,0}, - {34036,34028,33912 ,18563,18539,18541 ,0,0,0}, {34036,33892,34026 ,18563,18536,18535 ,0,0,0}, - {33892,34036,33893 ,18536,18563,18562 ,0,0,0}, {33911,33908,33931 ,18534,18528,18530 ,0,0,0}, - {33911,33931,34026 ,18534,18530,18535 ,0,0,0}, {33909,33910,34024 ,18529,18532,18531 ,0,0,0}, - {33909,34024,33931 ,18529,18531,18530 ,0,0,0}, {34025,33907,34023 ,18533,18564,18527 ,0,0,0}, - {33910,33907,34025 ,18532,18564,18533 ,0,0,0}, {33768,34023,33907 ,126,18527,18564 ,0,0,0}, - {33802,34036,34026 ,17561,17561,730 ,0,0,0}, {34027,33802,33801 ,730,17561,730 ,0,0,0}, - {34036,33802,34028 ,17561,17561,730 ,0,0,0}, {33802,34027,34028 ,17561,730,730 ,0,0,0}, - {34026,33931,33802 ,730,7376,17561 ,0,0,0}, {33795,33928,33787 ,18207,730,730 ,0,0,0}, - {33928,34034,34033 ,730,730,730 ,0,0,0}, {33797,33928,33792 ,17561,730,7433 ,0,0,0}, - {33928,33795,33792 ,730,18207,7433 ,0,0,0}, {34034,33928,33798 ,730,730,17561 ,0,0,0}, - {33928,33797,33798 ,730,17561,17561 ,0,0,0}, {34033,34032,33928 ,730,7433,730 ,0,0,0}, - {34032,33929,33928 ,7433,730,730 ,0,0,0}, {33771,33887,33770 ,7017,730,730 ,0,0,0}, - {33887,33756,33770 ,730,11465,730 ,0,0,0}, {33777,33887,33776 ,18565,730,730 ,0,0,0}, - {33887,33771,33776 ,730,7017,730 ,0,0,0}, {33760,33887,33777 ,18566,730,18565 ,0,0,0}, - {34035,33800,34029 ,730,7376,17561 ,0,0,0}, {34031,34029,33800 ,730,17561,7376 ,0,0,0}, - {33929,34031,33800 ,730,730,7376 ,0,0,0}, {34030,33801,33800 ,7376,730,7376 ,0,0,0}, - {34030,33800,34035 ,7376,7376,730 ,0,0,0}, {33781,33780,33950 ,18207,18207,9877 ,0,0,0}, - {33760,33781,33950 ,18567,18207,9877 ,0,0,0}, {33784,33790,33950 ,730,9878,9877 ,0,0,0}, - {33784,33950,33780 ,730,9877,18207 ,0,0,0}, {33787,33950,33790 ,730,9877,9878 ,0,0,0}, - {33931,34024,33885 ,730,730,730 ,0,0,0}, {33885,34023,33769 ,730,730,9877 ,0,0,0}, - {34023,33885,34025 ,730,730,730 ,0,0,0}, {33885,34024,34025 ,730,730,730 ,0,0,0}, - {33769,33767,33885 ,9877,730,730 ,0,0,0}, {33885,33765,33763 ,730,9878,730 ,0,0,0}, - {33767,33765,33885 ,730,9878,730 ,0,0,0}, {33763,33756,33885 ,730,730,730 ,0,0,0}, - {33932,33935,33741 ,730,730,9878 ,0,0,0}, {33725,33724,33736 ,730,730,730 ,0,0,0}, - {33722,33725,33739 ,9875,730,730 ,0,0,0}, {33741,33740,33932 ,9878,730,730 ,0,0,0}, - {33731,33734,33736 ,730,730,730 ,0,0,0}, {33727,33729,33724 ,730,730,730 ,0,0,0}, - {33731,33736,33729 ,730,730,730 ,0,0,0}, {33724,33729,33736 ,730,730,730 ,0,0,0}, - {33736,33737,33725 ,730,730,730 ,0,0,0}, {33932,33722,33739 ,730,9875,730 ,0,0,0}, - {33739,33725,33737 ,730,730,730 ,0,0,0}, {33741,33935,33934 ,9878,730,730 ,0,0,0}, - {33932,33740,33722 ,730,730,9875 ,0,0,0}, {33744,33934,33933 ,9878,730,730 ,0,0,0}, - {33934,33744,33741 ,730,9878,9878 ,0,0,0}, {33933,33747,33745 ,730,730,730 ,0,0,0}, - {33744,33933,33745 ,9878,730,730 ,0,0,0}, {33948,33747,33933 ,730,730,730 ,0,0,0}, - {33747,33938,33750 ,730,9875,9878 ,0,0,0}, {33938,33747,33948 ,9875,730,730 ,0,0,0}, - {33938,33936,33750 ,9875,730,9878 ,0,0,0}, {33751,33936,33753 ,9878,730,730 ,0,0,0}, - {33751,33750,33936 ,9878,9878,730 ,0,0,0}, {33753,33937,33941 ,730,9875,9875 ,0,0,0}, - {33936,33937,33753 ,730,9875,730 ,0,0,0}, {33940,33755,33941 ,730,9878,9875 ,0,0,0}, - {33753,33941,33755 ,730,9875,9878 ,0,0,0}, {33942,33946,33939 ,9878,9878,730 ,0,0,0}, - {33939,33943,33942 ,730,9878,9878 ,0,0,0}, {33946,33945,33944 ,9878,9878,9877 ,0,0,0}, - {33946,33940,33939 ,9878,730,730 ,0,0,0}, {33946,33947,33940 ,9878,730,730 ,0,0,0}, - {33946,33942,33945 ,9878,9878,9878 ,0,0,0}, {33940,33947,33755 ,730,730,9878 ,0,0,0} -// Airframe2.prt - , {34037,34038,34039 ,18568,18569,18569 ,0,0,0}, {34040,34041,34042 ,18570,18571,18572 ,0,0,0}, - {34039,34038,34042 ,18569,18569,18572 ,0,0,0}, {34043,34044,34045 ,18573,18573,18571 ,0,0,0}, - {34041,34040,34045 ,18571,18570,18571 ,0,0,0}, {34045,34044,34041 ,18571,18573,18571 ,0,0,0}, - {34040,34042,34038 ,18570,18572,18569 ,0,0,0}, {34039,34046,34037 ,18569,18568,18568 ,0,0,0}, - {34046,34047,34048 ,18568,18574,18574 ,0,0,0}, {34048,34037,34046 ,18574,18568,18568 ,0,0,0}, - {34049,34047,34050 ,18575,18574,18575 ,0,0,0}, {34047,34049,34048 ,18574,18575,18574 ,0,0,0}, - {34051,34052,34053 ,18576,18577,18577 ,0,0,0}, {34054,34055,34056 ,18578,18579,18580 ,0,0,0}, - {34053,34052,34056 ,18577,18577,18580 ,0,0,0}, {34057,34058,34059 ,18581,18581,18579 ,0,0,0}, - {34055,34054,34059 ,18579,18578,18579 ,0,0,0}, {34059,34058,34055 ,18579,18581,18579 ,0,0,0}, - {34054,34056,34052 ,18578,18580,18577 ,0,0,0}, {34053,34060,34051 ,18577,18576,18576 ,0,0,0}, - {34060,34061,34062 ,18576,18582,18582 ,0,0,0}, {34062,34051,34060 ,18582,18576,18576 ,0,0,0}, - {34063,34061,34064 ,18583,18582,18583 ,0,0,0}, {34061,34063,34062 ,18582,18583,18582 ,0,0,0}, - {34065,34066,34067 ,18584,18585,18585 ,0,0,0}, {34068,34069,34070 ,18586,18587,18586 ,0,0,0}, - {34067,34066,34070 ,18585,18585,18586 ,0,0,0}, {34071,34072,34073 ,18588,18588,18587 ,0,0,0}, - {34069,34068,34073 ,18587,18586,18587 ,0,0,0}, {34073,34072,34069 ,18587,18588,18587 ,0,0,0}, - {34068,34070,34066 ,18586,18586,18585 ,0,0,0}, {34067,34074,34065 ,18585,18584,18584 ,0,0,0}, - {34074,34075,34076 ,18584,18589,18589 ,0,0,0}, {34076,34065,34074 ,18589,18584,18584 ,0,0,0}, - {34077,34075,34078 ,18573,18589,18573 ,0,0,0}, {34075,34077,34076 ,18589,18573,18589 ,0,0,0}, - {34079,34080,34081 ,18590,18591,18591 ,0,0,0}, {34082,34083,34084 ,18592,18593,18592 ,0,0,0}, - {34081,34080,34084 ,18591,18591,18592 ,0,0,0}, {34085,34086,34087 ,18594,18594,18593 ,0,0,0}, - {34083,34082,34087 ,18593,18592,18593 ,0,0,0}, {34087,34086,34083 ,18593,18594,18593 ,0,0,0}, - {34082,34084,34080 ,18592,18592,18591 ,0,0,0}, {34081,34088,34079 ,18591,18590,18590 ,0,0,0}, - {34088,34089,34090 ,18590,18595,18595 ,0,0,0}, {34090,34079,34088 ,18595,18590,18590 ,0,0,0}, - {34091,34089,34092 ,18581,18595,18581 ,0,0,0}, {34089,34091,34090 ,18595,18581,18595 ,0,0,0}, - {34093,34094,34095 ,18596,18597,18597 ,0,0,0}, {34096,34097,34098 ,18598,18599,18600 ,0,0,0}, - {34095,34094,34098 ,18597,18597,18600 ,0,0,0}, {34099,34100,34101 ,18601,18601,18599 ,0,0,0}, - {34097,34096,34101 ,18599,18598,18599 ,0,0,0}, {34101,34100,34097 ,18599,18601,18599 ,0,0,0}, - {34096,34098,34094 ,18598,18600,18597 ,0,0,0}, {34095,34102,34093 ,18597,18596,18596 ,0,0,0}, - {34102,34103,34104 ,18596,18602,18602 ,0,0,0}, {34104,34093,34102 ,18602,18596,18596 ,0,0,0}, - {34105,34103,34106 ,18588,18602,18588 ,0,0,0}, {34103,34105,34104 ,18602,18588,18602 ,0,0,0}, - {34107,34108,34109 ,18603,18604,18605 ,0,0,0}, {34110,34111,34112 ,18606,18607,18608 ,0,0,0}, - {34109,34108,34112 ,18605,18604,18608 ,0,0,0}, {34113,34114,34115 ,18609,18609,18607 ,0,0,0}, - {34111,34110,34115 ,18607,18606,18607 ,0,0,0}, {34115,34114,34111 ,18607,18609,18607 ,0,0,0}, - {34110,34112,34108 ,18606,18608,18604 ,0,0,0}, {34109,34116,34107 ,18605,18603,18603 ,0,0,0}, - {34116,34117,34118 ,18603,18610,18610 ,0,0,0}, {34118,34107,34116 ,18610,18603,18603 ,0,0,0}, - {34119,34117,34120 ,18594,18610,18594 ,0,0,0}, {34117,34119,34118 ,18610,18594,18610 ,0,0,0}, - {34121,34122,34123 ,18611,18612,18612 ,0,0,0}, {34124,34125,34126 ,18613,18614,18613 ,0,0,0}, - {34123,34122,34126 ,18612,18612,18613 ,0,0,0}, {34127,34128,34129 ,18588,18588,18614 ,0,0,0}, - {34125,34124,34129 ,18614,18613,18614 ,0,0,0}, {34129,34128,34125 ,18614,18588,18614 ,0,0,0}, - {34124,34126,34122 ,18613,18613,18612 ,0,0,0}, {34123,34130,34121 ,18612,18611,18611 ,0,0,0}, - {34130,34131,34132 ,18611,18615,18615 ,0,0,0}, {34132,34121,34130 ,18615,18611,18611 ,0,0,0}, - {34133,34131,34134 ,18573,18615,18573 ,0,0,0}, {34131,34133,34132 ,18615,18573,18615 ,0,0,0}, - {34135,34136,34137 ,18616,18617,18617 ,0,0,0}, {34138,34139,34140 ,18618,18619,18618 ,0,0,0}, - {34137,34136,34140 ,18617,18617,18618 ,0,0,0}, {34141,34142,34143 ,18594,18594,18619 ,0,0,0}, - {34139,34138,34143 ,18619,18618,18619 ,0,0,0}, {34143,34142,34139 ,18619,18594,18619 ,0,0,0}, - {34138,34140,34136 ,18618,18618,18617 ,0,0,0}, {34137,34144,34135 ,18617,18616,18616 ,0,0,0}, - {34144,34145,34146 ,18616,18620,18620 ,0,0,0}, {34146,34135,34144 ,18620,18616,18616 ,0,0,0}, - {34147,34145,34148 ,18581,18620,18581 ,0,0,0}, {34145,34147,34146 ,18620,18581,18620 ,0,0,0}, - {34149,34150,34151 ,18621,18622,18622 ,0,0,0}, {34152,34153,34154 ,18623,18624,18623 ,0,0,0}, - {34151,34150,34154 ,18622,18622,18623 ,0,0,0}, {34155,34156,34157 ,18601,18601,18624 ,0,0,0}, - {34153,34152,34157 ,18624,18623,18624 ,0,0,0}, {34157,34156,34153 ,18624,18601,18624 ,0,0,0}, - {34152,34154,34150 ,18623,18623,18622 ,0,0,0}, {34151,34158,34149 ,18622,18621,18621 ,0,0,0}, - {34158,34159,34160 ,18621,18625,18625 ,0,0,0}, {34160,34149,34158 ,18625,18621,18621 ,0,0,0}, - {34161,34159,34162 ,18588,18625,18588 ,0,0,0}, {34159,34161,34160 ,18625,18588,18625 ,0,0,0}, - {34163,34164,34165 ,18626,18627,18627 ,0,0,0}, {34166,34167,34168 ,18628,18629,18628 ,0,0,0}, - {34165,34164,34168 ,18627,18627,18628 ,0,0,0}, {34169,34170,34171 ,18609,18609,18629 ,0,0,0}, - {34167,34166,34171 ,18629,18628,18629 ,0,0,0}, {34171,34170,34167 ,18629,18609,18629 ,0,0,0}, - {34166,34168,34164 ,18628,18628,18627 ,0,0,0}, {34165,34172,34163 ,18627,18626,18626 ,0,0,0}, - {34172,34173,34174 ,18626,18630,18630 ,0,0,0}, {34174,34163,34172 ,18630,18626,18626 ,0,0,0}, - {34175,34173,34176 ,18594,18630,18594 ,0,0,0}, {34173,34175,34174 ,18630,18594,18630 ,0,0,0}, - {34177,34178,34179 ,18631,18632,18632 ,0,0,0}, {34180,34181,34182 ,18633,18634,18633 ,0,0,0}, - {34179,34178,34182 ,18632,18632,18633 ,0,0,0}, {34183,34184,34185 ,18575,18575,18634 ,0,0,0}, - {34181,34180,34185 ,18634,18633,18634 ,0,0,0}, {34185,34184,34181 ,18634,18575,18634 ,0,0,0}, - {34180,34182,34178 ,18633,18633,18632 ,0,0,0}, {34179,34186,34177 ,18632,18631,18631 ,0,0,0}, - {34186,34187,34188 ,18631,18635,18635 ,0,0,0}, {34188,34177,34186 ,18635,18631,18631 ,0,0,0}, - {34189,34187,34190 ,18601,18635,18601 ,0,0,0}, {34187,34189,34188 ,18635,18601,18635 ,0,0,0}, - {34191,34192,34193 ,18636,18637,18637 ,0,0,0}, {34194,34195,34196 ,18638,18639,18638 ,0,0,0}, - {34193,34192,34196 ,18637,18637,18638 ,0,0,0}, {34197,34198,34199 ,18583,18583,18639 ,0,0,0}, - {34195,34194,34199 ,18639,18638,18639 ,0,0,0}, {34199,34198,34195 ,18639,18583,18639 ,0,0,0}, - {34194,34196,34192 ,18638,18638,18637 ,0,0,0}, {34193,34200,34191 ,18637,18636,18636 ,0,0,0}, - {34200,34201,34202 ,18636,18640,18640 ,0,0,0}, {34202,34191,34200 ,18640,18636,18636 ,0,0,0}, - {34203,34201,34204 ,18609,18640,18609 ,0,0,0}, {34201,34203,34202 ,18640,18609,18640 ,0,0,0}, - {34205,34206,34207 ,18641,18642,18642 ,0,0,0}, {34208,34209,34210 ,18643,18644,18645 ,0,0,0}, - {34207,34206,34210 ,18642,18642,18645 ,0,0,0}, {34211,34212,34213 ,18601,18601,18644 ,0,0,0}, - {34209,34208,34213 ,18644,18643,18644 ,0,0,0}, {34213,34212,34209 ,18644,18601,18644 ,0,0,0}, - {34208,34210,34206 ,18643,18645,18642 ,0,0,0}, {34207,34214,34205 ,18642,18641,18641 ,0,0,0}, - {34214,34215,34216 ,18641,18646,18646 ,0,0,0}, {34216,34205,34214 ,18646,18641,18641 ,0,0,0}, - {34217,34215,34218 ,18588,18646,18588 ,0,0,0}, {34215,34217,34216 ,18646,18588,18646 ,0,0,0}, - {34219,34220,34221 ,18647,18648,18649 ,0,0,0}, {34222,34223,34224 ,18650,18651,18652 ,0,0,0}, - {34221,34220,34224 ,18649,18648,18652 ,0,0,0}, {34225,34226,34227 ,18609,18609,18651 ,0,0,0}, - {34223,34222,34227 ,18651,18650,18651 ,0,0,0}, {34227,34226,34223 ,18651,18609,18651 ,0,0,0}, - {34222,34224,34220 ,18650,18652,18648 ,0,0,0}, {34221,34228,34219 ,18649,18647,18647 ,0,0,0}, - {34228,34229,34230 ,18647,18653,18653 ,0,0,0}, {34230,34219,34228 ,18653,18647,18647 ,0,0,0}, - {34231,34229,34232 ,18594,18653,18594 ,0,0,0}, {34229,34231,34230 ,18653,18594,18653 ,0,0,0}, - {34233,34234,34235 ,18654,18655,18655 ,0,0,0}, {34236,34237,34238 ,18656,18657,18658 ,0,0,0}, - {34235,34234,34238 ,18655,18655,18658 ,0,0,0}, {34239,34240,34241 ,18575,18575,18657 ,0,0,0}, - {34237,34236,34241 ,18657,18656,18657 ,0,0,0}, {34241,34240,34237 ,18657,18575,18657 ,0,0,0}, - {34236,34238,34234 ,18656,18658,18655 ,0,0,0}, {34235,34242,34233 ,18655,18654,18654 ,0,0,0}, - {34242,34243,34244 ,18654,18659,18659 ,0,0,0}, {34244,34233,34242 ,18659,18654,18654 ,0,0,0}, - {34245,34243,34246 ,18601,18659,18601 ,0,0,0}, {34243,34245,34244 ,18659,18601,18659 ,0,0,0}, - {34247,34248,34249 ,18660,18661,18661 ,0,0,0}, {34250,34251,34252 ,18662,18663,18662 ,0,0,0}, - {34249,34248,34252 ,18661,18661,18662 ,0,0,0}, {34253,34254,34255 ,18583,18583,18663 ,0,0,0}, - {34251,34250,34255 ,18663,18662,18663 ,0,0,0}, {34255,34254,34251 ,18663,18583,18663 ,0,0,0}, - {34250,34252,34248 ,18662,18662,18661 ,0,0,0}, {34249,34256,34247 ,18661,18660,18660 ,0,0,0}, - {34256,34257,34258 ,18660,18664,18664 ,0,0,0}, {34258,34247,34256 ,18664,18660,18660 ,0,0,0}, - {34259,34257,34260 ,18609,18664,18609 ,0,0,0}, {34257,34259,34258 ,18664,18609,18664 ,0,0,0}, - {34261,34262,34263 ,18665,18666,18666 ,0,0,0}, {34264,34265,34266 ,18667,18668,18667 ,0,0,0}, - {34263,34262,34266 ,18666,18666,18667 ,0,0,0}, {34267,34268,34269 ,18573,18573,18668 ,0,0,0}, - {34265,34264,34269 ,18668,18667,18668 ,0,0,0}, {34269,34268,34265 ,18668,18573,18668 ,0,0,0}, - {34264,34266,34262 ,18667,18667,18666 ,0,0,0}, {34263,34270,34261 ,18666,18665,18665 ,0,0,0}, - {34270,34271,34272 ,18665,18669,18669 ,0,0,0}, {34272,34261,34270 ,18669,18665,18665 ,0,0,0}, - {34273,34271,34274 ,18575,18669,18575 ,0,0,0}, {34271,34273,34272 ,18669,18575,18669 ,0,0,0}, - {34275,34276,34277 ,18670,18671,18671 ,0,0,0}, {34278,34279,34280 ,18672,18673,18672 ,0,0,0}, - {34277,34276,34280 ,18671,18671,18672 ,0,0,0}, {34281,34282,34283 ,18581,18581,18673 ,0,0,0}, - {34279,34278,34283 ,18673,18672,18673 ,0,0,0}, {34283,34282,34279 ,18673,18581,18673 ,0,0,0}, - {34278,34280,34276 ,18672,18672,18671 ,0,0,0}, {34277,34284,34275 ,18671,18670,18670 ,0,0,0}, - {34284,34285,34286 ,18670,18582,18582 ,0,0,0}, {34286,34275,34284 ,18582,18670,18670 ,0,0,0}, - {34287,34285,34288 ,18583,18582,18583 ,0,0,0}, {34285,34287,34286 ,18582,18583,18582 ,0,0,0}, - {34289,34290,34291 ,18674,18675,18675 ,0,0,0}, {34292,34293,34294 ,18676,18677,18676 ,0,0,0}, - {34291,34290,34294 ,18675,18675,18676 ,0,0,0}, {34295,34296,34297 ,18575,18575,18677 ,0,0,0}, - {34293,34292,34297 ,18677,18676,18677 ,0,0,0}, {34297,34296,34293 ,18677,18575,18677 ,0,0,0}, - {34292,34294,34290 ,18676,18676,18675 ,0,0,0}, {34291,34298,34289 ,18675,18674,18674 ,0,0,0}, - {34298,34299,34300 ,18674,18678,18678 ,0,0,0}, {34300,34289,34298 ,18678,18674,18674 ,0,0,0}, - {34301,34299,34302 ,18601,18678,18601 ,0,0,0}, {34299,34301,34300 ,18678,18601,18678 ,0,0,0}, - {34303,34304,34305 ,18679,18680,18680 ,0,0,0}, {34306,34307,34308 ,18681,18682,18681 ,0,0,0}, - {34305,34304,34308 ,18680,18680,18681 ,0,0,0}, {34309,34310,34311 ,18583,18583,18682 ,0,0,0}, - {34307,34306,34311 ,18682,18681,18682 ,0,0,0}, {34311,34310,34307 ,18682,18583,18682 ,0,0,0}, - {34306,34308,34304 ,18681,18681,18680 ,0,0,0}, {34305,34312,34303 ,18680,18679,18679 ,0,0,0}, - {34312,34313,34314 ,18679,18683,18683 ,0,0,0}, {34314,34303,34312 ,18683,18679,18679 ,0,0,0}, - {34315,34313,34316 ,18609,18683,18609 ,0,0,0}, {34313,34315,34314 ,18683,18609,18683 ,0,0,0}, - {34317,34318,34319 ,18684,18685,18685 ,0,0,0}, {34320,34321,34322 ,18686,18687,18686 ,0,0,0}, - {34319,34318,34322 ,18685,18685,18686 ,0,0,0}, {34323,34324,34325 ,18573,18573,18687 ,0,0,0}, - {34321,34320,34325 ,18687,18686,18687 ,0,0,0}, {34325,34324,34321 ,18687,18573,18687 ,0,0,0}, - {34320,34322,34318 ,18686,18686,18685 ,0,0,0}, {34319,34326,34317 ,18685,18684,18684 ,0,0,0}, - {34326,34327,34328 ,18684,18688,18688 ,0,0,0}, {34328,34317,34326 ,18688,18684,18684 ,0,0,0}, - {34329,34327,34330 ,18575,18688,18575 ,0,0,0}, {34327,34329,34328 ,18688,18575,18688 ,0,0,0}, - {34331,34332,34333 ,18689,18690,18690 ,0,0,0}, {34334,34335,34336 ,18691,18692,18691 ,0,0,0}, - {34333,34332,34336 ,18690,18690,18691 ,0,0,0}, {34337,34338,34339 ,18581,18581,18692 ,0,0,0}, - {34335,34334,34339 ,18692,18691,18692 ,0,0,0}, {34339,34338,34335 ,18692,18581,18692 ,0,0,0}, - {34334,34336,34332 ,18691,18691,18690 ,0,0,0}, {34333,34340,34331 ,18690,18689,18689 ,0,0,0}, - {34340,34341,34342 ,18689,18693,18693 ,0,0,0}, {34342,34331,34340 ,18693,18689,18689 ,0,0,0}, - {34343,34341,34344 ,18583,18693,18583 ,0,0,0}, {34341,34343,34342 ,18693,18583,18693 ,0,0,0}, - {34345,34346,34347 ,18694,18695,18695 ,0,0,0}, {34348,34349,34350 ,18696,18697,18696 ,0,0,0}, - {34347,34346,34350 ,18695,18695,18696 ,0,0,0}, {34351,34352,34353 ,18588,18588,18697 ,0,0,0}, - {34349,34348,34353 ,18697,18696,18697 ,0,0,0}, {34353,34352,34349 ,18697,18588,18697 ,0,0,0}, - {34348,34350,34346 ,18696,18696,18695 ,0,0,0}, {34347,34354,34345 ,18695,18694,18694 ,0,0,0}, - {34354,34355,34356 ,18694,18615,18615 ,0,0,0}, {34356,34345,34354 ,18615,18694,18694 ,0,0,0}, - {34357,34355,34358 ,18573,18615,18573 ,0,0,0}, {34355,34357,34356 ,18615,18573,18615 ,0,0,0}, - {34359,34360,34361 ,18698,18699,18699 ,0,0,0}, {34362,34363,34364 ,18700,18701,18700 ,0,0,0}, - {34361,34360,34364 ,18699,18699,18700 ,0,0,0}, {34365,34366,34367 ,18594,18594,18701 ,0,0,0}, - {34363,34362,34367 ,18701,18700,18701 ,0,0,0}, {34367,34366,34363 ,18701,18594,18701 ,0,0,0}, - {34362,34364,34360 ,18700,18700,18699 ,0,0,0}, {34361,34368,34359 ,18699,18698,18698 ,0,0,0}, - {34368,34369,34370 ,18698,18702,18702 ,0,0,0}, {34370,34359,34368 ,18702,18698,18698 ,0,0,0}, - {34371,34369,34372 ,18581,18702,18581 ,0,0,0}, {34369,34371,34370 ,18702,18581,18702 ,0,0,0}, - {34373,34374,34375 ,18703,18704,18704 ,0,0,0}, {34376,34377,34378 ,18705,18706,18707 ,0,0,0}, - {34375,34374,34378 ,18704,18704,18707 ,0,0,0}, {34379,34380,34381 ,18575,18575,18706 ,0,0,0}, - {34377,34376,34381 ,18706,18705,18706 ,0,0,0}, {34381,34380,34377 ,18706,18575,18706 ,0,0,0}, - {34376,34378,34374 ,18705,18707,18704 ,0,0,0}, {34375,34382,34373 ,18704,18703,18703 ,0,0,0}, - {34382,34383,34384 ,18703,18708,18708 ,0,0,0}, {34384,34373,34382 ,18708,18703,18703 ,0,0,0}, - {34385,34383,34386 ,18601,18708,18601 ,0,0,0}, {34383,34385,34384 ,18708,18601,18708 ,0,0,0}, - {34387,34388,34389 ,18709,18710,18710 ,0,0,0}, {34390,34391,34392 ,18711,18712,18711 ,0,0,0}, - {34389,34388,34392 ,18710,18710,18711 ,0,0,0}, {34393,34394,34395 ,18583,18583,18712 ,0,0,0}, - {34391,34390,34395 ,18712,18711,18712 ,0,0,0}, {34395,34394,34391 ,18712,18583,18712 ,0,0,0}, - {34390,34392,34388 ,18711,18711,18710 ,0,0,0}, {34389,34396,34387 ,18710,18709,18709 ,0,0,0}, - {34396,34397,34398 ,18709,18713,18713 ,0,0,0}, {34398,34387,34396 ,18713,18709,18709 ,0,0,0}, - {34399,34397,34400 ,18609,18713,18609 ,0,0,0}, {34397,34399,34398 ,18713,18609,18713 ,0,0,0}, - {34401,34402,34403 ,18714,18715,18715 ,0,0,0}, {34404,34405,34406 ,18716,18717,18716 ,0,0,0}, - {34403,34402,34406 ,18715,18715,18716 ,0,0,0}, {34407,34408,34409 ,18573,18573,18717 ,0,0,0}, - {34405,34404,34409 ,18717,18716,18717 ,0,0,0}, {34409,34408,34405 ,18717,18573,18717 ,0,0,0}, - {34404,34406,34402 ,18716,18716,18715 ,0,0,0}, {34403,34410,34401 ,18715,18714,18714 ,0,0,0}, - {34410,34411,34412 ,18714,18718,18718 ,0,0,0}, {34412,34401,34410 ,18718,18714,18714 ,0,0,0}, - {34413,34411,34414 ,18575,18718,18575 ,0,0,0}, {34411,34413,34412 ,18718,18575,18718 ,0,0,0}, - {34415,34416,34417 ,18719,18720,18720 ,0,0,0}, {34418,34419,34420 ,18721,18722,18721 ,0,0,0}, - {34417,34416,34420 ,18720,18720,18721 ,0,0,0}, {34421,34422,34423 ,18581,18581,18722 ,0,0,0}, - {34419,34418,34423 ,18722,18721,18722 ,0,0,0}, {34423,34422,34419 ,18722,18581,18722 ,0,0,0}, - {34418,34420,34416 ,18721,18721,18720 ,0,0,0}, {34417,34424,34415 ,18720,18719,18719 ,0,0,0}, - {34424,34425,34426 ,18719,18723,18723 ,0,0,0}, {34426,34415,34424 ,18723,18719,18719 ,0,0,0}, - {34427,34425,34428 ,18583,18723,18583 ,0,0,0}, {34425,34427,34426 ,18723,18583,18723 ,0,0,0}, - {34429,34430,34431 ,18724,18725,18725 ,0,0,0}, {34432,34433,34434 ,18726,18727,18726 ,0,0,0}, - {34431,34430,34434 ,18725,18725,18726 ,0,0,0}, {34435,34436,34437 ,18588,18588,18727 ,0,0,0}, - {34433,34432,34437 ,18727,18726,18727 ,0,0,0}, {34437,34436,34433 ,18727,18588,18727 ,0,0,0}, - {34432,34434,34430 ,18726,18726,18725 ,0,0,0}, {34431,34438,34429 ,18725,18724,18724 ,0,0,0}, - {34438,34439,34440 ,18724,18728,18728 ,0,0,0}, {34440,34429,34438 ,18728,18724,18724 ,0,0,0}, - {34441,34439,34442 ,18573,18728,18573 ,0,0,0}, {34439,34441,34440 ,18728,18573,18728 ,0,0,0}, - {34443,34444,34445 ,18729,18730,18731 ,0,0,0}, {34446,34447,34448 ,18732,18733,18734 ,0,0,0}, - {34445,34444,34448 ,18731,18730,18734 ,0,0,0}, {34449,34450,34451 ,18594,18594,18733 ,0,0,0}, - {34447,34446,34451 ,18733,18732,18733 ,0,0,0}, {34451,34450,34447 ,18733,18594,18733 ,0,0,0}, - {34446,34448,34444 ,18732,18734,18730 ,0,0,0}, {34445,34452,34443 ,18731,18729,18729 ,0,0,0}, - {34452,34453,34454 ,18729,18595,18595 ,0,0,0}, {34454,34443,34452 ,18595,18729,18729 ,0,0,0}, - {34455,34453,34456 ,18581,18595,18581 ,0,0,0}, {34453,34455,34454 ,18595,18581,18595 ,0,0,0}, - {34457,34458,34459 ,18735,18736,18737 ,0,0,0}, {34457,34460,34461 ,18735,18738,18739 ,0,0,0}, - {34460,34462,34461 ,18738,18740,18739 ,0,0,0}, {34459,34460,34457 ,18737,18738,18735 ,0,0,0}, - {34463,34464,34465 ,18741,18742,18743 ,0,0,0}, {34462,34463,34465 ,18740,18741,18743 ,0,0,0}, - {34464,34466,34467 ,18742,18744,18745 ,0,0,0}, {34466,34464,34463 ,18744,18742,18741 ,0,0,0}, - {34467,34466,34468 ,18745,18744,18746 ,0,0,0}, {34469,34467,34468 ,18747,18745,18746 ,0,0,0}, - {34469,34470,34471 ,18747,18748,18749 ,0,0,0}, {34469,34468,34470 ,18747,18746,18748 ,0,0,0}, - {34465,34461,34462 ,18743,18739,18740 ,0,0,0}, {34472,34473,34474 ,18750,18751,126 ,0,0,0}, - {34472,34474,34471 ,18750,126,18749 ,0,0,0}, {34470,34472,34471 ,18748,18750,18749 ,0,0,0}, - {34459,34458,34475 ,18737,18736,18752 ,0,0,0}, {34476,34475,34477 ,18753,18752,18754 ,0,0,0}, - {34458,34477,34475 ,18736,18754,18752 ,0,0,0}, {34478,34479,34476 ,18755,18756,18753 ,0,0,0}, - {34476,34477,34478 ,18753,18754,18755 ,0,0,0}, {34479,34480,34481 ,18756,18757,18758 ,0,0,0}, - {34480,34479,34478 ,18757,18756,18755 ,0,0,0}, {34482,34481,34483 ,18759,18758,18760 ,0,0,0}, - {34480,34483,34481 ,18757,18760,18758 ,0,0,0}, {34484,34485,34482 ,18761,18067,18759 ,0,0,0}, - {34482,34483,34484 ,18759,18760,18761 ,0,0,0}, {34485,34486,34487 ,18067,18762,18763 ,0,0,0}, - {34486,34485,34484 ,18762,18067,18761 ,0,0,0}, {34486,34488,34487 ,18762,82,18763 ,0,0,0}, - {34489,34490,34491 ,18764,18765,18766 ,0,0,0}, {34489,34492,34493 ,18764,18767,18768 ,0,0,0}, - {34492,34494,34493 ,18767,18769,18768 ,0,0,0}, {34491,34492,34489 ,18766,18767,18764 ,0,0,0}, - {34495,34496,34497 ,18770,18771,18239 ,0,0,0}, {34494,34495,34497 ,18769,18770,18239 ,0,0,0}, - {34496,34498,34499 ,18771,18772,18773 ,0,0,0}, {34498,34496,34495 ,18772,18771,18770 ,0,0,0}, - {34499,34498,34500 ,18773,18772,18774 ,0,0,0}, {34501,34499,34500 ,18775,18773,18774 ,0,0,0}, - {34501,34502,34503 ,18775,18776,18777 ,0,0,0}, {34501,34500,34502 ,18775,18774,18776 ,0,0,0}, - {34497,34493,34494 ,18239,18768,18769 ,0,0,0}, {34504,34505,1297 ,18778,18751,126 ,0,0,0}, - {34504,1297,34503 ,18778,126,18777 ,0,0,0}, {34502,34504,34503 ,18776,18778,18777 ,0,0,0}, - {34491,34490,34506 ,18766,18765,18779 ,0,0,0}, {34507,34506,34508 ,18780,18779,18781 ,0,0,0}, - {34490,34508,34506 ,18765,18781,18779 ,0,0,0}, {34509,34510,34507 ,18782,18756,18780 ,0,0,0}, - {34507,34508,34509 ,18780,18781,18782 ,0,0,0}, {34510,34511,34512 ,18756,18783,18758 ,0,0,0}, - {34511,34510,34509 ,18783,18756,18782 ,0,0,0}, {34513,34512,34514 ,18784,18758,18785 ,0,0,0}, - {34511,34514,34512 ,18783,18785,18758 ,0,0,0}, {34515,34516,34513 ,18761,18786,18784 ,0,0,0}, - {34513,34514,34515 ,18784,18785,18761 ,0,0,0}, {34516,34517,34518 ,18786,18787,18763 ,0,0,0}, - {34517,34516,34515 ,18787,18786,18761 ,0,0,0}, {34517,2073,34518 ,18787,82,18763 ,0,0,0}, - {34519,34520,34521 ,18788,18789,18790 ,0,0,0}, {34519,34522,34523 ,18788,18791,18792 ,0,0,0}, - {34522,34524,34523 ,18791,18793,18792 ,0,0,0}, {34521,34522,34519 ,18790,18791,18788 ,0,0,0}, - {34525,34526,34527 ,18794,18795,18796 ,0,0,0}, {34524,34525,34527 ,18793,18794,18796 ,0,0,0}, - {34526,34528,34529 ,18795,18797,18798 ,0,0,0}, {34528,34526,34525 ,18797,18795,18794 ,0,0,0}, - {34529,34528,34530 ,18798,18797,18799 ,0,0,0}, {34531,34529,34530 ,18800,18798,18799 ,0,0,0}, - {34531,34532,34533 ,18800,18801,18802 ,0,0,0}, {34531,34530,34532 ,18800,18799,18801 ,0,0,0}, - {34527,34523,34524 ,18796,18792,18793 ,0,0,0}, {34534,34535,34536 ,18803,18804,126 ,0,0,0}, - {34534,34536,34533 ,18803,126,18802 ,0,0,0}, {34532,34534,34533 ,18801,18803,18802 ,0,0,0}, - {34521,34520,34537 ,18790,18789,18805 ,0,0,0}, {34538,34537,34539 ,18806,18805,18781 ,0,0,0}, - {34520,34539,34537 ,18789,18781,18805 ,0,0,0}, {34540,34541,34538 ,18807,18808,18806 ,0,0,0}, - {34538,34539,34540 ,18806,18781,18807 ,0,0,0}, {34541,34542,34543 ,18808,18809,18758 ,0,0,0}, - {34542,34541,34540 ,18809,18808,18807 ,0,0,0}, {34544,34543,34545 ,18810,18758,18811 ,0,0,0}, - {34542,34545,34543 ,18809,18811,18758 ,0,0,0}, {34546,34547,34544 ,18812,18813,18810 ,0,0,0}, - {34544,34545,34546 ,18810,18811,18812 ,0,0,0}, {34547,34548,34549 ,18813,18814,18763 ,0,0,0}, - {34548,34547,34546 ,18814,18813,18812 ,0,0,0}, {34548,34550,34549 ,18814,82,18763 ,0,0,0}, - {34551,34552,34553 ,18815,18816,18817 ,0,0,0}, {34551,34554,34555 ,18815,18818,18819 ,0,0,0}, - {34554,34556,34555 ,18818,18820,18819 ,0,0,0}, {34553,34554,34551 ,18817,18818,18815 ,0,0,0}, - {34557,34558,34559 ,18821,18822,18823 ,0,0,0}, {34556,34557,34559 ,18820,18821,18823 ,0,0,0}, - {34558,34560,34561 ,18822,18824,18825 ,0,0,0}, {34560,34558,34557 ,18824,18822,18821 ,0,0,0}, - {34561,34560,34562 ,18825,18824,18826 ,0,0,0}, {34563,34561,34562 ,18827,18825,18826 ,0,0,0}, - {34563,34564,34565 ,18827,18828,18829 ,0,0,0}, {34563,34562,34564 ,18827,18826,18828 ,0,0,0}, - {34559,34555,34556 ,18823,18819,18820 ,0,0,0}, {34566,34567,1263 ,18830,18804,126 ,0,0,0}, - {34566,1263,34565 ,18830,126,18829 ,0,0,0}, {34564,34566,34565 ,18828,18830,18829 ,0,0,0}, - {34553,34552,34568 ,18817,18816,18831 ,0,0,0}, {34569,34568,34570 ,18832,18831,18754 ,0,0,0}, - {34552,34570,34568 ,18816,18754,18831 ,0,0,0}, {34571,34572,34569 ,18833,18808,18832 ,0,0,0}, - {34569,34570,34571 ,18832,18754,18833 ,0,0,0}, {34572,34573,34574 ,18808,18834,18758 ,0,0,0}, - {34573,34572,34571 ,18834,18808,18833 ,0,0,0}, {34575,34574,34576 ,18835,18758,18836 ,0,0,0}, - {34573,34576,34574 ,18834,18836,18758 ,0,0,0}, {34577,34578,34575 ,18812,18837,18835 ,0,0,0}, - {34575,34576,34577 ,18835,18836,18812 ,0,0,0}, {34578,34579,34580 ,18837,18838,18763 ,0,0,0}, - {34579,34578,34577 ,18838,18837,18812 ,0,0,0}, {34579,2082,34580 ,18838,82,18763 ,0,0,0}, - {34581,34582,34583 ,18839,18840,18841 ,0,0,0}, {34581,34584,34585 ,18839,18842,18843 ,0,0,0}, - {34584,34586,34585 ,18842,18844,18843 ,0,0,0}, {34583,34584,34581 ,18841,18842,18839 ,0,0,0}, - {34587,34588,34589 ,18845,18846,18847 ,0,0,0}, {34586,34587,34589 ,18844,18845,18847 ,0,0,0}, - {34588,34590,34591 ,18846,18848,18849 ,0,0,0}, {34590,34588,34587 ,18848,18846,18845 ,0,0,0}, - {34591,34590,34592 ,18849,18848,18850 ,0,0,0}, {34593,34591,34592 ,18851,18849,18850 ,0,0,0}, - {34593,34594,34595 ,18851,18852,18853 ,0,0,0}, {34593,34592,34594 ,18851,18850,18852 ,0,0,0}, - {34589,34585,34586 ,18847,18843,18844 ,0,0,0}, {34596,34597,3049 ,18854,3316,126 ,0,0,0}, - {34596,3049,34595 ,18854,126,18853 ,0,0,0}, {34594,34596,34595 ,18852,18854,18853 ,0,0,0}, - {34583,34582,34598 ,18841,18840,18855 ,0,0,0}, {34599,34598,34600 ,18856,18855,18857 ,0,0,0}, - {34582,34600,34598 ,18840,18857,18855 ,0,0,0}, {34601,34602,34599 ,18858,18859,18856 ,0,0,0}, - {34599,34600,34601 ,18856,18857,18858 ,0,0,0}, {34602,34603,34604 ,18859,18860,18861 ,0,0,0}, - {34603,34602,34601 ,18860,18859,18858 ,0,0,0}, {34605,34604,34606 ,18784,18861,18862 ,0,0,0}, - {34603,34606,34604 ,18860,18862,18861 ,0,0,0}, {34607,34608,34605 ,18863,18864,18784 ,0,0,0}, - {34605,34606,34607 ,18784,18862,18863 ,0,0,0}, {34608,34609,34610 ,18864,18865,3343 ,0,0,0}, - {34609,34608,34607 ,18865,18864,18863 ,0,0,0}, {34609,3063,34610 ,18865,3370,3343 ,0,0,0}, - {34611,34612,34613 ,18866,18867,18868 ,0,0,0}, {34611,34614,34615 ,18866,18869,18870 ,0,0,0}, - {34614,34616,34615 ,18869,18871,18870 ,0,0,0}, {34613,34614,34611 ,18868,18869,18866 ,0,0,0}, - {34617,34618,34619 ,18872,18873,18874 ,0,0,0}, {34616,34617,34619 ,18871,18872,18874 ,0,0,0}, - {34618,34620,34621 ,18873,18875,18876 ,0,0,0}, {34620,34618,34617 ,18875,18873,18872 ,0,0,0}, - {34621,34620,34622 ,18876,18875,18877 ,0,0,0}, {34623,34621,34622 ,18878,18876,18877 ,0,0,0}, - {34623,34624,34625 ,18878,18879,18880 ,0,0,0}, {34623,34622,34624 ,18878,18877,18879 ,0,0,0}, - {34619,34615,34616 ,18874,18870,18871 ,0,0,0}, {34626,34627,34628 ,18881,18882,2619 ,0,0,0}, - {34626,34628,34625 ,18881,2619,18880 ,0,0,0}, {34624,34626,34625 ,18879,18881,18880 ,0,0,0}, - {34613,34612,34629 ,18868,18867,18883 ,0,0,0}, {34630,34629,34631 ,18884,18883,18885 ,0,0,0}, - {34612,34631,34629 ,18867,18885,18883 ,0,0,0}, {34632,34633,34630 ,18886,18887,18884 ,0,0,0}, - {34630,34631,34632 ,18884,18885,18886 ,0,0,0}, {34633,34634,34635 ,18887,18888,18889 ,0,0,0}, - {34634,34633,34632 ,18888,18887,18886 ,0,0,0}, {34636,34635,34637 ,18784,18889,18862 ,0,0,0}, - {34634,34637,34635 ,18888,18862,18889 ,0,0,0}, {34638,34639,34636 ,18890,18067,18784 ,0,0,0}, - {34636,34637,34638 ,18784,18862,18890 ,0,0,0}, {34639,34640,34641 ,18067,18891,2602 ,0,0,0}, - {34640,34639,34638 ,18891,18067,18890 ,0,0,0}, {34640,34642,34641 ,18891,82,2602 ,0,0,0}, - {34643,34644,34645 ,18839,18892,18893 ,0,0,0}, {34643,34646,34647 ,18839,18842,18843 ,0,0,0}, - {34646,34648,34647 ,18842,18894,18843 ,0,0,0}, {34645,34646,34643 ,18893,18842,18839 ,0,0,0}, - {34649,34650,34651 ,18895,18896,18897 ,0,0,0}, {34648,34649,34651 ,18894,18895,18897 ,0,0,0}, - {34650,34652,34653 ,18896,18898,18899 ,0,0,0}, {34652,34650,34649 ,18898,18896,18895 ,0,0,0}, - {34653,34652,34654 ,18899,18898,18900 ,0,0,0}, {34655,34653,34654 ,18901,18899,18900 ,0,0,0}, - {34655,34656,34657 ,18901,18902,18903 ,0,0,0}, {34655,34654,34656 ,18901,18900,18902 ,0,0,0}, - {34651,34647,34648 ,18897,18843,18894 ,0,0,0}, {34658,34659,34660 ,18904,2589,126 ,0,0,0}, - {34658,34660,34657 ,18904,126,18903 ,0,0,0}, {34656,34658,34657 ,18902,18904,18903 ,0,0,0}, - {34645,34644,34661 ,18893,18892,18905 ,0,0,0}, {34662,34661,34663 ,18906,18905,18907 ,0,0,0}, - {34644,34663,34661 ,18892,18907,18905 ,0,0,0}, {34664,34665,34662 ,18908,18909,18906 ,0,0,0}, - {34662,34663,34664 ,18906,18907,18908 ,0,0,0}, {34665,34666,34667 ,18909,18910,18911 ,0,0,0}, - {34666,34665,34664 ,18910,18909,18908 ,0,0,0}, {34668,34667,34669 ,18784,18911,18912 ,0,0,0}, - {34666,34669,34667 ,18910,18912,18911 ,0,0,0}, {34670,34671,34668 ,18913,18914,18784 ,0,0,0}, - {34668,34669,34670 ,18784,18912,18913 ,0,0,0}, {34671,34672,34673 ,18914,18891,3371 ,0,0,0}, - {34672,34671,34670 ,18891,18914,18913 ,0,0,0}, {34672,34674,34673 ,18891,82,3371 ,0,0,0}, - {34675,34676,34677 ,18866,18915,18916 ,0,0,0}, {34675,34678,34679 ,18866,18917,18843 ,0,0,0}, - {34678,34680,34679 ,18917,18918,18843 ,0,0,0}, {34677,34678,34675 ,18916,18917,18866 ,0,0,0}, - {34681,34682,34683 ,18919,18920,18921 ,0,0,0}, {34680,34681,34683 ,18918,18919,18921 ,0,0,0}, - {34682,34684,34685 ,18920,18922,18923 ,0,0,0}, {34684,34682,34681 ,18922,18920,18919 ,0,0,0}, - {34685,34684,34686 ,18923,18922,18924 ,0,0,0}, {34687,34685,34686 ,18925,18923,18924 ,0,0,0}, - {34687,34688,34689 ,18925,18926,18927 ,0,0,0}, {34687,34686,34688 ,18925,18924,18926 ,0,0,0}, - {34683,34679,34680 ,18921,18843,18918 ,0,0,0}, {34690,34691,3015 ,18928,18929,126 ,0,0,0}, - {34690,3015,34689 ,18928,126,18927 ,0,0,0}, {34688,34690,34689 ,18926,18928,18927 ,0,0,0}, - {34677,34676,34692 ,18916,18915,18930 ,0,0,0}, {34693,34692,34694 ,18931,18930,18932 ,0,0,0}, - {34676,34694,34692 ,18915,18932,18930 ,0,0,0}, {34695,34696,34693 ,18933,18934,18931 ,0,0,0}, - {34693,34694,34695 ,18931,18932,18933 ,0,0,0}, {34696,34697,34698 ,18934,18935,18936 ,0,0,0}, - {34697,34696,34695 ,18935,18934,18933 ,0,0,0}, {34699,34698,34700 ,18937,18936,18811 ,0,0,0}, - {34697,34700,34698 ,18935,18811,18936 ,0,0,0}, {34701,34702,34699 ,18761,18938,18937 ,0,0,0}, - {34699,34700,34701 ,18937,18811,18761 ,0,0,0}, {34702,34703,34704 ,18938,18865,3371 ,0,0,0}, - {34703,34702,34701 ,18865,18938,18761 ,0,0,0}, {34703,3029,34704 ,18865,82,3371 ,0,0,0}, - {34705,34706,34707 ,18939,18765,18940 ,0,0,0}, {34705,34708,34709 ,18939,18941,18942 ,0,0,0}, - {34708,34710,34709 ,18941,18943,18942 ,0,0,0}, {34707,34708,34705 ,18940,18941,18939 ,0,0,0}, - {34711,34712,34713 ,18944,18945,18946 ,0,0,0}, {34710,34711,34713 ,18943,18944,18946 ,0,0,0}, - {34712,34714,34715 ,18945,18797,18947 ,0,0,0}, {34714,34712,34711 ,18797,18945,18944 ,0,0,0}, - {34715,34714,34716 ,18947,18797,18948 ,0,0,0}, {34717,34715,34716 ,18949,18947,18948 ,0,0,0}, - {34717,34718,34719 ,18949,18950,18951 ,0,0,0}, {34717,34716,34718 ,18949,18948,18950 ,0,0,0}, - {34713,34709,34710 ,18946,18942,18943 ,0,0,0}, {34720,34721,34722 ,18952,8371,126 ,0,0,0}, - {34720,34722,34719 ,18952,126,18951 ,0,0,0}, {34718,34720,34719 ,18950,18952,18951 ,0,0,0}, - {34707,34706,34723 ,18940,18765,18953 ,0,0,0}, {34724,34723,34725 ,18954,18953,18955 ,0,0,0}, - {34706,34725,34723 ,18765,18955,18953 ,0,0,0}, {34726,34727,34724 ,18956,18957,18954 ,0,0,0}, - {34724,34725,34726 ,18954,18955,18956 ,0,0,0}, {34727,34728,34729 ,18957,18958,18959 ,0,0,0}, - {34728,34727,34726 ,18958,18957,18956 ,0,0,0}, {34730,34729,34731 ,18784,18959,18811 ,0,0,0}, - {34728,34731,34729 ,18958,18811,18959 ,0,0,0}, {34732,34733,34730 ,18960,18786,18784 ,0,0,0}, - {34730,34731,34732 ,18784,18811,18960 ,0,0,0}, {34733,34734,34735 ,18786,18814,18961 ,0,0,0}, - {34734,34733,34732 ,18814,18786,18960 ,0,0,0}, {34734,34736,34735 ,18814,82,18961 ,0,0,0}, - {34737,34738,34739 ,18962,18765,18940 ,0,0,0}, {34737,34740,34741 ,18962,18791,18963 ,0,0,0}, - {34740,34742,34741 ,18791,18943,18963 ,0,0,0}, {34739,34740,34737 ,18940,18791,18962 ,0,0,0}, - {34743,34744,34745 ,18964,18965,18239 ,0,0,0}, {34742,34743,34745 ,18943,18964,18239 ,0,0,0}, - {34744,34746,34747 ,18965,18966,18967 ,0,0,0}, {34746,34744,34743 ,18966,18965,18964 ,0,0,0}, - {34747,34746,34748 ,18967,18966,18968 ,0,0,0}, {34749,34747,34748 ,18969,18967,18968 ,0,0,0}, - {34749,34750,34751 ,18969,18970,18971 ,0,0,0}, {34749,34748,34750 ,18969,18968,18970 ,0,0,0}, - {34745,34741,34742 ,18239,18963,18943 ,0,0,0}, {34752,34753,2950 ,18972,18973,126 ,0,0,0}, - {34752,2950,34751 ,18972,126,18971 ,0,0,0}, {34750,34752,34751 ,18970,18972,18971 ,0,0,0}, - {34739,34738,34754 ,18940,18765,18805 ,0,0,0}, {34755,34754,34756 ,18954,18805,18974 ,0,0,0}, - {34738,34756,34754 ,18765,18974,18805 ,0,0,0}, {34757,34758,34755 ,18956,18957,18954 ,0,0,0}, - {34755,34756,34757 ,18954,18974,18956 ,0,0,0}, {34758,34759,34760 ,18957,18958,18975 ,0,0,0}, - {34759,34758,34757 ,18958,18957,18956 ,0,0,0}, {34761,34760,34762 ,18976,18975,18811 ,0,0,0}, - {34759,34762,34760 ,18958,18811,18975 ,0,0,0}, {34763,34764,34761 ,18812,18786,18976 ,0,0,0}, - {34761,34762,34763 ,18976,18811,18812 ,0,0,0}, {34764,34765,34766 ,18786,18814,18961 ,0,0,0}, - {34765,34764,34763 ,18814,18786,18812 ,0,0,0}, {34765,2131,34766 ,18814,82,18961 ,0,0,0}, - {34767,34768,34769 ,18977,18736,18978 ,0,0,0}, {34767,34770,34771 ,18977,18818,18979 ,0,0,0}, - {34770,34772,34771 ,18818,18980,18979 ,0,0,0}, {34769,34770,34767 ,18978,18818,18977 ,0,0,0}, - {34773,34774,34775 ,18981,18982,18743 ,0,0,0}, {34772,34773,34775 ,18980,18981,18743 ,0,0,0}, - {34774,34776,34777 ,18982,18983,18984 ,0,0,0}, {34776,34774,34773 ,18983,18982,18981 ,0,0,0}, - {34777,34776,34778 ,18984,18983,18985 ,0,0,0}, {34779,34777,34778 ,18986,18984,18985 ,0,0,0}, - {34779,34780,34781 ,18986,18987,18988 ,0,0,0}, {34779,34778,34780 ,18986,18985,18987 ,0,0,0}, - {34775,34771,34772 ,18743,18979,18980 ,0,0,0}, {34782,34783,34784 ,18989,18973,126 ,0,0,0}, - {34782,34784,34781 ,18989,126,18988 ,0,0,0}, {34780,34782,34781 ,18987,18989,18988 ,0,0,0}, - {34769,34768,34785 ,18978,18736,18831 ,0,0,0}, {34786,34785,34787 ,18990,18831,18991 ,0,0,0}, - {34768,34787,34785 ,18736,18991,18831 ,0,0,0}, {34788,34789,34786 ,18992,18957,18990 ,0,0,0}, - {34786,34787,34788 ,18990,18991,18992 ,0,0,0}, {34789,34790,34791 ,18957,18993,18975 ,0,0,0}, - {34790,34789,34788 ,18993,18957,18992 ,0,0,0}, {34792,34791,34793 ,18994,18975,18836 ,0,0,0}, - {34790,34793,34791 ,18993,18836,18975 ,0,0,0}, {34794,34795,34792 ,18812,18067,18994 ,0,0,0}, - {34792,34793,34794 ,18994,18836,18812 ,0,0,0}, {34795,34796,34797 ,18067,18838,18961 ,0,0,0}, - {34796,34795,34794 ,18838,18067,18812 ,0,0,0}, {34796,34798,34797 ,18838,82,18961 ,0,0,0}, - {34799,34800,34801 ,18995,18736,18978 ,0,0,0}, {34799,34802,34803 ,18995,18996,18997 ,0,0,0}, - {34802,34804,34803 ,18996,18980,18997 ,0,0,0}, {34801,34802,34799 ,18978,18996,18995 ,0,0,0}, - {34805,34806,34807 ,18998,18999,19000 ,0,0,0}, {34804,34805,34807 ,18980,18998,19000 ,0,0,0}, - {34806,34808,34809 ,18999,18824,19001 ,0,0,0}, {34808,34806,34805 ,18824,18999,18998 ,0,0,0}, - {34809,34808,34810 ,19001,18824,19002 ,0,0,0}, {34811,34809,34810 ,19003,19001,19002 ,0,0,0}, - {34811,34812,34813 ,19003,19004,19005 ,0,0,0}, {34811,34810,34812 ,19003,19002,19004 ,0,0,0}, - {34807,34803,34804 ,19000,18997,18980 ,0,0,0}, {34814,34815,2941 ,19006,8371,126 ,0,0,0}, - {34814,2941,34813 ,19006,126,19005 ,0,0,0}, {34812,34814,34813 ,19004,19006,19005 ,0,0,0}, - {34801,34800,34816 ,18978,18736,19007 ,0,0,0}, {34817,34816,34818 ,18990,19007,19008 ,0,0,0}, - {34800,34818,34816 ,18736,19008,19007 ,0,0,0}, {34819,34820,34817 ,18992,18957,18990 ,0,0,0}, - {34817,34818,34819 ,18990,19008,18992 ,0,0,0}, {34820,34821,34822 ,18957,18993,18959 ,0,0,0}, - {34821,34820,34819 ,18993,18957,18992 ,0,0,0}, {34823,34822,34824 ,18759,18959,18836 ,0,0,0}, - {34821,34824,34822 ,18993,18836,18959 ,0,0,0}, {34825,34826,34823 ,18960,18067,18759 ,0,0,0}, - {34823,34824,34825 ,18759,18836,18960 ,0,0,0}, {34826,34827,34828 ,18067,18838,18961 ,0,0,0}, - {34827,34826,34825 ,18838,18067,18960 ,0,0,0}, {34827,2165,34828 ,18838,82,18961 ,0,0,0}, - {34829,34830,34831 ,19009,19010,19011 ,0,0,0}, {34829,34832,34833 ,19009,19012,19013 ,0,0,0}, - {34832,34834,34833 ,19012,18844,19013 ,0,0,0}, {34831,34832,34829 ,19011,19012,19009 ,0,0,0}, - {34835,34836,34837 ,19014,19015,19016 ,0,0,0}, {34834,34835,34837 ,18844,19014,19016 ,0,0,0}, - {34836,34838,34839 ,19015,19017,19018 ,0,0,0}, {34838,34836,34835 ,19017,19015,19014 ,0,0,0}, - {34839,34838,34840 ,19018,19017,19019 ,0,0,0}, {34841,34839,34840 ,19020,19018,19019 ,0,0,0}, - {34841,34842,34843 ,19020,19021,19022 ,0,0,0}, {34841,34840,34842 ,19020,19019,19021 ,0,0,0}, - {34837,34833,34834 ,19016,19013,18844 ,0,0,0}, {34844,34845,3931 ,19023,2589,126 ,0,0,0}, - {34844,3931,34843 ,19023,126,19022 ,0,0,0}, {34842,34844,34843 ,19021,19023,19022 ,0,0,0}, - {34831,34830,34846 ,19011,19010,19024 ,0,0,0}, {34847,34846,34848 ,19025,19024,19026 ,0,0,0}, - {34830,34848,34846 ,19010,19026,19024 ,0,0,0}, {34849,34850,34847 ,19027,18756,19025 ,0,0,0}, - {34847,34848,34849 ,19025,19026,19027 ,0,0,0}, {34850,34851,34852 ,18756,18910,19028 ,0,0,0}, - {34851,34850,34849 ,18910,18756,19027 ,0,0,0}, {34853,34852,34854 ,18937,19028,19029 ,0,0,0}, - {34851,34854,34852 ,18910,19029,19028 ,0,0,0}, {34855,34856,34853 ,19030,18864,18937 ,0,0,0}, - {34853,34854,34855 ,18937,19029,19030 ,0,0,0}, {34856,34857,34858 ,18864,19031,3371 ,0,0,0}, - {34857,34856,34855 ,19031,18864,19030 ,0,0,0}, {34857,3917,34858 ,19031,82,3371 ,0,0,0}, - {34859,34860,34861 ,19032,19033,19034 ,0,0,0}, {34859,34862,34863 ,19032,19035,19036 ,0,0,0}, - {34862,34864,34863 ,19035,19037,19036 ,0,0,0}, {34861,34862,34859 ,19034,19035,19032 ,0,0,0}, - {34865,34866,34867 ,19038,19039,19040 ,0,0,0}, {34864,34865,34867 ,19037,19038,19040 ,0,0,0}, - {34866,34868,34869 ,19039,19041,19042 ,0,0,0}, {34868,34866,34865 ,19041,19039,19038 ,0,0,0}, - {34869,34868,34870 ,19042,19041,19043 ,0,0,0}, {34871,34869,34870 ,19044,19042,19043 ,0,0,0}, - {34871,34872,34873 ,19044,19045,19046 ,0,0,0}, {34871,34870,34872 ,19044,19043,19045 ,0,0,0}, - {34867,34863,34864 ,19040,19036,19037 ,0,0,0}, {34874,34875,34876 ,19047,18929,126 ,0,0,0}, - {34874,34876,34873 ,19047,126,19046 ,0,0,0}, {34872,34874,34873 ,19045,19047,19046 ,0,0,0}, - {34861,34860,34877 ,19034,19033,19048 ,0,0,0}, {34878,34877,34879 ,19049,19048,19050 ,0,0,0}, - {34860,34879,34877 ,19033,19050,19048 ,0,0,0}, {34880,34881,34878 ,19051,19052,19049 ,0,0,0}, - {34878,34879,34880 ,19049,19050,19051 ,0,0,0}, {34881,34882,34883 ,19052,19053,19054 ,0,0,0}, - {34882,34881,34880 ,19053,19052,19051 ,0,0,0}, {34884,34883,34885 ,19055,19054,18811 ,0,0,0}, - {34882,34885,34883 ,19053,18811,19054 ,0,0,0}, {34886,34887,34884 ,19056,18938,19055 ,0,0,0}, - {34884,34885,34886 ,19055,18811,19056 ,0,0,0}, {34887,34888,34889 ,18938,19057,3371 ,0,0,0}, - {34888,34887,34886 ,19057,18938,19056 ,0,0,0}, {34888,34890,34889 ,19057,82,3371 ,0,0,0}, - {34891,34892,34893 ,19058,19059,19060 ,0,0,0}, {34891,34894,34895 ,19058,19061,19062 ,0,0,0}, - {34894,34896,34895 ,19061,19063,19062 ,0,0,0}, {34893,34894,34891 ,19060,19061,19058 ,0,0,0}, - {34897,34898,34899 ,19064,19065,19066 ,0,0,0}, {34896,34897,34899 ,19063,19064,19066 ,0,0,0}, - {34898,34900,34901 ,19065,19067,19068 ,0,0,0}, {34900,34898,34897 ,19067,19065,19064 ,0,0,0}, - {34901,34900,34902 ,19068,19067,19069 ,0,0,0}, {34903,34901,34902 ,19070,19068,19069 ,0,0,0}, - {34903,34904,34905 ,19070,19071,19072 ,0,0,0}, {34903,34902,34904 ,19070,19069,19071 ,0,0,0}, - {34899,34895,34896 ,19066,19062,19063 ,0,0,0}, {34906,34907,3897 ,19073,3316,126 ,0,0,0}, - {34906,3897,34905 ,19073,126,19072 ,0,0,0}, {34904,34906,34905 ,19071,19073,19072 ,0,0,0}, - {34893,34892,34908 ,19060,19059,19074 ,0,0,0}, {34909,34908,34910 ,19075,19074,19076 ,0,0,0}, - {34892,34910,34908 ,19059,19076,19074 ,0,0,0}, {34911,34912,34909 ,18933,19077,19075 ,0,0,0}, - {34909,34910,34911 ,19075,19076,18933 ,0,0,0}, {34912,34913,34914 ,19077,19078,19079 ,0,0,0}, - {34913,34912,34911 ,19078,19077,18933 ,0,0,0}, {34915,34914,34916 ,19080,19079,18811 ,0,0,0}, - {34913,34916,34914 ,19078,18811,19079 ,0,0,0}, {34917,34918,34915 ,19081,18067,19080 ,0,0,0}, - {34915,34916,34917 ,19080,18811,19081 ,0,0,0}, {34918,34919,34920 ,18067,18838,2602 ,0,0,0}, - {34919,34918,34917 ,18838,18067,19081 ,0,0,0}, {34919,3883,34920 ,18838,82,2602 ,0,0,0}, - {34921,34922,34923 ,19009,19082,19083 ,0,0,0}, {34921,34924,34925 ,19009,19084,19085 ,0,0,0}, - {34924,34926,34925 ,19084,19086,19085 ,0,0,0}, {34923,34924,34921 ,19083,19084,19009 ,0,0,0}, - {34927,34928,34929 ,19087,19088,19089 ,0,0,0}, {34926,34927,34929 ,19086,19087,19089 ,0,0,0}, - {34928,34930,34931 ,19088,19090,19091 ,0,0,0}, {34930,34928,34927 ,19090,19088,19087 ,0,0,0}, - {34931,34930,34932 ,19091,19090,19092 ,0,0,0}, {34933,34931,34932 ,19093,19091,19092 ,0,0,0}, - {34933,34934,34935 ,19093,19094,19095 ,0,0,0}, {34933,34932,34934 ,19093,19092,19094 ,0,0,0}, - {34929,34925,34926 ,19089,19085,19086 ,0,0,0}, {34936,34937,34938 ,19096,3316,126 ,0,0,0}, - {34936,34938,34935 ,19096,126,19095 ,0,0,0}, {34934,34936,34935 ,19094,19096,19095 ,0,0,0}, - {34923,34922,34939 ,19083,19082,19097 ,0,0,0}, {34940,34939,34941 ,18906,19097,19098 ,0,0,0}, - {34922,34941,34939 ,19082,19098,19097 ,0,0,0}, {34942,34943,34940 ,19099,19100,18906 ,0,0,0}, - {34940,34941,34942 ,18906,19098,19099 ,0,0,0}, {34943,34944,34945 ,19100,19101,19102 ,0,0,0}, - {34944,34943,34942 ,19101,19100,19099 ,0,0,0}, {34946,34945,34947 ,18784,19102,19103 ,0,0,0}, - {34944,34947,34945 ,19101,19103,19102 ,0,0,0}, {34948,34949,34946 ,18761,19104,18784 ,0,0,0}, - {34946,34947,34948 ,18784,19103,18761 ,0,0,0}, {34949,34950,34951 ,19104,19105,3343 ,0,0,0}, - {34950,34949,34948 ,19105,19104,18761 ,0,0,0}, {34950,34952,34951 ,19105,3370,3343 ,0,0,0}, - {34953,34954,34955 ,19106,19107,19108 ,0,0,0}, {34956,34957,34958 ,19109,19110,19111 ,0,0,0}, - {34959,34953,34955 ,19112,19106,19108 ,0,0,0}, {34956,34958,34960 ,19109,19111,19113 ,0,0,0}, - {34957,34956,34959 ,19110,19109,19112 ,0,0,0}, {34957,34959,34955 ,19110,19112,19108 ,0,0,0}, - {34961,34962,34963 ,19114,126,19115 ,0,0,0}, {34963,34960,34964 ,19115,19113,19116 ,0,0,0}, - {34961,34963,34964 ,19114,19115,19116 ,0,0,0}, {34962,34961,34965 ,126,19114,18751 ,0,0,0}, - {34964,34960,34958 ,19116,19113,19111 ,0,0,0}, {34953,34966,34954 ,19106,19117,19107 ,0,0,0}, - {34967,34966,34968 ,19118,19117,19119 ,0,0,0}, {34966,34967,34954 ,19117,19118,19107 ,0,0,0}, - {34969,34970,34968 ,19120,19121,19119 ,0,0,0}, {34967,34968,34970 ,19118,19119,19121 ,0,0,0}, - {34969,34971,34972 ,19120,19122,19123 ,0,0,0}, {34972,34970,34969 ,19123,19121,19120 ,0,0,0}, - {34973,34971,34974 ,793,19122,18961 ,0,0,0}, {34971,34973,34972 ,19122,793,19123 ,0,0,0}, - {34975,34976,34977 ,19124,19125,19126 ,0,0,0}, {34978,34979,34980 ,19127,19128,19129 ,0,0,0}, - {34981,34975,34977 ,19130,19124,19126 ,0,0,0}, {34978,34980,34982 ,19127,19129,19131 ,0,0,0}, - {34979,34978,34981 ,19128,19127,19130 ,0,0,0}, {34979,34981,34977 ,19128,19130,19126 ,0,0,0}, - {34983,34984,34985 ,19132,126,19133 ,0,0,0}, {34985,34982,34986 ,19133,19131,19134 ,0,0,0}, - {34983,34985,34986 ,19132,19133,19134 ,0,0,0}, {34984,34983,34987 ,126,19132,8371 ,0,0,0}, - {34986,34982,34980 ,19134,19131,19129 ,0,0,0}, {34975,34988,34976 ,19124,19135,19125 ,0,0,0}, - {34989,34988,34990 ,19136,19135,19137 ,0,0,0}, {34988,34989,34976 ,19135,19136,19125 ,0,0,0}, - {34991,34992,34990 ,19138,19139,19137 ,0,0,0}, {34989,34990,34992 ,19136,19137,19139 ,0,0,0}, - {34991,34993,34994 ,19138,19140,19141 ,0,0,0}, {34994,34992,34991 ,19141,19139,19138 ,0,0,0}, - {34995,34993,34996 ,19142,19140,18961 ,0,0,0}, {34993,34995,34994 ,19140,19142,19141 ,0,0,0}, - {34997,34998,34999 ,19143,19144,19145 ,0,0,0}, {35000,35001,35002 ,19146,19147,19148 ,0,0,0}, - {35003,34997,34999 ,19149,19143,19145 ,0,0,0}, {35000,35002,35004 ,19146,19148,19150 ,0,0,0}, - {35001,35000,35003 ,19147,19146,19149 ,0,0,0}, {35001,35003,34999 ,19147,19149,19145 ,0,0,0}, - {35005,35006,35007 ,19151,35,19152 ,0,0,0}, {35007,35004,35008 ,19152,19150,19153 ,0,0,0}, - {35005,35007,35008 ,19151,19152,19153 ,0,0,0}, {35006,35005,35009 ,35,19151,40 ,0,0,0}, - {35008,35004,35002 ,19153,19150,19148 ,0,0,0}, {34997,35010,34998 ,19143,19154,19144 ,0,0,0}, - {35011,35010,35012 ,19155,19154,19156 ,0,0,0}, {35010,35011,34998 ,19154,19155,19144 ,0,0,0}, - {35013,35014,35012 ,19157,19158,19156 ,0,0,0}, {35011,35012,35014 ,19155,19156,19158 ,0,0,0}, - {35013,35015,35016 ,19157,19159,19160 ,0,0,0}, {35016,35014,35013 ,19160,19158,19157 ,0,0,0}, - {35017,35015,35018 ,19161,19159,82 ,0,0,0}, {35015,35017,35016 ,19159,19161,19160 ,0,0,0}, - {35019,35020,35021 ,19162,19163,19164 ,0,0,0}, {35022,35023,35024 ,19165,19166,19167 ,0,0,0}, - {35025,35019,35021 ,19168,19162,19164 ,0,0,0}, {35022,35024,35026 ,19165,19167,19169 ,0,0,0}, - {35023,35022,35025 ,19166,19165,19168 ,0,0,0}, {35023,35025,35021 ,19166,19168,19164 ,0,0,0}, - {35027,35028,35029 ,19170,35,19171 ,0,0,0}, {35029,35026,35030 ,19171,19169,19172 ,0,0,0}, - {35027,35029,35030 ,19170,19171,19172 ,0,0,0}, {35028,35027,35031 ,35,19170,40 ,0,0,0}, - {35030,35026,35024 ,19172,19169,19167 ,0,0,0}, {35019,35032,35020 ,19162,19154,19163 ,0,0,0}, - {35033,35032,35034 ,19173,19154,19174 ,0,0,0}, {35032,35033,35020 ,19154,19173,19163 ,0,0,0}, - {35035,35036,35034 ,19175,19176,19174 ,0,0,0}, {35033,35034,35036 ,19173,19174,19176 ,0,0,0}, - {35035,35037,35038 ,19175,19159,19177 ,0,0,0}, {35038,35036,35035 ,19177,19176,19175 ,0,0,0}, - {35039,35037,35040 ,19161,19159,82 ,0,0,0}, {35037,35039,35038 ,19159,19161,19177 ,0,0,0}, - {35041,35042,35043 ,19106,19178,19108 ,0,0,0}, {35044,35045,35046 ,19179,19180,19181 ,0,0,0}, - {35047,35041,35043 ,19112,19106,19108 ,0,0,0}, {35044,35046,35048 ,19179,19181,19182 ,0,0,0}, - {35045,35044,35047 ,19180,19179,19112 ,0,0,0}, {35045,35047,35043 ,19180,19112,19108 ,0,0,0}, - {35049,35050,35051 ,19183,19184,19185 ,0,0,0}, {35051,35048,35052 ,19185,19182,19186 ,0,0,0}, - {35049,35051,35052 ,19183,19185,19186 ,0,0,0}, {35050,35049,35053 ,19184,19183,19187 ,0,0,0}, - {35052,35048,35046 ,19186,19182,19181 ,0,0,0}, {35041,35054,35042 ,19106,19188,19178 ,0,0,0}, - {35055,35054,35056 ,19189,19188,19190 ,0,0,0}, {35054,35055,35042 ,19188,19189,19178 ,0,0,0}, - {35057,35058,35056 ,19120,19191,19190 ,0,0,0}, {35055,35056,35058 ,19189,19190,19191 ,0,0,0}, - {35057,35059,35060 ,19120,19192,19193 ,0,0,0}, {35060,35058,35057 ,19193,19191,19120 ,0,0,0}, - {35061,35059,35062 ,19142,19192,18961 ,0,0,0}, {35059,35061,35060 ,19192,19142,19193 ,0,0,0}, - {35063,35064,35065 ,19194,19195,19196 ,0,0,0}, {35066,35067,35068 ,19197,19198,19199 ,0,0,0}, - {35069,35063,35065 ,19200,19194,19196 ,0,0,0}, {35066,35068,35070 ,19197,19199,19201 ,0,0,0}, - {35067,35066,35069 ,19198,19197,19200 ,0,0,0}, {35067,35069,35065 ,19198,19200,19196 ,0,0,0}, - {35071,35072,35073 ,19202,35,19203 ,0,0,0}, {35073,35070,35074 ,19203,19201,19204 ,0,0,0}, - {35071,35073,35074 ,19202,19203,19204 ,0,0,0}, {35072,35071,35075 ,35,19202,40 ,0,0,0}, - {35074,35070,35068 ,19204,19201,19199 ,0,0,0}, {35063,35076,35064 ,19194,19205,19195 ,0,0,0}, - {35077,35076,35078 ,19206,19205,19207 ,0,0,0}, {35076,35077,35064 ,19205,19206,19195 ,0,0,0}, - {35079,35080,35078 ,19157,19176,19207 ,0,0,0}, {35077,35078,35080 ,19206,19207,19176 ,0,0,0}, - {35079,35081,35082 ,19157,19159,8359 ,0,0,0}, {35082,35080,35079 ,8359,19176,19157 ,0,0,0}, - {35083,35081,35084 ,19161,19159,82 ,0,0,0}, {35081,35083,35082 ,19159,19161,8359 ,0,0,0}, - {35085,35086,35087 ,19208,19209,19210 ,0,0,0}, {35088,35089,35090 ,19197,19166,19211 ,0,0,0}, - {35091,35085,35087 ,19212,19208,19210 ,0,0,0}, {35088,35090,35092 ,19197,19211,19213 ,0,0,0}, - {35089,35088,35091 ,19166,19197,19212 ,0,0,0}, {35089,35091,35087 ,19166,19212,19210 ,0,0,0}, - {35093,35094,35095 ,19214,35,19215 ,0,0,0}, {35095,35092,35096 ,19215,19213,19216 ,0,0,0}, - {35093,35095,35096 ,19214,19215,19216 ,0,0,0}, {35094,35093,35097 ,35,19214,40 ,0,0,0}, - {35096,35092,35090 ,19216,19213,19211 ,0,0,0}, {35085,35098,35086 ,19208,19217,19209 ,0,0,0}, - {35099,35098,35100 ,19206,19217,19218 ,0,0,0}, {35098,35099,35086 ,19217,19206,19209 ,0,0,0}, - {35101,35102,35100 ,19157,8360,19218 ,0,0,0}, {35099,35100,35102 ,19206,19218,8360 ,0,0,0}, - {35101,35103,35104 ,19157,19159,19160 ,0,0,0}, {35104,35102,35101 ,19160,8360,19157 ,0,0,0}, - {35105,35103,35106 ,19161,19159,82 ,0,0,0}, {35103,35105,35104 ,19159,19161,19160 ,0,0,0}, - {35107,35108,35109 ,19124,19219,19126 ,0,0,0}, {35110,35111,35112 ,19220,19221,19222 ,0,0,0}, - {35113,35107,35109 ,19223,19124,19126 ,0,0,0}, {35110,35112,35114 ,19220,19222,19224 ,0,0,0}, - {35111,35110,35113 ,19221,19220,19223 ,0,0,0}, {35111,35113,35109 ,19221,19223,19126 ,0,0,0}, - {35115,35116,35117 ,19225,126,19226 ,0,0,0}, {35117,35114,35118 ,19226,19224,19227 ,0,0,0}, - {35115,35117,35118 ,19225,19226,19227 ,0,0,0}, {35116,35115,35119 ,126,19225,18751 ,0,0,0}, - {35118,35114,35112 ,19227,19224,19222 ,0,0,0}, {35107,35120,35108 ,19124,19228,19219 ,0,0,0}, - {35121,35120,35122 ,19229,19228,19230 ,0,0,0}, {35120,35121,35108 ,19228,19229,19219 ,0,0,0}, - {35123,35124,35122 ,19231,19232,19230 ,0,0,0}, {35121,35122,35124 ,19229,19230,19232 ,0,0,0}, - {35123,35125,35126 ,19231,19140,19233 ,0,0,0}, {35126,35124,35123 ,19233,19232,19231 ,0,0,0}, - {35127,35125,35128 ,19234,19140,18763 ,0,0,0}, {35125,35127,35126 ,19140,19234,19233 ,0,0,0}, - {35129,35130,35131 ,19235,19236,19237 ,0,0,0}, {35132,35133,35134 ,19238,19239,19240 ,0,0,0}, - {35135,35133,35136 ,19241,19239,19242 ,0,0,0}, {35132,35136,35133 ,19238,19242,19239 ,0,0,0}, - {35137,35132,35134 ,19243,19238,19240 ,0,0,0}, {35137,35138,35139 ,19243,19244,19245 ,0,0,0}, - {35138,35140,35139 ,19244,19246,19245 ,0,0,0}, {35139,35140,35141 ,19245,19246,19247 ,0,0,0}, - {35141,35142,35143 ,19247,19248,19249 ,0,0,0}, {35141,35140,35142 ,19247,19246,19248 ,0,0,0}, - {35144,35145,35146 ,19250,19251,19252 ,0,0,0}, {35147,35143,35142 ,19253,19249,19248 ,0,0,0}, - {35145,35148,35146 ,19251,19254,19252 ,0,0,0}, {35147,35148,35149 ,19253,19254,19255 ,0,0,0}, - {35143,35147,35149 ,19249,19253,19255 ,0,0,0}, {35149,35148,35145 ,19255,19254,19251 ,0,0,0}, - {35150,35151,35152 ,19256,19257,19258 ,0,0,0}, {35146,35151,35144 ,19252,19257,19250 ,0,0,0}, - {35150,35152,35153 ,19256,19258,19259 ,0,0,0}, {35151,35150,35144 ,19257,19256,19250 ,0,0,0}, - {35138,35137,35134 ,19244,19243,19240 ,0,0,0}, {35154,35155,35156 ,19260,19261,19262 ,0,0,0}, - {35155,35153,35156 ,19261,19259,19262 ,0,0,0}, {35157,35158,35159 ,19263,19264,19265 ,0,0,0}, - {35157,35155,35154 ,19263,19261,19260 ,0,0,0}, {35160,35159,35158 ,19266,19265,19264 ,0,0,0}, - {35154,35158,35157 ,19260,19264,19263 ,0,0,0}, {35161,35162,35160 ,19267,19268,19266 ,0,0,0}, - {35162,35159,35160 ,19268,19265,19266 ,0,0,0}, {35163,35164,35165 ,19269,19270,19271 ,0,0,0}, - {35166,35167,35168 ,19272,19273,19274 ,0,0,0}, {35169,35161,35170 ,19275,19267,19276 ,0,0,0}, - {35171,35167,35166 ,19277,19273,19272 ,0,0,0}, {35168,35170,35166 ,19274,19276,19272 ,0,0,0}, - {35171,35172,35167 ,19277,19278,19273 ,0,0,0}, {35169,35170,35168 ,19275,19276,19274 ,0,0,0}, - {35171,35173,35172 ,19277,19279,19278 ,0,0,0}, {35174,35173,35175 ,19280,19279,19281 ,0,0,0}, - {35174,35175,35176 ,19280,19281,19282 ,0,0,0}, {35164,35163,35176 ,19270,19269,19282 ,0,0,0}, - {35173,35174,35172 ,19279,19280,19278 ,0,0,0}, {35164,35176,35175 ,19270,19282,19281 ,0,0,0}, - {35177,35178,35179 ,19283,19284,19285 ,0,0,0}, {35180,35165,35177 ,19286,19271,19283 ,0,0,0}, - {35163,35165,35180 ,19269,19271,19286 ,0,0,0}, {35162,35161,35169 ,19268,19267,19275 ,0,0,0}, - {35180,35177,35179 ,19286,19283,19285 ,0,0,0}, {35179,35178,35181 ,19285,19284,82 ,0,0,0}, - {35178,35182,35181 ,19284,19287,82 ,0,0,0}, {35152,35156,35153 ,19258,19262,19259 ,0,0,0}, - {35183,35135,35136 ,19288,19241,19242 ,0,0,0}, {35183,35184,35185 ,19288,19289,19290 ,0,0,0}, - {35185,35135,35183 ,19290,19241,19288 ,0,0,0}, {35186,35184,35187 ,19291,19289,19292 ,0,0,0}, - {35184,35186,35185 ,19289,19291,19290 ,0,0,0}, {35188,35189,35187 ,19293,19294,19292 ,0,0,0}, - {35186,35187,35189 ,19291,19292,19294 ,0,0,0}, {35188,35190,35191 ,19293,19295,19296 ,0,0,0}, - {35191,35189,35188 ,19296,19294,19293 ,0,0,0}, {35192,35190,35193 ,19297,19295,19298 ,0,0,0}, - {35190,35192,35191 ,19295,19297,19296 ,0,0,0}, {35194,35195,35193 ,19299,19300,19298 ,0,0,0}, - {35192,35193,35195 ,19297,19298,19300 ,0,0,0}, {35194,35196,35197 ,19299,19301,19302 ,0,0,0}, - {35197,35195,35194 ,19302,19300,19299 ,0,0,0}, {35198,35196,35199 ,19303,19301,19304 ,0,0,0}, - {35196,35198,35197 ,19301,19303,19302 ,0,0,0}, {35200,35201,35199 ,19305,19306,19304 ,0,0,0}, - {35198,35199,35201 ,19303,19304,19306 ,0,0,0}, {35200,35202,35203 ,19305,19307,19308 ,0,0,0}, - {35203,35201,35200 ,19308,19306,19305 ,0,0,0}, {35204,35202,35205 ,19309,19307,19310 ,0,0,0}, - {35202,35204,35203 ,19307,19309,19308 ,0,0,0}, {35131,35130,35205 ,19237,19236,19310 ,0,0,0}, - {35204,35205,35130 ,19309,19310,19236 ,0,0,0}, {35129,35131,35206 ,19235,19237,19311 ,0,0,0}, - {35206,35207,35208 ,19311,19312,19313 ,0,0,0}, {35208,35129,35206 ,19313,19235,19311 ,0,0,0}, - {35209,35207,35210 ,19314,19312,19315 ,0,0,0}, {35207,35209,35208 ,19312,19314,19313 ,0,0,0}, - {35211,35212,35210 ,19316,19317,19315 ,0,0,0}, {35209,35210,35212 ,19314,19315,19317 ,0,0,0}, - {35211,35213,35214 ,19316,19318,19319 ,0,0,0}, {35214,35212,35211 ,19319,19317,19316 ,0,0,0}, - {35215,35213,35216 ,19320,19318,19321 ,0,0,0}, {35213,35215,35214 ,19318,19320,19319 ,0,0,0}, - {35217,35218,35216 ,19322,19323,19321 ,0,0,0}, {35215,35216,35218 ,19320,19321,19323 ,0,0,0}, - {35217,35219,35220 ,19322,19324,19325 ,0,0,0}, {35220,35218,35217 ,19325,19323,19322 ,0,0,0}, - {35221,35219,35222 ,19326,19324,19327 ,0,0,0}, {35219,35221,35220 ,19324,19326,19325 ,0,0,0}, - {35223,35224,35222 ,19328,19329,19327 ,0,0,0}, {35221,35222,35224 ,19326,19327,19329 ,0,0,0}, - {35223,35225,35226 ,19328,19330,19331 ,0,0,0}, {35226,35224,35223 ,19331,19329,19328 ,0,0,0}, - {35227,35225,35228 ,19332,19330,19332 ,0,0,0}, {35225,35227,35226 ,19330,19332,19331 ,0,0,0}, - {35229,35230,35231 ,19333,19334,19335 ,0,0,0}, {35232,35233,35234 ,19336,19337,19338 ,0,0,0}, - {35235,35233,35236 ,19339,19337,19340 ,0,0,0}, {35232,35236,35233 ,19336,19340,19337 ,0,0,0}, - {35237,35232,35234 ,19341,19336,19338 ,0,0,0}, {35237,35238,35239 ,19341,19342,19343 ,0,0,0}, - {35238,35240,35239 ,19342,19344,19343 ,0,0,0}, {35239,35240,35241 ,19343,19344,19345 ,0,0,0}, - {35241,35242,35243 ,19345,19346,19347 ,0,0,0}, {35241,35240,35242 ,19345,19344,19346 ,0,0,0}, - {35244,35245,35246 ,19348,19349,19350 ,0,0,0}, {35247,35243,35242 ,19351,19347,19346 ,0,0,0}, - {35245,35248,35246 ,19349,19352,19350 ,0,0,0}, {35247,35248,35249 ,19351,19352,19353 ,0,0,0}, - {35243,35247,35249 ,19347,19351,19353 ,0,0,0}, {35249,35248,35245 ,19353,19352,19349 ,0,0,0}, - {35250,35251,35252 ,19354,19355,19356 ,0,0,0}, {35246,35251,35244 ,19350,19355,19348 ,0,0,0}, - {35250,35252,35253 ,19354,19356,19357 ,0,0,0}, {35251,35250,35244 ,19355,19354,19348 ,0,0,0}, - {35238,35237,35234 ,19342,19341,19338 ,0,0,0}, {35254,35255,35256 ,19358,19359,19360 ,0,0,0}, - {35255,35253,35256 ,19359,19357,19360 ,0,0,0}, {35257,35258,35259 ,19361,19362,19363 ,0,0,0}, - {35257,35255,35254 ,19361,19359,19358 ,0,0,0}, {35260,35259,35258 ,19364,19363,19362 ,0,0,0}, - {35254,35258,35257 ,19358,19362,19361 ,0,0,0}, {35261,35262,35260 ,19365,19366,19364 ,0,0,0}, - {35262,35259,35260 ,19366,19363,19364 ,0,0,0}, {35263,35264,35265 ,19367,19368,19369 ,0,0,0}, - {35266,35267,35268 ,19370,19371,19372 ,0,0,0}, {35269,35261,35270 ,19373,19365,19374 ,0,0,0}, - {35271,35267,35266 ,19375,19371,19370 ,0,0,0}, {35268,35270,35266 ,19372,19374,19370 ,0,0,0}, - {35271,35272,35267 ,19375,19376,19371 ,0,0,0}, {35269,35270,35268 ,19373,19374,19372 ,0,0,0}, - {35271,35273,35272 ,19375,19377,19376 ,0,0,0}, {35274,35273,35275 ,19378,19377,19379 ,0,0,0}, - {35274,35275,35276 ,19378,19379,19380 ,0,0,0}, {35264,35263,35276 ,19368,19367,19380 ,0,0,0}, - {35273,35274,35272 ,19377,19378,19376 ,0,0,0}, {35264,35276,35275 ,19368,19380,19379 ,0,0,0}, - {35277,35278,35279 ,19381,19382,19383 ,0,0,0}, {35280,35265,35277 ,19384,19369,19381 ,0,0,0}, - {35263,35265,35280 ,19367,19369,19384 ,0,0,0}, {35262,35261,35269 ,19366,19365,19373 ,0,0,0}, - {35280,35277,35279 ,19384,19381,19383 ,0,0,0}, {35279,35278,35281 ,19383,19382,82 ,0,0,0}, - {35278,35282,35281 ,19382,19287,82 ,0,0,0}, {35252,35256,35253 ,19356,19360,19357 ,0,0,0}, - {35283,35235,35236 ,19385,19339,19340 ,0,0,0}, {35283,35284,35285 ,19385,19386,19387 ,0,0,0}, - {35285,35235,35283 ,19387,19339,19385 ,0,0,0}, {35286,35284,35287 ,19388,19386,19389 ,0,0,0}, - {35284,35286,35285 ,19386,19388,19387 ,0,0,0}, {35288,35289,35287 ,19390,19391,19389 ,0,0,0}, - {35286,35287,35289 ,19388,19389,19391 ,0,0,0}, {35288,35290,35291 ,19390,19392,19393 ,0,0,0}, - {35291,35289,35288 ,19393,19391,19390 ,0,0,0}, {35292,35290,35293 ,19394,19392,19395 ,0,0,0}, - {35290,35292,35291 ,19392,19394,19393 ,0,0,0}, {35294,35295,35293 ,19396,19397,19395 ,0,0,0}, - {35292,35293,35295 ,19394,19395,19397 ,0,0,0}, {35294,35296,35297 ,19396,19398,19399 ,0,0,0}, - {35297,35295,35294 ,19399,19397,19396 ,0,0,0}, {35298,35296,35299 ,19400,19398,19401 ,0,0,0}, - {35296,35298,35297 ,19398,19400,19399 ,0,0,0}, {35300,35301,35299 ,19402,19403,19401 ,0,0,0}, - {35298,35299,35301 ,19400,19401,19403 ,0,0,0}, {35300,35302,35303 ,19402,19404,19405 ,0,0,0}, - {35303,35301,35300 ,19405,19403,19402 ,0,0,0}, {35304,35302,35305 ,19406,19404,19407 ,0,0,0}, - {35302,35304,35303 ,19404,19406,19405 ,0,0,0}, {35231,35230,35305 ,19335,19334,19407 ,0,0,0}, - {35304,35305,35230 ,19406,19407,19334 ,0,0,0}, {35229,35231,35306 ,19333,19335,19408 ,0,0,0}, - {35306,35307,35308 ,19408,19409,19410 ,0,0,0}, {35308,35229,35306 ,19410,19333,19408 ,0,0,0}, - {35309,35307,35310 ,19411,19409,19412 ,0,0,0}, {35307,35309,35308 ,19409,19411,19410 ,0,0,0}, - {35311,35312,35310 ,19413,19317,19412 ,0,0,0}, {35309,35310,35312 ,19411,19412,19317 ,0,0,0}, - {35311,35313,35314 ,19413,19414,19415 ,0,0,0}, {35314,35312,35311 ,19415,19317,19413 ,0,0,0}, - {35315,35313,35316 ,19416,19414,19417 ,0,0,0}, {35313,35315,35314 ,19414,19416,19415 ,0,0,0}, - {35317,35318,35316 ,19418,19419,19417 ,0,0,0}, {35315,35316,35318 ,19416,19417,19419 ,0,0,0}, - {35317,35319,35320 ,19418,19420,19421 ,0,0,0}, {35320,35318,35317 ,19421,19419,19418 ,0,0,0}, - {35321,35319,35322 ,19422,19420,19423 ,0,0,0}, {35319,35321,35320 ,19420,19422,19421 ,0,0,0}, - {35323,35324,35322 ,19328,19424,19423 ,0,0,0}, {35321,35322,35324 ,19422,19423,19424 ,0,0,0}, - {35323,35325,35326 ,19328,19330,19425 ,0,0,0}, {35326,35324,35323 ,19425,19424,19328 ,0,0,0}, - {35327,35325,35328 ,19332,19330,19332 ,0,0,0}, {35325,35327,35326 ,19330,19332,19425 ,0,0,0}, - {35329,35330,35331 ,19426,19427,19428 ,0,0,0}, {35332,35333,35334 ,19429,19430,19240 ,0,0,0}, - {35335,35333,35336 ,19431,19430,19432 ,0,0,0}, {35332,35336,35333 ,19429,19432,19430 ,0,0,0}, - {35337,35332,35334 ,19433,19429,19240 ,0,0,0}, {35337,35338,35339 ,19433,19434,19435 ,0,0,0}, - {35338,35340,35339 ,19434,19436,19435 ,0,0,0}, {35339,35340,35341 ,19435,19436,19437 ,0,0,0}, - {35341,35342,35343 ,19437,19438,19439 ,0,0,0}, {35341,35340,35342 ,19437,19436,19438 ,0,0,0}, - {35344,35345,35346 ,19440,19441,19442 ,0,0,0}, {35347,35343,35342 ,19443,19439,19438 ,0,0,0}, - {35345,35348,35346 ,19441,19444,19442 ,0,0,0}, {35347,35348,35349 ,19443,19444,19445 ,0,0,0}, - {35343,35347,35349 ,19439,19443,19445 ,0,0,0}, {35349,35348,35345 ,19445,19444,19441 ,0,0,0}, - {35350,35351,35352 ,19446,19447,19448 ,0,0,0}, {35346,35351,35344 ,19442,19447,19440 ,0,0,0}, - {35350,35352,35353 ,19446,19448,19449 ,0,0,0}, {35351,35350,35344 ,19447,19446,19440 ,0,0,0}, - {35338,35337,35334 ,19434,19433,19240 ,0,0,0}, {35354,35355,35356 ,19450,19451,19452 ,0,0,0}, - {35355,35353,35356 ,19451,19449,19452 ,0,0,0}, {35357,35358,35359 ,19453,19454,19455 ,0,0,0}, - {35357,35355,35354 ,19453,19451,19450 ,0,0,0}, {35360,35359,35358 ,19456,19455,19454 ,0,0,0}, - {35354,35358,35357 ,19450,19454,19453 ,0,0,0}, {35361,35362,35360 ,19457,19458,19456 ,0,0,0}, - {35362,35359,35360 ,19458,19455,19456 ,0,0,0}, {35363,35364,35365 ,19459,19460,19461 ,0,0,0}, - {35366,35367,35368 ,19462,19463,19464 ,0,0,0}, {35369,35361,35370 ,19465,19457,19466 ,0,0,0}, - {35371,35367,35366 ,19467,19463,19462 ,0,0,0}, {35368,35370,35366 ,19464,19466,19462 ,0,0,0}, - {35371,35372,35367 ,19467,19468,19463 ,0,0,0}, {35369,35370,35368 ,19465,19466,19464 ,0,0,0}, - {35371,35373,35372 ,19467,19469,19468 ,0,0,0}, {35374,35373,35375 ,19470,19469,19471 ,0,0,0}, - {35374,35375,35376 ,19470,19471,19472 ,0,0,0}, {35364,35363,35376 ,19460,19459,19472 ,0,0,0}, - {35373,35374,35372 ,19469,19470,19468 ,0,0,0}, {35364,35376,35375 ,19460,19472,19471 ,0,0,0}, - {35377,35378,35379 ,19473,19474,19475 ,0,0,0}, {35380,35365,35377 ,19476,19461,19473 ,0,0,0}, - {35363,35365,35380 ,19459,19461,19476 ,0,0,0}, {35362,35361,35369 ,19458,19457,19465 ,0,0,0}, - {35380,35377,35379 ,19476,19473,19475 ,0,0,0}, {35379,35378,35381 ,19475,19474,19477 ,0,0,0}, - {35378,35382,35381 ,19474,19478,19477 ,0,0,0}, {35352,35356,35353 ,19448,19452,19449 ,0,0,0}, - {35383,35335,35336 ,19479,19431,19432 ,0,0,0}, {35383,35384,35385 ,19479,19480,19481 ,0,0,0}, - {35385,35335,35383 ,19481,19431,19479 ,0,0,0}, {35386,35384,35387 ,19482,19480,19483 ,0,0,0}, - {35384,35386,35385 ,19480,19482,19481 ,0,0,0}, {35388,35389,35387 ,19484,19485,19483 ,0,0,0}, - {35386,35387,35389 ,19482,19483,19485 ,0,0,0}, {35388,35390,35391 ,19484,19486,19487 ,0,0,0}, - {35391,35389,35388 ,19487,19485,19484 ,0,0,0}, {35392,35390,35393 ,19488,19486,19489 ,0,0,0}, - {35390,35392,35391 ,19486,19488,19487 ,0,0,0}, {35394,35395,35393 ,19490,19491,19489 ,0,0,0}, - {35392,35393,35395 ,19488,19489,19491 ,0,0,0}, {35394,35396,35397 ,19490,19492,19493 ,0,0,0}, - {35397,35395,35394 ,19493,19491,19490 ,0,0,0}, {35398,35396,35399 ,19494,19492,19495 ,0,0,0}, - {35396,35398,35397 ,19492,19494,19493 ,0,0,0}, {35400,35401,35399 ,19496,19497,19495 ,0,0,0}, - {35398,35399,35401 ,19494,19495,19497 ,0,0,0}, {35400,35402,35403 ,19496,19498,19499 ,0,0,0}, - {35403,35401,35400 ,19499,19497,19496 ,0,0,0}, {35404,35402,35405 ,19500,19498,19501 ,0,0,0}, - {35402,35404,35403 ,19498,19500,19499 ,0,0,0}, {35331,35330,35405 ,19428,19427,19501 ,0,0,0}, - {35404,35405,35330 ,19500,19501,19427 ,0,0,0}, {35329,35331,35406 ,19426,19428,19502 ,0,0,0}, - {35406,35407,35408 ,19502,19503,19504 ,0,0,0}, {35408,35329,35406 ,19504,19426,19502 ,0,0,0}, - {35409,35407,35410 ,19505,19503,19506 ,0,0,0}, {35407,35409,35408 ,19503,19505,19504 ,0,0,0}, - {35411,35412,35410 ,19507,19508,19506 ,0,0,0}, {35409,35410,35412 ,19505,19506,19508 ,0,0,0}, - {35411,35413,35414 ,19507,19509,19510 ,0,0,0}, {35414,35412,35411 ,19510,19508,19507 ,0,0,0}, - {35415,35413,35416 ,19511,19509,19321 ,0,0,0}, {35413,35415,35414 ,19509,19511,19510 ,0,0,0}, - {35417,35418,35416 ,19512,19513,19321 ,0,0,0}, {35415,35416,35418 ,19511,19321,19513 ,0,0,0}, - {35417,35419,35420 ,19512,19324,19325 ,0,0,0}, {35420,35418,35417 ,19325,19513,19512 ,0,0,0}, - {35421,35419,35422 ,19326,19324,19514 ,0,0,0}, {35419,35421,35420 ,19324,19326,19325 ,0,0,0}, - {35423,35424,35422 ,19515,19329,19514 ,0,0,0}, {35421,35422,35424 ,19326,19514,19329 ,0,0,0}, - {35423,35425,35426 ,19515,19516,19517 ,0,0,0}, {35426,35424,35423 ,19517,19329,19515 ,0,0,0}, - {35427,35425,35428 ,19518,19516,126 ,0,0,0}, {35425,35427,35426 ,19516,19518,19517 ,0,0,0}, - {35429,35430,35431 ,19519,19520,19521 ,0,0,0}, {35432,35433,35434 ,19522,19523,19524 ,0,0,0}, - {35435,35433,35436 ,19525,19523,19526 ,0,0,0}, {35432,35436,35433 ,19522,19526,19523 ,0,0,0}, - {35437,35432,35434 ,19527,19522,19524 ,0,0,0}, {35437,35438,35439 ,19527,19528,19529 ,0,0,0}, - {35438,35440,35439 ,19528,19530,19529 ,0,0,0}, {35439,35440,35441 ,19529,19530,19531 ,0,0,0}, - {35441,35442,35443 ,19531,19532,19533 ,0,0,0}, {35441,35440,35442 ,19531,19530,19532 ,0,0,0}, - {35444,35445,35446 ,19534,19535,19536 ,0,0,0}, {35447,35443,35442 ,19537,19533,19532 ,0,0,0}, - {35445,35448,35446 ,19535,19538,19536 ,0,0,0}, {35447,35448,35449 ,19537,19538,19539 ,0,0,0}, - {35443,35447,35449 ,19533,19537,19539 ,0,0,0}, {35449,35448,35445 ,19539,19538,19535 ,0,0,0}, - {35450,35451,35452 ,19540,19541,19542 ,0,0,0}, {35446,35451,35444 ,19536,19541,19534 ,0,0,0}, - {35450,35452,35453 ,19540,19542,19543 ,0,0,0}, {35451,35450,35444 ,19541,19540,19534 ,0,0,0}, - {35438,35437,35434 ,19528,19527,19524 ,0,0,0}, {35454,35455,35456 ,19544,19545,19546 ,0,0,0}, - {35455,35453,35456 ,19545,19543,19546 ,0,0,0}, {35457,35458,35459 ,19547,19548,19549 ,0,0,0}, - {35457,35455,35454 ,19547,19545,19544 ,0,0,0}, {35460,35459,35458 ,19550,19549,19548 ,0,0,0}, - {35454,35458,35457 ,19544,19548,19547 ,0,0,0}, {35461,35462,35460 ,19551,19552,19550 ,0,0,0}, - {35462,35459,35460 ,19552,19549,19550 ,0,0,0}, {35463,35464,35465 ,19553,19554,19555 ,0,0,0}, - {35466,35467,35468 ,19556,19557,19558 ,0,0,0}, {35469,35461,35470 ,19559,19551,19560 ,0,0,0}, - {35471,35467,35466 ,19561,19557,19556 ,0,0,0}, {35468,35470,35466 ,19558,19560,19556 ,0,0,0}, - {35471,35472,35467 ,19561,19562,19557 ,0,0,0}, {35469,35470,35468 ,19559,19560,19558 ,0,0,0}, - {35471,35473,35472 ,19561,19563,19562 ,0,0,0}, {35474,35473,35475 ,19564,19563,19565 ,0,0,0}, - {35474,35475,35476 ,19564,19565,19566 ,0,0,0}, {35464,35463,35476 ,19554,19553,19566 ,0,0,0}, - {35473,35474,35472 ,19563,19564,19562 ,0,0,0}, {35464,35476,35475 ,19554,19566,19565 ,0,0,0}, - {35477,35478,35479 ,19567,19568,19569 ,0,0,0}, {35480,35465,35477 ,19570,19555,19567 ,0,0,0}, - {35463,35465,35480 ,19553,19555,19570 ,0,0,0}, {35462,35461,35469 ,19552,19551,19559 ,0,0,0}, - {35480,35477,35479 ,19570,19567,19569 ,0,0,0}, {35479,35478,35481 ,19569,19568,878 ,0,0,0}, - {35478,35482,35481 ,19568,19571,878 ,0,0,0}, {35452,35456,35453 ,19542,19546,19543 ,0,0,0}, - {35483,35435,35436 ,19572,19525,19526 ,0,0,0}, {35483,35484,35485 ,19572,19573,19387 ,0,0,0}, - {35485,35435,35483 ,19387,19525,19572 ,0,0,0}, {35486,35484,35487 ,19574,19573,19575 ,0,0,0}, - {35484,35486,35485 ,19573,19574,19387 ,0,0,0}, {35488,35489,35487 ,19576,19577,19575 ,0,0,0}, - {35486,35487,35489 ,19574,19575,19577 ,0,0,0}, {35488,35490,35491 ,19576,19578,19579 ,0,0,0}, - {35491,35489,35488 ,19579,19577,19576 ,0,0,0}, {35492,35490,35493 ,19580,19578,19581 ,0,0,0}, - {35490,35492,35491 ,19578,19580,19579 ,0,0,0}, {35494,35495,35493 ,19299,19582,19581 ,0,0,0}, - {35492,35493,35495 ,19580,19581,19582 ,0,0,0}, {35494,35496,35497 ,19299,19492,19583 ,0,0,0}, - {35497,35495,35494 ,19583,19582,19299 ,0,0,0}, {35498,35496,35499 ,19584,19492,19585 ,0,0,0}, - {35496,35498,35497 ,19492,19584,19583 ,0,0,0}, {35500,35501,35499 ,19586,19497,19585 ,0,0,0}, - {35498,35499,35501 ,19584,19585,19497 ,0,0,0}, {35500,35502,35503 ,19586,19587,19308 ,0,0,0}, - {35503,35501,35500 ,19308,19497,19586 ,0,0,0}, {35504,35502,35505 ,19588,19587,19589 ,0,0,0}, - {35502,35504,35503 ,19587,19588,19308 ,0,0,0}, {35431,35430,35505 ,19521,19520,19589 ,0,0,0}, - {35504,35505,35430 ,19588,19589,19520 ,0,0,0}, {35429,35431,35506 ,19519,19521,19590 ,0,0,0}, - {35506,35507,35508 ,19590,19591,19592 ,0,0,0}, {35508,35429,35506 ,19592,19519,19590 ,0,0,0}, - {35509,35507,35510 ,19593,19591,19506 ,0,0,0}, {35507,35509,35508 ,19591,19593,19592 ,0,0,0}, - {35511,35512,35510 ,19594,19595,19506 ,0,0,0}, {35509,35510,35512 ,19593,19506,19595 ,0,0,0}, - {35511,35513,35514 ,19594,19596,19597 ,0,0,0}, {35514,35512,35511 ,19597,19595,19594 ,0,0,0}, - {35515,35513,35516 ,19598,19596,19599 ,0,0,0}, {35513,35515,35514 ,19596,19598,19597 ,0,0,0}, - {35517,35518,35516 ,19600,19513,19599 ,0,0,0}, {35515,35516,35518 ,19598,19599,19513 ,0,0,0}, - {35517,35519,35520 ,19600,19601,19602 ,0,0,0}, {35520,35518,35517 ,19602,19513,19600 ,0,0,0}, - {35521,35519,35522 ,19326,19601,19603 ,0,0,0}, {35519,35521,35520 ,19601,19326,19602 ,0,0,0}, - {35523,35524,35522 ,19604,19605,19603 ,0,0,0}, {35521,35522,35524 ,19326,19603,19605 ,0,0,0}, - {35523,35525,35526 ,19604,19330,19517 ,0,0,0}, {35526,35524,35523 ,19517,19605,19604 ,0,0,0}, - {35527,35525,35528 ,19606,19330,126 ,0,0,0}, {35525,35527,35526 ,19330,19606,19517 ,0,0,0}, - {35529,35530,35531 ,19607,19608,19609 ,0,0,0}, {35529,35532,35533 ,19607,19610,19611 ,0,0,0}, - {35532,35534,35533 ,19610,19612,19611 ,0,0,0}, {35531,35532,35529 ,19609,19610,19607 ,0,0,0}, - {35535,35536,35537 ,19613,19614,19615 ,0,0,0}, {35534,35535,35537 ,19612,19613,19615 ,0,0,0}, - {35536,35538,35539 ,19614,19616,19617 ,0,0,0}, {35538,35536,35535 ,19616,19614,19613 ,0,0,0}, - {35539,35538,35540 ,19617,19616,19618 ,0,0,0}, {35541,35539,35540 ,19619,19617,19618 ,0,0,0}, - {35541,35542,35543 ,19619,19620,19621 ,0,0,0}, {35541,35540,35542 ,19619,19618,19620 ,0,0,0}, - {35537,35533,35534 ,19615,19611,19612 ,0,0,0}, {35544,35545,33824 ,19622,19623,126 ,0,0,0}, - {35544,33824,35543 ,19622,126,19621 ,0,0,0}, {35542,35544,35543 ,19620,19622,19621 ,0,0,0}, - {35531,35530,35546 ,19609,19608,18805 ,0,0,0}, {35547,35546,35548 ,19624,18805,19625 ,0,0,0}, - {35530,35548,35546 ,19608,19625,18805 ,0,0,0}, {35549,35550,35547 ,19626,19627,19624 ,0,0,0}, - {35547,35548,35549 ,19624,19625,19626 ,0,0,0}, {35550,35551,35552 ,19627,19628,19629 ,0,0,0}, - {35551,35550,35549 ,19628,19627,19626 ,0,0,0}, {35553,35552,35554 ,19630,19629,19631 ,0,0,0}, - {35551,35554,35552 ,19628,19631,19629 ,0,0,0}, {35555,35556,35553 ,19632,18067,19630 ,0,0,0}, - {35553,35554,35555 ,19630,19631,19632 ,0,0,0}, {35556,35557,35558 ,18067,18838,19633 ,0,0,0}, - {35557,35556,35555 ,18838,18067,19632 ,0,0,0}, {35557,33841,35558 ,18838,82,19633 ,0,0,0}, - {35559,35560,35561 ,19634,19635,19636 ,0,0,0}, {35559,35562,35563 ,19634,19637,19638 ,0,0,0}, - {35562,35564,35563 ,19637,19639,19638 ,0,0,0}, {35561,35562,35559 ,19636,19637,19634 ,0,0,0}, - {35565,35566,35567 ,19640,19614,19641 ,0,0,0}, {35564,35565,35567 ,19639,19640,19641 ,0,0,0}, - {35566,35568,35569 ,19614,19642,19643 ,0,0,0}, {35568,35566,35565 ,19642,19614,19640 ,0,0,0}, - {35569,35568,35570 ,19643,19642,19644 ,0,0,0}, {35571,35569,35570 ,19645,19643,19644 ,0,0,0}, - {35571,35572,35573 ,19645,19646,19647 ,0,0,0}, {35571,35570,35572 ,19645,19644,19646 ,0,0,0}, - {35567,35563,35564 ,19641,19638,19639 ,0,0,0}, {35574,35575,33192 ,19648,19649,126 ,0,0,0}, - {35574,33192,35573 ,19648,126,19647 ,0,0,0}, {35572,35574,35573 ,19646,19648,19647 ,0,0,0}, - {35561,35560,35576 ,19636,19635,19650 ,0,0,0}, {35577,35576,35578 ,19624,19650,19651 ,0,0,0}, - {35560,35578,35576 ,19635,19651,19650 ,0,0,0}, {35579,35580,35577 ,19626,19627,19624 ,0,0,0}, - {35577,35578,35579 ,19624,19651,19626 ,0,0,0}, {35580,35581,35582 ,19627,19628,19629 ,0,0,0}, - {35581,35580,35579 ,19628,19627,19626 ,0,0,0}, {35583,35582,35584 ,19630,19629,19652 ,0,0,0}, - {35581,35584,35582 ,19628,19652,19629 ,0,0,0}, {35585,35586,35583 ,19653,18067,19630 ,0,0,0}, - {35583,35584,35585 ,19630,19652,19653 ,0,0,0}, {35586,35587,35588 ,18067,19654,19655 ,0,0,0}, - {35587,35586,35585 ,19654,18067,19653 ,0,0,0}, {35587,33209,35588 ,19654,82,19655 ,0,0,0}, - {35589,35590,35591 ,19656,19657,19658 ,0,0,0}, {35589,35592,35593 ,19656,19659,19660 ,0,0,0}, - {35592,35594,35593 ,19659,19612,19660 ,0,0,0}, {35591,35592,35589 ,19658,19659,19656 ,0,0,0}, - {35595,35596,35597 ,19661,19662,19663 ,0,0,0}, {35594,35595,35597 ,19612,19661,19663 ,0,0,0}, - {35596,35598,35599 ,19662,19664,19665 ,0,0,0}, {35598,35596,35595 ,19664,19662,19661 ,0,0,0}, - {35599,35598,35600 ,19665,19664,19666 ,0,0,0}, {35601,35599,35600 ,19667,19665,19666 ,0,0,0}, - {35601,35602,35603 ,19667,19668,19669 ,0,0,0}, {35601,35600,35602 ,19667,19666,19668 ,0,0,0}, - {35597,35593,35594 ,19663,19660,19612 ,0,0,0}, {35604,35605,32876 ,19670,19623,126 ,0,0,0}, - {35604,32876,35603 ,19670,126,19669 ,0,0,0}, {35602,35604,35603 ,19668,19670,19669 ,0,0,0}, - {35591,35590,35606 ,19658,19657,19671 ,0,0,0}, {35607,35606,35608 ,19672,19671,19673 ,0,0,0}, - {35590,35608,35606 ,19657,19673,19671 ,0,0,0}, {35609,35610,35607 ,19626,19674,19672 ,0,0,0}, - {35607,35608,35609 ,19672,19673,19626 ,0,0,0}, {35610,35611,35612 ,19674,19675,19629 ,0,0,0}, - {35611,35610,35609 ,19675,19674,19626 ,0,0,0}, {35613,35612,35614 ,19676,19629,19677 ,0,0,0}, - {35611,35614,35612 ,19675,19677,19629 ,0,0,0}, {35615,35616,35613 ,19632,18067,19676 ,0,0,0}, - {35613,35614,35615 ,19676,19677,19632 ,0,0,0}, {35616,35617,35618 ,18067,18838,19633 ,0,0,0}, - {35617,35616,35615 ,18838,18067,19632 ,0,0,0}, {35617,32893,35618 ,18838,82,19633 ,0,0,0}, - {35619,35620,35621 ,19678,19679,19680 ,0,0,0}, {35619,35622,35623 ,19678,19681,19682 ,0,0,0}, - {35622,35624,35623 ,19681,19639,19682 ,0,0,0}, {35621,35622,35619 ,19680,19681,19678 ,0,0,0}, - {35625,35626,35627 ,19683,19662,19684 ,0,0,0}, {35624,35625,35627 ,19639,19683,19684 ,0,0,0}, - {35626,35628,35629 ,19662,19685,19686 ,0,0,0}, {35628,35626,35625 ,19685,19662,19683 ,0,0,0}, - {35629,35628,35630 ,19686,19685,19687 ,0,0,0}, {35631,35629,35630 ,19688,19686,19687 ,0,0,0}, - {35631,35632,35633 ,19688,19689,19690 ,0,0,0}, {35631,35630,35632 ,19688,19687,19689 ,0,0,0}, - {35627,35623,35624 ,19684,19682,19639 ,0,0,0}, {35634,35635,33508 ,19691,19649,126 ,0,0,0}, - {35634,33508,35633 ,19691,126,19690 ,0,0,0}, {35632,35634,35633 ,19689,19691,19690 ,0,0,0}, - {35621,35620,35636 ,19680,19679,19692 ,0,0,0}, {35637,35636,35638 ,19672,19692,19693 ,0,0,0}, - {35620,35638,35636 ,19679,19693,19692 ,0,0,0}, {35639,35640,35637 ,19626,19674,19672 ,0,0,0}, - {35637,35638,35639 ,19672,19693,19626 ,0,0,0}, {35640,35641,35642 ,19674,19675,19629 ,0,0,0}, - {35641,35640,35639 ,19675,19674,19626 ,0,0,0}, {35643,35642,35644 ,19676,19629,19694 ,0,0,0}, - {35641,35644,35642 ,19675,19694,19629 ,0,0,0}, {35645,35646,35643 ,19653,18067,19676 ,0,0,0}, - {35643,35644,35645 ,19676,19694,19653 ,0,0,0}, {35646,35647,35648 ,18067,19654,19655 ,0,0,0}, - {35647,35646,35645 ,19654,18067,19653 ,0,0,0}, {35647,33525,35648 ,19654,82,19655 ,0,0,0}, - {35649,35650,35651 ,19695,19696,19697 ,0,0,0}, {35649,35652,35653 ,19695,19698,19699 ,0,0,0}, - {35652,35654,35653 ,19698,19700,19699 ,0,0,0}, {35651,35652,35649 ,19697,19698,19695 ,0,0,0}, - {35655,35656,35657 ,19701,19702,19703 ,0,0,0}, {35654,35655,35657 ,19700,19701,19703 ,0,0,0}, - {35656,35658,35659 ,19702,19704,19705 ,0,0,0}, {35658,35656,35655 ,19704,19702,19701 ,0,0,0}, - {35659,35658,35660 ,19705,19704,19706 ,0,0,0}, {35661,35659,35660 ,19707,19705,19706 ,0,0,0}, - {35661,35662,35663 ,19707,19708,19709 ,0,0,0}, {35661,35660,35662 ,19707,19706,19708 ,0,0,0}, - {35657,35653,35654 ,19703,19699,19700 ,0,0,0}, {35664,35665,35666 ,19710,19711,126 ,0,0,0}, - {35664,35666,35663 ,19710,126,19709 ,0,0,0}, {35662,35664,35663 ,19708,19710,19709 ,0,0,0}, - {35651,35650,35667 ,19697,19696,19712 ,0,0,0}, {35668,35667,35669 ,19672,19712,19673 ,0,0,0}, - {35650,35669,35667 ,19696,19673,19712 ,0,0,0}, {35670,35671,35668 ,19713,19674,19672 ,0,0,0}, - {35668,35669,35670 ,19672,19673,19713 ,0,0,0}, {35671,35672,35673 ,19674,19714,19715 ,0,0,0}, - {35672,35671,35670 ,19714,19674,19713 ,0,0,0}, {35674,35673,35675 ,19676,19715,19694 ,0,0,0}, - {35672,35675,35673 ,19714,19694,19715 ,0,0,0}, {35676,35677,35674 ,18761,18067,19676 ,0,0,0}, - {35674,35675,35676 ,19676,19694,18761 ,0,0,0}, {35677,35678,35679 ,18067,19716,140 ,0,0,0}, - {35678,35677,35676 ,19716,18067,18761 ,0,0,0}, {35678,35680,35679 ,19716,82,140 ,0,0,0}, - {35681,35682,35683 ,19656,19657,19717 ,0,0,0}, {35681,35684,35685 ,19656,19698,19718 ,0,0,0}, - {35684,35686,35685 ,19698,19719,19718 ,0,0,0}, {35683,35684,35681 ,19717,19698,19656 ,0,0,0}, - {35687,35688,35689 ,19720,19721,19722 ,0,0,0}, {35686,35687,35689 ,19719,19720,19722 ,0,0,0}, - {35688,35690,35691 ,19721,19723,19724 ,0,0,0}, {35690,35688,35687 ,19723,19721,19720 ,0,0,0}, - {35691,35690,35692 ,19724,19723,19725 ,0,0,0}, {35693,35691,35692 ,19726,19724,19725 ,0,0,0}, - {35693,35694,35695 ,19726,19727,19728 ,0,0,0}, {35693,35692,35694 ,19726,19725,19727 ,0,0,0}, - {35689,35685,35686 ,19722,19718,19719 ,0,0,0}, {35696,35697,35698 ,19729,19730,126 ,0,0,0}, - {35696,35698,35695 ,19729,126,19728 ,0,0,0}, {35694,35696,35695 ,19727,19729,19728 ,0,0,0}, - {35683,35682,35699 ,19717,19657,19671 ,0,0,0}, {35700,35699,35701 ,19731,19671,19732 ,0,0,0}, - {35682,35701,35699 ,19657,19732,19671 ,0,0,0}, {35702,35703,35700 ,19733,19674,19731 ,0,0,0}, - {35700,35701,35702 ,19731,19732,19733 ,0,0,0}, {35703,35704,35705 ,19674,19734,19715 ,0,0,0}, - {35704,35703,35702 ,19734,19674,19733 ,0,0,0}, {35706,35705,35707 ,19676,19715,19735 ,0,0,0}, - {35704,35707,35705 ,19734,19735,19715 ,0,0,0}, {35708,35709,35706 ,18761,18067,19676 ,0,0,0}, - {35706,35707,35708 ,19676,19735,18761 ,0,0,0}, {35709,35710,35711 ,18067,18838,793 ,0,0,0}, - {35710,35709,35708 ,18838,18067,18761 ,0,0,0}, {35710,35712,35711 ,18838,82,793 ,0,0,0}, - {35713,35714,35715 ,19607,19608,19736 ,0,0,0}, {35713,35716,35717 ,19607,19737,19738 ,0,0,0}, - {35716,35718,35717 ,19737,19719,19738 ,0,0,0}, {35715,35716,35713 ,19736,19737,19607 ,0,0,0}, - {35719,35720,35721 ,19739,19740,19741 ,0,0,0}, {35718,35719,35721 ,19719,19739,19741 ,0,0,0}, - {35720,35722,35723 ,19740,19742,19743 ,0,0,0}, {35722,35720,35719 ,19742,19740,19739 ,0,0,0}, - {35723,35722,35724 ,19743,19742,19744 ,0,0,0}, {35725,35723,35724 ,19745,19743,19744 ,0,0,0}, - {35725,35726,35727 ,19745,19746,19747 ,0,0,0}, {35725,35724,35726 ,19745,19744,19746 ,0,0,0}, - {35721,35717,35718 ,19741,19738,19719 ,0,0,0}, {35728,35729,35730 ,19748,19730,126 ,0,0,0}, - {35728,35730,35727 ,19748,126,19747 ,0,0,0}, {35726,35728,35727 ,19746,19748,19747 ,0,0,0}, - {35715,35714,35731 ,19736,19608,18805 ,0,0,0}, {35732,35731,35733 ,19749,18805,19750 ,0,0,0}, - {35714,35733,35731 ,19608,19750,18805 ,0,0,0}, {35734,35735,35732 ,19733,19627,19749 ,0,0,0}, - {35732,35733,35734 ,19749,19750,19733 ,0,0,0}, {35735,35736,35737 ,19627,19751,19715 ,0,0,0}, - {35736,35735,35734 ,19751,19627,19733 ,0,0,0}, {35738,35737,35739 ,19630,19715,19752 ,0,0,0}, - {35736,35739,35737 ,19751,19752,19715 ,0,0,0}, {35740,35741,35738 ,18761,18067,19630 ,0,0,0}, - {35738,35739,35740 ,19630,19752,18761 ,0,0,0}, {35741,35742,35743 ,18067,18838,793 ,0,0,0}, - {35742,35741,35740 ,18838,18067,18761 ,0,0,0}, {35742,35744,35743 ,18838,82,793 ,0,0,0}, - {35745,35746,35747 ,19634,19753,19754 ,0,0,0}, {35745,35748,35749 ,19634,19610,19755 ,0,0,0}, - {35748,35750,35749 ,19610,19756,19755 ,0,0,0}, {35747,35748,35745 ,19754,19610,19634 ,0,0,0}, - {35751,35752,35753 ,19757,19758,19759 ,0,0,0}, {35750,35751,35753 ,19756,19757,19759 ,0,0,0}, - {35752,35754,35755 ,19758,19760,19761 ,0,0,0}, {35754,35752,35751 ,19760,19758,19757 ,0,0,0}, - {35755,35754,35756 ,19761,19760,19762 ,0,0,0}, {35757,35755,35756 ,19763,19761,19762 ,0,0,0}, - {35757,35758,35759 ,19763,19764,19765 ,0,0,0}, {35757,35756,35758 ,19763,19762,19764 ,0,0,0}, - {35753,35749,35750 ,19759,19755,19756 ,0,0,0}, {35760,35761,35762 ,19766,19767,18751 ,0,0,0}, - {35760,35762,35759 ,19766,18751,19765 ,0,0,0}, {35758,35760,35759 ,19764,19766,19765 ,0,0,0}, - {35747,35746,35763 ,19754,19753,19768 ,0,0,0}, {35764,35763,35765 ,19749,19768,19769 ,0,0,0}, - {35746,35765,35763 ,19753,19769,19768 ,0,0,0}, {35766,35767,35764 ,19713,19770,19749 ,0,0,0}, - {35764,35765,35766 ,19749,19769,19713 ,0,0,0}, {35767,35768,35769 ,19770,19771,19772 ,0,0,0}, - {35768,35767,35766 ,19771,19770,19713 ,0,0,0}, {35770,35769,35771 ,19773,19772,19774 ,0,0,0}, - {35768,35771,35769 ,19771,19774,19772 ,0,0,0}, {35772,35773,35770 ,19653,19775,19773 ,0,0,0}, - {35770,35771,35772 ,19773,19774,19653 ,0,0,0}, {35773,35774,35775 ,19775,19654,140 ,0,0,0}, - {35774,35773,35772 ,19654,19775,19653 ,0,0,0}, {35774,35776,35775 ,19654,82,140 ,0,0,0}, - {35777,35778,35779 ,19776,19777,19777 ,0,0,0}, {35780,35781,35782 ,19778,19779,19778 ,0,0,0}, - {35779,35778,35782 ,19777,19777,19778 ,0,0,0}, {35783,35784,35785 ,18601,18601,19779 ,0,0,0}, - {35781,35780,35785 ,19779,19778,19779 ,0,0,0}, {35785,35784,35781 ,19779,18601,19779 ,0,0,0}, - {35780,35782,35778 ,19778,19778,19777 ,0,0,0}, {35779,35786,35777 ,19777,19776,19776 ,0,0,0}, - {35786,35787,35788 ,19776,19780,19780 ,0,0,0}, {35788,35777,35786 ,19780,19776,19776 ,0,0,0}, - {35789,35787,35790 ,18588,19780,18588 ,0,0,0}, {35787,35789,35788 ,19780,18588,19780 ,0,0,0}, - {35791,35792,35793 ,19781,19782,19782 ,0,0,0}, {35794,35795,35796 ,19783,19784,19783 ,0,0,0}, - {35793,35792,35796 ,19782,19782,19783 ,0,0,0}, {35797,35798,35799 ,18609,18609,19784 ,0,0,0}, - {35795,35794,35799 ,19784,19783,19784 ,0,0,0}, {35799,35798,35795 ,19784,18609,19784 ,0,0,0}, - {35794,35796,35792 ,19783,19783,19782 ,0,0,0}, {35793,35800,35791 ,19782,19781,19781 ,0,0,0}, - {35800,35801,35802 ,19781,19785,19785 ,0,0,0}, {35802,35791,35800 ,19785,19781,19781 ,0,0,0}, - {35803,35801,35804 ,18594,19785,18594 ,0,0,0}, {35801,35803,35802 ,19785,18594,19785 ,0,0,0}, - {35805,35806,35807 ,19786,19787,19788 ,0,0,0}, {35808,35809,35810 ,19789,19790,19791 ,0,0,0}, - {35809,35805,35807 ,19790,19786,19788 ,0,0,0}, {35811,35808,35810 ,19792,19789,19791 ,0,0,0}, - {35809,35808,35805 ,19790,19789,19786 ,0,0,0}, {35811,35810,35812 ,19792,19791,19793 ,0,0,0}, - {35812,35813,35814 ,19793,19794,19795 ,0,0,0}, {35815,35814,35813 ,19796,19795,19794 ,0,0,0}, - {35816,35817,35818 ,19797,19798,19799 ,0,0,0}, {35813,35819,35815 ,19794,19800,19796 ,0,0,0}, - {35818,35820,35821 ,19799,19801,19802 ,0,0,0}, {35820,35819,35821 ,19801,19800,19802 ,0,0,0}, - {35815,35819,35820 ,19796,19800,19801 ,0,0,0}, {35818,35821,35816 ,19799,19802,19797 ,0,0,0}, - {35817,35816,35822 ,19798,19797,19803 ,0,0,0}, {35817,35822,35823 ,19798,19803,19804 ,0,0,0}, - {35824,35823,35822 ,19805,19804,19803 ,0,0,0}, {35825,35826,35827 ,19806,82,19807 ,0,0,0}, - {35827,35823,35824 ,19807,19804,19805 ,0,0,0}, {35825,35827,35824 ,19806,19807,19805 ,0,0,0}, - {35825,35828,35826 ,19806,3370,82 ,0,0,0}, {35811,35812,35814 ,19792,19793,19795 ,0,0,0}, - {35807,35806,35829 ,19788,19787,19808 ,0,0,0}, {35830,35829,35831 ,19809,19808,19810 ,0,0,0}, - {35806,35831,35829 ,19787,19810,19808 ,0,0,0}, {35832,35833,35830 ,19811,19812,19809 ,0,0,0}, - {35830,35831,35832 ,19809,19810,19811 ,0,0,0}, {35833,35834,35835 ,19812,19813,19814 ,0,0,0}, - {35834,35833,35832 ,19813,19812,19811 ,0,0,0}, {35836,35835,35837 ,19815,19814,19816 ,0,0,0}, - {35834,35837,35835 ,19813,19816,19814 ,0,0,0}, {35838,35839,35836 ,19817,19818,19815 ,0,0,0}, - {35836,35837,35838 ,19815,19816,19817 ,0,0,0}, {35839,35840,35841 ,19818,19819,19820 ,0,0,0}, - {35840,35839,35838 ,19819,19818,19817 ,0,0,0}, {35842,35841,35843 ,19821,19820,19822 ,0,0,0}, - {35840,35843,35841 ,19819,19822,19820 ,0,0,0}, {35844,35845,35842 ,19823,19824,19821 ,0,0,0}, - {35842,35843,35844 ,19821,19822,19823 ,0,0,0}, {35845,35846,35847 ,19824,19825,2614 ,0,0,0}, - {35846,35845,35844 ,19825,19824,19823 ,0,0,0}, {35846,35848,35847 ,19825,126,2614 ,0,0,0}, - {35849,35850,35851 ,19826,19827,19828 ,0,0,0}, {35852,35853,35854 ,19829,19830,19831 ,0,0,0}, - {35853,35849,35851 ,19830,19826,19828 ,0,0,0}, {35855,35852,35854 ,19832,19829,19831 ,0,0,0}, - {35853,35852,35849 ,19830,19829,19826 ,0,0,0}, {35855,35854,35856 ,19832,19831,19833 ,0,0,0}, - {35856,35857,35858 ,19833,19834,19835 ,0,0,0}, {35859,35858,35857 ,19836,19835,19834 ,0,0,0}, - {35860,35861,35862 ,19837,19838,19839 ,0,0,0}, {35857,35863,35859 ,19834,19840,19836 ,0,0,0}, - {35862,35864,35865 ,19839,19841,19842 ,0,0,0}, {35864,35863,35865 ,19841,19840,19842 ,0,0,0}, - {35859,35863,35864 ,19836,19840,19841 ,0,0,0}, {35862,35865,35860 ,19839,19842,19837 ,0,0,0}, - {35861,35860,35866 ,19838,19837,19843 ,0,0,0}, {35861,35866,35867 ,19838,19843,19844 ,0,0,0}, - {35868,35867,35866 ,19845,19844,19843 ,0,0,0}, {35869,35870,35871 ,19846,9510,19847 ,0,0,0}, - {35871,35867,35868 ,19847,19844,19845 ,0,0,0}, {35869,35871,35868 ,19846,19847,19845 ,0,0,0}, - {35869,35872,35870 ,19846,8396,9510 ,0,0,0}, {35855,35856,35858 ,19832,19833,19835 ,0,0,0}, - {35851,35850,35873 ,19828,19827,19848 ,0,0,0}, {35874,35873,35875 ,19849,19848,19850 ,0,0,0}, - {35850,35875,35873 ,19827,19850,19848 ,0,0,0}, {35876,35877,35874 ,19851,19852,19849 ,0,0,0}, - {35874,35875,35876 ,19849,19850,19851 ,0,0,0}, {35877,35878,35879 ,19852,4543,19853 ,0,0,0}, - {35878,35877,35876 ,4543,19852,19851 ,0,0,0}, {35880,35879,35881 ,19854,19853,19855 ,0,0,0}, - {35878,35881,35879 ,4543,19855,19853 ,0,0,0}, {35882,35883,35880 ,19856,19857,19854 ,0,0,0}, - {35880,35881,35882 ,19854,19855,19856 ,0,0,0}, {35883,35884,35885 ,19857,19858,19859 ,0,0,0}, - {35884,35883,35882 ,19858,19857,19856 ,0,0,0}, {35886,35885,35887 ,19860,19859,19861 ,0,0,0}, - {35884,35887,35885 ,19858,19861,19859 ,0,0,0}, {35888,35889,35886 ,19862,19863,19860 ,0,0,0}, - {35886,35887,35888 ,19860,19861,19862 ,0,0,0}, {35889,35890,35891 ,19863,19864,96 ,0,0,0}, - {35890,35889,35888 ,19864,19863,19862 ,0,0,0}, {35890,35892,35891 ,19864,126,96 ,0,0,0}, - {35893,35894,35895 ,19865,19866,19867 ,0,0,0}, {35896,35897,35898 ,19868,19869,19870 ,0,0,0}, - {35897,35893,35895 ,19869,19865,19867 ,0,0,0}, {35899,35896,35898 ,19871,19868,19870 ,0,0,0}, - {35897,35896,35893 ,19869,19868,19865 ,0,0,0}, {35899,35898,35900 ,19871,19870,19872 ,0,0,0}, - {35900,35901,35902 ,19872,19873,19874 ,0,0,0}, {35903,35902,35901 ,19875,19874,19873 ,0,0,0}, - {35904,35905,35906 ,19876,19877,19878 ,0,0,0}, {35901,35907,35903 ,19873,19879,19875 ,0,0,0}, - {35906,35908,35909 ,19878,19880,19881 ,0,0,0}, {35908,35907,35909 ,19880,19879,19881 ,0,0,0}, - {35903,35907,35908 ,19875,19879,19880 ,0,0,0}, {35906,35909,35904 ,19878,19881,19876 ,0,0,0}, - {35905,35904,35910 ,19877,19876,19882 ,0,0,0}, {35905,35910,35911 ,19877,19882,19883 ,0,0,0}, - {35912,35911,35910 ,19884,19883,19882 ,0,0,0}, {35913,35914,35915 ,19885,82,19886 ,0,0,0}, - {35915,35911,35912 ,19886,19883,19884 ,0,0,0}, {35913,35915,35912 ,19885,19886,19884 ,0,0,0}, - {35913,35916,35914 ,19885,2602,82 ,0,0,0}, {35899,35900,35902 ,19871,19872,19874 ,0,0,0}, - {35895,35894,35917 ,19867,19866,19887 ,0,0,0}, {35918,35917,35919 ,19809,19887,19888 ,0,0,0}, - {35894,35919,35917 ,19866,19888,19887 ,0,0,0}, {35920,35921,35918 ,19811,19812,19809 ,0,0,0}, - {35918,35919,35920 ,19809,19888,19811 ,0,0,0}, {35921,35922,35923 ,19812,19889,19890 ,0,0,0}, - {35922,35921,35920 ,19889,19812,19811 ,0,0,0}, {35924,35923,35925 ,19891,19890,19892 ,0,0,0}, - {35922,35925,35923 ,19889,19892,19890 ,0,0,0}, {35926,35927,35924 ,19893,19894,19891 ,0,0,0}, - {35924,35925,35926 ,19891,19892,19893 ,0,0,0}, {35927,35928,35929 ,19894,19895,19820 ,0,0,0}, - {35928,35927,35926 ,19895,19894,19893 ,0,0,0}, {35930,35929,35931 ,19896,19820,19822 ,0,0,0}, - {35928,35931,35929 ,19895,19822,19820 ,0,0,0}, {35932,35933,35930 ,19897,19824,19896 ,0,0,0}, - {35930,35931,35932 ,19896,19822,19897 ,0,0,0}, {35933,35934,35935 ,19824,19825,3345 ,0,0,0}, - {35934,35933,35932 ,19825,19824,19897 ,0,0,0}, {35934,35936,35935 ,19825,126,3345 ,0,0,0}, - {35937,35938,35939 ,19898,19899,19900 ,0,0,0}, {35940,35941,35942 ,19901,19902,19903 ,0,0,0}, - {35941,35937,35939 ,19902,19898,19900 ,0,0,0}, {35943,35940,35942 ,19904,19901,19903 ,0,0,0}, - {35941,35940,35937 ,19902,19901,19898 ,0,0,0}, {35943,35942,35944 ,19904,19903,19905 ,0,0,0}, - {35944,35945,35946 ,19905,19906,19907 ,0,0,0}, {35947,35946,35945 ,19908,19907,19906 ,0,0,0}, - {35948,35949,35950 ,19909,19910,19911 ,0,0,0}, {35945,35951,35947 ,19906,19912,19908 ,0,0,0}, - {35950,35952,35953 ,19911,19913,19914 ,0,0,0}, {35952,35951,35953 ,19913,19912,19914 ,0,0,0}, - {35947,35951,35952 ,19908,19912,19913 ,0,0,0}, {35950,35953,35948 ,19911,19914,19909 ,0,0,0}, - {35949,35948,35954 ,19910,19909,19915 ,0,0,0}, {35949,35954,35955 ,19910,19915,19916 ,0,0,0}, - {35956,35955,35954 ,19917,19916,19915 ,0,0,0}, {35957,35958,35959 ,19918,9510,19919 ,0,0,0}, - {35959,35955,35956 ,19919,19916,19917 ,0,0,0}, {35957,35959,35956 ,19918,19919,19917 ,0,0,0}, - {35957,35960,35958 ,19918,8396,9510 ,0,0,0}, {35943,35944,35946 ,19904,19905,19907 ,0,0,0}, - {35939,35938,35961 ,19900,19899,19920 ,0,0,0}, {35962,35961,35963 ,19921,19920,19922 ,0,0,0}, - {35938,35963,35961 ,19899,19922,19920 ,0,0,0}, {35964,35965,35962 ,19923,19852,19921 ,0,0,0}, - {35962,35963,35964 ,19921,19922,19923 ,0,0,0}, {35965,35966,35967 ,19852,19924,19925 ,0,0,0}, - {35966,35965,35964 ,19924,19852,19923 ,0,0,0}, {35968,35967,35969 ,19926,19925,19927 ,0,0,0}, - {35966,35969,35967 ,19924,19927,19925 ,0,0,0}, {35970,35971,35968 ,19928,19929,19926 ,0,0,0}, - {35968,35969,35970 ,19926,19927,19928 ,0,0,0}, {35971,35972,35973 ,19929,19930,19931 ,0,0,0}, - {35972,35971,35970 ,19930,19929,19928 ,0,0,0}, {35974,35973,35975 ,19932,19931,4552 ,0,0,0}, - {35972,35975,35973 ,19930,4552,19931 ,0,0,0}, {35976,35977,35974 ,19933,19934,19932 ,0,0,0}, - {35974,35975,35976 ,19932,4552,19933 ,0,0,0}, {35977,35978,35979 ,19934,19935,18053 ,0,0,0}, - {35978,35977,35976 ,19935,19934,19933 ,0,0,0}, {35978,35980,35979 ,19935,96,18053 ,0,0,0}, - {35981,35982,35983 ,19936,19937,19938 ,0,0,0}, {35984,35983,35985 ,19939,19938,19940 ,0,0,0}, - {35982,35985,35983 ,19937,19940,19938 ,0,0,0}, {35986,35987,35984 ,19941,19942,19939 ,0,0,0}, - {35984,35985,35986 ,19939,19940,19941 ,0,0,0}, {35987,35988,35989 ,19942,19943,19944 ,0,0,0}, - {35988,35987,35986 ,19943,19942,19941 ,0,0,0}, {35990,35989,35991 ,19945,19944,19946 ,0,0,0}, - {35988,35991,35989 ,19943,19946,19944 ,0,0,0}, {35992,35993,35990 ,19947,19948,19945 ,0,0,0}, - {35990,35991,35992 ,19945,19946,19947 ,0,0,0}, {35993,35994,35995 ,19948,19949,19950 ,0,0,0}, - {35994,35993,35992 ,19949,19948,19947 ,0,0,0}, {35996,35995,35997 ,19951,19950,19952 ,0,0,0}, - {35994,35997,35995 ,19949,19952,19950 ,0,0,0}, {35998,35999,35996 ,19953,19954,19951 ,0,0,0}, - {35996,35997,35998 ,19951,19952,19953 ,0,0,0}, {35999,36000,36001 ,19954,19955,19956 ,0,0,0}, - {36000,35999,35998 ,19955,19954,19953 ,0,0,0}, {36002,36001,36003 ,19957,19956,19958 ,0,0,0}, - {36000,36003,36001 ,19955,19958,19956 ,0,0,0}, {36004,36005,36002 ,19959,19960,19957 ,0,0,0}, - {36002,36003,36004 ,19957,19958,19959 ,0,0,0}, {36005,36006,36007 ,19960,19961,19962 ,0,0,0}, - {36006,36005,36004 ,19961,19960,19959 ,0,0,0}, {36008,36007,36009 ,19963,19962,19964 ,0,0,0}, - {36006,36009,36007 ,19961,19964,19962 ,0,0,0}, {36010,36011,36008 ,19965,19966,19963 ,0,0,0}, - {36008,36009,36010 ,19963,19964,19965 ,0,0,0}, {36012,36011,36010 ,19967,19966,19965 ,0,0,0}, - {36012,36013,36011 ,19967,19968,19966 ,0,0,0}, {35982,35981,36014 ,19937,19936,19969 ,0,0,0}, - {36015,36016,36014 ,19970,19971,19969 ,0,0,0}, {36014,35981,36015 ,19969,19936,19970 ,0,0,0}, - {36016,36017,36018 ,19971,19972,19973 ,0,0,0}, {36017,36016,36015 ,19972,19971,19970 ,0,0,0}, - {36019,36018,36020 ,19974,19973,19975 ,0,0,0}, {36017,36020,36018 ,19972,19975,19973 ,0,0,0}, - {36021,36022,36019 ,19976,19977,19974 ,0,0,0}, {36019,36020,36021 ,19974,19975,19976 ,0,0,0}, - {36022,36023,36024 ,19977,19978,19979 ,0,0,0}, {36023,36022,36021 ,19978,19977,19976 ,0,0,0}, - {36025,36024,36026 ,19980,19979,19981 ,0,0,0}, {36023,36026,36024 ,19978,19981,19979 ,0,0,0}, - {36027,36028,36025 ,19982,19983,19980 ,0,0,0}, {36025,36026,36027 ,19980,19981,19982 ,0,0,0}, - {36028,36029,36030 ,19983,19984,19985 ,0,0,0}, {36029,36028,36027 ,19984,19983,19982 ,0,0,0}, - {36031,36030,36032 ,19986,19985,19987 ,0,0,0}, {36029,36032,36030 ,19984,19987,19985 ,0,0,0}, - {36033,36034,36031 ,19988,19989,19986 ,0,0,0}, {36031,36032,36033 ,19986,19987,19988 ,0,0,0}, - {36034,36035,36036 ,19989,19990,19991 ,0,0,0}, {36035,36034,36033 ,19990,19989,19988 ,0,0,0}, - {36037,36036,36038 ,19992,19991,19993 ,0,0,0}, {36035,36038,36036 ,19990,19993,19991 ,0,0,0}, - {36039,36040,36037 ,19994,19995,19992 ,0,0,0}, {36037,36038,36039 ,19992,19993,19994 ,0,0,0}, - {36040,36041,36042 ,19995,19996,19997 ,0,0,0}, {36041,36040,36039 ,19996,19995,19994 ,0,0,0}, - {36041,36043,36042 ,19996,19998,19997 ,0,0,0}, {36042,36043,36044 ,19997,19998,19998 ,0,0,0}, - {36045,36046,36047 ,19999,20000,20001 ,0,0,0}, {36048,36047,36049 ,20002,20001,20003 ,0,0,0}, - {36046,36049,36047 ,20000,20003,20001 ,0,0,0}, {36050,36051,36048 ,20004,20005,20002 ,0,0,0}, - {36048,36049,36050 ,20002,20003,20004 ,0,0,0}, {36051,36052,36053 ,20005,20006,20007 ,0,0,0}, - {36052,36051,36050 ,20006,20005,20004 ,0,0,0}, {36054,36053,36055 ,20008,20007,20009 ,0,0,0}, - {36052,36055,36053 ,20006,20009,20007 ,0,0,0}, {36056,36057,36054 ,20010,20011,20008 ,0,0,0}, - {36054,36055,36056 ,20008,20009,20010 ,0,0,0}, {36057,36058,36059 ,20011,20012,20013 ,0,0,0}, - {36058,36057,36056 ,20012,20011,20010 ,0,0,0}, {36060,36059,36061 ,20014,20013,20015 ,0,0,0}, - {36058,36061,36059 ,20012,20015,20013 ,0,0,0}, {36062,36063,36060 ,20016,20017,20014 ,0,0,0}, - {36060,36061,36062 ,20014,20015,20016 ,0,0,0}, {36063,36064,36065 ,20017,20018,20019 ,0,0,0}, - {36064,36063,36062 ,20018,20017,20016 ,0,0,0}, {36066,36065,36067 ,20020,20019,20021 ,0,0,0}, - {36064,36067,36065 ,20018,20021,20019 ,0,0,0}, {36068,36069,36066 ,20022,20023,20020 ,0,0,0}, - {36066,36067,36068 ,20020,20021,20022 ,0,0,0}, {36069,36070,36071 ,20023,20024,20025 ,0,0,0}, - {36070,36069,36068 ,20024,20023,20022 ,0,0,0}, {36072,36071,36073 ,20026,20025,20027 ,0,0,0}, - {36070,36073,36071 ,20024,20027,20025 ,0,0,0}, {36074,36075,36072 ,20028,20029,20026 ,0,0,0}, - {36072,36073,36074 ,20026,20027,20028 ,0,0,0}, {36076,36075,36074 ,20030,20029,20028 ,0,0,0}, - {36076,36077,36075 ,20030,126,20029 ,0,0,0}, {36046,36045,36078 ,20000,19999,20031 ,0,0,0}, - {36079,36080,36078 ,20032,20033,20031 ,0,0,0}, {36078,36045,36079 ,20031,19999,20032 ,0,0,0}, - {36080,36081,36082 ,20033,20034,20035 ,0,0,0}, {36081,36080,36079 ,20034,20033,20032 ,0,0,0}, - {36083,36082,36084 ,20036,20035,20037 ,0,0,0}, {36081,36084,36082 ,20034,20037,20035 ,0,0,0}, - {36085,36086,36083 ,20038,20039,20036 ,0,0,0}, {36083,36084,36085 ,20036,20037,20038 ,0,0,0}, - {36086,36087,36088 ,20039,20040,20041 ,0,0,0}, {36087,36086,36085 ,20040,20039,20038 ,0,0,0}, - {36089,36088,36090 ,20042,20041,20043 ,0,0,0}, {36087,36090,36088 ,20040,20043,20041 ,0,0,0}, - {36091,36092,36089 ,20044,20045,20042 ,0,0,0}, {36089,36090,36091 ,20042,20043,20044 ,0,0,0}, - {36092,36093,36094 ,20045,20046,20047 ,0,0,0}, {36093,36092,36091 ,20046,20045,20044 ,0,0,0}, - {36095,36094,36096 ,20048,20047,20049 ,0,0,0}, {36093,36096,36094 ,20046,20049,20047 ,0,0,0}, - {36097,36098,36095 ,20050,20051,20048 ,0,0,0}, {36095,36096,36097 ,20048,20049,20050 ,0,0,0}, - {36098,36099,36100 ,20051,20052,20053 ,0,0,0}, {36099,36098,36097 ,20052,20051,20050 ,0,0,0}, - {36101,36100,36102 ,20054,20053,20055 ,0,0,0}, {36099,36102,36100 ,20052,20055,20053 ,0,0,0}, - {36103,36104,36101 ,20056,20057,20054 ,0,0,0}, {36101,36102,36103 ,20054,20055,20056 ,0,0,0}, - {36104,36105,36106 ,20057,20058,20059 ,0,0,0}, {36105,36104,36103 ,20058,20057,20056 ,0,0,0}, - {36105,36107,36106 ,20058,20060,20059 ,0,0,0}, {36106,36107,36108 ,20059,20060,20060 ,0,0,0}, - {36109,36110,36111 ,20061,20062,20063 ,0,0,0}, {36112,36111,36113 ,20064,20063,20065 ,0,0,0}, - {36110,36113,36111 ,20062,20065,20063 ,0,0,0}, {36114,36115,36112 ,20066,20067,20064 ,0,0,0}, - {36112,36113,36114 ,20064,20065,20066 ,0,0,0}, {36115,36116,36117 ,20067,20068,20069 ,0,0,0}, - {36116,36115,36114 ,20068,20067,20066 ,0,0,0}, {36118,36117,36119 ,20070,20069,20071 ,0,0,0}, - {36116,36119,36117 ,20068,20071,20069 ,0,0,0}, {36120,36121,36118 ,20072,20073,20070 ,0,0,0}, - {36118,36119,36120 ,20070,20071,20072 ,0,0,0}, {36121,36122,36123 ,20073,20074,20075 ,0,0,0}, - {36122,36121,36120 ,20074,20073,20072 ,0,0,0}, {36124,36123,36125 ,20076,20075,20077 ,0,0,0}, - {36122,36125,36123 ,20074,20077,20075 ,0,0,0}, {36126,36127,36124 ,20078,20079,20076 ,0,0,0}, - {36124,36125,36126 ,20076,20077,20078 ,0,0,0}, {36127,36128,36129 ,20079,20080,20081 ,0,0,0}, - {36128,36127,36126 ,20080,20079,20078 ,0,0,0}, {36130,36129,36131 ,20082,20081,20083 ,0,0,0}, - {36128,36131,36129 ,20080,20083,20081 ,0,0,0}, {36132,36133,36130 ,20084,20085,20082 ,0,0,0}, - {36130,36131,36132 ,20082,20083,20084 ,0,0,0}, {36133,36134,36135 ,20085,20086,20087 ,0,0,0}, - {36134,36133,36132 ,20086,20085,20084 ,0,0,0}, {36136,36135,36137 ,20088,20087,20089 ,0,0,0}, - {36134,36137,36135 ,20086,20089,20087 ,0,0,0}, {36138,36139,36136 ,20090,20091,20088 ,0,0,0}, - {36136,36137,36138 ,20088,20089,20090 ,0,0,0}, {36140,36139,36138 ,20092,20091,20090 ,0,0,0}, - {36140,36141,36139 ,20092,20093,20091 ,0,0,0}, {36110,36109,36142 ,20062,20061,20094 ,0,0,0}, - {36143,36144,36142 ,20095,20096,20094 ,0,0,0}, {36142,36109,36143 ,20094,20061,20095 ,0,0,0}, - {36144,36145,36146 ,20096,20097,20098 ,0,0,0}, {36145,36144,36143 ,20097,20096,20095 ,0,0,0}, - {36147,36146,36148 ,20099,20098,20100 ,0,0,0}, {36145,36148,36146 ,20097,20100,20098 ,0,0,0}, - {36149,36150,36147 ,20101,20102,20099 ,0,0,0}, {36147,36148,36149 ,20099,20100,20101 ,0,0,0}, - {36150,36151,36152 ,20102,20103,20104 ,0,0,0}, {36151,36150,36149 ,20103,20102,20101 ,0,0,0}, - {36153,36152,36154 ,20105,20104,20106 ,0,0,0}, {36151,36154,36152 ,20103,20106,20104 ,0,0,0}, - {36155,36156,36153 ,20107,20108,20105 ,0,0,0}, {36153,36154,36155 ,20105,20106,20107 ,0,0,0}, - {36156,36157,36158 ,20108,20109,20110 ,0,0,0}, {36157,36156,36155 ,20109,20108,20107 ,0,0,0}, - {36159,36158,36160 ,20111,20110,20112 ,0,0,0}, {36157,36160,36158 ,20109,20112,20110 ,0,0,0}, - {36161,36162,36159 ,20113,20114,20111 ,0,0,0}, {36159,36160,36161 ,20111,20112,20113 ,0,0,0}, - {36162,36163,36164 ,20114,20115,20116 ,0,0,0}, {36163,36162,36161 ,20115,20114,20113 ,0,0,0}, - {36165,36164,36166 ,20117,20116,20118 ,0,0,0}, {36163,36166,36164 ,20115,20118,20116 ,0,0,0}, - {36167,36168,36165 ,20119,20120,20117 ,0,0,0}, {36165,36166,36167 ,20117,20118,20119 ,0,0,0}, - {36168,36169,36170 ,20120,20121,20122 ,0,0,0}, {36169,36168,36167 ,20121,20120,20119 ,0,0,0}, - {36169,36171,36170 ,20121,20123,20122 ,0,0,0}, {36170,36171,36172 ,20122,20123,20123 ,0,0,0}, - {36173,35775,36174 ,726,726,20124 ,0,0,0}, {36175,36176,36177 ,727,726,20124 ,0,0,0}, - {36178,36179,36180 ,726,726,726 ,0,0,0}, {36181,35773,35775 ,726,20124,726 ,0,0,0}, - {36182,36183,36184 ,726,726,20124 ,0,0,0}, {35769,36181,35767 ,20124,726,726 ,0,0,0}, - {36181,35770,35773 ,726,726,20124 ,0,0,0}, {36185,36186,36187 ,726,726,726 ,0,0,0}, - {35750,35748,36181 ,726,20124,726 ,0,0,0}, {35764,35767,36181 ,726,726,726 ,0,0,0}, - {34562,36108,36188 ,726,726,726 ,0,0,0}, {36189,36190,34340 ,726,726,726 ,0,0,0}, - {36191,36192,36193 ,726,726,726 ,0,0,0}, {36194,36195,36196 ,726,726,726 ,0,0,0}, - {34084,34580,36197 ,728,726,726 ,0,0,0}, {35814,35815,36198 ,728,726,726 ,0,0,0}, - {35750,36181,36199 ,726,726,20124 ,0,0,0}, {36200,36201,36202 ,20124,20124,726 ,0,0,0}, - {35159,36194,35157 ,20124,726,726 ,0,0,0}, {36181,35748,35747 ,726,20124,726 ,0,0,0}, - {36203,35193,36204 ,726,20124,726 ,0,0,0}, {36205,36206,35131 ,20124,20124,20124 ,0,0,0}, - {36207,35300,36208 ,726,20124,20124 ,0,0,0}, {36209,35357,36210 ,726,727,726 ,0,0,0}, - {36211,36212,36210 ,20124,727,726 ,0,0,0}, {36213,35741,35743 ,726,1793,726 ,0,0,0}, - {36214,36215,36216 ,726,726,727 ,0,0,0}, {36216,36217,36214 ,727,727,726 ,0,0,0}, - {36216,36212,36217 ,727,727,727 ,0,0,0}, {36215,36192,36191 ,726,726,726 ,0,0,0}, - {36214,36192,36215 ,726,726,726 ,0,0,0}, {36191,36193,36218 ,726,726,727 ,0,0,0}, - {36219,36220,35940 ,20124,727,20124 ,0,0,0}, {36221,35946,35947 ,20124,20124,726 ,0,0,0}, - {36153,36156,36222 ,727,727,727 ,0,0,0}, {34936,36113,34937 ,727,727,726 ,0,0,0}, - {36110,34039,36113 ,726,726,727 ,0,0,0}, {34904,36223,34906 ,727,727,727 ,0,0,0}, - {36224,36225,36226 ,727,727,727 ,0,0,0}, {34221,36227,36228 ,726,726,20124 ,0,0,0}, - {36229,36134,36230 ,20124,727,726 ,0,0,0}, {34878,34212,36231 ,727,20124,20124 ,0,0,0}, - {34209,34212,34883 ,726,20124,726 ,0,0,0}, {36232,34868,34865 ,726,20124,20124 ,0,0,0}, - {34865,34864,36233 ,20124,726,20124 ,0,0,0}, {34856,36234,36235 ,20124,20124,20124 ,0,0,0}, - {36235,36236,34853 ,20124,727,20124 ,0,0,0}, {34877,36231,34861 ,727,20124,726 ,0,0,0}, - {36237,34850,34852 ,726,726,726 ,0,0,0}, {36238,36239,36240 ,20124,726,726 ,0,0,0}, - {35947,35952,36241 ,726,727,726 ,0,0,0}, {34846,36242,36243 ,727,20124,727 ,0,0,0}, - {36244,34568,34569 ,726,726,726 ,0,0,0}, {34543,36245,34541 ,726,726,729 ,0,0,0}, - {34945,34946,34139 ,20124,726,726 ,0,0,0}, {36246,36088,36247 ,726,726,728 ,0,0,0}, - {36248,34840,34128 ,20124,20124,726 ,0,0,0}, {34923,34939,36249 ,20124,726,726 ,0,0,0}, - {36250,36251,36252 ,726,726,726 ,0,0,0}, {35827,34176,34173 ,728,726,728 ,0,0,0}, - {34932,34930,36119 ,726,727,727 ,0,0,0}, {34044,36253,36254 ,726,727,727 ,0,0,0}, - {36255,36256,34260 ,726,726,726 ,0,0,0}, {36257,36258,34165 ,726,726,726 ,0,0,0}, - {36259,36260,35972 ,726,726,726 ,0,0,0}, {34934,34932,36116 ,727,726,727 ,0,0,0}, - {36261,36262,36256 ,726,726,726 ,0,0,0}, {36186,36185,36263 ,726,726,726 ,0,0,0}, - {34047,34046,36144 ,727,726,726 ,0,0,0}, {36113,34936,36114 ,727,727,727 ,0,0,0}, - {36061,36058,34482 ,726,726,726 ,0,0,0}, {34481,36056,34479 ,726,726,726 ,0,0,0}, - {36100,36101,34554 ,726,726,726 ,0,0,0}, {36259,35970,35969 ,726,726,20124 ,0,0,0}, - {34145,35963,34148 ,20124,726,726 ,0,0,0}, {35937,36264,35938 ,20124,20124,726 ,0,0,0}, - {36153,36222,36265 ,727,727,727 ,0,0,0}, {34058,36266,34902 ,726,726,726 ,0,0,0}, - {36114,34934,36116 ,727,727,727 ,0,0,0}, {36116,34932,36119 ,727,726,727 ,0,0,0}, - {36267,34907,36223 ,726,726,727 ,0,0,0}, {35978,35976,36268 ,726,726,726 ,0,0,0}, - {34838,34128,34840 ,20124,726,20124 ,0,0,0}, {36122,36120,34927 ,727,20124,726 ,0,0,0}, - {34044,36254,36269 ,726,727,727 ,0,0,0}, {34906,36223,34907 ,727,727,726 ,0,0,0}, - {34041,34044,36269 ,726,726,727 ,0,0,0}, {36270,34923,36249 ,20124,20124,726 ,0,0,0}, - {36126,36125,34926 ,727,726,20124 ,0,0,0}, {36170,36172,36271 ,727,727,727 ,0,0,0}, - {34053,34908,34909 ,726,726,726 ,0,0,0}, {36128,36270,36131 ,726,20124,726 ,0,0,0}, - {34923,36270,34924 ,20124,20124,20124 ,0,0,0}, {34912,34914,36272 ,726,20124,20124 ,0,0,0}, - {36273,36274,34060 ,727,727,726 ,0,0,0}, {35345,36275,35349 ,726,727,727 ,0,0,0}, - {36221,36276,36277 ,20124,727,726 ,0,0,0}, {36278,34130,36279 ,726,20124,20124 ,0,0,0}, - {36138,36280,36281 ,20124,727,20124 ,0,0,0}, {36239,36238,36282 ,726,20124,727 ,0,0,0}, - {34229,35959,34232 ,726,20124,726 ,0,0,0}, {36283,36284,34868 ,726,726,20124 ,0,0,0}, - {36285,36286,34847 ,20124,20124,727 ,0,0,0}, {36287,36282,36238 ,20124,727,20124 ,0,0,0}, - {34308,34875,34874 ,726,727,726 ,0,0,0}, {35105,36288,36289 ,727,727,727 ,0,0,0}, - {34316,36290,36291 ,20124,726,726 ,0,0,0}, {36218,36292,36293 ,727,727,727 ,0,0,0}, - {36284,34870,34868 ,726,20124,20124 ,0,0,0}, {35071,36294,36295 ,20124,727,727 ,0,0,0}, - {36296,36297,36298 ,726,727,20124 ,0,0,0}, {36299,36300,36301 ,727,20124,726 ,0,0,0}, - {36302,36303,34296 ,726,726,726 ,0,0,0}, {35075,36304,36305 ,726,727,20124 ,0,0,0}, - {36306,36307,36308 ,727,726,726 ,0,0,0}, {36309,36310,36308 ,20124,20124,726 ,0,0,0}, - {36311,35083,36299 ,727,727,727 ,0,0,0}, {36306,36312,36307 ,727,20124,726 ,0,0,0}, - {36301,36311,36299 ,726,727,727 ,0,0,0}, {36289,36313,36312 ,727,726,20124 ,0,0,0}, - {36304,36310,36305 ,727,20124,20124 ,0,0,0}, {36289,36288,36292 ,727,727,727 ,0,0,0}, - {36193,36292,36218 ,726,727,727 ,0,0,0}, {36210,36206,36211 ,726,20124,20124 ,0,0,0}, - {36212,36211,36217 ,727,20124,727 ,0,0,0}, {35339,35341,36314 ,727,726,726 ,0,0,0}, - {36315,35716,36316 ,1793,1793,1793 ,0,0,0}, {36213,36317,35735 ,726,1793,1793 ,0,0,0}, - {35394,36213,35743 ,726,726,726 ,0,0,0}, {36318,36319,36320 ,1792,1793,727 ,0,0,0}, - {35379,35223,35380 ,726,20124,726 ,0,0,0}, {35216,35372,35374 ,726,20124,727 ,0,0,0}, - {36321,36322,35728 ,1793,1793,1793 ,0,0,0}, {35729,35728,36322 ,726,1793,1793 ,0,0,0}, - {36322,36323,35729 ,1793,1793,726 ,0,0,0}, {35726,36321,35728 ,1793,1793,1793 ,0,0,0}, - {36324,36325,36326 ,1793,1793,1792 ,0,0,0}, {35724,36321,35726 ,726,1793,1793 ,0,0,0}, - {36327,36328,36329 ,726,727,1793 ,0,0,0}, {36321,35724,36330 ,1793,726,1793 ,0,0,0}, - {36331,36332,36333 ,1793,1793,726 ,0,0,0}, {36330,35722,35719 ,1793,1793,1793 ,0,0,0}, - {36334,36327,36335 ,1793,726,726 ,0,0,0}, {35718,36336,35719 ,727,726,1793 ,0,0,0}, - {35425,36337,35428 ,726,726,1793 ,0,0,0}, {35425,35423,36337 ,726,1793,726 ,0,0,0}, - {36338,36339,36340 ,20124,727,727 ,0,0,0}, {35210,35207,35369 ,726,726,726 ,0,0,0}, - {36341,35519,35517 ,726,726,726 ,0,0,0}, {36342,36343,36344 ,726,1792,727 ,0,0,0}, - {36345,36346,36347 ,727,1792,727 ,0,0,0}, {36332,36331,36343 ,1793,1793,1792 ,0,0,0}, - {36332,36343,36342 ,1793,1792,726 ,0,0,0}, {36348,36333,36349 ,1793,726,1793 ,0,0,0}, - {36333,36348,36331 ,726,1793,1793 ,0,0,0}, {36350,36351,34394 ,20125,20126,1792 ,0,0,0}, - {36348,36349,36352 ,1793,1793,1792 ,0,0,0}, {36353,36354,36355 ,20127,20128,20129 ,0,0,0}, - {34424,36356,36357 ,20130,20131,20132 ,0,0,0}, {34718,36358,34720 ,20133,20134,20135 ,0,0,0}, - {34417,34723,34724 ,1793,20136,1793 ,0,0,0}, {35934,35932,36359 ,20137,1793,20136 ,0,0,0}, - {34408,36360,36361 ,20126,20138,20128 ,0,0,0}, {35896,36362,36363 ,20137,20139,20140 ,0,0,0}, - {36364,36365,36366 ,20141,20142,20143 ,0,0,0}, {35926,35925,36367 ,20137,1792,20133 ,0,0,0}, - {36368,34814,34812 ,20144,20135,20133 ,0,0,0}, {34410,36369,34411 ,1793,20145,20146 ,0,0,0}, - {35919,34456,34453 ,20147,20148,20137 ,0,0,0}, {34410,34403,36370 ,1793,20143,20149 ,0,0,0}, - {34815,34814,36371 ,20127,20135,20150 ,0,0,0}, {36372,36373,36374 ,20131,20151,20152 ,0,0,0}, - {34456,35919,35894 ,20148,20147,726 ,0,0,0}, {34814,36375,36371 ,20135,20153,20150 ,0,0,0}, - {36376,36377,36378 ,20154,20155,20156 ,0,0,0}, {36379,36380,36381 ,20157,20158,20159 ,0,0,0}, - {35928,36367,36382 ,727,20133,20136 ,0,0,0}, {34812,36383,36368 ,20133,20160,20144 ,0,0,0}, - {34812,34810,36383 ,20133,20127,20160 ,0,0,0}, {34721,36366,36365 ,20127,20143,20142 ,0,0,0}, - {36384,36385,36386 ,1793,1792,20161 ,0,0,0}, {36383,34810,36387 ,20160,20127,20148 ,0,0,0}, - {36387,34808,36388 ,20148,20126,20162 ,0,0,0}, {34436,34778,34776 ,1792,20137,20126 ,0,0,0}, - {35903,36389,35902 ,20162,20137,726 ,0,0,0}, {36390,36360,34408 ,20137,20138,20126 ,0,0,0}, - {36361,34405,34408 ,20128,20131,20126 ,0,0,0}, {36391,34805,34804 ,20163,20135,20164 ,0,0,0}, - {34436,36392,34778 ,1792,20124,20137 ,0,0,0}, {34720,36358,34721 ,20135,20134,20127 ,0,0,0}, - {36393,36394,34802 ,20124,20133,1792 ,0,0,0}, {34817,36395,34816 ,1793,20140,20136 ,0,0,0}, - {36396,34802,34801 ,20165,1792,726 ,0,0,0}, {36397,36398,36399 ,20132,20137,20166 ,0,0,0}, - {36400,36401,36402 ,20167,20137,20138 ,0,0,0}, {36403,36404,34386 ,20134,20165,20161 ,0,0,0}, - {36405,36406,36407 ,20167,20167,20126 ,0,0,0}, {34822,34823,34447 ,20131,20139,20134 ,0,0,0}, - {36408,34377,36409 ,20136,20136,20133 ,0,0,0}, {36356,34724,34727 ,20131,1793,1792 ,0,0,0}, - {36410,36411,36412 ,20168,1792,20139 ,0,0,0}, {34733,36413,36414 ,20165,1792,20133 ,0,0,0}, - {36415,36416,36417 ,20169,20128,20168 ,0,0,0}, {36418,36419,36420 ,20137,20167,20137 ,0,0,0}, - {36421,36422,36423 ,20147,20170,20139 ,0,0,0}, {34742,34740,36424 ,20124,1792,20137 ,0,0,0}, - {35779,36425,35786 ,1793,20139,1793 ,0,0,0}, {34740,36426,36424 ,1792,20162,20137 ,0,0,0}, - {34748,34746,36427 ,20137,20126,20139 ,0,0,0}, {36428,36429,36430 ,20140,726,1793 ,0,0,0}, - {36431,36427,34746 ,1793,20139,20126 ,0,0,0}, {36432,36433,36434 ,20137,20140,20139 ,0,0,0}, - {34397,36435,34400 ,20168,20125,20140 ,0,0,0}, {35782,34764,34766 ,20137,20137,20170 ,0,0,0}, - {34764,35782,34761 ,20137,20137,727 ,0,0,0}, {34769,36436,36437 ,726,1793,20130 ,0,0,0}, - {36438,36439,35914 ,20125,20125,20167 ,0,0,0}, {36440,36441,36442 ,20124,20147,1793 ,0,0,0}, - {36443,36352,36349 ,1792,1792,1793 ,0,0,0}, {36443,34995,36352 ,1792,20130,1792 ,0,0,0}, - {36444,35903,35908 ,20126,20162,20139 ,0,0,0}, {36445,34797,36446 ,20170,20170,1793 ,0,0,0}, - {34789,34791,36447 ,20125,20147,20130 ,0,0,0}, {36448,36449,35061 ,20140,20140,726 ,0,0,0}, - {36450,35790,35053 ,20140,20147,20140 ,0,0,0}, {36432,36451,36452 ,20137,20168,1793 ,0,0,0}, - {34792,34795,36453 ,727,20137,20124 ,0,0,0}, {36454,35046,36455 ,20167,1792,727 ,0,0,0}, - {36456,35049,36457 ,20147,1793,726 ,0,0,0}, {36448,36458,36459 ,20140,20130,20124 ,0,0,0}, - {36448,36459,36460 ,20140,20124,1792 ,0,0,0}, {35061,36458,36448 ,726,20130,20140 ,0,0,0}, - {35043,36461,36455 ,1793,726,727 ,0,0,0}, {36462,35055,35058 ,20167,1792,20140 ,0,0,0}, - {36463,36448,36464 ,1793,20140,20148 ,0,0,0}, {36344,36346,36465 ,727,1792,1793 ,0,0,0}, - {36344,36465,36342 ,727,1793,726 ,0,0,0}, {35517,36466,36341 ,726,1793,726 ,0,0,0}, - {36346,36345,36465 ,1792,727,1793 ,0,0,0}, {36467,35605,36468 ,20124,726,1793 ,0,0,0}, - {35522,35519,36341 ,1793,726,726 ,0,0,0}, {36469,36470,36471 ,726,726,1793 ,0,0,0}, - {36472,36473,36474 ,726,726,726 ,0,0,0}, {35207,35206,35362 ,726,726,727 ,0,0,0}, - {36475,36476,36477 ,727,726,726 ,0,0,0}, {36475,36478,36476 ,727,727,726 ,0,0,0}, - {35496,36479,35499 ,1793,726,1793 ,0,0,0}, {36480,36478,36481 ,727,727,726 ,0,0,0}, - {36482,36483,36484 ,1792,726,1793 ,0,0,0}, {35696,36485,36486 ,1793,1793,1793 ,0,0,0}, - {36487,35697,36486 ,727,726,1793 ,0,0,0}, {35696,36486,35697 ,1793,1793,726 ,0,0,0}, - {36488,36489,36490 ,1793,727,1793 ,0,0,0}, {36491,36492,36493 ,727,1793,1792 ,0,0,0}, - {36494,36495,36496 ,726,726,726 ,0,0,0}, {36497,36469,36498 ,726,726,726 ,0,0,0}, - {36499,36489,36500 ,1792,727,727 ,0,0,0}, {36497,36501,36502 ,726,727,727 ,0,0,0}, - {35694,36485,35696 ,1793,1793,1793 ,0,0,0}, {36503,36504,36505 ,727,726,727 ,0,0,0}, - {35692,36506,35694 ,726,1793,1793 ,0,0,0}, {35490,36507,36508 ,1793,726,1792 ,0,0,0}, - {35630,35628,36509 ,726,726,20124 ,0,0,0}, {36510,36511,35634 ,726,726,726 ,0,0,0}, - {36512,36513,36514 ,20124,726,726 ,0,0,0}, {36515,36516,36517 ,727,726,726 ,0,0,0}, - {36518,36519,36520 ,727,726,726 ,0,0,0}, {36521,36522,36523 ,726,727,726 ,0,0,0}, - {36523,36516,36521 ,726,726,726 ,0,0,0}, {36524,36522,36525 ,726,727,727 ,0,0,0}, - {36522,36524,36523 ,727,726,726 ,0,0,0}, {36526,36527,36525 ,727,726,727 ,0,0,0}, - {36524,36525,36527 ,726,727,726 ,0,0,0}, {36528,36527,36526 ,727,726,727 ,0,0,0}, - {36529,34686,34352 ,20124,20124,726 ,0,0,0}, {34649,34648,36530 ,20124,726,20124 ,0,0,0}, - {34114,36531,36532 ,20124,726,727 ,0,0,0}, {36533,36534,34200 ,726,726,726 ,0,0,0}, - {34692,36535,34677 ,727,727,726 ,0,0,0}, {34201,36536,34204 ,726,726,20124 ,0,0,0}, - {36537,36010,36538 ,20124,726,727 ,0,0,0}, {35888,36539,35890 ,726,726,726 ,0,0,0}, - {36540,36541,34268 ,727,727,726 ,0,0,0}, {35882,35881,36542 ,726,20124,726 ,0,0,0}, - {36543,36544,36545 ,727,726,727 ,0,0,0}, {36546,35884,36542 ,726,726,726 ,0,0,0}, - {34627,34266,36547 ,726,727,727 ,0,0,0}, {36548,36549,36550 ,727,727,727 ,0,0,0}, - {34597,36551,36552 ,726,726,726 ,0,0,0}, {34594,36553,36554 ,727,727,727 ,0,0,0}, - {36555,36552,36551 ,727,726,726 ,0,0,0}, {34182,36556,36557 ,20124,20124,727 ,0,0,0}, - {36558,36559,36560 ,727,727,727 ,0,0,0}, {36561,36003,36000 ,726,727,20124 ,0,0,0}, - {36562,34622,34620 ,727,726,727 ,0,0,0}, {36563,35991,35988 ,726,726,726 ,0,0,0}, - {36561,36564,36565 ,726,20124,726 ,0,0,0}, {36040,34702,36037 ,727,20124,726 ,0,0,0}, - {36530,34646,36566 ,20124,726,20124 ,0,0,0}, {36028,36567,36025 ,20124,20124,726 ,0,0,0}, - {36568,36024,36025 ,726,727,726 ,0,0,0}, {34652,36569,36533 ,20124,726,726 ,0,0,0}, - {34654,34652,36533 ,20124,20124,726 ,0,0,0}, {34097,34667,34668 ,726,726,20124 ,0,0,0}, - {36570,36571,36572 ,726,20124,726 ,0,0,0}, {36572,36571,34704 ,726,20124,726 ,0,0,0}, - {36019,34103,36018 ,20124,726,20124 ,0,0,0}, {36573,34200,36534 ,726,726,726 ,0,0,0}, - {35985,34673,36574 ,726,726,726 ,0,0,0}, {34699,36042,34698 ,20124,20124,726 ,0,0,0}, - {34696,36044,36575 ,726,20124,20124 ,0,0,0}, {36576,36577,36578 ,20124,726,20124 ,0,0,0}, - {36536,36577,34204 ,726,726,20124 ,0,0,0}, {36579,34109,36580 ,20124,726,726 ,0,0,0}, - {36581,36582,36583 ,20124,727,726 ,0,0,0}, {36584,35998,36585 ,727,20124,726 ,0,0,0}, - {36586,34610,36587 ,727,726,726 ,0,0,0}, {34117,35871,34120 ,726,20124,726 ,0,0,0}, - {36588,36589,36590 ,726,20124,727 ,0,0,0}, {36561,36000,36584 ,726,20124,727 ,0,0,0}, - {36591,36592,36593 ,20124,727,20124 ,0,0,0}, {36594,36595,36596 ,726,726,726 ,0,0,0}, - {34195,36597,34196 ,20124,726,726 ,0,0,0}, {34495,36598,34498 ,728,726,726 ,0,0,0}, - {34190,36599,36600 ,727,726,726 ,0,0,0}, {36601,36602,34284 ,727,727,726 ,0,0,0}, - {34599,34277,34598 ,726,726,726 ,0,0,0}, {36603,34288,34285 ,726,20124,726 ,0,0,0}, - {36541,34265,34268 ,727,726,726 ,0,0,0}, {36554,34596,34594 ,727,727,727 ,0,0,0}, - {36604,36540,34268 ,727,727,726 ,0,0,0}, {34641,36605,34364 ,726,726,20124 ,0,0,0}, - {36606,34270,36607 ,726,726,20124 ,0,0,0}, {35875,34372,34369 ,726,726,20124 ,0,0,0}, - {36608,35005,36609 ,726,20124,727 ,0,0,0}, {34627,36610,36611 ,726,726,727 ,0,0,0}, - {34684,34349,34352 ,20124,726,726 ,0,0,0}, {35249,35245,36612 ,726,726,20124 ,0,0,0}, - {36610,34627,34626 ,726,726,727 ,0,0,0}, {36613,36610,34626 ,727,726,727 ,0,0,0}, - {35481,35328,35325 ,727,727,726 ,0,0,0}, {35009,36608,36614 ,726,726,20124 ,0,0,0}, - {36615,36616,36596 ,727,20124,726 ,0,0,0}, {36615,36596,36617 ,727,726,726 ,0,0,0}, - {36617,35017,36615 ,726,727,727 ,0,0,0}, {36589,35858,35859 ,20124,20124,726 ,0,0,0}, - {34998,35011,36618 ,727,726,726 ,0,0,0}, {34635,34366,34633 ,20124,726,726 ,0,0,0}, - {36619,35001,34999 ,727,726,20124 ,0,0,0}, {36620,36592,36591 ,727,727,20124 ,0,0,0}, - {36621,36609,35008 ,727,727,726 ,0,0,0}, {36614,36620,36622 ,20124,727,20124 ,0,0,0}, - {36623,36624,36625 ,727,726,726 ,0,0,0}, {36521,36516,36515 ,726,726,727 ,0,0,0}, - {36515,36517,36626 ,727,726,20124 ,0,0,0}, {36627,36628,36626 ,20124,726,20124 ,0,0,0}, - {36626,36517,36627 ,20124,726,20124 ,0,0,0}, {36629,35628,35625 ,726,726,20124 ,0,0,0}, - {35630,36630,35632 ,726,726,726 ,0,0,0}, {35479,35481,35325 ,726,727,726 ,0,0,0}, - {35296,35294,36631 ,726,20124,726 ,0,0,0}, {36632,35293,36633 ,726,20124,20124 ,0,0,0}, - {36634,36635,36636 ,20124,726,20124 ,0,0,0}, {35243,36637,36638 ,726,727,726 ,0,0,0}, - {36639,36640,36641 ,20124,726,726 ,0,0,0}, {36642,36643,35677 ,726,727,20124 ,0,0,0}, - {36643,36644,35674 ,727,726,726 ,0,0,0}, {36644,36645,35673 ,726,726,726 ,0,0,0}, - {36646,35679,36647 ,726,726,726 ,0,0,0}, {36645,35668,35671 ,726,726,20124 ,0,0,0}, - {36648,36647,36649 ,726,726,726 ,0,0,0}, {36650,36651,36652 ,726,20124,726 ,0,0,0}, - {36645,35651,35667 ,726,726,726 ,0,0,0}, {36653,36654,35276 ,726,20124,726 ,0,0,0}, - {36655,36656,36657 ,726,20124,726 ,0,0,0}, {36658,36659,36653 ,726,20124,726 ,0,0,0}, - {36660,36661,36662 ,726,727,726 ,0,0,0}, {36663,35250,36664 ,726,726,726 ,0,0,0}, - {36182,36195,35176 ,726,726,726 ,0,0,0}, {35181,36182,35179 ,20124,726,20124 ,0,0,0}, - {36665,36666,36513 ,20124,726,726 ,0,0,0}, {36636,36667,36668 ,20124,20124,726 ,0,0,0}, - {36669,36670,36671 ,20124,727,726 ,0,0,0}, {36672,36673,36670 ,726,20124,727 ,0,0,0}, - {36179,36674,36180 ,726,727,726 ,0,0,0}, {36675,36179,36178 ,20124,726,726 ,0,0,0}, - {36676,36677,36674 ,20124,20124,727 ,0,0,0}, {36180,36674,36677 ,726,727,20124 ,0,0,0}, - {36678,36679,36680 ,729,726,726 ,0,0,0}, {35806,34092,35831 ,728,726,726 ,0,0,0}, - {34964,34958,36681 ,726,729,20124 ,0,0,0}, {34156,34512,34153 ,726,726,726 ,0,0,0}, - {34506,36682,34491 ,726,726,726 ,0,0,0}, {34507,34510,34156 ,726,726,726 ,0,0,0}, - {36683,36073,36684 ,726,726,726 ,0,0,0}, {36685,36064,34487 ,726,726,728 ,0,0,0}, - {36686,34498,36687 ,726,726,726 ,0,0,0}, {34498,36686,34500 ,726,726,726 ,0,0,0}, - {36062,36061,34485 ,726,726,726 ,0,0,0}, {34256,36686,36688 ,726,726,726 ,0,0,0}, - {36689,34158,36690 ,726,726,729 ,0,0,0}, {36688,36691,34256 ,726,726,726 ,0,0,0}, - {34257,36691,36255 ,726,726,726 ,0,0,0}, {34260,34257,36255 ,726,726,726 ,0,0,0}, - {36055,36052,34476 ,726,726,726 ,0,0,0}, {36692,36693,36694 ,729,726,726 ,0,0,0}, - {36695,36696,36697 ,726,726,728 ,0,0,0}, {36698,36699,36700 ,726,729,728 ,0,0,0}, - {36049,36046,34067 ,726,726,728 ,0,0,0}, {35820,36701,35815 ,726,726,726 ,0,0,0}, - {35818,36258,36702 ,726,726,726 ,0,0,0}, {36703,36704,36198 ,726,726,726 ,0,0,0}, - {34070,34462,34460 ,726,726,726 ,0,0,0}, {36705,36706,36707 ,726,726,726 ,0,0,0}, - {36708,34238,36709 ,726,726,726 ,0,0,0}, {34556,36104,34557 ,726,726,726 ,0,0,0}, - {34463,34069,34466 ,728,726,726 ,0,0,0}, {36108,34560,36106 ,726,728,726 ,0,0,0}, - {36710,34468,34072 ,726,726,726 ,0,0,0}, {34566,36188,36711 ,726,726,726 ,0,0,0}, - {34562,36188,34564 ,726,726,726 ,0,0,0}, {35838,35837,36712 ,726,726,726 ,0,0,0}, - {36713,34327,36714 ,726,726,726 ,0,0,0}, {36715,35808,36716 ,726,728,726 ,0,0,0}, - {34566,36711,34567 ,726,726,726 ,0,0,0}, {34072,34468,34466 ,726,726,726 ,0,0,0}, - {36188,34566,34564 ,726,726,726 ,0,0,0}, {36717,35848,34344 ,726,726,726 ,0,0,0}, - {35840,36712,36718 ,726,726,726 ,0,0,0}, {34341,36719,36717 ,726,726,726 ,0,0,0}, - {36720,36721,36722 ,726,726,728 ,0,0,0}, {34338,34530,34528 ,726,726,728 ,0,0,0}, - {34532,36723,36724 ,726,726,726 ,0,0,0}, {36725,36726,34324 ,726,726,726 ,0,0,0}, - {36727,36728,36729 ,726,726,726 ,0,0,0}, {36730,34535,36731 ,726,726,726 ,0,0,0}, - {36724,34535,34534 ,726,726,726 ,0,0,0}, {34970,36732,34967 ,726,726,726 ,0,0,0}, - {36733,36720,36734 ,726,726,726 ,0,0,0}, {36735,36678,36736 ,726,729,728 ,0,0,0}, - {36678,36737,36736 ,729,726,728 ,0,0,0}, {34965,36738,36739 ,726,20124,726 ,0,0,0}, - {36676,36740,36741 ,20124,726,20124 ,0,0,0}, {36738,36740,36676 ,20124,726,20124 ,0,0,0}, - {36675,36178,36669 ,20124,726,20124 ,0,0,0}, {36670,36673,36671 ,727,20124,726 ,0,0,0}, - {36669,36671,36675 ,20124,726,20124 ,0,0,0}, {36672,36742,36673 ,726,727,20124 ,0,0,0}, - {36665,36743,36744 ,20124,726,726 ,0,0,0}, {36672,36745,36742 ,726,727,727 ,0,0,0}, - {36746,36668,36667 ,20124,726,20124 ,0,0,0}, {36747,35237,36748 ,726,726,727 ,0,0,0}, - {36182,35181,36749 ,726,20124,20124 ,0,0,0}, {35350,35353,36750 ,727,726,727 ,0,0,0}, - {35754,35580,35582 ,726,20124,20124 ,0,0,0}, {36202,36751,36752 ,726,726,726 ,0,0,0}, - {35169,36195,35162 ,727,726,726 ,0,0,0}, {35345,35344,36753 ,726,726,726 ,0,0,0}, - {36195,35169,35168 ,726,727,20124 ,0,0,0}, {35332,35337,36754 ,726,726,726 ,0,0,0}, - {36755,35384,35383 ,726,726,726 ,0,0,0}, {35552,35553,36756 ,726,726,727 ,0,0,0}, - {36209,36750,35353 ,726,727,726 ,0,0,0}, {35131,36206,35206 ,20124,20124,726 ,0,0,0}, - {35205,35202,36205 ,726,20124,20124 ,0,0,0}, {35205,36205,35131 ,726,20124,20124 ,0,0,0}, - {36757,35202,35200 ,20124,20124,20124 ,0,0,0}, {35202,36757,36205 ,20124,20124,20124 ,0,0,0}, - {35199,36758,35200 ,726,726,20124 ,0,0,0}, {36757,35200,36758 ,20124,20124,726 ,0,0,0}, - {35575,36758,35196 ,727,726,726 ,0,0,0}, {36758,35199,35196 ,726,726,726 ,0,0,0}, - {36758,35575,36759 ,726,727,726 ,0,0,0}, {35196,35194,36760 ,726,20124,726 ,0,0,0}, - {35575,35574,36759 ,727,726,726 ,0,0,0}, {35188,36761,35190 ,726,726,726 ,0,0,0}, - {36762,35184,36763 ,20124,20124,726 ,0,0,0}, {35187,36764,36765 ,726,726,20124 ,0,0,0}, - {35132,35137,36766 ,726,726,20124 ,0,0,0}, {36767,36768,35136 ,726,20124,726 ,0,0,0}, - {36769,35139,36770 ,726,20124,20124 ,0,0,0}, {36770,35139,36771 ,20124,20124,726 ,0,0,0}, - {35582,35583,35756 ,20124,20124,726 ,0,0,0}, {36772,35149,36773 ,20124,726,726 ,0,0,0}, - {35141,35143,36774 ,726,726,726 ,0,0,0}, {35150,36775,36776 ,726,20124,727 ,0,0,0}, - {35145,36777,36778 ,726,726,20124 ,0,0,0}, {36779,36780,35155 ,726,726,726 ,0,0,0}, - {35155,36780,35153 ,726,726,20124 ,0,0,0}, {36181,35763,35764 ,726,726,726 ,0,0,0}, - {35157,36194,36779 ,726,726,726 ,0,0,0}, {36202,36781,35775 ,726,726,726 ,0,0,0}, - {36174,35775,36781 ,20124,726,726 ,0,0,0}, {36201,36782,36202 ,20124,20124,726 ,0,0,0}, - {35159,35162,36195 ,20124,726,726 ,0,0,0}, {35172,36195,35167 ,20124,726,727 ,0,0,0}, - {36195,35168,35167 ,726,20124,727 ,0,0,0}, {35176,36195,35174 ,726,726,727 ,0,0,0}, - {36195,35172,35174 ,726,20124,727 ,0,0,0}, {36182,35176,35163 ,726,726,726 ,0,0,0}, - {35179,36182,35180 ,20124,726,726 ,0,0,0}, {36182,35163,35180 ,726,726,726 ,0,0,0}, - {36182,36749,36183 ,726,20124,726 ,0,0,0}, {36182,36184,36783 ,726,20124,20124 ,0,0,0}, - {36746,36667,36182 ,20124,20124,726 ,0,0,0}, {36182,36783,36746 ,726,20124,20124 ,0,0,0}, - {36636,36635,36743 ,20124,726,726 ,0,0,0}, {36634,36636,36668 ,20124,20124,726 ,0,0,0}, - {36665,36744,36666 ,20124,726,726 ,0,0,0}, {36743,36635,36744 ,726,726,726 ,0,0,0}, - {36514,36784,36512 ,726,726,20124 ,0,0,0}, {36513,36512,36665 ,726,20124,20124 ,0,0,0}, - {36784,36664,35253 ,726,726,20124 ,0,0,0}, {36512,36784,36745 ,20124,726,727 ,0,0,0}, - {35244,36663,36785 ,726,726,726 ,0,0,0}, {36786,36748,35239 ,726,727,20124 ,0,0,0}, - {35243,36638,35241 ,726,726,726 ,0,0,0}, {35232,35237,36747 ,726,726,726 ,0,0,0}, - {35236,36787,35283 ,726,20124,20124 ,0,0,0}, {36788,36633,35290 ,726,20124,726 ,0,0,0}, - {35284,36789,35287 ,20124,726,726 ,0,0,0}, {36631,35294,36632 ,726,20124,726 ,0,0,0}, - {35255,36784,35253 ,726,726,20124 ,0,0,0}, {35307,35462,35469 ,726,727,726 ,0,0,0}, - {35443,35449,36790 ,726,727,726 ,0,0,0}, {36791,35654,35652 ,726,726,726 ,0,0,0}, - {36792,36793,36794 ,20124,20124,726 ,0,0,0}, {36795,36790,35449 ,727,726,727 ,0,0,0}, - {36796,35616,36797 ,726,727,727 ,0,0,0}, {36798,36799,36800 ,726,726,726 ,0,0,0}, - {35437,36801,35432 ,726,727,726 ,0,0,0}, {36802,36803,35635 ,726,726,727 ,0,0,0}, - {36790,36804,35443 ,726,727,726 ,0,0,0}, {36805,35450,35453 ,726,727,726 ,0,0,0}, - {35449,35445,36795 ,727,726,727 ,0,0,0}, {36478,36475,36481 ,727,727,726 ,0,0,0}, - {36476,36806,36477 ,726,727,726 ,0,0,0}, {36177,36807,36808 ,20124,726,727 ,0,0,0}, - {36480,36176,36175 ,727,726,727 ,0,0,0}, {36807,36809,36810 ,726,726,726 ,0,0,0}, - {36809,36811,36810 ,726,727,726 ,0,0,0}, {35225,35381,35228 ,726,727,727 ,0,0,0}, - {36812,36813,36814 ,727,726,20124 ,0,0,0}, {35516,36815,36466 ,726,1792,1793 ,0,0,0}, - {35632,36510,35634 ,726,726,726 ,0,0,0}, {35374,35217,35216 ,727,726,726 ,0,0,0}, - {35363,35219,35376 ,726,726,20124 ,0,0,0}, {35213,35372,35216 ,726,20124,726 ,0,0,0}, - {36816,35507,35506 ,1793,1793,1792 ,0,0,0}, {35211,35367,35213 ,726,727,726 ,0,0,0}, - {36817,36818,36819 ,1793,1793,727 ,0,0,0}, {35368,35367,35211 ,726,727,726 ,0,0,0}, - {35369,35368,35210 ,726,726,726 ,0,0,0}, {35422,36337,35423 ,1793,726,1793 ,0,0,0}, - {35217,35376,35219 ,726,20124,726 ,0,0,0}, {36337,35419,36327 ,726,726,726 ,0,0,0}, - {35419,36337,35422 ,726,726,1793 ,0,0,0}, {36327,35417,35416 ,726,726,726 ,0,0,0}, - {35419,35417,36327 ,726,726,726 ,0,0,0}, {36820,35410,35407 ,727,1793,1793 ,0,0,0}, - {35416,35413,36327 ,726,727,726 ,0,0,0}, {36821,35402,36822 ,727,1793,727 ,0,0,0}, - {36823,35331,35405 ,1793,726,1793 ,0,0,0}, {35399,36824,35400 ,1793,726,1793 ,0,0,0}, - {36824,36822,35400 ,726,727,1793 ,0,0,0}, {35394,35743,35396 ,726,726,1793 ,0,0,0}, - {35359,35362,35206 ,726,727,726 ,0,0,0}, {35732,36825,35731 ,726,1792,1792 ,0,0,0}, - {35393,35545,35544 ,726,726,727 ,0,0,0}, {35390,35388,36826 ,1793,726,20124 ,0,0,0}, - {35393,35390,35545 ,726,1793,726 ,0,0,0}, {36210,35359,36206 ,726,726,20124 ,0,0,0}, - {35387,36827,36828 ,1793,727,727 ,0,0,0}, {35355,35357,36209 ,726,727,726 ,0,0,0}, - {36829,36830,35336 ,726,727,20124 ,0,0,0}, {35343,36831,36832 ,726,726,726 ,0,0,0}, - {35341,35343,36832 ,726,726,726 ,0,0,0}, {35355,36209,35353 ,726,726,726 ,0,0,0}, - {35535,36213,35538 ,726,726,727 ,0,0,0}, {35349,36275,36831 ,727,727,726 ,0,0,0}, - {35350,36753,35344 ,727,726,726 ,0,0,0}, {35531,35546,36833 ,727,726,726 ,0,0,0}, - {36833,35535,35534 ,726,726,726 ,0,0,0}, {35556,36834,36756 ,727,727,727 ,0,0,0}, - {35350,36750,36753 ,727,727,726 ,0,0,0}, {35359,36210,35357 ,726,726,727 ,0,0,0}, - {36206,35359,35206 ,20124,726,726 ,0,0,0}, {35362,35369,35207 ,727,726,726 ,0,0,0}, - {35368,35211,35210 ,726,726,726 ,0,0,0}, {35372,35213,35367 ,20124,726,727 ,0,0,0}, - {35217,35374,35376 ,726,727,20124 ,0,0,0}, {35219,35363,35222 ,726,726,726 ,0,0,0}, - {35380,35223,35222 ,726,20124,726 ,0,0,0}, {35222,35363,35380 ,726,726,726 ,0,0,0}, - {35225,35223,35379 ,726,20124,726 ,0,0,0}, {36812,35228,35381 ,727,727,727 ,0,0,0}, - {35381,35225,35379 ,727,726,726 ,0,0,0}, {36813,36338,36814 ,726,20124,20124 ,0,0,0}, - {36812,36814,35228 ,727,20124,727 ,0,0,0}, {35511,36835,36815 ,727,727,1792 ,0,0,0}, - {36339,36811,36340 ,727,727,727 ,0,0,0}, {36813,36339,36338 ,726,727,20124 ,0,0,0}, - {36836,35612,35613 ,727,726,726 ,0,0,0}, {36340,36811,36809 ,727,727,726 ,0,0,0}, - {36807,36810,36808 ,726,726,727 ,0,0,0}, {35302,36837,35305 ,20124,726,726 ,0,0,0}, - {36177,36808,36175 ,20124,727,727 ,0,0,0}, {36176,36480,36481 ,726,727,726 ,0,0,0}, - {36838,36806,36839 ,726,727,727 ,0,0,0}, {36477,36806,36838 ,726,727,726 ,0,0,0}, - {36805,35453,36840 ,726,726,726 ,0,0,0}, {36838,36839,36841 ,726,727,727 ,0,0,0}, - {36804,35441,35443 ,727,726,726 ,0,0,0}, {36795,35445,36842 ,727,726,726 ,0,0,0}, - {36843,35437,35439 ,20124,726,727 ,0,0,0}, {36801,35437,36843 ,727,726,20124 ,0,0,0}, - {36844,36845,35436 ,726,727,20124 ,0,0,0}, {36845,35483,35436 ,727,726,20124 ,0,0,0}, - {36846,35640,35642 ,727,20124,20124 ,0,0,0}, {36845,36847,35483 ,727,726,726 ,0,0,0}, - {36469,36848,36849 ,726,726,726 ,0,0,0}, {36850,35607,36851 ,727,726,20124 ,0,0,0}, - {36852,36853,35598 ,726,727,727 ,0,0,0}, {36854,35592,35591 ,726,726,727 ,0,0,0}, - {35502,35500,36855 ,1793,1793,1792 ,0,0,0}, {36856,36852,35594 ,727,726,726 ,0,0,0}, - {36857,35505,35502 ,1792,1793,1793 ,0,0,0}, {36341,35528,35525 ,726,1793,726 ,0,0,0}, - {35523,36341,35525 ,1793,726,726 ,0,0,0}, {36857,36858,35505 ,1792,726,1793 ,0,0,0}, - {35431,36859,35506 ,726,726,1792 ,0,0,0}, {35505,36859,35431 ,1793,726,726 ,0,0,0}, - {36341,35523,35522 ,726,1793,1793 ,0,0,0}, {35511,36815,35513 ,727,1792,727 ,0,0,0}, - {35505,36347,36859 ,1793,727,726 ,0,0,0}, {35507,36816,35510 ,1793,1793,1793 ,0,0,0}, - {36345,36858,36860 ,727,726,727 ,0,0,0}, {36858,36345,36347 ,726,727,727 ,0,0,0}, - {36817,36861,36860 ,1793,1792,727 ,0,0,0}, {36345,36860,36861 ,727,727,1792 ,0,0,0}, - {36819,36818,36862 ,727,1793,1793 ,0,0,0}, {36819,36861,36817 ,727,1792,1793 ,0,0,0}, - {36862,36319,36863 ,1793,1793,726 ,0,0,0}, {36863,36819,36862 ,726,727,1793 ,0,0,0}, - {36864,36318,36320 ,726,1792,727 ,0,0,0}, {36319,36318,36863 ,1793,1792,726 ,0,0,0}, - {36865,36864,36866 ,1793,726,1793 ,0,0,0}, {36864,36865,36318 ,726,1793,1792 ,0,0,0}, - {36337,36865,36867 ,726,1793,726 ,0,0,0}, {36866,36867,36865 ,1793,726,1793 ,0,0,0}, - {36868,36337,36869 ,727,726,1792 ,0,0,0}, {36337,36867,36869 ,726,726,1792 ,0,0,0}, - {35428,36337,36870 ,1793,726,1793 ,0,0,0}, {36337,36868,36870 ,726,727,1793 ,0,0,0}, - {34951,36871,34140 ,726,726,20124 ,0,0,0}, {36872,34302,35065 ,20124,727,20124 ,0,0,0}, - {36873,36874,36875 ,20124,726,20124 ,0,0,0}, {34930,36120,36119 ,727,20124,727 ,0,0,0}, - {34927,36120,34930 ,726,20124,727 ,0,0,0}, {36125,34927,34926 ,726,726,20124 ,0,0,0}, - {34924,36128,36126 ,20124,726,727 ,0,0,0}, {36876,34940,34943 ,727,726,726 ,0,0,0}, - {34125,34128,34838 ,726,726,20124 ,0,0,0}, {34832,34126,34834 ,726,726,726 ,0,0,0}, - {36138,36137,36280 ,20124,20124,727 ,0,0,0}, {36877,35950,36228 ,727,20124,20124 ,0,0,0}, - {34831,36243,36878 ,726,727,726 ,0,0,0}, {36286,36242,34846 ,20124,20124,727 ,0,0,0}, - {34850,36237,36285 ,726,726,20124 ,0,0,0}, {36236,34852,34853 ,727,726,20124 ,0,0,0}, - {36879,36880,36881 ,20124,726,20124 ,0,0,0}, {34862,36882,36233 ,726,20124,20124 ,0,0,0}, - {36232,36283,34868 ,726,726,20124 ,0,0,0}, {34887,34889,34210 ,20124,726,726 ,0,0,0}, - {36883,36884,36885 ,726,726,726 ,0,0,0}, {36284,36886,34312 ,726,726,726 ,0,0,0}, - {36887,36888,34215 ,20124,726,726 ,0,0,0}, {36886,36889,34312 ,726,726,726 ,0,0,0}, - {36890,36891,34214 ,20124,20124,726 ,0,0,0}, {34316,34313,36290 ,20124,726,726 ,0,0,0}, - {36291,36892,36893 ,726,20124,20124 ,0,0,0}, {36894,36895,36896 ,726,726,726 ,0,0,0}, - {36897,36898,36899 ,726,726,726 ,0,0,0}, {36294,35074,35068 ,727,726,726 ,0,0,0}, - {36294,35068,36900 ,727,726,727 ,0,0,0}, {36901,36902,36903 ,727,726,726 ,0,0,0}, - {36904,35077,36905 ,726,726,726 ,0,0,0}, {36273,34909,34912 ,727,726,726 ,0,0,0}, - {34064,36906,35980 ,20124,726,726 ,0,0,0}, {36906,34064,34061 ,726,20124,726 ,0,0,0}, - {36907,36172,36908 ,727,727,726 ,0,0,0}, {36909,36910,36168 ,727,727,727 ,0,0,0}, - {36164,36165,34907 ,726,726,726 ,0,0,0}, {36911,36268,35975 ,20124,726,20124 ,0,0,0}, - {36266,36223,34904 ,726,727,727 ,0,0,0}, {36164,36267,36162 ,726,726,20124 ,0,0,0}, - {34428,34425,36912 ,20138,20130,20137 ,0,0,0}, {36913,36410,36412 ,20130,20168,20139 ,0,0,0}, - {34810,34808,36387 ,20127,20126,20148 ,0,0,0}, {34808,34805,36388 ,20126,20135,20162 ,0,0,0}, - {36394,36391,34804 ,20133,20163,20164 ,0,0,0}, {36396,34801,36914 ,20165,726,20130 ,0,0,0}, - {36396,36393,34802 ,20165,20124,1792 ,0,0,0}, {34826,34448,34447 ,20165,20165,20134 ,0,0,0}, - {34770,34434,34772 ,1792,1792,20124 ,0,0,0}, {36915,36916,36389 ,20126,20126,20137 ,0,0,0}, - {36917,34442,36918 ,20137,20167,20124 ,0,0,0}, {36919,35795,36920 ,20126,20126,1793 ,0,0,0}, - {35793,36921,36922 ,20170,20137,20137 ,0,0,0}, {34438,36923,36924 ,20162,1793,727 ,0,0,0}, - {35906,35905,35800 ,20125,20148,20167 ,0,0,0}, {36925,34431,36437 ,20147,20168,20130 ,0,0,0}, - {35911,35801,35905 ,20168,20170,20148 ,0,0,0}, {35804,35915,35914 ,1792,20168,20167 ,0,0,0}, - {36433,36432,36452 ,20140,20137,1793 ,0,0,0}, {36926,36927,36928 ,20148,1792,20140 ,0,0,0}, - {36929,36930,36931 ,727,20148,727 ,0,0,0}, {36932,35787,35786 ,20124,20167,1793 ,0,0,0}, - {34755,35784,36933 ,20168,20167,20137 ,0,0,0}, {36425,35779,34766 ,20139,1793,20170 ,0,0,0}, - {36934,36935,36936 ,20126,20162,20126 ,0,0,0}, {36413,34735,36937 ,1792,20169,20164 ,0,0,0}, - {36938,36411,36410 ,20147,1792,20168 ,0,0,0}, {36939,36938,36410 ,20168,20147,20168 ,0,0,0}, - {36940,36941,36942 ,20135,20168,20133 ,0,0,0}, {36943,36944,36945 ,20126,20139,20148 ,0,0,0}, - {36414,36941,34730 ,20133,20168,20139 ,0,0,0}, {34378,36946,36947 ,20132,1792,1792 ,0,0,0}, - {12820,36948,36406 ,20140,1792,20167 ,0,0,0}, {36912,35936,34428 ,20137,20169,20138 ,0,0,0}, - {36949,36950,34382 ,20131,20162,20135 ,0,0,0}, {34375,36951,36952 ,20165,20148,20132 ,0,0,0}, - {36912,34425,36953 ,20137,20130,20165 ,0,0,0}, {36954,36955,36956 ,20169,20168,20171 ,0,0,0}, - {36957,36955,36365 ,20172,20168,20142 ,0,0,0}, {36958,36359,35931 ,20132,20136,20148 ,0,0,0}, - {36959,36358,34718 ,20135,20134,20133 ,0,0,0}, {34716,36959,34718 ,20127,20135,20133 ,0,0,0}, - {34366,36960,34633 ,726,727,726 ,0,0,0}, {36961,36962,36963 ,727,726,727 ,0,0,0}, - {36964,36965,36966 ,726,726,726 ,0,0,0}, {36967,35852,36968 ,727,20124,20124 ,0,0,0}, - {36613,34626,34624 ,727,727,727 ,0,0,0}, {36589,36968,35855 ,20124,20124,726 ,0,0,0}, - {36969,36613,34624 ,726,727,727 ,0,0,0}, {36969,34624,34622 ,726,727,726 ,0,0,0}, - {34363,34635,34636 ,726,20124,726 ,0,0,0}, {36616,36594,36596 ,20124,726,726 ,0,0,0}, - {36579,36970,35862 ,20124,727,20124 ,0,0,0}, {36575,34692,34693 ,20124,727,727 ,0,0,0}, - {36044,34696,34698 ,20124,726,726 ,0,0,0}, {34699,36040,36042 ,20124,727,20124 ,0,0,0}, - {34702,34704,36037 ,20124,726,726 ,0,0,0}, {36571,36971,34704 ,20124,727,726 ,0,0,0}, - {34648,34646,36530 ,726,726,20124 ,0,0,0}, {34671,34098,34668 ,20124,726,20124 ,0,0,0}, - {36028,36972,36567 ,20124,20124,20124 ,0,0,0}, {34095,36014,34102 ,727,726,726 ,0,0,0}, - {34201,36573,36536 ,726,726,726 ,0,0,0}, {35992,35991,36973 ,20124,726,727 ,0,0,0}, - {36974,35997,35994 ,726,726,20124 ,0,0,0}, {36975,36976,36977 ,726,726,20124 ,0,0,0}, - {36564,36561,36584 ,20124,726,727 ,0,0,0}, {34608,36586,36978 ,726,727,726 ,0,0,0}, - {34198,36979,36980 ,726,727,726 ,0,0,0}, {36981,34605,36978 ,726,726,726 ,0,0,0}, - {34602,36601,34599 ,726,727,726 ,0,0,0}, {36982,36983,36006 ,726,726,726 ,0,0,0}, - {36009,36538,36010 ,726,727,726 ,0,0,0}, {36603,35892,34288 ,726,726,20124 ,0,0,0}, - {34186,36984,36985 ,726,726,726 ,0,0,0}, {36963,36986,36987 ,727,726,726 ,0,0,0}, - {35887,36539,35888 ,20124,726,726 ,0,0,0}, {36988,36989,36552 ,727,727,726 ,0,0,0}, - {34597,36554,36551 ,726,727,726 ,0,0,0}, {36990,36539,35887 ,20124,726,20124 ,0,0,0}, - {34596,36554,34597 ,727,727,726 ,0,0,0}, {36991,36992,36993 ,727,726,727 ,0,0,0}, - {34554,34553,36994 ,726,726,726 ,0,0,0}, {34569,34572,36244 ,726,729,726 ,0,0,0}, - {36995,36996,36997 ,729,726,726 ,0,0,0}, {34562,34560,36108 ,726,728,726 ,0,0,0}, - {34560,34557,36106 ,728,726,726 ,0,0,0}, {36101,36104,34556 ,726,726,726 ,0,0,0}, - {36994,34553,36998 ,726,726,726 ,0,0,0}, {36098,36100,36994 ,726,726,726 ,0,0,0}, - {34574,34575,34083 ,726,726,726 ,0,0,0}, {36999,36094,37000 ,726,726,726 ,0,0,0}, - {36089,36092,36247 ,726,726,728 ,0,0,0}, {36080,34075,34074 ,726,726,726 ,0,0,0}, - {36050,34459,34475 ,726,726,726 ,0,0,0}, {36052,36050,34475 ,726,726,726 ,0,0,0}, - {36056,36055,34479 ,726,726,726 ,0,0,0}, {36058,34481,34482 ,726,726,726 ,0,0,0}, - {37001,37002,34170 ,726,726,726 ,0,0,0}, {36598,36687,34498 ,726,726,726 ,0,0,0}, - {37003,37004,37001 ,726,729,726 ,0,0,0}, {36074,36073,36683 ,726,726,726 ,0,0,0}, - {36076,36074,37005 ,728,726,726 ,0,0,0}, {37006,37007,34159 ,728,726,726 ,0,0,0}, - {34518,37008,37009 ,728,726,726 ,0,0,0}, {37010,37011,37012 ,726,726,726 ,0,0,0}, - {36697,37013,36692 ,728,726,729 ,0,0,0}, {36705,37014,34254 ,726,726,726 ,0,0,0}, - {34240,37015,37016 ,726,726,726 ,0,0,0}, {37017,34547,34549 ,726,726,726 ,0,0,0}, - {36245,34543,36250 ,726,726,726 ,0,0,0}, {37018,36997,36996 ,726,726,726 ,0,0,0}, - {34541,36189,34538 ,729,726,726 ,0,0,0}, {37019,37020,37021 ,726,726,726 ,0,0,0}, - {37022,37023,37024 ,726,726,729 ,0,0,0}, {37025,37023,34246 ,726,726,728 ,0,0,0}, - {37026,37025,34246 ,726,726,728 ,0,0,0}, {34344,34341,36717 ,726,726,726 ,0,0,0}, - {37027,37028,34242 ,726,726,726 ,0,0,0}, {37029,37030,37031 ,726,726,726 ,0,0,0}, - {37032,37033,37034 ,726,726,726 ,0,0,0}, {37035,37036,35843 ,726,729,726 ,0,0,0}, - {37037,37038,37039 ,729,726,726 ,0,0,0}, {37040,34322,37041 ,726,726,726 ,0,0,0}, - {36927,37042,36928 ,1792,1793,20140 ,0,0,0}, {34785,37043,36436 ,1793,20168,1793 ,0,0,0}, - {36446,37044,37045 ,1793,20139,20162 ,0,0,0}, {37045,36445,36446 ,20162,20170,1793 ,0,0,0}, - {36457,37046,37045 ,726,20130,20162 ,0,0,0}, {36457,37045,37044 ,726,20162,20139 ,0,0,0}, - {37042,35787,36928 ,1793,20167,20140 ,0,0,0}, {36429,36930,37047 ,726,20148,1793 ,0,0,0}, - {34397,37048,36435 ,20168,20139,20125 ,0,0,0}, {36425,36932,35786 ,20139,20124,1793 ,0,0,0}, - {36932,36928,35787 ,20124,20140,20167 ,0,0,0}, {37049,37050,37051 ,1793,20168,20140 ,0,0,0}, - {35781,34761,35782 ,20139,727,20137 ,0,0,0}, {34746,34743,37052 ,20126,20137,20125 ,0,0,0}, - {36423,36422,36425 ,20139,20170,20139 ,0,0,0}, {37053,37054,36936 ,20147,1793,20126 ,0,0,0}, - {37055,37056,37057 ,20130,1793,20139 ,0,0,0}, {36933,36426,34739 ,20137,20162,726 ,0,0,0}, - {36434,36433,37052 ,20139,20140,20125 ,0,0,0}, {36451,36438,35914 ,20168,20125,20167 ,0,0,0}, - {36438,36451,36432 ,20125,20168,20137 ,0,0,0}, {35801,35915,35804 ,20170,20168,1792 ,0,0,0}, - {35804,35914,36439 ,1792,20167,20125 ,0,0,0}, {35801,35800,35905 ,20170,20167,20148 ,0,0,0}, - {35801,35911,35915 ,20170,20168,20168 ,0,0,0}, {37058,36921,35793 ,20139,20137,20170 ,0,0,0}, - {35793,35796,37058 ,20170,20125,20139 ,0,0,0}, {37059,35906,36922 ,20125,20125,20137 ,0,0,0}, - {37060,37061,12921 ,20137,20132,20140 ,0,0,0}, {37062,34797,37063 ,20167,20170,20139 ,0,0,0}, - {35580,35754,35751 ,20124,726,726 ,0,0,0}, {37064,36770,35761 ,726,20124,726 ,0,0,0}, - {35150,35153,36775 ,726,20124,20124 ,0,0,0}, {35136,35132,37065 ,726,726,20124 ,0,0,0}, - {35577,35580,35751 ,20124,20124,726 ,0,0,0}, {36199,35562,35561 ,20124,726,727 ,0,0,0}, - {35570,35568,36199 ,726,726,20124 ,0,0,0}, {36199,35751,35750 ,20124,726,726 ,0,0,0}, - {35763,36181,35747 ,726,726,726 ,0,0,0}, {35770,36181,35769 ,726,726,20124 ,0,0,0}, - {36181,35775,36173 ,726,726,726 ,0,0,0}, {36781,36202,36782 ,726,726,20124 ,0,0,0}, - {37066,36196,36195 ,20124,726,726 ,0,0,0}, {36752,36200,36202 ,726,20124,726 ,0,0,0}, - {36196,37067,36202 ,726,726,726 ,0,0,0}, {36751,36202,37067 ,726,726,726 ,0,0,0}, - {36196,37066,37068 ,726,20124,20124 ,0,0,0}, {37068,37067,36196 ,20124,726,726 ,0,0,0}, - {36194,35159,36195 ,726,20124,726 ,0,0,0}, {36779,35155,35157 ,726,726,726 ,0,0,0}, - {36775,35153,36780 ,20124,20124,726 ,0,0,0}, {35144,35150,36776 ,726,726,727 ,0,0,0}, - {35144,36777,35145 ,726,726,726 ,0,0,0}, {36777,35144,36776 ,726,726,727 ,0,0,0}, - {36773,35145,36778 ,726,726,20124 ,0,0,0}, {36772,35143,35149 ,20124,726,726 ,0,0,0}, - {36773,35149,35145 ,726,726,726 ,0,0,0}, {36774,36771,35141 ,726,726,726 ,0,0,0}, - {36772,36774,35143 ,20124,726,726 ,0,0,0}, {35588,35760,35586 ,726,726,726 ,0,0,0}, - {35141,36771,35139 ,726,726,20124 ,0,0,0}, {35754,35582,35756 ,726,20124,726 ,0,0,0}, - {35743,36824,35399 ,726,726,1793 ,0,0,0}, {35716,36315,35718 ,1793,1793,727 ,0,0,0}, - {35402,35400,36822 ,1793,1793,727 ,0,0,0}, {35722,36330,35724 ,1793,1793,726 ,0,0,0}, - {36336,36330,35719 ,726,1793,1793 ,0,0,0}, {36315,36336,35718 ,1793,726,727 ,0,0,0}, - {35731,36316,35715 ,1792,1793,727 ,0,0,0}, {36316,35716,35715 ,1793,1793,727 ,0,0,0}, - {35738,35741,36213 ,727,1793,726 ,0,0,0}, {36825,36316,35731 ,1792,1793,1792 ,0,0,0}, - {36317,35732,35735 ,1793,726,1793 ,0,0,0}, {35732,36317,36825 ,726,1793,1792 ,0,0,0}, - {35735,35737,36213 ,1793,1793,726 ,0,0,0}, {35737,35738,36213 ,1793,727,726 ,0,0,0}, - {35399,35396,35743 ,1793,1793,726 ,0,0,0}, {36821,35405,35402 ,727,1793,1793 ,0,0,0}, - {37069,36335,35413 ,727,726,727 ,0,0,0}, {36821,36823,35405 ,727,1793,1793 ,0,0,0}, - {37070,35406,36823 ,727,1792,1793 ,0,0,0}, {35331,36823,35406 ,726,1793,1792 ,0,0,0}, - {37070,36820,35407 ,727,727,1793 ,0,0,0}, {35407,35406,37070 ,1793,1792,727 ,0,0,0}, - {37069,35410,36820 ,727,1793,727 ,0,0,0}, {35411,37069,35413 ,727,727,727 ,0,0,0}, - {37069,35411,35410 ,727,727,1793 ,0,0,0}, {36334,37071,36327 ,1793,1792,726 ,0,0,0}, - {35413,36335,36327 ,727,726,726 ,0,0,0}, {36329,37072,36327 ,1793,1792,726 ,0,0,0}, - {37071,36328,36327 ,1792,727,726 ,0,0,0}, {36324,37072,36325 ,1793,1792,1793 ,0,0,0}, - {36329,36325,37072 ,1793,1793,1792 ,0,0,0}, {36324,36326,36323 ,1793,1792,1793 ,0,0,0}, - {35729,36323,36326 ,726,1793,1792 ,0,0,0}, {36852,35598,35595 ,726,727,726 ,0,0,0}, - {35694,36506,36485 ,1793,1793,1793 ,0,0,0}, {36500,36503,37073 ,727,727,1793 ,0,0,0}, - {36506,35690,36849 ,1793,1793,726 ,0,0,0}, {35690,36506,35692 ,1793,1793,726 ,0,0,0}, - {36849,35687,35686 ,726,1793,727 ,0,0,0}, {35690,35687,36849 ,1793,1793,726 ,0,0,0}, - {35700,36469,35699 ,726,726,1792 ,0,0,0}, {35686,35684,36849 ,727,1793,726 ,0,0,0}, - {37074,37075,36469 ,1793,1793,726 ,0,0,0}, {37076,37077,36469 ,1793,1793,726 ,0,0,0}, - {35706,35709,36469 ,727,1793,726 ,0,0,0}, {36853,37078,35600 ,727,1793,727 ,0,0,0}, - {35602,35600,37078 ,727,727,1793 ,0,0,0}, {35602,37078,37079 ,727,1793,726 ,0,0,0}, - {35602,37079,35604 ,727,726,727 ,0,0,0}, {35604,37080,35605 ,727,1792,726 ,0,0,0}, - {36498,36501,36497 ,726,727,726 ,0,0,0}, {36488,36490,36497 ,1793,1793,726 ,0,0,0}, - {36488,36497,36502 ,1793,726,727 ,0,0,0}, {36489,36499,36490 ,727,1792,1793 ,0,0,0}, - {36500,37073,36499 ,727,1793,1792 ,0,0,0}, {37081,36505,36504 ,1793,727,726 ,0,0,0}, - {36503,36505,37073 ,727,727,1793 ,0,0,0}, {37082,37081,36493 ,1792,1793,1792 ,0,0,0}, - {37081,37082,36505 ,1793,1792,727 ,0,0,0}, {36491,37083,36492 ,727,1793,1793 ,0,0,0}, - {37082,36493,36492 ,1792,1792,1793 ,0,0,0}, {36484,36483,37083 ,1793,726,1793 ,0,0,0}, - {36492,37083,36483 ,1793,1793,726 ,0,0,0}, {36483,36482,36487 ,726,1792,727 ,0,0,0}, - {35697,36487,36482 ,726,727,1792 ,0,0,0}, {37084,36645,36653 ,20124,726,726 ,0,0,0}, - {37085,36645,37084 ,20124,726,20124 ,0,0,0}, {36648,37086,36639 ,726,20124,20124 ,0,0,0}, - {37087,36658,36653 ,20124,726,726 ,0,0,0}, {37088,37089,35648 ,726,726,726 ,0,0,0}, - {35257,37090,36742 ,726,20124,727 ,0,0,0}, {37091,35646,35648 ,726,726,726 ,0,0,0}, - {36654,37092,35272 ,20124,20124,20124 ,0,0,0}, {36653,35281,37087 ,726,20124,20124 ,0,0,0}, - {35667,35668,36645 ,726,726,726 ,0,0,0}, {35673,36645,35671 ,726,726,20124 ,0,0,0}, - {35674,36644,35673 ,726,726,726 ,0,0,0}, {35677,36643,35674 ,20124,727,726 ,0,0,0}, - {35679,36646,36642 ,726,726,726 ,0,0,0}, {35679,36642,35677 ,726,726,20124 ,0,0,0}, - {36647,36648,36646 ,726,726,726 ,0,0,0}, {37086,36648,36649 ,20124,726,726 ,0,0,0}, - {36652,36639,36641 ,726,20124,726 ,0,0,0}, {36640,36639,37086 ,726,20124,20124 ,0,0,0}, - {36656,36651,36650 ,20124,20124,726 ,0,0,0}, {36650,36652,36641 ,726,726,726 ,0,0,0}, - {36662,36655,36657 ,726,726,726 ,0,0,0}, {36656,36655,36651 ,20124,726,20124 ,0,0,0}, - {36660,37093,36661 ,726,726,727 ,0,0,0}, {36662,36661,36655 ,726,727,726 ,0,0,0}, - {37094,37093,37095 ,726,726,20124 ,0,0,0}, {36660,37095,37093 ,726,20124,726 ,0,0,0}, - {37096,37094,37097 ,726,726,20124 ,0,0,0}, {37094,37095,37097 ,726,20124,20124 ,0,0,0}, - {35665,37094,37098 ,726,726,20124 ,0,0,0}, {37094,37096,37098 ,726,726,20124 ,0,0,0}, - {35453,35455,36840 ,726,726,726 ,0,0,0}, {37099,37100,37094 ,20124,726,726 ,0,0,0}, - {35322,35319,35463 ,726,726,726 ,0,0,0}, {35323,35479,35325 ,20124,726,726 ,0,0,0}, - {35457,35231,36841 ,727,20124,727 ,0,0,0}, {35296,37101,35299 ,726,726,726 ,0,0,0}, - {35299,37101,36208 ,726,726,20124 ,0,0,0}, {37091,35648,37089 ,726,726,726 ,0,0,0}, - {35255,36742,36745 ,726,727,727 ,0,0,0}, {37102,35658,37103 ,726,726,726 ,0,0,0}, - {37104,35658,37102 ,726,726,726 ,0,0,0}, {35660,37105,35662 ,20124,726,726 ,0,0,0}, - {37105,37106,35662 ,726,726,726 ,0,0,0}, {35665,35664,37107 ,726,727,726 ,0,0,0}, - {37108,37094,37088 ,726,726,726 ,0,0,0}, {35665,37109,37110 ,726,20124,727 ,0,0,0}, - {37094,37111,37099 ,726,20124,20124 ,0,0,0}, {37094,37108,37111 ,726,726,20124 ,0,0,0}, - {37112,36792,37100 ,20124,20124,726 ,0,0,0}, {37094,37100,36792 ,726,726,20124 ,0,0,0}, - {37113,36792,37114 ,20124,20124,726 ,0,0,0}, {36792,37112,37114 ,20124,20124,726 ,0,0,0}, - {36793,36792,37115 ,20124,20124,726 ,0,0,0}, {36792,37113,37115 ,20124,20124,726 ,0,0,0}, - {36794,37116,36792 ,726,726,20124 ,0,0,0}, {36798,36800,37116 ,726,726,726 ,0,0,0}, - {36792,37116,36800 ,20124,726,726 ,0,0,0}, {36800,36799,36803 ,726,726,726 ,0,0,0}, - {35635,36803,36799 ,727,726,726 ,0,0,0}, {37117,35618,37118 ,726,726,726 ,0,0,0}, - {35594,36852,35595 ,726,726,726 ,0,0,0}, {37119,37118,37120 ,726,726,727 ,0,0,0}, - {35499,36479,37121 ,1793,726,1793 ,0,0,0}, {35618,36797,35616 ,726,727,727 ,0,0,0}, - {37122,35496,35494 ,727,1793,726 ,0,0,0}, {35493,36508,37123 ,726,1792,1793 ,0,0,0}, - {35494,37123,37122 ,726,1793,727 ,0,0,0}, {35490,35488,36507 ,1793,726,726 ,0,0,0}, - {35490,36508,35493 ,1793,1792,726 ,0,0,0}, {35484,37124,35487 ,726,727,1793 ,0,0,0}, - {35306,35459,35462 ,726,726,727 ,0,0,0}, {37125,37117,37126 ,726,726,726 ,0,0,0}, - {36841,35231,37127 ,727,20124,726 ,0,0,0}, {35480,35323,35322 ,726,20124,726 ,0,0,0}, - {37128,37125,37126 ,726,726,726 ,0,0,0}, {35618,37120,37118 ,726,727,726 ,0,0,0}, - {37119,37129,37130 ,726,726,726 ,0,0,0}, {37120,37129,37119 ,727,726,726 ,0,0,0}, - {37131,36494,37130 ,726,726,726 ,0,0,0}, {37119,37130,36494 ,726,726,726 ,0,0,0}, - {37132,36494,37133 ,726,726,727 ,0,0,0}, {36494,37131,37133 ,726,726,727 ,0,0,0}, - {36496,37134,36494 ,726,727,726 ,0,0,0}, {36494,37132,36495 ,726,726,726 ,0,0,0}, - {36497,36494,37135 ,726,726,726 ,0,0,0}, {37134,37135,36494 ,727,726,726 ,0,0,0}, - {37136,36497,37137 ,727,726,726 ,0,0,0}, {36497,37135,37137 ,726,726,726 ,0,0,0}, - {36467,36497,37138 ,20124,726,727 ,0,0,0}, {36497,37136,37138 ,726,727,727 ,0,0,0}, - {36468,35605,37080 ,1793,726,1792 ,0,0,0}, {35137,36769,36766 ,726,726,20124 ,0,0,0}, - {35574,37139,36759 ,726,726,726 ,0,0,0}, {37139,35572,35570 ,726,726,726 ,0,0,0}, - {35574,35572,37139 ,726,726,726 ,0,0,0}, {35577,35751,36199 ,20124,726,20124 ,0,0,0}, - {37139,35570,36199 ,726,726,20124 ,0,0,0}, {35564,36199,35565 ,726,20124,20124 ,0,0,0}, - {36199,35568,35565 ,20124,726,20124 ,0,0,0}, {36199,35576,35577 ,20124,726,20124 ,0,0,0}, - {36199,35564,35562 ,20124,726,726 ,0,0,0}, {36199,35561,35576 ,20124,727,726 ,0,0,0}, - {35586,35758,35583 ,726,726,20124 ,0,0,0}, {35756,35583,35758 ,726,20124,726 ,0,0,0}, - {35588,37064,35761 ,726,726,726 ,0,0,0}, {35760,35758,35586 ,726,726,726 ,0,0,0}, - {35588,35761,35760 ,726,726,726 ,0,0,0}, {36769,36770,37064 ,726,20124,726 ,0,0,0}, - {36769,35137,35139 ,726,726,20124 ,0,0,0}, {37065,35132,36766 ,20124,726,20124 ,0,0,0}, - {35183,35136,36768 ,20124,726,20124 ,0,0,0}, {36767,35136,37065 ,726,726,20124 ,0,0,0}, - {35183,36763,35184 ,20124,726,20124 ,0,0,0}, {36763,35183,36768 ,726,20124,20124 ,0,0,0}, - {36762,35187,35184 ,20124,726,20124 ,0,0,0}, {36765,35188,35187 ,20124,726,726 ,0,0,0}, - {36762,36764,35187 ,20124,726,726 ,0,0,0}, {36761,36204,35190 ,726,726,726 ,0,0,0}, - {36765,36761,35188 ,20124,726,726 ,0,0,0}, {35193,36203,35194 ,20124,726,20124 ,0,0,0}, - {35190,36204,35193 ,726,726,20124 ,0,0,0}, {35196,36760,35575 ,726,726,727 ,0,0,0}, - {35194,36203,36760 ,20124,726,726 ,0,0,0}, {36213,35394,35544 ,726,726,727 ,0,0,0}, - {35393,35544,35394 ,726,727,726 ,0,0,0}, {35337,35339,37140 ,726,727,727 ,0,0,0}, - {35540,36213,35542 ,727,726,727 ,0,0,0}, {36213,35544,35542 ,726,727,727 ,0,0,0}, - {36213,35540,35538 ,726,727,727 ,0,0,0}, {36213,35535,36833 ,726,726,726 ,0,0,0}, - {36833,35532,35531 ,726,726,727 ,0,0,0}, {35534,35532,36833 ,726,726,726 ,0,0,0}, - {35547,36833,35546 ,726,726,726 ,0,0,0}, {36753,35558,35345 ,726,726,726 ,0,0,0}, - {35550,35552,36833 ,726,726,726 ,0,0,0}, {35550,36833,35547 ,726,726,726 ,0,0,0}, - {35558,36753,36834 ,726,726,727 ,0,0,0}, {35552,36756,36833 ,726,727,726 ,0,0,0}, - {35558,36834,35556 ,726,727,727 ,0,0,0}, {35553,35556,36756 ,726,727,727 ,0,0,0}, - {35558,36275,35345 ,726,727,726 ,0,0,0}, {36831,35343,35349 ,726,726,727 ,0,0,0}, - {36314,35341,36832 ,726,726,726 ,0,0,0}, {37140,35339,36314 ,727,727,726 ,0,0,0}, - {37141,36754,35337 ,726,726,726 ,0,0,0}, {37141,35337,37140 ,726,726,727 ,0,0,0}, - {36829,35332,36754 ,726,726,726 ,0,0,0}, {36830,35383,35336 ,727,726,20124 ,0,0,0}, - {36829,35336,35332 ,726,20124,726 ,0,0,0}, {35383,37142,36755 ,726,726,726 ,0,0,0}, - {36830,37142,35383 ,727,726,726 ,0,0,0}, {36755,36827,35384 ,726,727,726 ,0,0,0}, - {35387,36828,35388 ,1793,727,726 ,0,0,0}, {35384,36827,35387 ,726,727,1793 ,0,0,0}, - {35390,36826,35545 ,1793,20124,726 ,0,0,0}, {35388,36828,36826 ,726,727,20124 ,0,0,0}, - {35616,36796,35613 ,727,726,726 ,0,0,0}, {37121,36855,35500 ,1793,1792,1793 ,0,0,0}, - {35612,36836,37143 ,726,727,20124 ,0,0,0}, {35510,36816,36835 ,1793,1793,727 ,0,0,0}, - {35510,36835,35511 ,1793,727,727 ,0,0,0}, {36466,35517,35516 ,1793,726,726 ,0,0,0}, - {35513,36815,35516 ,727,1792,726 ,0,0,0}, {35506,36859,36816 ,1792,726,1793 ,0,0,0}, - {35505,36858,36347 ,1793,726,727 ,0,0,0}, {36857,35502,36855 ,1792,1793,1792 ,0,0,0}, - {35500,35499,37121 ,1793,1793,1793 ,0,0,0}, {35496,37122,36479 ,1793,727,726 ,0,0,0}, - {35493,37123,35494 ,726,1793,726 ,0,0,0}, {36507,35488,37144 ,726,726,1793 ,0,0,0}, - {35487,37124,37144 ,1793,727,1793 ,0,0,0}, {37144,35488,35487 ,1793,726,1793 ,0,0,0}, - {36847,37124,35484 ,726,727,726 ,0,0,0}, {36797,37117,37145 ,727,726,726 ,0,0,0}, - {37117,37125,37145 ,726,726,726 ,0,0,0}, {35483,36847,35484 ,726,726,726 ,0,0,0}, - {36844,35432,36801 ,726,726,727 ,0,0,0}, {35436,35432,36844 ,20124,726,726 ,0,0,0}, - {35439,35441,37146 ,727,726,20124 ,0,0,0}, {36843,35439,37146 ,20124,727,20124 ,0,0,0}, - {35307,35306,35462 ,726,726,727 ,0,0,0}, {35441,36804,37146 ,726,727,20124 ,0,0,0}, - {35444,37147,36842 ,726,726,726 ,0,0,0}, {35445,35444,36842 ,726,726,726 ,0,0,0}, - {37147,35450,36805 ,726,727,726 ,0,0,0}, {35450,37147,35444 ,727,726,726 ,0,0,0}, - {36839,36840,35455 ,727,726,726 ,0,0,0}, {36839,35457,36841 ,727,727,727 ,0,0,0}, - {35457,36839,35455 ,727,727,726 ,0,0,0}, {35468,35310,35469 ,726,726,726 ,0,0,0}, - {35231,35459,35306 ,20124,726,726 ,0,0,0}, {35319,35476,35463 ,726,20124,726 ,0,0,0}, - {35467,35472,35313 ,727,20124,726 ,0,0,0}, {35468,35467,35311 ,726,727,726 ,0,0,0}, - {35476,35319,35317 ,20124,726,726 ,0,0,0}, {35472,35474,35316 ,20124,727,726 ,0,0,0}, - {35476,35317,35474 ,20124,726,727 ,0,0,0}, {35463,35480,35322 ,726,726,726 ,0,0,0}, - {35480,35479,35323 ,726,726,20124 ,0,0,0}, {37128,37148,37149 ,726,727,726 ,0,0,0}, - {37127,35305,36837 ,726,726,726 ,0,0,0}, {36802,35635,36511 ,726,727,726 ,0,0,0}, - {37150,37151,37152 ,20124,20124,726 ,0,0,0}, {35481,37153,35328 ,727,727,727 ,0,0,0}, - {37154,37155,37156 ,727,727,727 ,0,0,0}, {37157,35636,37158 ,726,726,20124 ,0,0,0}, - {35622,35621,37159 ,726,727,726 ,0,0,0}, {37160,37161,37162 ,726,727,726 ,0,0,0}, - {37163,37164,37165 ,726,20124,727 ,0,0,0}, {35624,37166,35625 ,726,726,20124 ,0,0,0}, - {37167,37168,37169 ,727,727,726 ,0,0,0}, {37170,37171,37172 ,727,726,726 ,0,0,0}, - {36509,36630,35630 ,20124,726,726 ,0,0,0}, {36511,37173,36802 ,726,20124,726 ,0,0,0}, - {35634,36511,35635 ,726,726,727 ,0,0,0}, {36472,36519,36473 ,726,726,726 ,0,0,0}, - {37174,36628,37170 ,727,726,727 ,0,0,0}, {36627,36519,36518 ,20124,726,727 ,0,0,0}, - {37149,37148,37174 ,726,727,727 ,0,0,0}, {37148,36628,37174 ,727,726,727 ,0,0,0}, - {37126,37148,37128 ,726,727,726 ,0,0,0}, {36797,35618,37117 ,727,726,726 ,0,0,0}, - {36836,35613,36796 ,727,726,726 ,0,0,0}, {37143,36851,35610 ,20124,20124,726 ,0,0,0}, - {35610,35612,37143 ,726,726,20124 ,0,0,0}, {36850,35606,35607 ,727,726,726 ,0,0,0}, - {36851,35607,35610 ,20124,726,726 ,0,0,0}, {36854,35591,36850 ,726,727,727 ,0,0,0}, - {35606,36850,35591 ,726,727,727 ,0,0,0}, {35592,36854,36856 ,726,726,727 ,0,0,0}, - {35600,35598,36853 ,727,727,727 ,0,0,0}, {35594,35592,36856 ,726,726,727 ,0,0,0}, - {36467,36468,37175 ,20124,1793,727 ,0,0,0}, {37079,37080,35604 ,726,1792,727 ,0,0,0}, - {36469,36497,36467 ,726,726,20124 ,0,0,0}, {36467,37175,36469 ,20124,727,726 ,0,0,0}, - {35711,36498,36469 ,726,726,726 ,0,0,0}, {36470,36469,37175 ,726,726,727 ,0,0,0}, - {36469,35709,35711 ,726,1793,726 ,0,0,0}, {37176,36469,36471 ,1792,726,1793 ,0,0,0}, - {37177,37178,36469 ,1792,726,726 ,0,0,0}, {37176,37177,36469 ,1792,1792,726 ,0,0,0}, - {37179,37074,36469 ,727,1793,726 ,0,0,0}, {36469,35705,35706 ,726,1793,727 ,0,0,0}, - {35703,36469,35700 ,1793,726,726 ,0,0,0}, {36469,35683,35699 ,726,727,1792 ,0,0,0}, - {37075,37076,36469 ,1793,1793,726 ,0,0,0}, {37180,36848,36469 ,727,726,726 ,0,0,0}, - {36469,37077,37180 ,726,1793,727 ,0,0,0}, {35684,36469,36849 ,1793,726,726 ,0,0,0}, - {35684,35683,36469 ,1793,727,726 ,0,0,0}, {36848,37181,36849 ,726,1793,726 ,0,0,0}, - {36341,36849,37182 ,726,726,726 ,0,0,0}, {37181,37182,36849 ,1793,726,726 ,0,0,0}, - {37183,36341,37184 ,727,726,1792 ,0,0,0}, {36341,37182,37184 ,726,726,1792 ,0,0,0}, - {35528,36341,37185 ,1793,726,1793 ,0,0,0}, {36341,37183,37185 ,726,727,1793 ,0,0,0}, - {35643,35646,37186 ,20124,726,727 ,0,0,0}, {36207,35302,35300 ,726,20124,20124 ,0,0,0}, - {35643,37186,37187 ,20124,727,726 ,0,0,0}, {35310,35468,35311 ,726,726,726 ,0,0,0}, - {35316,35313,35472 ,726,726,20124 ,0,0,0}, {35317,35316,35474 ,726,726,727 ,0,0,0}, - {35311,35467,35313 ,726,727,726 ,0,0,0}, {35469,35310,35307 ,726,726,726 ,0,0,0}, - {35231,35457,35459 ,20124,727,726 ,0,0,0}, {37127,35231,35305 ,726,20124,726 ,0,0,0}, - {36837,35302,36207 ,726,20124,726 ,0,0,0}, {35300,35299,36208 ,20124,726,20124 ,0,0,0}, - {35296,36631,37101 ,726,726,726 ,0,0,0}, {35293,36632,35294 ,20124,726,20124 ,0,0,0}, - {35288,36788,35290 ,726,726,726 ,0,0,0}, {35290,36633,35293 ,726,20124,20124 ,0,0,0}, - {37188,35288,35287 ,726,726,726 ,0,0,0}, {35288,37188,36788 ,726,726,726 ,0,0,0}, - {36789,35284,37189 ,726,20124,726 ,0,0,0}, {37188,35287,36789 ,726,726,726 ,0,0,0}, - {35250,36663,35244 ,726,726,726 ,0,0,0}, {35283,36787,37189 ,20124,20124,726 ,0,0,0}, - {37189,35284,35283 ,726,20124,20124 ,0,0,0}, {37190,36787,35236 ,727,20124,726 ,0,0,0}, - {37190,35232,36747 ,727,726,726 ,0,0,0}, {35232,37190,35236 ,726,727,726 ,0,0,0}, - {36785,36612,35245 ,726,20124,726 ,0,0,0}, {35239,35241,36786 ,20124,726,726 ,0,0,0}, - {35237,35239,36748 ,726,20124,727 ,0,0,0}, {36612,36637,35249 ,20124,727,726 ,0,0,0}, - {36786,35241,36638 ,726,726,726 ,0,0,0}, {35243,35249,36637 ,726,726,727 ,0,0,0}, - {35245,35244,36785 ,726,726,726 ,0,0,0}, {36664,35250,35253 ,726,726,20124 ,0,0,0}, - {36745,36784,35255 ,727,726,726 ,0,0,0}, {35257,36742,35255 ,726,727,726 ,0,0,0}, - {37090,35259,37191 ,20124,20124,20124 ,0,0,0}, {35259,37090,35257 ,20124,20124,726 ,0,0,0}, - {37191,35262,35269 ,20124,726,727 ,0,0,0}, {35259,35262,37191 ,20124,726,20124 ,0,0,0}, - {35279,35281,36653 ,20124,20124,726 ,0,0,0}, {35268,37192,35269 ,20124,726,727 ,0,0,0}, - {37191,35269,37192 ,20124,727,726 ,0,0,0}, {35268,35267,37092 ,20124,727,20124 ,0,0,0}, - {37092,37192,35268 ,20124,726,20124 ,0,0,0}, {35280,35279,36653 ,726,20124,726 ,0,0,0}, - {35272,37092,35267 ,20124,20124,727 ,0,0,0}, {36654,35274,35276 ,20124,727,726 ,0,0,0}, - {35272,35274,36654 ,20124,727,20124 ,0,0,0}, {35276,35263,36653 ,726,726,726 ,0,0,0}, - {35263,35280,36653 ,726,726,726 ,0,0,0}, {37110,37088,37094 ,727,726,726 ,0,0,0}, - {36653,36659,37084 ,726,20124,20124 ,0,0,0}, {36645,37085,37193 ,726,20124,726 ,0,0,0}, - {37194,35651,36645 ,20124,726,726 ,0,0,0}, {36645,37193,37194 ,726,726,20124 ,0,0,0}, - {35652,37194,37195 ,726,20124,726 ,0,0,0}, {37194,35652,35651 ,20124,726,726 ,0,0,0}, - {35665,37110,37094 ,726,727,726 ,0,0,0}, {36791,37196,35654 ,726,726,726 ,0,0,0}, - {37195,36791,35652 ,726,726,726 ,0,0,0}, {37103,35655,37196 ,726,726,726 ,0,0,0}, - {35654,37196,35655 ,726,726,726 ,0,0,0}, {35665,37107,37109 ,726,726,20124 ,0,0,0}, - {35658,35655,37103 ,726,726,726 ,0,0,0}, {37104,37105,35660 ,726,726,20124 ,0,0,0}, - {35660,35658,37104 ,20124,726,726 ,0,0,0}, {35664,35662,37106 ,727,726,726 ,0,0,0}, - {37107,35664,37106 ,726,727,726 ,0,0,0}, {37110,37089,37088 ,727,726,726 ,0,0,0}, - {37186,35646,37091 ,727,726,726 ,0,0,0}, {37187,36846,35642 ,726,727,20124 ,0,0,0}, - {35642,35643,37187 ,20124,20124,726 ,0,0,0}, {37158,35640,36846 ,20124,20124,727 ,0,0,0}, - {35636,35637,37158 ,726,20124,20124 ,0,0,0}, {37158,35637,35640 ,20124,20124,20124 ,0,0,0}, - {35636,37157,35621 ,726,726,727 ,0,0,0}, {35622,37159,37166 ,726,726,726 ,0,0,0}, - {35621,37157,37159 ,727,726,726 ,0,0,0}, {36629,35625,37166 ,726,20124,726 ,0,0,0}, - {35624,35622,37166 ,726,726,726 ,0,0,0}, {36509,35628,36629 ,20124,726,726 ,0,0,0}, - {36630,36510,35632 ,726,726,726 ,0,0,0}, {36802,37173,36474 ,726,20124,726 ,0,0,0}, - {36519,36472,36520 ,726,726,726 ,0,0,0}, {36474,36473,36802 ,726,726,726 ,0,0,0}, - {36518,37171,36627 ,727,726,20124 ,0,0,0}, {36628,37171,37170 ,726,726,727 ,0,0,0}, - {36628,36627,37171 ,726,20124,726 ,0,0,0}, {37172,37197,37170 ,726,726,727 ,0,0,0}, - {37167,37197,37168 ,727,726,727 ,0,0,0}, {37172,37168,37197 ,726,727,726 ,0,0,0}, - {37167,37169,37198 ,727,726,727 ,0,0,0}, {37163,37165,37198 ,726,727,727 ,0,0,0}, - {37198,37169,37163 ,727,726,726 ,0,0,0}, {37161,37165,37164 ,727,727,20124 ,0,0,0}, - {37199,37160,37162 ,726,726,726 ,0,0,0}, {37162,37161,37164 ,726,727,20124 ,0,0,0}, - {37155,37199,37156 ,727,726,727 ,0,0,0}, {37199,37155,37160 ,726,727,726 ,0,0,0}, - {37156,37150,37154 ,727,20124,727 ,0,0,0}, {37152,37151,37153 ,726,20124,727 ,0,0,0}, - {37154,37150,37152 ,727,20124,726 ,0,0,0}, {35328,37153,37151 ,727,727,20124 ,0,0,0}, - {36738,37200,35127 ,20124,20124,726 ,0,0,0}, {37201,36738,37202 ,727,20124,726 ,0,0,0}, - {36738,35127,37202 ,20124,726,726 ,0,0,0}, {37203,36738,37204 ,726,20124,727 ,0,0,0}, - {36738,37201,37204 ,20124,727,727 ,0,0,0}, {36738,37205,36740 ,20124,726,726 ,0,0,0}, - {36738,37203,37205 ,20124,726,726 ,0,0,0}, {36676,37206,37207 ,20124,726,727 ,0,0,0}, - {36741,37206,36676 ,20124,726,20124 ,0,0,0}, {37200,35111,35109 ,20124,726,726 ,0,0,0}, - {37207,35119,36676 ,727,727,20124 ,0,0,0}, {35115,36677,35119 ,727,20124,727 ,0,0,0}, - {36676,35119,36677 ,20124,727,20124 ,0,0,0}, {35112,36677,35118 ,726,20124,726 ,0,0,0}, - {36677,35115,35118 ,20124,727,726 ,0,0,0}, {37200,36677,35111 ,20124,20124,726 ,0,0,0}, - {36677,35112,35111 ,20124,726,726 ,0,0,0}, {35121,37200,35108 ,726,20124,20124 ,0,0,0}, - {37200,35109,35108 ,20124,726,20124 ,0,0,0}, {35126,37200,35124 ,726,20124,726 ,0,0,0}, - {37200,35121,35124 ,20124,726,726 ,0,0,0}, {35127,37200,35126 ,726,20124,726 ,0,0,0}, - {36306,35097,35093 ,727,726,20124 ,0,0,0}, {36288,37208,36292 ,727,20124,727 ,0,0,0}, - {36292,37209,37210 ,727,726,726 ,0,0,0}, {37208,37209,36292 ,20124,726,727 ,0,0,0}, - {36293,36292,37211 ,727,727,20124 ,0,0,0}, {37210,37211,36292 ,726,20124,727 ,0,0,0}, - {37212,36293,37213 ,20124,727,726 ,0,0,0}, {36293,37211,37213 ,727,20124,726 ,0,0,0}, - {37214,36293,37215 ,20124,727,20124 ,0,0,0}, {36293,37212,37215 ,727,20124,20124 ,0,0,0}, - {36306,36293,37214 ,727,727,20124 ,0,0,0}, {36306,35090,35089 ,727,726,726 ,0,0,0}, - {36306,37214,35097 ,727,20124,726 ,0,0,0}, {36306,35096,35090 ,727,726,726 ,0,0,0}, - {36306,35093,35096 ,727,20124,726 ,0,0,0}, {36289,36306,35087 ,727,727,20124 ,0,0,0}, - {35089,35087,36306 ,726,20124,727 ,0,0,0}, {35099,36289,35086 ,726,727,727 ,0,0,0}, - {36289,35087,35086 ,727,20124,727 ,0,0,0}, {35104,36289,35102 ,727,727,726 ,0,0,0}, - {36289,35099,35102 ,727,726,726 ,0,0,0}, {35105,36289,35104 ,727,727,727 ,0,0,0}, - {35080,35082,37216 ,726,727,726 ,0,0,0}, {37217,37218,37219 ,726,727,20124 ,0,0,0}, - {37220,36300,37221 ,727,20124,726 ,0,0,0}, {36300,37220,36301 ,20124,727,726 ,0,0,0}, - {37220,36313,36289 ,727,726,727 ,0,0,0}, {37221,36313,37220 ,726,726,727 ,0,0,0}, - {36289,36312,36306 ,727,20124,727 ,0,0,0}, {36307,36309,36308 ,726,20124,726 ,0,0,0}, - {36310,36304,36308 ,20124,727,726 ,0,0,0}, {36295,36304,35075 ,727,727,726 ,0,0,0}, - {35071,36295,35075 ,20124,727,726 ,0,0,0}, {34302,35067,35065 ,727,726,20124 ,0,0,0}, - {35074,36294,35071 ,726,727,20124 ,0,0,0}, {37222,34296,36303 ,726,726,726 ,0,0,0}, - {37223,36883,36885 ,726,726,726 ,0,0,0}, {37224,35065,35064 ,727,20124,727 ,0,0,0}, - {36898,34915,37225 ,726,726,726 ,0,0,0}, {37226,36904,37227 ,726,726,20124 ,0,0,0}, - {35080,37216,35077 ,726,726,726 ,0,0,0}, {36905,35077,37216 ,726,726,726 ,0,0,0}, - {37216,35082,36311 ,726,727,727 ,0,0,0}, {35083,36311,35082 ,727,727,727 ,0,0,0}, - {35052,36454,37046 ,20148,20167,20130 ,0,0,0}, {36931,36930,36460 ,727,20148,1792 ,0,0,0}, - {36931,36460,36459 ,727,1792,20124 ,0,0,0}, {37047,36930,36929 ,1793,20148,727 ,0,0,0}, - {36428,36927,36926 ,20140,1792,20148 ,0,0,0}, {36430,36429,37047 ,1793,726,1793 ,0,0,0}, - {36428,36926,36429 ,20140,20148,726 ,0,0,0}, {37042,35053,35790 ,1793,20140,20147 ,0,0,0}, - {35790,35787,37042 ,20147,20167,1793 ,0,0,0}, {35053,36456,36450 ,20140,20147,20140 ,0,0,0}, - {35053,35049,36456 ,20140,1793,20147 ,0,0,0}, {35049,35052,37046 ,1793,20148,20130 ,0,0,0}, - {35049,37046,36457 ,1793,20130,726 ,0,0,0}, {35052,35046,36454 ,20148,1792,20167 ,0,0,0}, - {36455,35045,35043 ,727,726,1793 ,0,0,0}, {35046,35045,36455 ,1792,726,727 ,0,0,0}, - {35043,35042,36461 ,1793,20130,726 ,0,0,0}, {36462,36461,35055 ,20167,726,1792 ,0,0,0}, - {35042,35055,36461 ,20130,1792,726 ,0,0,0}, {36462,35058,36449 ,20167,20140,20140 ,0,0,0}, - {35061,36449,35060 ,726,20140,20130 ,0,0,0}, {36449,35058,35060 ,20140,20140,20130 ,0,0,0}, - {36528,35036,35038 ,727,726,727 ,0,0,0}, {36526,36619,35027 ,727,727,20124 ,0,0,0}, - {37228,36623,37229 ,20124,727,727 ,0,0,0}, {36623,35039,37229 ,727,727,727 ,0,0,0}, - {36623,37228,36624 ,727,20124,726 ,0,0,0}, {36526,35027,35030 ,727,20124,726 ,0,0,0}, - {36619,36623,37230 ,727,727,20124 ,0,0,0}, {36625,37230,36623 ,726,20124,727 ,0,0,0}, - {37231,36619,37232 ,20124,727,726 ,0,0,0}, {36619,37230,37232 ,727,20124,726 ,0,0,0}, - {37233,36619,37234 ,20124,727,20124 ,0,0,0}, {36619,37231,37234 ,727,20124,20124 ,0,0,0}, - {36619,35031,35027 ,727,726,20124 ,0,0,0}, {36619,37233,35031 ,727,20124,726 ,0,0,0}, - {36526,35024,35023 ,727,726,726 ,0,0,0}, {35030,35024,36526 ,726,726,727 ,0,0,0}, - {36528,36526,35021 ,727,727,20124 ,0,0,0}, {35023,35021,36526 ,726,20124,727 ,0,0,0}, - {35033,36528,35020 ,726,727,727 ,0,0,0}, {36528,35021,35020 ,727,20124,727 ,0,0,0}, - {35038,35039,36623 ,727,727,727 ,0,0,0}, {36528,35033,35036 ,727,726,726 ,0,0,0}, - {36623,36528,35038 ,727,727,727 ,0,0,0}, {37235,35017,36617 ,727,727,726 ,0,0,0}, - {37236,37237,36593 ,726,726,20124 ,0,0,0}, {37238,37239,37240 ,726,727,20124 ,0,0,0}, - {37240,34358,37241 ,20124,727,726 ,0,0,0}, {34614,37242,37243 ,20124,20124,726 ,0,0,0}, - {36562,36969,34622 ,727,726,726 ,0,0,0}, {34686,34684,34352 ,20124,20124,726 ,0,0,0}, - {37242,34614,34613 ,20124,20124,20124 ,0,0,0}, {36591,36622,36620 ,20124,20124,727 ,0,0,0}, - {36614,36608,36620 ,20124,726,727 ,0,0,0}, {35005,36608,35009 ,20124,726,726 ,0,0,0}, - {36623,34999,34998 ,727,20124,727 ,0,0,0}, {35008,36609,35005 ,726,727,20124 ,0,0,0}, - {36621,35002,35001 ,727,726,726 ,0,0,0}, {35008,35002,36621 ,726,726,727 ,0,0,0}, - {36621,35001,36619 ,727,726,727 ,0,0,0}, {36619,34999,36623 ,727,20124,727 ,0,0,0}, - {35011,35014,36618 ,726,726,726 ,0,0,0}, {36623,34998,36618 ,727,727,726 ,0,0,0}, - {35016,37235,35014 ,727,727,726 ,0,0,0}, {36618,35014,37235 ,726,726,727 ,0,0,0}, - {35017,37235,35016 ,727,727,727 ,0,0,0}, {36449,34986,34980 ,20140,20130,1793 ,0,0,0}, - {36448,37244,37245 ,20140,1792,20167 ,0,0,0}, {37246,36352,37247 ,20140,1792,727 ,0,0,0}, - {36352,34995,37247 ,1792,20130,727 ,0,0,0}, {37244,36352,37248 ,1792,1792,20140 ,0,0,0}, - {36352,37246,37248 ,1792,20140,20140 ,0,0,0}, {36448,36352,37244 ,20140,1792,1792 ,0,0,0}, - {37249,36448,37250 ,1792,20140,1793 ,0,0,0}, {36448,37245,37250 ,20140,20167,1793 ,0,0,0}, - {36448,37249,36464 ,20140,1792,20148 ,0,0,0}, {36463,34987,36448 ,1793,20140,20140 ,0,0,0}, - {34983,36449,34987 ,1793,20140,20140 ,0,0,0}, {36448,34987,36449 ,20140,20140,20140 ,0,0,0}, - {36449,34983,34986 ,20140,1793,20130 ,0,0,0}, {34976,36443,36449 ,20167,1792,20140 ,0,0,0}, - {34977,36449,34979 ,20167,20140,726 ,0,0,0}, {36449,34980,34979 ,20140,1793,726 ,0,0,0}, - {36449,34977,34976 ,20140,20167,20167 ,0,0,0}, {34992,36443,34989 ,726,1792,726 ,0,0,0}, - {36443,34976,34989 ,1792,20167,726 ,0,0,0}, {34995,36443,34994 ,20130,1792,727 ,0,0,0}, - {36443,34992,34994 ,1792,726,727 ,0,0,0}, {34955,37251,37252 ,728,726,726 ,0,0,0}, - {34964,36681,37200 ,726,20124,20124 ,0,0,0}, {36733,36680,36679 ,726,726,726 ,0,0,0}, - {36733,36679,36720 ,726,726,726 ,0,0,0}, {36680,36737,36678 ,726,726,729 ,0,0,0}, - {37253,37254,36735 ,726,726,726 ,0,0,0}, {37253,36735,36736 ,726,726,728 ,0,0,0}, - {37255,37254,37256 ,20124,726,726 ,0,0,0}, {37254,37255,36735 ,726,20124,726 ,0,0,0}, - {36738,37256,36739 ,20124,726,726 ,0,0,0}, {37255,37256,36738 ,20124,726,20124 ,0,0,0}, - {36738,34965,37200 ,20124,726,20124 ,0,0,0}, {34961,34964,37200 ,726,726,20124 ,0,0,0}, - {34965,34961,37200 ,726,726,20124 ,0,0,0}, {37252,34958,34957 ,726,729,726 ,0,0,0}, - {34958,37252,36681 ,729,726,20124 ,0,0,0}, {34955,34954,37251 ,728,726,726 ,0,0,0}, - {34957,34955,37252 ,726,728,726 ,0,0,0}, {36732,37251,34967 ,726,726,726 ,0,0,0}, - {34954,34967,37251 ,726,726,726 ,0,0,0}, {36732,34970,36713 ,726,726,726 ,0,0,0}, - {34535,36724,36731 ,726,726,726 ,0,0,0}, {36713,34970,34972 ,726,726,726 ,0,0,0}, - {34148,35963,35938 ,726,726,726 ,0,0,0}, {34936,34934,36114 ,727,727,727 ,0,0,0}, - {34144,35966,35964 ,20124,726,726 ,0,0,0}, {36122,34927,36125 ,727,726,726 ,0,0,0}, - {34926,34924,36126 ,20124,20124,727 ,0,0,0}, {34939,34940,36876 ,726,726,727 ,0,0,0}, - {36219,35943,36221 ,20124,726,20124 ,0,0,0}, {36876,36249,34939 ,727,726,726 ,0,0,0}, - {36128,34924,36270 ,726,20124,20124 ,0,0,0}, {36131,36270,36230 ,726,20124,726 ,0,0,0}, - {34943,34142,36876 ,726,726,727 ,0,0,0}, {34140,34139,34949 ,20124,726,726 ,0,0,0}, - {34142,34943,34945 ,726,726,20124 ,0,0,0}, {34125,34838,34835 ,726,20124,20124 ,0,0,0}, - {34144,37257,37258 ,20124,726,726 ,0,0,0}, {34145,35964,35963 ,20124,726,726 ,0,0,0}, - {34144,35969,35966 ,20124,20124,726 ,0,0,0}, {35972,35970,36259 ,726,726,726 ,0,0,0}, - {35969,37258,36259 ,20124,726,726 ,0,0,0}, {37259,36224,36260 ,20124,727,726 ,0,0,0}, - {36225,37260,36226 ,727,726,727 ,0,0,0}, {37259,36225,36224 ,20124,727,727 ,0,0,0}, - {34044,37261,36253 ,726,726,727 ,0,0,0}, {34900,34058,34902 ,727,726,726 ,0,0,0}, - {34907,36267,36164 ,726,726,726 ,0,0,0}, {34902,36266,34904 ,726,726,727 ,0,0,0}, - {36158,37262,37263 ,726,727,727 ,0,0,0}, {36222,36156,37263 ,727,727,727 ,0,0,0}, - {36152,36153,36265 ,20124,727,727 ,0,0,0}, {36147,34047,36146 ,727,727,726 ,0,0,0}, - {36265,34050,36150 ,727,727,726 ,0,0,0}, {34061,37264,36906 ,726,20124,726 ,0,0,0}, - {35976,35975,36268 ,726,20124,726 ,0,0,0}, {36272,36273,34912 ,20124,727,726 ,0,0,0}, - {36269,37265,34041 ,727,727,726 ,0,0,0}, {36159,37262,36158 ,726,727,726 ,0,0,0}, - {34897,34896,34055 ,726,20124,727 ,0,0,0}, {34893,34056,34894 ,20124,727,20124 ,0,0,0}, - {35980,37266,37267 ,726,20124,20124 ,0,0,0}, {34060,36274,34061 ,726,727,726 ,0,0,0}, - {34914,36897,36272 ,20124,726,20124 ,0,0,0}, {34299,36900,35068 ,726,727,726 ,0,0,0}, - {37225,34918,37268 ,726,726,727 ,0,0,0}, {36898,34914,34915 ,726,20124,726 ,0,0,0}, - {34920,37269,37268 ,726,726,727 ,0,0,0}, {34920,37268,34918 ,726,727,726 ,0,0,0}, - {37270,37271,34307 ,726,727,20124 ,0,0,0}, {37269,36302,37268 ,726,726,727 ,0,0,0}, - {34293,34296,37222 ,20124,726,726 ,0,0,0}, {37272,37273,37274 ,726,726,726 ,0,0,0}, - {37275,37276,37218 ,726,726,727 ,0,0,0}, {36905,37227,36904 ,726,20124,726 ,0,0,0}, - {37277,37278,37279 ,727,727,726 ,0,0,0}, {36900,34299,37280 ,727,726,727 ,0,0,0}, - {36908,37277,37281 ,726,727,727 ,0,0,0}, {37277,36908,37278 ,727,726,727 ,0,0,0}, - {36907,36271,36172 ,727,727,727 ,0,0,0}, {37281,36907,36908 ,727,727,726 ,0,0,0}, - {36271,36909,36170 ,727,727,727 ,0,0,0}, {36168,36910,36165 ,727,727,726 ,0,0,0}, - {36170,36909,36168 ,727,727,727 ,0,0,0}, {34907,36165,36910 ,726,726,727 ,0,0,0}, - {37282,34889,37283 ,20124,726,726 ,0,0,0}, {36889,36290,34313 ,726,726,726 ,0,0,0}, - {36896,37283,36894 ,726,726,726 ,0,0,0}, {34858,36234,34856 ,726,20124,20124 ,0,0,0}, - {34881,34883,34212 ,726,726,20124 ,0,0,0}, {34862,36233,34864 ,726,20124,726 ,0,0,0}, - {34878,34881,34212 ,727,726,20124 ,0,0,0}, {34862,34861,36882 ,726,726,20124 ,0,0,0}, - {34226,37284,37285 ,20124,726,727 ,0,0,0}, {37286,37287,37288 ,726,20124,20124 ,0,0,0}, - {36874,37289,36875 ,726,20124,20124 ,0,0,0}, {36873,36296,36298 ,20124,726,20124 ,0,0,0}, - {36888,37290,34218 ,726,726,20124 ,0,0,0}, {36890,34214,34207 ,20124,726,727 ,0,0,0}, - {37282,37291,34889 ,20124,20124,726 ,0,0,0}, {36896,37282,37283 ,726,20124,726 ,0,0,0}, - {36895,36894,37292 ,726,726,726 ,0,0,0}, {37292,36901,37293 ,726,727,20124 ,0,0,0}, - {37293,36895,37292 ,20124,726,726 ,0,0,0}, {37276,36903,36902 ,726,726,726 ,0,0,0}, - {36901,36903,37293 ,727,726,20124 ,0,0,0}, {37219,37272,37274 ,20124,726,726 ,0,0,0}, - {37276,37275,36903 ,726,726,726 ,0,0,0}, {37272,37294,37273 ,726,20124,726 ,0,0,0}, - {34310,37273,37295 ,726,726,727 ,0,0,0}, {37273,37294,37295 ,726,20124,727 ,0,0,0}, - {37274,37217,37219 ,726,726,20124 ,0,0,0}, {34293,37296,34294 ,20124,20124,20124 ,0,0,0}, - {37275,37226,37227 ,726,726,20124 ,0,0,0}, {34293,37222,37297 ,20124,726,726 ,0,0,0}, - {37298,34308,34307 ,726,726,20124 ,0,0,0}, {37223,36898,36883 ,726,726,726 ,0,0,0}, - {34312,34872,34870 ,726,726,20124 ,0,0,0}, {36279,34130,37299 ,20124,20124,726 ,0,0,0}, - {35955,35959,34229 ,726,20124,726 ,0,0,0}, {36137,36229,36280 ,20124,20124,727 ,0,0,0}, - {37300,36281,34134 ,726,20124,727 ,0,0,0}, {36278,37301,34131 ,726,20124,726 ,0,0,0}, - {36878,37299,34123 ,726,726,726 ,0,0,0}, {36243,34831,34846 ,727,726,727 ,0,0,0}, - {36286,34846,34847 ,20124,727,727 ,0,0,0}, {36285,34847,34850 ,20124,727,726 ,0,0,0}, - {36237,34852,36236 ,726,726,727 ,0,0,0}, {34853,34856,36235 ,20124,20124,20124 ,0,0,0}, - {37286,37288,37302 ,726,20124,726 ,0,0,0}, {37303,34858,37288 ,727,726,20124 ,0,0,0}, - {37288,34858,37302 ,20124,726,726 ,0,0,0}, {37303,37304,36234 ,727,726,20124 ,0,0,0}, - {37287,37284,34226 ,20124,726,20124 ,0,0,0}, {37284,37287,37286 ,726,20124,726 ,0,0,0}, - {36234,34858,37303 ,20124,726,727 ,0,0,0}, {34883,34884,34209 ,726,20124,726 ,0,0,0}, - {34887,34210,34884 ,20124,726,20124 ,0,0,0}, {37305,37306,34223 ,726,726,727 ,0,0,0}, - {37307,34224,37308 ,20124,726,727 ,0,0,0}, {35959,35958,34232 ,20124,727,726 ,0,0,0}, - {35958,37309,37310 ,727,726,726 ,0,0,0}, {34228,35949,34229 ,726,726,726 ,0,0,0}, - {35950,35949,34228 ,20124,726,726 ,0,0,0}, {36877,35952,35950 ,727,727,20124 ,0,0,0}, - {36221,36241,36276 ,20124,726,727 ,0,0,0}, {36877,36241,35952 ,727,726,727 ,0,0,0}, - {36277,37311,37312 ,726,726,726 ,0,0,0}, {36248,37312,34844 ,20124,726,726 ,0,0,0}, - {34845,37312,37311 ,727,726,726 ,0,0,0}, {35893,37313,35894 ,20130,20140,726 ,0,0,0}, - {36375,34814,36368 ,20153,20135,20144 ,0,0,0}, {35922,35920,34452 ,20137,20169,20140 ,0,0,0}, - {36388,34805,36391 ,20162,20135,20163 ,0,0,0}, {34804,34802,36394 ,20164,1792,20133 ,0,0,0}, - {34801,34816,36914 ,726,20136,20130 ,0,0,0}, {34816,36395,36914 ,20136,20140,20130 ,0,0,0}, - {36362,35899,36389 ,20139,20124,20137 ,0,0,0}, {36396,37314,36393 ,20165,20124,20124 ,0,0,0}, - {36395,34817,34820 ,20140,1793,1792 ,0,0,0}, {36354,37314,36396 ,20128,20124,20165 ,0,0,0}, - {34820,34450,36395 ,1792,20133,20140 ,0,0,0}, {34450,34820,34822 ,20133,1792,20131 ,0,0,0}, - {34776,34433,34436 ,20126,20137,1792 ,0,0,0}, {34433,34776,34773 ,20137,20126,20137 ,0,0,0}, - {34828,37315,34448 ,20169,20164,20165 ,0,0,0}, {34452,37316,37317 ,20140,20131,1793 ,0,0,0}, - {34453,35920,35919 ,20137,20169,20147 ,0,0,0}, {34452,35925,35922 ,20140,1792,20137 ,0,0,0}, - {35928,35926,36367 ,727,20137,20133 ,0,0,0}, {35925,37317,36367 ,1792,1793,20133 ,0,0,0}, - {37318,36384,36382 ,1792,1793,20136 ,0,0,0}, {36385,37319,36386 ,1792,20139,20161 ,0,0,0}, - {37318,36385,36384 ,1792,1792,1793 ,0,0,0}, {34408,37320,36390 ,20126,20136,20137 ,0,0,0}, - {34714,34422,34716 ,20126,20126,20127 ,0,0,0}, {34721,36358,36366 ,20127,20134,20143 ,0,0,0}, - {34716,34422,36959 ,20127,20126,20135 ,0,0,0}, {34815,34406,37321 ,20127,20130,20168 ,0,0,0}, - {36372,36374,36380 ,20131,20152,20158 ,0,0,0}, {36380,36379,36378 ,20158,20157,20156 ,0,0,0}, - {34414,34411,37322 ,20158,20146,20173 ,0,0,0}, {37063,36441,37062 ,20139,20147,20167 ,0,0,0}, - {37323,37324,37325 ,20131,20140,20136 ,0,0,0}, {37326,35798,36442 ,20139,20167,1793 ,0,0,0}, - {37327,37325,37324 ,20161,20136,20140 ,0,0,0}, {37327,12921,37061 ,20161,20140,20132 ,0,0,0}, - {36924,36918,34439 ,727,20124,1793 ,0,0,0}, {34438,36925,36923 ,20162,20147,1793 ,0,0,0}, - {36436,34769,34785 ,1793,726,1793 ,0,0,0}, {34786,37328,37043 ,20168,20168,20168 ,0,0,0}, - {37043,34785,34786 ,20168,1793,20168 ,0,0,0}, {37328,34789,36447 ,20168,20125,20130 ,0,0,0}, - {34789,37328,34786 ,20125,20168,20168 ,0,0,0}, {34791,36453,36447 ,20147,20124,20130 ,0,0,0}, - {36445,34795,34797 ,20170,20137,20170 ,0,0,0}, {34791,34792,36453 ,20147,727,20124 ,0,0,0}, - {36453,34795,36445 ,20124,20137,20170 ,0,0,0}, {36446,34797,37062 ,1793,20170,20167 ,0,0,0}, - {36441,36440,37062 ,20147,20124,20167 ,0,0,0}, {36442,35798,36440 ,1793,20167,20124 ,0,0,0}, - {35798,36920,35795 ,20167,1793,20126 ,0,0,0}, {36920,35798,37326 ,1793,20167,20139 ,0,0,0}, - {37329,35795,36919 ,1792,20126,20126 ,0,0,0}, {35796,37329,37058 ,20125,1792,20139 ,0,0,0}, - {37329,35796,35795 ,1792,20125,20126 ,0,0,0}, {35793,36922,35800 ,20170,20137,20167 ,0,0,0}, - {37059,35908,35906 ,20125,20139,20125 ,0,0,0}, {36922,35906,35800 ,20137,20125,20167 ,0,0,0}, - {36389,36444,36915 ,20137,20126,20126 ,0,0,0}, {37059,36444,35908 ,20125,20126,20139 ,0,0,0}, - {36916,37330,37331 ,20126,20168,20125 ,0,0,0}, {36392,37331,34782 ,20124,20125,726 ,0,0,0}, - {34783,37331,37330 ,20137,20125,20168 ,0,0,0}, {34743,36424,36434 ,20137,20137,20139 ,0,0,0}, - {34400,36435,37049 ,20140,20125,1793 ,0,0,0}, {34396,36427,37332 ,20148,20139,1793 ,0,0,0}, - {34396,37332,37048 ,20148,1793,20139 ,0,0,0}, {37052,36431,34746 ,20125,1793,20126 ,0,0,0}, - {34743,36434,37052 ,20137,20139,20125 ,0,0,0}, {34743,34742,36424 ,20137,20124,20137 ,0,0,0}, - {34739,36426,34740 ,726,20162,1792 ,0,0,0}, {36422,37056,37055 ,20170,1793,20130 ,0,0,0}, - {34754,34755,36933 ,1793,20168,20137 ,0,0,0}, {34754,36933,34739 ,1793,20137,726 ,0,0,0}, - {34758,35784,34755 ,20125,20167,20168 ,0,0,0}, {35784,34760,35781 ,20167,20147,20139 ,0,0,0}, - {34760,35784,34758 ,20147,20167,20125 ,0,0,0}, {34760,34761,35781 ,20147,727,20139 ,0,0,0}, - {35779,35782,34766 ,1793,20137,20170 ,0,0,0}, {36423,36425,34766 ,20139,20139,20170 ,0,0,0}, - {36422,36421,37056 ,20170,20147,1793 ,0,0,0}, {37055,37057,37053 ,20130,20139,20147 ,0,0,0}, - {36936,37054,36934 ,20126,1793,20126 ,0,0,0}, {37053,37057,37054 ,20147,20139,1793 ,0,0,0}, - {36935,36934,36411 ,20162,20126,1792 ,0,0,0}, {36420,36913,36412 ,20137,20130,20139 ,0,0,0}, - {36938,36935,36411 ,20147,20162,1792 ,0,0,0}, {36913,36420,36419 ,20130,20137,20167 ,0,0,0}, - {36418,36350,36419 ,20137,20125,20167 ,0,0,0}, {36419,36350,34394 ,20167,20125,1792 ,0,0,0}, - {36417,37333,36415 ,20168,20135,20169 ,0,0,0}, {37334,34392,34391 ,20168,20168,1793 ,0,0,0}, - {36940,37335,34729 ,20135,726,20131 ,0,0,0}, {37336,36409,34380 ,1793,20133,20133 ,0,0,0}, - {34727,34729,37335 ,1792,20131,726 ,0,0,0}, {34396,34750,34748 ,20148,20140,20137 ,0,0,0}, - {36359,35932,35931 ,20136,1793,20148 ,0,0,0}, {37337,37338,37339 ,20128,1793,20167 ,0,0,0}, - {37335,36356,34727 ,726,20131,1792 ,0,0,0}, {36361,37340,34405 ,20128,20169,20131 ,0,0,0}, - {37341,36377,36376 ,20174,20155,20154 ,0,0,0}, {34711,34710,34419 ,20135,20164,20133 ,0,0,0}, - {34707,34420,34708 ,726,20138,1792 ,0,0,0}, {35936,37342,37343 ,20169,727,727 ,0,0,0}, - {34424,36357,34425 ,20130,20132,20130 ,0,0,0}, {34383,36403,34386 ,20127,20134,20161 ,0,0,0}, - {36941,34729,34730 ,20168,20131,20139 ,0,0,0}, {36413,36937,37344 ,1792,20164,726 ,0,0,0}, - {36413,34733,34735 ,1792,20165,20169 ,0,0,0}, {34392,34753,34752 ,20168,20137,726 ,0,0,0}, - {34380,37344,37336 ,20133,726,1793 ,0,0,0}, {34377,34380,36409 ,20136,20133,20133 ,0,0,0}, - {37333,36941,36415 ,20135,20168,20169 ,0,0,0}, {37345,36943,36945 ,20130,20126,20148 ,0,0,0}, - {36405,36944,36406 ,20167,20139,20167 ,0,0,0}, {36948,12820,36404 ,1792,20140,20165 ,0,0,0}, - {36950,34383,34382 ,20162,20127,20135 ,0,0,0}, {36397,36951,37346 ,20132,20148,20139 ,0,0,0}, - {34375,36952,36949 ,20165,20132,20131 ,0,0,0}, {36401,36399,36398 ,20137,20166,20137 ,0,0,0}, - {36398,36397,37346 ,20137,20132,20139 ,0,0,0}, {36402,37339,36400 ,20138,20167,20167 ,0,0,0}, - {36401,36400,36399 ,20137,20167,20166 ,0,0,0}, {37337,36954,37338 ,20128,20169,1793 ,0,0,0}, - {36402,37337,37339 ,20138,20128,20167 ,0,0,0}, {36956,36955,36957 ,20171,20168,20172 ,0,0,0}, - {37338,36954,36956 ,1793,20169,20171 ,0,0,0}, {36365,36955,34721 ,20142,20168,20127 ,0,0,0}, - {37347,34358,37240 ,20124,727,20124 ,0,0,0}, {37348,35859,35864 ,726,726,727 ,0,0,0}, - {34117,35867,35871 ,726,726,20124 ,0,0,0}, {37243,37349,34616 ,726,20124,20124 ,0,0,0}, - {34616,37349,34617 ,20124,20124,726 ,0,0,0}, {36592,37236,36593 ,727,726,20124 ,0,0,0}, - {36595,34355,37350 ,726,726,726 ,0,0,0}, {36575,36535,34692 ,20124,727,727 ,0,0,0}, - {36575,34693,34696 ,20124,727,726 ,0,0,0}, {36044,34698,36042 ,20124,726,20124 ,0,0,0}, - {34699,34702,36040 ,20124,20124,727 ,0,0,0}, {34704,36036,36037 ,726,726,726 ,0,0,0}, - {36570,37351,36571 ,726,20124,20124 ,0,0,0}, {34114,37351,36531 ,20124,20124,726 ,0,0,0}, - {37351,36570,36531 ,20124,726,726 ,0,0,0}, {36036,34704,36971 ,726,726,727 ,0,0,0}, - {36582,36581,37352 ,727,20124,20124 ,0,0,0}, {36036,36971,36034 ,726,727,726 ,0,0,0}, - {34100,34662,34665 ,20124,727,726 ,0,0,0}, {34112,37353,37354 ,726,727,20124 ,0,0,0}, - {37355,36569,34652 ,726,726,20124 ,0,0,0}, {35871,35870,34120 ,20124,727,726 ,0,0,0}, - {35870,37356,37357 ,727,726,726 ,0,0,0}, {34116,35861,34117 ,726,726,726 ,0,0,0}, - {35862,35861,34116 ,20124,726,726 ,0,0,0}, {36970,35864,35862 ,727,727,20124 ,0,0,0}, - {36589,37348,36590 ,20124,726,727 ,0,0,0}, {36970,37348,35864 ,727,726,727 ,0,0,0}, - {36588,37358,37359 ,726,726,726 ,0,0,0}, {36529,37359,34690 ,20124,726,726 ,0,0,0}, - {34691,37359,37358 ,727,726,726 ,0,0,0}, {37360,35988,35986 ,726,726,20124 ,0,0,0}, - {35985,36574,35986 ,726,726,20124 ,0,0,0}, {35991,36563,36973 ,726,726,727 ,0,0,0}, - {37355,34652,34649 ,726,20124,20124 ,0,0,0}, {34667,34097,34100 ,726,726,20124 ,0,0,0}, - {34661,37361,34645 ,727,20124,726 ,0,0,0}, {34646,34645,36566 ,726,726,20124 ,0,0,0}, - {34667,34100,34665 ,726,20124,726 ,0,0,0}, {37361,34662,34100 ,20124,727,20124 ,0,0,0}, - {36583,37362,36581 ,726,726,20124 ,0,0,0}, {37363,37364,34111 ,726,726,727 ,0,0,0}, - {37365,36972,36030 ,20124,20124,726 ,0,0,0}, {36567,36568,36025 ,20124,726,726 ,0,0,0}, - {36022,36568,34106 ,726,726,20124 ,0,0,0}, {34102,36016,34103 ,726,726,726 ,0,0,0}, - {35982,34095,35985 ,726,727,726 ,0,0,0}, {35986,36574,37360 ,20124,726,726 ,0,0,0}, - {35988,37360,36563 ,726,726,726 ,0,0,0}, {36973,36974,35992 ,727,726,20124 ,0,0,0}, - {35997,36974,36585 ,726,726,726 ,0,0,0}, {35992,36974,35994 ,20124,726,20124 ,0,0,0}, - {36000,35998,36584 ,20124,20124,727 ,0,0,0}, {35998,35997,36585 ,20124,726,726 ,0,0,0}, - {36976,36565,36564 ,726,726,20124 ,0,0,0}, {36565,36976,36975 ,726,726,726 ,0,0,0}, - {36977,36979,36975 ,20124,727,726 ,0,0,0}, {36975,36979,34198 ,726,727,726 ,0,0,0}, - {36964,37366,36965 ,726,726,726 ,0,0,0}, {34659,34658,34196 ,727,726,726 ,0,0,0}, - {34604,37367,37368 ,20124,726,20124 ,0,0,0}, {37369,37367,36981 ,726,726,726 ,0,0,0}, - {34602,34604,37368 ,726,20124,20124 ,0,0,0}, {34200,34656,34654 ,726,726,20124 ,0,0,0}, - {35850,35849,37370 ,726,20124,20124 ,0,0,0}, {34372,35875,35850 ,726,726,726 ,0,0,0}, - {35876,34368,35878 ,726,20124,726 ,0,0,0}, {34617,37349,34620 ,726,20124,727 ,0,0,0}, - {37349,36562,34620 ,20124,727,727 ,0,0,0}, {34613,34629,37371 ,20124,726,726 ,0,0,0}, - {37243,34616,34614 ,726,20124,20124 ,0,0,0}, {36960,34629,34630 ,727,726,726 ,0,0,0}, - {36960,37371,34629 ,727,726,726 ,0,0,0}, {36960,34630,34633 ,727,726,726 ,0,0,0}, - {37371,37242,34613 ,726,20124,20124 ,0,0,0}, {34680,34350,34349 ,726,726,726 ,0,0,0}, - {34681,34349,34684 ,20124,726,20124 ,0,0,0}, {34364,34363,34639 ,20124,726,726 ,0,0,0}, - {34368,37372,37373 ,20124,726,726 ,0,0,0}, {34369,35876,35875 ,20124,726,726 ,0,0,0}, - {34368,35881,35878 ,20124,20124,726 ,0,0,0}, {35884,35882,36542 ,726,726,726 ,0,0,0}, - {35881,37373,36542 ,20124,726,726 ,0,0,0}, {37374,36550,36546 ,20124,727,726 ,0,0,0}, - {36548,37375,36549 ,727,726,727 ,0,0,0}, {37374,36548,36550 ,20124,727,727 ,0,0,0}, - {34268,37376,36604 ,726,726,727 ,0,0,0}, {34592,34590,34282 ,726,727,726 ,0,0,0}, - {34594,34592,36553 ,727,726,727 ,0,0,0}, {34592,34282,36553 ,726,726,727 ,0,0,0}, - {37377,37378,37379 ,726,726,727 ,0,0,0}, {37378,37377,37380 ,726,726,727 ,0,0,0}, - {37381,34274,37382 ,726,727,727 ,0,0,0}, {36545,36544,37380 ,727,726,727 ,0,0,0}, - {37382,34271,37383 ,727,727,726 ,0,0,0}, {34263,36607,34270 ,726,20124,726 ,0,0,0}, - {37384,36603,34285 ,20124,726,726 ,0,0,0}, {37385,37386,37387 ,727,726,20124 ,0,0,0}, - {37368,36601,34602 ,20124,727,726 ,0,0,0}, {36541,37388,34265 ,727,727,726 ,0,0,0}, - {36992,36991,37377 ,726,727,726 ,0,0,0}, {34587,34586,34279 ,726,20124,727 ,0,0,0}, - {34583,34280,34584 ,20124,727,20124 ,0,0,0}, {35892,37389,37390 ,726,20124,20124 ,0,0,0}, - {34284,36602,34285 ,726,727,726 ,0,0,0}, {37391,36984,34186 ,727,726,726 ,0,0,0}, - {36981,34604,34605 ,726,20124,726 ,0,0,0}, {36586,36587,37392 ,727,726,726 ,0,0,0}, - {36586,34608,34610 ,727,726,726 ,0,0,0}, {37393,37394,34181 ,726,726,20124 ,0,0,0}, - {37395,37393,34184 ,726,726,726 ,0,0,0}, {34184,37392,37395 ,726,726,726 ,0,0,0}, - {34181,34184,37393 ,20124,726,726 ,0,0,0}, {36981,36965,37366 ,726,726,726 ,0,0,0}, - {36006,36004,36982 ,726,726,726 ,0,0,0}, {36009,36983,36538 ,726,726,727 ,0,0,0}, - {36600,36537,34190 ,726,20124,727 ,0,0,0}, {36985,36599,34187 ,726,726,726 ,0,0,0}, - {37396,37391,34179 ,727,727,20124 ,0,0,0}, {37397,36986,36963 ,727,726,727 ,0,0,0}, - {36986,37396,36987 ,726,727,726 ,0,0,0}, {36961,37387,36962 ,727,20124,726 ,0,0,0}, - {36963,36962,37397 ,727,726,727 ,0,0,0}, {37385,36560,37386 ,727,727,726 ,0,0,0}, - {36961,37385,37387 ,727,727,20124 ,0,0,0}, {36559,36558,36988 ,727,727,727 ,0,0,0}, - {37386,36560,36559 ,726,727,727 ,0,0,0}, {36552,36989,34597 ,726,727,726 ,0,0,0}, - {36988,36558,36989 ,727,727,727 ,0,0,0}, {34092,34089,35831 ,726,726,726 ,0,0,0}, - {35805,37398,35806 ,726,726,728 ,0,0,0}, {34088,35834,35832 ,726,726,726 ,0,0,0}, - {36106,34557,36104 ,726,726,726 ,0,0,0}, {34556,34554,36101 ,726,726,726 ,0,0,0}, - {34553,34568,36998 ,726,726,726 ,0,0,0}, {36716,35811,36198 ,726,726,726 ,0,0,0}, - {36244,36998,34568 ,726,726,726 ,0,0,0}, {36244,34572,34086 ,726,729,726 ,0,0,0}, - {36100,34554,36994 ,726,726,726 ,0,0,0}, {36098,36994,37000 ,726,726,726 ,0,0,0}, - {34084,34083,34578 ,728,726,726 ,0,0,0}, {34086,34572,34574 ,726,729,726 ,0,0,0}, - {34072,34466,34069 ,726,726,726 ,0,0,0}, {34088,37399,37400 ,726,726,726 ,0,0,0}, - {34089,35832,35831 ,726,726,726 ,0,0,0}, {34088,35837,35834 ,726,726,726 ,0,0,0}, - {35840,35838,36712 ,726,726,726 ,0,0,0}, {35837,37400,36712 ,726,726,726 ,0,0,0}, - {37401,36728,36718 ,726,726,726 ,0,0,0}, {36729,37402,36727 ,726,726,726 ,0,0,0}, - {37401,36729,36728 ,726,726,726 ,0,0,0}, {34324,37403,36725 ,726,726,726 ,0,0,0}, - {36726,37404,34324 ,726,729,726 ,0,0,0}, {34530,34338,36723 ,726,726,726 ,0,0,0}, - {34321,34324,37404 ,726,726,729 ,0,0,0}, {34532,34530,36723 ,726,726,726 ,0,0,0}, - {34532,36724,34534 ,726,726,726 ,0,0,0}, {36722,36721,37405 ,728,726,726 ,0,0,0}, - {34973,37406,34330 ,729,726,726 ,0,0,0}, {37407,37406,34973 ,726,726,729 ,0,0,0}, - {34326,36714,34327 ,726,726,726 ,0,0,0}, {35844,35843,37036 ,726,726,729 ,0,0,0}, - {34537,34538,34333 ,726,726,726 ,0,0,0}, {36245,36189,34541 ,726,726,729 ,0,0,0}, - {37404,37041,34321 ,729,726,726 ,0,0,0}, {34528,34525,34338 ,728,726,726 ,0,0,0}, - {34525,34524,34335 ,726,726,726 ,0,0,0}, {34521,34336,34522 ,726,726,726 ,0,0,0}, - {35848,37408,37409 ,726,726,726 ,0,0,0}, {34340,36190,34341 ,726,726,726 ,0,0,0}, - {36251,34544,37410 ,726,726,726 ,0,0,0}, {36251,34543,34544 ,726,726,726 ,0,0,0}, - {34237,34240,37016 ,726,726,726 ,0,0,0}, {37411,37017,34549 ,726,726,726 ,0,0,0}, - {37017,37410,34547 ,726,726,726 ,0,0,0}, {34505,34504,34252 ,726,729,726 ,0,0,0}, - {37412,37015,34240 ,726,726,726 ,0,0,0}, {37411,37412,37017 ,726,726,726 ,0,0,0}, - {37413,36707,36706 ,726,726,726 ,0,0,0}, {37414,36696,36700 ,726,726,728 ,0,0,0}, - {37415,37019,37021 ,726,726,726 ,0,0,0}, {37415,37023,37022 ,726,726,726 ,0,0,0}, - {37416,37026,34243 ,726,726,728 ,0,0,0}, {37417,37027,34235 ,729,726,726 ,0,0,0}, - {37418,37032,37034 ,726,726,726 ,0,0,0}, {37032,37417,37033 ,726,729,726 ,0,0,0}, - {37418,37419,37031 ,726,726,726 ,0,0,0}, {37419,37418,37034 ,726,726,726 ,0,0,0}, - {37029,37420,37030 ,726,729,726 ,0,0,0}, {37419,37029,37031 ,726,726,726 ,0,0,0}, - {37038,37037,37420 ,726,729,729 ,0,0,0}, {37030,37420,37037 ,726,729,729 ,0,0,0}, - {37037,37039,36730 ,729,726,726 ,0,0,0}, {34535,36730,37039 ,726,726,726 ,0,0,0}, - {37421,37011,37422 ,729,726,726 ,0,0,0}, {37009,37008,37422 ,726,726,726 ,0,0,0}, - {36694,37010,37012 ,726,726,726 ,0,0,0}, {37423,34495,34494 ,726,728,726 ,0,0,0}, - {34485,34487,36062 ,726,728,726 ,0,0,0}, {34492,37424,37423 ,726,726,726 ,0,0,0}, - {34492,37423,34494 ,726,726,726 ,0,0,0}, {34510,34512,34156 ,726,726,726 ,0,0,0}, - {36682,34507,34156 ,726,726,726 ,0,0,0}, {34492,34491,37424 ,726,726,726 ,0,0,0}, - {36186,37425,36187 ,726,728,726 ,0,0,0}, {37426,37004,37427 ,726,729,726 ,0,0,0}, - {37428,36684,36070 ,726,726,726 ,0,0,0}, {36683,37005,36074 ,726,726,726 ,0,0,0}, - {37429,37005,34162 ,726,726,726 ,0,0,0}, {36690,34158,34151 ,729,726,726 ,0,0,0}, - {37009,37430,34518 ,726,726,728 ,0,0,0}, {37422,37008,37421 ,726,726,729 ,0,0,0}, - {37011,37421,37012 ,726,729,726 ,0,0,0}, {36693,36692,37013 ,726,729,726 ,0,0,0}, - {37010,36694,36693 ,726,726,726 ,0,0,0}, {37013,36697,37431 ,726,728,726 ,0,0,0}, - {36696,36695,36700 ,726,726,728 ,0,0,0}, {36696,37431,36697 ,726,726,728 ,0,0,0}, - {37413,36699,36698 ,726,729,726 ,0,0,0}, {36699,37413,36706 ,729,726,726 ,0,0,0}, - {36698,36700,36695 ,726,728,726 ,0,0,0}, {36706,36705,34254 ,726,726,726 ,0,0,0}, - {37432,37433,37434 ,726,726,726 ,0,0,0}, {37434,37433,37021 ,726,726,726 ,0,0,0}, - {34237,37016,37435 ,726,726,726 ,0,0,0}, {37436,34252,34251 ,729,726,726 ,0,0,0}, - {37018,36251,36997 ,726,726,726 ,0,0,0}, {34256,34502,34500 ,726,726,726 ,0,0,0}, - {36080,34074,36078 ,726,726,729 ,0,0,0}, {35823,35827,34173 ,729,728,728 ,0,0,0}, - {36092,36999,36247 ,726,726,728 ,0,0,0}, {36086,36246,34078 ,729,726,726 ,0,0,0}, - {36082,36083,34075 ,726,726,726 ,0,0,0}, {36046,36078,34067 ,726,729,728 ,0,0,0}, - {36050,36049,34459 ,726,726,726 ,0,0,0}, {36052,34475,34476 ,726,726,726 ,0,0,0}, - {36055,34476,34479 ,726,726,726 ,0,0,0}, {36056,34481,36058 ,726,726,726 ,0,0,0}, - {34482,34485,36061 ,726,726,726 ,0,0,0}, {37426,37427,34487 ,726,726,728 ,0,0,0}, - {34487,36064,36062 ,728,726,726 ,0,0,0}, {36685,36067,36064 ,726,726,726 ,0,0,0}, - {37427,37004,37003 ,726,729,726 ,0,0,0}, {37003,37001,34170 ,726,726,726 ,0,0,0}, - {36685,34487,37427 ,726,728,726 ,0,0,0}, {34512,34513,34153 ,726,726,726 ,0,0,0}, - {34516,34154,34513 ,726,726,726 ,0,0,0}, {37437,37438,34167 ,729,728,726 ,0,0,0}, - {37439,34168,37440 ,726,726,726 ,0,0,0}, {35827,35826,34176 ,728,726,726 ,0,0,0}, - {35826,37441,37442 ,726,726,726 ,0,0,0}, {34172,35817,34173 ,726,726,728 ,0,0,0}, - {35818,35817,34172 ,726,726,726 ,0,0,0}, {36702,35820,35818 ,726,726,726 ,0,0,0}, - {36198,36701,36703 ,726,726,726 ,0,0,0}, {36702,36701,35820 ,726,726,726 ,0,0,0}, - {36704,37443,37444 ,726,729,726 ,0,0,0}, {36710,37444,34472 ,726,726,729 ,0,0,0}, - {34473,37444,37443 ,726,726,729 ,0,0,0}, {34772,34434,34433 ,20124,1792,20137 ,0,0,0}, - {37324,36353,36355 ,20140,20127,20129 ,0,0,0}, {35896,35899,36362 ,20137,20124,20139 ,0,0,0}, - {36355,36354,36396 ,20129,20128,20165 ,0,0,0}, {37323,36353,37324 ,20131,20127,20140 ,0,0,0}, - {37061,37325,37327 ,20132,20136,20161 ,0,0,0}, {34431,34434,34770 ,20168,1792,1792 ,0,0,0}, - {37060,12921,34442 ,20137,20140,20167 ,0,0,0}, {34439,36918,34442 ,1793,20124,20167 ,0,0,0}, - {36917,37060,34442 ,20137,20137,20167 ,0,0,0}, {34769,34431,34770 ,726,20168,1792 ,0,0,0}, - {34438,36924,34439 ,20162,727,1793 ,0,0,0}, {34438,34431,36925 ,20162,20168,20147 ,0,0,0}, - {34431,34769,36437 ,20168,726,20130 ,0,0,0}, {34433,34773,34772 ,20137,20137,20124 ,0,0,0}, - {36389,35903,36444 ,20137,20162,20126 ,0,0,0}, {34780,34778,36392 ,20140,20137,20124 ,0,0,0}, - {36392,34782,34780 ,20124,726,20140 ,0,0,0}, {37330,36916,36915 ,20168,20126,20126 ,0,0,0}, - {37331,34783,34782 ,20125,20137,726 ,0,0,0}, {36389,35899,35902 ,20137,20124,726 ,0,0,0}, - {35893,35896,36363 ,20130,20137,20140 ,0,0,0}, {34456,35894,37313 ,20148,726,20140 ,0,0,0}, - {37313,35893,36363 ,20140,20130,20140 ,0,0,0}, {35920,34453,34452 ,20169,20137,20140 ,0,0,0}, - {37316,34445,37315 ,20131,20135,20164 ,0,0,0}, {35925,34452,37317 ,1792,20140,1793 ,0,0,0}, - {34452,34445,37316 ,20140,20135,20131 ,0,0,0}, {34828,34448,34826 ,20169,20165,20165 ,0,0,0}, - {34445,34448,37315 ,20135,20165,20164 ,0,0,0}, {34826,34447,34823 ,20165,20134,20139 ,0,0,0}, - {34822,34447,34450 ,20131,20134,20133 ,0,0,0}, {34422,34714,34711 ,20126,20126,20135 ,0,0,0}, - {37321,34406,37340 ,20168,20130,20169 ,0,0,0}, {37341,36364,36377 ,20174,20141,20155 ,0,0,0}, - {36364,36366,36377 ,20141,20143,20155 ,0,0,0}, {36379,36376,36378 ,20157,20154,20156 ,0,0,0}, - {36374,36381,36380 ,20152,20159,20158 ,0,0,0}, {36373,36372,34414 ,20151,20131,20158 ,0,0,0}, - {37445,37322,34411 ,20175,20173,20146 ,0,0,0}, {37322,36373,34414 ,20173,20151,20158 ,0,0,0}, - {34406,34815,34403 ,20130,20127,20143 ,0,0,0}, {34410,37446,36369 ,1793,20139,20145 ,0,0,0}, - {34411,36369,37445 ,20146,20145,20175 ,0,0,0}, {34815,36371,34403 ,20127,20150,20143 ,0,0,0}, - {34403,36371,36370 ,20143,20150,20149 ,0,0,0}, {37446,34410,36370 ,20139,1793,20149 ,0,0,0}, - {34406,34405,37340 ,20130,20131,20169 ,0,0,0}, {37447,36390,37320 ,20137,20137,20136 ,0,0,0}, - {36958,35928,36382 ,20132,727,20136 ,0,0,0}, {37319,37320,36386 ,20139,20136,20161 ,0,0,0}, - {37320,37319,37447 ,20136,20139,20137 ,0,0,0}, {36382,36384,36958 ,20136,1793,20132 ,0,0,0}, - {36958,35931,35928 ,20132,20148,727 ,0,0,0}, {35934,37342,35936 ,20137,727,20169 ,0,0,0}, - {37342,35934,36359 ,727,20137,20136 ,0,0,0}, {34428,35936,37343 ,20138,20169,727 ,0,0,0}, - {34417,34724,34424 ,1793,1793,20130 ,0,0,0}, {34425,36357,36953 ,20130,20132,20165 ,0,0,0}, - {34724,36356,34424 ,1793,20131,20130 ,0,0,0}, {34417,34707,34723 ,1793,726,20136 ,0,0,0}, - {34420,34419,34708 ,20138,20133,1792 ,0,0,0}, {34417,34420,34707 ,1793,20138,726 ,0,0,0}, - {34711,34419,34422 ,20135,20133,20126 ,0,0,0}, {34708,34419,34710 ,1792,20133,20164 ,0,0,0}, - {34391,36351,37448 ,1793,20126,20126 ,0,0,0}, {34378,34377,36946 ,20132,20136,1792 ,0,0,0}, - {37345,36939,36943 ,20130,20168,20126 ,0,0,0}, {36939,36410,36943 ,20168,20168,20126 ,0,0,0}, - {36405,36945,36944 ,20167,20148,20139 ,0,0,0}, {36948,36407,36406 ,1792,20126,20167 ,0,0,0}, - {36404,12820,34386 ,20165,20140,20161 ,0,0,0}, {34375,34378,36947 ,20165,20132,1792 ,0,0,0}, - {37449,36403,34383 ,20170,20134,20127 ,0,0,0}, {37449,34383,36950 ,20170,20127,20162 ,0,0,0}, - {37346,34375,36947 ,20139,20165,1792 ,0,0,0}, {37346,36951,34375 ,20139,20148,20165 ,0,0,0}, - {34382,34375,36949 ,20135,20165,20131 ,0,0,0}, {34377,36408,36946 ,20136,20136,1792 ,0,0,0}, - {37450,37336,37344 ,20131,1793,726 ,0,0,0}, {36941,36940,34729 ,20168,20135,20131 ,0,0,0}, - {37344,36937,37450 ,726,20164,20131 ,0,0,0}, {34733,36414,34730 ,20165,20133,20139 ,0,0,0}, - {36941,37333,36942 ,20168,20135,20133 ,0,0,0}, {37050,36417,36416 ,20168,20168,20128 ,0,0,0}, - {37051,37050,36416 ,20140,20168,20128 ,0,0,0}, {34400,37049,37051 ,20140,1793,20140 ,0,0,0}, - {34750,34389,34752 ,20140,20124,726 ,0,0,0}, {36427,34396,34748 ,20139,20148,20137 ,0,0,0}, - {34396,37048,34397 ,20148,20139,20168 ,0,0,0}, {34396,34389,34750 ,20148,20124,20140 ,0,0,0}, - {34753,34392,37334 ,20137,20168,20168 ,0,0,0}, {34389,34392,34752 ,20124,20168,726 ,0,0,0}, - {37334,34391,37448 ,20168,1793,20126 ,0,0,0}, {36351,34391,34394 ,20126,1793,1792 ,0,0,0}, - {34678,34350,34680 ,726,726,726 ,0,0,0}, {37236,37243,37237 ,726,726,726 ,0,0,0}, - {36968,35852,35855 ,20124,20124,726 ,0,0,0}, {37237,37243,37242 ,726,726,20124 ,0,0,0}, - {34347,34350,34678 ,726,726,726 ,0,0,0}, {36593,37239,37238 ,20124,727,726 ,0,0,0}, - {37238,36591,36593 ,726,20124,20124 ,0,0,0}, {37240,37239,37347 ,20124,727,20124 ,0,0,0}, - {34355,36594,37241 ,726,726,726 ,0,0,0}, {34358,34355,37241 ,727,726,726 ,0,0,0}, - {34347,34678,34677 ,726,726,726 ,0,0,0}, {34355,34354,37350 ,726,20124,726 ,0,0,0}, - {34355,36595,36594 ,726,726,726 ,0,0,0}, {34677,36535,34347 ,726,727,726 ,0,0,0}, - {37350,34347,36535 ,726,726,727 ,0,0,0}, {34354,34347,37350 ,20124,726,726 ,0,0,0}, - {34349,34681,34680 ,726,20124,726 ,0,0,0}, {36589,35859,37348 ,20124,726,726 ,0,0,0}, - {34688,34686,36529 ,726,20124,20124 ,0,0,0}, {36529,34690,34688 ,20124,726,726 ,0,0,0}, - {37358,36588,36590 ,726,726,727 ,0,0,0}, {37359,34691,34690 ,726,727,726 ,0,0,0}, - {36589,35855,35858 ,20124,726,20124 ,0,0,0}, {35849,35852,36967 ,20124,20124,727 ,0,0,0}, - {34372,35850,37370 ,726,726,20124 ,0,0,0}, {37370,35849,36967 ,20124,20124,727 ,0,0,0}, - {35876,34369,34368 ,726,20124,20124 ,0,0,0}, {37372,34361,36605 ,726,726,726 ,0,0,0}, - {35881,34368,37373 ,20124,20124,726 ,0,0,0}, {34368,34361,37372 ,20124,726,726 ,0,0,0}, - {34641,34364,34639 ,726,20124,726 ,0,0,0}, {34361,34364,36605 ,726,20124,726 ,0,0,0}, - {34639,34363,34636 ,726,726,726 ,0,0,0}, {34635,34363,34366 ,20124,726,726 ,0,0,0}, - {34567,34322,37040 ,726,726,726 ,0,0,0}, {36731,37405,36721 ,726,726,726 ,0,0,0}, - {35844,37036,35846 ,726,729,726 ,0,0,0}, {36731,36721,36730 ,726,726,726 ,0,0,0}, - {34322,34567,34319 ,726,726,726 ,0,0,0}, {36722,37407,36734 ,728,726,726 ,0,0,0}, - {36734,36720,36722 ,726,726,728 ,0,0,0}, {37407,34973,36734 ,726,729,726 ,0,0,0}, - {34330,34327,34972 ,726,726,726 ,0,0,0}, {34972,34973,34330 ,726,729,726 ,0,0,0}, - {34319,34567,36711 ,726,726,726 ,0,0,0}, {34327,36713,34972 ,726,726,726 ,0,0,0}, - {36711,34326,34319 ,726,726,726 ,0,0,0}, {36714,34326,36711 ,726,726,726 ,0,0,0}, - {34322,34321,37041 ,726,726,726 ,0,0,0}, {37451,36725,37403 ,726,726,726 ,0,0,0}, - {37035,35840,36718 ,726,726,726 ,0,0,0}, {37402,37403,36727 ,726,726,726 ,0,0,0}, - {37403,37402,37451 ,726,726,726 ,0,0,0}, {36718,36728,37035 ,726,726,726 ,0,0,0}, - {37035,35843,35840 ,726,726,726 ,0,0,0}, {35846,37408,35848 ,726,726,726 ,0,0,0}, - {37408,35846,37036 ,726,726,729 ,0,0,0}, {34344,35848,37409 ,726,726,726 ,0,0,0}, - {34333,34538,34340 ,726,726,726 ,0,0,0}, {34341,36190,36719 ,726,726,726 ,0,0,0}, - {34538,36189,34340 ,726,726,726 ,0,0,0}, {34333,34521,34537 ,726,726,726 ,0,0,0}, - {34336,34335,34522 ,726,726,726 ,0,0,0}, {34333,34336,34521 ,726,726,726 ,0,0,0}, - {34525,34335,34338 ,726,726,726 ,0,0,0}, {34522,34335,34524 ,726,726,726 ,0,0,0}, - {37270,34310,37295 ,726,726,727 ,0,0,0}, {37452,34294,37296 ,727,20124,20124 ,0,0,0}, - {37226,37275,37217 ,726,726,726 ,0,0,0}, {37275,37218,37217 ,726,727,726 ,0,0,0}, - {34291,34294,37452 ,20124,20124,727 ,0,0,0}, {36904,37224,35064 ,726,727,727 ,0,0,0}, - {35064,35077,36904 ,727,726,726 ,0,0,0}, {35065,37224,36872 ,20124,727,20124 ,0,0,0}, - {35067,34302,34299 ,726,727,726 ,0,0,0}, {34291,37452,37279 ,20124,727,726 ,0,0,0}, - {35068,35067,34299 ,726,726,726 ,0,0,0}, {34299,34298,37280 ,726,726,727 ,0,0,0}, - {37279,37278,34291 ,726,727,20124 ,0,0,0}, {37280,34291,37278 ,727,20124,727 ,0,0,0}, - {34298,34291,37280 ,726,20124,727 ,0,0,0}, {34293,37297,37296 ,20124,726,20124 ,0,0,0}, - {37453,36303,36302 ,726,726,726 ,0,0,0}, {36898,36897,34914 ,726,726,20124 ,0,0,0}, - {36302,37269,37453 ,726,726,726 ,0,0,0}, {34918,37225,34915 ,726,726,726 ,0,0,0}, - {36898,37223,36899 ,726,726,726 ,0,0,0}, {36892,36885,36884 ,20124,726,726 ,0,0,0}, - {36893,36892,36884 ,20124,20124,726 ,0,0,0}, {34316,36291,36893 ,20124,726,20124 ,0,0,0}, - {34872,34305,34874 ,726,20124,726 ,0,0,0}, {36284,34312,34870 ,726,726,20124 ,0,0,0}, - {34312,36889,34313 ,726,726,726 ,0,0,0}, {34312,34305,34872 ,726,20124,726 ,0,0,0}, - {34875,34308,37298 ,727,726,726 ,0,0,0}, {34305,34308,34874 ,20124,726,726 ,0,0,0}, - {37298,34307,37271 ,726,20124,727 ,0,0,0}, {37270,34307,34310 ,726,20124,726 ,0,0,0}, - {34282,34590,34587 ,726,727,726 ,0,0,0}, {36547,34266,37388 ,727,727,727 ,0,0,0}, - {36991,36993,36551 ,727,727,726 ,0,0,0}, {36993,36555,36551 ,727,727,726 ,0,0,0}, - {37379,36992,37377 ,727,726,726 ,0,0,0}, {36544,37378,37380 ,726,726,727 ,0,0,0}, - {36543,36545,34274 ,727,727,727 ,0,0,0}, {34271,37382,34274 ,727,727,727 ,0,0,0}, - {37381,36543,34274 ,726,727,727 ,0,0,0}, {34266,34627,34263 ,727,726,726 ,0,0,0}, - {37383,34270,36606 ,726,726,726 ,0,0,0}, {34270,37383,34271 ,726,726,727 ,0,0,0}, - {34627,36611,34263 ,726,727,726 ,0,0,0}, {36607,34263,36611 ,20124,726,727 ,0,0,0}, - {34266,34265,37388 ,727,726,727 ,0,0,0}, {37454,36604,37376 ,727,727,726 ,0,0,0}, - {36990,35884,36546 ,20124,726,726 ,0,0,0}, {37375,37376,36549 ,726,726,727 ,0,0,0}, - {37376,37375,37454 ,726,726,727 ,0,0,0}, {36546,36550,36990 ,726,727,20124 ,0,0,0}, - {36990,35887,35884 ,20124,20124,726 ,0,0,0}, {35890,37389,35892 ,726,20124,726 ,0,0,0}, - {37389,35890,36539 ,20124,726,726 ,0,0,0}, {34288,35892,37390 ,20124,726,20124 ,0,0,0}, - {34277,34599,34284 ,726,726,726 ,0,0,0}, {34285,36602,37384 ,726,727,20124 ,0,0,0}, - {34599,36601,34284 ,726,727,726 ,0,0,0}, {34277,34583,34598 ,726,20124,726 ,0,0,0}, - {34280,34279,34584 ,727,727,20124 ,0,0,0}, {34277,34280,34583 ,726,727,20124 ,0,0,0}, - {34587,34279,34282 ,726,727,726 ,0,0,0}, {34584,34279,34586 ,20124,727,20124 ,0,0,0}, - {34251,37014,37455 ,726,726,726 ,0,0,0}, {36709,34238,34237 ,726,726,726 ,0,0,0}, - {37433,37432,36700 ,726,726,728 ,0,0,0}, {37432,37414,36700 ,726,726,728 ,0,0,0}, - {37020,37434,37021 ,726,726,726 ,0,0,0}, {37022,37019,37415 ,726,726,726 ,0,0,0}, - {34235,34238,36708 ,726,726,726 ,0,0,0}, {37025,37024,37023 ,726,729,726 ,0,0,0}, - {34242,37416,34243 ,726,726,728 ,0,0,0}, {34243,37026,34246 ,728,726,728 ,0,0,0}, - {37033,34235,36708 ,726,726,726 ,0,0,0}, {34242,34235,37027 ,726,726,726 ,0,0,0}, - {34242,37028,37416 ,726,726,726 ,0,0,0}, {34235,37033,37417 ,726,726,729 ,0,0,0}, - {34237,37435,36709 ,726,726,726 ,0,0,0}, {37456,37015,37412 ,726,726,726 ,0,0,0}, - {36251,36250,34543 ,726,726,726 ,0,0,0}, {37412,37411,37456 ,726,726,726 ,0,0,0}, - {34547,37410,34544 ,726,726,726 ,0,0,0}, {36251,37018,36252 ,726,726,726 ,0,0,0}, - {36261,36996,36995 ,726,726,729 ,0,0,0}, {36262,36261,36995 ,726,726,729 ,0,0,0}, - {34260,36256,36262 ,726,726,726 ,0,0,0}, {34502,34249,34504 ,726,726,729 ,0,0,0}, - {36686,34256,34500 ,726,726,726 ,0,0,0}, {34256,36691,34257 ,726,726,726 ,0,0,0}, - {34256,34249,34502 ,726,726,726 ,0,0,0}, {34505,34252,37436 ,726,726,729 ,0,0,0}, - {34249,34252,34504 ,726,726,729 ,0,0,0}, {37436,34251,37455 ,729,726,726 ,0,0,0}, - {37014,34251,34254 ,726,726,726 ,0,0,0}, {36879,36875,36880 ,20124,20124,726 ,0,0,0}, - {34226,37285,37305 ,20124,727,726 ,0,0,0}, {36879,36881,37303 ,20124,20124,727 ,0,0,0}, - {36881,37304,37303 ,20124,726,727 ,0,0,0}, {37289,36880,36875 ,20124,726,20124 ,0,0,0}, - {36298,36874,36873 ,20124,726,20124 ,0,0,0}, {36297,36296,34218 ,727,726,20124 ,0,0,0}, - {37290,36297,34218 ,726,727,20124 ,0,0,0}, {34210,34889,34207 ,726,726,727 ,0,0,0}, - {34215,36888,34218 ,726,726,20124 ,0,0,0}, {34214,36887,34215 ,726,20124,726 ,0,0,0}, - {34889,37291,34207 ,726,20124,727 ,0,0,0}, {34214,36891,36887 ,726,20124,20124 ,0,0,0}, - {36890,34207,37291 ,20124,727,20124 ,0,0,0}, {34210,34209,34884 ,726,726,20124 ,0,0,0}, - {34877,34878,36231 ,727,727,20124 ,0,0,0}, {36240,36232,34865 ,726,726,20124 ,0,0,0}, - {34865,36233,36240 ,20124,20124,726 ,0,0,0}, {36231,36882,34861 ,20124,20124,726 ,0,0,0}, - {36240,36239,36232 ,726,726,726 ,0,0,0}, {36287,37309,35958 ,20124,726,727 ,0,0,0}, - {37309,36287,36238 ,726,20124,20124 ,0,0,0}, {34232,35958,37310 ,726,727,726 ,0,0,0}, - {34221,36228,34228 ,726,20124,726 ,0,0,0}, {36228,35950,34228 ,20124,20124,726 ,0,0,0}, - {34229,35949,35955 ,726,726,726 ,0,0,0}, {34221,37307,36227 ,726,20124,726 ,0,0,0}, - {34224,34223,37308 ,726,727,727 ,0,0,0}, {34221,34224,37307 ,726,726,20124 ,0,0,0}, - {37305,34223,34226 ,726,727,20124 ,0,0,0}, {37308,34223,37306 ,727,727,726 ,0,0,0}, - {34195,36980,37457 ,20124,726,727 ,0,0,0}, {36556,34182,34181 ,20124,20124,20124 ,0,0,0}, - {36004,36003,36982 ,726,727,726 ,0,0,0}, {36003,36561,36982 ,727,726,726 ,0,0,0}, - {36009,36006,36983 ,726,726,726 ,0,0,0}, {36010,36537,36012 ,726,20124,20124 ,0,0,0}, - {34182,36557,34179 ,20124,727,20124 ,0,0,0}, {36600,36012,36537 ,726,20124,20124 ,0,0,0}, - {34186,36985,34187 ,726,726,726 ,0,0,0}, {34187,36599,34190 ,726,726,727 ,0,0,0}, - {36987,34179,36557 ,726,20124,727 ,0,0,0}, {34179,36987,37396 ,20124,726,727 ,0,0,0}, - {34186,34179,37391 ,726,20124,727 ,0,0,0}, {34181,37394,36556 ,20124,726,20124 ,0,0,0}, - {37458,37395,37392 ,726,726,726 ,0,0,0}, {36981,37367,34604 ,726,726,20124 ,0,0,0}, - {37392,36587,37458 ,726,726,726 ,0,0,0}, {34608,36978,34605 ,726,726,726 ,0,0,0}, - {36981,37366,37369 ,726,726,726 ,0,0,0}, {36578,36964,36966 ,20124,726,726 ,0,0,0}, - {36576,36578,36966 ,20124,20124,726 ,0,0,0}, {34204,36577,36576 ,20124,726,20124 ,0,0,0}, - {34656,34193,34658 ,726,20124,726 ,0,0,0}, {36533,34200,34654 ,726,726,20124 ,0,0,0}, - {34200,36573,34201 ,726,726,726 ,0,0,0}, {34200,34193,34656 ,726,20124,726 ,0,0,0}, - {34659,34196,36597 ,727,726,726 ,0,0,0}, {34193,34196,34658 ,20124,726,726 ,0,0,0}, - {36597,34195,37457 ,726,20124,727 ,0,0,0}, {36980,34195,34198 ,726,20124,726 ,0,0,0}, - {37428,36070,36068 ,726,726,726 ,0,0,0}, {34170,37002,37437 ,726,726,729 ,0,0,0}, - {36068,36067,37428 ,726,726,726 ,0,0,0}, {36067,36685,37428 ,726,726,726 ,0,0,0}, - {36073,36070,36684 ,726,726,726 ,0,0,0}, {34154,34516,34518 ,726,726,728 ,0,0,0}, - {37429,36076,37005 ,726,728,726 ,0,0,0}, {37007,37429,34162 ,726,726,726 ,0,0,0}, - {34154,34518,34151 ,726,728,726 ,0,0,0}, {34159,37007,34162 ,726,726,726 ,0,0,0}, - {34158,37006,34159 ,726,728,726 ,0,0,0}, {34518,37430,34151 ,728,726,726 ,0,0,0}, - {34158,36689,37006 ,726,726,728 ,0,0,0}, {36690,34151,37430 ,729,726,726 ,0,0,0}, - {34154,34153,34513 ,726,726,726 ,0,0,0}, {34506,34507,36682 ,726,726,726 ,0,0,0}, - {36263,36598,34495 ,726,726,728 ,0,0,0}, {34495,37423,36263 ,728,726,726 ,0,0,0}, - {36682,37424,34491 ,726,726,726 ,0,0,0}, {36263,36185,36598 ,726,726,726 ,0,0,0}, - {37425,37441,35826 ,728,726,726 ,0,0,0}, {37441,37425,36186 ,726,728,726 ,0,0,0}, - {34176,35826,37442 ,726,726,726 ,0,0,0}, {34165,36258,34172 ,726,726,726 ,0,0,0}, - {36258,35818,34172 ,726,726,726 ,0,0,0}, {34173,35817,35823 ,728,726,729 ,0,0,0}, - {34165,37439,36257 ,726,726,726 ,0,0,0}, {34168,34167,37440 ,726,726,726 ,0,0,0}, - {34165,34168,37439 ,726,726,726 ,0,0,0}, {37437,34167,34170 ,729,726,726 ,0,0,0}, - {37440,34167,37438 ,726,726,728 ,0,0,0}, {34834,34126,34125 ,726,726,726 ,0,0,0}, - {36134,36132,36230 ,727,20124,726 ,0,0,0}, {36219,35940,35943 ,20124,20124,726 ,0,0,0}, - {36132,36131,36230 ,20124,726,726 ,0,0,0}, {36137,36134,36229 ,20124,727,20124 ,0,0,0}, - {36138,36281,36140 ,20124,20124,20124 ,0,0,0}, {34126,34832,34123 ,726,726,726 ,0,0,0}, - {37300,36140,36281 ,726,20124,20124 ,0,0,0}, {34134,34131,37301 ,727,726,20124 ,0,0,0}, - {37301,37300,34134 ,20124,726,727 ,0,0,0}, {34831,34123,34832 ,726,726,726 ,0,0,0}, - {34130,36278,34131 ,20124,726,726 ,0,0,0}, {34123,34831,36878 ,726,726,726 ,0,0,0}, - {34130,34123,37299 ,20124,726,726 ,0,0,0}, {34125,34835,34834 ,726,20124,726 ,0,0,0}, - {36221,35947,36241 ,20124,726,726 ,0,0,0}, {34842,34840,36248 ,726,20124,20124 ,0,0,0}, - {36248,34844,34842 ,20124,726,726 ,0,0,0}, {37311,36277,36276 ,726,726,727 ,0,0,0}, - {37312,34845,34844 ,726,727,726 ,0,0,0}, {36221,35943,35946 ,20124,726,20124 ,0,0,0}, - {35937,35940,36220 ,20124,20124,727 ,0,0,0}, {34148,35938,36264 ,726,726,20124 ,0,0,0}, - {36264,35937,36220 ,20124,20124,727 ,0,0,0}, {35964,34145,34144 ,726,20124,20124 ,0,0,0}, - {37257,34137,36871 ,726,726,726 ,0,0,0}, {35969,34144,37258 ,20124,20124,726 ,0,0,0}, - {34144,34137,37257 ,20124,726,726 ,0,0,0}, {34951,34140,34949 ,726,20124,726 ,0,0,0}, - {34137,34140,36871 ,726,20124,726 ,0,0,0}, {34949,34139,34946 ,726,726,726 ,0,0,0}, - {34945,34139,34142 ,20124,726,726 ,0,0,0}, {37365,36030,36031 ,20124,726,726 ,0,0,0}, - {34114,36532,37363 ,20124,727,726 ,0,0,0}, {36031,36034,37365 ,726,726,20124 ,0,0,0}, - {36034,36971,37365 ,726,727,20124 ,0,0,0}, {36028,36030,36972 ,20124,726,20124 ,0,0,0}, - {34098,34671,34673 ,726,20124,726 ,0,0,0}, {36022,36024,36568 ,726,727,726 ,0,0,0}, - {36019,36022,34106 ,20124,726,20124 ,0,0,0}, {34098,34673,34095 ,726,726,727 ,0,0,0}, - {34103,36019,34106 ,726,20124,20124 ,0,0,0}, {34103,36016,36018 ,726,726,20124 ,0,0,0}, - {35985,34095,34673 ,726,727,726 ,0,0,0}, {34102,36014,36016 ,726,726,726 ,0,0,0}, - {36014,34095,35982 ,726,727,726 ,0,0,0}, {34098,34097,34668 ,726,726,20124 ,0,0,0}, - {34661,34662,37361 ,727,727,20124 ,0,0,0}, {37362,37355,34649 ,726,726,20124 ,0,0,0}, - {34649,36530,37362 ,20124,20124,726 ,0,0,0}, {37361,36566,34645 ,20124,20124,726 ,0,0,0}, - {37362,36583,37355 ,726,726,726 ,0,0,0}, {37352,37356,35870 ,20124,726,727 ,0,0,0}, - {37356,37352,36581 ,726,20124,20124 ,0,0,0}, {34120,35870,37357 ,726,727,726 ,0,0,0}, - {34109,36579,34116 ,726,20124,726 ,0,0,0}, {36579,35862,34116 ,20124,20124,726 ,0,0,0}, - {34117,35861,35867 ,726,726,726 ,0,0,0}, {34109,37354,36580 ,726,20124,726 ,0,0,0}, - {34112,34111,37353 ,726,727,727 ,0,0,0}, {34109,34112,37354 ,726,726,20124 ,0,0,0}, - {37363,34111,34114 ,726,727,20124 ,0,0,0}, {37353,34111,37364 ,727,727,726 ,0,0,0}, - {34462,34070,34069 ,726,726,726 ,0,0,0}, {36094,36095,37000 ,726,726,726 ,0,0,0}, - {36716,35808,35811 ,726,728,726 ,0,0,0}, {36095,36098,37000 ,726,726,726 ,0,0,0}, - {36092,36094,36999 ,726,726,726 ,0,0,0}, {36088,36089,36247 ,726,726,728 ,0,0,0}, - {34070,34460,34067 ,726,726,728 ,0,0,0}, {36086,36088,36246 ,729,726,726 ,0,0,0}, - {34078,34075,36083 ,726,726,726 ,0,0,0}, {36083,36086,34078 ,726,729,726 ,0,0,0}, - {34459,34067,34460 ,726,728,726 ,0,0,0}, {34075,36080,36082 ,726,726,726 ,0,0,0}, - {34459,36049,34067 ,726,726,728 ,0,0,0}, {34074,34067,36078 ,726,728,729 ,0,0,0}, - {34069,34463,34462 ,726,728,726 ,0,0,0}, {36198,35815,36701 ,726,726,726 ,0,0,0}, - {34470,34468,36710 ,726,726,726 ,0,0,0}, {36710,34472,34470 ,726,729,726 ,0,0,0}, - {37443,36704,36703 ,729,726,726 ,0,0,0}, {37444,34473,34472 ,726,726,729 ,0,0,0}, - {36198,35811,35814 ,726,726,728 ,0,0,0}, {35805,35808,36715 ,726,728,726 ,0,0,0}, - {34092,35806,37398 ,726,728,726 ,0,0,0}, {37398,35805,36715 ,726,726,726 ,0,0,0}, - {35832,34089,34088 ,726,726,726 ,0,0,0}, {37399,34081,36197 ,726,726,726 ,0,0,0}, - {35837,34088,37400 ,726,726,726 ,0,0,0}, {34088,34081,37399 ,726,726,726 ,0,0,0}, - {34580,34084,34578 ,726,728,726 ,0,0,0}, {34081,34084,36197 ,726,728,726 ,0,0,0}, - {34578,34083,34575 ,726,726,726 ,0,0,0}, {34574,34083,34086 ,726,726,726 ,0,0,0}, - {34058,34900,34897 ,726,727,726 ,0,0,0}, {37459,34042,37265 ,727,727,727 ,0,0,0}, - {36159,36162,37262 ,726,20124,727 ,0,0,0}, {36162,36267,37262 ,20124,726,727 ,0,0,0}, - {36156,36158,37263 ,727,726,727 ,0,0,0}, {34042,37459,34937 ,727,727,726 ,0,0,0}, - {36150,36152,36265 ,726,20124,727 ,0,0,0}, {34050,34047,36147 ,727,727,727 ,0,0,0}, - {36147,36150,34050 ,727,726,727 ,0,0,0}, {34042,34937,34039 ,727,726,726 ,0,0,0}, - {34046,36142,36144 ,726,726,726 ,0,0,0}, {34047,36144,36146 ,727,726,726 ,0,0,0}, - {36113,34039,34937 ,727,726,726 ,0,0,0}, {36142,34039,36110 ,726,726,726 ,0,0,0}, - {34046,34039,36142 ,726,726,726 ,0,0,0}, {34042,34041,37265 ,727,726,727 ,0,0,0}, - {37460,36253,37261 ,727,727,726 ,0,0,0}, {36911,35972,36260 ,20124,726,726 ,0,0,0}, - {37260,37261,36226 ,726,726,727 ,0,0,0}, {37261,37260,37460 ,726,726,727 ,0,0,0}, - {36260,36224,36911 ,726,727,20124 ,0,0,0}, {36911,35975,35972 ,20124,20124,726 ,0,0,0}, - {35978,37266,35980 ,726,20124,726 ,0,0,0}, {37266,35978,36268 ,20124,726,726 ,0,0,0}, - {34064,35980,37267 ,20124,726,20124 ,0,0,0}, {34053,34909,34060 ,726,726,726 ,0,0,0}, - {34061,36274,37264 ,726,727,20124 ,0,0,0}, {34909,36273,34060 ,726,727,726 ,0,0,0}, - {34053,34893,34908 ,726,20124,726 ,0,0,0}, {34056,34055,34894 ,727,727,20124 ,0,0,0}, - {34053,34056,34893 ,726,727,20124 ,0,0,0}, {34897,34055,34058 ,726,727,726 ,0,0,0}, - {34894,34055,34896 ,20124,727,20124 ,0,0,0}, {35705,36469,35703 ,1793,726,1793 ,0,0,0}, - {37178,37179,36469 ,726,727,726 ,0,0,0}, {37461,37462,37463 ,730,730,730 ,0,0,0}, - {37464,37465,37466 ,730,730,730 ,0,0,0}, {35142,35140,37467 ,730,730,730 ,0,0,0}, - {37468,37469,37470 ,730,730,730 ,0,0,0}, {37471,37472,37463 ,730,730,730 ,0,0,0}, - {37462,37473,37463 ,730,730,730 ,0,0,0}, {37474,37475,37476 ,730,730,730 ,0,0,0}, - {37463,37477,37478 ,730,730,730 ,0,0,0}, {37477,37463,37472 ,730,730,730 ,0,0,0}, - {35956,34230,35957 ,730,730,730 ,0,0,0}, {34882,34211,34885 ,730,730,730 ,0,0,0}, - {37479,37480,35154 ,730,730,730 ,0,0,0}, {37478,37481,37482 ,730,730,730 ,0,0,0}, - {34205,34216,37483 ,730,730,730 ,0,0,0}, {34890,37484,37485 ,730,730,730 ,0,0,0}, - {37482,35158,37480 ,730,730,730 ,0,0,0}, {35160,37481,35161 ,730,730,730 ,0,0,0}, - {37478,37486,37487 ,730,730,730 ,0,0,0}, {37478,37487,37481 ,730,730,730 ,0,0,0}, - {37488,35178,35177 ,730,730,730 ,0,0,0}, {35182,35178,37488 ,730,730,730 ,0,0,0}, - {37489,35146,37490 ,730,730,730 ,0,0,0}, {37491,37492,37493 ,730,730,730 ,0,0,0}, - {37494,37495,37496 ,730,730,730 ,0,0,0}, {37497,37498,37499 ,730,730,730 ,0,0,0}, - {37500,37499,37498 ,730,730,730 ,0,0,0}, {37499,37501,37497 ,730,730,730 ,0,0,0}, - {37491,37500,37498 ,730,730,730 ,0,0,0}, {37491,37493,37500 ,730,730,730 ,0,0,0}, - {37502,37503,37501 ,730,730,730 ,0,0,0}, {37497,37501,37503 ,730,730,730 ,0,0,0}, - {37504,37505,34164 ,730,730,730 ,0,0,0}, {37506,37503,37502 ,730,730,730 ,0,0,0}, - {34517,34152,2073 ,730,730,730 ,0,0,0}, {37507,37508,37509 ,730,730,730 ,0,0,0}, - {37510,37511,37512 ,730,730,730 ,0,0,0}, {34234,37513,37514 ,730,730,730 ,0,0,0}, - {37515,37516,37517 ,730,730,730 ,0,0,0}, {37507,37518,37519 ,730,730,730 ,0,0,0}, - {36075,37520,37521 ,730,730,730 ,0,0,0}, {37522,37523,37524 ,730,730,730 ,0,0,0}, - {37525,37526,37527 ,730,730,730 ,0,0,0}, {36057,34480,36054 ,730,730,730 ,0,0,0}, - {37528,34071,34467 ,730,730,730 ,0,0,0}, {34552,37529,34570 ,730,730,730 ,0,0,0}, - {34040,34938,37530 ,730,730,730 ,0,0,0}, {34087,34576,34085 ,730,730,730 ,0,0,0}, - {34076,36084,36081 ,730,730,730 ,0,0,0}, {36051,34477,34458 ,730,730,730 ,0,0,0}, - {37525,37527,35819 ,730,730,730 ,0,0,0}, {36051,36053,34477 ,730,730,730 ,0,0,0}, - {35835,34079,35833 ,730,730,730 ,0,0,0}, {34885,34213,34886 ,730,730,730 ,0,0,0}, - {34049,4039,36149 ,730,730,730 ,0,0,0}, {37531,37532,37533 ,730,730,730 ,0,0,0}, - {36063,34488,34486 ,730,730,730 ,0,0,0}, {37534,37535,35942 ,730,730,730 ,0,0,0}, - {37536,34913,37537 ,730,730,730 ,0,0,0}, {37532,37538,37539 ,730,730,730 ,0,0,0}, - {37540,37541,37542 ,730,730,730 ,0,0,0}, {34892,34054,34052 ,730,730,730 ,0,0,0}, - {37543,37544,37545 ,730,730,730 ,0,0,0}, {34150,2073,34152 ,730,730,730 ,0,0,0}, - {34038,36109,36111 ,730,730,730 ,0,0,0}, {34854,34851,37546 ,730,730,730 ,0,0,0}, - {37547,37548,37549 ,730,730,730 ,0,0,0}, {35824,34174,35825 ,730,730,730 ,0,0,0}, - {34935,34938,36112 ,730,730,730 ,0,0,0}, {35951,37550,37551 ,730,730,730 ,0,0,0}, - {35828,37509,37508 ,730,730,730 ,0,0,0}, {34848,37552,37553 ,730,730,730 ,0,0,0}, - {35967,34135,35965 ,730,730,730 ,0,0,0}, {34497,34496,37554 ,730,730,730 ,0,0,0}, - {37555,34255,34250 ,730,730,730 ,0,0,0}, {37556,37557,34859 ,730,730,730 ,0,0,0}, - {37558,34244,37559 ,730,730,730 ,0,0,0}, {34247,34501,34248 ,730,730,730 ,0,0,0}, - {34248,34503,34250 ,730,730,730 ,0,0,0}, {37510,37560,37511 ,730,730,730 ,0,0,0}, - {34234,37561,34236 ,730,730,730 ,0,0,0}, {37562,34550,37563 ,730,730,730 ,0,0,0}, - {35824,35822,34174 ,730,730,730 ,0,0,0}, {34258,37564,37565 ,730,730,730 ,0,0,0}, - {37543,37523,37544 ,730,730,730 ,0,0,0}, {37566,37567,37568 ,730,730,730 ,0,0,0}, - {37569,34166,34164 ,730,730,730 ,0,0,0}, {37570,37571,37572 ,730,730,730 ,0,0,0}, - {37573,37574,37575 ,730,730,730 ,0,0,0}, {37576,37575,37577 ,730,730,730 ,0,0,0}, - {37578,34150,37579 ,730,730,730 ,0,0,0}, {34169,34171,37580 ,730,730,730 ,0,0,0}, - {37541,34545,37542 ,730,730,730 ,0,0,0}, {37581,37574,34974 ,730,730,730 ,0,0,0}, - {37582,37583,37584 ,730,730,730 ,0,0,0}, {37585,37579,34149 ,730,730,730 ,0,0,0}, - {37542,34545,34542 ,730,730,730 ,0,0,0}, {37581,34974,34329 ,730,730,730 ,0,0,0}, - {35821,35819,37586 ,730,730,730 ,0,0,0}, {37587,37588,37589 ,730,730,730 ,0,0,0}, - {34520,34519,34334 ,730,730,730 ,0,0,0}, {34483,36057,36059 ,730,730,730 ,0,0,0}, - {36059,36060,34484 ,730,730,730 ,0,0,0}, {34080,34079,37590 ,730,730,730 ,0,0,0}, - {34079,34090,35830 ,730,730,730 ,0,0,0}, {37591,37592,37593 ,730,730,730 ,0,0,0}, - {37594,35835,35836 ,730,730,730 ,0,0,0}, {35123,35122,37595 ,730,730,730 ,0,0,0}, - {34536,37596,37597 ,730,730,730 ,0,0,0}, {37506,37598,37599 ,730,730,730 ,0,0,0}, - {37600,37601,37602 ,730,730,730 ,0,0,0}, {37603,34342,37604 ,730,730,730 ,0,0,0}, - {37605,37601,37600 ,730,730,730 ,0,0,0}, {37606,37542,34542 ,730,730,730 ,0,0,0}, - {34956,34960,37607 ,730,730,730 ,0,0,0}, {37605,37608,37609 ,730,730,730 ,0,0,0}, - {37610,37611,37612 ,730,730,730 ,0,0,0}, {37613,37608,37614 ,730,730,730 ,0,0,0}, - {36107,36105,34558 ,730,730,730 ,0,0,0}, {37615,37616,37613 ,730,730,730 ,0,0,0}, - {37616,37615,34962 ,730,730,730 ,0,0,0}, {37617,34969,34968 ,730,730,730 ,0,0,0}, - {37595,34962,37615 ,730,730,730 ,0,0,0}, {34953,37618,37619 ,730,730,730 ,0,0,0}, - {37599,37598,35116 ,730,730,730 ,0,0,0}, {37502,37598,37506 ,730,730,730 ,0,0,0}, - {37620,35270,35261 ,730,730,730 ,0,0,0}, {37493,37492,37621 ,730,730,730 ,0,0,0}, - {35663,35666,37622 ,730,730,730 ,0,0,0}, {37623,35629,37624 ,730,730,730 ,0,0,0}, - {37625,37626,35264 ,730,730,730 ,0,0,0}, {35627,37627,37628 ,730,730,730 ,0,0,0}, - {37625,35273,37629 ,730,730,730 ,0,0,0}, {37630,37631,37632 ,730,730,730 ,0,0,0}, - {37633,37634,37635 ,730,730,730 ,0,0,0}, {37636,37637,37638 ,730,730,730 ,0,0,0}, - {37639,35247,35242 ,730,730,730 ,0,0,0}, {37640,37641,37642 ,730,730,730 ,0,0,0}, - {37637,37643,37644 ,730,730,730 ,0,0,0}, {37645,37646,37647 ,730,730,730 ,0,0,0}, - {37648,37649,37650 ,730,730,730 ,0,0,0}, {37651,37652,37653 ,730,730,730 ,0,0,0}, - {37648,35666,37654 ,730,730,730 ,0,0,0}, {35680,37655,37656 ,730,730,730 ,0,0,0}, - {35678,37657,37655 ,730,730,730 ,0,0,0}, {35680,35678,37655 ,730,730,730 ,0,0,0}, - {37642,37638,37658 ,730,730,730 ,0,0,0}, {37659,37660,37661 ,730,730,730 ,0,0,0}, - {37662,37657,35676 ,730,730,730 ,0,0,0}, {37663,35292,37664 ,730,730,730 ,0,0,0}, - {35238,35234,37665 ,730,730,730 ,0,0,0}, {37666,35614,37667 ,730,730,730 ,0,0,0}, - {37668,37669,37670 ,730,730,730 ,0,0,0}, {37671,37672,37673 ,730,730,730 ,0,0,0}, - {37674,37675,37494 ,730,730,730 ,0,0,0}, {37672,37676,37677 ,730,730,730 ,0,0,0}, - {37676,37672,37671 ,730,730,730 ,0,0,0}, {37678,37677,37679 ,730,730,730 ,0,0,0}, - {37676,37679,37677 ,730,730,730 ,0,0,0}, {37680,37681,37678 ,730,730,730 ,0,0,0}, - {37678,37679,37680 ,730,730,730 ,0,0,0}, {34606,37682,37683 ,730,730,730 ,0,0,0}, - {37684,37685,37686 ,730,730,730 ,0,0,0}, {37687,37688,37689 ,730,730,730 ,0,0,0}, - {37690,37691,37692 ,730,730,730 ,0,0,0}, {37693,37694,37695 ,730,730,730 ,0,0,0}, - {37696,37697,37698 ,730,730,730 ,0,0,0}, {37699,35872,37700 ,730,730,730 ,0,0,0}, - {37701,34191,37702 ,730,730,730 ,0,0,0}, {37703,34183,34185 ,730,730,730 ,0,0,0}, - {37704,37705,37706 ,730,730,730 ,0,0,0}, {34651,34650,37707 ,730,730,730 ,0,0,0}, - {37708,36013,37709 ,730,730,730 ,0,0,0}, {34650,34653,37710 ,730,730,730 ,0,0,0}, - {34657,34660,34194 ,730,730,730 ,0,0,0}, {37710,34653,37701 ,730,730,730 ,0,0,0}, - {37711,36011,37708 ,730,730,730 ,0,0,0}, {36005,37712,36002 ,730,730,730 ,0,0,0}, - {37683,34607,34606 ,730,730,730 ,0,0,0}, {37704,37699,37700 ,730,730,730 ,0,0,0}, - {37713,34202,37714 ,730,730,730 ,0,0,0}, {37715,37695,37716 ,730,730,730 ,0,0,0}, - {35866,34118,35868 ,730,730,730 ,0,0,0}, {34118,35869,35868 ,730,730,730 ,0,0,0}, - {37717,35987,37718 ,730,730,730 ,0,0,0}, {34670,34096,34672 ,730,730,730 ,0,0,0}, - {37719,37715,37716 ,730,730,730 ,0,0,0}, {37692,3049,37690 ,730,730,730 ,0,0,0}, - {34107,34118,35866 ,730,730,730 ,0,0,0}, {37720,34643,34647 ,730,730,730 ,0,0,0}, - {34674,34096,34094 ,730,730,730 ,0,0,0}, {37721,34113,37722 ,730,730,730 ,0,0,0}, - {34104,36020,36017 ,730,730,730 ,0,0,0}, {34110,37723,34115 ,730,730,730 ,0,0,0}, - {34110,34108,37724 ,730,730,730 ,0,0,0}, {34669,34666,34099 ,730,730,730 ,0,0,0}, - {37592,37725,37593 ,730,730,730 ,0,0,0}, {37682,37726,37683 ,730,730,730 ,0,0,0}, - {37688,37727,34273 ,730,730,730 ,0,0,0}, {3049,37728,34595 ,730,730,730 ,0,0,0}, - {34591,34281,34588 ,730,730,730 ,0,0,0}, {37682,34603,37729 ,730,730,730 ,0,0,0}, - {37730,34267,37731 ,730,730,730 ,0,0,0}, {34272,37732,34261 ,730,730,730 ,0,0,0}, - {34264,34628,37733 ,730,730,730 ,0,0,0}, {37734,34262,37735 ,730,730,730 ,0,0,0}, - {34600,34276,34601 ,730,730,730 ,0,0,0}, {37736,37737,37738 ,730,730,730 ,0,0,0}, - {37739,34286,37740 ,730,730,730 ,0,0,0}, {37741,34360,34359 ,730,730,730 ,0,0,0}, - {34618,34621,37742 ,730,730,730 ,0,0,0}, {34615,37743,34611 ,730,730,730 ,0,0,0}, - {34628,37744,34625 ,730,730,730 ,0,0,0}, {34621,34623,37745 ,730,730,730 ,0,0,0}, - {3171,37746,36026 ,730,730,730 ,0,0,0}, {37747,34365,34634 ,730,730,730 ,0,0,0}, - {34700,36043,36041 ,730,730,730 ,0,0,0}, {35252,37748,37749 ,730,730,730 ,0,0,0}, - {35035,37750,35037 ,730,730,730 ,0,0,0}, {37750,37681,37680 ,730,730,730 ,0,0,0}, - {34365,34637,34634 ,730,730,730 ,0,0,0}, {35863,37751,35865 ,730,730,730 ,0,0,0}, - {34703,34701,36039 ,730,730,730 ,0,0,0}, {34703,36038,3029 ,730,730,730 ,0,0,0}, - {35012,37752,35013 ,730,730,730 ,0,0,0}, {37753,37754,37755 ,730,730,730 ,0,0,0}, - {37756,37737,37757 ,730,730,730 ,0,0,0}, {37758,37755,37754 ,730,730,730 ,0,0,0}, - {34694,37759,34695 ,730,730,730 ,0,0,0}, {37758,37760,35007 ,730,730,730 ,0,0,0}, - {37761,37762,35863 ,730,730,730 ,0,0,0}, {37763,35003,35000 ,730,730,730 ,0,0,0}, - {37764,37765,37766 ,730,730,730 ,0,0,0}, {34997,37767,35010 ,730,730,730 ,0,0,0}, - {37766,37768,37769 ,730,730,730 ,0,0,0}, {35018,35015,37770 ,730,730,730 ,0,0,0}, - {37771,37671,37673 ,730,730,730 ,0,0,0}, {37674,37771,37675 ,730,730,730 ,0,0,0}, - {37673,37675,37771 ,730,730,730 ,0,0,0}, {37772,37773,37774 ,730,730,730 ,0,0,0}, - {37773,37775,37774 ,730,730,730 ,0,0,0}, {35615,35614,37666 ,730,730,730 ,0,0,0}, - {37772,37776,37777 ,730,730,730 ,0,0,0}, {37778,37779,37780 ,730,730,730 ,0,0,0}, - {37781,35611,35609 ,730,730,730 ,0,0,0}, {37782,35497,35498 ,730,730,730 ,0,0,0}, - {35370,35361,35208 ,730,730,730 ,0,0,0}, {35501,37783,35498 ,730,730,730 ,0,0,0}, - {37784,37785,37786 ,730,730,730 ,0,0,0}, {37787,37788,37789 ,730,730,730 ,0,0,0}, - {37790,37791,37792 ,730,730,730 ,0,0,0}, {37793,37787,37794 ,730,730,730 ,0,0,0}, - {35691,37795,35688 ,730,730,730 ,0,0,0}, {37796,35698,37785 ,730,730,730 ,0,0,0}, - {37797,37798,37799 ,730,730,730 ,0,0,0}, {37800,35681,35685 ,730,730,730 ,0,0,0}, - {37800,35689,35688 ,730,730,730 ,0,0,0}, {37801,35518,35520 ,730,730,730 ,0,0,0}, - {35695,37802,37803 ,730,730,730 ,0,0,0}, {37803,37795,35693 ,730,730,730 ,0,0,0}, - {37804,37805,37801 ,730,730,730 ,0,0,0}, {37806,37792,37784 ,730,730,730 ,0,0,0}, - {35366,35212,35371 ,730,730,730 ,0,0,0}, {35221,35224,35377 ,730,730,730 ,0,0,0}, - {35426,35427,37807 ,730,730,730 ,0,0,0}, {37808,37809,37810 ,730,730,730 ,0,0,0}, - {37635,37811,37812 ,730,730,730 ,0,0,0}, {37813,37814,37798 ,730,730,730 ,0,0,0}, - {37814,37813,37810 ,730,730,730 ,0,0,0}, {37813,37798,37797 ,730,730,730 ,0,0,0}, - {37815,37816,37799 ,730,730,730 ,0,0,0}, {37797,37799,37816 ,730,730,730 ,0,0,0}, - {37817,37816,37815 ,730,730,730 ,0,0,0}, {35907,37818,35909 ,730,730,730 ,0,0,0}, - {37819,34809,34811 ,730,730,730 ,0,0,0}, {37820,37821,37822 ,730,730,730 ,0,0,0}, - {37823,37824,34426 ,730,730,730 ,0,0,0}, {34407,37825,37826 ,730,730,730 ,0,0,0}, - {37827,34788,34787 ,730,730,730 ,0,0,0}, {35780,2131,34765 ,730,730,730 ,0,0,0}, - {37828,37829,37830 ,730,730,730 ,0,0,0}, {34732,34731,37831 ,730,730,730 ,0,0,0}, - {37832,37833,37834 ,730,730,730 ,0,0,0}, {37835,34747,37836 ,730,730,730 ,0,0,0}, - {37835,34744,34747 ,730,730,730 ,0,0,0}, {37837,34734,37838 ,730,730,730 ,0,0,0}, - {34751,2950,34390 ,730,730,730 ,0,0,0}, {34398,37839,37840 ,730,730,730 ,0,0,0}, - {37841,37842,37843 ,730,730,730 ,0,0,0}, {37844,37845,37846 ,730,730,730 ,0,0,0}, - {37847,37848,37849 ,730,730,730 ,0,0,0}, {37850,37851,37852 ,730,730,730 ,0,0,0}, - {37853,37854,37855 ,730,730,730 ,0,0,0}, {37856,34413,37857 ,730,730,730 ,0,0,0}, - {37858,37859,35797 ,730,730,730 ,0,0,0}, {37823,34426,37860 ,730,730,730 ,0,0,0}, - {34725,34416,34726 ,730,730,730 ,0,0,0}, {37861,37862,37863 ,730,730,730 ,0,0,0}, - {34440,37864,34429 ,730,730,730 ,0,0,0}, {37865,37866,37821 ,730,730,730 ,0,0,0}, - {34444,34443,37867 ,730,730,730 ,0,0,0}, {37868,34818,34800 ,730,730,730 ,0,0,0}, - {34437,34774,34435 ,730,730,730 ,0,0,0}, {37869,35933,37870 ,730,730,730 ,0,0,0}, - {37871,34807,37872 ,730,730,730 ,0,0,0}, {34449,34451,34824 ,730,730,730 ,0,0,0}, - {37873,37874,37875 ,730,730,730 ,0,0,0}, {34779,34781,37876 ,730,730,730 ,0,0,0}, - {37877,37878,35792 ,730,730,730 ,0,0,0}, {34811,37879,37819 ,730,730,730 ,0,0,0}, - {2941,37880,34404 ,730,730,730 ,0,0,0}, {34790,37881,37882 ,730,730,730 ,0,0,0}, - {37883,37884,34796 ,730,730,730 ,0,0,0}, {34409,37885,37825 ,730,730,730 ,0,0,0}, - {34454,35918,34443 ,730,730,730 ,0,0,0}, {37856,37886,34413 ,730,730,730 ,0,0,0}, - {34728,37887,37888 ,730,730,730 ,0,0,0}, {35802,35913,35912 ,730,730,730 ,0,0,0}, - {37874,37818,35907 ,730,730,730 ,0,0,0}, {37889,37830,37829 ,730,730,730 ,0,0,0}, - {37890,37851,37891 ,730,730,730 ,0,0,0}, {37888,34731,34728 ,730,730,730 ,0,0,0}, - {37888,37892,37831 ,730,730,730 ,0,0,0}, {37853,37893,37854 ,730,730,730 ,0,0,0}, - {34731,37888,37831 ,730,730,730 ,0,0,0}, {37847,37894,37895 ,730,730,730 ,0,0,0}, - {35720,37896,35721 ,730,730,730 ,0,0,0}, {37849,37848,37897 ,730,730,730 ,0,0,0}, - {37898,37899,37900 ,730,730,730 ,0,0,0}, {35916,35803,37901 ,730,730,730 ,0,0,0}, - {37902,34374,34373 ,730,730,730 ,0,0,0}, {34744,37903,34745 ,730,730,730 ,0,0,0}, - {37904,37905,37906 ,730,730,730 ,0,0,0}, {37907,34737,37908 ,730,730,730 ,0,0,0}, - {34765,34763,35780 ,730,730,730 ,0,0,0}, {35209,35366,35370 ,730,730,730 ,0,0,0}, - {34757,35783,34759 ,730,730,730 ,0,0,0}, {37909,37910,37911 ,730,730,730 ,0,0,0}, - {35777,35788,37912 ,730,730,730 ,0,0,0}, {35050,37913,37914 ,730,730,730 ,0,0,0}, - {37913,35050,35789 ,730,730,730 ,0,0,0}, {35041,37915,37916 ,730,730,730 ,0,0,0}, - {37917,35788,35789 ,730,730,730 ,0,0,0}, {37917,37918,35788 ,730,730,730 ,0,0,0}, - {35062,37919,37920 ,730,730,730 ,0,0,0}, {37921,37922,37918 ,730,730,730 ,0,0,0}, - {37904,37923,37905 ,730,730,730 ,0,0,0}, {37924,37905,37922 ,730,730,730 ,0,0,0}, - {37919,34984,37925 ,730,730,730 ,0,0,0}, {37814,37810,37809 ,730,730,730 ,0,0,0}, - {37809,37808,37926 ,730,730,730 ,0,0,0}, {37927,37928,37926 ,730,730,730 ,0,0,0}, - {37926,37808,37927 ,730,730,730 ,0,0,0}, {37811,37929,37812 ,730,730,730 ,0,0,0}, - {37807,35427,37930 ,730,730,730 ,0,0,0}, {37909,37633,37910 ,730,730,730 ,0,0,0}, - {35366,35209,35212 ,730,730,730 ,0,0,0}, {35361,35129,35208 ,730,730,730 ,0,0,0}, - {35189,37931,37932 ,730,730,730 ,0,0,0}, {35373,35214,35215 ,730,730,730 ,0,0,0}, - {37933,35733,35714 ,730,730,730 ,0,0,0}, {35734,35733,37934 ,730,730,730 ,0,0,0}, - {35736,35734,37935 ,730,730,730 ,0,0,0}, {35713,37936,37933 ,730,730,730 ,0,0,0}, - {35730,37937,37938 ,730,730,730 ,0,0,0}, {37939,37936,35717 ,730,730,730 ,0,0,0}, - {35720,35723,37896 ,730,730,730 ,0,0,0}, {37940,35742,35740 ,730,730,730 ,0,0,0}, - {35744,35742,37940 ,730,730,730 ,0,0,0}, {35725,37941,35723 ,730,730,730 ,0,0,0}, - {37942,35358,37943 ,730,730,730 ,0,0,0}, {33841,37944,37945 ,730,730,730 ,0,0,0}, - {35142,37946,35147 ,730,730,730 ,0,0,0}, {37947,35201,35203 ,730,730,730 ,0,0,0}, - {35567,37948,35563 ,730,730,730 ,0,0,0}, {37949,37950,37951 ,730,730,730 ,0,0,0}, - {37952,37953,37950 ,730,730,730 ,0,0,0}, {37468,37954,37469 ,730,730,730 ,0,0,0}, - {37955,37468,37470 ,730,730,730 ,0,0,0}, {37956,37957,37954 ,730,730,730 ,0,0,0}, - {37469,37954,37957 ,730,730,730 ,0,0,0}, {35072,37958,37959 ,730,730,730 ,0,0,0}, - {35072,37959,37960 ,730,730,730 ,0,0,0}, {37550,37961,37551 ,730,730,730 ,0,0,0}, - {34854,37546,37962 ,730,730,730 ,0,0,0}, {34848,37963,37552 ,730,730,730 ,0,0,0}, - {34132,37964,37965 ,730,730,730 ,0,0,0}, {37966,34121,37967 ,730,730,730 ,0,0,0}, - {37968,35977,37969 ,730,730,730 ,0,0,0}, {37970,37971,36139 ,730,730,730 ,0,0,0}, - {34136,34135,37972 ,730,730,730 ,0,0,0}, {34941,34922,37973 ,730,730,730 ,0,0,0}, - {36124,36127,34925 ,730,730,730 ,0,0,0}, {36139,37971,36136 ,730,730,730 ,0,0,0}, - {36124,34925,34929 ,730,730,730 ,0,0,0}, {34141,34143,34947 ,730,730,730 ,0,0,0}, - {34928,34931,36118 ,730,730,730 ,0,0,0}, {37974,37975,34062 ,730,730,730 ,0,0,0}, - {34052,34911,34910 ,730,730,730 ,0,0,0}, {34933,36117,34931 ,730,730,730 ,0,0,0}, - {34135,34146,35962 ,730,730,730 ,0,0,0}, {35962,34146,35961 ,730,730,730 ,0,0,0}, - {37976,35941,35939 ,730,730,730 ,0,0,0}, {37977,37978,34043 ,730,730,730 ,0,0,0}, - {37979,37980,37981 ,730,730,730 ,0,0,0}, {37982,37983,37984 ,730,730,730 ,0,0,0}, - {37536,34916,34913 ,730,730,730 ,0,0,0}, {4039,36154,36151 ,730,730,730 ,0,0,0}, - {37985,37986,3917 ,730,730,730 ,0,0,0}, {34873,34306,34304 ,730,730,730 ,0,0,0}, - {37987,34220,37988 ,730,730,730 ,0,0,0}, {34227,37989,34225 ,730,730,730 ,0,0,0}, - {34222,34220,37990 ,730,730,730 ,0,0,0}, {34208,34888,34886 ,730,730,730 ,0,0,0}, - {37991,37992,37993 ,730,730,730 ,0,0,0}, {35956,35954,34230 ,730,730,730 ,0,0,0}, - {35063,37994,35076 ,730,730,730 ,0,0,0}, {37995,37996,34295 ,730,730,730 ,0,0,0}, - {37474,37476,37997 ,730,730,730 ,0,0,0}, {34311,34306,37998 ,730,730,730 ,0,0,0}, - {37999,38000,38001 ,730,730,730 ,0,0,0}, {38002,37991,38003 ,730,730,730 ,0,0,0}, - {38004,38005,37536 ,730,730,730 ,0,0,0}, {38006,36155,38007 ,730,730,730 ,0,0,0}, - {38008,38009,34314 ,730,730,730 ,0,0,0}, {38010,38011,38012 ,730,730,730 ,0,0,0}, - {37994,35063,38013 ,730,730,730 ,0,0,0}, {37536,38005,34916 ,730,730,730 ,0,0,0}, - {38014,34292,34290 ,730,730,730 ,0,0,0}, {35081,38015,38016 ,730,730,730 ,0,0,0}, - {38017,34289,34300 ,730,730,730 ,0,0,0}, {38018,38019,38016 ,730,730,730 ,0,0,0}, - {35073,38020,35070 ,730,730,730 ,0,0,0}, {38021,37959,38022 ,730,730,730 ,0,0,0}, - {38023,38024,38025 ,730,730,730 ,0,0,0}, {37959,37958,38022 ,730,730,730 ,0,0,0}, - {38025,38026,38027 ,730,730,730 ,0,0,0}, {35101,38024,35103 ,730,730,730 ,0,0,0}, - {37955,37470,37949 ,730,730,730 ,0,0,0}, {37956,38026,38028 ,730,730,730 ,0,0,0}, - {37950,37953,37951 ,730,730,730 ,0,0,0}, {37949,37951,37955 ,730,730,730 ,0,0,0}, - {37952,37942,37953 ,730,730,730 ,0,0,0}, {37947,38029,35201 ,730,730,730 ,0,0,0}, - {37952,38030,37942 ,730,730,730 ,0,0,0}, {35579,35578,37948 ,730,730,730 ,0,0,0}, - {38031,38032,35195 ,730,730,730 ,0,0,0}, {35192,38033,35191 ,730,730,730 ,0,0,0}, - {38034,38035,38036 ,730,730,730 ,0,0,0}, {37629,35266,38037 ,730,730,730 ,0,0,0}, - {35151,38038,35152 ,730,730,730 ,0,0,0}, {38037,35270,37620 ,730,730,730 ,0,0,0}, - {35129,38030,35130 ,730,730,730 ,0,0,0}, {35165,35164,37488 ,730,730,730 ,0,0,0}, - {35165,37488,35177 ,730,730,730 ,0,0,0}, {37481,35164,35175 ,730,730,730 ,0,0,0}, - {35164,37481,37488 ,730,730,730 ,0,0,0}, {37481,35173,35171 ,730,730,730 ,0,0,0}, - {35175,35173,37481 ,730,730,730 ,0,0,0}, {37481,35166,35170 ,730,730,730 ,0,0,0}, - {35171,35166,37481 ,730,730,730 ,0,0,0}, {37461,37463,38039 ,730,730,730 ,0,0,0}, - {35170,35161,37481 ,730,730,730 ,0,0,0}, {38040,35776,38041 ,730,730,730 ,0,0,0}, - {38040,38039,35776 ,730,730,730 ,0,0,0}, {37479,35156,38042 ,730,730,730 ,0,0,0}, - {38043,35148,38044 ,730,730,730 ,0,0,0}, {38045,35762,38046 ,730,730,730 ,0,0,0}, - {38047,35138,38048 ,730,730,730 ,0,0,0}, {35142,37467,37946 ,730,730,730 ,0,0,0}, - {35135,38049,35133 ,730,730,730 ,0,0,0}, {35745,38050,35746 ,730,730,730 ,0,0,0}, - {35759,33209,35587 ,730,730,730 ,0,0,0}, {38033,35192,38032 ,730,730,730 ,0,0,0}, - {35581,35579,35753 ,730,730,730 ,0,0,0}, {35195,35197,38031 ,730,730,730 ,0,0,0}, - {38051,35130,38030 ,730,730,730 ,0,0,0}, {38029,35197,35198 ,730,730,730 ,0,0,0}, - {38052,35573,38053 ,730,730,730 ,0,0,0}, {38051,37947,35203 ,730,730,730 ,0,0,0}, - {35198,35201,38029 ,730,730,730 ,0,0,0}, {35204,35130,38051 ,730,730,730 ,0,0,0}, - {35203,35204,38051 ,730,730,730 ,0,0,0}, {35377,35365,35221 ,730,730,730 ,0,0,0}, - {35364,35375,35218 ,730,730,730 ,0,0,0}, {35373,35215,35375 ,730,730,730 ,0,0,0}, - {38054,38055,38056 ,730,730,730 ,0,0,0}, {35364,35220,35365 ,730,730,730 ,0,0,0}, - {35221,35365,35220 ,730,730,730 ,0,0,0}, {35414,38057,35412 ,730,730,730 ,0,0,0}, - {35378,35224,35226 ,730,730,730 ,0,0,0}, {35224,35378,35377 ,730,730,730 ,0,0,0}, - {35226,35382,35378 ,730,730,730 ,0,0,0}, {35129,35361,35360 ,730,730,730 ,0,0,0}, - {37942,38030,35360 ,730,730,730 ,0,0,0}, {35227,35382,35226 ,730,730,730 ,0,0,0}, - {38058,38059,38060 ,730,730,730 ,0,0,0}, {38061,38062,38063 ,730,730,730 ,0,0,0}, - {38064,38065,38066 ,730,730,730 ,0,0,0}, {38067,38068,38069 ,730,730,730 ,0,0,0}, - {38070,38071,38072 ,730,730,730 ,0,0,0}, {35420,37807,37668 ,730,730,730 ,0,0,0}, - {38073,37807,38074 ,730,730,730 ,0,0,0}, {35285,38075,38076 ,730,730,730 ,0,0,0}, - {38077,38078,38079 ,730,730,730 ,0,0,0}, {38080,38081,38082 ,730,730,730 ,0,0,0}, - {38083,35492,35495 ,730,730,730 ,0,0,0}, {38084,38085,35440 ,730,730,730 ,0,0,0}, - {38086,35458,38087 ,730,730,730 ,0,0,0}, {38088,35448,38089 ,730,730,730 ,0,0,0}, - {38090,38091,38092 ,730,730,730 ,0,0,0}, {38093,38094,35593 ,730,730,730 ,0,0,0}, - {38095,38096,35633 ,730,730,730 ,0,0,0}, {35633,33508,38095 ,730,730,730 ,0,0,0}, - {37748,35252,35251 ,730,730,730 ,0,0,0}, {35631,37624,35629 ,730,730,730 ,0,0,0}, - {38097,33525,38098 ,730,730,730 ,0,0,0}, {35638,38099,35639 ,730,730,730 ,0,0,0}, - {38099,35638,38100 ,730,730,730 ,0,0,0}, {35278,37626,35282 ,730,730,730 ,0,0,0}, - {35620,35619,38101 ,730,730,730 ,0,0,0}, {35256,38102,35254 ,730,730,730 ,0,0,0}, - {35256,37749,38102 ,730,730,730 ,0,0,0}, {37492,35254,37621 ,730,730,730 ,0,0,0}, - {37626,35278,35277 ,730,730,730 ,0,0,0}, {37626,35277,35265 ,730,730,730 ,0,0,0}, - {38103,35260,35258 ,730,730,730 ,0,0,0}, {35271,37629,35273 ,730,730,730 ,0,0,0}, - {35260,37620,35261 ,730,730,730 ,0,0,0}, {35254,37492,35258 ,730,730,730 ,0,0,0}, - {35258,37492,38103 ,730,730,730 ,0,0,0}, {38104,38035,38102 ,730,730,730 ,0,0,0}, - {37621,38102,38035 ,730,730,730 ,0,0,0}, {38034,38036,38105 ,730,730,730 ,0,0,0}, - {38035,38104,38036 ,730,730,730 ,0,0,0}, {38106,38107,38034 ,730,730,730 ,0,0,0}, - {38034,38105,38106 ,730,730,730 ,0,0,0}, {38107,37466,37465 ,730,730,730 ,0,0,0}, - {37466,38107,38106 ,730,730,730 ,0,0,0}, {38108,37465,37464 ,730,730,730 ,0,0,0}, - {38109,38108,38110 ,730,730,730 ,0,0,0}, {38108,38109,37465 ,730,730,730 ,0,0,0}, - {38111,37488,38110 ,730,730,730 ,0,0,0}, {38109,38110,37488 ,730,730,730 ,0,0,0}, - {38112,37488,38113 ,730,730,730 ,0,0,0}, {37488,38111,38113 ,730,730,730 ,0,0,0}, - {35182,37488,38114 ,730,730,730 ,0,0,0}, {37488,38112,38114 ,730,730,730 ,0,0,0}, - {38115,35227,38116 ,730,730,730 ,0,0,0}, {38117,35391,33824 ,730,730,730 ,0,0,0}, - {35218,35375,35215 ,730,730,730 ,0,0,0}, {35220,35364,35218 ,730,730,730 ,0,0,0}, - {35371,35214,35373 ,730,730,730 ,0,0,0}, {35214,35371,35212 ,730,730,730 ,0,0,0}, - {35208,35209,35370 ,730,730,730 ,0,0,0}, {38030,35129,35360 ,730,730,730 ,0,0,0}, - {35358,37942,35360 ,730,730,730 ,0,0,0}, {35354,35356,37943 ,730,730,730 ,0,0,0}, - {35354,37943,35358 ,730,730,730 ,0,0,0}, {38118,35356,35352 ,730,730,730 ,0,0,0}, - {35356,38118,37943 ,730,730,730 ,0,0,0}, {35351,37945,35352 ,730,730,730 ,0,0,0}, - {38118,35352,37945 ,730,730,730 ,0,0,0}, {33841,37945,35346 ,730,730,730 ,0,0,0}, - {37945,35351,35346 ,730,730,730 ,0,0,0}, {35347,38119,38120 ,730,730,730 ,0,0,0}, - {35346,35348,38121 ,730,730,730 ,0,0,0}, {37944,33841,35557 ,730,730,730 ,0,0,0}, - {35340,38122,35342 ,730,730,730 ,0,0,0}, {38123,35334,38124 ,730,730,730 ,0,0,0}, - {35338,38125,38126 ,730,730,730 ,0,0,0}, {38127,38128,35386 ,730,730,730 ,0,0,0}, - {38129,38130,35335 ,730,730,730 ,0,0,0}, {35389,38117,38127 ,730,730,730 ,0,0,0}, - {35392,35395,35543 ,730,730,730 ,0,0,0}, {33824,35391,35392 ,730,730,730 ,0,0,0}, - {35543,35395,37940 ,730,730,730 ,0,0,0}, {35385,38131,35335 ,730,730,730 ,0,0,0}, - {35541,37940,35539 ,730,730,730 ,0,0,0}, {38132,35530,35529 ,730,730,730 ,0,0,0}, - {35397,35398,35744 ,730,730,730 ,0,0,0}, {35397,35744,35395 ,730,730,730 ,0,0,0}, - {38133,38134,35403 ,730,730,730 ,0,0,0}, {38135,35401,38134 ,730,730,730 ,0,0,0}, - {35329,35408,38136 ,730,730,730 ,0,0,0}, {35404,35330,38137 ,730,730,730 ,0,0,0}, - {37941,35727,37938 ,730,730,730 ,0,0,0}, {37670,38138,37668 ,730,730,730 ,0,0,0}, - {35415,37668,35414 ,730,730,730 ,0,0,0}, {37669,37668,38139 ,730,730,730 ,0,0,0}, - {35420,37668,35418 ,730,730,730 ,0,0,0}, {37668,35415,35418 ,730,730,730 ,0,0,0}, - {37807,35420,35421 ,730,730,730 ,0,0,0}, {35426,37807,35424 ,730,730,730 ,0,0,0}, - {37807,35421,35424 ,730,730,730 ,0,0,0}, {37807,37930,38074 ,730,730,730 ,0,0,0}, - {37807,38073,38140 ,730,730,730 ,0,0,0}, {38140,37911,37910 ,730,730,730 ,0,0,0}, - {37910,37807,38140 ,730,730,730 ,0,0,0}, {37634,37633,38141 ,730,730,730 ,0,0,0}, - {37909,38141,37633 ,730,730,730 ,0,0,0}, {37635,37634,37811 ,730,730,730 ,0,0,0}, - {38080,37812,38081 ,730,730,730 ,0,0,0}, {38081,37812,37929 ,730,730,730 ,0,0,0}, - {38080,38082,37927 ,730,730,730 ,0,0,0}, {38142,37928,37927 ,730,730,730 ,0,0,0}, - {37927,38082,38142 ,730,730,730 ,0,0,0}, {35601,38143,38144 ,730,730,730 ,0,0,0}, - {38145,38083,35495 ,730,730,730 ,0,0,0}, {38146,38147,35503 ,730,730,730 ,0,0,0}, - {38148,38149,35248 ,730,730,730 ,0,0,0}, {38150,35486,35489 ,730,730,730 ,0,0,0}, - {38151,35491,38152 ,730,730,730 ,0,0,0}, {38153,35435,35485 ,730,730,730 ,0,0,0}, - {38154,35486,38150 ,730,730,730 ,0,0,0}, {38155,32893,37772 ,730,730,730 ,0,0,0}, - {38156,35434,35433 ,730,730,730 ,0,0,0}, {38157,38158,38159 ,730,730,730 ,0,0,0}, - {35448,35447,38089 ,730,730,730 ,0,0,0}, {38088,38160,35446 ,730,730,730 ,0,0,0}, - {38161,35447,35442 ,730,730,730 ,0,0,0}, {38162,38163,38164 ,730,730,730 ,0,0,0}, - {38165,35596,35599 ,730,730,730 ,0,0,0}, {38166,38167,38168 ,730,730,730 ,0,0,0}, - {35301,35303,38169 ,730,730,730 ,0,0,0}, {38170,35298,35301 ,730,730,730 ,0,0,0}, - {35608,38171,35609 ,730,730,730 ,0,0,0}, {38172,35246,38149 ,730,730,730 ,0,0,0}, - {35295,35297,38173 ,730,730,730 ,0,0,0}, {35233,38174,38175 ,730,730,730 ,0,0,0}, - {38086,38087,38068 ,730,730,730 ,0,0,0}, {35298,38176,35297 ,730,730,730 ,0,0,0}, - {38069,38177,38067 ,730,730,730 ,0,0,0}, {38087,38069,38068 ,730,730,730 ,0,0,0}, - {38070,38072,38177 ,730,730,730 ,0,0,0}, {38067,38177,38072 ,730,730,730 ,0,0,0}, - {38071,38070,38066 ,730,730,730 ,0,0,0}, {38178,38065,38064 ,730,730,730 ,0,0,0}, - {38065,38071,38066 ,730,730,730 ,0,0,0}, {38178,37780,37779 ,730,730,730 ,0,0,0}, - {37780,38178,38064 ,730,730,730 ,0,0,0}, {37778,38059,37779 ,730,730,730 ,0,0,0}, - {38060,38061,38058 ,730,730,730 ,0,0,0}, {37778,38060,38059 ,730,730,730 ,0,0,0}, - {38063,38062,38116 ,730,730,730 ,0,0,0}, {38058,38061,38063 ,730,730,730 ,0,0,0}, - {35227,38115,35382 ,730,730,730 ,0,0,0}, {38116,38062,38115 ,730,730,730 ,0,0,0}, - {38179,35953,35951 ,730,730,730 ,0,0,0}, {34905,3897,38180 ,730,730,730 ,0,0,0}, - {34141,34944,38181 ,730,730,730 ,0,0,0}, {38182,38011,38183 ,730,730,730 ,0,0,0}, - {36155,38006,36157 ,730,730,730 ,0,0,0}, {38184,36166,3897 ,730,730,730 ,0,0,0}, - {36161,38185,38186 ,730,730,730 ,0,0,0}, {38187,36169,36167 ,730,730,730 ,0,0,0}, - {38188,38189,38190 ,730,730,730 ,0,0,0}, {38015,35079,35078 ,730,730,730 ,0,0,0}, - {34866,38191,34867 ,730,730,730 ,0,0,0}, {38002,38003,35960 ,730,730,730 ,0,0,0}, - {38192,38193,38194 ,730,730,730 ,0,0,0}, {34208,34890,34888 ,730,730,730 ,0,0,0}, - {34890,34208,34206 ,730,730,730 ,0,0,0}, {37484,34206,38195 ,730,730,730 ,0,0,0}, - {34205,38196,38195 ,730,730,730 ,0,0,0}, {34219,34230,35954 ,730,730,730 ,0,0,0}, - {38197,38198,38199 ,730,730,730 ,0,0,0}, {38200,38201,38202 ,730,730,730 ,0,0,0}, - {3917,34857,37982 ,730,730,730 ,0,0,0}, {37962,38203,34855 ,730,730,730 ,0,0,0}, - {34855,34854,37962 ,730,730,730 ,0,0,0}, {34851,38204,37546 ,730,730,730 ,0,0,0}, - {34849,38204,34851 ,730,730,730 ,0,0,0}, {34841,34843,38205 ,730,730,730 ,0,0,0}, - {38206,37964,34133 ,730,730,730 ,0,0,0}, {34947,34944,34141 ,730,730,730 ,0,0,0}, - {37963,34830,38207 ,730,730,730 ,0,0,0}, {34829,34124,34122 ,730,730,730 ,0,0,0}, - {34952,34950,34138 ,730,730,730 ,0,0,0}, {38208,37973,34922 ,730,730,730 ,0,0,0}, - {38209,35967,35968 ,730,730,730 ,0,0,0}, {36130,36133,38210 ,730,730,730 ,0,0,0}, - {34921,36127,36129 ,730,730,730 ,0,0,0}, {38211,34062,37975 ,730,730,730 ,0,0,0}, - {36121,36123,34929 ,730,730,730 ,0,0,0}, {34928,36118,36121 ,730,730,730 ,0,0,0}, - {34052,34910,34892 ,730,730,730 ,0,0,0}, {36115,36117,34933 ,730,730,730 ,0,0,0}, - {36115,34935,36112 ,730,730,730 ,0,0,0}, {34040,37530,38212 ,730,730,730 ,0,0,0}, - {35791,35802,35910 ,730,730,730 ,0,0,0}, {34722,38213,34719 ,730,730,730 ,0,0,0}, - {37882,37883,34793 ,730,730,730 ,0,0,0}, {37833,38214,38215 ,730,730,730 ,0,0,0}, - {38216,37843,38217 ,730,730,730 ,0,0,0}, {37841,38218,34374 ,730,730,730 ,0,0,0}, - {34395,38219,34393 ,730,730,730 ,0,0,0}, {38220,34379,38221 ,730,730,730 ,0,0,0}, - {38222,38223,38224 ,730,730,730 ,0,0,0}, {34762,34759,35783 ,730,730,730 ,0,0,0}, - {34744,37835,37903 ,730,730,730 ,0,0,0}, {37908,34737,34741 ,730,730,730 ,0,0,0}, - {38225,37903,38226 ,730,730,730 ,0,0,0}, {34741,34745,37908 ,730,730,730 ,0,0,0}, - {38227,38228,38226 ,730,730,730 ,0,0,0}, {38229,34736,37837 ,730,730,730 ,0,0,0}, - {38228,38230,38231 ,730,730,730 ,0,0,0}, {35913,35802,35803 ,730,730,730 ,0,0,0}, - {35912,35910,35802 ,730,730,730 ,0,0,0}, {38232,35044,35048 ,730,730,730 ,0,0,0}, - {35051,38233,35048 ,730,730,730 ,0,0,0}, {38234,38235,38236 ,730,730,730 ,0,0,0}, - {38237,38238,38239 ,730,730,730 ,0,0,0}, {38239,34798,38240 ,730,730,730 ,0,0,0}, - {34794,37883,34796 ,730,730,730 ,0,0,0}, {34821,38241,34449 ,730,730,730 ,0,0,0}, - {38242,37827,34787 ,730,730,730 ,0,0,0}, {38243,38244,34441 ,730,730,730 ,0,0,0}, - {34824,34821,34449 ,730,730,730 ,0,0,0}, {34430,34767,34432 ,730,730,730 ,0,0,0}, - {38242,34768,38245 ,730,730,730 ,0,0,0}, {2165,34827,34446 ,730,730,730 ,0,0,0}, - {37868,34800,37863 ,730,730,730 ,0,0,0}, {38246,35923,35924 ,730,730,730 ,0,0,0}, - {37865,38247,37866 ,730,730,730 ,0,0,0}, {34799,34803,38248 ,730,730,730 ,0,0,0}, - {37871,38248,34803 ,730,730,730 ,0,0,0}, {37872,34807,34806 ,730,730,730 ,0,0,0}, - {38249,34806,34809 ,730,730,730 ,0,0,0}, {34416,34725,34706 ,730,730,730 ,0,0,0}, - {37879,34813,38250 ,730,730,730 ,0,0,0}, {34813,38251,38250 ,730,730,730 ,0,0,0}, - {34404,37880,37885 ,730,730,730 ,0,0,0}, {34108,38252,38253 ,730,730,730 ,0,0,0}, - {34603,37682,34606 ,730,730,730 ,0,0,0}, {38254,36033,36032 ,730,730,730 ,0,0,0}, - {38255,38256,38257 ,730,730,730 ,0,0,0}, {37589,38258,38255 ,730,730,730 ,0,0,0}, - {34180,34178,38259 ,730,730,730 ,0,0,0}, {34199,38260,34197 ,730,730,730 ,0,0,0}, - {34191,34655,34192 ,730,730,730 ,0,0,0}, {38261,38262,34183 ,730,730,730 ,0,0,0}, - {38263,38264,38265 ,730,730,730 ,0,0,0}, {38264,38263,38266 ,730,730,730 ,0,0,0}, - {36008,36011,37711 ,730,730,730 ,0,0,0}, {38267,35999,38268 ,730,730,730 ,0,0,0}, - {37718,35989,38269 ,730,730,730 ,0,0,0}, {34674,34094,35984 ,730,730,730 ,0,0,0}, - {34096,34674,34672 ,730,730,730 ,0,0,0}, {34099,34664,38270 ,730,730,730 ,0,0,0}, - {38271,34113,37721 ,730,730,730 ,0,0,0}, {35981,35983,34094 ,730,730,730 ,0,0,0}, - {38272,3029,38273 ,730,730,730 ,0,0,0}, {35854,38274,38275 ,730,730,730 ,0,0,0}, - {36035,3029,36038 ,730,730,730 ,0,0,0}, {34367,34637,34365 ,730,730,730 ,0,0,0}, - {34701,36041,36039 ,730,730,730 ,0,0,0}, {35873,35874,34370 ,730,730,730 ,0,0,0}, - {35874,34359,34370 ,730,730,730 ,0,0,0}, {36041,34701,34700 ,730,730,730 ,0,0,0}, - {34359,35877,35879 ,730,730,730 ,0,0,0}, {37754,37753,37736 ,730,730,730 ,0,0,0}, - {38276,37754,37736 ,730,730,730 ,0,0,0}, {34640,34362,34642 ,730,730,730 ,0,0,0}, - {34353,34682,34351 ,730,730,730 ,0,0,0}, {38277,34612,34611 ,730,730,730 ,0,0,0}, - {38278,34612,38277 ,730,730,730 ,0,0,0}, {38279,35889,38280 ,730,730,730 ,0,0,0}, - {38281,34286,37739 ,730,730,730 ,0,0,0}, {34619,38282,34615 ,730,730,730 ,0,0,0}, - {34618,37742,38282 ,730,730,730 ,0,0,0}, {34276,34600,34582 ,730,730,730 ,0,0,0}, - {38283,37745,34623 ,730,730,730 ,0,0,0}, {38283,34625,37744 ,730,730,730 ,0,0,0}, - {37733,38284,34264 ,730,730,730 ,0,0,0}, {38285,35810,38286 ,730,730,730 ,0,0,0}, - {36069,36071,38287 ,730,730,730 ,0,0,0}, {38288,34085,34573 ,730,730,730 ,0,0,0}, - {38289,37517,38290 ,730,730,730 ,0,0,0}, {38291,38292,38293 ,730,730,730 ,0,0,0}, - {38294,38295,34241 ,730,730,730 ,0,0,0}, {34233,38296,37513 ,730,730,730 ,0,0,0}, - {38297,37562,38298 ,730,730,730 ,0,0,0}, {38299,38300,38301 ,730,730,730 ,0,0,0}, - {38302,38303,38304 ,730,730,730 ,0,0,0}, {38305,38306,38303 ,730,730,730 ,0,0,0}, - {38307,37582,37584 ,730,730,730 ,0,0,0}, {38308,37548,38309 ,730,730,730 ,0,0,0}, - {37567,38310,38311 ,730,730,730 ,0,0,0}, {38312,2073,37578 ,730,730,730 ,0,0,0}, - {34152,34517,34515 ,730,730,730 ,0,0,0}, {34514,34157,34515 ,730,730,730 ,0,0,0}, - {34155,34514,34511 ,730,730,730 ,0,0,0}, {34155,34509,38313 ,730,730,730 ,0,0,0}, - {34488,37539,37538 ,730,730,730 ,0,0,0}, {34488,36063,36065 ,730,730,730 ,0,0,0}, - {34484,36060,34486 ,730,730,730 ,0,0,0}, {36059,34484,34483 ,730,730,730 ,0,0,0}, - {35830,34090,35829 ,730,730,730 ,0,0,0}, {34483,34480,36057 ,730,730,730 ,0,0,0}, - {34478,36054,34480 ,730,730,730 ,0,0,0}, {34077,36085,36084 ,730,730,730 ,0,0,0}, - {34469,34471,37528 ,730,730,730 ,0,0,0}, {34576,34573,34085 ,730,730,730 ,0,0,0}, - {34066,34458,34457 ,730,730,730 ,0,0,0}, {34068,34457,34461 ,730,730,730 ,0,0,0}, - {2082,34579,34082 ,730,730,730 ,0,0,0}, {34552,38314,37529 ,730,730,730 ,0,0,0}, - {36091,36090,38315 ,730,730,730 ,0,0,0}, {38315,38316,36091 ,730,730,730 ,0,0,0}, - {35845,38317,38318 ,730,730,730 ,0,0,0}, {36097,38314,36099 ,730,730,730 ,0,0,0}, - {37604,34342,38319 ,730,730,730 ,0,0,0}, {36102,36099,34551 ,730,730,730 ,0,0,0}, - {34520,34332,34539 ,730,730,730 ,0,0,0}, {36102,34555,36103 ,730,730,730 ,0,0,0}, - {34559,36105,36103 ,730,730,730 ,0,0,0}, {34971,38320,34328 ,730,730,730 ,0,0,0}, - {35051,38235,38233 ,730,730,730 ,0,0,0}, {2131,35778,38321 ,730,730,730 ,0,0,0}, - {35917,35918,34454 ,730,730,730 ,0,0,0}, {38234,38233,38235 ,730,730,730 ,0,0,0}, - {38234,38236,38240 ,730,730,730 ,0,0,0}, {38240,34798,37884 ,730,730,730 ,0,0,0}, - {37884,38234,38240 ,730,730,730 ,0,0,0}, {34796,37884,34798 ,730,730,730 ,0,0,0}, - {37818,38322,35904 ,730,730,730 ,0,0,0}, {38323,38324,35794 ,730,730,730 ,0,0,0}, - {34443,35921,35923 ,730,730,730 ,0,0,0}, {37883,34794,34793 ,730,730,730 ,0,0,0}, - {38325,35897,35895 ,730,730,730 ,0,0,0}, {35791,35910,35904 ,730,730,730 ,0,0,0}, - {35916,35913,35803 ,730,730,730 ,0,0,0}, {35916,37901,38231 ,730,730,730 ,0,0,0}, - {38231,38230,35916 ,730,730,730 ,0,0,0}, {38227,38230,38228 ,730,730,730 ,0,0,0}, - {38225,38226,38228 ,730,730,730 ,0,0,0}, {38326,38327,38328 ,730,730,730 ,0,0,0}, - {35780,34763,35785 ,730,730,730 ,0,0,0}, {37908,34745,38225 ,730,730,730 ,0,0,0}, - {38329,38330,38331 ,730,730,730 ,0,0,0}, {38332,38333,38334 ,730,730,730 ,0,0,0}, - {35778,2131,35780 ,730,730,730 ,0,0,0}, {38335,38336,38337 ,730,730,730 ,0,0,0}, - {35778,35777,38321 ,730,730,730 ,0,0,0}, {38338,38339,38340 ,730,730,730 ,0,0,0}, - {37912,35788,37918 ,730,730,730 ,0,0,0}, {38321,35777,37912 ,730,730,730 ,0,0,0}, - {37917,35789,35050 ,730,730,730 ,0,0,0}, {35776,38050,38041 ,730,730,730 ,0,0,0}, - {35133,38341,35134 ,730,730,730 ,0,0,0}, {35772,38050,35774 ,730,730,730 ,0,0,0}, - {38050,35776,35774 ,730,730,730 ,0,0,0}, {35768,38050,35771 ,730,730,730 ,0,0,0}, - {38050,35772,35771 ,730,730,730 ,0,0,0}, {35765,38050,35766 ,730,730,730 ,0,0,0}, - {38050,35768,35766 ,730,730,730 ,0,0,0}, {38050,35765,35746 ,730,730,730 ,0,0,0}, - {37948,38050,35749 ,730,730,730 ,0,0,0}, {35745,35749,38050 ,730,730,730 ,0,0,0}, - {35587,35757,35759 ,730,730,730 ,0,0,0}, {35755,35585,35584 ,730,730,730 ,0,0,0}, - {37948,35749,35753 ,730,730,730 ,0,0,0}, {35587,35585,35757 ,730,730,730 ,0,0,0}, - {35191,37931,35189 ,730,730,730 ,0,0,0}, {35138,38047,35140 ,730,730,730 ,0,0,0}, - {37467,35140,38046 ,730,730,730 ,0,0,0}, {35147,37946,38044 ,730,730,730 ,0,0,0}, - {35146,35148,38043 ,730,730,730 ,0,0,0}, {35148,35147,38044 ,730,730,730 ,0,0,0}, - {35151,35146,37489 ,730,730,730 ,0,0,0}, {37490,35146,38043 ,730,730,730 ,0,0,0}, - {38042,35152,38038 ,730,730,730 ,0,0,0}, {38038,35151,37489 ,730,730,730 ,0,0,0}, - {37479,35154,35156 ,730,730,730 ,0,0,0}, {38042,35156,35152 ,730,730,730 ,0,0,0}, - {37480,35158,35154 ,730,730,730 ,0,0,0}, {37482,35160,35158 ,730,730,730 ,0,0,0}, - {37477,37486,37478 ,730,730,730 ,0,0,0}, {35160,37482,37481 ,730,730,730 ,0,0,0}, - {37473,37471,37463 ,730,730,730 ,0,0,0}, {35776,38039,37463 ,730,730,730 ,0,0,0}, - {37940,35395,35744 ,730,730,730 ,0,0,0}, {35409,38342,35408 ,730,730,730 ,0,0,0}, - {35739,35736,37940 ,730,730,730 ,0,0,0}, {35739,37940,35740 ,730,730,730 ,0,0,0}, - {35736,37935,37940 ,730,730,730 ,0,0,0}, {35734,37934,37935 ,730,730,730 ,0,0,0}, - {35733,37933,37934 ,730,730,730 ,0,0,0}, {35713,37933,35714 ,730,730,730 ,0,0,0}, - {35717,37936,35713 ,730,730,730 ,0,0,0}, {35721,37896,37939 ,730,730,730 ,0,0,0}, - {35721,37939,35717 ,730,730,730 ,0,0,0}, {37941,37896,35723 ,730,730,730 ,0,0,0}, - {37941,35725,35727 ,730,730,730 ,0,0,0}, {37938,35727,35730 ,730,730,730 ,0,0,0}, - {38343,38344,37937 ,730,730,730 ,0,0,0}, {37937,35730,38343 ,730,730,730 ,0,0,0}, - {38343,38056,38344 ,730,730,730 ,0,0,0}, {38057,35414,38138 ,730,730,730 ,0,0,0}, - {38056,38055,38344 ,730,730,730 ,0,0,0}, {37668,38054,38139 ,730,730,730 ,0,0,0}, - {38055,38054,37668 ,730,730,730 ,0,0,0}, {35414,37668,38138 ,730,730,730 ,0,0,0}, - {35409,35412,38057 ,730,730,730 ,0,0,0}, {38136,35408,38342 ,730,730,730 ,0,0,0}, - {38342,35409,38057 ,730,730,730 ,0,0,0}, {38137,35329,38136 ,730,730,730 ,0,0,0}, - {38137,38133,35404 ,730,730,730 ,0,0,0}, {38137,35330,35329 ,730,730,730 ,0,0,0}, - {35403,38134,35401 ,730,730,730 ,0,0,0}, {35404,38133,35403 ,730,730,730 ,0,0,0}, - {35401,38135,35398 ,730,730,730 ,0,0,0}, {35744,35398,38135 ,730,730,730 ,0,0,0}, - {38345,37800,38346 ,730,730,730 ,0,0,0}, {38347,38348,38349 ,730,730,730 ,0,0,0}, - {37801,37805,38350 ,730,730,730 ,0,0,0}, {38346,37800,38351 ,730,730,730 ,0,0,0}, - {38352,32876,38353 ,730,730,730 ,0,0,0}, {38354,35504,35430 ,730,730,730 ,0,0,0}, - {35508,35509,38355 ,730,730,730 ,0,0,0}, {35451,38356,35452 ,730,730,730 ,0,0,0}, - {37801,35526,35527 ,730,730,730 ,0,0,0}, {35685,35689,37800 ,730,730,730 ,0,0,0}, - {35688,37795,37800 ,730,730,730 ,0,0,0}, {35693,37795,35691 ,730,730,730 ,0,0,0}, - {35695,37803,35693 ,730,730,730 ,0,0,0}, {35698,37796,37802 ,730,730,730 ,0,0,0}, - {35698,37802,35695 ,730,730,730 ,0,0,0}, {37785,37784,37796 ,730,730,730 ,0,0,0}, - {37806,37784,37786 ,730,730,730 ,0,0,0}, {37794,37792,37791 ,730,730,730 ,0,0,0}, - {37790,37792,37806 ,730,730,730 ,0,0,0}, {38357,37787,37793 ,730,730,730 ,0,0,0}, - {37793,37794,37791 ,730,730,730 ,0,0,0}, {38349,37789,37788 ,730,730,730 ,0,0,0}, - {37788,37787,38357 ,730,730,730 ,0,0,0}, {38347,38358,38348 ,730,730,730 ,0,0,0}, - {38349,38348,37789 ,730,730,730 ,0,0,0}, {38359,38358,38360 ,730,730,730 ,0,0,0}, - {38347,38360,38358 ,730,730,730 ,0,0,0}, {38361,38359,38362 ,730,730,730 ,0,0,0}, - {38359,38360,38362 ,730,730,730 ,0,0,0}, {38363,38364,35712 ,730,730,730 ,0,0,0}, - {38359,38361,38364 ,730,730,730 ,0,0,0}, {37657,35678,35676 ,730,730,730 ,0,0,0}, - {38099,38365,35641 ,730,730,730 ,0,0,0}, {37662,35675,38366 ,730,730,730 ,0,0,0}, - {35675,37662,35676 ,730,730,730 ,0,0,0}, {38366,35672,35670 ,730,730,730 ,0,0,0}, - {35675,35672,38366 ,730,730,730 ,0,0,0}, {38366,35669,35650 ,730,730,730 ,0,0,0}, - {35670,35669,38366 ,730,730,730 ,0,0,0}, {38367,38368,35653 ,730,730,730 ,0,0,0}, - {35657,38367,35653 ,730,730,730 ,0,0,0}, {35661,38369,35659 ,730,730,730 ,0,0,0}, - {35656,38370,38371 ,730,730,730 ,0,0,0}, {38372,35645,35644 ,730,730,730 ,0,0,0}, - {35644,38365,38372 ,730,730,730 ,0,0,0}, {35645,38373,35647 ,730,730,730 ,0,0,0}, - {38372,38373,35645 ,730,730,730 ,0,0,0}, {35647,38374,33525 ,730,730,730 ,0,0,0}, - {37654,37649,37648 ,730,730,730 ,0,0,0}, {37644,37643,37648 ,730,730,730 ,0,0,0}, - {37644,37648,37650 ,730,730,730 ,0,0,0}, {37637,37636,37643 ,730,730,730 ,0,0,0}, - {37638,37642,37636 ,730,730,730 ,0,0,0}, {38375,37641,37640 ,730,730,730 ,0,0,0}, - {37640,37642,37658 ,730,730,730 ,0,0,0}, {38376,38375,37647 ,730,730,730 ,0,0,0}, - {38375,38376,37641 ,730,730,730 ,0,0,0}, {37645,38377,37646 ,730,730,730 ,0,0,0}, - {38376,37647,37646 ,730,730,730 ,0,0,0}, {37651,37653,38377 ,730,730,730 ,0,0,0}, - {37646,38377,37653 ,730,730,730 ,0,0,0}, {37653,37652,37656 ,730,730,730 ,0,0,0}, - {35680,37656,37652 ,730,730,730 ,0,0,0}, {35641,35639,38099 ,730,730,730 ,0,0,0}, - {38378,33508,38379 ,730,730,730 ,0,0,0}, {38380,38381,38379 ,730,730,730 ,0,0,0}, - {35246,38172,35251 ,730,730,730 ,0,0,0}, {35309,35466,35470 ,730,730,730 ,0,0,0}, - {35470,35308,35309 ,730,730,730 ,0,0,0}, {35473,35315,35475 ,730,730,730 ,0,0,0}, - {35308,35461,35229 ,730,730,730 ,0,0,0}, {35460,35229,35461 ,730,730,730 ,0,0,0}, - {35324,35478,35477 ,730,730,730 ,0,0,0}, {35247,38148,35248 ,730,730,730 ,0,0,0}, - {37495,37494,38078 ,730,730,730 ,0,0,0}, {38382,35617,35615 ,730,730,730 ,0,0,0}, - {37667,35614,35611 ,730,730,730 ,0,0,0}, {35617,37776,32893 ,730,730,730 ,0,0,0}, - {38383,38384,38378 ,730,730,730 ,0,0,0}, {33508,38380,38379 ,730,730,730 ,0,0,0}, - {38381,38385,38386 ,730,730,730 ,0,0,0}, {38380,38385,38381 ,730,730,730 ,0,0,0}, - {38387,37661,38386 ,730,730,730 ,0,0,0}, {38381,38386,37661 ,730,730,730 ,0,0,0}, - {38388,37661,38389 ,730,730,730 ,0,0,0}, {37661,38387,38389 ,730,730,730 ,0,0,0}, - {37660,38390,37661 ,730,730,730 ,0,0,0}, {37661,38388,37659 ,730,730,730 ,0,0,0}, - {37648,37661,38391 ,730,730,730 ,0,0,0}, {38390,38391,37661 ,730,730,730 ,0,0,0}, - {38392,37648,38393 ,730,730,730 ,0,0,0}, {37648,38391,38393 ,730,730,730 ,0,0,0}, - {38097,37648,38394 ,730,730,730 ,0,0,0}, {37648,38392,38394 ,730,730,730 ,0,0,0}, - {38098,33525,38374 ,730,730,730 ,0,0,0}, {38395,38363,38396 ,730,730,730 ,0,0,0}, - {38087,35458,35454 ,730,730,730 ,0,0,0}, {38397,38398,38359 ,730,730,730 ,0,0,0}, - {35456,38399,38400 ,730,730,730 ,0,0,0}, {35454,35456,38400 ,730,730,730 ,0,0,0}, - {38399,35452,38356 ,730,730,730 ,0,0,0}, {38143,35601,35603 ,730,730,730 ,0,0,0}, - {38160,35451,35446 ,730,730,730 ,0,0,0}, {32876,38401,35603 ,730,730,730 ,0,0,0}, - {38401,32876,38352 ,730,730,730 ,0,0,0}, {37928,38142,35504 ,730,730,730 ,0,0,0}, - {38363,35682,35681 ,730,730,730 ,0,0,0}, {35702,38363,35704 ,730,730,730 ,0,0,0}, - {38402,38403,38363 ,730,730,730 ,0,0,0}, {38363,38404,38405 ,730,730,730 ,0,0,0}, - {35708,35707,38363 ,730,730,730 ,0,0,0}, {38405,38406,38363 ,730,730,730 ,0,0,0}, - {38407,38359,38353 ,730,730,730 ,0,0,0}, {38363,38359,38364 ,730,730,730 ,0,0,0}, - {38359,38408,38397 ,730,730,730 ,0,0,0}, {38359,38407,38408 ,730,730,730 ,0,0,0}, - {38409,38167,38398 ,730,730,730 ,0,0,0}, {38359,38398,38167 ,730,730,730 ,0,0,0}, - {38410,38167,38411 ,730,730,730 ,0,0,0}, {38167,38409,38411 ,730,730,730 ,0,0,0}, - {38168,38167,38412 ,730,730,730 ,0,0,0}, {38167,38410,38412 ,730,730,730 ,0,0,0}, - {38166,38413,38167 ,730,730,730 ,0,0,0}, {38091,38090,38413 ,730,730,730 ,0,0,0}, - {38167,38413,38090 ,730,730,730 ,0,0,0}, {38090,38092,38155 ,730,730,730 ,0,0,0}, - {32893,38155,38092 ,730,730,730 ,0,0,0}, {33209,35759,35762 ,730,730,730 ,0,0,0}, - {35186,38414,35185 ,730,730,730 ,0,0,0}, {35584,35752,35755 ,730,730,730 ,0,0,0}, - {35585,35755,35757 ,730,730,730 ,0,0,0}, {35752,35581,35753 ,730,730,730 ,0,0,0}, - {35584,35581,35752 ,730,730,730 ,0,0,0}, {35753,35579,37948 ,730,730,730 ,0,0,0}, - {37948,35560,35559 ,730,730,730 ,0,0,0}, {35578,35560,37948 ,730,730,730 ,0,0,0}, - {33192,35197,38029 ,730,730,730 ,0,0,0}, {35566,37948,35567 ,730,730,730 ,0,0,0}, - {35559,35563,37948 ,730,730,730 ,0,0,0}, {37948,35569,38052 ,730,730,730 ,0,0,0}, - {35569,37948,35566 ,730,730,730 ,0,0,0}, {33192,38029,38053 ,730,730,730 ,0,0,0}, - {38052,35571,35573 ,730,730,730 ,0,0,0}, {35569,35571,38052 ,730,730,730 ,0,0,0}, - {33192,38053,35573 ,730,730,730 ,0,0,0}, {33192,38031,35197 ,730,730,730 ,0,0,0}, - {38032,35192,35195 ,730,730,730 ,0,0,0}, {37931,35191,38033 ,730,730,730 ,0,0,0}, - {35186,35189,37932 ,730,730,730 ,0,0,0}, {38415,38414,35186 ,730,730,730 ,0,0,0}, - {38415,35186,37932 ,730,730,730 ,0,0,0}, {38416,35185,38414 ,730,730,730 ,0,0,0}, - {35135,38416,38049 ,730,730,730 ,0,0,0}, {38416,35135,35185 ,730,730,730 ,0,0,0}, - {38049,38417,35133 ,730,730,730 ,0,0,0}, {38341,38048,35134 ,730,730,730 ,0,0,0}, - {38417,38341,35133 ,730,730,730 ,0,0,0}, {38047,38046,35140 ,730,730,730 ,0,0,0}, - {35134,38048,35138 ,730,730,730 ,0,0,0}, {35762,38045,33209 ,730,730,730 ,0,0,0}, - {38046,38047,38045 ,730,730,730 ,0,0,0}, {35557,38418,37944 ,730,730,730 ,0,0,0}, - {35385,35386,38128 ,730,730,730 ,0,0,0}, {38418,35555,35554 ,730,730,730 ,0,0,0}, - {35557,35555,38418 ,730,730,730 ,0,0,0}, {35551,38132,35554 ,730,730,730 ,0,0,0}, - {38418,35554,38132 ,730,730,730 ,0,0,0}, {35548,38132,35549 ,730,730,730 ,0,0,0}, - {38132,35551,35549 ,730,730,730 ,0,0,0}, {38132,35548,35530 ,730,730,730 ,0,0,0}, - {38132,35533,35537 ,730,730,730 ,0,0,0}, {35529,35533,38132 ,730,730,730 ,0,0,0}, - {35536,37940,35537 ,730,730,730 ,0,0,0}, {38132,35537,37940 ,730,730,730 ,0,0,0}, - {35543,37940,35541 ,730,730,730 ,0,0,0}, {37940,35536,35539 ,730,730,730 ,0,0,0}, - {35543,33824,35392 ,730,730,730 ,0,0,0}, {38117,35389,35391 ,730,730,730 ,0,0,0}, - {38127,35386,35389 ,730,730,730 ,0,0,0}, {38131,35385,38128 ,730,730,730 ,0,0,0}, - {35333,35335,38130 ,730,730,730 ,0,0,0}, {38129,35335,38131 ,730,730,730 ,0,0,0}, - {35333,38124,35334 ,730,730,730 ,0,0,0}, {38124,35333,38130 ,730,730,730 ,0,0,0}, - {38123,35338,35334 ,730,730,730 ,0,0,0}, {38126,35340,35338 ,730,730,730 ,0,0,0}, - {38123,38125,35338 ,730,730,730 ,0,0,0}, {38122,38119,35342 ,730,730,730 ,0,0,0}, - {38126,38122,35340 ,730,730,730 ,0,0,0}, {35347,38120,35348 ,730,730,730 ,0,0,0}, - {35342,38119,35347 ,730,730,730 ,0,0,0}, {35346,38121,33841 ,730,730,730 ,0,0,0}, - {35348,38120,38121 ,730,730,730 ,0,0,0}, {38419,37639,35242 ,730,730,730 ,0,0,0}, - {38420,35590,35589 ,730,730,730 ,0,0,0}, {35233,35235,38174 ,730,730,730 ,0,0,0}, - {35286,38075,35285 ,730,730,730 ,0,0,0}, {35289,38421,38422 ,730,730,730 ,0,0,0}, - {35295,38173,37664 ,730,730,730 ,0,0,0}, {38423,38424,35304 ,730,730,730 ,0,0,0}, - {38087,35454,38400 ,730,730,730 ,0,0,0}, {35456,35452,38399 ,730,730,730 ,0,0,0}, - {35451,38160,38356 ,730,730,730 ,0,0,0}, {35448,38088,35446 ,730,730,730 ,0,0,0}, - {38161,38089,35447 ,730,730,730 ,0,0,0}, {35503,35504,38146 ,730,730,730 ,0,0,0}, - {35442,35440,38085 ,730,730,730 ,0,0,0}, {38085,38161,35442 ,730,730,730 ,0,0,0}, - {35438,38084,35440 ,730,730,730 ,0,0,0}, {38425,35438,35434 ,730,730,730 ,0,0,0}, - {35438,38425,38084 ,730,730,730 ,0,0,0}, {38156,35433,38426 ,730,730,730 ,0,0,0}, - {38425,35434,38156 ,730,730,730 ,0,0,0}, {35501,38147,37783 ,730,730,730 ,0,0,0}, - {35435,38153,38426 ,730,730,730 ,0,0,0}, {38426,35433,35435 ,730,730,730 ,0,0,0}, - {38154,38153,35485 ,730,730,730 ,0,0,0}, {35497,37782,38145 ,730,730,730 ,0,0,0}, - {35486,38154,35485 ,730,730,730 ,0,0,0}, {38151,35489,35491 ,730,730,730 ,0,0,0}, - {35489,38151,38150 ,730,730,730 ,0,0,0}, {35491,35492,38152 ,730,730,730 ,0,0,0}, - {35497,38145,35495 ,730,730,730 ,0,0,0}, {38152,35492,38083 ,730,730,730 ,0,0,0}, - {37783,37782,35498 ,730,730,730 ,0,0,0}, {35503,38147,35501 ,730,730,730 ,0,0,0}, - {38142,38146,35504 ,730,730,730 ,0,0,0}, {35504,38354,37928 ,730,730,730 ,0,0,0}, - {38354,35429,38355 ,730,730,730 ,0,0,0}, {35429,38354,35430 ,730,730,730 ,0,0,0}, - {35527,37804,37801 ,730,730,730 ,0,0,0}, {35429,35508,38355 ,730,730,730 ,0,0,0}, - {35512,38427,35509 ,730,730,730 ,0,0,0}, {38355,35509,38427 ,730,730,730 ,0,0,0}, - {35512,35514,38428 ,730,730,730 ,0,0,0}, {38428,38427,35512 ,730,730,730 ,0,0,0}, - {35526,37801,35524 ,730,730,730 ,0,0,0}, {38428,35515,38429 ,730,730,730 ,0,0,0}, - {35515,38428,35514 ,730,730,730 ,0,0,0}, {37801,38429,35518 ,730,730,730 ,0,0,0}, - {35515,35518,38429 ,730,730,730 ,0,0,0}, {35520,35521,37801 ,730,730,730 ,0,0,0}, - {35521,35524,37801 ,730,730,730 ,0,0,0}, {38351,37800,37801 ,730,730,730 ,0,0,0}, - {37801,38350,38351 ,730,730,730 ,0,0,0}, {38359,38363,38353 ,730,730,730 ,0,0,0}, - {37800,38345,38363 ,730,730,730 ,0,0,0}, {38345,38430,38363 ,730,730,730 ,0,0,0}, - {38430,38431,38363 ,730,730,730 ,0,0,0}, {35681,37800,38363 ,730,730,730 ,0,0,0}, - {38432,38353,38363 ,730,730,730 ,0,0,0}, {38396,38363,38431 ,730,730,730 ,0,0,0}, - {38363,38395,38402 ,730,730,730 ,0,0,0}, {35701,35682,38363 ,730,730,730 ,0,0,0}, - {38406,38432,38363 ,730,730,730 ,0,0,0}, {38363,35702,35701 ,730,730,730 ,0,0,0}, - {38363,38433,38404 ,730,730,730 ,0,0,0}, {35704,38363,35707 ,730,730,730 ,0,0,0}, - {38363,35710,35708 ,730,730,730 ,0,0,0}, {38363,35712,35710 ,730,730,730 ,0,0,0}, - {38432,38352,38353 ,730,730,730 ,0,0,0}, {38143,35603,38401 ,730,730,730 ,0,0,0}, - {38144,38165,35599 ,730,730,730 ,0,0,0}, {35599,35601,38144 ,730,730,730 ,0,0,0}, - {38093,35596,38165 ,730,730,730 ,0,0,0}, {35593,35597,38093 ,730,730,730 ,0,0,0}, - {38093,35597,35596 ,730,730,730 ,0,0,0}, {35593,38094,35589 ,730,730,730 ,0,0,0}, - {35590,38420,38171 ,730,730,730 ,0,0,0}, {35589,38094,38420 ,730,730,730 ,0,0,0}, - {37781,35609,38171 ,730,730,730 ,0,0,0}, {35608,35590,38171 ,730,730,730 ,0,0,0}, - {37667,35611,37781 ,730,730,730 ,0,0,0}, {37666,38382,35615 ,730,730,730 ,0,0,0}, - {37772,32893,37776 ,730,730,730 ,0,0,0}, {38382,37776,35617 ,730,730,730 ,0,0,0}, - {37772,37777,37773 ,730,730,730 ,0,0,0}, {38077,38079,37775 ,730,730,730 ,0,0,0}, - {38079,37774,37775 ,730,730,730 ,0,0,0}, {38079,38078,37494 ,730,730,730 ,0,0,0}, - {38434,37495,38435 ,730,730,730 ,0,0,0}, {38436,38437,37632 ,730,730,730 ,0,0,0}, - {37632,38437,37630 ,730,730,730 ,0,0,0}, {38159,38438,38157 ,730,730,730 ,0,0,0}, - {38438,38439,38440 ,730,730,730 ,0,0,0}, {38164,38163,38441 ,730,730,730 ,0,0,0}, - {38442,38443,38441 ,730,730,730 ,0,0,0}, {35326,35478,35324 ,730,730,730 ,0,0,0}, - {38444,35482,35327 ,730,730,730 ,0,0,0}, {35320,35465,35464 ,730,730,730 ,0,0,0}, - {35314,35315,35473 ,730,730,730 ,0,0,0}, {35312,35471,35466 ,730,730,730 ,0,0,0}, - {35314,35471,35312 ,730,730,730 ,0,0,0}, {38445,38446,38366 ,730,730,730 ,0,0,0}, - {35631,35633,38096 ,730,730,730 ,0,0,0}, {37625,35264,35275 ,730,730,730 ,0,0,0}, - {37626,35265,35264 ,730,730,730 ,0,0,0}, {35266,35270,38037 ,730,730,730 ,0,0,0}, - {37625,35275,35273 ,730,730,730 ,0,0,0}, {35271,35266,37629 ,730,730,730 ,0,0,0}, - {37620,35260,38103 ,730,730,730 ,0,0,0}, {37621,35254,38102 ,730,730,730 ,0,0,0}, - {35256,35252,37749 ,730,730,730 ,0,0,0}, {35251,38172,37748 ,730,730,730 ,0,0,0}, - {35248,38149,35246 ,730,730,730 ,0,0,0}, {37639,38148,35247 ,730,730,730 ,0,0,0}, - {35240,38447,38419 ,730,730,730 ,0,0,0}, {38419,35242,35240 ,730,730,730 ,0,0,0}, - {35460,35458,35230 ,730,730,730 ,0,0,0}, {38447,35238,37665 ,730,730,730 ,0,0,0}, - {35238,38447,35240 ,730,730,730 ,0,0,0}, {35234,38175,37665 ,730,730,730 ,0,0,0}, - {35230,38086,38423 ,730,730,730 ,0,0,0}, {35234,35233,38175 ,730,730,730 ,0,0,0}, - {38174,35235,38076 ,730,730,730 ,0,0,0}, {38423,35304,35230 ,730,730,730 ,0,0,0}, - {38076,35235,35285 ,730,730,730 ,0,0,0}, {38422,38075,35286 ,730,730,730 ,0,0,0}, - {35303,38424,38169 ,730,730,730 ,0,0,0}, {35291,38421,35289 ,730,730,730 ,0,0,0}, - {35289,38422,35286 ,730,730,730 ,0,0,0}, {38169,38170,35301 ,730,730,730 ,0,0,0}, - {37663,35291,35292 ,730,730,730 ,0,0,0}, {35291,37663,38421 ,730,730,730 ,0,0,0}, - {35292,35295,37664 ,730,730,730 ,0,0,0}, {38176,38173,35297 ,730,730,730 ,0,0,0}, - {38170,38176,35298 ,730,730,730 ,0,0,0}, {38424,35303,35304 ,730,730,730 ,0,0,0}, - {38086,35230,35458 ,730,730,730 ,0,0,0}, {35460,35230,35229 ,730,730,730 ,0,0,0}, - {35461,35308,35470 ,730,730,730 ,0,0,0}, {35309,35312,35466 ,730,730,730 ,0,0,0}, - {35314,35473,35471 ,730,730,730 ,0,0,0}, {38378,38448,38095 ,730,730,730 ,0,0,0}, - {35475,35318,35464 ,730,730,730 ,0,0,0}, {35318,35475,35315 ,730,730,730 ,0,0,0}, - {35320,35321,35465 ,730,730,730 ,0,0,0}, {35318,35320,35464 ,730,730,730 ,0,0,0}, - {35324,35477,35321 ,730,730,730 ,0,0,0}, {35465,35321,35477 ,730,730,730 ,0,0,0}, - {38448,38378,38384 ,730,730,730 ,0,0,0}, {35326,35327,35482 ,730,730,730 ,0,0,0}, - {35482,35478,35326 ,730,730,730 ,0,0,0}, {38162,38444,35327 ,730,730,730 ,0,0,0}, - {38383,38449,38384 ,730,730,730 ,0,0,0}, {38162,38164,38444 ,730,730,730 ,0,0,0}, - {38442,38440,38443 ,730,730,730 ,0,0,0}, {38163,38442,38441 ,730,730,730 ,0,0,0}, - {38449,38450,38451 ,730,730,730 ,0,0,0}, {38439,38438,38159 ,730,730,730 ,0,0,0}, - {38443,38440,38439 ,730,730,730 ,0,0,0}, {37631,38158,38157 ,730,730,730 ,0,0,0}, - {38158,37631,37630 ,730,730,730 ,0,0,0}, {38435,38436,38434 ,730,730,730 ,0,0,0}, - {38435,38437,38436 ,730,730,730 ,0,0,0}, {37494,37496,37674 ,730,730,730 ,0,0,0}, - {37496,37495,38434 ,730,730,730 ,0,0,0}, {38452,38450,37674 ,730,730,730 ,0,0,0}, - {37674,37496,38452 ,730,730,730 ,0,0,0}, {38451,38450,38452 ,730,730,730 ,0,0,0}, - {38383,38450,38449 ,730,730,730 ,0,0,0}, {38095,33508,38378 ,730,730,730 ,0,0,0}, - {37624,35631,38096 ,730,730,730 ,0,0,0}, {37623,37627,35626 ,730,730,730 ,0,0,0}, - {35626,35629,37623 ,730,730,730 ,0,0,0}, {37628,35623,35627 ,730,730,730 ,0,0,0}, - {37627,35627,35626 ,730,730,730 ,0,0,0}, {38101,35619,37628 ,730,730,730 ,0,0,0}, - {35623,37628,35619 ,730,730,730 ,0,0,0}, {35620,38101,38100 ,730,730,730 ,0,0,0}, - {35641,38365,35644 ,730,730,730 ,0,0,0}, {35638,35620,38100 ,730,730,730 ,0,0,0}, - {38097,38098,38453 ,730,730,730 ,0,0,0}, {35647,38373,38374 ,730,730,730 ,0,0,0}, - {37648,38453,35666 ,730,730,730 ,0,0,0}, {37648,38097,38453 ,730,730,730 ,0,0,0}, - {35666,38454,37622 ,730,730,730 ,0,0,0}, {38453,38454,35666 ,730,730,730 ,0,0,0}, - {37622,38455,35663 ,730,730,730 ,0,0,0}, {38369,35661,38455 ,730,730,730 ,0,0,0}, - {35663,38455,35661 ,730,730,730 ,0,0,0}, {35659,38369,38456 ,730,730,730 ,0,0,0}, - {38456,38370,35656 ,730,730,730 ,0,0,0}, {35656,35659,38456 ,730,730,730 ,0,0,0}, - {35657,35656,38371 ,730,730,730 ,0,0,0}, {35653,38368,35649 ,730,730,730 ,0,0,0}, - {38367,35657,38371 ,730,730,730 ,0,0,0}, {38457,38445,35649 ,730,730,730 ,0,0,0}, - {38457,35649,38368 ,730,730,730 ,0,0,0}, {38366,35650,38445 ,730,730,730 ,0,0,0}, - {38445,35650,35649 ,730,730,730 ,0,0,0}, {38446,38458,38366 ,730,730,730 ,0,0,0}, - {37626,38366,38459 ,730,730,730 ,0,0,0}, {38458,38459,38366 ,730,730,730 ,0,0,0}, - {38460,37626,38461 ,730,730,730 ,0,0,0}, {37626,38459,38461 ,730,730,730 ,0,0,0}, - {35282,37626,38462 ,730,730,730 ,0,0,0}, {37626,38460,38462 ,730,730,730 ,0,0,0}, - {37615,38463,38464 ,730,730,730 ,0,0,0}, {38465,37615,38466 ,730,730,730 ,0,0,0}, - {38467,37599,38468 ,730,730,730 ,0,0,0}, {37599,35116,38468 ,730,730,730 ,0,0,0}, - {38463,37599,38469 ,730,730,730 ,0,0,0}, {37599,38467,38469 ,730,730,730 ,0,0,0}, - {37615,37599,38463 ,730,730,730 ,0,0,0}, {38470,37615,38471 ,730,730,730 ,0,0,0}, - {37615,38464,38471 ,730,730,730 ,0,0,0}, {37615,38470,38466 ,730,730,730 ,0,0,0}, - {38465,35128,37615 ,730,730,730 ,0,0,0}, {37615,35128,37595 ,730,730,730 ,0,0,0}, - {35123,37595,35125 ,730,730,730 ,0,0,0}, {37595,35128,35125 ,730,730,730 ,0,0,0}, - {35113,37598,37595 ,730,730,730 ,0,0,0}, {35107,37595,35120 ,730,730,730 ,0,0,0}, - {37595,35122,35120 ,730,730,730 ,0,0,0}, {37595,35107,35113 ,730,730,730 ,0,0,0}, - {35114,37598,35110 ,730,730,730 ,0,0,0}, {37598,35113,35110 ,730,730,730 ,0,0,0}, - {35116,37598,35117 ,730,730,730 ,0,0,0}, {37598,35114,35117 ,730,730,730 ,0,0,0}, - {38028,38472,37956 ,730,730,730 ,0,0,0}, {38026,35094,38028 ,730,730,730 ,0,0,0}, - {37956,38473,38474 ,730,730,730 ,0,0,0}, {38472,38473,37956 ,730,730,730 ,0,0,0}, - {37957,37956,38475 ,730,730,730 ,0,0,0}, {38474,38475,37956 ,730,730,730 ,0,0,0}, - {38476,37957,38477 ,730,730,730 ,0,0,0}, {37957,38475,38477 ,730,730,730 ,0,0,0}, - {38478,37957,38479 ,730,730,730 ,0,0,0}, {37957,38476,38479 ,730,730,730 ,0,0,0}, - {38024,37957,38478 ,730,730,730 ,0,0,0}, {38024,38478,35106 ,730,730,730 ,0,0,0}, - {35098,38024,35100 ,730,730,730 ,0,0,0}, {38024,35106,35103 ,730,730,730 ,0,0,0}, - {38024,35101,35100 ,730,730,730 ,0,0,0}, {38026,38024,35085 ,730,730,730 ,0,0,0}, - {35098,35085,38024 ,730,730,730 ,0,0,0}, {35088,38026,35091 ,730,730,730 ,0,0,0}, - {38026,35085,35091 ,730,730,730 ,0,0,0}, {35095,38026,35092 ,730,730,730 ,0,0,0}, - {38026,35088,35092 ,730,730,730 ,0,0,0}, {35094,38026,35095 ,730,730,730 ,0,0,0}, - {38480,38481,38482 ,730,730,730 ,0,0,0}, {38024,38023,38482 ,730,730,730 ,0,0,0}, - {38481,38019,38018 ,730,730,730 ,0,0,0}, {38021,38483,38027 ,730,730,730 ,0,0,0}, - {38022,38483,38021 ,730,730,730 ,0,0,0}, {38021,38027,38026 ,730,730,730 ,0,0,0}, - {38026,38025,38024 ,730,730,730 ,0,0,0}, {38023,38480,38482 ,730,730,730 ,0,0,0}, - {38481,38018,38482 ,730,730,730 ,0,0,0}, {35084,38016,38019 ,730,730,730 ,0,0,0}, - {35081,38016,35084 ,730,730,730 ,0,0,0}, {35079,38015,35081 ,730,730,730 ,0,0,0}, - {38484,38485,38486 ,730,730,730 ,0,0,0}, {38487,38015,35078 ,730,730,730 ,0,0,0}, - {35066,34300,35069 ,730,730,730 ,0,0,0}, {34919,38488,38489 ,730,730,730 ,0,0,0}, - {34304,34303,34871 ,730,730,730 ,0,0,0}, {38490,34300,35066 ,730,730,730 ,0,0,0}, - {35070,38020,35066 ,730,730,730 ,0,0,0}, {38490,35066,38020 ,730,730,730 ,0,0,0}, - {38020,35073,37960 ,730,730,730 ,0,0,0}, {35072,37960,35073 ,730,730,730 ,0,0,0}, - {38491,35057,35056 ,730,730,730 ,0,0,0}, {37917,37921,37918 ,730,730,730 ,0,0,0}, - {38491,38492,35057 ,730,730,730 ,0,0,0}, {37921,37924,37922 ,730,730,730 ,0,0,0}, - {37924,37906,37905 ,730,730,730 ,0,0,0}, {38493,38494,37923 ,730,730,730 ,0,0,0}, - {38493,37923,37904 ,730,730,730 ,0,0,0}, {38495,38494,38496 ,730,730,730 ,0,0,0}, - {38494,38495,37923 ,730,730,730 ,0,0,0}, {37919,38496,37920 ,730,730,730 ,0,0,0}, - {38495,38496,37919 ,730,730,730 ,0,0,0}, {37919,35062,38492 ,730,730,730 ,0,0,0}, - {35059,35057,38492 ,730,730,730 ,0,0,0}, {35062,35059,38492 ,730,730,730 ,0,0,0}, - {35056,37916,38491 ,730,730,730 ,0,0,0}, {37916,35054,35041 ,730,730,730 ,0,0,0}, - {35056,35054,37916 ,730,730,730 ,0,0,0}, {35041,35047,37915 ,730,730,730 ,0,0,0}, - {38232,37915,35044 ,730,730,730 ,0,0,0}, {35047,35044,37915 ,730,730,730 ,0,0,0}, - {38232,35048,38233 ,730,730,730 ,0,0,0}, {35051,37914,38235 ,730,730,730 ,0,0,0}, - {35050,37914,35051 ,730,730,730 ,0,0,0}, {38497,38498,38499 ,730,730,730 ,0,0,0}, - {38500,38498,38501 ,730,730,730 ,0,0,0}, {38498,35028,38501 ,730,730,730 ,0,0,0}, - {38498,38500,38499 ,730,730,730 ,0,0,0}, {35037,37750,37767 ,730,730,730 ,0,0,0}, - {37767,38498,38502 ,730,730,730 ,0,0,0}, {38497,38502,38498 ,730,730,730 ,0,0,0}, - {38503,37767,38504 ,730,730,730 ,0,0,0}, {37767,38502,38504 ,730,730,730 ,0,0,0}, - {38505,37767,38506 ,730,730,730 ,0,0,0}, {37767,38503,38506 ,730,730,730 ,0,0,0}, - {37767,35040,35037 ,730,730,730 ,0,0,0}, {37767,38505,35040 ,730,730,730 ,0,0,0}, - {35035,35034,37750 ,730,730,730 ,0,0,0}, {37750,35032,35019 ,730,730,730 ,0,0,0}, - {35034,35032,37750 ,730,730,730 ,0,0,0}, {35025,37681,35019 ,730,730,730 ,0,0,0}, - {37750,35019,37681 ,730,730,730 ,0,0,0}, {35026,37681,35022 ,730,730,730 ,0,0,0}, - {37681,35025,35022 ,730,730,730 ,0,0,0}, {35029,35028,38498 ,730,730,730 ,0,0,0}, - {38498,37681,35029 ,730,730,730 ,0,0,0}, {37681,35026,35029 ,730,730,730 ,0,0,0}, - {37764,34356,37765 ,730,730,730 ,0,0,0}, {37758,35006,37755 ,730,730,730 ,0,0,0}, - {38507,37769,35018 ,730,730,730 ,0,0,0}, {37765,34356,38508 ,730,730,730 ,0,0,0}, - {38509,37756,37757 ,730,730,730 ,0,0,0}, {34694,38510,37759 ,730,730,730 ,0,0,0}, - {34676,34346,38510 ,730,730,730 ,0,0,0}, {38511,34345,34356 ,730,730,730 ,0,0,0}, - {37765,37768,37766 ,730,730,730 ,0,0,0}, {37769,38507,37766 ,730,730,730 ,0,0,0}, - {35018,37770,38507 ,730,730,730 ,0,0,0}, {35013,37770,35015 ,730,730,730 ,0,0,0}, - {35003,38498,34997 ,730,730,730 ,0,0,0}, {35013,37752,37770 ,730,730,730 ,0,0,0}, - {37752,35010,37767 ,730,730,730 ,0,0,0}, {35012,35010,37752 ,730,730,730 ,0,0,0}, - {37767,34997,38498 ,730,730,730 ,0,0,0}, {35000,35004,37763 ,730,730,730 ,0,0,0}, - {38498,35003,37763 ,730,730,730 ,0,0,0}, {35007,37760,35004 ,730,730,730 ,0,0,0}, - {37763,35004,37760 ,730,730,730 ,0,0,0}, {37758,35007,35006 ,730,730,730 ,0,0,0}, - {37919,38512,37815 ,730,730,730 ,0,0,0}, {37919,38492,34984 ,730,730,730 ,0,0,0}, - {38513,37815,38512 ,730,730,730 ,0,0,0}, {38514,37919,38515 ,730,730,730 ,0,0,0}, - {37919,37925,38515 ,730,730,730 ,0,0,0}, {38516,37919,38517 ,730,730,730 ,0,0,0}, - {37919,38514,38517 ,730,730,730 ,0,0,0}, {37919,38516,38512 ,730,730,730 ,0,0,0}, - {37815,38518,38519 ,730,730,730 ,0,0,0}, {38513,38518,37815 ,730,730,730 ,0,0,0}, - {38492,34988,34975 ,730,730,730 ,0,0,0}, {38519,34996,37815 ,730,730,730 ,0,0,0}, - {37815,34996,37817 ,730,730,730 ,0,0,0}, {34991,37817,34993 ,730,730,730 ,0,0,0}, - {37817,34996,34993 ,730,730,730 ,0,0,0}, {34988,37817,34990 ,730,730,730 ,0,0,0}, - {37817,34991,34990 ,730,730,730 ,0,0,0}, {38492,37817,34988 ,730,730,730 ,0,0,0}, - {34978,38492,34981 ,730,730,730 ,0,0,0}, {38492,34975,34981 ,730,730,730 ,0,0,0}, - {34985,38492,34982 ,730,730,730 ,0,0,0}, {38492,34978,34982 ,730,730,730 ,0,0,0}, - {34984,38492,34985 ,730,730,730 ,0,0,0}, {34969,38320,34971 ,730,730,730 ,0,0,0}, - {37613,37614,37615 ,730,730,730 ,0,0,0}, {37608,37605,37614 ,730,730,730 ,0,0,0}, - {37601,37605,37609 ,730,730,730 ,0,0,0}, {38520,37611,37600 ,730,730,730 ,0,0,0}, - {37600,37602,38520 ,730,730,730 ,0,0,0}, {37612,37611,38520 ,730,730,730 ,0,0,0}, - {34320,38521,38522 ,730,730,730 ,0,0,0}, {37573,37610,37612 ,730,730,730 ,0,0,0}, - {38523,34565,38524 ,730,730,730 ,0,0,0}, {1263,38521,34320 ,730,730,730 ,0,0,0}, - {34317,34328,38525 ,730,730,730 ,0,0,0}, {34968,37619,37617 ,730,730,730 ,0,0,0}, - {34969,37617,38320 ,730,730,730 ,0,0,0}, {37619,34966,34953 ,730,730,730 ,0,0,0}, - {34968,34966,37619 ,730,730,730 ,0,0,0}, {34953,34959,37618 ,730,730,730 ,0,0,0}, - {37607,37618,34956 ,730,730,730 ,0,0,0}, {34959,34956,37618 ,730,730,730 ,0,0,0}, - {37607,34960,37595 ,730,730,730 ,0,0,0}, {34962,37595,34963 ,730,730,730 ,0,0,0}, - {37595,34960,34963 ,730,730,730 ,0,0,0}, {38526,38527,35971 ,730,730,730 ,0,0,0}, - {37970,36139,36141 ,730,730,730 ,0,0,0}, {36141,38206,37970 ,730,730,730 ,0,0,0}, - {37971,38528,36136 ,730,730,730 ,0,0,0}, {36135,36136,38528 ,730,730,730 ,0,0,0}, - {36129,36130,38208 ,730,730,730 ,0,0,0}, {36127,34921,34925 ,730,730,730 ,0,0,0}, - {36124,34929,36123 ,730,730,730 ,0,0,0}, {36121,34929,34928 ,730,730,730 ,0,0,0}, - {36118,34931,36117 ,730,730,730 ,0,0,0}, {34933,34935,36115 ,730,730,730 ,0,0,0}, - {34038,36112,34938 ,730,730,730 ,0,0,0}, {34038,34938,34040 ,730,730,730 ,0,0,0}, - {38529,38530,34043 ,730,730,730 ,0,0,0}, {38212,38529,34045 ,730,730,730 ,0,0,0}, - {36109,34037,36143 ,730,730,730 ,0,0,0}, {34049,36149,36148 ,730,730,730 ,0,0,0}, - {34048,36148,36145 ,730,730,730 ,0,0,0}, {34057,34898,34901 ,730,730,730 ,0,0,0}, - {34057,34901,38531 ,730,730,730 ,0,0,0}, {38187,36167,38184 ,730,730,730 ,0,0,0}, - {35977,35979,37969 ,730,730,730 ,0,0,0}, {35979,37974,34063 ,730,730,730 ,0,0,0}, - {35973,35974,37968 ,730,730,730 ,0,0,0}, {35973,37968,38532 ,730,730,730 ,0,0,0}, - {38527,35968,35971 ,730,730,730 ,0,0,0}, {34135,38209,37972 ,730,730,730 ,0,0,0}, - {38527,38209,35968 ,730,730,730 ,0,0,0}, {34136,38533,34138 ,730,730,730 ,0,0,0}, - {34143,34138,34950 ,730,730,730 ,0,0,0}, {34952,34138,38533 ,730,730,730 ,0,0,0}, - {38534,38182,38183 ,730,730,730 ,0,0,0}, {38010,38012,38535 ,730,730,730 ,0,0,0}, - {38536,34913,34911 ,730,730,730 ,0,0,0}, {37537,34913,38536 ,730,730,730 ,0,0,0}, - {37979,38537,37980 ,730,730,730 ,0,0,0}, {34054,34892,34891 ,730,730,730 ,0,0,0}, - {34899,34898,34057 ,730,730,730 ,0,0,0}, {34059,34899,34057 ,730,730,730 ,0,0,0}, - {38211,34051,34062 ,730,730,730 ,0,0,0}, {34903,38531,34901 ,730,730,730 ,0,0,0}, - {4039,36151,36149 ,730,730,730 ,0,0,0}, {38007,36154,4039 ,730,730,730 ,0,0,0}, - {36155,36154,38007 ,730,730,730 ,0,0,0}, {38185,36161,36160 ,730,730,730 ,0,0,0}, - {36166,36163,3897 ,730,730,730 ,0,0,0}, {36167,36166,38184 ,730,730,730 ,0,0,0}, - {36169,38187,38538 ,730,730,730 ,0,0,0}, {38538,38189,36171 ,730,730,730 ,0,0,0}, - {36171,36169,38538 ,730,730,730 ,0,0,0}, {38486,38188,38190 ,730,730,730 ,0,0,0}, - {38189,38188,36171 ,730,730,730 ,0,0,0}, {38014,38539,34292 ,730,730,730 ,0,0,0}, - {38486,38485,38188 ,730,730,730 ,0,0,0}, {38540,34297,38539 ,730,730,730 ,0,0,0}, - {34297,38541,34295 ,730,730,730 ,0,0,0}, {38485,38484,34290 ,730,730,730 ,0,0,0}, - {34309,34311,38542 ,730,730,730 ,0,0,0}, {34866,38543,38191 ,730,730,730 ,0,0,0}, - {38544,38545,38546 ,730,730,730 ,0,0,0}, {34303,34314,38009 ,730,730,730 ,0,0,0}, - {38543,34866,34869 ,730,730,730 ,0,0,0}, {38008,34314,34315 ,730,730,730 ,0,0,0}, - {38547,38548,38549 ,730,730,730 ,0,0,0}, {38550,34217,38551 ,730,730,730 ,0,0,0}, - {34211,34880,38552 ,730,730,730 ,0,0,0}, {37556,34859,34863 ,730,730,730 ,0,0,0}, - {38553,38554,38555 ,730,730,730 ,0,0,0}, {34222,37990,38556 ,730,730,730 ,0,0,0}, - {35960,35957,34231 ,730,730,730 ,0,0,0}, {37993,38557,37991 ,730,730,730 ,0,0,0}, - {34869,38558,38543 ,730,730,730 ,0,0,0}, {34303,34869,34871 ,730,730,730 ,0,0,0}, - {3883,38489,38559 ,730,730,730 ,0,0,0}, {34306,34873,34876 ,730,730,730 ,0,0,0}, - {34309,38542,38544 ,730,730,730 ,0,0,0}, {34916,38005,34917 ,730,730,730 ,0,0,0}, - {34303,38560,38558 ,730,730,730 ,0,0,0}, {38544,38546,34309 ,730,730,730 ,0,0,0}, - {38561,37475,38546 ,730,730,730 ,0,0,0}, {3883,34919,38489 ,730,730,730 ,0,0,0}, - {38562,38559,37996 ,730,730,730 ,0,0,0}, {35063,34301,38013 ,730,730,730 ,0,0,0}, - {37994,38563,35076 ,730,730,730 ,0,0,0}, {38564,38565,37997 ,730,730,730 ,0,0,0}, - {38487,38563,38566 ,730,730,730 ,0,0,0}, {38547,38564,38548 ,730,730,730 ,0,0,0}, - {38564,38547,38565 ,730,730,730 ,0,0,0}, {38549,37999,38547 ,730,730,730 ,0,0,0}, - {38000,38194,38001 ,730,730,730 ,0,0,0}, {38549,38000,37999 ,730,730,730 ,0,0,0}, - {38193,38192,37485 ,730,730,730 ,0,0,0}, {38001,38194,38193 ,730,730,730 ,0,0,0}, - {34890,37485,38192 ,730,730,730 ,0,0,0}, {34857,34855,38203 ,730,730,730 ,0,0,0}, - {38203,37982,34857 ,730,730,730 ,0,0,0}, {34849,34848,37553 ,730,730,730 ,0,0,0}, - {34849,37553,38204 ,730,730,730 ,0,0,0}, {34848,34830,37963 ,730,730,730 ,0,0,0}, - {34833,34124,34829 ,730,730,730 ,0,0,0}, {34830,34829,34122 ,730,730,730 ,0,0,0}, - {34833,34837,34129 ,730,730,730 ,0,0,0}, {37966,38207,34122 ,730,730,730 ,0,0,0}, - {34129,34836,34127 ,730,730,730 ,0,0,0}, {34127,34839,38205 ,730,730,730 ,0,0,0}, - {34944,34942,38181 ,730,730,730 ,0,0,0}, {34133,37970,38206 ,730,730,730 ,0,0,0}, - {38567,38568,38569 ,730,730,730 ,0,0,0}, {35961,34146,34147 ,730,730,730 ,0,0,0}, - {37535,35944,35942 ,730,730,730 ,0,0,0}, {35945,37550,35951 ,730,730,730 ,0,0,0}, - {35948,35953,38179 ,730,730,730 ,0,0,0}, {35951,37551,38179 ,730,730,730 ,0,0,0}, - {37987,37990,34220 ,730,730,730 ,0,0,0}, {37988,35948,38179 ,730,730,730 ,0,0,0}, - {34222,38570,34227 ,730,730,730 ,0,0,0}, {38571,34225,37989 ,730,730,730 ,0,0,0}, - {38555,38554,34225 ,730,730,730 ,0,0,0}, {38555,34225,38571 ,730,730,730 ,0,0,0}, - {38553,37986,37985 ,730,730,730 ,0,0,0}, {38572,38199,38198 ,730,730,730 ,0,0,0}, - {38572,34217,38199 ,730,730,730 ,0,0,0}, {37557,34860,34859 ,730,730,730 ,0,0,0}, - {38573,38200,38574 ,730,730,730 ,0,0,0}, {38198,38197,38573 ,730,730,730 ,0,0,0}, - {37984,38575,38201 ,730,730,730 ,0,0,0}, {35927,38576,38577 ,730,730,730 ,0,0,0}, - {38578,38579,37865 ,730,730,730 ,0,0,0}, {37820,37822,38580 ,730,730,730 ,0,0,0}, - {37820,38580,34441 ,730,730,730 ,0,0,0}, {37866,37822,37821 ,730,730,730 ,0,0,0}, - {38579,38578,38581 ,730,730,730 ,0,0,0}, {37863,37862,38581 ,730,730,730 ,0,0,0}, - {38248,37861,34799 ,730,730,730 ,0,0,0}, {37871,34803,34807 ,730,730,730 ,0,0,0}, - {37872,34806,38249 ,730,730,730 ,0,0,0}, {38249,34809,37819 ,730,730,730 ,0,0,0}, - {34811,34813,37879 ,730,730,730 ,0,0,0}, {34813,2941,38251 ,730,730,730 ,0,0,0}, - {2941,34402,38251 ,730,730,730 ,0,0,0}, {2941,34404,34402 ,730,730,730 ,0,0,0}, - {34401,34412,38582 ,730,730,730 ,0,0,0}, {38583,34401,38584 ,730,730,730 ,0,0,0}, - {34706,34418,34416 ,730,730,730 ,0,0,0}, {38585,38586,34407 ,730,730,730 ,0,0,0}, - {34412,37886,38587 ,730,730,730 ,0,0,0}, {34712,34715,34421 ,730,730,730 ,0,0,0}, - {34421,34713,34712 ,730,730,730 ,0,0,0}, {38214,37899,38215 ,730,730,730 ,0,0,0}, - {35933,35935,37870 ,730,730,730 ,0,0,0}, {35935,37860,34427 ,730,730,730 ,0,0,0}, - {35929,35930,37869 ,730,730,730 ,0,0,0}, {35929,37869,38588 ,730,730,730 ,0,0,0}, - {38577,35924,35927 ,730,730,730 ,0,0,0}, {34443,38246,37867 ,730,730,730 ,0,0,0}, - {38577,38246,35924 ,730,730,730 ,0,0,0}, {34444,38589,34446 ,730,730,730 ,0,0,0}, - {34451,34446,34827 ,730,730,730 ,0,0,0}, {2165,34446,38589 ,730,730,730 ,0,0,0}, - {34793,34790,37882 ,730,730,730 ,0,0,0}, {35792,35791,38322 ,730,730,730 ,0,0,0}, - {37881,34788,37827 ,730,730,730 ,0,0,0}, {34790,34788,37881 ,730,730,730 ,0,0,0}, - {34787,34768,38242 ,730,730,730 ,0,0,0}, {34437,34771,34775 ,730,730,730 ,0,0,0}, - {34767,34771,34432 ,730,730,730 ,0,0,0}, {34430,38590,38245 ,730,730,730 ,0,0,0}, - {34767,34430,34768 ,730,730,730 ,0,0,0}, {38590,34429,38591 ,730,730,730 ,0,0,0}, - {37876,34435,34777 ,730,730,730 ,0,0,0}, {34821,34819,38241 ,730,730,730 ,0,0,0}, - {38243,34441,38580 ,730,730,730 ,0,0,0}, {38592,38593,38594 ,730,730,730 ,0,0,0}, - {35917,34454,34455 ,730,730,730 ,0,0,0}, {38595,38596,35898 ,730,730,730 ,0,0,0}, - {38596,35900,35898 ,730,730,730 ,0,0,0}, {37875,35907,35901 ,730,730,730 ,0,0,0}, - {37875,37874,35907 ,730,730,730 ,0,0,0}, {35909,37818,35904 ,730,730,730 ,0,0,0}, - {38322,35791,35904 ,730,730,730 ,0,0,0}, {38322,37877,35792 ,730,730,730 ,0,0,0}, - {35794,37878,38323 ,730,730,730 ,0,0,0}, {37878,35794,35792 ,730,730,730 ,0,0,0}, - {38324,35799,35794 ,730,730,730 ,0,0,0}, {35797,35799,37858 ,730,730,730 ,0,0,0}, - {38324,37858,35799 ,730,730,730 ,0,0,0}, {37859,38597,35797 ,730,730,730 ,0,0,0}, - {38238,38237,38597 ,730,730,730 ,0,0,0}, {35797,38597,38237 ,730,730,730 ,0,0,0}, - {38239,38238,38598 ,730,730,730 ,0,0,0}, {34798,38239,38598 ,730,730,730 ,0,0,0}, - {38224,38223,38327 ,730,730,730 ,0,0,0}, {2303,38599,38600 ,730,730,730 ,0,0,0}, - {34762,35783,35785 ,730,730,730 ,0,0,0}, {34762,35785,34763 ,730,730,730 ,0,0,0}, - {34757,34756,38601 ,730,730,730 ,0,0,0}, {38601,35783,34757 ,730,730,730 ,0,0,0}, - {34738,34737,37907 ,730,730,730 ,0,0,0}, {34738,37907,38601 ,730,730,730 ,0,0,0}, - {34738,38601,34756 ,730,730,730 ,0,0,0}, {38225,34745,37903 ,730,730,730 ,0,0,0}, - {38331,38602,38603 ,730,730,730 ,0,0,0}, {38600,38604,34385 ,730,730,730 ,0,0,0}, - {34387,34749,34388 ,730,730,730 ,0,0,0}, {34387,34747,34749 ,730,730,730 ,0,0,0}, - {34387,38605,37836 ,730,730,730 ,0,0,0}, {34390,34388,34751 ,730,730,730 ,0,0,0}, - {38606,34393,38219 ,730,730,730 ,0,0,0}, {38607,34395,34390 ,730,730,730 ,0,0,0}, - {37842,37841,34374 ,730,730,730 ,0,0,0}, {34384,38604,38608 ,730,730,730 ,0,0,0}, - {38603,38599,2303 ,730,730,730 ,0,0,0}, {38602,38599,38603 ,730,730,730 ,0,0,0}, - {38609,38330,38610 ,730,730,730 ,0,0,0}, {38333,38328,38611 ,730,730,730 ,0,0,0}, - {38610,38326,38609 ,730,730,730 ,0,0,0}, {38337,38332,38334 ,730,730,730 ,0,0,0}, - {38334,38333,38611 ,730,730,730 ,0,0,0}, {38335,38612,38336 ,730,730,730 ,0,0,0}, - {38337,38336,38332 ,730,730,730 ,0,0,0}, {38338,38612,38613 ,730,730,730 ,0,0,0}, - {38335,38613,38612 ,730,730,730 ,0,0,0}, {38338,38340,38321 ,730,730,730 ,0,0,0}, - {38338,38613,38339 ,730,730,730 ,0,0,0}, {2131,38321,38340 ,730,730,730 ,0,0,0}, - {37894,38614,37895 ,730,730,730 ,0,0,0}, {37900,37846,37898 ,730,730,730 ,0,0,0}, - {38615,34728,34726 ,730,730,730 ,0,0,0}, {37887,34728,38615 ,730,730,730 ,0,0,0}, - {34418,34706,34705 ,730,730,730 ,0,0,0}, {34715,38616,34421 ,730,730,730 ,0,0,0}, - {34423,34713,34421 ,730,730,730 ,0,0,0}, {37824,34415,34426 ,730,730,730 ,0,0,0}, - {34717,38616,34715 ,730,730,730 ,0,0,0}, {37857,37850,37856 ,730,730,730 ,0,0,0}, - {37851,37850,37857 ,730,730,730 ,0,0,0}, {37890,37852,37851 ,730,730,730 ,0,0,0}, - {37854,38617,37891 ,730,730,730 ,0,0,0}, {37845,34722,37846 ,730,730,730 ,0,0,0}, - {37900,37844,37846 ,730,730,730 ,0,0,0}, {37899,37898,38215 ,730,730,730 ,0,0,0}, - {38214,37833,37832 ,730,730,730 ,0,0,0}, {37832,37834,38217 ,730,730,730 ,0,0,0}, - {37843,38216,37841 ,730,730,730 ,0,0,0}, {38217,37834,38216 ,730,730,730 ,0,0,0}, - {38218,34376,34374 ,730,730,730 ,0,0,0}, {38618,34381,38619 ,730,730,730 ,0,0,0}, - {38619,34376,38218 ,730,730,730 ,0,0,0}, {34379,34381,38620 ,730,730,730 ,0,0,0}, - {34373,34384,38621 ,730,730,730 ,0,0,0}, {38622,38229,38220 ,730,730,730 ,0,0,0}, - {34736,34734,37837 ,730,730,730 ,0,0,0}, {38606,38623,34393 ,730,730,730 ,0,0,0}, - {38606,38624,38623 ,730,730,730 ,0,0,0}, {34398,37840,34387 ,730,730,730 ,0,0,0}, - {37839,34398,34399 ,730,730,730 ,0,0,0}, {34703,36039,36038 ,730,730,730 ,0,0,0}, - {38625,35853,35851 ,730,730,730 ,0,0,0}, {34697,37759,36043 ,730,730,730 ,0,0,0}, - {36043,34700,34697 ,730,730,730 ,0,0,0}, {34695,37759,34697 ,730,730,730 ,0,0,0}, - {34675,34679,34348 ,730,730,730 ,0,0,0}, {38510,34694,34676 ,730,730,730 ,0,0,0}, - {34679,34683,34353 ,730,730,730 ,0,0,0}, {34675,34348,34346 ,730,730,730 ,0,0,0}, - {37762,37761,38626 ,730,730,730 ,0,0,0}, {38627,38628,38629 ,730,730,730 ,0,0,0}, - {38630,34351,34685 ,730,730,730 ,0,0,0}, {34634,34632,37747 ,730,730,730 ,0,0,0}, - {35873,34370,34371 ,730,730,730 ,0,0,0}, {38275,35856,35854 ,730,730,730 ,0,0,0}, - {35857,37761,35863 ,730,730,730 ,0,0,0}, {35860,35865,37751 ,730,730,730 ,0,0,0}, - {35863,37762,37751 ,730,730,730 ,0,0,0}, {38253,37724,34108 ,730,730,730 ,0,0,0}, - {38252,35860,37751 ,730,730,730 ,0,0,0}, {37724,38631,34110 ,730,730,730 ,0,0,0}, - {34113,34115,37722 ,730,730,730 ,0,0,0}, {37707,34650,37710 ,730,730,730 ,0,0,0}, - {34669,34101,34670 ,730,730,730 ,0,0,0}, {36015,35981,34093 ,730,730,730 ,0,0,0}, - {36021,3171,36023 ,730,730,730 ,0,0,0}, {36023,3171,36026 ,730,730,730 ,0,0,0}, - {38632,34644,34643 ,730,730,730 ,0,0,0}, {36027,38633,36029 ,730,730,730 ,0,0,0}, - {36026,37746,36027 ,730,730,730 ,0,0,0}, {38634,36033,38254 ,730,730,730 ,0,0,0}, - {38635,35990,35993 ,730,730,730 ,0,0,0}, {35996,38636,35995 ,730,730,730 ,0,0,0}, - {38637,38272,38273 ,730,730,730 ,0,0,0}, {36021,36020,34105 ,730,730,730 ,0,0,0}, - {38637,38638,38271 ,730,730,730 ,0,0,0}, {37720,38632,34643 ,730,730,730 ,0,0,0}, - {38638,34113,38271 ,730,730,730 ,0,0,0}, {35872,35869,34119 ,730,730,730 ,0,0,0}, - {37706,38639,37704 ,730,730,730 ,0,0,0}, {36007,37712,36005 ,730,730,730 ,0,0,0}, - {38640,38641,38262 ,730,730,730 ,0,0,0}, {34191,34653,34655 ,730,730,730 ,0,0,0}, - {38642,38643,34609 ,730,730,730 ,0,0,0}, {34194,34192,34657 ,730,730,730 ,0,0,0}, - {38644,34197,38260 ,730,730,730 ,0,0,0}, {38645,34199,34194 ,730,730,730 ,0,0,0}, - {38646,38647,34185 ,730,730,730 ,0,0,0}, {38648,34177,38649 ,730,730,730 ,0,0,0}, - {37708,36011,36013 ,730,730,730 ,0,0,0}, {3063,38643,38641 ,730,730,730 ,0,0,0}, - {36007,36008,38650 ,730,730,730 ,0,0,0}, {36001,36002,38266 ,730,730,730 ,0,0,0}, - {35996,35999,38267 ,730,730,730 ,0,0,0}, {35999,36001,38268 ,730,730,730 ,0,0,0}, - {38636,35993,35995 ,730,730,730 ,0,0,0}, {38636,35996,38267 ,730,730,730 ,0,0,0}, - {38635,38269,35990 ,730,730,730 ,0,0,0}, {38636,38635,35993 ,730,730,730 ,0,0,0}, - {35989,37718,35987 ,730,730,730 ,0,0,0}, {35990,38269,35989 ,730,730,730 ,0,0,0}, - {35987,37717,35984 ,730,730,730 ,0,0,0}, {34674,35984,37717 ,730,730,730 ,0,0,0}, - {38651,35879,35880 ,730,730,730 ,0,0,0}, {38652,38653,35883 ,730,730,730 ,0,0,0}, - {34631,38278,37747 ,730,730,730 ,0,0,0}, {3015,38628,38627 ,730,730,730 ,0,0,0}, - {38508,34357,37757 ,730,730,730 ,0,0,0}, {37757,34357,38509 ,730,730,730 ,0,0,0}, - {37756,37738,37737 ,730,730,730 ,0,0,0}, {38276,37738,38654 ,730,730,730 ,0,0,0}, - {38282,37743,34615 ,730,730,730 ,0,0,0}, {38282,34619,34618 ,730,730,730 ,0,0,0}, - {37742,34621,37745 ,730,730,730 ,0,0,0}, {34623,34625,38283 ,730,730,730 ,0,0,0}, - {34628,37734,37744 ,730,730,730 ,0,0,0}, {34269,38284,38655 ,730,730,730 ,0,0,0}, - {34628,34264,34262 ,730,730,730 ,0,0,0}, {38655,38656,34267 ,730,730,730 ,0,0,0}, - {37735,34261,38657 ,730,730,730 ,0,0,0}, {34278,34276,34582 ,730,730,730 ,0,0,0}, - {34591,34593,38658 ,730,730,730 ,0,0,0}, {34273,37727,38659 ,730,730,730 ,0,0,0}, - {37697,38257,37698 ,730,730,730 ,0,0,0}, {35889,35891,38280 ,730,730,730 ,0,0,0}, - {35891,37740,34287 ,730,730,730 ,0,0,0}, {35885,35886,38279 ,730,730,730 ,0,0,0}, - {35885,38279,38660 ,730,730,730 ,0,0,0}, {38653,35880,35883 ,730,730,730 ,0,0,0}, - {34359,38651,37741 ,730,730,730 ,0,0,0}, {38653,38651,35880 ,730,730,730 ,0,0,0}, - {34360,38661,34362 ,730,730,730 ,0,0,0}, {34367,34362,34640 ,730,730,730 ,0,0,0}, - {34642,34362,38661 ,730,730,730 ,0,0,0}, {37694,37693,38662 ,730,730,730 ,0,0,0}, - {38663,37696,37691 ,730,730,730 ,0,0,0}, {38664,34603,34601 ,730,730,730 ,0,0,0}, - {37729,34603,38664 ,730,730,730 ,0,0,0}, {34278,34582,34581 ,730,730,730 ,0,0,0}, - {34591,38658,34281 ,730,730,730 ,0,0,0}, {34589,34588,34281 ,730,730,730 ,0,0,0}, - {34283,34589,34281 ,730,730,730 ,0,0,0}, {38281,34275,34286 ,730,730,730 ,0,0,0}, - {38665,37686,37685 ,730,730,730 ,0,0,0}, {34273,37689,37688 ,730,730,730 ,0,0,0}, - {37725,37687,37689 ,730,730,730 ,0,0,0}, {37592,37687,37725 ,730,730,730 ,0,0,0}, - {38666,38667,37593 ,730,730,730 ,0,0,0}, {38668,38669,37692 ,730,730,730 ,0,0,0}, - {37691,37690,38663 ,730,730,730 ,0,0,0}, {37696,38663,37697 ,730,730,730 ,0,0,0}, - {38256,38255,38258 ,730,730,730 ,0,0,0}, {37698,38257,38256 ,730,730,730 ,0,0,0}, - {38258,37589,38670 ,730,730,730 ,0,0,0}, {38671,37588,37587 ,730,730,730 ,0,0,0}, - {37588,38670,37589 ,730,730,730 ,0,0,0}, {34180,38259,38646 ,730,730,730 ,0,0,0}, - {37587,38259,34178 ,730,730,730 ,0,0,0}, {38671,34178,38648 ,730,730,730 ,0,0,0}, - {38672,34188,38673 ,730,730,730 ,0,0,0}, {3063,34609,38643 ,730,730,730 ,0,0,0}, - {37709,38673,34189 ,730,730,730 ,0,0,0}, {38644,38674,34197 ,730,730,730 ,0,0,0}, - {38644,38675,38674 ,730,730,730 ,0,0,0}, {34202,37713,34191 ,730,730,730 ,0,0,0}, - {37714,34202,34203 ,730,730,730 ,0,0,0}, {38676,38677,35839 ,730,730,730 ,0,0,0}, - {38315,36087,1435 ,730,730,730 ,0,0,0}, {36087,36085,1435 ,730,730,730 ,0,0,0}, - {36090,36087,38315 ,730,730,730 ,0,0,0}, {36093,36091,38316 ,730,730,730 ,0,0,0}, - {38678,36097,36096 ,730,730,730 ,0,0,0}, {36102,34551,34555 ,730,730,730 ,0,0,0}, - {36103,34555,34559 ,730,730,730 ,0,0,0}, {36105,34559,34558 ,730,730,730 ,0,0,0}, - {38523,34563,34565 ,730,730,730 ,0,0,0}, {34561,38523,36107 ,730,730,730 ,0,0,0}, - {36107,34558,34561 ,730,730,730 ,0,0,0}, {34563,38523,34561 ,730,730,730 ,0,0,0}, - {34332,34540,34539 ,730,730,730 ,0,0,0}, {38524,34565,1263 ,730,730,730 ,0,0,0}, - {38524,1263,34318 ,730,730,730 ,0,0,0}, {34325,38522,38679 ,730,730,730 ,0,0,0}, - {38680,38681,38682 ,730,730,730 ,0,0,0}, {34323,38679,38683 ,730,730,730 ,0,0,0}, - {34529,38684,34337 ,730,730,730 ,0,0,0}, {34520,34334,34332 ,730,730,730 ,0,0,0}, - {37571,37570,38685 ,730,730,730 ,0,0,0}, {35845,35847,38317 ,730,730,730 ,0,0,0}, - {35847,38319,34343 ,730,730,730 ,0,0,0}, {35841,35842,38318 ,730,730,730 ,0,0,0}, - {35841,38318,38686 ,730,730,730 ,0,0,0}, {38677,35836,35839 ,730,730,730 ,0,0,0}, - {34079,37594,37590 ,730,730,730 ,0,0,0}, {38677,37594,35836 ,730,730,730 ,0,0,0}, - {34080,38687,34082 ,730,730,730 ,0,0,0}, {34087,34082,34579 ,730,730,730 ,0,0,0}, - {2082,34082,38687 ,730,730,730 ,0,0,0}, {37522,37524,38688 ,730,730,730 ,0,0,0}, - {38685,37570,38689 ,730,730,730 ,0,0,0}, {38690,34542,34540 ,730,730,730 ,0,0,0}, - {37606,34542,38690 ,730,730,730 ,0,0,0}, {34339,34527,34337 ,730,730,730 ,0,0,0}, - {38684,34529,34531 ,730,730,730 ,0,0,0}, {34529,34337,34526 ,730,730,730 ,0,0,0}, - {34337,34527,34526 ,730,730,730 ,0,0,0}, {34342,37603,34331 ,730,730,730 ,0,0,0}, - {34533,37597,34531 ,730,730,730 ,0,0,0}, {38681,38691,38682 ,730,730,730 ,0,0,0}, - {34971,34329,34974 ,730,730,730 ,0,0,0}, {38692,38693,38691 ,730,730,730 ,0,0,0}, - {37574,37573,34974 ,730,730,730 ,0,0,0}, {37610,37575,37576 ,730,730,730 ,0,0,0}, - {38685,38689,34536 ,730,730,730 ,0,0,0}, {37570,37572,38290 ,730,730,730 ,0,0,0}, - {37517,38289,37515 ,730,730,730 ,0,0,0}, {38290,37572,38289 ,730,730,730 ,0,0,0}, - {37516,37515,38291 ,730,730,730 ,0,0,0}, {37514,38293,38292 ,730,730,730 ,0,0,0}, - {38293,37516,38291 ,730,730,730 ,0,0,0}, {38294,34236,37561 ,730,730,730 ,0,0,0}, - {38292,37561,34234 ,730,730,730 ,0,0,0}, {34239,34241,38694 ,730,730,730 ,0,0,0}, - {38298,34239,38695 ,730,730,730 ,0,0,0}, {38302,37559,34245 ,730,730,730 ,0,0,0}, - {38299,34253,38300 ,730,730,730 ,0,0,0}, {37554,34496,38696 ,730,730,730 ,0,0,0}, - {34247,34258,37565 ,730,730,730 ,0,0,0}, {38696,34496,34499 ,730,730,730 ,0,0,0}, - {37564,34258,34259 ,730,730,730 ,0,0,0}, {38697,38698,38699 ,730,730,730 ,0,0,0}, - {34161,38700,38701 ,730,730,730 ,0,0,0}, {34160,38701,38702 ,730,730,730 ,0,0,0}, - {35822,34163,34174 ,730,730,730 ,0,0,0}, {38703,34489,34493 ,730,730,730 ,0,0,0}, - {34166,37569,38704 ,730,730,730 ,0,0,0}, {35828,35825,34175 ,730,730,730 ,0,0,0}, - {37519,38705,37507 ,730,730,730 ,0,0,0}, {34499,38706,38696 ,730,730,730 ,0,0,0}, - {34247,34499,34501 ,730,730,730 ,0,0,0}, {37563,34548,38707 ,730,730,730 ,0,0,0}, - {34250,34503,1297 ,730,730,730 ,0,0,0}, {38708,38300,34253 ,730,730,730 ,0,0,0}, - {34253,34255,38708 ,730,730,730 ,0,0,0}, {34545,37541,34546 ,730,730,730 ,0,0,0}, - {38706,34247,38709 ,730,730,730 ,0,0,0}, {37563,34550,34548 ,730,730,730 ,0,0,0}, - {38303,38306,38304 ,730,730,730 ,0,0,0}, {38710,38306,38305 ,730,730,730 ,0,0,0}, - {38711,38710,38307 ,730,730,730 ,0,0,0}, {38712,37583,37560 ,730,730,730 ,0,0,0}, - {38713,37549,37548 ,730,730,730 ,0,0,0}, {38712,37560,37549 ,730,730,730 ,0,0,0}, - {38309,38698,38308 ,730,730,730 ,0,0,0}, {37548,38308,38713 ,730,730,730 ,0,0,0}, - {38699,38311,38697 ,730,730,730 ,0,0,0}, {38309,38699,38698 ,730,730,730 ,0,0,0}, - {38310,37567,37566 ,730,730,730 ,0,0,0}, {38697,38311,38310 ,730,730,730 ,0,0,0}, - {37566,37568,38312 ,730,730,730 ,0,0,0}, {2073,38312,37568 ,730,730,730 ,0,0,0}, - {34486,36060,36063 ,730,730,730 ,0,0,0}, {38714,35809,35807 ,730,730,730 ,0,0,0}, - {34478,34477,36053 ,730,730,730 ,0,0,0}, {34478,36053,36054 ,730,730,730 ,0,0,0}, - {34458,36048,36051 ,730,730,730 ,0,0,0}, {34461,34465,34073 ,730,730,730 ,0,0,0}, - {34068,34066,34457 ,730,730,730 ,0,0,0}, {34071,34073,34464 ,730,730,730 ,0,0,0}, - {34066,36048,34458 ,730,730,730 ,0,0,0}, {34065,34076,36079 ,730,730,730 ,0,0,0}, - {36047,34066,36045 ,730,730,730 ,0,0,0}, {34573,34571,38288 ,730,730,730 ,0,0,0}, - {34077,1435,36085 ,730,730,730 ,0,0,0}, {38715,38716,38717 ,730,730,730 ,0,0,0}, - {35829,34090,34091 ,730,730,730 ,0,0,0}, {38285,35812,35810 ,730,730,730 ,0,0,0}, - {35813,37525,35819 ,730,730,730 ,0,0,0}, {35816,35821,37586 ,730,730,730 ,0,0,0}, - {35819,37527,37586 ,730,730,730 ,0,0,0}, {37505,37569,34164 ,730,730,730 ,0,0,0}, - {37504,35816,37586 ,730,730,730 ,0,0,0}, {34166,38718,34171 ,730,730,730 ,0,0,0}, - {38719,34169,37580 ,730,730,730 ,0,0,0}, {37531,37533,34169 ,730,730,730 ,0,0,0}, - {37531,34169,38719 ,730,730,730 ,0,0,0}, {34489,38703,38720 ,730,730,730 ,0,0,0}, - {38700,37520,36077 ,730,730,730 ,0,0,0}, {36077,37520,36075 ,730,730,730 ,0,0,0}, - {38720,34490,34489 ,730,730,730 ,0,0,0}, {36072,38721,36071 ,730,730,730 ,0,0,0}, - {36075,37521,36072 ,730,730,730 ,0,0,0}, {38722,36066,38287 ,730,730,730 ,0,0,0}, - {34784,38593,38592 ,730,730,730 ,0,0,0}, {34818,37868,38241 ,730,730,730 ,0,0,0}, - {34781,34784,38592 ,730,730,730 ,0,0,0}, {37865,38579,38247 ,730,730,730 ,0,0,0}, - {34799,37863,34800 ,730,730,730 ,0,0,0}, {34799,37861,37863 ,730,730,730 ,0,0,0}, - {38578,37863,38581 ,730,730,730 ,0,0,0}, {38241,34819,34818 ,730,730,730 ,0,0,0}, - {34825,34451,34827 ,730,730,730 ,0,0,0}, {34825,34824,34451 ,730,730,730 ,0,0,0}, - {34443,35923,38246 ,730,730,730 ,0,0,0}, {38589,34444,37867 ,730,730,730 ,0,0,0}, - {34443,35918,35921 ,730,730,730 ,0,0,0}, {34455,38325,35895 ,730,730,730 ,0,0,0}, - {35895,35917,34455 ,730,730,730 ,0,0,0}, {38595,35898,35897 ,730,730,730 ,0,0,0}, - {38595,35897,38325 ,730,730,730 ,0,0,0}, {37873,38594,38593 ,730,730,730 ,0,0,0}, - {37875,35901,35900 ,730,730,730 ,0,0,0}, {37875,35900,38596 ,730,730,730 ,0,0,0}, - {37875,38594,37873 ,730,730,730 ,0,0,0}, {37876,34777,34779 ,730,730,730 ,0,0,0}, - {37876,34781,38592 ,730,730,730 ,0,0,0}, {34435,34774,34777 ,730,730,730 ,0,0,0}, - {34437,34775,34774 ,730,730,730 ,0,0,0}, {34430,38245,34768 ,730,730,730 ,0,0,0}, - {34437,34432,34771 ,730,730,730 ,0,0,0}, {34430,34429,38590 ,730,730,730 ,0,0,0}, - {38591,34429,37864 ,730,730,730 ,0,0,0}, {37864,34440,38244 ,730,730,730 ,0,0,0}, - {34441,38244,34440 ,730,730,730 ,0,0,0}, {37889,38586,38723 ,730,730,730 ,0,0,0}, - {34719,38213,34717 ,730,730,730 ,0,0,0}, {38723,37830,37889 ,730,730,730 ,0,0,0}, - {38213,34722,37855 ,730,730,730 ,0,0,0}, {37854,37893,38617 ,730,730,730 ,0,0,0}, - {37891,38617,37890 ,730,730,730 ,0,0,0}, {34722,37845,37855 ,730,730,730 ,0,0,0}, - {37853,37855,37845 ,730,730,730 ,0,0,0}, {38213,38616,34717 ,730,730,730 ,0,0,0}, - {34709,34713,34423 ,730,730,730 ,0,0,0}, {34415,38615,34726 ,730,730,730 ,0,0,0}, - {34709,34418,34705 ,730,730,730 ,0,0,0}, {34418,34709,34423 ,730,730,730 ,0,0,0}, - {34726,34416,34415 ,730,730,730 ,0,0,0}, {34415,37824,38615 ,730,730,730 ,0,0,0}, - {38724,35935,34427 ,730,730,730 ,0,0,0}, {34427,37860,34426 ,730,730,730 ,0,0,0}, - {35933,37869,35930 ,730,730,730 ,0,0,0}, {37870,35935,38724 ,730,730,730 ,0,0,0}, - {38576,35927,38588 ,730,730,730 ,0,0,0}, {35929,38588,35927 ,730,730,730 ,0,0,0}, - {37829,37828,38576 ,730,730,730 ,0,0,0}, {37829,38576,38588 ,730,730,730 ,0,0,0}, - {38725,38723,38586 ,730,730,730 ,0,0,0}, {34407,37826,38585 ,730,730,730 ,0,0,0}, - {38586,38585,38725 ,730,730,730 ,0,0,0}, {34407,34409,37825 ,730,730,730 ,0,0,0}, - {38583,38251,34402 ,730,730,730 ,0,0,0}, {34409,34404,37885 ,730,730,730 ,0,0,0}, - {38584,34401,38582 ,730,730,730 ,0,0,0}, {34402,34401,38583 ,730,730,730 ,0,0,0}, - {38582,34412,38587 ,730,730,730 ,0,0,0}, {37886,34412,34413 ,730,730,730 ,0,0,0}, - {38222,38224,38623 ,730,730,730 ,0,0,0}, {34385,2303,38600 ,730,730,730 ,0,0,0}, - {38329,38331,38603 ,730,730,730 ,0,0,0}, {38611,38327,38223 ,730,730,730 ,0,0,0}, - {38610,38330,38329 ,730,730,730 ,0,0,0}, {38610,38327,38326 ,730,730,730 ,0,0,0}, - {38327,38611,38328 ,730,730,730 ,0,0,0}, {38623,38624,38222 ,730,730,730 ,0,0,0}, - {34387,37836,34747 ,730,730,730 ,0,0,0}, {38726,38219,34395 ,730,730,730 ,0,0,0}, - {34395,38607,38726 ,730,730,730 ,0,0,0}, {34751,34388,34749 ,730,730,730 ,0,0,0}, - {34390,2950,38607 ,730,730,730 ,0,0,0}, {34387,37840,38605 ,730,730,730 ,0,0,0}, - {34399,37849,37897 ,730,730,730 ,0,0,0}, {37897,37839,34399 ,730,730,730 ,0,0,0}, - {37831,38614,37894 ,730,730,730 ,0,0,0}, {37847,37895,37848 ,730,730,730 ,0,0,0}, - {34732,37838,34734 ,730,730,730 ,0,0,0}, {37831,37892,38614 ,730,730,730 ,0,0,0}, - {37831,37838,34732 ,730,730,730 ,0,0,0}, {38220,38221,38622 ,730,730,730 ,0,0,0}, - {38220,38229,37837 ,730,730,730 ,0,0,0}, {34379,38620,38221 ,730,730,730 ,0,0,0}, - {34381,38618,38620 ,730,730,730 ,0,0,0}, {34381,34376,38619 ,730,730,730 ,0,0,0}, - {38727,37842,34374 ,730,730,730 ,0,0,0}, {37902,34373,38621 ,730,730,730 ,0,0,0}, - {38727,34374,37902 ,730,730,730 ,0,0,0}, {38621,34384,38608 ,730,730,730 ,0,0,0}, - {38604,34384,34385 ,730,730,730 ,0,0,0}, {38630,34687,34689 ,730,730,730 ,0,0,0}, - {34612,38278,34631 ,730,730,730 ,0,0,0}, {3015,38627,34689 ,730,730,730 ,0,0,0}, - {37736,37738,38276 ,730,730,730 ,0,0,0}, {37738,38728,38654 ,730,730,730 ,0,0,0}, - {34611,37743,38277 ,730,730,730 ,0,0,0}, {37743,38728,38277 ,730,730,730 ,0,0,0}, - {38654,38728,37743 ,730,730,730 ,0,0,0}, {37747,34632,34631 ,730,730,730 ,0,0,0}, - {34638,34367,34640 ,730,730,730 ,0,0,0}, {34638,34637,34367 ,730,730,730 ,0,0,0}, - {34359,35879,38651 ,730,730,730 ,0,0,0}, {38661,34360,37741 ,730,730,730 ,0,0,0}, - {34359,35874,35877 ,730,730,730 ,0,0,0}, {34371,38625,35851 ,730,730,730 ,0,0,0}, - {35851,35873,34371 ,730,730,730 ,0,0,0}, {38274,35854,35853 ,730,730,730 ,0,0,0}, - {38274,35853,38625 ,730,730,730 ,0,0,0}, {38626,38629,38628 ,730,730,730 ,0,0,0}, - {37761,35857,35856 ,730,730,730 ,0,0,0}, {37761,35856,38275 ,730,730,730 ,0,0,0}, - {37761,38629,38626 ,730,730,730 ,0,0,0}, {38630,34685,34687 ,730,730,730 ,0,0,0}, - {38630,34689,38627 ,730,730,730 ,0,0,0}, {34351,34682,34685 ,730,730,730 ,0,0,0}, - {34353,34683,34682 ,730,730,730 ,0,0,0}, {34346,34676,34675 ,730,730,730 ,0,0,0}, - {34353,34348,34679 ,730,730,730 ,0,0,0}, {38510,34346,38511 ,730,730,730 ,0,0,0}, - {38511,34356,37764 ,730,730,730 ,0,0,0}, {38511,34346,34345 ,730,730,730 ,0,0,0}, - {34356,34357,38508 ,730,730,730 ,0,0,0}, {38729,38692,34323 ,730,730,730 ,0,0,0}, - {37597,34533,34536 ,730,730,730 ,0,0,0}, {38682,38691,38693 ,730,730,730 ,0,0,0}, - {37596,34536,38689 ,730,730,730 ,0,0,0}, {37575,37610,37573 ,730,730,730 ,0,0,0}, - {37576,37596,38689 ,730,730,730 ,0,0,0}, {37577,37596,37576 ,730,730,730 ,0,0,0}, - {37597,38684,34531 ,730,730,730 ,0,0,0}, {34523,34527,34339 ,730,730,730 ,0,0,0}, - {34331,38690,34540 ,730,730,730 ,0,0,0}, {34523,34334,34519 ,730,730,730 ,0,0,0}, - {34334,34523,34339 ,730,730,730 ,0,0,0}, {34540,34332,34331 ,730,730,730 ,0,0,0}, - {34331,37603,38690 ,730,730,730 ,0,0,0}, {38730,35847,34343 ,730,730,730 ,0,0,0}, - {34343,38319,34342 ,730,730,730 ,0,0,0}, {35845,38318,35842 ,730,730,730 ,0,0,0}, - {38317,35847,38730 ,730,730,730 ,0,0,0}, {38676,35839,38686 ,730,730,730 ,0,0,0}, - {35841,38686,35839 ,730,730,730 ,0,0,0}, {38681,38680,38676 ,730,730,730 ,0,0,0}, - {38681,38676,38686 ,730,730,730 ,0,0,0}, {38731,38693,38692 ,730,730,730 ,0,0,0}, - {34323,38683,38729 ,730,730,730 ,0,0,0}, {38692,38729,38731 ,730,730,730 ,0,0,0}, - {34323,34325,38679 ,730,730,730 ,0,0,0}, {34318,1263,34320 ,730,730,730 ,0,0,0}, - {34325,34320,38522 ,730,730,730 ,0,0,0}, {34318,34317,38524 ,730,730,730 ,0,0,0}, - {38525,34328,38320 ,730,730,730 ,0,0,0}, {38524,34317,38525 ,730,730,730 ,0,0,0}, - {34971,34328,34329 ,730,730,730 ,0,0,0}, {37476,37475,38561 ,730,730,730 ,0,0,0}, - {34301,35063,35069 ,730,730,730 ,0,0,0}, {35078,35076,38563 ,730,730,730 ,0,0,0}, - {38563,38732,38566 ,730,730,730 ,0,0,0}, {38563,38487,35078 ,730,730,730 ,0,0,0}, - {37997,38565,37474 ,730,730,730 ,0,0,0}, {38565,38732,37474 ,730,730,730 ,0,0,0}, - {38566,38732,38565 ,730,730,730 ,0,0,0}, {38546,38545,38561 ,730,730,730 ,0,0,0}, - {34303,38558,34869 ,730,730,730 ,0,0,0}, {38733,38542,34311 ,730,730,730 ,0,0,0}, - {34311,37998,38733 ,730,730,730 ,0,0,0}, {34873,34304,34871 ,730,730,730 ,0,0,0}, - {34306,34876,37998 ,730,730,730 ,0,0,0}, {34303,38009,38560 ,730,730,730 ,0,0,0}, - {34315,38010,38535 ,730,730,730 ,0,0,0}, {38535,38008,34315 ,730,730,730 ,0,0,0}, - {38005,38534,38183 ,730,730,730 ,0,0,0}, {38011,38182,38012 ,730,730,730 ,0,0,0}, - {34917,38488,34919 ,730,730,730 ,0,0,0}, {38005,38004,38534 ,730,730,730 ,0,0,0}, - {38005,38488,34917 ,730,730,730 ,0,0,0}, {37996,37995,38562 ,730,730,730 ,0,0,0}, - {37996,38559,38489 ,730,730,730 ,0,0,0}, {34295,38541,37995 ,730,730,730 ,0,0,0}, - {34297,38540,38541 ,730,730,730 ,0,0,0}, {34297,34292,38539 ,730,730,730 ,0,0,0}, - {34290,38484,38014 ,730,730,730 ,0,0,0}, {38485,34290,38017 ,730,730,730 ,0,0,0}, - {38017,34300,38490 ,730,730,730 ,0,0,0}, {38017,34290,34289 ,730,730,730 ,0,0,0}, - {34300,34301,35069 ,730,730,730 ,0,0,0}, {37684,37730,38734 ,730,730,730 ,0,0,0}, - {34595,37728,34593 ,730,730,730 ,0,0,0}, {38734,37685,37684 ,730,730,730 ,0,0,0}, - {37728,3049,38669 ,730,730,730 ,0,0,0}, {38666,38735,38667 ,730,730,730 ,0,0,0}, - {37593,38667,37591 ,730,730,730 ,0,0,0}, {37692,38669,3049 ,730,730,730 ,0,0,0}, - {38735,38669,38668 ,730,730,730 ,0,0,0}, {38666,38669,38735 ,730,730,730 ,0,0,0}, - {37728,38658,34593 ,730,730,730 ,0,0,0}, {34585,34589,34283 ,730,730,730 ,0,0,0}, - {34275,38664,34601 ,730,730,730 ,0,0,0}, {34585,34278,34581 ,730,730,730 ,0,0,0}, - {34278,34585,34283 ,730,730,730 ,0,0,0}, {34601,34276,34275 ,730,730,730 ,0,0,0}, - {34275,38281,38664 ,730,730,730 ,0,0,0}, {38736,35891,34287 ,730,730,730 ,0,0,0}, - {34287,37740,34286 ,730,730,730 ,0,0,0}, {35889,38279,35886 ,730,730,730 ,0,0,0}, - {38280,35891,38736 ,730,730,730 ,0,0,0}, {38652,35883,38660 ,730,730,730 ,0,0,0}, - {35885,38660,35883 ,730,730,730 ,0,0,0}, {37686,38665,38652 ,730,730,730 ,0,0,0}, - {37686,38652,38660 ,730,730,730 ,0,0,0}, {38737,38734,37730 ,730,730,730 ,0,0,0}, - {34267,38656,37731 ,730,730,730 ,0,0,0}, {37730,37731,38737 ,730,730,730 ,0,0,0}, - {34267,34269,38655 ,730,730,730 ,0,0,0}, {34262,37734,34628 ,730,730,730 ,0,0,0}, - {34269,34264,38284 ,730,730,730 ,0,0,0}, {34262,34261,37735 ,730,730,730 ,0,0,0}, - {38657,34261,37732 ,730,730,730 ,0,0,0}, {37732,34272,38659 ,730,730,730 ,0,0,0}, - {34273,38659,34272 ,730,730,730 ,0,0,0}, {37512,37511,38299 ,730,730,730 ,0,0,0}, - {38303,38302,34245 ,730,730,730 ,0,0,0}, {38307,38710,38305 ,730,730,730 ,0,0,0}, - {37547,37560,37510 ,730,730,730 ,0,0,0}, {38307,37584,38711 ,730,730,730 ,0,0,0}, - {37547,37549,37560 ,730,730,730 ,0,0,0}, {37582,37560,37583 ,730,730,730 ,0,0,0}, - {38299,38301,37512 ,730,730,730 ,0,0,0}, {34247,38706,34499 ,730,730,730 ,0,0,0}, - {38738,38708,34255 ,730,730,730 ,0,0,0}, {34255,37555,38738 ,730,730,730 ,0,0,0}, - {34503,34248,34501 ,730,730,730 ,0,0,0}, {34250,1297,37555 ,730,730,730 ,0,0,0}, - {34247,37565,38709 ,730,730,730 ,0,0,0}, {34259,37543,37545 ,730,730,730 ,0,0,0}, - {37545,37564,34259 ,730,730,730 ,0,0,0}, {37541,38688,37524 ,730,730,730 ,0,0,0}, - {37523,37522,37544 ,730,730,730 ,0,0,0}, {34546,38707,34548 ,730,730,730 ,0,0,0}, - {37541,37540,38688 ,730,730,730 ,0,0,0}, {37541,38707,34546 ,730,730,730 ,0,0,0}, - {38298,38695,38297 ,730,730,730 ,0,0,0}, {38298,37562,37563 ,730,730,730 ,0,0,0}, - {34239,38694,38695 ,730,730,730 ,0,0,0}, {34241,38295,38694 ,730,730,730 ,0,0,0}, - {34241,34236,38294 ,730,730,730 ,0,0,0}, {34234,37514,38292 ,730,730,730 ,0,0,0}, - {34234,34233,37513 ,730,730,730 ,0,0,0}, {38296,34233,37558 ,730,730,730 ,0,0,0}, - {37559,34244,34245 ,730,730,730 ,0,0,0}, {37558,34233,34244 ,730,730,730 ,0,0,0}, - {38551,34217,38572 ,730,730,730 ,0,0,0}, {37557,38552,34860 ,730,730,730 ,0,0,0}, - {37985,3917,37984 ,730,730,730 ,0,0,0}, {38200,38573,38197 ,730,730,730 ,0,0,0}, - {38200,38202,38574 ,730,730,730 ,0,0,0}, {37982,37984,3917 ,730,730,730 ,0,0,0}, - {38201,38575,38202 ,730,730,730 ,0,0,0}, {38575,37984,37983 ,730,730,730 ,0,0,0}, - {37985,38554,38553 ,730,730,730 ,0,0,0}, {38570,37989,34227 ,730,730,730 ,0,0,0}, - {34219,35948,37988 ,730,730,730 ,0,0,0}, {37988,34220,34219 ,730,730,730 ,0,0,0}, - {34222,38556,38570 ,730,730,730 ,0,0,0}, {34219,35954,35948 ,730,730,730 ,0,0,0}, - {37993,37992,38191 ,730,730,730 ,0,0,0}, {38739,35960,34231 ,730,730,730 ,0,0,0}, - {34231,35957,34230 ,730,730,730 ,0,0,0}, {38739,38002,35960 ,730,730,730 ,0,0,0}, - {38003,37991,38557 ,730,730,730 ,0,0,0}, {37556,34867,37992 ,730,730,730 ,0,0,0}, - {37992,34867,38191 ,730,730,730 ,0,0,0}, {37556,34863,34867 ,730,730,730 ,0,0,0}, - {34879,34860,38552 ,730,730,730 ,0,0,0}, {34211,34882,34880 ,730,730,730 ,0,0,0}, - {38552,34880,34879 ,730,730,730 ,0,0,0}, {34213,34208,34886 ,730,730,730 ,0,0,0}, - {34211,34213,34885 ,730,730,730 ,0,0,0}, {34206,37484,34890 ,730,730,730 ,0,0,0}, - {34206,34205,38195 ,730,730,730 ,0,0,0}, {38196,34205,37483 ,730,730,730 ,0,0,0}, - {37483,34216,38550 ,730,730,730 ,0,0,0}, {34217,38550,34216 ,730,730,730 ,0,0,0}, - {38265,38264,38674 ,730,730,730 ,0,0,0}, {37708,37709,34189 ,730,730,730 ,0,0,0}, - {38650,36008,37711 ,730,730,730 ,0,0,0}, {38268,38266,38263 ,730,730,730 ,0,0,0}, - {37712,36007,38650 ,730,730,730 ,0,0,0}, {37712,38266,36002 ,730,730,730 ,0,0,0}, - {38266,38268,36001 ,730,730,730 ,0,0,0}, {38674,38675,38265 ,730,730,730 ,0,0,0}, - {34191,37701,34653 ,730,730,730 ,0,0,0}, {38740,38260,34199 ,730,730,730 ,0,0,0}, - {34199,38645,38740 ,730,730,730 ,0,0,0}, {34657,34192,34655 ,730,730,730 ,0,0,0}, - {34194,34660,38645 ,730,730,730 ,0,0,0}, {34191,37713,37702 ,730,730,730 ,0,0,0}, - {34203,37715,37719 ,730,730,730 ,0,0,0}, {37719,37714,34203 ,730,730,730 ,0,0,0}, - {37683,38662,37693 ,730,730,730 ,0,0,0}, {37695,37694,37716 ,730,730,730 ,0,0,0}, - {34607,38642,34609 ,730,730,730 ,0,0,0}, {37683,37726,38662 ,730,730,730 ,0,0,0}, - {37683,38642,34607 ,730,730,730 ,0,0,0}, {38262,38261,38640 ,730,730,730 ,0,0,0}, - {38262,38641,38643 ,730,730,730 ,0,0,0}, {34183,37703,38261 ,730,730,730 ,0,0,0}, - {34185,38647,37703 ,730,730,730 ,0,0,0}, {34185,34180,38646 ,730,730,730 ,0,0,0}, - {38671,37587,34178 ,730,730,730 ,0,0,0}, {34178,34177,38648 ,730,730,730 ,0,0,0}, - {38649,34177,38672 ,730,730,730 ,0,0,0}, {38673,34188,34189 ,730,730,730 ,0,0,0}, - {38672,34177,34188 ,730,730,730 ,0,0,0}, {34161,37520,38700 ,730,730,730 ,0,0,0}, - {38720,38313,34490 ,730,730,730 ,0,0,0}, {37539,34488,38722 ,730,730,730 ,0,0,0}, - {38721,36072,37521 ,730,730,730 ,0,0,0}, {38287,36071,38721 ,730,730,730 ,0,0,0}, - {34488,36065,38722 ,730,730,730 ,0,0,0}, {38287,36066,36069 ,730,730,730 ,0,0,0}, - {36066,38722,36065 ,730,730,730 ,0,0,0}, {37539,37533,37532 ,730,730,730 ,0,0,0}, - {38718,37580,34171 ,730,730,730 ,0,0,0}, {34163,35816,37504 ,730,730,730 ,0,0,0}, - {37504,34164,34163 ,730,730,730 ,0,0,0}, {34166,38704,38718 ,730,730,730 ,0,0,0}, - {34163,35822,35816 ,730,730,730 ,0,0,0}, {37519,37518,37554 ,730,730,730 ,0,0,0}, - {38741,35828,34175 ,730,730,730 ,0,0,0}, {34175,35825,34174 ,730,730,730 ,0,0,0}, - {38741,37509,35828 ,730,730,730 ,0,0,0}, {37508,37507,38705 ,730,730,730 ,0,0,0}, - {38703,34497,37518 ,730,730,730 ,0,0,0}, {37518,34497,37554 ,730,730,730 ,0,0,0}, - {38703,34493,34497 ,730,730,730 ,0,0,0}, {34508,34490,38313 ,730,730,730 ,0,0,0}, - {34155,34511,34509 ,730,730,730 ,0,0,0}, {38313,34509,34508 ,730,730,730 ,0,0,0}, - {34157,34152,34515 ,730,730,730 ,0,0,0}, {34155,34157,34514 ,730,730,730 ,0,0,0}, - {34150,37578,2073 ,730,730,730 ,0,0,0}, {34150,34149,37579 ,730,730,730 ,0,0,0}, - {37585,34149,38702 ,730,730,730 ,0,0,0}, {38701,34160,34161 ,730,730,730 ,0,0,0}, - {38702,34149,34160 ,730,730,730 ,0,0,0}, {3931,38568,38567 ,730,730,730 ,0,0,0}, - {34941,37973,38181 ,730,730,730 ,0,0,0}, {34843,3931,38567 ,730,730,730 ,0,0,0}, - {38210,36135,38528 ,730,730,730 ,0,0,0}, {34921,38208,34922 ,730,730,730 ,0,0,0}, - {38210,38208,36130 ,730,730,730 ,0,0,0}, {38210,36133,36135 ,730,730,730 ,0,0,0}, - {38208,34921,36129 ,730,730,730 ,0,0,0}, {38181,34942,34941 ,730,730,730 ,0,0,0}, - {34948,34143,34950 ,730,730,730 ,0,0,0}, {34948,34947,34143 ,730,730,730 ,0,0,0}, - {34135,35967,38209 ,730,730,730 ,0,0,0}, {38533,34136,37972 ,730,730,730 ,0,0,0}, - {34135,35962,35965 ,730,730,730 ,0,0,0}, {34147,37976,35939 ,730,730,730 ,0,0,0}, - {35939,35961,34147 ,730,730,730 ,0,0,0}, {37534,35942,35941 ,730,730,730 ,0,0,0}, - {37534,35941,37976 ,730,730,730 ,0,0,0}, {37961,38569,38568 ,730,730,730 ,0,0,0}, - {37550,35945,35944 ,730,730,730 ,0,0,0}, {37550,35944,37535 ,730,730,730 ,0,0,0}, - {37550,38569,37961 ,730,730,730 ,0,0,0}, {38205,34839,34841 ,730,730,730 ,0,0,0}, - {38205,34843,38567 ,730,730,730 ,0,0,0}, {34127,34836,34839 ,730,730,730 ,0,0,0}, - {34129,34837,34836 ,730,730,730 ,0,0,0}, {38207,34830,34122 ,730,730,730 ,0,0,0}, - {34129,34124,34833 ,730,730,730 ,0,0,0}, {34122,34121,37966 ,730,730,730 ,0,0,0}, - {37967,34121,37965 ,730,730,730 ,0,0,0}, {37964,34132,34133 ,730,730,730 ,0,0,0}, - {37965,34121,34132 ,730,730,730 ,0,0,0}, {34105,3171,36021 ,730,730,730 ,0,0,0}, - {38632,38270,34644 ,730,730,730 ,0,0,0}, {38273,3029,38634 ,730,730,730 ,0,0,0}, - {38633,36027,37746 ,730,730,730 ,0,0,0}, {38254,36029,38633 ,730,730,730 ,0,0,0}, - {36035,38634,3029 ,730,730,730 ,0,0,0}, {38254,36032,36029 ,730,730,730 ,0,0,0}, - {36033,38634,36035 ,730,730,730 ,0,0,0}, {38273,38638,38637 ,730,730,730 ,0,0,0}, - {37723,37722,34115 ,730,730,730 ,0,0,0}, {34107,35860,38252 ,730,730,730 ,0,0,0}, - {38252,34108,34107 ,730,730,730 ,0,0,0}, {34110,38631,37723 ,730,730,730 ,0,0,0}, - {34107,35866,35860 ,730,730,730 ,0,0,0}, {37706,37705,37707 ,730,730,730 ,0,0,0}, - {38742,35872,34119 ,730,730,730 ,0,0,0}, {34119,35869,34118 ,730,730,730 ,0,0,0}, - {38742,37700,35872 ,730,730,730 ,0,0,0}, {37699,37704,38639 ,730,730,730 ,0,0,0}, - {37720,34651,37705 ,730,730,730 ,0,0,0}, {37705,34651,37707 ,730,730,730 ,0,0,0}, - {37720,34647,34651 ,730,730,730 ,0,0,0}, {34663,34644,38270 ,730,730,730 ,0,0,0}, - {34099,34666,34664 ,730,730,730 ,0,0,0}, {38270,34664,34663 ,730,730,730 ,0,0,0}, - {34101,34096,34670 ,730,730,730 ,0,0,0}, {34099,34101,34669 ,730,730,730 ,0,0,0}, - {35984,34094,35983 ,730,730,730 ,0,0,0}, {34094,34093,35981 ,730,730,730 ,0,0,0}, - {34093,34104,36015 ,730,730,730 ,0,0,0}, {36020,34104,34105 ,730,730,730 ,0,0,0}, - {36015,34104,36017 ,730,730,730 ,0,0,0}, {34474,38716,38715 ,730,730,730 ,0,0,0}, - {34570,37529,38288 ,730,730,730 ,0,0,0}, {34471,34474,38715 ,730,730,730 ,0,0,0}, - {38678,36093,38316 ,730,730,730 ,0,0,0}, {34551,38314,34552 ,730,730,730 ,0,0,0}, - {38678,38314,36097 ,730,730,730 ,0,0,0}, {38678,36096,36093 ,730,730,730 ,0,0,0}, - {38314,34551,36099 ,730,730,730 ,0,0,0}, {38288,34571,34570 ,730,730,730 ,0,0,0}, - {34577,34087,34579 ,730,730,730 ,0,0,0}, {34577,34576,34087 ,730,730,730 ,0,0,0}, - {34079,35835,37594 ,730,730,730 ,0,0,0}, {38687,34080,37590 ,730,730,730 ,0,0,0}, - {34079,35830,35833 ,730,730,730 ,0,0,0}, {34091,38714,35807 ,730,730,730 ,0,0,0}, - {35807,35829,34091 ,730,730,730 ,0,0,0}, {38286,35810,35809 ,730,730,730 ,0,0,0}, - {38286,35809,38714 ,730,730,730 ,0,0,0}, {37526,38717,38716 ,730,730,730 ,0,0,0}, - {37525,35813,35812 ,730,730,730 ,0,0,0}, {37525,35812,38285 ,730,730,730 ,0,0,0}, - {37525,38717,37526 ,730,730,730 ,0,0,0}, {37528,34467,34469 ,730,730,730 ,0,0,0}, - {37528,34471,38715 ,730,730,730 ,0,0,0}, {34071,34464,34467 ,730,730,730 ,0,0,0}, - {34073,34465,34464 ,730,730,730 ,0,0,0}, {36047,36048,34066 ,730,730,730 ,0,0,0}, - {34073,34068,34461 ,730,730,730 ,0,0,0}, {34066,34065,36045 ,730,730,730 ,0,0,0}, - {36079,34076,36081 ,730,730,730 ,0,0,0}, {36045,34065,36079 ,730,730,730 ,0,0,0}, - {36084,34076,34077 ,730,730,730 ,0,0,0}, {37981,37978,38743 ,730,730,730 ,0,0,0}, - {34905,38180,34903 ,730,730,730 ,0,0,0}, {38743,37979,37981 ,730,730,730 ,0,0,0}, - {38180,3897,38186 ,730,730,730 ,0,0,0}, {36157,38185,36160 ,730,730,730 ,0,0,0}, - {38185,36157,38006 ,730,730,730 ,0,0,0}, {36163,38186,3897 ,730,730,730 ,0,0,0}, - {36161,38186,36163 ,730,730,730 ,0,0,0}, {38180,38531,34903 ,730,730,730 ,0,0,0}, - {34895,34899,34059 ,730,730,730 ,0,0,0}, {34051,38536,34911 ,730,730,730 ,0,0,0}, - {34895,34054,34891 ,730,730,730 ,0,0,0}, {34054,34895,34059 ,730,730,730 ,0,0,0}, - {34911,34052,34051 ,730,730,730 ,0,0,0}, {34051,38211,38536 ,730,730,730 ,0,0,0}, - {38744,35979,34063 ,730,730,730 ,0,0,0}, {34063,37974,34062 ,730,730,730 ,0,0,0}, - {35977,37968,35974 ,730,730,730 ,0,0,0}, {37969,35979,38744 ,730,730,730 ,0,0,0}, - {38526,35971,38532 ,730,730,730 ,0,0,0}, {35973,38532,35971 ,730,730,730 ,0,0,0}, - {37980,38537,38526 ,730,730,730 ,0,0,0}, {37980,38526,38532 ,730,730,730 ,0,0,0}, - {38745,38743,37978 ,730,730,730 ,0,0,0}, {34043,38530,37977 ,730,730,730 ,0,0,0}, - {37978,37977,38745 ,730,730,730 ,0,0,0}, {34043,34045,38529 ,730,730,730 ,0,0,0}, - {36112,34038,36111 ,730,730,730 ,0,0,0}, {34045,34040,38212 ,730,730,730 ,0,0,0}, - {34038,34037,36109 ,730,730,730 ,0,0,0}, {34037,34048,36143 ,730,730,730 ,0,0,0}, - {36148,34048,34049 ,730,730,730 ,0,0,0}, {36143,34048,36145 ,730,730,730 ,0,0,0}, - {38403,38746,38363 ,730,730,730 ,0,0,0}, {38363,38746,38433 ,730,730,730 ,0,0,0}, - {37815,36352,36448 ,20176,20176,20176 ,0,0,0}, {37815,36448,37919 ,20176,20176,20176 ,0,0,0}, - {36374,36373,37850 ,20177,20178,20179 ,0,0,0}, {37852,36381,36374 ,20180,20181,20177 ,0,0,0}, - {36374,37850,37852 ,20177,20179,20180 ,0,0,0}, {36381,37890,36379 ,20181,20182,20183 ,0,0,0}, - {37890,36381,37852 ,20182,20181,20180 ,0,0,0}, {36376,36379,38617 ,20184,20183,20185 ,0,0,0}, - {37890,38617,36379 ,20182,20185,20183 ,0,0,0}, {37893,37341,36376 ,20186,20187,20184 ,0,0,0}, - {36376,38617,37893 ,20184,20185,20186 ,0,0,0}, {37341,37853,36364 ,20187,20188,20189 ,0,0,0}, - {37853,37341,37893 ,20188,20187,20186 ,0,0,0}, {36365,36364,37845 ,20190,20189,20191 ,0,0,0}, - {37853,37845,36364 ,20188,20191,20189 ,0,0,0}, {37844,36957,36365 ,20192,20193,20190 ,0,0,0}, - {36365,37845,37844 ,20190,20191,20192 ,0,0,0}, {36957,37900,36956 ,20193,20194,20195 ,0,0,0}, - {37900,36957,37844 ,20194,20193,20192 ,0,0,0}, {37338,36956,37899 ,20196,20195,20197 ,0,0,0}, - {37900,37899,36956 ,20194,20197,20195 ,0,0,0}, {38214,37339,37338 ,20198,20199,20196 ,0,0,0}, - {37338,37899,38214 ,20196,20197,20198 ,0,0,0}, {37339,37832,36400 ,20199,20200,20201 ,0,0,0}, - {37832,37339,38214 ,20200,20199,20198 ,0,0,0}, {36399,36400,38217 ,20202,20201,20203 ,0,0,0}, - {37832,38217,36400 ,20200,20203,20201 ,0,0,0}, {37843,36397,36399 ,20204,20205,20202 ,0,0,0}, - {36399,38217,37843 ,20202,20203,20204 ,0,0,0}, {36397,37842,36951 ,20205,20206,20207 ,0,0,0}, - {37842,36397,37843 ,20206,20205,20204 ,0,0,0}, {36952,36951,38727 ,20208,20207,20209 ,0,0,0}, - {37842,38727,36951 ,20206,20209,20207 ,0,0,0}, {37902,36949,36952 ,20210,20211,20208 ,0,0,0}, - {36952,38727,37902 ,20208,20209,20210 ,0,0,0}, {36949,38621,36950 ,20211,20212,20213 ,0,0,0}, - {38621,36949,37902 ,20212,20211,20210 ,0,0,0}, {37449,36950,38608 ,20214,20213,20215 ,0,0,0}, - {38621,38608,36950 ,20212,20215,20213 ,0,0,0}, {38604,36403,37449 ,20216,20217,20214 ,0,0,0}, - {37449,38608,38604 ,20214,20215,20216 ,0,0,0}, {36403,38600,36404 ,20217,20218,20219 ,0,0,0}, - {38600,36403,38604 ,20218,20217,20216 ,0,0,0}, {36948,36404,38599 ,20220,20219,20221 ,0,0,0}, - {38600,38599,36404 ,20218,20221,20219 ,0,0,0}, {38602,36407,36948 ,20222,20223,20220 ,0,0,0}, - {36948,38599,38602 ,20220,20221,20222 ,0,0,0}, {36407,38331,36405 ,20223,20224,20225 ,0,0,0}, - {38331,36407,38602 ,20224,20223,20222 ,0,0,0}, {36945,36405,38330 ,20226,20225,20227 ,0,0,0}, - {38331,38330,36405 ,20224,20227,20225 ,0,0,0}, {38609,37345,36945 ,20228,20229,20226 ,0,0,0}, - {36945,38330,38609 ,20226,20227,20228 ,0,0,0}, {37345,38326,36939 ,20229,20230,20231 ,0,0,0}, - {38326,37345,38609 ,20230,20229,20228 ,0,0,0}, {36938,36939,38328 ,20232,20231,20233 ,0,0,0}, - {38326,38328,36939 ,20230,20233,20231 ,0,0,0}, {38333,36935,36938 ,20234,20235,20232 ,0,0,0}, - {36938,38328,38333 ,20232,20233,20234 ,0,0,0}, {36935,38332,36936 ,20235,20236,20237 ,0,0,0}, - {38332,36935,38333 ,20236,20235,20234 ,0,0,0}, {37053,36936,38336 ,20238,20237,20239 ,0,0,0}, - {38332,38336,36936 ,20236,20239,20237 ,0,0,0}, {38612,37055,37053 ,20240,20240,20238 ,0,0,0}, - {37053,38336,38612 ,20238,20239,20240 ,0,0,0}, {37850,36373,37856 ,20179,20178,20241 ,0,0,0}, - {37886,37856,37322 ,20242,20241,20243 ,0,0,0}, {36373,37322,37856 ,20178,20243,20241 ,0,0,0}, - {37445,38587,37886 ,20244,20245,20242 ,0,0,0}, {37886,37322,37445 ,20242,20243,20244 ,0,0,0}, - {38587,36369,38582 ,20245,20246,20247 ,0,0,0}, {36369,38587,37445 ,20246,20245,20244 ,0,0,0}, - {38584,38582,37446 ,20248,20247,20249 ,0,0,0}, {36369,37446,38582 ,20246,20249,20247 ,0,0,0}, - {36370,38583,38584 ,20250,20251,20248 ,0,0,0}, {38584,37446,36370 ,20248,20249,20250 ,0,0,0}, - {38583,36371,38251 ,20251,20252,20253 ,0,0,0}, {36371,38583,36370 ,20252,20251,20250 ,0,0,0}, - {38250,38251,36375 ,20254,20253,20255 ,0,0,0}, {36371,36375,38251 ,20252,20255,20253 ,0,0,0}, - {36368,37879,38250 ,20256,20257,20254 ,0,0,0}, {38250,36375,36368 ,20254,20255,20256 ,0,0,0}, - {37879,36383,37819 ,20257,20258,20259 ,0,0,0}, {36383,37879,36368 ,20258,20257,20256 ,0,0,0}, - {38249,37819,36387 ,20260,20259,20261 ,0,0,0}, {36383,36387,37819 ,20258,20261,20259 ,0,0,0}, - {36388,37872,38249 ,20262,20263,20260 ,0,0,0}, {38249,36387,36388 ,20260,20261,20262 ,0,0,0}, - {37872,36391,37871 ,20263,20264,20265 ,0,0,0}, {36391,37872,36388 ,20264,20263,20262 ,0,0,0}, - {38248,37871,36394 ,20266,20265,20267 ,0,0,0}, {36391,36394,37871 ,20264,20267,20265 ,0,0,0}, - {36393,37861,38248 ,20268,20269,20266 ,0,0,0}, {38248,36394,36393 ,20266,20267,20268 ,0,0,0}, - {37861,37314,37862 ,20269,20270,20271 ,0,0,0}, {37314,37861,36393 ,20270,20269,20268 ,0,0,0}, - {38581,37862,36354 ,20272,20271,20273 ,0,0,0}, {37314,36354,37862 ,20270,20273,20271 ,0,0,0}, - {36353,38579,38581 ,20274,20275,20272 ,0,0,0}, {38581,36354,36353 ,20272,20273,20274 ,0,0,0}, - {38579,37323,38247 ,20275,20276,20277 ,0,0,0}, {37323,38579,36353 ,20276,20275,20274 ,0,0,0}, - {37866,38247,37325 ,20278,20277,20279 ,0,0,0}, {37323,37325,38247 ,20276,20279,20277 ,0,0,0}, - {37061,37822,37866 ,20280,20281,20278 ,0,0,0}, {37866,37325,37061 ,20278,20279,20280 ,0,0,0}, - {37822,37060,38580 ,20281,20282,20283 ,0,0,0}, {37060,37822,37061 ,20282,20281,20280 ,0,0,0}, - {38243,38580,36917 ,20284,20283,20285 ,0,0,0}, {37060,36917,38580 ,20282,20285,20283 ,0,0,0}, - {36918,38244,38243 ,20286,20287,20284 ,0,0,0}, {38243,36917,36918 ,20284,20285,20286 ,0,0,0}, - {38244,36924,37864 ,20287,20288,20289 ,0,0,0}, {36924,38244,36918 ,20288,20287,20286 ,0,0,0}, - {38591,37864,36923 ,20290,20289,20291 ,0,0,0}, {36924,36923,37864 ,20288,20291,20289 ,0,0,0}, - {36925,38590,38591 ,20292,20293,20290 ,0,0,0}, {38591,36923,36925 ,20290,20291,20292 ,0,0,0}, - {38590,36437,38245 ,20293,20294,20295 ,0,0,0}, {36437,38590,36925 ,20294,20293,20292 ,0,0,0}, - {38242,38245,36436 ,20296,20295,20297 ,0,0,0}, {36437,36436,38245 ,20294,20297,20295 ,0,0,0}, - {37043,37827,38242 ,20298,20299,20296 ,0,0,0}, {38242,36436,37043 ,20296,20297,20298 ,0,0,0}, - {37827,37328,37881 ,20299,20300,20301 ,0,0,0}, {37328,37827,37043 ,20300,20299,20298 ,0,0,0}, - {37328,36447,37881 ,20300,20302,20301 ,0,0,0}, {37881,36447,37882 ,20301,20302,20302 ,0,0,0}, - {38492,36443,37817 ,20303,9968,20303 ,0,0,0}, {36443,38492,36449 ,9968,20303,9968 ,0,0,0}, - {36327,37668,37807 ,4303,4303,4303 ,0,0,0}, {36327,37807,36337 ,4303,4303,4303 ,0,0,0}, - {37940,36213,36833 ,21,20304,20304 ,0,0,0}, {37940,36833,38132 ,21,20304,21 ,0,0,0}, - {36306,37956,36293 ,20305,20306,20305 ,0,0,0}, {37956,36306,38026 ,20306,20305,20306 ,0,0,0}, - {37300,36141,36140 ,20307,20308,20309 ,0,0,0}, {37967,37965,36279 ,20310,20311,20312 ,0,0,0}, - {36278,37964,37301 ,20313,20314,20315 ,0,0,0}, {38207,36243,37963 ,20316,20317,20318 ,0,0,0}, - {37299,36878,37966 ,20319,20320,20321 ,0,0,0}, {36237,38204,36285 ,20322,20323,20324 ,0,0,0}, - {37553,37552,36286 ,20325,20326,20327 ,0,0,0}, {38203,36235,36234 ,20328,20329,20330 ,0,0,0}, - {37546,36236,37962 ,20331,20332,20333 ,0,0,0}, {36881,36880,38575 ,20334,20335,20336 ,0,0,0}, - {37304,37983,37982 ,20337,20338,20339 ,0,0,0}, {36298,38573,36874 ,20340,20341,20342 ,0,0,0}, - {38574,38202,37289 ,20343,20344,20345 ,0,0,0}, {38551,38572,37290 ,20346,20347,20348 ,0,0,0}, - {38198,36297,38572 ,20349,20350,20347 ,0,0,0}, {37483,38550,36887 ,20351,20352,20353 ,0,0,0}, - {38551,36888,38550 ,20346,20354,20352 ,0,0,0}, {36891,38196,37483 ,20355,20356,20351 ,0,0,0}, - {37483,36887,36891 ,20351,20353,20355 ,0,0,0}, {38196,36890,38195 ,20356,20357,20358 ,0,0,0}, - {36890,38196,36891 ,20357,20356,20355 ,0,0,0}, {37484,38195,37291 ,20359,20358,20360 ,0,0,0}, - {36890,37291,38195 ,20357,20360,20358 ,0,0,0}, {37282,37485,37484 ,20361,20362,20359 ,0,0,0}, - {37484,37291,37282 ,20359,20360,20361 ,0,0,0}, {37485,36896,38193 ,20362,20363,20364 ,0,0,0}, - {36896,37485,37282 ,20363,20362,20361 ,0,0,0}, {38001,38193,36895 ,20365,20364,20366 ,0,0,0}, - {36896,36895,38193 ,20363,20366,20364 ,0,0,0}, {37293,37999,38001 ,20367,20367,20365 ,0,0,0}, - {38001,36895,37293 ,20365,20366,20367 ,0,0,0}, {37290,36888,38551 ,20348,20354,20346 ,0,0,0}, - {38550,36888,36887 ,20352,20354,20353 ,0,0,0}, {36298,36297,38198 ,20340,20350,20349 ,0,0,0}, - {38572,36297,37290 ,20347,20350,20348 ,0,0,0}, {38573,38574,36874 ,20341,20343,20342 ,0,0,0}, - {38198,38573,36298 ,20349,20341,20340 ,0,0,0}, {37289,38202,36880 ,20345,20344,20335 ,0,0,0}, - {36874,38574,37289 ,20342,20343,20345 ,0,0,0}, {36881,38575,37983 ,20334,20336,20338 ,0,0,0}, - {36880,38202,38575 ,20335,20344,20336 ,0,0,0}, {36234,37304,37982 ,20330,20337,20339 ,0,0,0}, - {37304,36881,37983 ,20337,20334,20338 ,0,0,0}, {37962,36235,38203 ,20333,20329,20328 ,0,0,0}, - {38203,36234,37982 ,20328,20330,20339 ,0,0,0}, {37546,36237,36236 ,20331,20322,20332 ,0,0,0}, - {37962,36236,36235 ,20333,20332,20329 ,0,0,0}, {38204,37553,36285 ,20323,20325,20324 ,0,0,0}, - {37546,38204,36237 ,20331,20323,20322 ,0,0,0}, {36286,37552,36242 ,20327,20326,20368 ,0,0,0}, - {36285,37553,36286 ,20324,20325,20327 ,0,0,0}, {37963,36243,36242 ,20318,20317,20368 ,0,0,0}, - {36242,37552,37963 ,20368,20326,20318 ,0,0,0}, {37966,36878,38207 ,20321,20320,20316 ,0,0,0}, - {36878,36243,38207 ,20320,20317,20316 ,0,0,0}, {37967,36279,37299 ,20310,20312,20319 ,0,0,0}, - {37967,37299,37966 ,20310,20319,20321 ,0,0,0}, {37965,37964,36278 ,20311,20314,20313 ,0,0,0}, - {37965,36278,36279 ,20311,20313,20312 ,0,0,0}, {37301,38206,37300 ,20315,20369,20307 ,0,0,0}, - {37964,38206,37301 ,20314,20369,20315 ,0,0,0}, {36141,37300,38206 ,20308,20307,20369 ,0,0,0}, - {36292,37957,38024 ,20370,20370,20370 ,0,0,0}, {36292,38024,36289 ,20370,20370,20370 ,0,0,0}, - {37948,36181,38050 ,20371,20372,20371 ,0,0,0}, {36181,37948,36199 ,20372,20371,20372 ,0,0,0}, - {37488,37481,36195 ,20373,126,126 ,0,0,0}, {37488,36195,36182 ,20373,126,20373 ,0,0,0}, - {37598,36677,37200 ,20374,20375,20375 ,0,0,0}, {37598,37200,37595 ,20374,20375,20374 ,0,0,0}, - {37429,36077,36076 ,20376,20377,20378 ,0,0,0}, {37585,38702,36689 ,20379,20380,20381 ,0,0,0}, - {37006,38701,37007 ,20382,20383,20384 ,0,0,0}, {37578,37009,38312 ,20385,20386,20387 ,0,0,0}, - {36690,37430,37579 ,20388,20389,20390 ,0,0,0}, {36693,38697,37010 ,20391,20392,20393 ,0,0,0}, - {38310,37566,37011 ,20394,20395,20396 ,0,0,0}, {38713,37431,36696 ,20397,20398,20399 ,0,0,0}, - {38698,37013,38308 ,20400,20401,20402 ,0,0,0}, {37432,37434,37583 ,20403,20404,20405 ,0,0,0}, - {37414,38712,37549 ,20406,20407,20408 ,0,0,0}, {37022,38710,37019 ,20409,20410,20411 ,0,0,0}, - {38711,37584,37020 ,20412,20413,20414 ,0,0,0}, {38302,38304,37025 ,20415,20416,20417 ,0,0,0}, - {38306,37024,38304 ,20418,20419,20416 ,0,0,0}, {37558,37559,37416 ,20420,20421,20422 ,0,0,0}, - {38302,37026,37559 ,20415,20423,20421 ,0,0,0}, {37028,38296,37558 ,20424,20425,20420 ,0,0,0}, - {37558,37416,37028 ,20420,20422,20424 ,0,0,0}, {38296,37027,37513 ,20425,20426,20427 ,0,0,0}, - {37027,38296,37028 ,20426,20425,20424 ,0,0,0}, {37514,37513,37417 ,20428,20427,20429 ,0,0,0}, - {37027,37417,37513 ,20426,20429,20427 ,0,0,0}, {37032,38293,37514 ,20430,20431,20428 ,0,0,0}, - {37514,37417,37032 ,20428,20429,20430 ,0,0,0}, {38293,37418,37516 ,20431,20432,20433 ,0,0,0}, - {37418,38293,37032 ,20432,20431,20430 ,0,0,0}, {37517,37516,37031 ,20434,20433,20435 ,0,0,0}, - {37418,37031,37516 ,20432,20435,20433 ,0,0,0}, {37030,38290,37517 ,20436,20436,20434 ,0,0,0}, - {37517,37031,37030 ,20434,20435,20436 ,0,0,0}, {37025,37026,38302 ,20417,20423,20415 ,0,0,0}, - {37559,37026,37416 ,20421,20423,20422 ,0,0,0}, {37022,37024,38306 ,20409,20419,20418 ,0,0,0}, - {38304,37024,37025 ,20416,20419,20417 ,0,0,0}, {38710,38711,37019 ,20410,20412,20411 ,0,0,0}, - {38306,38710,37022 ,20418,20410,20409 ,0,0,0}, {37020,37584,37434 ,20414,20413,20404 ,0,0,0}, - {37019,38711,37020 ,20411,20412,20414 ,0,0,0}, {37432,37583,38712 ,20403,20405,20407 ,0,0,0}, - {37434,37584,37583 ,20404,20413,20405 ,0,0,0}, {36696,37414,37549 ,20399,20406,20408 ,0,0,0}, - {37414,37432,38712 ,20406,20403,20407 ,0,0,0}, {38308,37431,38713 ,20402,20398,20397 ,0,0,0}, - {38713,36696,37549 ,20397,20399,20408 ,0,0,0}, {38698,36693,37013 ,20400,20391,20401 ,0,0,0}, - {38308,37013,37431 ,20402,20401,20398 ,0,0,0}, {38697,38310,37010 ,20392,20394,20393 ,0,0,0}, - {38698,38697,36693 ,20400,20392,20391 ,0,0,0}, {37011,37566,37422 ,20396,20395,20437 ,0,0,0}, - {37010,38310,37011 ,20393,20394,20396 ,0,0,0}, {38312,37009,37422 ,20387,20386,20437 ,0,0,0}, - {37422,37566,38312 ,20437,20395,20387 ,0,0,0}, {37579,37430,37578 ,20390,20389,20385 ,0,0,0}, - {37430,37009,37578 ,20389,20386,20385 ,0,0,0}, {37585,36689,36690 ,20379,20381,20388 ,0,0,0}, - {37585,36690,37579 ,20379,20388,20390 ,0,0,0}, {38702,38701,37006 ,20380,20383,20382 ,0,0,0}, - {38702,37006,36689 ,20380,20382,20381 ,0,0,0}, {37007,38700,37429 ,20384,20438,20376 ,0,0,0}, - {38701,38700,37007 ,20383,20438,20384 ,0,0,0}, {36077,37429,38700 ,20377,20376,20438 ,0,0,0}, - {37615,36676,37599 ,20439,20440,20439 ,0,0,0}, {36676,37615,36738 ,20440,20439,20440 ,0,0,0}, - {36645,38366,37626 ,7656,7656,7656 ,0,0,0}, {36645,37626,36653 ,7656,7656,7656 ,0,0,0}, - {37648,37094,36792 ,20441,9944,9944 ,0,0,0}, {37648,36792,37661 ,20441,9944,20441 ,0,0,0}, - {36623,37750,36528 ,20442,20443,20442 ,0,0,0}, {37750,36623,37767 ,20443,20442,20443 ,0,0,0}, - {36600,36013,36012 ,20444,20445,20446 ,0,0,0}, {38649,38672,36984 ,20447,20448,20449 ,0,0,0}, - {36985,38673,36599 ,20450,20451,20452 ,0,0,0}, {38671,36986,37588 ,20453,20454,20455 ,0,0,0}, - {37391,37396,38648 ,20456,20457,20458 ,0,0,0}, {37386,38256,37387 ,20459,20460,20461 ,0,0,0}, - {38258,38670,36962 ,20462,20463,20464 ,0,0,0}, {37691,36988,36552 ,20465,20466,20467 ,0,0,0}, - {37698,36559,37696 ,20468,20469,20470 ,0,0,0}, {36993,36992,38735 ,20471,20472,20473 ,0,0,0}, - {36555,38668,37692 ,20474,20475,20476 ,0,0,0}, {36544,37592,37378 ,20477,20478,20479 ,0,0,0}, - {37591,38667,37379 ,20480,20481,20482 ,0,0,0}, {37727,37688,37381 ,20483,20484,20485 ,0,0,0}, - {37687,36543,37688 ,20486,20487,20484 ,0,0,0}, {37732,38659,37383 ,20488,20489,20490 ,0,0,0}, - {37727,37382,38659 ,20483,20491,20489 ,0,0,0}, {36606,38657,37732 ,20492,20493,20488 ,0,0,0}, - {37732,37383,36606 ,20488,20490,20492 ,0,0,0}, {38657,36607,37735 ,20493,20494,20495 ,0,0,0}, - {36607,38657,36606 ,20494,20493,20492 ,0,0,0}, {37734,37735,36611 ,20496,20495,20497 ,0,0,0}, - {36607,36611,37735 ,20494,20497,20495 ,0,0,0}, {36610,37744,37734 ,20498,20499,20496 ,0,0,0}, - {37734,36611,36610 ,20496,20497,20498 ,0,0,0}, {37744,36613,38283 ,20499,20500,20501 ,0,0,0}, - {36613,37744,36610 ,20500,20499,20498 ,0,0,0}, {37745,38283,36969 ,20502,20501,20503 ,0,0,0}, - {36613,36969,38283 ,20500,20503,20501 ,0,0,0}, {36562,37742,37745 ,20504,20504,20502 ,0,0,0}, - {37745,36969,36562 ,20502,20503,20504 ,0,0,0}, {37381,37382,37727 ,20485,20491,20483 ,0,0,0}, - {38659,37382,37383 ,20489,20491,20490 ,0,0,0}, {36544,36543,37687 ,20477,20487,20486 ,0,0,0}, - {37688,36543,37381 ,20484,20487,20485 ,0,0,0}, {37592,37591,37378 ,20478,20480,20479 ,0,0,0}, - {37687,37592,36544 ,20486,20478,20477 ,0,0,0}, {37379,38667,36992 ,20482,20481,20472 ,0,0,0}, - {37378,37591,37379 ,20479,20480,20482 ,0,0,0}, {36993,38735,38668 ,20471,20473,20475 ,0,0,0}, - {36992,38667,38735 ,20472,20481,20473 ,0,0,0}, {36552,36555,37692 ,20467,20474,20476 ,0,0,0}, - {36555,36993,38668 ,20474,20471,20475 ,0,0,0}, {37696,36988,37691 ,20470,20466,20465 ,0,0,0}, - {37691,36552,37692 ,20465,20467,20476 ,0,0,0}, {37698,37386,36559 ,20468,20459,20469 ,0,0,0}, - {37696,36559,36988 ,20470,20469,20466 ,0,0,0}, {38256,38258,37387 ,20460,20462,20461 ,0,0,0}, - {37698,38256,37386 ,20468,20460,20459 ,0,0,0}, {36962,38670,37397 ,20464,20463,20505 ,0,0,0}, - {37387,38258,36962 ,20461,20462,20464 ,0,0,0}, {37588,36986,37397 ,20455,20454,20505 ,0,0,0}, - {37397,38670,37588 ,20505,20463,20455 ,0,0,0}, {38648,37396,38671 ,20458,20457,20453 ,0,0,0}, - {37396,36986,38671 ,20457,20454,20453 ,0,0,0}, {38649,36984,37391 ,20447,20449,20456 ,0,0,0}, - {38649,37391,38648 ,20447,20456,20458 ,0,0,0}, {38672,38673,36985 ,20448,20451,20450 ,0,0,0}, - {38672,36985,36984 ,20448,20450,20449 ,0,0,0}, {36599,37709,36600 ,20452,20506,20444 ,0,0,0}, - {38673,37709,36599 ,20451,20506,20452 ,0,0,0}, {36013,36600,37709 ,20445,20444,20506 ,0,0,0}, - {36526,37681,38498 ,20507,20508,20508 ,0,0,0}, {36526,38498,36619 ,20507,20508,20507 ,0,0,0}, - {38167,36497,38359 ,20509,11097,20509 ,0,0,0}, {36497,38167,36494 ,11097,20509,11097 ,0,0,0}, - {36341,37800,36849 ,8396,20510,8396 ,0,0,0}, {37800,36341,37801 ,20510,8396,20510 ,0,0,0}, - {37611,37610,36720 ,20511,20512,20513 ,0,0,0}, {37600,36679,36678 ,20514,20511,20514 ,0,0,0}, - {36679,37611,36720 ,20511,20511,20513 ,0,0,0}, {37600,36678,37605 ,20514,20514,20515 ,0,0,0}, - {37255,37615,37614 ,20516,20517,20516 ,0,0,0}, {37605,36678,36735 ,20515,20514,20515 ,0,0,0}, - {36735,37614,37605 ,20515,20516,20515 ,0,0,0}, {37614,36735,37255 ,20516,20515,20516 ,0,0,0}, - {37615,37255,36738 ,20517,20516,20518 ,0,0,0}, {36679,37600,37611 ,20511,20514,20511 ,0,0,0}, - {36721,36720,37610 ,20519,20513,20512 ,0,0,0}, {36730,36721,37576 ,20520,20519,20519 ,0,0,0}, - {37610,37576,36721 ,20512,20519,20519 ,0,0,0}, {38689,37037,36730 ,20520,20521,20520 ,0,0,0}, - {36730,37576,38689 ,20520,20519,20520 ,0,0,0}, {37037,37570,37030 ,20521,20522,20436 ,0,0,0}, - {37570,37037,38689 ,20522,20521,20520 ,0,0,0}, {37570,38290,37030 ,20522,20436,20436 ,0,0,0}, - {38320,37617,36732 ,20523,20524,20525 ,0,0,0}, {38525,36713,36714 ,20526,20523,20526 ,0,0,0}, - {36713,38320,36732 ,20523,20523,20525 ,0,0,0}, {38525,36714,38524 ,20526,20526,20527 ,0,0,0}, - {36188,36107,38523 ,20528,20060,20528 ,0,0,0}, {38524,36714,36711 ,20527,20526,20527 ,0,0,0}, - {36711,38523,38524 ,20527,20528,20527 ,0,0,0}, {38523,36711,36188 ,20528,20527,20528 ,0,0,0}, - {36107,36188,36108 ,20060,20528,20060 ,0,0,0}, {36713,38525,38320 ,20523,20526,20523 ,0,0,0}, - {37251,36732,37617 ,20529,20525,20524 ,0,0,0}, {37252,37251,37619 ,20530,20529,20529 ,0,0,0}, - {37617,37619,37251 ,20524,20529,20529 ,0,0,0}, {37618,36681,37252 ,20530,20531,20530 ,0,0,0}, - {37252,37619,37618 ,20530,20529,20530 ,0,0,0}, {36681,37607,37200 ,20531,20531,21 ,0,0,0}, - {37607,36681,37618 ,20531,20531,20530 ,0,0,0}, {37607,37595,37200 ,20531,20532,21 ,0,0,0}, - {37764,37766,36596 ,20533,20534,20534 ,0,0,0}, {38511,36595,37350 ,20535,20533,20535 ,0,0,0}, - {36595,37764,36596 ,20533,20533,20534 ,0,0,0}, {38511,37350,38510 ,20535,20535,20536 ,0,0,0}, - {36575,36043,37759 ,20537,19998,20537 ,0,0,0}, {38510,37350,36535 ,20536,20535,20536 ,0,0,0}, - {36535,37759,38510 ,20536,20537,20536 ,0,0,0}, {37759,36535,36575 ,20537,20536,20537 ,0,0,0}, - {36043,36575,36044 ,19998,20537,19998 ,0,0,0}, {36595,38511,37764 ,20533,20535,20533 ,0,0,0}, - {36617,36596,37766 ,20538,20534,20534 ,0,0,0}, {37235,36617,38507 ,20539,20538,20538 ,0,0,0}, - {37766,38507,36617 ,20534,20538,20538 ,0,0,0}, {37770,36618,37235 ,20539,20540,20539 ,0,0,0}, - {37235,38507,37770 ,20539,20538,20539 ,0,0,0}, {36618,37752,36623 ,20540,20540,20541 ,0,0,0}, - {37752,36618,37770 ,20540,20540,20539 ,0,0,0}, {37752,37767,36623 ,20540,20542,20541 ,0,0,0}, - {38015,38487,36905 ,20543,20544,20545 ,0,0,0}, {38016,37216,36311 ,20546,20543,20546 ,0,0,0}, - {37216,38015,36905 ,20543,20543,20545 ,0,0,0}, {38016,36311,38018 ,20546,20546,20547 ,0,0,0}, - {37220,38024,38482 ,20548,20549,20548 ,0,0,0}, {38018,36311,36301 ,20547,20546,20547 ,0,0,0}, - {36301,38482,38018 ,20547,20548,20547 ,0,0,0}, {38482,36301,37220 ,20548,20547,20548 ,0,0,0}, - {38024,37220,36289 ,20549,20548,20550 ,0,0,0}, {37216,38016,38015 ,20543,20546,20543 ,0,0,0}, - {37227,36905,38487 ,20551,20545,20544 ,0,0,0}, {37275,37227,38566 ,20552,20551,20551 ,0,0,0}, - {38487,38566,37227 ,20544,20551,20551 ,0,0,0}, {38565,36903,37275 ,20552,20553,20552 ,0,0,0}, - {37275,38566,38565 ,20552,20551,20552 ,0,0,0}, {36903,38547,37293 ,20553,20553,20367 ,0,0,0}, - {38547,36903,38565 ,20553,20553,20552 ,0,0,0}, {38547,37999,37293 ,20553,20367,20367 ,0,0,0}, - {38490,38020,36294 ,20554,20555,20556 ,0,0,0}, {38017,36900,37280 ,20557,20554,20557 ,0,0,0}, - {36900,38490,36294 ,20554,20554,20556 ,0,0,0}, {38017,37280,38485 ,20557,20557,20558 ,0,0,0}, - {36908,36171,38188 ,20559,20123,20559 ,0,0,0}, {38485,37280,37278 ,20558,20557,20558 ,0,0,0}, - {37278,38188,38485 ,20558,20559,20558 ,0,0,0}, {38188,37278,36908 ,20559,20558,20559 ,0,0,0}, - {36171,36908,36172 ,20123,20559,20123 ,0,0,0}, {36900,38017,38490 ,20554,20557,20554 ,0,0,0}, - {36295,36294,38020 ,20560,20556,20555 ,0,0,0}, {36304,36295,37960 ,20561,20560,20560 ,0,0,0}, - {38020,37960,36295 ,20555,20560,20560 ,0,0,0}, {37959,36308,36304 ,20561,20562,20561 ,0,0,0}, - {36304,37960,37959 ,20561,20560,20561 ,0,0,0}, {36308,38021,36306 ,20562,20562,20563 ,0,0,0}, - {38021,36308,37959 ,20562,20562,20561 ,0,0,0}, {38021,38026,36306 ,20562,20564,20563 ,0,0,0}, - {37754,38276,36592 ,20565,20566,20567 ,0,0,0}, {37758,36620,36608 ,20568,20565,20568 ,0,0,0}, - {36620,37754,36592 ,20565,20565,20567 ,0,0,0}, {37758,36608,37760 ,20568,20568,20569 ,0,0,0}, - {36621,38498,37763 ,20570,20571,20570 ,0,0,0}, {37760,36608,36609 ,20569,20568,20569 ,0,0,0}, - {36609,37763,37760 ,20569,20570,20569 ,0,0,0}, {37763,36609,36621 ,20570,20569,20570 ,0,0,0}, - {38498,36621,36619 ,20571,20570,20572 ,0,0,0}, {36620,37758,37754 ,20565,20568,20565 ,0,0,0}, - {37236,36592,38276 ,20573,20567,20566 ,0,0,0}, {37243,37236,38654 ,20574,20573,20573 ,0,0,0}, - {38276,38654,37236 ,20566,20573,20573 ,0,0,0}, {37743,37349,37243 ,20574,20575,20574 ,0,0,0}, - {37243,38654,37743 ,20574,20573,20574 ,0,0,0}, {37349,38282,36562 ,20575,20575,20504 ,0,0,0}, - {38282,37349,37743 ,20575,20575,20574 ,0,0,0}, {38282,37742,36562 ,20575,20504,20504 ,0,0,0}, - {37918,37922,36926 ,20576,20577,20577 ,0,0,0}, {37912,36928,36932 ,20578,20576,20578 ,0,0,0}, - {36928,37918,36926 ,20576,20576,20577 ,0,0,0}, {37912,36932,38321 ,20578,20578,20579 ,0,0,0}, - {36422,38612,38338 ,20580,20240,20580 ,0,0,0}, {38321,36932,36425 ,20579,20578,20579 ,0,0,0}, - {36425,38338,38321 ,20579,20580,20579 ,0,0,0}, {38338,36425,36422 ,20580,20579,20580 ,0,0,0}, - {38612,36422,37055 ,20240,20580,20240 ,0,0,0}, {36928,37912,37918 ,20576,20578,20576 ,0,0,0}, - {36429,36926,37922 ,20581,20577,20577 ,0,0,0}, {36930,36429,37905 ,20582,20581,20581 ,0,0,0}, - {37922,37905,36429 ,20577,20581,20581 ,0,0,0}, {37923,36460,36930 ,20582,20583,20582 ,0,0,0}, - {36930,37905,37923 ,20582,20581,20582 ,0,0,0}, {36460,38495,36448 ,20583,20583,20584 ,0,0,0}, - {38495,36460,37923 ,20583,20583,20582 ,0,0,0}, {38495,37919,36448 ,20583,324,20584 ,0,0,0}, - {38232,38233,37046 ,20585,20586,20586 ,0,0,0}, {37915,36454,36455 ,20587,20585,20587 ,0,0,0}, - {36454,38232,37046 ,20585,20585,20586 ,0,0,0}, {37915,36455,37916 ,20587,20587,20588 ,0,0,0}, - {36462,38492,38491 ,20589,20590,20589 ,0,0,0}, {37916,36455,36461 ,20588,20587,20588 ,0,0,0}, - {36461,38491,37916 ,20588,20589,20588 ,0,0,0}, {38491,36461,36462 ,20589,20588,20589 ,0,0,0}, - {38492,36462,36449 ,20590,20589,20591 ,0,0,0}, {36454,37915,38232 ,20585,20587,20585 ,0,0,0}, - {37045,37046,38233 ,20592,20586,20586 ,0,0,0}, {36445,37045,38234 ,20593,20592,20592 ,0,0,0}, - {38233,38234,37045 ,20586,20592,20592 ,0,0,0}, {37884,36453,36445 ,20593,20594,20593 ,0,0,0}, - {36445,38234,37884 ,20593,20592,20593 ,0,0,0}, {36453,37883,36447 ,20594,20594,20302 ,0,0,0}, - {37883,36453,37884 ,20594,20594,20593 ,0,0,0}, {37883,37882,36447 ,20594,20302,20302 ,0,0,0}, - {38051,38030,36206 ,20595,20596,20596 ,0,0,0}, {38051,36206,36205 ,20595,20596,20595 ,0,0,0}, - {37947,36205,36757 ,20597,20595,20597 ,0,0,0}, {36757,36758,38029 ,20597,20598,20598 ,0,0,0}, - {38029,37947,36757 ,20598,20597,20597 ,0,0,0}, {38051,36205,37947 ,20595,20595,20597 ,0,0,0}, - {38053,38029,36758 ,20599,20598,20598 ,0,0,0}, {38053,36759,38052 ,20599,20599,20600 ,0,0,0}, - {37139,37948,38052 ,20600,20601,20600 ,0,0,0}, {38053,36758,36759 ,20599,20598,20599 ,0,0,0}, - {37139,36199,37948 ,20600,20602,20601 ,0,0,0}, {37139,38052,36759 ,20600,20600,20599 ,0,0,0}, - {38030,37952,36211 ,20596,20603,20603 ,0,0,0}, {36211,36206,38030 ,20603,20596,20596 ,0,0,0}, - {36217,37952,37950 ,20604,20603,20604 ,0,0,0}, {37952,36217,36211 ,20603,20604,20603 ,0,0,0}, - {37949,36214,37950 ,20605,20605,20604 ,0,0,0}, {36217,37950,36214 ,20604,20604,20605 ,0,0,0}, - {37949,37470,36192 ,20605,20606,20606 ,0,0,0}, {36192,36214,37949 ,20606,20605,20605 ,0,0,0}, - {36193,37470,37469 ,20607,20606,20607 ,0,0,0}, {37470,36193,36192 ,20606,20607,20606 ,0,0,0}, - {36193,37469,36292 ,20607,20607,20608 ,0,0,0}, {36292,37469,37957 ,20608,20607,20609 ,0,0,0}, - {37926,37928,36347 ,20610,2038,2038 ,0,0,0}, {37926,36347,36346 ,20610,2038,20610 ,0,0,0}, - {37809,36346,36344 ,20611,20610,20611 ,0,0,0}, {36344,36343,37814 ,20611,20612,20612 ,0,0,0}, - {37814,37809,36344 ,20612,20611,20611 ,0,0,0}, {37926,36346,37809 ,20610,20610,20611 ,0,0,0}, - {37798,37814,36343 ,20613,20612,20612 ,0,0,0}, {37798,36331,37799 ,20613,20613,20614 ,0,0,0}, - {36348,37815,37799 ,20614,20615,20614 ,0,0,0}, {37798,36343,36331 ,20613,20612,20613 ,0,0,0}, - {36348,36352,37815 ,20614,20616,20615 ,0,0,0}, {36348,37799,36331 ,20614,20614,20613 ,0,0,0}, - {37928,38354,36859 ,2038,20617,20617 ,0,0,0}, {36859,36347,37928 ,20617,2038,2038 ,0,0,0}, - {36816,38354,38355 ,20618,20617,20618 ,0,0,0}, {38354,36816,36859 ,20617,20618,20617 ,0,0,0}, - {38427,36835,38355 ,20619,20619,20618 ,0,0,0}, {36816,38355,36835 ,20618,20618,20619 ,0,0,0}, - {38427,38428,36815 ,20619,20620,20620 ,0,0,0}, {36815,36835,38427 ,20620,20619,20619 ,0,0,0}, - {36466,38428,38429 ,20621,20620,20621 ,0,0,0}, {38428,36466,36815 ,20620,20621,20620 ,0,0,0}, - {36466,38429,36341 ,20621,20621,20622 ,0,0,0}, {36341,38429,37801 ,20622,20621,20623 ,0,0,0}, - {38079,37494,36628 ,20624,20625,20625 ,0,0,0}, {38079,36628,37148 ,20624,20625,20624 ,0,0,0}, - {37774,37148,37126 ,20626,20624,20626 ,0,0,0}, {37126,37117,37772 ,20626,2040,2040 ,0,0,0}, - {37772,37774,37126 ,2040,20626,20626 ,0,0,0}, {38079,37148,37774 ,20624,20624,20626 ,0,0,0}, - {38155,37772,37117 ,20627,2040,2040 ,0,0,0}, {38155,37118,38090 ,20627,20627,20628 ,0,0,0}, - {37119,38167,38090 ,20628,20629,20628 ,0,0,0}, {38155,37117,37118 ,20627,2040,20627 ,0,0,0}, - {37119,36494,38167 ,20628,20629,20629 ,0,0,0}, {37119,38090,37118 ,20628,20628,20627 ,0,0,0}, - {37494,37675,36626 ,20625,20630,20630 ,0,0,0}, {36626,36628,37494 ,20630,20625,20625 ,0,0,0}, - {36515,37675,37673 ,20631,20630,20631 ,0,0,0}, {37675,36515,36626 ,20630,20631,20630 ,0,0,0}, - {37672,36521,37673 ,20632,20632,20631 ,0,0,0}, {36515,37673,36521 ,20631,20631,20632 ,0,0,0}, - {37672,37677,36522 ,20632,20633,20633 ,0,0,0}, {36522,36521,37672 ,20633,20632,20632 ,0,0,0}, - {36525,37677,37678 ,20634,20633,20634 ,0,0,0}, {37677,36525,36522 ,20633,20634,20633 ,0,0,0}, - {36525,37678,36526 ,20634,20634,20635 ,0,0,0}, {36526,37678,37681 ,20635,20634,20636 ,0,0,0}, - {37771,37674,36627 ,20637,20638,20638 ,0,0,0}, {37771,36627,36517 ,20637,20638,20637 ,0,0,0}, - {37671,36517,36516 ,20639,20637,20639 ,0,0,0}, {36516,36523,37676 ,20639,20640,20640 ,0,0,0}, - {37676,37671,36516 ,20640,20639,20639 ,0,0,0}, {37771,36517,37671 ,20637,20637,20639 ,0,0,0}, - {37679,37676,36523 ,20641,20640,20640 ,0,0,0}, {37679,36524,37680 ,20641,20641,20642 ,0,0,0}, - {36527,37750,37680 ,20642,20643,20642 ,0,0,0}, {37679,36523,36524 ,20641,20640,20641 ,0,0,0}, - {36527,36528,37750 ,20642,20644,20643 ,0,0,0}, {36527,37680,36524 ,20642,20642,20641 ,0,0,0}, - {37674,38450,36519 ,20638,20645,20646 ,0,0,0}, {36519,36627,37674 ,20646,20638,20638 ,0,0,0}, - {36473,38450,38383 ,20647,20645,20647 ,0,0,0}, {38450,36473,36519 ,20645,20647,20646 ,0,0,0}, - {38378,36802,38383 ,20648,20648,20647 ,0,0,0}, {36473,38383,36802 ,20647,20647,20648 ,0,0,0}, - {38378,38379,36803 ,20648,20649,20649 ,0,0,0}, {36803,36802,38378 ,20649,20648,20648 ,0,0,0}, - {36800,38379,38381 ,20650,20649,20650 ,0,0,0}, {38379,36800,36803 ,20649,20650,20649 ,0,0,0}, - {36800,38381,36792 ,20650,20650,324 ,0,0,0}, {36792,38381,37661 ,324,20650,20651 ,0,0,0}, - {38103,37492,36742 ,20652,20653,20653 ,0,0,0}, {38103,36742,37090 ,20652,20653,20652 ,0,0,0}, - {37620,37090,37191 ,20654,20652,20654 ,0,0,0}, {37191,37192,38037 ,20654,20655,20655 ,0,0,0}, - {38037,37620,37191 ,20655,20654,20654 ,0,0,0}, {38103,37090,37620 ,20652,20652,20654 ,0,0,0}, - {37629,38037,37192 ,20656,20655,20655 ,0,0,0}, {37629,37092,37625 ,20656,20656,20657 ,0,0,0}, - {36654,37626,37625 ,20657,20658,20657 ,0,0,0}, {37629,37192,37092 ,20656,20655,20656 ,0,0,0}, - {36654,36653,37626 ,20657,20658,20658 ,0,0,0}, {36654,37625,37092 ,20657,20657,20656 ,0,0,0}, - {37492,37491,36673 ,20653,20659,20659 ,0,0,0}, {36673,36742,37492 ,20659,20653,20653 ,0,0,0}, - {36671,37491,37498 ,20660,20659,20660 ,0,0,0}, {37491,36671,36673 ,20659,20660,20659 ,0,0,0}, - {37497,36675,37498 ,20661,20661,20660 ,0,0,0}, {36671,37498,36675 ,20660,20660,20661 ,0,0,0}, - {37497,37503,36179 ,20661,20662,20662 ,0,0,0}, {36179,36675,37497 ,20662,20661,20661 ,0,0,0}, - {36674,37503,37506 ,20663,20662,20663 ,0,0,0}, {37503,36674,36179 ,20662,20663,20662 ,0,0,0}, - {36674,37506,36676 ,20663,20663,324 ,0,0,0}, {36676,37506,37599 ,324,20663,20664 ,0,0,0}, - {38080,37927,36345 ,20665,20666,20666 ,0,0,0}, {38080,36345,36861 ,20665,20666,20665 ,0,0,0}, - {37812,36861,36819 ,20667,20665,20667 ,0,0,0}, {36819,36863,37635 ,20667,20668,20668 ,0,0,0}, - {37635,37812,36819 ,20668,20667,20667 ,0,0,0}, {38080,36861,37812 ,20665,20665,20667 ,0,0,0}, - {37633,37635,36863 ,20669,20668,20668 ,0,0,0}, {37633,36318,37910 ,20669,20669,20670 ,0,0,0}, - {36865,37807,37910 ,20670,20671,20670 ,0,0,0}, {37633,36863,36318 ,20669,20668,20669 ,0,0,0}, - {36865,36337,37807 ,20670,20672,20671 ,0,0,0}, {36865,37910,36318 ,20670,20670,20669 ,0,0,0}, - {37927,37808,36465 ,20666,20673,20673 ,0,0,0}, {36465,36345,37927 ,20673,20666,20666 ,0,0,0}, - {36342,37808,37810 ,20674,20673,20674 ,0,0,0}, {37808,36342,36465 ,20673,20674,20673 ,0,0,0}, - {37813,36332,37810 ,20675,20675,20674 ,0,0,0}, {36342,37810,36332 ,20674,20674,20675 ,0,0,0}, - {37813,37797,36333 ,20675,20676,20676 ,0,0,0}, {36333,36332,37813 ,20676,20675,20675 ,0,0,0}, - {36349,37797,37816 ,20677,20676,20677 ,0,0,0}, {37797,36349,36333 ,20676,20677,20676 ,0,0,0}, - {36349,37816,36443 ,20677,20677,20678 ,0,0,0}, {36443,37816,37817 ,20678,20677,20679 ,0,0,0}, - {37953,37942,36210 ,20680,20681,20681 ,0,0,0}, {37953,36210,36212 ,20680,20681,20680 ,0,0,0}, - {37951,36212,36216 ,20682,20680,20682 ,0,0,0}, {36216,36215,37955 ,20682,20683,20683 ,0,0,0}, - {37955,37951,36216 ,20683,20682,20682 ,0,0,0}, {37953,36212,37951 ,20680,20680,20682 ,0,0,0}, - {37468,37955,36215 ,20684,20683,20683 ,0,0,0}, {37468,36191,37954 ,20684,20684,20685 ,0,0,0}, - {36218,37956,37954 ,20685,20686,20685 ,0,0,0}, {37468,36215,36191 ,20684,20683,20684 ,0,0,0}, - {36218,36293,37956 ,20685,82,20686 ,0,0,0}, {36218,37954,36191 ,20685,20685,20684 ,0,0,0}, - {37942,37943,36209 ,20681,20687,20687 ,0,0,0}, {36209,36210,37942 ,20687,20681,20681 ,0,0,0}, - {36750,37943,38118 ,20688,20687,20688 ,0,0,0}, {37943,36750,36209 ,20687,20688,20687 ,0,0,0}, - {37945,36753,38118 ,20689,20689,20688 ,0,0,0}, {36750,38118,36753 ,20688,20688,20689 ,0,0,0}, - {37945,37944,36834 ,20689,20690,20690 ,0,0,0}, {36834,36753,37945 ,20690,20689,20689 ,0,0,0}, - {36756,37944,38418 ,20691,20690,20691 ,0,0,0}, {37944,36756,36834 ,20690,20691,20690 ,0,0,0}, - {36756,38418,36833 ,20691,20691,20692 ,0,0,0}, {36833,38418,38132 ,20692,20691,20693 ,0,0,0}, - {37493,37621,36745 ,20694,20695,20695 ,0,0,0}, {37493,36745,36672 ,20694,20695,20694 ,0,0,0}, - {37500,36672,36670 ,20696,20694,20696 ,0,0,0}, {36670,36669,37499 ,20696,20697,20697 ,0,0,0}, - {37499,37500,36670 ,20697,20696,20696 ,0,0,0}, {37493,36672,37500 ,20694,20694,20696 ,0,0,0}, - {37501,37499,36669 ,20698,20697,20697 ,0,0,0}, {37501,36178,37502 ,20698,20698,20699 ,0,0,0}, - {36180,37598,37502 ,20699,20700,20699 ,0,0,0}, {37501,36669,36178 ,20698,20697,20698 ,0,0,0}, - {36180,36677,37598 ,20699,21,20700 ,0,0,0}, {36180,37502,36178 ,20699,20699,20698 ,0,0,0}, - {37621,38035,36512 ,20695,20701,20701 ,0,0,0}, {36512,36745,37621 ,20701,20695,20695 ,0,0,0}, - {36665,38035,38034 ,20702,20701,20702 ,0,0,0}, {38035,36665,36512 ,20701,20702,20701 ,0,0,0}, - {38107,36743,38034 ,20703,20703,20702 ,0,0,0}, {36665,38034,36743 ,20702,20702,20703 ,0,0,0}, - {38107,37465,36636 ,20703,20704,20704 ,0,0,0}, {36636,36743,38107 ,20704,20703,20703 ,0,0,0}, - {36667,37465,38109 ,20705,20704,20705 ,0,0,0}, {37465,36667,36636 ,20704,20705,20704 ,0,0,0}, - {36667,38109,36182 ,20705,20705,126 ,0,0,0}, {36182,38109,37488 ,126,20705,20706 ,0,0,0}, - {35960,38003,36287 ,8396,20707,7586 ,0,0,0}, {38191,36232,37993 ,20708,20709,20710 ,0,0,0}, - {36239,36282,38557 ,20711,20712,20713 ,0,0,0}, {36886,38560,36889 ,20714,20715,20716 ,0,0,0}, - {38543,38558,36284 ,4334,20717,20718 ,0,0,0}, {38012,36892,38535 ,20719,20720,20721 ,0,0,0}, - {36291,36290,38008 ,20722,20723,20724 ,0,0,0}, {36899,37223,38534 ,20725,20726,20727 ,0,0,0}, - {36885,38182,37223 ,20728,20729,20726 ,0,0,0}, {36272,37536,37537 ,20730,20731,20732 ,0,0,0}, - {36899,38004,36897 ,20725,20733,20734 ,0,0,0}, {38536,36273,37537 ,20735,20736,20732 ,0,0,0}, - {36272,37537,36273 ,20730,20732,20736 ,0,0,0}, {38536,38211,36274 ,20735,20737,20738 ,0,0,0}, - {36274,36273,38536 ,20738,20736,20735 ,0,0,0}, {37264,38211,37975 ,20739,20737,20740 ,0,0,0}, - {38211,37264,36274 ,20737,20739,20738 ,0,0,0}, {37974,36906,37975 ,20741,20742,20740 ,0,0,0}, - {37264,37975,36906 ,20739,20740,20742 ,0,0,0}, {37974,35979,35980 ,20741,4091,763 ,0,0,0}, - {35980,36906,37974 ,763,20742,20741 ,0,0,0}, {38534,37223,38182 ,20727,20726,20729 ,0,0,0}, - {37536,36897,38004 ,20731,20734,20733 ,0,0,0}, {36897,37536,36272 ,20734,20731,20730 ,0,0,0}, - {38534,38004,36899 ,20727,20733,20725 ,0,0,0}, {38012,38182,36885 ,20719,20729,20728 ,0,0,0}, - {36291,38008,38535 ,20722,20724,20721 ,0,0,0}, {36291,38535,36892 ,20722,20721,20720 ,0,0,0}, - {36885,36892,38012 ,20728,20720,20719 ,0,0,0}, {36290,38009,38008 ,20723,20743,20724 ,0,0,0}, - {38009,36290,36889 ,20743,20723,20716 ,0,0,0}, {38558,38560,36886 ,20717,20715,20714 ,0,0,0}, - {38560,38009,36889 ,20715,20743,20716 ,0,0,0}, {36284,38558,36886 ,20718,20717,20714 ,0,0,0}, - {36283,38191,38543 ,20744,20708,4334 ,0,0,0}, {36283,38543,36284 ,20744,4334,20718 ,0,0,0}, - {36232,36239,37993 ,20709,20711,20710 ,0,0,0}, {36283,36232,38191 ,20744,20709,20708 ,0,0,0}, - {36282,38003,38557 ,20712,20707,20713 ,0,0,0}, {37993,36239,38557 ,20710,20711,20713 ,0,0,0}, - {35960,36287,35958 ,8396,7586,9510 ,0,0,0}, {38003,36282,36287 ,20707,20712,7586 ,0,0,0}, - {35916,38230,36451 ,3370,20745,20746 ,0,0,0}, {37903,37052,38226 ,20747,20748,20749 ,0,0,0}, - {36433,36452,38227 ,20750,20751,20752 ,0,0,0}, {37332,38605,37048 ,20753,20754,20755 ,0,0,0}, - {37835,37836,36427 ,20756,20757,20758 ,0,0,0}, {37848,37050,37897 ,20759,20760,20761 ,0,0,0}, - {37049,36435,37839 ,20762,20763,20764 ,0,0,0}, {36942,37333,38614 ,20765,20766,20767 ,0,0,0}, - {36417,37895,37333 ,20768,20769,20766 ,0,0,0}, {37335,37888,37887 ,20770,20771,20772 ,0,0,0}, - {36942,37892,36940 ,20765,20773,20774 ,0,0,0}, {38615,36356,37887 ,20775,20776,20772 ,0,0,0}, - {37335,37887,36356 ,20770,20772,20776 ,0,0,0}, {38615,37824,36357 ,20775,20777,20778 ,0,0,0}, - {36357,36356,38615 ,20778,20776,20775 ,0,0,0}, {36953,37824,37823 ,20779,20777,20780 ,0,0,0}, - {37824,36953,36357 ,20777,20779,20778 ,0,0,0}, {37860,36912,37823 ,20781,20782,20780 ,0,0,0}, - {36953,37823,36912 ,20779,20780,20782 ,0,0,0}, {37860,35935,35936 ,20781,2614,126 ,0,0,0}, - {35936,36912,37860 ,126,20782,20781 ,0,0,0}, {38614,37333,37895 ,20767,20766,20769 ,0,0,0}, - {37888,36940,37892 ,20771,20774,20773 ,0,0,0}, {36940,37888,37335 ,20774,20771,20770 ,0,0,0}, - {38614,37892,36942 ,20767,20773,20765 ,0,0,0}, {37848,37895,36417 ,20759,20769,20768 ,0,0,0}, - {37049,37839,37897 ,20762,20764,20761 ,0,0,0}, {37049,37897,37050 ,20762,20761,20760 ,0,0,0}, - {36417,37050,37848 ,20768,20760,20759 ,0,0,0}, {36435,37840,37839 ,20763,20783,20764 ,0,0,0}, - {37840,36435,37048 ,20783,20763,20755 ,0,0,0}, {37836,38605,37332 ,20757,20754,20753 ,0,0,0}, - {38605,37840,37048 ,20754,20783,20755 ,0,0,0}, {36427,37836,37332 ,20758,20757,20753 ,0,0,0}, - {36431,37903,37835 ,20784,20747,20756 ,0,0,0}, {36431,37835,36427 ,20784,20756,20758 ,0,0,0}, - {37052,36433,38226 ,20748,20750,20749 ,0,0,0}, {36431,37052,37903 ,20784,20748,20747 ,0,0,0}, - {36452,38230,38227 ,20751,20745,20752 ,0,0,0}, {38226,36433,38227 ,20749,20750,20752 ,0,0,0}, - {35916,36451,35914 ,3370,20746,82 ,0,0,0}, {38230,36452,36451 ,20745,20751,20746 ,0,0,0}, - {35872,37699,37352 ,20785,20786,20787 ,0,0,0}, {37707,37355,37706 ,20788,20789,20790 ,0,0,0}, - {36583,36582,38639 ,20791,20792,20793 ,0,0,0}, {36534,37702,36573 ,20794,20795,7595 ,0,0,0}, - {37710,37701,36533 ,20796,4333,20797 ,0,0,0}, {37716,36578,37719 ,20798,20799,20721 ,0,0,0}, - {36577,36536,37714 ,20800,20801,20802 ,0,0,0}, {37369,37366,38662 ,20803,20804,20805 ,0,0,0}, - {36964,37694,37366 ,20806,20807,20804 ,0,0,0}, {37368,37682,37729 ,20808,20809,20810 ,0,0,0}, - {37369,37726,37367 ,20803,20811,20812 ,0,0,0}, {38664,36601,37729 ,20813,20814,20810 ,0,0,0}, - {37368,37729,36601 ,20808,20810,20814 ,0,0,0}, {38664,38281,36602 ,20813,20815,20816 ,0,0,0}, - {36602,36601,38664 ,20816,20814,20813 ,0,0,0}, {37384,38281,37739 ,20817,20815,20818 ,0,0,0}, - {38281,37384,36602 ,20815,20817,20816 ,0,0,0}, {37740,36603,37739 ,20819,20820,20818 ,0,0,0}, - {37384,37739,36603 ,20817,20818,20820 ,0,0,0}, {37740,35891,35892 ,20819,126,4090 ,0,0,0}, - {35892,36603,37740 ,4090,20820,20819 ,0,0,0}, {38662,37366,37694 ,20805,20804,20807 ,0,0,0}, - {37682,37367,37726 ,20809,20812,20811 ,0,0,0}, {37367,37682,37368 ,20812,20809,20808 ,0,0,0}, - {38662,37726,37369 ,20805,20811,20803 ,0,0,0}, {37716,37694,36964 ,20798,20807,20806 ,0,0,0}, - {36577,37714,37719 ,20800,20802,20721 ,0,0,0}, {36577,37719,36578 ,20800,20721,20799 ,0,0,0}, - {36964,36578,37716 ,20806,20799,20798 ,0,0,0}, {36536,37713,37714 ,20801,20821,20802 ,0,0,0}, - {37713,36536,36573 ,20821,20801,7595 ,0,0,0}, {37701,37702,36534 ,4333,20795,20794 ,0,0,0}, - {37702,37713,36573 ,20795,20821,7595 ,0,0,0}, {36533,37701,36534 ,20797,4333,20794 ,0,0,0}, - {36569,37707,37710 ,20822,20788,20796 ,0,0,0}, {36569,37710,36533 ,20822,20796,20797 ,0,0,0}, - {37355,36583,37706 ,20789,20791,20790 ,0,0,0}, {36569,37355,37707 ,20822,20789,20788 ,0,0,0}, - {36582,37699,38639 ,20792,20786,20793 ,0,0,0}, {37706,36583,38639 ,20790,20791,20793 ,0,0,0}, - {35872,37352,35870 ,20785,20787,878 ,0,0,0}, {37699,36582,37352 ,20786,20792,20787 ,0,0,0}, - {35828,37508,37425 ,2602,20745,20746 ,0,0,0}, {37554,36598,37519 ,20823,20824,20749 ,0,0,0}, - {36185,36187,38705 ,20750,20825,20826 ,0,0,0}, {36688,38709,36691 ,20827,20754,20755 ,0,0,0}, - {38696,38706,36686 ,20828,20829,20830 ,0,0,0}, {37544,36261,37545 ,20831,20832,20833 ,0,0,0}, - {36256,36255,37564 ,20834,20835,20836 ,0,0,0}, {36252,37018,38688 ,20837,20838,20839 ,0,0,0}, - {36996,37522,37018 ,20840,20841,20838 ,0,0,0}, {36245,37542,37606 ,20842,20843,20844 ,0,0,0}, - {36252,37540,36250 ,20837,20845,20846 ,0,0,0}, {38690,36189,37606 ,20847,20848,20844 ,0,0,0}, - {36245,37606,36189 ,20842,20844,20848 ,0,0,0}, {38690,37603,36190 ,20847,20849,20850 ,0,0,0}, - {36190,36189,38690 ,20850,20848,20847 ,0,0,0}, {36719,37603,37604 ,20851,20849,20852 ,0,0,0}, - {37603,36719,36190 ,20849,20851,20850 ,0,0,0}, {38319,36717,37604 ,20853,20854,20852 ,0,0,0}, - {36719,37604,36717 ,20851,20852,20854 ,0,0,0}, {38319,35847,35848 ,20853,3345,126 ,0,0,0}, - {35848,36717,38319 ,126,20854,20853 ,0,0,0}, {38688,37018,37522 ,20839,20838,20841 ,0,0,0}, - {37542,36250,37540 ,20843,20846,20845 ,0,0,0}, {36250,37542,36245 ,20846,20843,20842 ,0,0,0}, - {38688,37540,36252 ,20839,20845,20837 ,0,0,0}, {37544,37522,36996 ,20831,20841,20840 ,0,0,0}, - {36256,37564,37545 ,20834,20836,20833 ,0,0,0}, {36256,37545,36261 ,20834,20833,20832 ,0,0,0}, - {36996,36261,37544 ,20840,20832,20831 ,0,0,0}, {36255,37565,37564 ,20835,20783,20836 ,0,0,0}, - {37565,36255,36691 ,20783,20835,20755 ,0,0,0}, {38706,38709,36688 ,20829,20754,20827 ,0,0,0}, - {38709,37565,36691 ,20754,20783,20755 ,0,0,0}, {36686,38706,36688 ,20830,20829,20827 ,0,0,0}, - {36687,37554,38696 ,20855,20823,20828 ,0,0,0}, {36687,38696,36686 ,20855,20828,20830 ,0,0,0}, - {36598,36185,37519 ,20824,20750,20749 ,0,0,0}, {36687,36598,37554 ,20855,20824,20823 ,0,0,0}, - {36187,37508,38705 ,20825,20745,20826 ,0,0,0}, {37519,36185,38705 ,20749,20750,20826 ,0,0,0}, - {35828,37425,35826 ,2602,20746,82 ,0,0,0}, {37508,36187,37425 ,20745,20825,20746 ,0,0,0}, - {37913,36450,37914 ,20856,20857,18583 ,0,0,0}, {37913,35790,36450 ,20856,18588,20857 ,0,0,0}, - {35790,37913,35789 ,18588,20856,18588 ,0,0,0}, {36456,37914,36450 ,18583,18583,20857 ,0,0,0}, - {35797,38237,36440 ,18609,20858,20858 ,0,0,0}, {38236,37044,38240 ,20859,20859,20860 ,0,0,0}, - {36446,37062,38239 ,20860,20861,20861 ,0,0,0}, {38235,36456,36457 ,20862,18583,20862 ,0,0,0}, - {36457,38236,38235 ,20862,20859,20862 ,0,0,0}, {37914,36456,38235 ,18583,18583,20862 ,0,0,0}, - {36457,37044,38236 ,20862,20859,20859 ,0,0,0}, {36446,38240,37044 ,20860,20860,20859 ,0,0,0}, - {38240,36446,38239 ,20860,20860,20861 ,0,0,0}, {36440,35798,35797 ,20858,18609,18609 ,0,0,0}, - {38237,37062,36440 ,20858,20861,20858 ,0,0,0}, {38239,37062,38237 ,20861,20861,20858 ,0,0,0}, - {37901,35803,36439 ,20863,18594,20864 ,0,0,0}, {35803,35804,36439 ,18594,18594,20864 ,0,0,0}, - {36438,37901,36439 ,18575,20863,20864 ,0,0,0}, {37901,36438,38231 ,20863,18575,18575 ,0,0,0}, - {35783,38601,36933 ,18601,20865,20865 ,0,0,0}, {38225,36434,37908 ,20866,20866,20867 ,0,0,0}, - {36424,36426,37907 ,20867,20868,20868 ,0,0,0}, {38228,36438,36432 ,20869,18575,20869 ,0,0,0}, - {36432,38225,38228 ,20869,20866,20869 ,0,0,0}, {38231,36438,38228 ,18575,18575,20869 ,0,0,0}, - {36432,36434,38225 ,20869,20866,20866 ,0,0,0}, {36424,37908,36434 ,20867,20867,20866 ,0,0,0}, - {37908,36424,37907 ,20867,20867,20868 ,0,0,0}, {36933,35784,35783 ,20865,18601,18601 ,0,0,0}, - {38601,36426,36933 ,20865,20868,20865 ,0,0,0}, {37907,36426,38601 ,20868,20868,20865 ,0,0,0}, - {35761,36770,38046 ,20870,17362,20871 ,0,0,0}, {38043,38044,36772 ,20872,20873,20874 ,0,0,0}, - {37946,37467,36771 ,20875,20876,20877 ,0,0,0}, {37489,36777,38038 ,20878,20879,20880 ,0,0,0}, - {36773,36778,37490 ,20881,20882,20883 ,0,0,0}, {36775,36780,37479 ,20884,20885,20886 ,0,0,0}, - {36775,38042,36776 ,20884,20887,20888 ,0,0,0}, {36779,36194,37482 ,20889,20890,20891 ,0,0,0}, - {37482,37480,36779 ,20891,20892,20889 ,0,0,0}, {37478,36194,36196 ,20893,20890,20894 ,0,0,0}, - {36194,37478,37482 ,20890,20893,20891 ,0,0,0}, {36202,37463,36196 ,20895,20896,20894 ,0,0,0}, - {37478,36196,37463 ,20893,20894,20896 ,0,0,0}, {36202,35775,35776 ,20895,20897,82 ,0,0,0}, - {35776,37463,36202 ,82,20896,20895 ,0,0,0}, {36777,37489,36778 ,20879,20878,20882 ,0,0,0}, - {36780,37480,37479 ,20885,20892,20886 ,0,0,0}, {36779,37480,36780 ,20889,20892,20885 ,0,0,0}, - {36772,38044,36774 ,20874,20873,20898 ,0,0,0}, {36776,38042,38038 ,20888,20887,20880 ,0,0,0}, - {36775,37479,38042 ,20884,20886,20887 ,0,0,0}, {36777,36776,38038 ,20879,20888,20880 ,0,0,0}, - {37490,36778,37489 ,20883,20882,20878 ,0,0,0}, {38043,36772,36773 ,20872,20874,20881 ,0,0,0}, - {36773,37490,38043 ,20881,20883,20872 ,0,0,0}, {37467,36770,36771 ,20876,17362,20877 ,0,0,0}, - {36774,37946,36771 ,20898,20875,20877 ,0,0,0}, {38044,37946,36774 ,20873,20875,20898 ,0,0,0}, - {35761,38046,35762 ,20870,20871,8371 ,0,0,0}, {36770,37467,38046 ,17362,20876,20871 ,0,0,0}, - {35729,36326,38343 ,66,17362,20899 ,0,0,0}, {37669,38139,36328 ,20900,20901,20902 ,0,0,0}, - {38054,38056,36325 ,20875,20903,20877 ,0,0,0}, {38138,36335,38057 ,20904,20905,20906 ,0,0,0}, - {37071,36334,37670 ,20907,20908,20909 ,0,0,0}, {36820,37070,38136 ,20910,20911,20912 ,0,0,0}, - {36820,38342,37069 ,20910,20913,20914 ,0,0,0}, {36823,36821,38133 ,20915,20916,20917 ,0,0,0}, - {38133,38137,36823 ,20917,20918,20915 ,0,0,0}, {38134,36821,36822 ,20919,20916,20920 ,0,0,0}, - {36821,38134,38133 ,20916,20919,20917 ,0,0,0}, {36824,38135,36822 ,20921,20922,20920 ,0,0,0}, - {38134,36822,38135 ,20919,20920,20922 ,0,0,0}, {36824,35743,35744 ,20921,20923,82 ,0,0,0}, - {35744,38135,36824 ,82,20922,20921 ,0,0,0}, {36335,38138,36334 ,20905,20904,20908 ,0,0,0}, - {37070,38137,38136 ,20911,20918,20912 ,0,0,0}, {36823,38137,37070 ,20915,20918,20911 ,0,0,0}, - {36328,38139,36329 ,20902,20901,20924 ,0,0,0}, {37069,38342,38057 ,20914,20913,20906 ,0,0,0}, - {36820,38136,38342 ,20910,20912,20913 ,0,0,0}, {36335,37069,38057 ,20905,20914,20906 ,0,0,0}, - {37670,36334,38138 ,20909,20908,20904 ,0,0,0}, {37669,36328,37071 ,20900,20902,20907 ,0,0,0}, - {37071,37670,37669 ,20907,20909,20900 ,0,0,0}, {38056,36326,36325 ,20903,17362,20877 ,0,0,0}, - {36329,38054,36325 ,20924,20875,20877 ,0,0,0}, {38139,38054,36329 ,20901,20875,20924 ,0,0,0}, - {35729,38343,35730 ,66,20899,126 ,0,0,0}, {36326,38056,38343 ,17362,20903,20899 ,0,0,0}, - {35697,36482,37785 ,66,17362,20899 ,0,0,0}, {37791,37790,36491 ,20900,20925,20926 ,0,0,0}, - {37806,37786,36484 ,20927,20903,20928 ,0,0,0}, {38357,36504,37788 ,20929,20930,20931 ,0,0,0}, - {36493,37081,37793 ,20932,20933,20934 ,0,0,0}, {36500,36489,38347 ,20910,20935,20936 ,0,0,0}, - {36500,38349,36503 ,20910,20937,20938 ,0,0,0}, {36488,36502,38362 ,20939,20940,20941 ,0,0,0}, - {38362,38360,36488 ,20941,20942,20939 ,0,0,0}, {38361,36502,36501 ,20943,20940,20944 ,0,0,0}, - {36502,38361,38362 ,20940,20943,20941 ,0,0,0}, {36498,38364,36501 ,20945,20946,20944 ,0,0,0}, - {38361,36501,38364 ,20943,20944,20946 ,0,0,0}, {36498,35711,35712 ,20945,20923,82 ,0,0,0}, - {35712,38364,36498 ,82,20946,20945 ,0,0,0}, {36504,38357,37081 ,20930,20929,20933 ,0,0,0}, - {36489,38360,38347 ,20935,20942,20936 ,0,0,0}, {36488,38360,36489 ,20939,20942,20935 ,0,0,0}, - {36491,37790,37083 ,20926,20925,20924 ,0,0,0}, {36503,38349,37788 ,20938,20937,20931 ,0,0,0}, - {36500,38347,38349 ,20910,20936,20937 ,0,0,0}, {36504,36503,37788 ,20930,20938,20931 ,0,0,0}, - {37793,37081,38357 ,20934,20933,20929 ,0,0,0}, {37791,36491,36493 ,20900,20926,20932 ,0,0,0}, - {36493,37793,37791 ,20932,20934,20900 ,0,0,0}, {37786,36482,36484 ,20903,17362,20928 ,0,0,0}, - {37083,37806,36484 ,20924,20927,20928 ,0,0,0}, {37790,37806,37083 ,20925,20927,20924 ,0,0,0}, - {35697,37785,35698 ,66,20899,126 ,0,0,0}, {36482,37786,37785 ,17362,20903,20899 ,0,0,0}, - {35665,37098,37654 ,850,17362,20947 ,0,0,0}, {37637,37644,37095 ,20948,20949,20926 ,0,0,0}, - {37650,37649,37096 ,20950,20903,20928 ,0,0,0}, {37658,36657,37640 ,20951,20952,20953 ,0,0,0}, - {36660,36662,37638 ,20954,20955,20956 ,0,0,0}, {36650,36641,37647 ,20957,20958,20959 ,0,0,0}, - {36650,38375,36656 ,20957,20960,20938 ,0,0,0}, {36640,37086,38377 ,20961,20962,20963 ,0,0,0}, - {38377,37645,36640 ,20963,20964,20961 ,0,0,0}, {37651,37086,36649 ,20965,20962,20966 ,0,0,0}, - {37086,37651,38377 ,20962,20965,20963 ,0,0,0}, {36647,37652,36649 ,20967,20968,20966 ,0,0,0}, - {37651,36649,37652 ,20965,20966,20968 ,0,0,0}, {36647,35679,35680 ,20967,20969,82 ,0,0,0}, - {35680,37652,36647 ,82,20968,20967 ,0,0,0}, {36657,37658,36662 ,20952,20951,20955 ,0,0,0}, - {36641,37645,37647 ,20958,20964,20959 ,0,0,0}, {36640,37645,36641 ,20961,20964,20958 ,0,0,0}, - {37095,37644,37097 ,20926,20949,20924 ,0,0,0}, {36656,38375,37640 ,20938,20960,20953 ,0,0,0}, - {36650,37647,38375 ,20957,20959,20960 ,0,0,0}, {36657,36656,37640 ,20952,20938,20953 ,0,0,0}, - {37638,36662,37658 ,20956,20955,20951 ,0,0,0}, {37637,37095,36660 ,20948,20926,20954 ,0,0,0}, - {36660,37638,37637 ,20954,20956,20948 ,0,0,0}, {37649,37098,37096 ,20903,17362,20928 ,0,0,0}, - {37097,37650,37096 ,20924,20950,20928 ,0,0,0}, {37644,37650,37097 ,20949,20950,20924 ,0,0,0}, - {35665,37654,35666 ,850,20947,126 ,0,0,0}, {37098,37649,37654 ,17362,20903,20947 ,0,0,0}, - {35635,36799,38380 ,8371,17362,20947 ,0,0,0}, {38389,38387,36794 ,20872,20970,20926 ,0,0,0}, - {38386,38385,36798 ,20971,20972,20928 ,0,0,0}, {37659,37113,37660 ,20951,20973,20953 ,0,0,0}, - {36793,37115,38388 ,20932,20955,20934 ,0,0,0}, {37112,37100,38391 ,20884,20974,20975 ,0,0,0}, - {37112,38390,37114 ,20884,20976,20977 ,0,0,0}, {37099,37111,38392 ,20978,20979,20980 ,0,0,0}, - {38392,38393,37099 ,20980,20981,20978 ,0,0,0}, {38394,37111,37108 ,20982,20979,20983 ,0,0,0}, - {37111,38394,38392 ,20979,20982,20980 ,0,0,0}, {37088,38097,37108 ,20984,20985,20983 ,0,0,0}, - {38394,37108,38097 ,20982,20983,20985 ,0,0,0}, {37088,35648,33525 ,20984,20897,82 ,0,0,0}, - {33525,38097,37088 ,82,20985,20984 ,0,0,0}, {37113,37659,37115 ,20973,20951,20955 ,0,0,0}, - {37100,38393,38391 ,20974,20981,20975 ,0,0,0}, {37099,38393,37100 ,20978,20981,20974 ,0,0,0}, - {36794,38387,37116 ,20926,20970,20986 ,0,0,0}, {37114,38390,37660 ,20977,20976,20953 ,0,0,0}, - {37112,38391,38390 ,20884,20975,20976 ,0,0,0}, {37113,37114,37660 ,20973,20977,20953 ,0,0,0}, - {38388,37115,37659 ,20934,20955,20951 ,0,0,0}, {38389,36794,36793 ,20872,20926,20932 ,0,0,0}, - {36793,38388,38389 ,20932,20934,20872 ,0,0,0}, {38385,36799,36798 ,20972,17362,20928 ,0,0,0}, - {37116,38386,36798 ,20986,20971,20928 ,0,0,0}, {38387,38386,37116 ,20970,20971,20986 ,0,0,0}, - {35635,38380,33508 ,8371,20947,126 ,0,0,0}, {36799,38385,38380 ,17362,20972,20947 ,0,0,0}, - {35605,36467,38353 ,18751,17362,20871 ,0,0,0}, {38398,38397,37137 ,20872,20970,20926 ,0,0,0}, - {38408,38407,37138 ,20927,20876,20928 ,0,0,0}, {38411,36496,38410 ,20987,20988,20989 ,0,0,0}, - {37135,37134,38409 ,20932,20990,20991 ,0,0,0}, {37132,37133,38168 ,20992,20993,20994 ,0,0,0}, - {37132,38412,36495 ,20992,20995,20996 ,0,0,0}, {37131,37130,38413 ,20997,20998,20999 ,0,0,0}, - {38413,38166,37131 ,20999,20981,20997 ,0,0,0}, {38091,37130,37129 ,21000,20998,21001 ,0,0,0}, - {37130,38091,38413 ,20998,21000,20999 ,0,0,0}, {37120,38092,37129 ,21002,21003,21001 ,0,0,0}, - {38091,37129,38092 ,21000,21001,21003 ,0,0,0}, {37120,35618,32893 ,21002,21004,82 ,0,0,0}, - {32893,38092,37120 ,82,21003,21002 ,0,0,0}, {36496,38411,37134 ,20988,20987,20990 ,0,0,0}, - {37133,38166,38168 ,20993,20981,20994 ,0,0,0}, {37131,38166,37133 ,20997,20981,20993 ,0,0,0}, - {37137,38397,37136 ,20926,20970,20986 ,0,0,0}, {36495,38412,38410 ,20996,20995,20989 ,0,0,0}, - {37132,38168,38412 ,20992,20994,20995 ,0,0,0}, {36496,36495,38410 ,20988,20996,20989 ,0,0,0}, - {38409,37134,38411 ,20991,20990,20987 ,0,0,0}, {38398,37137,37135 ,20872,20926,20932 ,0,0,0}, - {37135,38409,38398 ,20932,20991,20872 ,0,0,0}, {38407,36467,37138 ,20876,17362,20928 ,0,0,0}, - {37136,38408,37138 ,20986,20927,20928 ,0,0,0}, {38397,38408,37136 ,20970,20927,20986 ,0,0,0}, - {35605,38353,32876 ,18751,20871,126 ,0,0,0}, {36467,38407,38353 ,17362,20876,20871 ,0,0,0}, - {35575,36760,38031 ,8371,17362,20947 ,0,0,0}, {37932,37931,36761 ,20872,21005,20902 ,0,0,0}, - {38033,38032,36203 ,21006,20972,20877 ,0,0,0}, {38414,36762,38416 ,21007,21008,21009 ,0,0,0}, - {36765,36764,38415 ,20907,20882,20909 ,0,0,0}, {36768,36767,38417 ,20884,21010,21011 ,0,0,0}, - {36768,38049,36763 ,20884,21012,21013 ,0,0,0}, {37065,36766,38048 ,21014,21015,21016 ,0,0,0}, - {38048,38341,37065 ,21016,21017,21014 ,0,0,0}, {38047,36766,36769 ,21018,21015,21019 ,0,0,0}, - {36766,38047,38048 ,21015,21018,21016 ,0,0,0}, {37064,38045,36769 ,21020,21021,21019 ,0,0,0}, - {38047,36769,38045 ,21018,21019,21021 ,0,0,0}, {37064,35588,33209 ,21020,20897,82 ,0,0,0}, - {33209,38045,37064 ,82,21021,21020 ,0,0,0}, {36762,38414,36764 ,21008,21007,20882 ,0,0,0}, - {36767,38341,38417 ,21010,21017,21011 ,0,0,0}, {37065,38341,36767 ,21014,21017,21010 ,0,0,0}, - {36761,37931,36204 ,20902,21005,20986 ,0,0,0}, {36763,38049,38416 ,21013,21012,21009 ,0,0,0}, - {36768,38417,38049 ,20884,21011,21012 ,0,0,0}, {36762,36763,38416 ,21008,21013,21009 ,0,0,0}, - {38415,36764,38414 ,20909,20882,21007 ,0,0,0}, {37932,36761,36765 ,20872,20902,20907 ,0,0,0}, - {36765,38415,37932 ,20907,20909,20872 ,0,0,0}, {38032,36760,36203 ,20972,17362,20877 ,0,0,0}, - {36204,38033,36203 ,20986,21006,20877 ,0,0,0}, {37931,38033,36204 ,21005,21006,20986 ,0,0,0}, - {35575,38031,33192 ,8371,20947,126 ,0,0,0}, {36760,38032,38031 ,17362,20972,20947 ,0,0,0}, - {35545,36826,38117 ,18751,17362,20871 ,0,0,0}, {38129,38131,36755 ,20872,21005,20902 ,0,0,0}, - {38128,38127,36828 ,20875,20876,20877 ,0,0,0}, {38124,36829,38123 ,21022,21023,21024 ,0,0,0}, - {37142,36830,38130 ,20907,21025,21026 ,0,0,0}, {37141,37140,38126 ,20992,20885,21027 ,0,0,0}, - {37141,38125,36754 ,20992,21028,21029 ,0,0,0}, {36314,36832,38119 ,21030,21031,21032 ,0,0,0}, - {38119,38122,36314 ,21032,21017,21030 ,0,0,0}, {38120,36832,36831 ,21033,21031,21034 ,0,0,0}, - {36832,38120,38119 ,21031,21033,21032 ,0,0,0}, {36275,38121,36831 ,21035,21036,21034 ,0,0,0}, - {38120,36831,38121 ,21033,21034,21036 ,0,0,0}, {36275,35558,33841 ,21035,21004,82 ,0,0,0}, - {33841,38121,36275 ,82,21036,21035 ,0,0,0}, {36829,38124,36830 ,21023,21022,21025 ,0,0,0}, - {37140,38122,38126 ,20885,21017,21027 ,0,0,0}, {36314,38122,37140 ,21030,21017,20885 ,0,0,0}, - {36755,38131,36827 ,20902,21005,20986 ,0,0,0}, {36754,38125,38123 ,21029,21028,21024 ,0,0,0}, - {37141,38126,38125 ,20992,21027,21028 ,0,0,0}, {36829,36754,38123 ,21023,21029,21024 ,0,0,0}, - {38130,36830,38124 ,21026,21025,21022 ,0,0,0}, {38129,36755,37142 ,20872,20902,20907 ,0,0,0}, - {37142,38130,38129 ,20907,21026,20872 ,0,0,0}, {38127,36826,36828 ,20876,17362,20877 ,0,0,0}, - {36827,38128,36828 ,20986,20875,20877 ,0,0,0}, {38131,38128,36827 ,21005,20875,20986 ,0,0,0}, - {35545,38117,33824 ,18751,20871,126 ,0,0,0}, {36826,38127,38117 ,17362,20876,20871 ,0,0,0}, - {35482,38444,37153 ,21037,21038,21039 ,0,0,0}, {38443,37155,38441 ,21040,21041,21042 ,0,0,0}, - {37154,37152,38164 ,21043,21044,21045 ,0,0,0}, {37165,38158,37198 ,21046,21047,21048 ,0,0,0}, - {37160,38439,37161 ,21049,21050,21051 ,0,0,0}, {37495,37170,38435 ,21052,21053,21054 ,0,0,0}, - {38437,37167,37630 ,21055,21056,21057 ,0,0,0}, {37128,37775,37125 ,21058,21059,21060 ,0,0,0}, - {37174,38078,37149 ,21061,21062,21063 ,0,0,0}, {38382,36796,37776 ,21064,21065,21066 ,0,0,0}, - {36797,37145,37777 ,21067,21068,21069 ,0,0,0}, {36851,37781,36850 ,21070,21071,21072 ,0,0,0}, - {37666,37667,37143 ,21073,21074,21075 ,0,0,0}, {38094,36852,36856 ,21076,21077,21078 ,0,0,0}, - {38420,36854,38171 ,21079,21080,21081 ,0,0,0}, {37079,37078,38144 ,21082,21083,21084 ,0,0,0}, - {36853,38093,38165 ,21085,21086,21087 ,0,0,0}, {36468,38401,38352 ,21088,21089,21090 ,0,0,0}, - {38143,38401,37080 ,21091,21089,21092 ,0,0,0}, {36470,38406,36471 ,21093,21094,21095 ,0,0,0}, - {38432,36470,37175 ,21096,21093,21097 ,0,0,0}, {37176,38404,37177 ,21098,21099,21100 ,0,0,0}, - {38405,37176,36471 ,21101,21098,21095 ,0,0,0}, {38746,38403,37179 ,21102,21103,21104 ,0,0,0}, - {38433,37178,37177 ,21105,21106,21100 ,0,0,0}, {37074,38403,38402 ,21107,21103,21108 ,0,0,0}, - {38403,37074,37179 ,21103,21107,21104 ,0,0,0}, {38395,37075,38402 ,21109,21110,21108 ,0,0,0}, - {37074,38402,37075 ,21107,21108,21110 ,0,0,0}, {38395,38396,37076 ,21109,21111,21112 ,0,0,0}, - {37076,37075,38395 ,21112,21110,21109 ,0,0,0}, {37077,38396,38431 ,21113,21111,21114 ,0,0,0}, - {38396,37077,37076 ,21111,21113,21112 ,0,0,0}, {38430,37180,38431 ,21115,21116,21114 ,0,0,0}, - {37077,38431,37180 ,21113,21114,21116 ,0,0,0}, {38430,38345,36848 ,21115,21117,21118 ,0,0,0}, - {36848,37180,38430 ,21118,21116,21115 ,0,0,0}, {37181,38345,38346 ,21119,21117,21120 ,0,0,0}, - {38345,37181,36848 ,21117,21119,21118 ,0,0,0}, {38351,37182,38346 ,21121,21122,21120 ,0,0,0}, - {37181,38346,37182 ,21119,21120,21122 ,0,0,0}, {38351,38350,37184 ,21121,21123,21124 ,0,0,0}, - {37184,37182,38351 ,21124,21122,21121 ,0,0,0}, {37183,38350,37805 ,21125,21123,21126 ,0,0,0}, - {38350,37183,37184 ,21123,21125,21124 ,0,0,0}, {37804,37185,37805 ,21127,21128,21126 ,0,0,0}, - {37183,37805,37185 ,21125,21126,21128 ,0,0,0}, {37804,35527,35528 ,21127,21129,21129 ,0,0,0}, - {35528,37185,37804 ,21129,21128,21127 ,0,0,0}, {37179,37178,38746 ,21104,21106,21102 ,0,0,0}, - {38433,38746,37178 ,21105,21102,21106 ,0,0,0}, {38404,38433,37177 ,21099,21105,21100 ,0,0,0}, - {38404,37176,38405 ,21099,21098,21101 ,0,0,0}, {38432,38406,36470 ,21096,21094,21093 ,0,0,0}, - {38406,38405,36471 ,21094,21101,21095 ,0,0,0}, {36468,38352,37175 ,21088,21090,21097 ,0,0,0}, - {38432,37175,38352 ,21096,21097,21090 ,0,0,0}, {37079,38143,37080 ,21082,21091,21092 ,0,0,0}, - {37080,38401,36468 ,21092,21089,21088 ,0,0,0}, {37079,38144,38143 ,21082,21084,21091 ,0,0,0}, - {37078,36853,38165 ,21083,21085,21087 ,0,0,0}, {37078,38165,38144 ,21083,21087,21084 ,0,0,0}, - {38093,36852,38094 ,21086,21077,21076 ,0,0,0}, {36853,36852,38093 ,21085,21077,21086 ,0,0,0}, - {36854,38420,36856 ,21080,21079,21078 ,0,0,0}, {38094,36856,38420 ,21076,21078,21079 ,0,0,0}, - {37781,38171,36850 ,21071,21081,21072 ,0,0,0}, {36854,36850,38171 ,21080,21072,21081 ,0,0,0}, - {37781,36851,37667 ,21071,21070,21074 ,0,0,0}, {37143,37667,36851 ,21075,21074,21070 ,0,0,0}, - {36796,38382,36836 ,21065,21064,21130 ,0,0,0}, {36836,38382,37666 ,21130,21064,21073 ,0,0,0}, - {36836,37666,37143 ,21130,21073,21075 ,0,0,0}, {36797,37776,36796 ,21067,21066,21065 ,0,0,0}, - {37145,37773,37777 ,21068,21131,21069 ,0,0,0}, {37776,36797,37777 ,21066,21067,21069 ,0,0,0}, - {37775,37773,37125 ,21059,21131,21060 ,0,0,0}, {37773,37145,37125 ,21131,21068,21060 ,0,0,0}, - {37149,38077,37128 ,21063,21132,21058 ,0,0,0}, {38077,37775,37128 ,21132,21059,21058 ,0,0,0}, - {37495,38078,37174 ,21052,21062,21061 ,0,0,0}, {37149,38078,38077 ,21063,21062,21132 ,0,0,0}, - {38159,37161,38439 ,21133,21051,21050 ,0,0,0}, {37197,38435,37170 ,21134,21054,21053 ,0,0,0}, - {37174,37170,37495 ,21061,21053,21052 ,0,0,0}, {38437,37197,37167 ,21055,21134,21056 ,0,0,0}, - {38435,37197,38437 ,21054,21134,21055 ,0,0,0}, {38158,37630,37198 ,21047,21057,21048 ,0,0,0}, - {37630,37167,37198 ,21057,21056,21048 ,0,0,0}, {37161,38159,37165 ,21051,21133,21046 ,0,0,0}, - {38159,38158,37165 ,21133,21047,21046 ,0,0,0}, {38443,38439,37160 ,21040,21050,21049 ,0,0,0}, - {37154,38164,38441 ,21043,21045,21042 ,0,0,0}, {37154,38441,37155 ,21043,21042,21041 ,0,0,0}, - {37160,37155,38443 ,21049,21041,21040 ,0,0,0}, {37152,38444,38164 ,21044,21038,21045 ,0,0,0}, - {35482,37153,35481 ,21037,21039,878 ,0,0,0}, {38444,37152,37153 ,21038,21044,21039 ,0,0,0}, - {35382,38115,36812 ,21135,21136,21039 ,0,0,0}, {38060,36811,38061 ,21137,21041,21042 ,0,0,0}, - {36339,36813,38062 ,21138,21139,21045 ,0,0,0}, {36175,38064,36480 ,21140,21141,21142 ,0,0,0}, - {36810,37778,36808 ,21143,21144,21145 ,0,0,0}, {38069,36806,38177 ,21146,21147,21148 ,0,0,0}, - {38070,36478,38066 ,21149,21150,21151 ,0,0,0}, {36805,38399,37147 ,21152,21059,21153 ,0,0,0}, - {36839,38087,36840 ,21154,21155,21156 ,0,0,0}, {38089,36790,38088 ,21157,21158,21159 ,0,0,0}, - {36795,36842,38160 ,21160,21161,21162 ,0,0,0}, {36843,38084,36801 ,21163,21164,21165 ,0,0,0}, - {38161,38085,37146 ,21166,21167,21168 ,0,0,0}, {38426,36847,36845 ,21169,21170,21171 ,0,0,0}, - {38156,36844,38425 ,21172,21173,21174 ,0,0,0}, {36507,37144,38150 ,21175,21176,21177 ,0,0,0}, - {37124,38153,38154 ,21178,21179,21180 ,0,0,0}, {37123,38152,38083 ,21181,21182,21183 ,0,0,0}, - {38151,38152,36508 ,21184,21182,21185 ,0,0,0}, {36479,37782,37121 ,21186,21187,21188 ,0,0,0}, - {38145,36479,37122 ,21189,21186,21190 ,0,0,0}, {36855,38147,36857 ,21191,21192,21193 ,0,0,0}, - {37783,36855,37121 ,21194,21191,21188 ,0,0,0}, {38142,38082,36860 ,21195,21196,21197 ,0,0,0}, - {38146,36858,36857 ,21198,21199,21193 ,0,0,0}, {36817,38082,38081 ,21200,21196,21201 ,0,0,0}, - {38082,36817,36860 ,21196,21200,21197 ,0,0,0}, {37929,36818,38081 ,21202,21203,21201 ,0,0,0}, - {36817,38081,36818 ,21200,21201,21203 ,0,0,0}, {37929,37811,36862 ,21202,21204,21205 ,0,0,0}, - {36862,36818,37929 ,21205,21203,21202 ,0,0,0}, {36319,37811,37634 ,21206,21204,21207 ,0,0,0}, - {37811,36319,36862 ,21204,21206,21205 ,0,0,0}, {38141,36320,37634 ,21208,21209,21207 ,0,0,0}, - {36319,37634,36320 ,21206,21207,21209 ,0,0,0}, {38141,37909,36864 ,21208,21210,21211 ,0,0,0}, - {36864,36320,38141 ,21211,21209,21208 ,0,0,0}, {36866,37909,37911 ,21212,21210,21213 ,0,0,0}, - {37909,36866,36864 ,21210,21212,21211 ,0,0,0}, {38140,36867,37911 ,21214,21215,21213 ,0,0,0}, - {36866,37911,36867 ,21212,21213,21215 ,0,0,0}, {38140,38073,36869 ,21214,21216,21217 ,0,0,0}, - {36869,36867,38140 ,21217,21215,21214 ,0,0,0}, {36868,38073,38074 ,21218,21216,21219 ,0,0,0}, - {38073,36868,36869 ,21216,21218,21217 ,0,0,0}, {37930,36870,38074 ,21220,21221,21219 ,0,0,0}, - {36868,38074,36870 ,21218,21219,21221 ,0,0,0}, {37930,35427,35428 ,21220,21129,21129 ,0,0,0}, - {35428,36870,37930 ,21129,21221,21220 ,0,0,0}, {36860,36858,38142 ,21197,21199,21195 ,0,0,0}, - {38146,38142,36858 ,21198,21195,21199 ,0,0,0}, {38147,38146,36857 ,21192,21198,21193 ,0,0,0}, - {38147,36855,37783 ,21192,21191,21194 ,0,0,0}, {38145,37782,36479 ,21189,21187,21186 ,0,0,0}, - {37782,37783,37121 ,21187,21194,21188 ,0,0,0}, {37123,38083,37122 ,21181,21183,21190 ,0,0,0}, - {38145,37122,38083 ,21189,21190,21183 ,0,0,0}, {36507,38151,36508 ,21175,21184,21185 ,0,0,0}, - {36508,38152,37123 ,21185,21182,21181 ,0,0,0}, {36507,38150,38151 ,21175,21177,21184 ,0,0,0}, - {37144,37124,38154 ,21176,21178,21180 ,0,0,0}, {37144,38154,38150 ,21176,21180,21177 ,0,0,0}, - {38153,36847,38426 ,21179,21170,21169 ,0,0,0}, {37124,36847,38153 ,21178,21170,21179 ,0,0,0}, - {36844,38156,36845 ,21173,21172,21171 ,0,0,0}, {38426,36845,38156 ,21169,21171,21172 ,0,0,0}, - {38084,38425,36801 ,21164,21174,21165 ,0,0,0}, {36844,36801,38425 ,21173,21165,21174 ,0,0,0}, - {38084,36843,38085 ,21164,21163,21167 ,0,0,0}, {37146,38085,36843 ,21168,21167,21163 ,0,0,0}, - {36790,38089,36804 ,21158,21157,21222 ,0,0,0}, {36804,38089,38161 ,21222,21157,21166 ,0,0,0}, - {36804,38161,37146 ,21222,21166,21168 ,0,0,0}, {36795,38088,36790 ,21160,21159,21158 ,0,0,0}, - {36842,38356,38160 ,21161,21223,21162 ,0,0,0}, {38088,36795,38160 ,21159,21160,21162 ,0,0,0}, - {38399,38356,37147 ,21059,21223,21153 ,0,0,0}, {38356,36842,37147 ,21223,21161,21153 ,0,0,0}, - {36840,38400,36805 ,21156,21224,21152 ,0,0,0}, {38400,38399,36805 ,21224,21059,21152 ,0,0,0}, - {38069,38087,36839 ,21146,21155,21154 ,0,0,0}, {36840,38087,38400 ,21156,21155,21224 ,0,0,0}, - {37780,36808,37778 ,21225,21145,21144 ,0,0,0}, {36476,38177,36806 ,21226,21148,21147 ,0,0,0}, - {36839,36806,38069 ,21154,21147,21146 ,0,0,0}, {38070,36476,36478 ,21149,21226,21150 ,0,0,0}, - {38177,36476,38070 ,21148,21226,21149 ,0,0,0}, {38064,38066,36480 ,21141,21151,21142 ,0,0,0}, - {38066,36478,36480 ,21151,21150,21142 ,0,0,0}, {36808,37780,36175 ,21145,21225,21140 ,0,0,0}, - {37780,38064,36175 ,21225,21141,21140 ,0,0,0}, {38060,37778,36810 ,21137,21144,21143 ,0,0,0}, - {36339,38062,38061 ,21138,21045,21042 ,0,0,0}, {36339,38061,36811 ,21138,21042,21041 ,0,0,0}, - {36810,36811,38060 ,21143,21041,21137 ,0,0,0}, {36813,38115,38062 ,21139,21136,21045 ,0,0,0}, - {35382,36812,35381 ,21135,21039,19477 ,0,0,0}, {38115,36813,36812 ,21136,21139,21039 ,0,0,0}, - {35282,38462,37087 ,18038,21227,21228 ,0,0,0}, {38459,37084,38461 ,21137,21229,21230 ,0,0,0}, - {36659,36658,38460 ,21231,21044,21045 ,0,0,0}, {37194,38445,37195 ,21046,21232,21233 ,0,0,0}, - {37085,38458,37193 ,21234,21235,21145 ,0,0,0}, {38371,37103,38367 ,21146,21236,21237 ,0,0,0}, - {38368,36791,38457 ,21238,21239,21240 ,0,0,0}, {37105,38369,37106 ,21241,21242,21243 ,0,0,0}, - {37102,38370,37104 ,21244,21245,21246 ,0,0,0}, {38453,37110,38454 ,21247,21248,21249 ,0,0,0}, - {37109,37107,37622 ,21250,21251,21252 ,0,0,0}, {37186,38373,37187 ,21253,21254,21255 ,0,0,0}, - {38098,38374,37091 ,21256,21257,21258 ,0,0,0}, {38099,37157,37158 ,21259,21260,21261 ,0,0,0}, - {38365,36846,38372 ,21262,21263,21264 ,0,0,0}, {36629,37166,37628 ,21265,21266,21267 ,0,0,0}, - {37159,38100,38101 ,21268,21269,21270 ,0,0,0}, {36630,37623,37624 ,21271,21272,21273 ,0,0,0}, - {37627,37623,36509 ,21274,21272,21275 ,0,0,0}, {36511,38095,37173 ,21276,21277,21278 ,0,0,0}, - {38096,36511,36510 ,21279,21276,21280 ,0,0,0}, {36474,38384,36472 ,21281,21282,21283 ,0,0,0}, - {38448,36474,37173 ,21284,21281,21278 ,0,0,0}, {38451,38452,36518 ,21285,21286,21287 ,0,0,0}, - {38449,36520,36472 ,21288,21289,21283 ,0,0,0}, {37171,38452,37496 ,21290,21286,21291 ,0,0,0}, - {38452,37171,36518 ,21286,21290,21287 ,0,0,0}, {38434,37172,37496 ,21292,21293,21291 ,0,0,0}, - {37171,37496,37172 ,21290,21291,21293 ,0,0,0}, {38434,38436,37168 ,21292,21294,21295 ,0,0,0}, - {37168,37172,38434 ,21295,21293,21292 ,0,0,0}, {37169,38436,37632 ,21296,21294,21297 ,0,0,0}, - {38436,37169,37168 ,21294,21296,21295 ,0,0,0}, {37631,37163,37632 ,21298,21299,21297 ,0,0,0}, - {37169,37632,37163 ,21296,21297,21299 ,0,0,0}, {37631,38157,37164 ,21298,21300,21301 ,0,0,0}, - {37164,37163,37631 ,21301,21299,21298 ,0,0,0}, {37162,38157,38438 ,21302,21300,21303 ,0,0,0}, - {38157,37162,37164 ,21300,21302,21301 ,0,0,0}, {38440,37199,38438 ,21304,21305,21303 ,0,0,0}, - {37162,38438,37199 ,21302,21303,21305 ,0,0,0}, {38440,38442,37156 ,21304,21306,21307 ,0,0,0}, - {37156,37199,38440 ,21307,21305,21304 ,0,0,0}, {37150,38442,38163 ,21308,21306,21309 ,0,0,0}, - {38442,37150,37156 ,21306,21308,21307 ,0,0,0}, {38162,37151,38163 ,21310,21311,21309 ,0,0,0}, - {37150,38163,37151 ,21308,21309,21311 ,0,0,0}, {38162,35327,35328 ,21310,21312,126 ,0,0,0}, - {35328,37151,38162 ,126,21311,21310 ,0,0,0}, {36518,36520,38451 ,21287,21289,21285 ,0,0,0}, - {38449,38451,36520 ,21288,21285,21289 ,0,0,0}, {38384,38449,36472 ,21282,21288,21283 ,0,0,0}, - {38384,36474,38448 ,21282,21281,21284 ,0,0,0}, {38096,38095,36511 ,21279,21277,21276 ,0,0,0}, - {38095,38448,37173 ,21277,21284,21278 ,0,0,0}, {36630,37624,36510 ,21271,21273,21280 ,0,0,0}, - {38096,36510,37624 ,21279,21280,21273 ,0,0,0}, {36629,37627,36509 ,21265,21274,21275 ,0,0,0}, - {36509,37623,36630 ,21275,21272,21271 ,0,0,0}, {36629,37628,37627 ,21265,21267,21274 ,0,0,0}, - {37166,37159,38101 ,21266,21268,21270 ,0,0,0}, {37166,38101,37628 ,21266,21270,21267 ,0,0,0}, - {38100,37157,38099 ,21269,21260,21259 ,0,0,0}, {37159,37157,38100 ,21268,21260,21269 ,0,0,0}, - {36846,38365,37158 ,21263,21262,21261 ,0,0,0}, {38099,37158,38365 ,21259,21261,21262 ,0,0,0}, - {38373,38372,37187 ,21254,21264,21255 ,0,0,0}, {36846,37187,38372 ,21263,21255,21264 ,0,0,0}, - {38373,37186,38374 ,21254,21253,21257 ,0,0,0}, {37091,38374,37186 ,21258,21257,21253 ,0,0,0}, - {37110,38453,37089 ,21248,21247,21313 ,0,0,0}, {37089,38453,38098 ,21313,21247,21256 ,0,0,0}, - {37089,38098,37091 ,21313,21256,21258 ,0,0,0}, {37109,38454,37110 ,21250,21249,21248 ,0,0,0}, - {37107,38455,37622 ,21251,21314,21252 ,0,0,0}, {38454,37109,37622 ,21249,21250,21252 ,0,0,0}, - {38369,38455,37106 ,21242,21314,21243 ,0,0,0}, {38455,37107,37106 ,21314,21251,21243 ,0,0,0}, - {37104,38456,37105 ,21246,21315,21241 ,0,0,0}, {38456,38369,37105 ,21315,21242,21241 ,0,0,0}, - {38371,38370,37102 ,21146,21245,21244 ,0,0,0}, {37104,38370,38456 ,21246,21245,21315 ,0,0,0}, - {38446,37193,38458 ,21316,21145,21235 ,0,0,0}, {37196,38367,37103 ,21317,21237,21236 ,0,0,0}, - {37102,37103,38371 ,21244,21236,21146 ,0,0,0}, {38368,37196,36791 ,21238,21317,21239 ,0,0,0}, - {38367,37196,38368 ,21237,21317,21238 ,0,0,0}, {38445,38457,37195 ,21232,21240,21233 ,0,0,0}, - {38457,36791,37195 ,21240,21239,21233 ,0,0,0}, {37193,38446,37194 ,21145,21316,21046 ,0,0,0}, - {38446,38445,37194 ,21316,21232,21046 ,0,0,0}, {38459,38458,37085 ,21137,21235,21234 ,0,0,0}, - {36659,38460,38461 ,21231,21045,21230 ,0,0,0}, {36659,38461,37084 ,21231,21230,21229 ,0,0,0}, - {37085,37084,38459 ,21234,21229,21137 ,0,0,0}, {36658,38462,38460 ,21044,21227,21045 ,0,0,0}, - {35282,37087,35281 ,18038,21228,21318 ,0,0,0}, {38462,36658,37087 ,21227,21044,21228 ,0,0,0}, - {35182,38114,36749 ,21319,21136,21320 ,0,0,0}, {38111,36783,38113 ,21321,21322,21323 ,0,0,0}, - {36184,36183,38112 ,21231,21139,21324 ,0,0,0}, {36634,37464,36635 ,21325,21232,21326 ,0,0,0}, - {36746,38110,36668 ,21327,21328,21329 ,0,0,0}, {38036,36513,38105 ,21146,21236,21330 ,0,0,0}, - {38106,36744,37466 ,21331,21332,21333 ,0,0,0}, {36664,37749,36663 ,21334,21335,21336 ,0,0,0}, - {36514,38104,36784 ,21337,21338,21339 ,0,0,0}, {38148,36637,38149 ,21340,21341,21249 ,0,0,0}, - {36612,36785,38172 ,21250,21342,21343 ,0,0,0}, {36748,38447,36747 ,21344,21345,21346 ,0,0,0}, - {37639,38419,36786 ,21347,21348,21168 ,0,0,0}, {38174,37189,36787 ,21349,21350,21351 ,0,0,0}, - {38175,37190,37665 ,21352,21353,21354 ,0,0,0}, {36788,37188,38422 ,21355,21356,21357 ,0,0,0}, - {36789,38076,38075 ,21358,21359,21360 ,0,0,0}, {36632,37663,37664 ,21361,21362,21363 ,0,0,0}, - {38421,37663,36633 ,21364,21362,21365 ,0,0,0}, {37101,38176,36208 ,21366,21367,21368 ,0,0,0}, - {38173,37101,36631 ,21369,21366,21370 ,0,0,0}, {36207,38169,36837 ,21371,21372,21373 ,0,0,0}, - {38170,36207,36208 ,21374,21371,21368 ,0,0,0}, {38423,38086,36841 ,21375,21376,21377 ,0,0,0}, - {38424,37127,36837 ,21378,21379,21373 ,0,0,0}, {36838,38086,38068 ,21380,21376,21381 ,0,0,0}, - {38086,36838,36841 ,21376,21380,21377 ,0,0,0}, {38067,36477,38068 ,21382,21383,21381 ,0,0,0}, - {36838,38068,36477 ,21380,21381,21383 ,0,0,0}, {38067,38072,36475 ,21382,21384,21385 ,0,0,0}, - {36475,36477,38067 ,21385,21383,21382 ,0,0,0}, {36481,38072,38071 ,21386,21384,21387 ,0,0,0}, - {38072,36481,36475 ,21384,21386,21385 ,0,0,0}, {38065,36176,38071 ,21388,21389,21387 ,0,0,0}, - {36481,38071,36176 ,21386,21387,21389 ,0,0,0}, {38065,38178,36177 ,21388,21390,21391 ,0,0,0}, - {36177,36176,38065 ,21391,21389,21388 ,0,0,0}, {36807,38178,37779 ,21392,21390,21393 ,0,0,0}, - {38178,36807,36177 ,21390,21392,21391 ,0,0,0}, {38059,36809,37779 ,21394,21395,21393 ,0,0,0}, - {36807,37779,36809 ,21392,21393,21395 ,0,0,0}, {38059,38058,36340 ,21394,21396,21397 ,0,0,0}, - {36340,36809,38059 ,21397,21395,21394 ,0,0,0}, {36338,38058,38063 ,21398,21396,21399 ,0,0,0}, - {38058,36338,36340 ,21396,21398,21397 ,0,0,0}, {38116,36814,38063 ,21400,21401,21399 ,0,0,0}, - {36338,38063,36814 ,21398,21399,21401 ,0,0,0}, {38116,35227,35228 ,21400,21312,126 ,0,0,0}, - {35228,36814,38116 ,126,21401,21400 ,0,0,0}, {36841,37127,38423 ,21377,21379,21375 ,0,0,0}, - {38424,38423,37127 ,21378,21375,21379 ,0,0,0}, {38169,38424,36837 ,21372,21378,21373 ,0,0,0}, - {38169,36207,38170 ,21372,21371,21374 ,0,0,0}, {38173,38176,37101 ,21369,21367,21366 ,0,0,0}, - {38176,38170,36208 ,21367,21374,21368 ,0,0,0}, {36632,37664,36631 ,21361,21363,21370 ,0,0,0}, - {38173,36631,37664 ,21369,21370,21363 ,0,0,0}, {36788,38421,36633 ,21355,21364,21365 ,0,0,0}, - {36633,37663,36632 ,21365,21362,21361 ,0,0,0}, {36788,38422,38421 ,21355,21357,21364 ,0,0,0}, - {37188,36789,38075 ,21356,21358,21360 ,0,0,0}, {37188,38075,38422 ,21356,21360,21357 ,0,0,0}, - {38076,37189,38174 ,21359,21350,21349 ,0,0,0}, {36789,37189,38076 ,21358,21350,21359 ,0,0,0}, - {37190,38175,36787 ,21353,21352,21351 ,0,0,0}, {38174,36787,38175 ,21349,21351,21352 ,0,0,0}, - {38447,37665,36747 ,21345,21354,21346 ,0,0,0}, {37190,36747,37665 ,21353,21346,21354 ,0,0,0}, - {38447,36748,38419 ,21345,21344,21348 ,0,0,0}, {36786,38419,36748 ,21168,21348,21344 ,0,0,0}, - {36637,38148,36638 ,21341,21340,21402 ,0,0,0}, {36638,38148,37639 ,21402,21340,21347 ,0,0,0}, - {36638,37639,36786 ,21402,21347,21168 ,0,0,0}, {36612,38149,36637 ,21250,21249,21341 ,0,0,0}, - {36785,37748,38172 ,21342,21403,21343 ,0,0,0}, {38149,36612,38172 ,21249,21250,21343 ,0,0,0}, - {37749,37748,36663 ,21335,21403,21336 ,0,0,0}, {37748,36785,36663 ,21403,21342,21336 ,0,0,0}, - {36784,38102,36664 ,21339,21404,21334 ,0,0,0}, {38102,37749,36664 ,21404,21335,21334 ,0,0,0}, - {38036,38104,36514 ,21146,21338,21337 ,0,0,0}, {36784,38104,38102 ,21339,21338,21404 ,0,0,0}, - {38108,36668,38110 ,21133,21329,21328 ,0,0,0}, {36666,38105,36513 ,21405,21330,21236 ,0,0,0}, - {36514,36513,38036 ,21337,21236,21146 ,0,0,0}, {38106,36666,36744 ,21331,21405,21332 ,0,0,0}, - {38105,36666,38106 ,21330,21405,21331 ,0,0,0}, {37464,37466,36635 ,21232,21333,21326 ,0,0,0}, - {37466,36744,36635 ,21333,21332,21326 ,0,0,0}, {36668,38108,36634 ,21329,21133,21325 ,0,0,0}, - {38108,37464,36634 ,21133,21232,21325 ,0,0,0}, {38111,38110,36746 ,21321,21328,21327 ,0,0,0}, - {36184,38112,38113 ,21231,21324,21323 ,0,0,0}, {36184,38113,36783 ,21231,21323,21322 ,0,0,0}, - {36746,36783,38111 ,21327,21322,21321 ,0,0,0}, {36183,38114,38112 ,21139,21136,21324 ,0,0,0}, - {35182,36749,35181 ,21319,21320,21406 ,0,0,0}, {38114,36183,36749 ,21136,21139,21320 ,0,0,0}, - {37473,36200,36752 ,1273,1273,21407 ,0,0,0}, {36751,37471,36752 ,21408,21409,21407 ,0,0,0}, - {37473,36752,37471 ,1273,21407,21409 ,0,0,0}, {36751,37067,37472 ,21408,1276,21408 ,0,0,0}, - {37472,37471,36751 ,21408,21409,21408 ,0,0,0}, {37477,37067,37068 ,1276,1276,21410 ,0,0,0}, - {37067,37477,37472 ,1276,1276,21408 ,0,0,0}, {37066,37486,37068 ,21411,21412,21410 ,0,0,0}, - {37477,37068,37486 ,1276,21410,21412 ,0,0,0}, {37066,36195,37487 ,21411,21413,21411 ,0,0,0}, - {37487,37486,37066 ,21411,21412,21411 ,0,0,0}, {36195,37481,37487 ,21413,20658,21411 ,0,0,0}, - {37462,36200,37473 ,21414,1273,1273 ,0,0,0}, {37462,37461,36201 ,21414,21415,21416 ,0,0,0}, - {36201,36200,37462 ,21416,1273,21414 ,0,0,0}, {36782,37461,38039 ,21415,21415,21417 ,0,0,0}, - {37461,36782,36201 ,21415,21415,21416 ,0,0,0}, {38040,36781,38039 ,21418,1275,21417 ,0,0,0}, - {36782,38039,36781 ,21415,21417,1275 ,0,0,0}, {38040,38041,36174 ,21418,21419,21420 ,0,0,0}, - {36174,36781,38040 ,21420,1275,21418 ,0,0,0}, {36173,38041,38050 ,21419,21419,21421 ,0,0,0}, - {38041,36173,36174 ,21419,21419,21420 ,0,0,0}, {36173,38050,36181 ,21419,21421,21422 ,0,0,0}, - {37646,36639,36652 ,1207,1207,21423 ,0,0,0}, {36651,38376,36652 ,21424,21425,21423 ,0,0,0}, - {37646,36652,38376 ,1207,21423,21425 ,0,0,0}, {36651,36655,37641 ,21424,1882,21424 ,0,0,0}, - {37641,38376,36651 ,21424,21425,21424 ,0,0,0}, {37642,36655,36661 ,1882,1882,21426 ,0,0,0}, - {36655,37642,37641 ,1882,1882,21424 ,0,0,0}, {37093,37636,36661 ,21427,21428,21426 ,0,0,0}, - {37642,36661,37636 ,1882,21426,21428 ,0,0,0}, {37093,37094,37643 ,21427,21429,21427 ,0,0,0}, - {37643,37636,37093 ,21427,21428,21427 ,0,0,0}, {37094,37648,37643 ,21429,21430,21427 ,0,0,0}, - {37653,36639,37646 ,21431,1207,1207 ,0,0,0}, {37653,37656,36648 ,21431,21432,21433 ,0,0,0}, - {36648,36639,37653 ,21433,1207,21431 ,0,0,0}, {36646,37656,37655 ,21432,21432,21434 ,0,0,0}, - {37656,36646,36648 ,21432,21432,21433 ,0,0,0}, {37657,36642,37655 ,21435,1887,21434 ,0,0,0}, - {36646,37655,36642 ,21432,21434,1887 ,0,0,0}, {37657,37662,36643 ,21435,21436,21437 ,0,0,0}, - {36643,36642,37657 ,21437,1887,21435 ,0,0,0}, {36644,37662,38366 ,21436,21436,21438 ,0,0,0}, - {37662,36644,36643 ,21436,21436,21437 ,0,0,0}, {36644,38366,36645 ,21436,21438,21439 ,0,0,0}, - {37792,36492,36483 ,2038,2038,21440 ,0,0,0}, {36487,37784,36483 ,21441,21442,21440 ,0,0,0}, - {37792,36483,37784 ,2038,21440,21442 ,0,0,0}, {36487,36486,37796 ,21441,2041,21441 ,0,0,0}, - {37796,37784,36487 ,21441,21442,21441 ,0,0,0}, {37802,36486,36485 ,2041,2041,21443 ,0,0,0}, - {36486,37802,37796 ,2041,2041,21441 ,0,0,0}, {36506,37803,36485 ,21444,21445,21443 ,0,0,0}, - {37802,36485,37803 ,2041,21443,21445 ,0,0,0}, {36506,36849,37795 ,21444,21446,21444 ,0,0,0}, - {37795,37803,36506 ,21444,21445,21444 ,0,0,0}, {36849,37800,37795 ,21446,21447,21444 ,0,0,0}, - {37794,36492,37792 ,21448,2038,2038 ,0,0,0}, {37794,37787,37082 ,21448,21449,21450 ,0,0,0}, - {37082,36492,37794 ,21450,2038,21448 ,0,0,0}, {36505,37787,37789 ,21449,21449,21451 ,0,0,0}, - {37787,36505,37082 ,21449,21449,21450 ,0,0,0}, {38348,37073,37789 ,21452,2040,21451 ,0,0,0}, - {36505,37789,37073 ,21449,21451,2040 ,0,0,0}, {38348,38358,36499 ,21452,21453,21454 ,0,0,0}, - {36499,37073,38348 ,21454,2040,21452 ,0,0,0}, {36490,38358,38359 ,21453,21453,21455 ,0,0,0}, - {38358,36490,36499 ,21453,21453,21454 ,0,0,0}, {36490,38359,36497 ,21453,21455,21429 ,0,0,0}, - {37896,36330,36336 ,1114,1114,21456 ,0,0,0}, {36315,37939,36336 ,21457,21458,21456 ,0,0,0}, - {37896,36336,37939 ,1114,21456,21458 ,0,0,0}, {36315,36316,37936 ,21457,1116,21457 ,0,0,0}, - {37936,37939,36315 ,21457,21458,21457 ,0,0,0}, {37933,36316,36825 ,1116,1116,21459 ,0,0,0}, - {36316,37933,37936 ,1116,1116,21457 ,0,0,0}, {36317,37934,36825 ,21460,21461,21459 ,0,0,0}, - {37933,36825,37934 ,1116,21459,21461 ,0,0,0}, {36317,36213,37935 ,21460,21462,21460 ,0,0,0}, - {37935,37934,36317 ,21460,21461,21460 ,0,0,0}, {36213,37940,37935 ,21462,21463,21460 ,0,0,0}, - {37941,36330,37896 ,21464,1114,1114 ,0,0,0}, {37941,37938,36321 ,21464,21465,21466 ,0,0,0}, - {36321,36330,37941 ,21466,1114,21464 ,0,0,0}, {36322,37938,37937 ,21465,21465,21467 ,0,0,0}, - {37938,36322,36321 ,21465,21465,21466 ,0,0,0}, {38344,36323,37937 ,21468,1121,21467 ,0,0,0}, - {36322,37937,36323 ,21465,21467,1121 ,0,0,0}, {38344,38055,36324 ,21468,21469,21470 ,0,0,0}, - {36324,36323,38344 ,21470,1121,21468 ,0,0,0}, {37072,38055,37668 ,21469,21469,21471 ,0,0,0}, - {38055,37072,36324 ,21469,21469,21470 ,0,0,0}, {37072,37668,36327 ,21469,21471,21472 ,0,0,0}, - {35119,37207,38468 ,21473,21474,21475 ,0,0,0}, {38464,38463,36740 ,21476,21477,21478 ,0,0,0}, - {38469,38467,37206 ,21479,21480,21481 ,0,0,0}, {38470,37203,37204 ,21482,21483,21484 ,0,0,0}, - {37205,37203,38471 ,21485,21483,21486 ,0,0,0}, {38465,38466,37201 ,21487,21488,21489 ,0,0,0}, - {37204,37201,38466 ,21484,21489,21488 ,0,0,0}, {37202,35128,38465 ,21490,82,21487 ,0,0,0}, - {38465,37201,37202 ,21487,21489,21490 ,0,0,0}, {35127,35128,37202 ,19633,82,21490 ,0,0,0}, - {38466,38470,37204 ,21488,21482,21484 ,0,0,0}, {38470,38471,37203 ,21482,21486,21483 ,0,0,0}, - {38464,36740,37205 ,21476,21478,21485 ,0,0,0}, {38464,37205,38471 ,21476,21485,21486 ,0,0,0}, - {38469,37206,36741 ,21479,21481,21491 ,0,0,0}, {38463,38469,36741 ,21477,21479,21491 ,0,0,0}, - {38463,36741,36740 ,21477,21491,21478 ,0,0,0}, {37207,38467,38468 ,21474,21480,21475 ,0,0,0}, - {37207,37206,38467 ,21474,21481,21480 ,0,0,0}, {38468,35116,35119 ,21475,21492,21473 ,0,0,0}, - {35097,37214,38028 ,21493,21494,21495 ,0,0,0}, {38475,38474,37213 ,21496,21497,21498 ,0,0,0}, - {38473,38472,37215 ,21499,21500,21501 ,0,0,0}, {38476,37210,37209 ,21502,21503,21504 ,0,0,0}, - {37211,37210,38477 ,21505,21503,21506 ,0,0,0}, {38478,38479,37208 ,21507,21508,21509 ,0,0,0}, - {37209,37208,38479 ,21504,21509,21508 ,0,0,0}, {36288,35106,38478 ,21510,761,21507 ,0,0,0}, - {38478,37208,36288 ,21507,21509,21510 ,0,0,0}, {35105,35106,36288 ,761,761,21510 ,0,0,0}, - {38479,38476,37209 ,21508,21502,21504 ,0,0,0}, {38476,38477,37210 ,21502,21506,21503 ,0,0,0}, - {38475,37213,37211 ,21496,21498,21505 ,0,0,0}, {38475,37211,38477 ,21496,21505,21506 ,0,0,0}, - {38473,37215,37212 ,21499,21501,21511 ,0,0,0}, {38474,38473,37212 ,21497,21499,21511 ,0,0,0}, - {38474,37212,37213 ,21497,21511,21498 ,0,0,0}, {37214,38472,38028 ,21494,21500,21495 ,0,0,0}, - {37214,37215,38472 ,21494,21501,21500 ,0,0,0}, {38028,35094,35097 ,21495,96,21493 ,0,0,0}, - {35075,36305,37958 ,21493,21512,21495 ,0,0,0}, {38025,38027,36307 ,21513,21497,21514 ,0,0,0}, - {38483,38022,36310 ,21515,21516,21517 ,0,0,0}, {38480,36313,37221 ,21518,21519,21520 ,0,0,0}, - {36312,36313,38023 ,21521,21519,21522 ,0,0,0}, {38019,38481,36300 ,21523,21524,21525 ,0,0,0}, - {37221,36300,38481 ,21520,21525,21524 ,0,0,0}, {36299,35084,38019 ,21526,761,21523 ,0,0,0}, - {38019,36300,36299 ,21523,21525,21526 ,0,0,0}, {35083,35084,36299 ,761,761,21526 ,0,0,0}, - {38481,38480,37221 ,21524,21518,21520 ,0,0,0}, {38480,38023,36313 ,21518,21522,21519 ,0,0,0}, - {38025,36307,36312 ,21513,21514,21521 ,0,0,0}, {38025,36312,38023 ,21513,21521,21522 ,0,0,0}, - {38483,36310,36309 ,21515,21517,21527 ,0,0,0}, {38027,38483,36309 ,21497,21515,21527 ,0,0,0}, - {38027,36309,36307 ,21497,21527,21514 ,0,0,0}, {36305,38022,37958 ,21512,21516,21495 ,0,0,0}, - {36305,36310,38022 ,21512,21517,21516 ,0,0,0}, {37958,35072,35075 ,21495,96,21493 ,0,0,0}, - {35053,37042,37917 ,850,21528,21529 ,0,0,0}, {37904,37906,36430 ,21530,21531,21532 ,0,0,0}, - {37924,37921,36927 ,21533,21534,21535 ,0,0,0}, {38494,36929,36931 ,21536,21537,21538 ,0,0,0}, - {37047,36929,38493 ,21539,21537,21540 ,0,0,0}, {37920,38496,36459 ,21541,21542,21543 ,0,0,0}, - {36931,36459,38496 ,21538,21543,21542 ,0,0,0}, {36458,35062,37920 ,21544,82,21541 ,0,0,0}, - {37920,36459,36458 ,21541,21543,21544 ,0,0,0}, {35061,35062,36458 ,19655,82,21544 ,0,0,0}, - {38496,38494,36931 ,21542,21536,21538 ,0,0,0}, {38494,38493,36929 ,21536,21540,21537 ,0,0,0}, - {37904,36430,37047 ,21530,21532,21539 ,0,0,0}, {37904,37047,38493 ,21530,21539,21540 ,0,0,0}, - {37924,36927,36428 ,21533,21535,21545 ,0,0,0}, {37906,37924,36428 ,21531,21533,21545 ,0,0,0}, - {37906,36428,36430 ,21531,21545,21532 ,0,0,0}, {37042,37921,37917 ,21528,21534,21529 ,0,0,0}, - {37042,36927,37921 ,21528,21535,21534 ,0,0,0}, {37917,35050,35053 ,21529,21492,850 ,0,0,0}, - {35031,37233,38501 ,21493,21512,21495 ,0,0,0}, {38502,38497,37232 ,21546,21547,21548 ,0,0,0}, - {38499,38500,37234 ,21549,21516,9914 ,0,0,0}, {38503,36625,36624 ,21550,21503,21551 ,0,0,0}, - {37230,36625,38504 ,21552,21503,21553 ,0,0,0}, {38505,38506,37228 ,21554,21555,21556 ,0,0,0}, - {36624,37228,38506 ,21551,21556,21555 ,0,0,0}, {37229,35040,38505 ,21557,761,21554 ,0,0,0}, - {38505,37228,37229 ,21554,21556,21557 ,0,0,0}, {35039,35040,37229 ,761,761,21557 ,0,0,0}, - {38506,38503,36624 ,21555,21550,21551 ,0,0,0}, {38503,38504,36625 ,21550,21553,21503 ,0,0,0}, - {38502,37232,37230 ,21546,21548,21552 ,0,0,0}, {38502,37230,38504 ,21546,21552,21553 ,0,0,0}, - {38499,37234,37231 ,21549,9914,21558 ,0,0,0}, {38497,38499,37231 ,21547,21549,21558 ,0,0,0}, - {38497,37231,37232 ,21547,21558,21548 ,0,0,0}, {37233,38500,38501 ,21512,21516,21495 ,0,0,0}, - {37233,37234,38500 ,21512,9914,21516 ,0,0,0}, {38501,35028,35031 ,21495,96,21493 ,0,0,0}, - {35009,36614,37755 ,21493,9918,21495 ,0,0,0}, {37757,37737,37238 ,21559,21560,9908 ,0,0,0}, - {37736,37753,36622 ,21561,21516,21501 ,0,0,0}, {37765,37241,36594 ,21550,21562,21563 ,0,0,0}, - {37240,37241,38508 ,21564,21562,21565 ,0,0,0}, {37769,37768,36616 ,21566,21567,21568 ,0,0,0}, - {36594,36616,37768 ,21563,21568,21567 ,0,0,0}, {36615,35018,37769 ,21569,761,21566 ,0,0,0}, - {37769,36616,36615 ,21566,21568,21569 ,0,0,0}, {35017,35018,36615 ,761,761,21569 ,0,0,0}, - {37768,37765,36594 ,21567,21550,21563 ,0,0,0}, {37765,38508,37241 ,21550,21565,21562 ,0,0,0}, - {37757,37238,37240 ,21559,9908,21564 ,0,0,0}, {37757,37240,38508 ,21559,21564,21565 ,0,0,0}, - {37736,36622,36591 ,21561,21501,21558 ,0,0,0}, {37737,37736,36591 ,21560,21561,21558 ,0,0,0}, - {37737,36591,37238 ,21560,21558,9908 ,0,0,0}, {36614,37753,37755 ,9918,21516,21495 ,0,0,0}, - {36614,36622,37753 ,9918,21501,21516 ,0,0,0}, {37755,35006,35009 ,21495,96,21493 ,0,0,0}, - {34987,36463,37925 ,19184,21570,21475 ,0,0,0}, {38516,38517,37250 ,21476,21571,21572 ,0,0,0}, - {38514,38515,36464 ,21573,21574,21575 ,0,0,0}, {38513,37244,37248 ,21576,21577,21578 ,0,0,0}, - {37245,37244,38512 ,21485,21577,21579 ,0,0,0}, {38519,38518,37246 ,21580,21581,21582 ,0,0,0}, - {37248,37246,38518 ,21578,21582,21581 ,0,0,0}, {37247,34996,38519 ,21583,82,21580 ,0,0,0}, - {38519,37246,37247 ,21580,21582,21583 ,0,0,0}, {34995,34996,37247 ,19655,82,21583 ,0,0,0}, - {38518,38513,37248 ,21581,21576,21578 ,0,0,0}, {38513,38512,37244 ,21576,21579,21577 ,0,0,0}, - {38516,37250,37245 ,21476,21572,21485 ,0,0,0}, {38516,37245,38512 ,21476,21485,21579 ,0,0,0}, - {38514,36464,37249 ,21573,21575,21584 ,0,0,0}, {38517,38514,37249 ,21571,21573,21584 ,0,0,0}, - {38517,37249,37250 ,21571,21584,21572 ,0,0,0}, {36463,38515,37925 ,21570,21574,21475 ,0,0,0}, - {36463,36464,38515 ,21570,21575,21574 ,0,0,0}, {37925,34984,34987 ,21475,21585,19184 ,0,0,0}, - {34965,36739,37616 ,21473,21586,21587 ,0,0,0}, {37601,37609,37253 ,21530,21588,21589 ,0,0,0}, - {37608,37613,37256 ,21590,21534,21591 ,0,0,0}, {38520,36737,36680 ,21592,21593,21594 ,0,0,0}, - {36736,36737,37602 ,21539,21593,21540 ,0,0,0}, {37573,37612,36733 ,21595,21596,21597 ,0,0,0}, - {36680,36733,37612 ,21594,21597,21596 ,0,0,0}, {36734,34974,37573 ,21598,19234,21595 ,0,0,0}, - {37573,36733,36734 ,21595,21597,21598 ,0,0,0}, {34973,34974,36734 ,21599,19234,21598 ,0,0,0}, - {37612,38520,36680 ,21596,21592,21594 ,0,0,0}, {38520,37602,36737 ,21592,21540,21593 ,0,0,0}, - {37601,37253,36736 ,21530,21589,21539 ,0,0,0}, {37601,36736,37602 ,21530,21539,21540 ,0,0,0}, - {37608,37256,37254 ,21590,21591,21600 ,0,0,0}, {37609,37608,37254 ,21588,21590,21600 ,0,0,0}, - {37609,37254,37253 ,21588,21600,21589 ,0,0,0}, {36739,37613,37616 ,21586,21534,21587 ,0,0,0}, - {36739,37256,37613 ,21586,21591,21534 ,0,0,0}, {37616,34962,34965 ,21587,21492,21473 ,0,0,0}, - {34937,37459,37530 ,2619,21601,21602 ,0,0,0}, {37977,38530,36254 ,21603,20873,21604 ,0,0,0}, - {38529,38212,37265 ,21605,21606,21607 ,0,0,0}, {38743,37260,37979 ,21608,21609,21610 ,0,0,0}, - {36253,37460,38745 ,21611,21612,21613 ,0,0,0}, {37259,36260,38526 ,21614,21615,21616 ,0,0,0}, - {37259,38537,36225 ,21614,21617,21618 ,0,0,0}, {36259,37258,38209 ,21619,21620,21621 ,0,0,0}, - {38209,38527,36259 ,21621,21622,21619 ,0,0,0}, {37972,37258,37257 ,21623,21620,21624 ,0,0,0}, - {37258,37972,38209 ,21620,21623,21621 ,0,0,0}, {36871,38533,37257 ,21625,21626,21624 ,0,0,0}, - {37972,37257,38533 ,21623,21624,21626 ,0,0,0}, {36871,34951,34952 ,21625,82,2602 ,0,0,0}, - {34952,38533,36871 ,2602,21626,21625 ,0,0,0}, {37260,38743,37460 ,21609,21608,21612 ,0,0,0}, - {36260,38527,38526 ,21615,21622,21616 ,0,0,0}, {36259,38527,36260 ,21619,21622,21615 ,0,0,0}, - {36254,38530,36269 ,21604,20873,21627 ,0,0,0}, {36225,38537,37979 ,21618,21617,21610 ,0,0,0}, - {37259,38526,38537 ,21614,21616,21617 ,0,0,0}, {37260,36225,37979 ,21609,21618,21610 ,0,0,0}, - {38745,37460,38743 ,21613,21612,21608 ,0,0,0}, {37977,36254,36253 ,21603,21604,21611 ,0,0,0}, - {36253,38745,37977 ,21611,21613,21603 ,0,0,0}, {38212,37459,37265 ,21606,21601,21607 ,0,0,0}, - {36269,38529,37265 ,21627,21605,21607 ,0,0,0}, {38530,38529,36269 ,20873,21605,21627 ,0,0,0}, - {34937,37530,34938 ,2619,21602,126 ,0,0,0}, {37459,38212,37530 ,21601,21606,21602 ,0,0,0}, - {34907,36910,38184 ,2619,17362,21602 ,0,0,0}, {38190,38189,36907 ,21628,21629,21630 ,0,0,0}, - {38538,38187,36909 ,21605,20903,21631 ,0,0,0}, {38484,37279,38014 ,21632,21609,21633 ,0,0,0}, - {37281,37277,38486 ,21634,21635,21636 ,0,0,0}, {37296,37297,38540 ,21637,21638,21639 ,0,0,0}, - {37296,38539,37452 ,21637,21640,21641 ,0,0,0}, {37222,36303,37995 ,21642,21643,21644 ,0,0,0}, - {37995,38541,37222 ,21644,21645,21642 ,0,0,0}, {38562,36303,37453 ,21646,21643,21647 ,0,0,0}, - {36303,38562,37995 ,21643,21646,21644 ,0,0,0}, {37269,38559,37453 ,21648,21649,21647 ,0,0,0}, - {38562,37453,38559 ,21646,21647,21649 ,0,0,0}, {37269,34920,3883 ,21648,21650,82 ,0,0,0}, - {3883,38559,37269 ,82,21649,21648 ,0,0,0}, {37279,38484,37277 ,21609,21632,21635 ,0,0,0}, - {37297,38541,38540 ,21638,21645,21639 ,0,0,0}, {37222,38541,37297 ,21642,21645,21638 ,0,0,0}, - {36907,38189,36271 ,21630,21629,21651 ,0,0,0}, {37452,38539,38014 ,21641,21640,21633 ,0,0,0}, - {37296,38540,38539 ,21637,21639,21640 ,0,0,0}, {37279,37452,38014 ,21609,21641,21633 ,0,0,0}, - {38486,37277,38484 ,21636,21635,21632 ,0,0,0}, {38190,36907,37281 ,21628,21630,21634 ,0,0,0}, - {37281,38486,38190 ,21634,21636,21628 ,0,0,0}, {38187,36910,36909 ,20903,17362,21631 ,0,0,0}, - {36271,38538,36909 ,21651,21605,21631 ,0,0,0}, {38189,38538,36271 ,21629,21605,21651 ,0,0,0}, - {34907,38184,3897 ,2619,21602,126 ,0,0,0}, {36910,38187,38184 ,17362,20903,21602 ,0,0,0}, - {34875,37298,37998 ,8383,21652,21653 ,0,0,0}, {38545,38544,37295 ,20948,21654,21655 ,0,0,0}, - {38542,38733,37271 ,21656,20903,21607 ,0,0,0}, {37476,37219,37997 ,21657,21609,21658 ,0,0,0}, - {37294,37272,38561 ,21659,21660,21661 ,0,0,0}, {37276,36902,38548 ,21662,21663,21664 ,0,0,0}, - {37276,38564,37218 ,21662,21665,21666 ,0,0,0}, {36901,37292,38000 ,21667,21668,21669 ,0,0,0}, - {38000,38549,36901 ,21669,21670,21667 ,0,0,0}, {38194,37292,36894 ,21671,21668,21672 ,0,0,0}, - {37292,38194,38000 ,21668,21671,21669 ,0,0,0}, {37283,38192,36894 ,21673,21674,21672 ,0,0,0}, - {38194,36894,38192 ,21671,21672,21674 ,0,0,0}, {37283,34889,34890 ,21673,2601,82 ,0,0,0}, - {34890,38192,37283 ,82,21674,21673 ,0,0,0}, {37219,37476,37272 ,21609,21657,21660 ,0,0,0}, - {36902,38549,38548 ,21663,21670,21664 ,0,0,0}, {36901,38549,36902 ,21667,21670,21663 ,0,0,0}, - {37295,38544,37270 ,21655,21654,21675 ,0,0,0}, {37218,38564,37997 ,21666,21665,21658 ,0,0,0}, - {37276,38548,38564 ,21662,21664,21665 ,0,0,0}, {37219,37218,37997 ,21609,21666,21658 ,0,0,0}, - {38561,37272,37476 ,21661,21660,21657 ,0,0,0}, {38545,37295,37294 ,20948,21655,21659 ,0,0,0}, - {37294,38561,38545 ,21659,21661,20948 ,0,0,0}, {38733,37298,37271 ,20903,21652,21607 ,0,0,0}, - {37270,38542,37271 ,21675,21656,21607 ,0,0,0}, {38544,38542,37270 ,21654,21656,21675 ,0,0,0}, - {34875,37998,34876 ,8383,21653,126 ,0,0,0}, {37298,38733,37998 ,21652,20903,21653 ,0,0,0}, - {34845,37311,38568 ,8383,21676,21653 ,0,0,0}, {37988,38179,36877 ,21603,20873,21677 ,0,0,0}, - {37551,37961,36276 ,21678,21679,21631 ,0,0,0}, {37990,37307,38556 ,21680,21681,21682 ,0,0,0}, - {36228,36227,37987 ,21683,21684,21685 ,0,0,0}, {37306,37305,37989 ,21686,21687,21688 ,0,0,0}, - {37306,38570,37308 ,21686,21689,21690 ,0,0,0}, {37285,37284,38555 ,21691,21692,21693 ,0,0,0}, - {38555,38571,37285 ,21693,21694,21691 ,0,0,0}, {38553,37284,37286 ,21695,21692,21696 ,0,0,0}, - {37284,38553,38555 ,21692,21695,21693 ,0,0,0}, {37302,37986,37286 ,21697,21698,21696 ,0,0,0}, - {38553,37286,37986 ,21695,21696,21698 ,0,0,0}, {37302,34858,3917 ,21697,2601,82 ,0,0,0}, - {3917,37986,37302 ,82,21698,21697 ,0,0,0}, {37307,37990,36227 ,21681,21680,21684 ,0,0,0}, - {37305,38571,37989 ,21687,21694,21688 ,0,0,0}, {37285,38571,37305 ,21691,21694,21687 ,0,0,0}, - {36877,38179,36241 ,21677,20873,21627 ,0,0,0}, {37308,38570,38556 ,21690,21689,21682 ,0,0,0}, - {37306,37989,38570 ,21686,21688,21689 ,0,0,0}, {37307,37308,38556 ,21681,21690,21682 ,0,0,0}, - {37987,36227,37990 ,21685,21684,21680 ,0,0,0}, {37988,36877,36228 ,21603,21677,21683 ,0,0,0}, - {36228,37987,37988 ,21683,21685,21603 ,0,0,0}, {37961,37311,36276 ,21679,21676,21631 ,0,0,0}, - {36241,37551,36276 ,21627,21678,21631 ,0,0,0}, {38179,37551,36241 ,20873,21678,21627 ,0,0,0}, - {34845,38568,3931 ,8383,21653,126 ,0,0,0}, {37311,37961,38568 ,21676,21679,21653 ,0,0,0}, - {34815,37321,37880 ,21585,17362,21699 ,0,0,0}, {38585,37826,36360 ,21700,21701,21702 ,0,0,0}, - {37825,37885,37340 ,21703,20903,21704 ,0,0,0}, {38723,37319,37830 ,21705,21706,21707 ,0,0,0}, - {36390,37447,38725 ,21708,21709,21710 ,0,0,0}, {37318,36382,38576 ,21711,21712,21713 ,0,0,0}, - {37318,37828,36385 ,21711,21714,21715 ,0,0,0}, {36367,37317,38246 ,21716,21717,21718 ,0,0,0}, - {38246,38577,36367 ,21718,21719,21716 ,0,0,0}, {37867,37317,37316 ,21720,21717,21721 ,0,0,0}, - {37317,37867,38246 ,21717,21720,21718 ,0,0,0}, {37315,38589,37316 ,21722,21723,21721 ,0,0,0}, - {37867,37316,38589 ,21720,21721,21723 ,0,0,0}, {37315,34828,2165 ,21722,19655,82 ,0,0,0}, - {2165,38589,37315 ,82,21723,21722 ,0,0,0}, {37319,38723,37447 ,21706,21705,21709 ,0,0,0}, - {36382,38577,38576 ,21712,21719,21713 ,0,0,0}, {36367,38577,36382 ,21716,21719,21712 ,0,0,0}, - {36360,37826,36361 ,21702,21701,21724 ,0,0,0}, {36385,37828,37830 ,21715,21714,21707 ,0,0,0}, - {37318,38576,37828 ,21711,21713,21714 ,0,0,0}, {37319,36385,37830 ,21706,21715,21707 ,0,0,0}, - {38725,37447,38723 ,21710,21709,21705 ,0,0,0}, {38585,36360,36390 ,21700,21702,21708 ,0,0,0}, - {36390,38725,38585 ,21708,21710,21700 ,0,0,0}, {37885,37321,37340 ,20903,17362,21704 ,0,0,0}, - {36361,37825,37340 ,21724,21703,21704 ,0,0,0}, {37826,37825,36361 ,21701,21703,21724 ,0,0,0}, - {34815,37880,2941 ,21585,21699,126 ,0,0,0}, {37321,37885,37880 ,17362,20903,21699 ,0,0,0}, - {34783,37330,38593 ,21585,21725,21726 ,0,0,0}, {38322,37818,37059 ,21727,21728,21729 ,0,0,0}, - {37874,37873,36915 ,21656,21730,21731 ,0,0,0}, {37878,37058,38323 ,21732,21733,21734 ,0,0,0}, - {36922,36921,37877 ,21735,21736,21710 ,0,0,0}, {36919,36920,37858 ,21737,21738,21739 ,0,0,0}, - {36919,38324,37329 ,21737,21740,21741 ,0,0,0}, {37326,36442,38597 ,21742,21743,21744 ,0,0,0}, - {38597,37859,37326 ,21744,21745,21742 ,0,0,0}, {38238,36442,36441 ,21746,21743,21747 ,0,0,0}, - {36442,38238,38597 ,21743,21746,21744 ,0,0,0}, {37063,38598,36441 ,21748,21749,21747 ,0,0,0}, - {38238,36441,38598 ,21746,21747,21749 ,0,0,0}, {37063,34797,34798 ,21748,21750,82 ,0,0,0}, - {34798,38598,37063 ,82,21749,21748 ,0,0,0}, {37058,37878,36921 ,21733,21732,21736 ,0,0,0}, - {36920,37859,37858 ,21738,21745,21739 ,0,0,0}, {37326,37859,36920 ,21742,21745,21738 ,0,0,0}, - {37059,37818,36444 ,21729,21728,21724 ,0,0,0}, {37329,38324,38323 ,21741,21740,21734 ,0,0,0}, - {36919,37858,38324 ,21737,21739,21740 ,0,0,0}, {37058,37329,38323 ,21733,21741,21734 ,0,0,0}, - {37877,36921,37878 ,21710,21736,21732 ,0,0,0}, {38322,37059,36922 ,21727,21729,21735 ,0,0,0}, - {36922,37877,38322 ,21735,21710,21727 ,0,0,0}, {37873,37330,36915 ,21730,21725,21731 ,0,0,0}, - {36444,37874,36915 ,21724,21656,21731 ,0,0,0}, {37818,37874,36444 ,21728,21656,21724 ,0,0,0}, - {34783,38593,34784 ,21585,21726,126 ,0,0,0}, {37330,37873,38593 ,21725,21730,21726 ,0,0,0}, - {34753,37334,38607 ,21585,21725,21726 ,0,0,0}, {38624,38606,36350 ,21751,20873,21752 ,0,0,0}, - {38219,38726,37448 ,21656,21730,21753 ,0,0,0}, {38223,36412,38611 ,21754,21755,21756 ,0,0,0}, - {36418,36420,38222 ,21757,21758,21710 ,0,0,0}, {36934,37054,38337 ,21759,21760,21761 ,0,0,0}, - {36934,38334,36411 ,21759,21762,21763 ,0,0,0}, {37057,37056,38613 ,21764,21765,21766 ,0,0,0}, - {38613,38335,37057 ,21766,21767,21764 ,0,0,0}, {38339,37056,36421 ,21768,21765,21769 ,0,0,0}, - {37056,38339,38613 ,21765,21768,21766 ,0,0,0}, {36423,38340,36421 ,21770,21771,21769 ,0,0,0}, - {38339,36421,38340 ,21768,21769,21771 ,0,0,0}, {36423,34766,2131 ,21770,21750,82 ,0,0,0}, - {2131,38340,36423 ,82,21771,21770 ,0,0,0}, {36412,38223,36420 ,21755,21754,21758 ,0,0,0}, - {37054,38335,38337 ,21760,21767,21761 ,0,0,0}, {37057,38335,37054 ,21764,21767,21760 ,0,0,0}, - {36350,38606,36351 ,21752,20873,21724 ,0,0,0}, {36411,38334,38611 ,21763,21762,21756 ,0,0,0}, - {36934,38337,38334 ,21759,21761,21762 ,0,0,0}, {36412,36411,38611 ,21755,21763,21756 ,0,0,0}, - {38222,36420,38223 ,21710,21758,21754 ,0,0,0}, {38624,36350,36418 ,21751,21752,21757 ,0,0,0}, - {36418,38222,38624 ,21757,21710,21751 ,0,0,0}, {38726,37334,37448 ,21730,21725,21753 ,0,0,0}, - {36351,38219,37448 ,21724,21656,21753 ,0,0,0}, {38606,38219,36351 ,20873,21656,21724 ,0,0,0}, - {34753,38607,2950 ,21585,21726,126 ,0,0,0}, {37334,38726,38607 ,21725,21730,21726 ,0,0,0}, - {34721,36955,37846 ,21585,17362,21699 ,0,0,0}, {37834,37833,36402 ,21772,21773,21774 ,0,0,0}, - {38215,37898,36954 ,21703,20903,21775 ,0,0,0}, {37841,37346,38218 ,21776,21777,21778 ,0,0,0}, - {36401,36398,38216 ,21779,21780,21710 ,0,0,0}, {36946,36408,38618 ,21781,21782,21783 ,0,0,0}, - {36946,38619,36947 ,21781,21784,21785 ,0,0,0}, {36409,37336,38221 ,21786,21787,21788 ,0,0,0}, - {38221,38620,36409 ,21788,21789,21786 ,0,0,0}, {38622,37336,37450 ,21790,21787,21791 ,0,0,0}, - {37336,38622,38221 ,21787,21790,21788 ,0,0,0}, {36937,38229,37450 ,21792,21793,21791 ,0,0,0}, - {38622,37450,38229 ,21790,21791,21793 ,0,0,0}, {36937,34735,34736 ,21792,19655,82 ,0,0,0}, - {34736,38229,36937 ,82,21793,21792 ,0,0,0}, {37346,37841,36398 ,21777,21776,21780 ,0,0,0}, - {36408,38620,38618 ,21782,21789,21783 ,0,0,0}, {36409,38620,36408 ,21786,21789,21782 ,0,0,0}, - {36402,37833,37337 ,21774,21773,21724 ,0,0,0}, {36947,38619,38218 ,21785,21784,21778 ,0,0,0}, - {36946,38618,38619 ,21781,21783,21784 ,0,0,0}, {37346,36947,38218 ,21777,21785,21778 ,0,0,0}, - {38216,36398,37841 ,21710,21780,21776 ,0,0,0}, {37834,36402,36401 ,21772,21774,21779 ,0,0,0}, - {36401,38216,37834 ,21779,21710,21772 ,0,0,0}, {37898,36955,36954 ,20903,17362,21775 ,0,0,0}, - {37337,38215,36954 ,21724,21703,21775 ,0,0,0}, {37833,38215,37337 ,21773,21703,21724 ,0,0,0}, - {34721,37846,34722 ,21585,21699,126 ,0,0,0}, {36955,37898,37846 ,17362,20903,21699 ,0,0,0}, - {34691,37358,38628 ,8383,17362,20947 ,0,0,0}, {38252,37751,36970 ,21794,21795,21796 ,0,0,0}, - {37762,38626,36590 ,21656,21797,21798 ,0,0,0}, {37724,37354,38631 ,21799,21800,21801 ,0,0,0}, - {36579,36580,38253 ,21802,21803,21804 ,0,0,0}, {37364,37363,37722 ,21662,21805,21806 ,0,0,0}, - {37364,37723,37353 ,21662,21807,21808 ,0,0,0}, {36532,36531,38271 ,21809,21810,21811 ,0,0,0}, - {38271,37721,36532 ,21811,21812,21809 ,0,0,0}, {38637,36531,36570 ,21813,21810,21814 ,0,0,0}, - {36531,38637,38271 ,21810,21813,21811 ,0,0,0}, {36572,38272,36570 ,21815,21816,21814 ,0,0,0}, - {38637,36570,38272 ,21813,21814,21816 ,0,0,0}, {36572,34704,3029 ,21815,2601,82 ,0,0,0}, - {3029,38272,36572 ,82,21816,21815 ,0,0,0}, {37354,37724,36580 ,21800,21799,21803 ,0,0,0}, - {37363,37721,37722 ,21805,21812,21806 ,0,0,0}, {36532,37721,37363 ,21809,21812,21805 ,0,0,0}, - {36970,37751,37348 ,21796,21795,21817 ,0,0,0}, {37353,37723,38631 ,21808,21807,21801 ,0,0,0}, - {37364,37722,37723 ,21662,21806,21807 ,0,0,0}, {37354,37353,38631 ,21800,21808,21801 ,0,0,0}, - {38253,36580,37724 ,21804,21803,21799 ,0,0,0}, {38252,36970,36579 ,21794,21796,21802 ,0,0,0}, - {36579,38253,38252 ,21802,21804,21794 ,0,0,0}, {38626,37358,36590 ,21797,17362,21798 ,0,0,0}, - {37348,37762,36590 ,21817,21656,21798 ,0,0,0}, {37751,37762,37348 ,21795,21656,21817 ,0,0,0}, - {34691,38628,3015 ,8383,20947,126 ,0,0,0}, {37358,38626,38628 ,17362,21797,20947 ,0,0,0}, - {34659,36597,38645 ,8383,21818,20947 ,0,0,0}, {38675,38644,36979 ,21819,21820,21821 ,0,0,0}, - {38260,38740,37457 ,21822,21823,21607 ,0,0,0}, {38263,36564,38268 ,21824,21825,21826 ,0,0,0}, - {36977,36976,38265 ,21611,21827,21828 ,0,0,0}, {36585,36974,38636 ,21686,21829,21830 ,0,0,0}, - {36585,38267,36584 ,21686,21831,21832 ,0,0,0}, {36973,36563,38269 ,21833,21834,21835 ,0,0,0}, - {38269,38635,36973 ,21835,21836,21833 ,0,0,0}, {37718,36563,37360 ,21837,21834,21838 ,0,0,0}, - {36563,37718,38269 ,21834,21837,21835 ,0,0,0}, {36574,37717,37360 ,21839,21840,21838 ,0,0,0}, - {37718,37360,37717 ,21837,21838,21840 ,0,0,0}, {36574,34673,34674 ,21839,2601,82 ,0,0,0}, - {34674,37717,36574 ,82,21840,21839 ,0,0,0}, {36564,38263,36976 ,21825,21824,21827 ,0,0,0}, - {36974,38635,38636 ,21829,21836,21830 ,0,0,0}, {36973,38635,36974 ,21833,21836,21829 ,0,0,0}, - {36979,38644,36980 ,21821,21820,21841 ,0,0,0}, {36584,38267,38268 ,21832,21831,21826 ,0,0,0}, - {36585,38636,38267 ,21686,21830,21831 ,0,0,0}, {36564,36584,38268 ,21825,21832,21826 ,0,0,0}, - {38265,36976,38263 ,21828,21827,21824 ,0,0,0}, {38675,36979,36977 ,21819,21821,21611 ,0,0,0}, - {36977,38265,38675 ,21611,21828,21819 ,0,0,0}, {38740,36597,37457 ,21823,21818,21607 ,0,0,0}, - {36980,38260,37457 ,21841,21822,21607 ,0,0,0}, {38644,38260,36980 ,21820,21822,21841 ,0,0,0}, - {34659,38645,34660 ,8383,20947,126 ,0,0,0}, {36597,38740,38645 ,21818,21823,20947 ,0,0,0}, - {34627,36547,37733 ,21842,21843,21844 ,0,0,0}, {37731,38656,36540 ,20948,21845,21796 ,0,0,0}, - {38655,38284,37388 ,21605,21846,21847 ,0,0,0}, {38734,37375,37685 ,21848,21849,21850 ,0,0,0}, - {36604,37454,38737 ,21802,21851,21852 ,0,0,0}, {37374,36546,38652 ,21662,21853,21854 ,0,0,0}, - {37374,38665,36548 ,21662,21855,21856 ,0,0,0}, {36542,37373,38651 ,21857,21858,21859 ,0,0,0}, - {38651,38653,36542 ,21859,21860,21857 ,0,0,0}, {37741,37373,37372 ,21861,21858,21862 ,0,0,0}, - {37373,37741,38651 ,21858,21861,21859 ,0,0,0}, {36605,38661,37372 ,21863,21864,21862 ,0,0,0}, - {37741,37372,38661 ,21861,21862,21864 ,0,0,0}, {36605,34641,34642 ,21863,21650,82 ,0,0,0}, - {34642,38661,36605 ,82,21864,21863 ,0,0,0}, {37375,38734,37454 ,21849,21848,21851 ,0,0,0}, - {36546,38653,38652 ,21853,21860,21854 ,0,0,0}, {36542,38653,36546 ,21857,21860,21853 ,0,0,0}, - {36540,38656,36541 ,21796,21845,21865 ,0,0,0}, {36548,38665,37685 ,21856,21855,21850 ,0,0,0}, - {37374,38652,38665 ,21662,21854,21855 ,0,0,0}, {37375,36548,37685 ,21849,21856,21850 ,0,0,0}, - {38737,37454,38734 ,21852,21851,21848 ,0,0,0}, {37731,36540,36604 ,20948,21796,21802 ,0,0,0}, - {36604,38737,37731 ,21802,21852,20948 ,0,0,0}, {38284,36547,37388 ,21846,21843,21847 ,0,0,0}, - {36541,38655,37388 ,21865,21605,21847 ,0,0,0}, {38656,38655,36541 ,21845,21605,21865 ,0,0,0}, - {34627,37733,34628 ,21842,21844,8383 ,0,0,0}, {36547,38284,37733 ,21843,21846,21844 ,0,0,0}, - {34597,36989,37690 ,2619,21818,21866 ,0,0,0}, {38255,38257,37385 ,21867,21868,21869 ,0,0,0}, - {37697,38663,36558 ,21870,20903,21607 ,0,0,0}, {37587,36987,38259 ,21871,21872,21873 ,0,0,0}, - {36961,36963,37589 ,21874,21875,21828 ,0,0,0}, {36556,37394,38647 ,21614,21876,21877 ,0,0,0}, - {36556,38646,36557 ,21614,21878,21879 ,0,0,0}, {37393,37395,38261 ,21880,21881,21882 ,0,0,0}, - {38261,37703,37393 ,21882,21883,21880 ,0,0,0}, {38640,37395,37458 ,21884,21881,21885 ,0,0,0}, - {37395,38640,38261 ,21881,21884,21882 ,0,0,0}, {36587,38641,37458 ,21886,21887,21885 ,0,0,0}, - {38640,37458,38641 ,21884,21885,21887 ,0,0,0}, {36587,34610,3063 ,21886,82,2602 ,0,0,0}, - {3063,38641,36587 ,2602,21887,21886 ,0,0,0}, {36987,37587,36963 ,21872,21871,21875 ,0,0,0}, - {37394,37703,38647 ,21876,21883,21877 ,0,0,0}, {37393,37703,37394 ,21880,21883,21876 ,0,0,0}, - {37385,38257,36560 ,21869,21868,21627 ,0,0,0}, {36557,38646,38259 ,21879,21878,21873 ,0,0,0}, - {36556,38647,38646 ,21614,21877,21878 ,0,0,0}, {36987,36557,38259 ,21872,21879,21873 ,0,0,0}, - {37589,36963,37587 ,21828,21875,21871 ,0,0,0}, {38255,37385,36961 ,21867,21869,21874 ,0,0,0}, - {36961,37589,38255 ,21874,21828,21867 ,0,0,0}, {38663,36989,36558 ,20903,21818,21607 ,0,0,0}, - {36560,37697,36558 ,21627,21870,21607 ,0,0,0}, {38257,37697,36560 ,21868,21870,21627 ,0,0,0}, - {34597,37690,3049 ,2619,21866,126 ,0,0,0}, {36989,38663,37690 ,21818,20903,21866 ,0,0,0}, - {34567,37040,38521 ,21492,17362,21726 ,0,0,0}, {38729,38683,36726 ,21888,21889,21890 ,0,0,0}, - {38679,38522,37041 ,21656,21730,21891 ,0,0,0}, {38693,37402,38682 ,21705,21892,21893 ,0,0,0}, - {36725,37451,38731 ,21894,21736,21895 ,0,0,0}, {37401,36718,38676 ,21896,21897,21713 ,0,0,0}, - {37401,38680,36729 ,21896,21898,21741 ,0,0,0}, {36712,37400,37594 ,21899,21900,21901 ,0,0,0}, - {37594,38677,36712 ,21901,21902,21899 ,0,0,0}, {37590,37400,37399 ,21903,21900,21904 ,0,0,0}, - {37400,37590,37594 ,21900,21903,21901 ,0,0,0}, {36197,38687,37399 ,21905,21906,21904 ,0,0,0}, - {37590,37399,38687 ,21903,21904,21906 ,0,0,0}, {36197,34580,2082 ,21905,21907,82 ,0,0,0}, - {2082,38687,36197 ,82,21906,21905 ,0,0,0}, {37402,38693,37451 ,21892,21705,21736 ,0,0,0}, - {36718,38677,38676 ,21897,21902,21713 ,0,0,0}, {36712,38677,36718 ,21899,21902,21897 ,0,0,0}, - {36726,38683,37404 ,21890,21889,21908 ,0,0,0}, {36729,38680,38682 ,21741,21898,21893 ,0,0,0}, - {37401,38676,38680 ,21896,21713,21898 ,0,0,0}, {37402,36729,38682 ,21892,21741,21893 ,0,0,0}, - {38731,37451,38693 ,21895,21736,21705 ,0,0,0}, {38729,36726,36725 ,21888,21890,21894 ,0,0,0}, - {36725,38731,38729 ,21894,21895,21888 ,0,0,0}, {38522,37040,37041 ,21730,17362,21891 ,0,0,0}, - {37404,38679,37041 ,21908,21656,21891 ,0,0,0}, {38683,38679,37404 ,21889,21656,21908 ,0,0,0}, - {34567,38521,1263 ,21492,21726,126 ,0,0,0}, {37040,38522,38521 ,17362,21730,21726 ,0,0,0}, - {34535,37039,38685 ,21492,17362,21726 ,0,0,0}, {37515,38289,37029 ,21909,21910,21911 ,0,0,0}, - {37572,37571,37038 ,21656,21730,21912 ,0,0,0}, {38292,37033,37561 ,21776,21913,21914 ,0,0,0}, - {37419,37034,38291 ,21915,21758,21895 ,0,0,0}, {36709,37435,38295 ,21916,21917,21783 ,0,0,0}, - {36709,38294,36708 ,21916,21918,21763 ,0,0,0}, {37016,37015,38695 ,21919,21920,21921 ,0,0,0}, - {38695,38694,37016 ,21921,21922,21919 ,0,0,0}, {38297,37015,37456 ,21923,21920,21924 ,0,0,0}, - {37015,38297,38695 ,21920,21923,21921 ,0,0,0}, {37411,37562,37456 ,21925,21926,21924 ,0,0,0}, - {38297,37456,37562 ,21923,21924,21926 ,0,0,0}, {37411,34549,34550 ,21925,21907,82 ,0,0,0}, - {34550,37562,37411 ,82,21926,21925 ,0,0,0}, {37033,38292,37034 ,21913,21776,21758 ,0,0,0}, - {37435,38694,38295 ,21917,21922,21783 ,0,0,0}, {37016,38694,37435 ,21919,21922,21917 ,0,0,0}, - {37029,38289,37420 ,21911,21910,21908 ,0,0,0}, {36708,38294,37561 ,21763,21918,21914 ,0,0,0}, - {36709,38295,38294 ,21916,21783,21918 ,0,0,0}, {37033,36708,37561 ,21913,21763,21914 ,0,0,0}, - {38291,37034,38292 ,21895,21758,21776 ,0,0,0}, {37515,37029,37419 ,21909,21911,21915 ,0,0,0}, - {37419,38291,37515 ,21915,21895,21909 ,0,0,0}, {37571,37039,37038 ,21730,17362,21912 ,0,0,0}, - {37420,37572,37038 ,21908,21656,21912 ,0,0,0}, {38289,37572,37420 ,21910,21656,21908 ,0,0,0}, - {34535,38685,34536 ,21492,21726,126 ,0,0,0}, {37039,37571,38685 ,17362,21730,21726 ,0,0,0}, - {34505,37436,37555 ,21492,17362,21726 ,0,0,0}, {38301,38300,36705 ,21909,21910,21911 ,0,0,0}, - {38708,38738,37455 ,21656,21927,21775 ,0,0,0}, {37510,36698,37547 ,21776,21913,21928 ,0,0,0}, - {36707,37413,37512 ,21915,21929,21930 ,0,0,0}, {36697,36692,38309 ,21916,21931,21932 ,0,0,0}, - {36697,37548,36695 ,21916,21933,21934 ,0,0,0}, {36694,37012,38311 ,21764,21935,21936 ,0,0,0}, - {38311,38699,36694 ,21936,21937,21764 ,0,0,0}, {37567,37012,37421 ,21938,21935,21939 ,0,0,0}, - {37012,37567,38311 ,21935,21938,21936 ,0,0,0}, {37008,37568,37421 ,21940,21941,21939 ,0,0,0}, - {37567,37421,37568 ,21938,21939,21941 ,0,0,0}, {37008,34518,2073 ,21940,19633,82 ,0,0,0}, - {2073,37568,37008 ,82,21941,21940 ,0,0,0}, {36698,37510,37413 ,21913,21776,21929 ,0,0,0}, - {36692,38699,38309 ,21931,21937,21932 ,0,0,0}, {36694,38699,36692 ,21764,21937,21931 ,0,0,0}, - {36705,38300,37014 ,21911,21910,21627 ,0,0,0}, {36695,37548,37547 ,21934,21933,21928 ,0,0,0}, - {36697,38309,37548 ,21916,21932,21933 ,0,0,0}, {36698,36695,37547 ,21913,21934,21928 ,0,0,0}, - {37512,37413,37510 ,21930,21929,21776 ,0,0,0}, {38301,36705,36707 ,21909,21911,21915 ,0,0,0}, - {36707,37512,38301 ,21915,21930,21909 ,0,0,0}, {38738,37436,37455 ,21927,17362,21775 ,0,0,0}, - {37014,38708,37455 ,21627,21656,21775 ,0,0,0}, {38300,38708,37014 ,21910,21656,21627 ,0,0,0}, - {34505,37555,1297 ,21492,21726,126 ,0,0,0}, {37436,38738,37555 ,17362,21927,21726 ,0,0,0}, - {34473,37443,38716 ,21492,17362,21726 ,0,0,0}, {37504,37586,36702 ,21888,21889,21890 ,0,0,0}, - {37527,37526,36703 ,21656,21927,21704 ,0,0,0}, {37569,37439,38704 ,21705,21892,21942 ,0,0,0}, - {36258,36257,37505 ,21894,21943,21930 ,0,0,0}, {37438,37437,37580 ,21896,21944,21945 ,0,0,0}, - {37438,38718,37440 ,21896,21946,21947 ,0,0,0}, {37002,37001,37531 ,21742,21948,21949 ,0,0,0}, - {37531,38719,37002 ,21949,21950,21742 ,0,0,0}, {37532,37001,37004 ,21951,21948,21952 ,0,0,0}, - {37001,37532,37531 ,21948,21951,21949 ,0,0,0}, {37426,37538,37004 ,21953,21954,21952 ,0,0,0}, - {37532,37004,37538 ,21951,21952,21954 ,0,0,0}, {37426,34487,34488 ,21953,19633,82 ,0,0,0}, - {34488,37538,37426 ,82,21954,21953 ,0,0,0}, {37439,37569,36257 ,21892,21705,21943 ,0,0,0}, - {37437,38719,37580 ,21944,21950,21945 ,0,0,0}, {37002,38719,37437 ,21742,21950,21944 ,0,0,0}, - {36702,37586,36701 ,21890,21889,21627 ,0,0,0}, {37440,38718,38704 ,21947,21946,21942 ,0,0,0}, - {37438,37580,38718 ,21896,21945,21946 ,0,0,0}, {37439,37440,38704 ,21892,21947,21942 ,0,0,0}, - {37505,36257,37569 ,21930,21943,21705 ,0,0,0}, {37504,36702,36258 ,21888,21890,21894 ,0,0,0}, - {36258,37505,37504 ,21894,21930,21888 ,0,0,0}, {37526,37443,36703 ,21927,17362,21704 ,0,0,0}, - {36701,37527,36703 ,21627,21656,21704 ,0,0,0}, {37586,37527,36701 ,21889,21656,21627 ,0,0,0}, - {34473,38716,34474 ,21492,21726,126 ,0,0,0}, {37443,37526,38716 ,17362,21927,21726 ,0,0,0}, - {37820,12921,37821 ,21955,21956,18609 ,0,0,0}, {37820,34442,12921 ,21955,18573,21956 ,0,0,0}, - {34442,37820,34441 ,18573,21955,18573 ,0,0,0}, {37327,37821,12921 ,18609,18609,21956 ,0,0,0}, - {34449,38241,36395 ,18594,21957,21957 ,0,0,0}, {38578,36355,37863 ,21958,21958,21959 ,0,0,0}, - {36396,36914,37868 ,21959,21960,21960 ,0,0,0}, {37865,37327,37324 ,21961,18609,21961 ,0,0,0}, - {37324,38578,37865 ,21961,21958,21961 ,0,0,0}, {37821,37327,37865 ,18609,18609,21961 ,0,0,0}, - {37324,36355,38578 ,21961,21958,21958 ,0,0,0}, {36396,37863,36355 ,21959,21959,21958 ,0,0,0}, - {37863,36396,37868 ,21959,21959,21960 ,0,0,0}, {36395,34450,34449 ,21957,18594,18594 ,0,0,0}, - {38241,36914,36395 ,21957,21960,21957 ,0,0,0}, {37868,36914,38241 ,21960,21960,21957 ,0,0,0}, - {38325,34455,37313 ,21962,18581,21963 ,0,0,0}, {34455,34456,37313 ,18581,18581,21963 ,0,0,0}, - {36363,38325,37313 ,18601,21962,21963 ,0,0,0}, {38325,36363,38595 ,21962,18601,18601 ,0,0,0}, - {34435,37876,36392 ,18588,21964,21964 ,0,0,0}, {37875,36389,38594 ,21965,21965,21966 ,0,0,0}, - {36916,37331,38592 ,21966,21967,21967 ,0,0,0}, {38596,36363,36362 ,21968,18601,21968 ,0,0,0}, - {36362,37875,38596 ,21968,21965,21968 ,0,0,0}, {38595,36363,38596 ,18601,18601,21968 ,0,0,0}, - {36362,36389,37875 ,21968,21965,21965 ,0,0,0}, {36916,38594,36389 ,21966,21966,21965 ,0,0,0}, - {38594,36916,38592 ,21966,21966,21967 ,0,0,0}, {36392,34436,34435 ,21964,18588,18588 ,0,0,0}, - {37876,37331,36392 ,21964,21967,21964 ,0,0,0}, {38592,37331,37876 ,21967,21967,21964 ,0,0,0}, - {37857,36372,37851 ,21969,21970,18594 ,0,0,0}, {37857,34414,36372 ,21969,18575,21970 ,0,0,0}, - {34414,37857,34413 ,18575,21969,18575 ,0,0,0}, {36380,37851,36372 ,18594,18594,21970 ,0,0,0}, - {34421,38616,36959 ,18581,21971,21971 ,0,0,0}, {37854,36377,37855 ,21972,21972,21973 ,0,0,0}, - {36366,36358,38213 ,21973,21974,21974 ,0,0,0}, {37891,36380,36378 ,21975,18594,21975 ,0,0,0}, - {36378,37854,37891 ,21975,21972,21975 ,0,0,0}, {37851,36380,37891 ,18594,18594,21975 ,0,0,0}, - {36378,36377,37854 ,21975,21972,21972 ,0,0,0}, {36366,37855,36377 ,21973,21973,21972 ,0,0,0}, - {37855,36366,38213 ,21973,21973,21974 ,0,0,0}, {36959,34422,34421 ,21971,18581,18581 ,0,0,0}, - {38616,36358,36959 ,21971,21974,21971 ,0,0,0}, {38213,36358,38616 ,21974,21974,21971 ,0,0,0}, - {38724,34427,37343 ,21976,18583,82 ,0,0,0}, {34427,34428,37343 ,18583,18583,82 ,0,0,0}, - {37342,38724,37343 ,18588,21976,82 ,0,0,0}, {38724,37342,37870 ,21976,18588,18588 ,0,0,0}, - {34407,38586,37320 ,18573,21977,21977 ,0,0,0}, {38588,36958,37829 ,21978,21978,21979 ,0,0,0}, - {36384,36386,37889 ,21979,21980,21980 ,0,0,0}, {37869,37342,36359 ,21981,18588,21981 ,0,0,0}, - {36359,38588,37869 ,21981,21978,21981 ,0,0,0}, {37870,37342,37869 ,18588,18588,21981 ,0,0,0}, - {36359,36958,38588 ,21981,21978,21978 ,0,0,0}, {36384,37829,36958 ,21979,21979,21978 ,0,0,0}, - {37829,36384,37889 ,21979,21979,21980 ,0,0,0}, {37320,34408,34407 ,21977,18573,18573 ,0,0,0}, - {38586,36386,37320 ,21977,21980,21977 ,0,0,0}, {37889,36386,38586 ,21980,21980,21977 ,0,0,0}, - {2303,12820,38603 ,21982,21983,18581 ,0,0,0}, {2303,34386,12820 ,21982,18601,21983 ,0,0,0}, - {34386,2303,34385 ,18601,21982,18601 ,0,0,0}, {36406,38603,12820 ,18581,18581,21983 ,0,0,0}, - {34393,38623,36419 ,18583,21984,21984 ,0,0,0}, {38610,36943,38327 ,21985,21985,21986 ,0,0,0}, - {36410,36913,38224 ,21986,21987,21987 ,0,0,0}, {38329,36406,36944 ,21988,18581,21988 ,0,0,0}, - {36944,38610,38329 ,21988,21985,21988 ,0,0,0}, {38603,36406,38329 ,18581,18581,21988 ,0,0,0}, - {36944,36943,38610 ,21988,21985,21985 ,0,0,0}, {36410,38327,36943 ,21986,21986,21985 ,0,0,0}, - {38327,36410,38224 ,21986,21986,21987 ,0,0,0}, {36419,34394,34393 ,21984,18583,18583 ,0,0,0}, - {38623,36913,36419 ,21984,21987,21984 ,0,0,0}, {38224,36913,38623 ,21987,21987,21984 ,0,0,0}, - {37849,34399,37051 ,21989,18609,21990 ,0,0,0}, {34399,34400,37051 ,18609,18609,21990 ,0,0,0}, - {36416,37849,37051 ,18573,21989,21990 ,0,0,0}, {37849,36416,37847 ,21989,18573,18573 ,0,0,0}, - {34379,38220,37344 ,18575,21991,21991 ,0,0,0}, {37831,36941,37838 ,21992,21992,21993 ,0,0,0}, - {36414,36413,37837 ,21993,21994,21994 ,0,0,0}, {37894,36416,36415 ,21995,18573,21996 ,0,0,0}, - {36415,37831,37894 ,21996,21992,21995 ,0,0,0}, {37847,36416,37894 ,18573,18573,21995 ,0,0,0}, - {36415,36941,37831 ,21996,21992,21992 ,0,0,0}, {36414,37838,36941 ,21993,21993,21992 ,0,0,0}, - {37838,36414,37837 ,21993,21993,21994 ,0,0,0}, {37344,34380,34379 ,21991,18575,18575 ,0,0,0}, - {38220,36413,37344 ,21991,21994,21991 ,0,0,0}, {37837,36413,38220 ,21994,21994,21991 ,0,0,0}, - {38509,37347,37756 ,21997,21998,18609 ,0,0,0}, {38509,34358,37347 ,21997,18573,21998 ,0,0,0}, - {34358,38509,34357 ,18573,21997,18573 ,0,0,0}, {37239,37756,37347 ,18609,18609,21998 ,0,0,0}, - {34365,37747,36960 ,18594,18610,18610 ,0,0,0}, {38728,37237,38277 ,21999,21999,22000 ,0,0,0}, - {37242,37371,38278 ,22000,22001,22001 ,0,0,0}, {37738,37239,36593 ,22002,18609,22002 ,0,0,0}, - {36593,38728,37738 ,22002,21999,22002 ,0,0,0}, {37756,37239,37738 ,18609,18609,22002 ,0,0,0}, - {36593,37237,38728 ,22002,21999,21999 ,0,0,0}, {37242,38277,37237 ,22000,22000,21999 ,0,0,0}, - {38277,37242,38278 ,22000,22000,22001 ,0,0,0}, {36960,34366,34365 ,18610,18594,18594 ,0,0,0}, - {37747,37371,36960 ,18610,22001,18610 ,0,0,0}, {38278,37371,37747 ,22001,22001,18610 ,0,0,0}, - {38625,34371,37370 ,22003,18581,22004 ,0,0,0}, {34371,34372,37370 ,18581,18581,22004 ,0,0,0}, - {36967,38625,37370 ,18601,22003,22004 ,0,0,0}, {38625,36967,38274 ,22003,18601,18601 ,0,0,0}, - {34351,38630,36529 ,18588,22005,22005 ,0,0,0}, {37761,36589,38629 ,22006,22006,22007 ,0,0,0}, - {36588,37359,38627 ,22007,22008,22008 ,0,0,0}, {38275,36967,36968 ,22009,18601,22009 ,0,0,0}, - {36968,37761,38275 ,22009,22006,22009 ,0,0,0}, {38274,36967,38275 ,18601,18601,22009 ,0,0,0}, - {36968,36589,37761 ,22009,22006,22006 ,0,0,0}, {36588,38629,36589 ,22007,22007,22006 ,0,0,0}, - {38629,36588,38627 ,22007,22007,22008 ,0,0,0}, {36529,34352,34351 ,22005,18588,18588 ,0,0,0}, - {38630,37359,36529 ,22005,22008,22005 ,0,0,0}, {38627,37359,38630 ,22008,22008,22005 ,0,0,0}, - {37581,37406,37574 ,22010,22011,18594 ,0,0,0}, {37581,34330,37406 ,22010,18575,22011 ,0,0,0}, - {34330,37581,34329 ,18575,22010,18575 ,0,0,0}, {37407,37574,37406 ,18594,18594,22011 ,0,0,0}, - {34337,38684,36723 ,18581,22012,22012 ,0,0,0}, {37577,37405,37596 ,22013,22013,22014 ,0,0,0}, - {36731,36724,37597 ,22014,22015,22015 ,0,0,0}, {37575,37407,36722 ,22016,18594,22016 ,0,0,0}, - {36722,37577,37575 ,22016,22013,22016 ,0,0,0}, {37574,37407,37575 ,18594,18594,22016 ,0,0,0}, - {36722,37405,37577 ,22016,22013,22013 ,0,0,0}, {36731,37596,37405 ,22014,22014,22013 ,0,0,0}, - {37596,36731,37597 ,22014,22014,22015 ,0,0,0}, {36723,34338,34337 ,22012,18581,18581 ,0,0,0}, - {38684,36724,36723 ,22012,22015,22012 ,0,0,0}, {37597,36724,38684 ,22015,22015,22012 ,0,0,0}, - {38730,34343,37409 ,22017,18583,22018 ,0,0,0}, {34343,34344,37409 ,18583,18583,22018 ,0,0,0}, - {37408,38730,37409 ,18588,22017,22018 ,0,0,0}, {38730,37408,38317 ,22017,18588,18588 ,0,0,0}, - {34323,38692,37403 ,18573,22019,22019 ,0,0,0}, {38686,37035,38681 ,22020,22020,22021 ,0,0,0}, - {36728,36727,38691 ,22021,22022,22022 ,0,0,0}, {38318,37408,37036 ,22023,18588,22023 ,0,0,0}, - {37036,38686,38318 ,22023,22020,22023 ,0,0,0}, {38317,37408,38318 ,18588,18588,22023 ,0,0,0}, - {37036,37035,38686 ,22023,22020,22020 ,0,0,0}, {36728,38681,37035 ,22021,22021,22020 ,0,0,0}, - {38681,36728,38691 ,22021,22021,22022 ,0,0,0}, {37403,34324,34323 ,22019,18573,18573 ,0,0,0}, - {38692,36727,37403 ,22019,22022,22019 ,0,0,0}, {38691,36727,38692 ,22022,22022,22019 ,0,0,0}, - {38013,36872,37994 ,22024,22025,18581 ,0,0,0}, {38013,34302,36872 ,22024,18601,22025 ,0,0,0}, - {34302,38013,34301 ,18601,22024,18601 ,0,0,0}, {37224,37994,36872 ,18581,18581,22025 ,0,0,0}, - {34309,38546,37273 ,18583,22026,22026 ,0,0,0}, {38732,37226,37474 ,22027,22027,22028 ,0,0,0}, - {37217,37274,37475 ,22028,22029,22029 ,0,0,0}, {38563,37224,36904 ,22030,18581,22030 ,0,0,0}, - {36904,38732,38563 ,22030,22027,22030 ,0,0,0}, {37994,37224,38563 ,18581,18581,22030 ,0,0,0}, - {36904,37226,38732 ,22030,22027,22027 ,0,0,0}, {37217,37474,37226 ,22028,22028,22027 ,0,0,0}, - {37474,37217,37475 ,22028,22028,22029 ,0,0,0}, {37273,34310,34309 ,22026,18583,18583 ,0,0,0}, - {38546,37274,37273 ,22026,22029,22026 ,0,0,0}, {37475,37274,38546 ,22029,22029,22026 ,0,0,0}, - {38010,34315,36893 ,22031,18609,22032 ,0,0,0}, {34315,34316,36893 ,18609,18609,22032 ,0,0,0}, - {36884,38010,36893 ,18573,22031,22032 ,0,0,0}, {38010,36884,38011 ,22031,18573,18573 ,0,0,0}, - {34295,37996,36302 ,18575,22033,22033 ,0,0,0}, {38005,36898,38488 ,22034,22034,22035 ,0,0,0}, - {37225,37268,38489 ,22035,22036,22036 ,0,0,0}, {38183,36884,36883 ,22037,18573,22037 ,0,0,0}, - {36883,38005,38183 ,22037,22034,22037 ,0,0,0}, {38011,36884,38183 ,18573,18573,22037 ,0,0,0}, - {36883,36898,38005 ,22037,22034,22034 ,0,0,0}, {37225,38488,36898 ,22035,22035,22034 ,0,0,0}, - {38488,37225,38489 ,22035,22035,22036 ,0,0,0}, {36302,34296,34295 ,22033,18575,18575 ,0,0,0}, - {37996,37268,36302 ,22033,22036,22033 ,0,0,0}, {38489,37268,37996 ,22036,22036,22033 ,0,0,0}, - {37689,36545,37725 ,22038,22039,18594 ,0,0,0}, {37689,34274,36545 ,22038,18575,22039 ,0,0,0}, - {34274,37689,34273 ,18575,22038,18575 ,0,0,0}, {37380,37725,36545 ,18594,18594,22039 ,0,0,0}, - {34281,38658,36553 ,18581,22040,22040 ,0,0,0}, {38666,36991,38669 ,22041,22041,22042 ,0,0,0}, - {36551,36554,37728 ,22042,22043,22043 ,0,0,0}, {37593,37380,37377 ,22044,18594,22044 ,0,0,0}, - {37377,38666,37593 ,22044,22041,22044 ,0,0,0}, {37725,37380,37593 ,18594,18594,22044 ,0,0,0}, - {37377,36991,38666 ,22044,22041,22041 ,0,0,0}, {36551,38669,36991 ,22042,22042,22041 ,0,0,0}, - {38669,36551,37728 ,22042,22042,22043 ,0,0,0}, {36553,34282,34281 ,22040,18581,18581 ,0,0,0}, - {38658,36554,36553 ,22040,22043,22040 ,0,0,0}, {37728,36554,38658 ,22043,22043,22040 ,0,0,0}, - {38736,34287,37390 ,22045,18583,22046 ,0,0,0}, {34287,34288,37390 ,18583,18583,22046 ,0,0,0}, - {37389,38736,37390 ,18588,22045,22046 ,0,0,0}, {38736,37389,38280 ,22045,18588,18588 ,0,0,0}, - {34267,37730,37376 ,18573,22047,22047 ,0,0,0}, {38660,36990,37686 ,22048,22048,22049 ,0,0,0}, - {36550,36549,37684 ,22049,22050,22050 ,0,0,0}, {38279,37389,36539 ,22051,18588,22051 ,0,0,0}, - {36539,38660,38279 ,22051,22048,22051 ,0,0,0}, {38280,37389,38279 ,18588,18588,22051 ,0,0,0}, - {36539,36990,38660 ,22051,22048,22048 ,0,0,0}, {36550,37686,36990 ,22049,22049,22048 ,0,0,0}, - {37686,36550,37684 ,22049,22049,22050 ,0,0,0}, {37376,34268,34267 ,22047,18573,18573 ,0,0,0}, - {37730,36549,37376 ,22047,22050,22047 ,0,0,0}, {37684,36549,37730 ,22050,22050,22047 ,0,0,0}, - {38303,37023,38305 ,22052,22053,18581 ,0,0,0}, {38303,34246,37023 ,22052,18601,22053 ,0,0,0}, - {34246,38303,34245 ,18601,22052,18601 ,0,0,0}, {37415,38305,37023 ,18581,18581,22053 ,0,0,0}, - {34253,38299,36706 ,18583,22054,22054 ,0,0,0}, {37582,37433,37560 ,22055,22055,22056 ,0,0,0}, - {36700,36699,37511 ,22056,22057,22057 ,0,0,0}, {38307,37415,37021 ,22058,18581,22058 ,0,0,0}, - {37021,37582,38307 ,22058,22055,22058 ,0,0,0}, {38305,37415,38307 ,18581,18581,22058 ,0,0,0}, - {37021,37433,37582 ,22058,22055,22055 ,0,0,0}, {36700,37560,37433 ,22056,22056,22055 ,0,0,0}, - {37560,36700,37511 ,22056,22056,22057 ,0,0,0}, {36706,34254,34253 ,22054,18583,18583 ,0,0,0}, - {38299,36699,36706 ,22054,22057,22054 ,0,0,0}, {37511,36699,38299 ,22057,22057,22054 ,0,0,0}, - {37543,34259,36262 ,22059,18609,21990 ,0,0,0}, {34259,34260,36262 ,18609,18609,21990 ,0,0,0}, - {36995,37543,36262 ,18573,22059,21990 ,0,0,0}, {37543,36995,37523 ,22059,18573,18573 ,0,0,0}, - {34239,38298,37412 ,18575,22060,22060 ,0,0,0}, {37541,36251,38707 ,22061,22061,22062 ,0,0,0}, - {37410,37017,37563 ,22062,22063,22063 ,0,0,0}, {37524,36995,36997 ,22064,18573,22065 ,0,0,0}, - {36997,37541,37524 ,22065,22061,22064 ,0,0,0}, {37523,36995,37524 ,18573,18573,22064 ,0,0,0}, - {36997,36251,37541 ,22065,22061,22061 ,0,0,0}, {37410,38707,36251 ,22062,22062,22061 ,0,0,0}, - {38707,37410,37563 ,22062,22062,22063 ,0,0,0}, {37412,34240,34239 ,22060,18575,18575 ,0,0,0}, - {38298,37017,37412 ,22060,22063,22060 ,0,0,0}, {37563,37017,38298 ,22063,22063,22060 ,0,0,0}, - {38199,36296,38197 ,22066,22067,18583 ,0,0,0}, {38199,34218,36296 ,22066,18588,22067 ,0,0,0}, - {34218,38199,34217 ,18588,22066,18588 ,0,0,0}, {36873,38197,36296 ,18583,18583,22067 ,0,0,0}, - {34225,38554,37287 ,18609,22068,22068 ,0,0,0}, {38201,36879,37984 ,22069,22069,22070 ,0,0,0}, - {37303,37288,37985 ,22070,20861,20861 ,0,0,0}, {38200,36873,36875 ,22071,18583,22071 ,0,0,0}, - {36875,38201,38200 ,22071,22069,22071 ,0,0,0}, {38197,36873,38200 ,18583,18583,22071 ,0,0,0}, - {36875,36879,38201 ,22071,22069,22069 ,0,0,0}, {37303,37984,36879 ,22070,22070,22069 ,0,0,0}, - {37984,37303,37985 ,22070,22070,20861 ,0,0,0}, {37287,34226,34225 ,22068,18609,18609 ,0,0,0}, - {38554,37288,37287 ,22068,20861,22068 ,0,0,0}, {37985,37288,38554 ,20861,20861,22068 ,0,0,0}, - {38739,34231,37310 ,22072,18594,22073 ,0,0,0}, {34231,34232,37310 ,18594,18594,22073 ,0,0,0}, - {37309,38739,37310 ,18575,22072,22073 ,0,0,0}, {38739,37309,38002 ,22072,18575,18575 ,0,0,0}, - {34211,38552,36231 ,18601,22074,18635 ,0,0,0}, {37992,36240,37556 ,22075,22075,22076 ,0,0,0}, - {36233,36882,37557 ,22076,22077,22077 ,0,0,0}, {37991,37309,36238 ,22078,18575,22078 ,0,0,0}, - {36238,37992,37991 ,22078,22075,22078 ,0,0,0}, {38002,37309,37991 ,18575,18575,22078 ,0,0,0}, - {36238,36240,37992 ,22078,22075,22075 ,0,0,0}, {36233,37556,36240 ,22076,22076,22075 ,0,0,0}, - {37556,36233,37557 ,22076,22076,22077 ,0,0,0}, {36231,34212,34211 ,18635,18601,18601 ,0,0,0}, - {38552,36882,36231 ,22074,22077,18635 ,0,0,0}, {37557,36882,38552 ,22077,22077,22074 ,0,0,0}, - {37708,36537,37711 ,22079,22080,18581 ,0,0,0}, {37708,34190,36537 ,22079,18601,22080 ,0,0,0}, - {34190,37708,34189 ,18601,22079,18601 ,0,0,0}, {36538,37711,36537 ,18581,18581,22080 ,0,0,0}, - {34197,38674,36975 ,18583,22081,22081 ,0,0,0}, {37712,36982,38266 ,22082,22082,22083 ,0,0,0}, - {36561,36565,38264 ,22083,18670,18670 ,0,0,0}, {38650,36538,36983 ,22084,18581,22084 ,0,0,0}, - {36983,37712,38650 ,22084,22082,22084 ,0,0,0}, {37711,36538,38650 ,18581,18581,22084 ,0,0,0}, - {36983,36982,37712 ,22084,22082,22082 ,0,0,0}, {36561,38266,36982 ,22083,22083,22082 ,0,0,0}, - {38266,36561,38264 ,22083,22083,18670 ,0,0,0}, {36975,34198,34197 ,22081,18583,18583 ,0,0,0}, - {38674,36565,36975 ,22081,18670,22081 ,0,0,0}, {38264,36565,38674 ,18670,18670,22081 ,0,0,0}, - {37715,34203,36576 ,22085,18609,324 ,0,0,0}, {34203,34204,36576 ,18609,18609,324 ,0,0,0}, - {36966,37715,36576 ,18573,22085,324 ,0,0,0}, {37715,36966,37695 ,22085,18573,18573 ,0,0,0}, - {34183,38262,37392 ,18575,22086,22086 ,0,0,0}, {37683,36981,38642 ,22087,22087,22088 ,0,0,0}, - {36978,36586,38643 ,22088,22089,22089 ,0,0,0}, {37693,36966,36965 ,22090,18573,22090 ,0,0,0}, - {36965,37683,37693 ,22090,22087,22090 ,0,0,0}, {37695,36966,37693 ,18573,18573,22090 ,0,0,0}, - {36965,36981,37683 ,22090,22087,22087 ,0,0,0}, {36978,38642,36981 ,22088,22088,22087 ,0,0,0}, - {38642,36978,38643 ,22088,22088,22089 ,0,0,0}, {37392,34184,34183 ,22086,18575,18575 ,0,0,0}, - {38262,36586,37392 ,22086,22089,22086 ,0,0,0}, {38643,36586,38262 ,22089,22089,22086 ,0,0,0}, - {37520,37005,37521 ,22091,22092,18583 ,0,0,0}, {37520,34162,37005 ,22091,18588,22092 ,0,0,0}, - {34162,37520,34161 ,18588,22091,18588 ,0,0,0}, {36683,37521,37005 ,18583,18583,22092 ,0,0,0}, - {34169,37533,37003 ,18609,22093,22093 ,0,0,0}, {38287,37428,38722 ,22094,22094,22095 ,0,0,0}, - {36685,37427,37539 ,22095,22096,22096 ,0,0,0}, {38721,36683,36684 ,22097,18583,22097 ,0,0,0}, - {36684,38287,38721 ,22097,22094,22097 ,0,0,0}, {37521,36683,38721 ,18583,18583,22097 ,0,0,0}, - {36684,37428,38287 ,22097,22094,22094 ,0,0,0}, {36685,38722,37428 ,22095,22095,22094 ,0,0,0}, - {38722,36685,37539 ,22095,22095,22096 ,0,0,0}, {37003,34170,34169 ,22093,18609,18609 ,0,0,0}, - {37533,37427,37003 ,22093,22096,22093 ,0,0,0}, {37539,37427,37533 ,22096,22096,22093 ,0,0,0}, - {38741,34175,37442 ,22098,18594,126 ,0,0,0}, {34175,34176,37442 ,18594,18594,126 ,0,0,0}, - {37441,38741,37442 ,18575,22098,126 ,0,0,0}, {38741,37441,37509 ,22098,18575,18575 ,0,0,0}, - {34155,38313,36682 ,18601,18635,18635 ,0,0,0}, {37518,36263,38703 ,22099,22099,22100 ,0,0,0}, - {37423,37424,38720 ,22100,22101,22101 ,0,0,0}, {37507,37441,36186 ,22102,18575,22102 ,0,0,0}, - {36186,37518,37507 ,22102,22099,22102 ,0,0,0}, {37509,37441,37507 ,18575,18575,22102 ,0,0,0}, - {36186,36263,37518 ,22102,22099,22099 ,0,0,0}, {37423,38703,36263 ,22100,22100,22099 ,0,0,0}, - {38703,37423,38720 ,22100,22100,22101 ,0,0,0}, {36682,34156,34155 ,18635,18601,18601 ,0,0,0}, - {38313,37424,36682 ,18635,22101,18635 ,0,0,0}, {38720,37424,38313 ,22101,22101,18635 ,0,0,0}, - {37970,36281,37971 ,22103,22104,18609 ,0,0,0}, {37970,34134,36281 ,22103,18573,22104 ,0,0,0}, - {34134,37970,34133 ,18573,22103,18573 ,0,0,0}, {36280,37971,36281 ,18609,18609,22104 ,0,0,0}, - {34141,38181,36876 ,18594,18653,18653 ,0,0,0}, {38210,36230,38208 ,22105,22105,22106 ,0,0,0}, - {36270,36249,37973 ,22106,22107,22107 ,0,0,0}, {38528,36280,36229 ,22108,18609,22108 ,0,0,0}, - {36229,38210,38528 ,22108,22105,22108 ,0,0,0}, {37971,36280,38528 ,18609,18609,22108 ,0,0,0}, - {36229,36230,38210 ,22108,22105,22105 ,0,0,0}, {36270,38208,36230 ,22106,22106,22105 ,0,0,0}, - {38208,36270,37973 ,22106,22106,22107 ,0,0,0}, {36876,34142,34141 ,18653,18594,18594 ,0,0,0}, - {38181,36249,36876 ,18653,22107,18653 ,0,0,0}, {37973,36249,38181 ,22107,22107,18653 ,0,0,0}, - {37976,34147,36264 ,22109,18581,22110 ,0,0,0}, {34147,34148,36264 ,18581,18581,22110 ,0,0,0}, - {36220,37976,36264 ,18601,22109,22110 ,0,0,0}, {37976,36220,37534 ,22109,18601,18601 ,0,0,0}, - {34127,38205,36248 ,18588,22111,22111 ,0,0,0}, {37550,36221,38569 ,22112,22112,22113 ,0,0,0}, - {36277,37312,38567 ,22113,22114,22114 ,0,0,0}, {37535,36220,36219 ,22115,18601,22115 ,0,0,0}, - {36219,37550,37535 ,22115,22112,22115 ,0,0,0}, {37534,36220,37535 ,18601,18601,22115 ,0,0,0}, - {36219,36221,37550 ,22115,22112,22112 ,0,0,0}, {36277,38569,36221 ,22113,22113,22112 ,0,0,0}, - {38569,36277,38567 ,22113,22113,22114 ,0,0,0}, {36248,34128,34127 ,22111,18588,18588 ,0,0,0}, - {38205,37312,36248 ,22111,22114,22111 ,0,0,0}, {38567,37312,38205 ,22114,22114,22111 ,0,0,0}, - {3171,36568,37746 ,22116,22117,18583 ,0,0,0}, {3171,34106,36568 ,22116,18588,22117 ,0,0,0}, - {34106,3171,34105 ,18588,22116,18588 ,0,0,0}, {36567,37746,36568 ,18583,18583,22117 ,0,0,0}, - {34113,38638,37351 ,18609,18683,18683 ,0,0,0}, {38254,37365,38634 ,22118,22118,22119 ,0,0,0}, - {36971,36571,38273 ,22119,22120,22120 ,0,0,0}, {38633,36567,36972 ,22121,18583,22121 ,0,0,0}, - {36972,38254,38633 ,22121,22118,22121 ,0,0,0}, {37746,36567,38633 ,18583,18583,22121 ,0,0,0}, - {36972,37365,38254 ,22121,22118,22118 ,0,0,0}, {36971,38634,37365 ,22119,22119,22118 ,0,0,0}, - {38634,36971,38273 ,22119,22119,22120 ,0,0,0}, {37351,34114,34113 ,18683,18609,18609 ,0,0,0}, - {38638,36571,37351 ,18683,22120,18683 ,0,0,0}, {38273,36571,38638 ,22120,22120,18683 ,0,0,0}, - {38742,34119,37357 ,22122,18594,22073 ,0,0,0}, {34119,34120,37357 ,18594,18594,22073 ,0,0,0}, - {37356,38742,37357 ,18575,22122,22073 ,0,0,0}, {38742,37356,37700 ,22122,18575,18575 ,0,0,0}, - {34099,38270,37361 ,18601,22123,22124 ,0,0,0}, {37705,37362,37720 ,22125,22125,22076 ,0,0,0}, - {36530,36566,38632 ,22076,22126,22126 ,0,0,0}, {37704,37356,36581 ,22127,18575,22127 ,0,0,0}, - {36581,37705,37704 ,22127,22125,22127 ,0,0,0}, {37700,37356,37704 ,18575,18575,22127 ,0,0,0}, - {36581,37362,37705 ,22127,22125,22125 ,0,0,0}, {36530,37720,37362 ,22076,22076,22125 ,0,0,0}, - {37720,36530,38632 ,22076,22076,22126 ,0,0,0}, {37361,34100,34099 ,22124,18601,18601 ,0,0,0}, - {38270,36566,37361 ,22123,22126,22124 ,0,0,0}, {38632,36566,38270 ,22126,22126,22123 ,0,0,0}, - {1435,36246,38315 ,22128,22129,18609 ,0,0,0}, {1435,34078,36246 ,22128,18573,22129 ,0,0,0}, - {34078,1435,34077 ,18573,22128,18573 ,0,0,0}, {36247,38315,36246 ,18609,18609,22129 ,0,0,0}, - {34085,38288,36244 ,18594,22130,22130 ,0,0,0}, {38678,37000,38314 ,22131,22131,22132 ,0,0,0}, - {36994,36998,37529 ,22132,22133,22133 ,0,0,0}, {38316,36247,36999 ,22134,18609,22134 ,0,0,0}, - {36999,38678,38316 ,22134,22131,22134 ,0,0,0}, {38315,36247,38316 ,18609,18609,22134 ,0,0,0}, - {36999,37000,38678 ,22134,22131,22131 ,0,0,0}, {36994,38314,37000 ,22132,22132,22131 ,0,0,0}, - {38314,36994,37529 ,22132,22132,22133 ,0,0,0}, {36244,34086,34085 ,22130,18594,18594 ,0,0,0}, - {38288,36998,36244 ,22130,22133,22130 ,0,0,0}, {37529,36998,38288 ,22133,22133,22130 ,0,0,0}, - {38714,34091,37398 ,22135,18581,21 ,0,0,0}, {34091,34092,37398 ,18581,18581,21 ,0,0,0}, - {36715,38714,37398 ,18601,22135,21 ,0,0,0}, {38714,36715,38286 ,22135,18601,18601 ,0,0,0}, - {34071,37528,36710 ,18588,22136,22136 ,0,0,0}, {37525,36198,38717 ,22137,22137,22138 ,0,0,0}, - {36704,37444,38715 ,22138,22139,22139 ,0,0,0}, {38285,36715,36716 ,22140,18601,22140 ,0,0,0}, - {36716,37525,38285 ,22140,22137,22140 ,0,0,0}, {38286,36715,38285 ,18601,18601,22140 ,0,0,0}, - {36716,36198,37525 ,22140,22137,22137 ,0,0,0}, {36704,38717,36198 ,22138,22138,22137 ,0,0,0}, - {38717,36704,38715 ,22138,22138,22139 ,0,0,0}, {36710,34072,34071 ,22136,18588,18588 ,0,0,0}, - {37528,37444,36710 ,22136,22139,22136 ,0,0,0}, {38715,37444,37528 ,22139,22139,22136 ,0,0,0}, - {4039,36265,38007 ,22141,22142,18594 ,0,0,0}, {4039,34050,36265 ,22141,18575,22142 ,0,0,0}, - {34050,4039,34049 ,18575,22141,18575 ,0,0,0}, {36222,38007,36265 ,18594,18594,22142 ,0,0,0}, - {34057,38531,36266 ,18581,22143,22143 ,0,0,0}, {38185,37262,38186 ,22144,22144,22145 ,0,0,0}, - {36267,36223,38180 ,22145,22146,22146 ,0,0,0}, {38006,36222,37263 ,22147,18594,22147 ,0,0,0}, - {37263,38185,38006 ,22147,22144,22147 ,0,0,0}, {38007,36222,38006 ,18594,18594,22147 ,0,0,0}, - {37263,37262,38185 ,22147,22144,22144 ,0,0,0}, {36267,38186,37262 ,22145,22145,22144 ,0,0,0}, - {38186,36267,38180 ,22145,22145,22146 ,0,0,0}, {36266,34058,34057 ,22143,18581,18581 ,0,0,0}, - {38531,36223,36266 ,22143,22146,22143 ,0,0,0}, {38180,36223,38531 ,22146,22146,22143 ,0,0,0}, - {38744,34063,37267 ,22148,18583,22149 ,0,0,0}, {34063,34064,37267 ,18583,18583,22149 ,0,0,0}, - {37266,38744,37267 ,18588,22148,22149 ,0,0,0}, {38744,37266,37969 ,22148,18588,18588 ,0,0,0}, - {34043,37978,37261 ,18573,22150,22150 ,0,0,0}, {38532,36911,37980 ,22151,22151,22152 ,0,0,0}, - {36224,36226,37981 ,22152,22153,22153 ,0,0,0}, {37968,37266,36268 ,22154,18588,22154 ,0,0,0}, - {36268,38532,37968 ,22154,22151,22154 ,0,0,0}, {37969,37266,37968 ,18588,18588,22154 ,0,0,0}, - {36268,36911,38532 ,22154,22151,22151 ,0,0,0}, {36224,37980,36911 ,22152,22152,22151 ,0,0,0}, - {37980,36224,37981 ,22152,22152,22153 ,0,0,0}, {37261,34044,34043 ,22150,18573,18573 ,0,0,0}, - {37978,36226,37261 ,22150,22153,22150 ,0,0,0}, {37981,36226,37978 ,22153,22153,22150 ,0,0,0} -}; -static GLfloat vertices [38747][3] = { -{-0.023239f,-0.071786f,0.0322314f},{-0.0231144f,-0.0708235f,0.0340958f},{-0.023239f,-0.0717882f,0.0340958f}, -{-0.0231106f,-0.0727502f,0.0322314f},{-0.0231103f,-0.0727513f,0.0340958f},{-0.0227371f,-0.0736484f,0.0322314f}, -{-0.0227371f,-0.0736484f,0.0340958f},{-0.0231141f,-0.0708224f,0.0322314f},{-0.0227444f,-0.0699238f,0.0340958f}, -{-0.0227444f,-0.0699238f,0.0322314f},{-0.0225127f,-0.00424291f,0.0322314f},{-0.0216035f,-0.00385992f,0.0340958f}, -{-0.0225146f,-0.00424405f,0.0340958f},{-0.0232912f,-0.00485238f,0.0322314f},{-0.023292f,-0.00485321f,0.0340958f}, -{-0.0238822f,-0.00564511f,0.0322314f},{-0.0238822f,-0.00564511f,0.0340958f},{-0.0216024f,-0.00385961f,0.0322314f}, -{-0.0206235f,-0.00372882f,0.0340958f},{-0.0206235f,-0.00372882f,0.0322314f},{-0.0243511f,0.0075482f,0.0322314f}, -{-0.024197f,0.00852259f,0.0340958f},{-0.0243512f,0.00754595f,0.0340958f},{-0.024244f,0.0065653f,0.0322314f}, -{-0.0242437f,0.00656417f,0.0340958f},{-0.0238822f,0.00564511f,0.0322314f},{-0.0238822f,0.00564511f,0.0340958f}, -{-0.0241967f,0.00852371f,0.0322314f},{-0.0237915f,0.00942436f,0.0340958f},{-0.0237915f,0.00942436f,0.0322314f}, -{-0.0213716f,0.0750107f,0.0322314f},{-0.0204747f,0.0753817f,0.0340958f},{-0.0213735f,0.0750096f,0.0340958f}, -{-0.022144f,0.0744194f,0.0322314f},{-0.0221448f,0.0744186f,0.0340958f},{-0.0227371f,0.0736484f,0.0322314f}, -{-0.0227371f,0.0736484f,0.0340958f},{-0.0204736f,0.075382f,0.0322314f},{-0.0195103f,0.0755086f,0.0340958f}, -{-0.0195103f,0.0755086f,0.0322314f},{-0.0391526f,-0.00279661f,0.0322314f},{-0.0397007f,-0.00274238f,0.0340958f}, -{-0.0391526f,-0.00279661f,0.0340958f},{-0.0380824f,-0.00258373f,0.0340958f},{-0.0380824f,-0.00258373f,0.0322314f}, -{-0.0386045f,-0.00274238f,0.0340958f},{-0.0386045f,-0.00274238f,0.0322314f},{-0.037601f,-0.00232674f,0.0322314f}, -{-0.0371751f,-0.00197751f,0.0322314f},{-0.0371751f,-0.00197751f,0.0340958f},{-0.0368259f,-0.00155157f,0.0322314f}, -{-0.0368259f,-0.00155157f,0.0340958f},{-0.037601f,-0.00232674f,0.0340958f},{-0.036356f,3.97423e-017f,0.0322314f}, -{-0.0364102f,-0.000548134f,0.0322314f},{-0.0364102f,-0.000548134f,0.0340958f},{-0.0365689f,-0.00107022f,0.0340958f}, -{-0.0365689f,-0.00107022f,0.0322314f},{-0.036356f,3.97423e-017f,0.0340958f},{-0.0397007f,-0.00274238f,0.0322314f}, -{-0.0402228f,-0.00258373f,0.0340958f},{-0.0402228f,-0.00258373f,0.0322314f},{-0.0407042f,-0.00232674f,0.0322314f}, -{-0.0407042f,-0.00232674f,0.0340958f},{-0.0411301f,-0.00197751f,0.0322314f},{-0.0411301f,-0.00197751f,0.0340958f}, -{-0.0414793f,-0.00155157f,0.0340958f},{-0.0414793f,-0.00155157f,0.0322314f},{-0.0417363f,-0.00107022f,0.0322314f}, -{-0.0417363f,-0.00107022f,0.0340958f},{-0.041895f,-0.000548134f,0.0322314f},{-0.041895f,-0.000548134f,0.0340958f}, -{-0.0419492f,3.97423e-017f,0.0340958f},{-0.0419492f,3.97423e-017f,0.0322314f},{0.0391526f,-0.00279661f,0.0322314f}, -{0.0386045f,-0.00274238f,0.0340958f},{0.0391526f,-0.00279661f,0.0340958f},{0.0402228f,-0.00258373f,0.0340958f}, -{0.0402228f,-0.00258373f,0.0322314f},{0.0397007f,-0.00274238f,0.0340958f},{0.0397007f,-0.00274238f,0.0322314f}, -{0.0407042f,-0.00232674f,0.0322314f},{0.0411301f,-0.00197751f,0.0322314f},{0.0411301f,-0.00197751f,0.0340958f}, -{0.0414793f,-0.00155157f,0.0322314f},{0.0414793f,-0.00155157f,0.0340958f},{0.0407042f,-0.00232674f,0.0340958f}, -{0.0419492f,3.97423e-017f,0.0322314f},{0.041895f,-0.000548134f,0.0322314f},{0.041895f,-0.000548134f,0.0340958f}, -{0.0417363f,-0.00107022f,0.0340958f},{0.0417363f,-0.00107022f,0.0322314f},{0.0419492f,3.97423e-017f,0.0340958f}, -{0.0386045f,-0.00274238f,0.0322314f},{0.0380824f,-0.00258373f,0.0340958f},{0.0380824f,-0.00258373f,0.0322314f}, -{0.037601f,-0.00232674f,0.0322314f},{0.037601f,-0.00232674f,0.0340958f},{0.0371751f,-0.00197751f,0.0322314f}, -{0.0371751f,-0.00197751f,0.0340958f},{0.0368259f,-0.00155157f,0.0340958f},{0.0368259f,-0.00155157f,0.0322314f}, -{0.0365689f,-0.00107022f,0.0322314f},{0.0365689f,-0.00107022f,0.0340958f},{0.0364102f,-0.000548134f,0.0322314f}, -{0.0364102f,-0.000548134f,0.0340958f},{0.036356f,3.97423e-017f,0.0340958f},{0.036356f,3.97423e-017f,0.0322314f}, -{-0.0391526f,0.0783052f,0.0322314f},{-0.0397007f,0.0783594f,0.0340958f},{-0.0391526f,0.0783052f,0.0340958f}, -{-0.0380824f,0.0785181f,0.0340958f},{-0.0380824f,0.0785181f,0.0322314f},{-0.0386045f,0.0783594f,0.0340958f}, -{-0.0386045f,0.0783594f,0.0322314f},{-0.037601f,0.0787751f,0.0322314f},{-0.0371751f,0.0791243f,0.0322314f}, -{-0.0371751f,0.0791243f,0.0340958f},{-0.0368259f,0.0795502f,0.0322314f},{-0.0368259f,0.0795502f,0.0340958f}, -{-0.037601f,0.0787751f,0.0340958f},{-0.036356f,0.0811018f,0.0322314f},{-0.0364102f,0.0805537f,0.0322314f}, -{-0.0364102f,0.0805537f,0.0340958f},{-0.0365689f,0.0800316f,0.0340958f},{-0.0365689f,0.0800316f,0.0322314f}, -{-0.036356f,0.0811018f,0.0340958f},{-0.0397007f,0.0783594f,0.0322314f},{-0.0402228f,0.0785181f,0.0340958f}, -{-0.0402228f,0.0785181f,0.0322314f},{-0.0407042f,0.0787751f,0.0322314f},{-0.0407042f,0.0787751f,0.0340958f}, -{-0.0411301f,0.0791243f,0.0322314f},{-0.0411301f,0.0791243f,0.0340958f},{-0.0414793f,0.0795502f,0.0340958f}, -{-0.0414793f,0.0795502f,0.0322314f},{-0.0417363f,0.0800316f,0.0322314f},{-0.0417363f,0.0800316f,0.0340958f}, -{-0.041895f,0.0805537f,0.0322314f},{-0.041895f,0.0805537f,0.0340958f},{-0.0419492f,0.0811018f,0.0340958f}, -{-0.0419492f,0.0811018f,0.0322314f},{0.0391526f,0.0783052f,0.0322314f},{0.0386045f,0.0783594f,0.0340958f}, -{0.0391526f,0.0783052f,0.0340958f},{0.0402228f,0.0785181f,0.0340958f},{0.0402228f,0.0785181f,0.0322314f}, -{0.0397007f,0.0783594f,0.0340958f},{0.0397007f,0.0783594f,0.0322314f},{0.0407042f,0.0787751f,0.0322314f}, -{0.0411301f,0.0791243f,0.0322314f},{0.0411301f,0.0791243f,0.0340958f},{0.0414793f,0.0795502f,0.0322314f}, -{0.0414793f,0.0795502f,0.0340958f},{0.0407042f,0.0787751f,0.0340958f},{0.0419492f,0.0811018f,0.0322314f}, -{0.041895f,0.0805537f,0.0322314f},{0.041895f,0.0805537f,0.0340958f},{0.0417363f,0.0800316f,0.0340958f}, -{0.0417363f,0.0800316f,0.0322314f},{0.0419492f,0.0811018f,0.0340958f},{0.0386045f,0.0783594f,0.0322314f}, -{0.0380824f,0.0785181f,0.0340958f},{0.0380824f,0.0785181f,0.0322314f},{0.037601f,0.0787751f,0.0322314f}, -{0.037601f,0.0787751f,0.0340958f},{0.0371751f,0.0791243f,0.0322314f},{0.0371751f,0.0791243f,0.0340958f}, -{0.0368259f,0.0795502f,0.0340958f},{0.0368259f,0.0795502f,0.0322314f},{0.0365689f,0.0800316f,0.0322314f}, -{0.0365689f,0.0800316f,0.0340958f},{0.0364102f,0.0805537f,0.0322314f},{0.0364102f,0.0805537f,0.0340958f}, -{0.036356f,0.0811018f,0.0340958f},{0.036356f,0.0811018f,0.0322314f},{0.0391526f,-0.0838984f,0.0322314f}, -{0.0386045f,-0.0838442f,0.0340958f},{0.0391526f,-0.0838984f,0.0340958f},{0.0402228f,-0.0836855f,0.0340958f}, -{0.0402228f,-0.0836855f,0.0322314f},{0.0397007f,-0.0838442f,0.0340958f},{0.0397007f,-0.0838442f,0.0322314f}, -{0.0407042f,-0.0834285f,0.0322314f},{0.0411301f,-0.0830793f,0.0322314f},{0.0411301f,-0.0830793f,0.0340958f}, -{0.0414793f,-0.0826534f,0.0322314f},{0.0414793f,-0.0826534f,0.0340958f},{0.0407042f,-0.0834285f,0.0340958f}, -{0.0419492f,-0.0811018f,0.0322314f},{0.041895f,-0.0816499f,0.0322314f},{0.041895f,-0.0816499f,0.0340958f}, -{0.0417363f,-0.082172f,0.0340958f},{0.0417363f,-0.082172f,0.0322314f},{0.0419492f,-0.0811018f,0.0340958f}, -{0.0386045f,-0.0838442f,0.0322314f},{0.0380824f,-0.0836855f,0.0340958f},{0.0380824f,-0.0836855f,0.0322314f}, -{0.037601f,-0.0834285f,0.0322314f},{0.037601f,-0.0834285f,0.0340958f},{0.0371751f,-0.0830793f,0.0322314f}, -{0.0371751f,-0.0830793f,0.0340958f},{0.0368259f,-0.0826534f,0.0340958f},{0.0368259f,-0.0826534f,0.0322314f}, -{0.0365689f,-0.082172f,0.0322314f},{0.0365689f,-0.082172f,0.0340958f},{0.0364102f,-0.0816499f,0.0322314f}, -{0.0364102f,-0.0816499f,0.0340958f},{0.036356f,-0.0811018f,0.0340958f},{0.036356f,-0.0811018f,0.0322314f}, -{-0.0391526f,-0.0838984f,0.0322314f},{-0.0397007f,-0.0838442f,0.0340958f},{-0.0391526f,-0.0838984f,0.0340958f}, -{-0.0380824f,-0.0836855f,0.0340958f},{-0.0380824f,-0.0836855f,0.0322314f},{-0.0386045f,-0.0838442f,0.0340958f}, -{-0.0386045f,-0.0838442f,0.0322314f},{-0.037601f,-0.0834285f,0.0322314f},{-0.0371751f,-0.0830793f,0.0322314f}, -{-0.0371751f,-0.0830793f,0.0340958f},{-0.0368259f,-0.0826534f,0.0322314f},{-0.0368259f,-0.0826534f,0.0340958f}, -{-0.037601f,-0.0834285f,0.0340958f},{-0.036356f,-0.0811018f,0.0322314f},{-0.0364102f,-0.0816499f,0.0322314f}, -{-0.0364102f,-0.0816499f,0.0340958f},{-0.0365689f,-0.082172f,0.0340958f},{-0.0365689f,-0.082172f,0.0322314f}, -{-0.036356f,-0.0811018f,0.0340958f},{-0.0397007f,-0.0838442f,0.0322314f},{-0.0402228f,-0.0836855f,0.0340958f}, -{-0.0402228f,-0.0836855f,0.0322314f},{-0.0407042f,-0.0834285f,0.0322314f},{-0.0407042f,-0.0834285f,0.0340958f}, -{-0.0411301f,-0.0830793f,0.0322314f},{-0.0411301f,-0.0830793f,0.0340958f},{-0.0414793f,-0.0826534f,0.0340958f}, -{-0.0414793f,-0.0826534f,0.0322314f},{-0.0417363f,-0.082172f,0.0322314f},{-0.0417363f,-0.082172f,0.0340958f}, -{-0.041895f,-0.0816499f,0.0322314f},{-0.041895f,-0.0816499f,0.0340958f},{-0.0419492f,-0.0811018f,0.0340958f}, -{-0.0419492f,-0.0811018f,0.0322314f},{0.0225785f,-0.0258241f,0.0322314f},{0.0237254f,-0.0222932f,0.0322314f}, -{0.0237253f,-0.0222933f,0.0340958f},{0.0216792f,-0.0294283f,0.0322314f},{0.0225785f,-0.0258242f,0.0340958f}, -{0.0216792f,-0.0294286f,0.0340958f},{0.0210317f,-0.0330928f,0.0322314f},{0.0206399f,-0.0368049f,0.0340958f}, -{0.0205085f,-0.0405509f,0.0322314f},{0.02064f,-0.0368047f,0.0322314f},{0.0210316f,-0.0330931f,0.0340958f}, -{0.0205085f,-0.0405509f,0.0340958f},{0.0251155f,-0.0188485f,0.0340958f},{0.0267447f,-0.0155029f,0.0340958f}, -{0.0251156f,-0.0188483f,0.0322314f},{0.0267448f,-0.0155026f,0.0322314f},{0.0286089f,-0.0122693f,0.0340958f}, -{0.028609f,-0.0122691f,0.0322314f},{0.0307038f,-0.00916071f,0.0340958f},{0.0307038f,-0.00916071f,0.0322314f}, -{-0.03984f,-0.0885276f,0.0340958f},{-0.0398371f,-0.0885279f,0.0322314f},{-0.0387004f,-0.0885456f,0.0322314f}, -{-0.0409568f,-0.0883379f,0.0322314f},{-0.0409588f,-0.0883374f,0.0340958f},{-0.0420378f,-0.0879786f,0.0340958f}, -{-0.042035f,-0.0879797f,0.0322314f},{-0.0430486f,-0.0874608f,0.0340958f},{-0.043047f,-0.0874618f,0.0322314f}, -{-0.0439672f,-0.0867969f,0.0322314f},{-0.0439685f,-0.086796f,0.0340958f},{-0.0447784f,-0.0859974f,0.0340958f}, -{-0.0447773f,-0.0859985f,0.0322314f},{-0.045456f,-0.0850872f,0.0340958f},{-0.0454557f,-0.0850877f,0.0322314f}, -{-0.0459883f,-0.0840833f,0.0340958f},{-0.0459883f,-0.0840833f,0.0322314f},{-0.0387033f,-0.0885458f,0.0340958f}, -{-0.037576f,-0.0883909f,0.0322314f},{-0.0375781f,-0.0883913f,0.0340958f},{-0.0364863f,-0.0880664f,0.0322314f}, -{-0.0364891f,-0.0880674f,0.0340958f},{-0.0354613f,-0.0875818f,0.0340958f},{-0.0354596f,-0.0875808f,0.0322314f}, -{-0.0345192f,-0.0869454f,0.0322314f},{-0.0345204f,-0.0869463f,0.0340958f},{-0.0336844f,-0.0861728f,0.0322314f}, -{-0.0336855f,-0.0861739f,0.0340958f},{-0.0329787f,-0.085285f,0.0340958f},{-0.0329784f,-0.0852846f,0.0322314f}, -{-0.0324146f,-0.0842979f,0.0322314f},{-0.0324146f,-0.0842979f,0.0340958f},{-0.0440592f,-0.00561614f,0.0322314f}, -{-0.0430328f,-0.00636862f,0.0322314f},{-0.0440603f,-0.00561515f,0.0340958f},{-0.044941f,-0.00470215f,0.0340958f}, -{-0.0449406f,-0.00470266f,0.0322314f},{-0.0456552f,-0.0036514f,0.0340958f},{-0.0456542f,-0.00365287f,0.0322314f}, -{-0.046181f,-0.00249363f,0.0322314f},{-0.0461811f,-0.00249326f,0.0340958f},{-0.046502f,-0.00126624f,0.0340958f}, -{-0.0465017f,-0.00126733f,0.0322314f},{-0.0466102f,3.97423e-017f,0.0340958f},{-0.0466102f,3.97423e-017f,0.0322314f}, -{-0.0430341f,-0.00636786f,0.0340958f},{-0.0418973f,-0.00693419f,0.0322314f},{-0.0418979f,-0.00693393f,0.0340958f}, -{-0.0406822f,-0.00729899f,0.0340958f},{-0.0406805f,-0.00729943f,0.0322314f},{-0.0394178f,-0.00745289f,0.0322314f}, -{-0.0394182f,-0.00745292f,0.0340958f},{-0.0381511f,-0.00739011f,0.0322314f},{-0.0381522f,-0.00739019f,0.0340958f}, -{-0.0369109f,-0.00711273f,0.0322314f},{-0.0369109f,-0.00711273f,0.0340958f},{-0.0450626f,0.0765535f,0.0340958f}, -{-0.0450608f,0.0765512f,0.0322314f},{-0.0443005f,0.075706f,0.0322314f},{-0.0456834f,0.0775011f,0.0322314f}, -{-0.0456844f,0.0775029f,0.0340958f},{-0.0461555f,0.0785378f,0.0340958f},{-0.0461544f,0.078535f,0.0322314f}, -{-0.0464637f,0.0796309f,0.0340958f},{-0.0464633f,0.079629f,0.0322314f},{-0.0466021f,0.0807558f,0.0322314f}, -{-0.0466023f,0.0807574f,0.0340958f},{-0.046568f,0.0818943f,0.0340958f},{-0.0465681f,0.0818927f,0.0322314f}, -{-0.046362f,0.0830101f,0.0340958f},{-0.0463621f,0.0830096f,0.0322314f},{-0.0459883f,0.0840833f,0.0340958f}, -{-0.0459883f,0.0840833f,0.0322314f},{-0.0443026f,0.0757081f,0.0340958f},{-0.0434222f,0.0749873f,0.0322314f}, -{-0.0434238f,0.0749885f,0.0340958f},{-0.0424429f,0.0744094f,0.0322314f},{-0.0424456f,0.0744107f,0.0340958f}, -{-0.0413904f,0.0739879f,0.0340958f},{-0.0413886f,0.0739873f,0.0322314f},{-0.040283f,0.0737303f,0.0322314f}, -{-0.0402846f,0.0737307f,0.0340958f},{-0.0391489f,0.0736442f,0.0322314f},{-0.0391504f,0.0736443f,0.0340958f}, -{-0.0380181f,0.073731f,0.0340958f},{-0.0380175f,0.073731f,0.0322314f},{-0.0369109f,0.0739891f,0.0322314f}, -{-0.0369109f,0.0739891f,0.0340958f},{0.0225785f,0.0552777f,0.0322314f},{0.0237254f,0.0588086f,0.0322314f}, -{0.0237253f,0.0588085f,0.0340958f},{0.0216792f,0.0516735f,0.0322314f},{0.0225785f,0.0552776f,0.0340958f}, -{0.0216792f,0.0516732f,0.0340958f},{0.0210317f,0.048009f,0.0322314f},{0.0206399f,0.0442969f,0.0340958f}, -{0.0205085f,0.0405509f,0.0322314f},{0.02064f,0.0442971f,0.0322314f},{0.0210316f,0.0480087f,0.0340958f}, -{0.0205085f,0.0405509f,0.0340958f},{0.0251155f,0.0622533f,0.0340958f},{0.0267447f,0.0655989f,0.0340958f}, -{0.0251156f,0.0622535f,0.0322314f},{0.0267448f,0.0655992f,0.0322314f},{0.0286089f,0.0688326f,0.0340958f}, -{0.028609f,0.0688327f,0.0322314f},{0.0307038f,0.0719411f,0.0340958f},{0.0307038f,0.0719411f,0.0322314f}, -{0.0167768f,-0.0552561f,0.0340958f},{0.0159195f,-0.0513911f,0.0340958f},{0.0167768f,-0.0552561f,0.0322314f}, -{0.0159195f,-0.0513911f,0.0322314f},{0.0153227f,-0.0474729f,0.0340958f},{0.0149897f,-0.0435148f,0.0340958f}, -{0.0153227f,-0.0474729f,0.0322314f},{0.0149241f,-0.0395297f,0.0340958f},{0.0149897f,-0.0435148f,0.0322314f}, -{0.0149241f,-0.0395297f,0.0322314f},{0.0178914f,-0.059055f,0.0322314f},{0.0192597f,-0.0627747f,0.0322314f}, -{0.0178914f,-0.059055f,0.0340958f},{0.0208785f,-0.066402f,0.0322314f},{0.0192597f,-0.0627747f,0.0340958f}, -{0.0208785f,-0.066402f,0.0340958f},{0.0227444f,-0.0699238f,0.0322314f},{0.0227444f,-0.0699238f,0.0340958f}, -{0.0173199f,0.0238768f,0.0340958f},{0.0163293f,0.0277099f,0.0340958f},{0.0173199f,0.0238768f,0.0322314f}, -{0.0163293f,0.0277099f,0.0322314f},{0.0155973f,0.031605f,0.0340958f},{0.0151276f,0.0355493f,0.0340958f}, -{0.0155973f,0.031605f,0.0322314f},{0.0149241f,0.0395297f,0.0340958f},{0.0151276f,0.0355493f,0.0322314f}, -{0.0149241f,0.0395297f,0.0322314f},{0.0185653f,0.0201187f,0.0322314f},{0.0200615f,0.0164487f,0.0322314f}, -{0.0185653f,0.0201187f,0.0340958f},{0.0218049f,0.0128796f,0.0322314f},{0.0200615f,0.0164487f,0.0340958f}, -{0.0218049f,0.0128796f,0.0340958f},{0.0237915f,0.00942436f,0.0322314f},{0.0237915f,0.00942436f,0.0340958f}, -{0.0149897f,0.0435148f,0.0340958f},{0.0167768f,0.0552561f,0.0340958f},{0.0159195f,0.0513911f,0.0322314f}, -{0.0159195f,0.0513911f,0.0340958f},{0.0153227f,0.0474729f,0.0340958f},{0.0153227f,0.0474729f,0.0322314f}, -{0.0149897f,0.0435148f,0.0322314f},{0.0192597f,0.0627747f,0.0322314f},{0.0192597f,0.0627747f,0.0340958f}, -{0.0208785f,0.066402f,0.0340958f},{0.0167768f,0.0552561f,0.0322314f},{0.0178914f,0.059055f,0.0340958f}, -{0.0178914f,0.059055f,0.0322314f},{0.0227444f,0.0699238f,0.0340958f},{0.0208785f,0.066402f,0.0322314f}, -{0.0227444f,0.0699238f,0.0322314f},{-0.0206235f,0.00372882f,0.0322314f},{-0.0206235f,0.00372882f,0.0340958f}, -{0.0206235f,0.00372882f,0.0340958f},{0.0206235f,0.00372882f,0.0322314f},{-0.0149256f,0.0416576f,0.0340958f}, -{-0.0149993f,0.0374031f,0.0340958f},{-0.0149257f,0.0416577f,0.0322314f},{-0.0151577f,0.0458938f,0.0322314f}, -{-0.0151576f,0.0458937f,0.0340958f},{-0.0156914f,0.0500904f,0.0322314f},{-0.0156914f,0.0500902f,0.0340958f}, -{-0.0165229f,0.0542313f,0.0340958f},{-0.016523f,0.0542315f,0.0322314f},{-0.0176481f,0.0583013f,0.0322314f}, -{-0.017648f,0.0583011f,0.0340958f},{-0.0190628f,0.0622838f,0.0322314f},{-0.0190627f,0.0622837f,0.0340958f}, -{-0.0207629f,0.0661632f,0.0340958f},{-0.0207629f,0.0661633f,0.0322314f},{-0.0227444f,0.0699238f,0.0322314f}, -{-0.0227444f,0.0699238f,0.0340958f},{-0.0149993f,0.0374031f,0.0322314f},{-0.0153777f,0.0331776f,0.0322314f}, -{-0.0153777f,0.0331775f,0.0340958f},{-0.0160564f,0.0290019f,0.0340958f},{-0.0160564f,0.0290021f,0.0322314f}, -{-0.0170307f,0.024892f,0.0340958f},{-0.0170307f,0.0248922f,0.0322314f},{-0.018296f,0.0208638f,0.0322314f}, -{-0.018296f,0.0208636f,0.0340958f},{-0.0198477f,0.0169324f,0.0340958f},{-0.0198476f,0.0169326f,0.0322314f}, -{-0.021681f,0.0131141f,0.0340958f},{-0.021681f,0.0131142f,0.0322314f},{0.0151276f,-0.0355493f,0.0340958f}, -{0.0173199f,-0.0238768f,0.0340958f},{0.0163293f,-0.0277099f,0.0322314f},{0.0163293f,-0.0277099f,0.0340958f}, -{0.0155973f,-0.031605f,0.0340958f},{0.0155973f,-0.031605f,0.0322314f},{0.0151276f,-0.0355493f,0.0322314f}, -{0.0200615f,-0.0164487f,0.0322314f},{0.0200615f,-0.0164487f,0.0340958f},{0.0218049f,-0.0128796f,0.0340958f}, -{0.0173199f,-0.0238768f,0.0322314f},{0.0185653f,-0.0201187f,0.0340958f},{0.0185653f,-0.0201187f,0.0322314f}, -{0.0237915f,-0.00942436f,0.0340958f},{0.0218049f,-0.0128796f,0.0322314f},{0.0237915f,-0.00942436f,0.0322314f}, -{-0.0195103f,-0.0755086f,0.0322314f},{0.0195103f,-0.0755086f,0.0340958f},{0.0195103f,-0.0755086f,0.0322314f}, -{-0.0195103f,-0.0755086f,0.0340958f},{-0.0149993f,-0.0374031f,0.0340958f},{-0.0149257f,-0.0416576f,0.0340958f}, -{-0.0149993f,-0.0374031f,0.0322314f},{-0.0153777f,-0.0331775f,0.0322314f},{-0.0153777f,-0.0331776f,0.0340958f}, -{-0.0160564f,-0.0290019f,0.0322314f},{-0.0160564f,-0.0290021f,0.0340958f},{-0.0170307f,-0.0248922f,0.0340958f}, -{-0.0170307f,-0.024892f,0.0322314f},{-0.018296f,-0.0208636f,0.0322314f},{-0.018296f,-0.0208638f,0.0340958f}, -{-0.0198477f,-0.0169324f,0.0322314f},{-0.0198476f,-0.0169326f,0.0340958f},{-0.021681f,-0.0131142f,0.0340958f}, -{-0.021681f,-0.0131141f,0.0322314f},{-0.0237915f,-0.00942436f,0.0322314f},{-0.0237915f,-0.00942436f,0.0340958f}, -{-0.0149256f,-0.0416576f,0.0322314f},{-0.0151576f,-0.0458937f,0.0322314f},{-0.0151577f,-0.0458938f,0.0340958f}, -{-0.0156914f,-0.0500904f,0.0340958f},{-0.0156914f,-0.0500902f,0.0322314f},{-0.016523f,-0.0542315f,0.0340958f}, -{-0.0165229f,-0.0542313f,0.0322314f},{-0.017648f,-0.0583011f,0.0322314f},{-0.0176481f,-0.0583013f,0.0340958f}, -{-0.0190628f,-0.0622838f,0.0340958f},{-0.0190627f,-0.0622837f,0.0322314f},{-0.0207629f,-0.0661633f,0.0340958f}, -{-0.0207629f,-0.0661632f,0.0322314f},{0.02064f,0.0368047f,0.0340958f},{0.0206399f,0.0368049f,0.0322314f}, -{0.0225785f,0.0258241f,0.0340958f},{0.0225785f,0.0258242f,0.0322314f},{0.0216792f,0.0294283f,0.0340958f}, -{0.0216792f,0.0294286f,0.0322314f},{0.0210316f,0.0330931f,0.0322314f},{0.0210317f,0.0330928f,0.0340958f}, -{0.0267447f,0.0155029f,0.0322314f},{0.0251156f,0.0188483f,0.0340958f},{0.0267448f,0.0155026f,0.0340958f}, -{0.0237253f,0.0222933f,0.0322314f},{0.0237254f,0.0222932f,0.0340958f},{0.0251155f,0.0188485f,0.0322314f}, -{0.028609f,0.0122691f,0.0340958f},{0.0286089f,0.0122693f,0.0322314f},{0.0307038f,0.00916071f,0.0340958f}, -{0.0307038f,0.00916071f,0.0322314f},{0.0462025f,0.0835337f,0.0340958f},{0.0457312f,0.0846141f,0.0322314f}, -{0.0457326f,0.0846116f,0.0340958f},{0.0450998f,0.0856014f,0.0340958f},{0.0450987f,0.085603f,0.0322314f}, -{0.044317f,0.0864818f,0.0322314f},{0.0443187f,0.0864801f,0.0340958f},{0.0434093f,0.0872252f,0.0340958f}, -{0.0434083f,0.0872259f,0.0322314f},{0.0423945f,0.087818f,0.0322314f},{0.0423947f,0.0878178f,0.0340958f}, -{0.0412975f,0.0882443f,0.0322314f},{0.041298f,0.0882442f,0.0340958f},{0.040151f,0.0884923f,0.0340958f}, -{0.0401493f,0.0884924f,0.0322314f},{0.0389772f,0.0885573f,0.0340958f},{0.0389749f,0.0885572f,0.0322314f}, -{0.0378063f,0.0884369f,0.0322314f},{0.0378083f,0.0884373f,0.0340958f},{0.0366734f,0.0881351f,0.0340958f}, -{0.0366703f,0.0881341f,0.0322314f},{0.0355963f,0.0876568f,0.0322314f},{0.0355984f,0.087658f,0.0340958f}, -{0.0346116f,0.0870176f,0.0322314f},{0.0346134f,0.0870188f,0.0340958f},{0.0337395f,0.0862314f,0.0340958f}, -{0.0337379f,0.0862299f,0.0322314f},{0.0330004f,0.0853169f,0.0322314f},{0.0330008f,0.0853175f,0.0340958f}, -{0.0324146f,0.0842979f,0.0322314f},{0.0324146f,0.0842979f,0.0340958f},{0.0462016f,0.0835364f,0.0322314f}, -{0.0464969f,0.0823973f,0.0340958f},{0.0464965f,0.0823992f,0.0322314f},{0.0466091f,0.0812265f,0.0340958f}, -{0.046609f,0.0812289f,0.0322314f},{0.0465363f,0.0800543f,0.0340958f},{0.0465364f,0.0800555f,0.0322314f}, -{0.0462805f,0.0789088f,0.0322314f},{0.0462804f,0.0789085f,0.0340958f},{0.0458466f,0.0778144f,0.0340958f}, -{0.0458468f,0.0778149f,0.0322314f},{0.0452473f,0.0768042f,0.0340958f},{0.0452483f,0.0768055f,0.0322314f}, -{0.0444957f,0.0758993f,0.0340958f},{0.0444974f,0.075901f,0.0322314f},{0.0436142f,0.075126f,0.0322314f}, -{0.0436125f,0.0751248f,0.0340958f},{0.0426177f,0.0744982f,0.0340958f},{0.0426206f,0.0744998f,0.0322314f}, -{0.0415395f,0.0740365f,0.0322314f},{0.0415373f,0.0740358f,0.0340958f},{0.0403988f,0.073749f,0.0340958f}, -{0.0404009f,0.0737495f,0.0322314f},{0.0392271f,0.0736446f,0.0340958f},{0.0392293f,0.0736447f,0.0322314f}, -{0.038057f,0.0737251f,0.0322314f},{0.0380562f,0.0737252f,0.0340958f},{0.0369109f,0.0739891f,0.0340958f}, -{0.0369109f,0.0739891f,0.0322314f},{0.027361f,0.0811018f,0.0322314f},{-0.027361f,0.0811018f,0.0322314f}, -{-0.027361f,0.0811018f,0.0340958f},{0.027361f,0.0811018f,0.0340958f},{-0.0454557f,0.0850877f,0.0340958f}, -{-0.043047f,0.0874618f,0.0340958f},{-0.0430486f,0.0874608f,0.0322314f},{-0.0439672f,0.0867969f,0.0340958f}, -{-0.0447773f,0.0859985f,0.0340958f},{-0.0439685f,0.086796f,0.0322314f},{-0.0447784f,0.0859974f,0.0322314f}, -{-0.03984f,0.0885276f,0.0322314f},{-0.0409568f,0.0883379f,0.0340958f},{-0.0398371f,0.0885279f,0.0340958f}, -{-0.0420378f,0.0879786f,0.0322314f},{-0.042035f,0.0879797f,0.0340958f},{-0.0409588f,0.0883374f,0.0322314f}, -{-0.037576f,0.0883909f,0.0340958f},{-0.0364863f,0.0880664f,0.0340958f},{-0.0364891f,0.0880674f,0.0322314f}, -{-0.0387004f,0.0885456f,0.0340958f},{-0.0375781f,0.0883913f,0.0322314f},{-0.0387033f,0.0885458f,0.0322314f}, -{-0.0354596f,0.0875809f,0.0340958f},{-0.0345192f,0.0869454f,0.0340958f},{-0.0345204f,0.0869463f,0.0322314f}, -{-0.0354613f,0.0875818f,0.0322314f},{-0.0336855f,0.0861739f,0.0322314f},{-0.0336844f,0.0861728f,0.0340958f}, -{-0.0329784f,0.0852846f,0.0340958f},{-0.0329787f,0.085285f,0.0322314f},{-0.0324146f,0.0842979f,0.0340958f}, -{-0.0324146f,0.0842979f,0.0322314f},{-0.045456f,0.0850872f,0.0322314f},{-0.021027f,0.0331264f,0.0340958f}, -{-0.0206381f,0.0368319f,0.0340958f},{-0.0206381f,0.0368317f,0.0322314f},{-0.0205085f,0.0405509f,0.0340958f}, -{-0.0205085f,0.0405509f,0.0322314f},{-0.021027f,0.0331261f,0.0322314f},{-0.0216751f,0.0294476f,0.0322314f}, -{-0.0216749f,0.0294486f,0.0340958f},{-0.0237299f,0.0222807f,0.0340958f},{-0.0225785f,0.0258242f,0.0340958f}, -{-0.0225785f,0.025824f,0.0322314f},{-0.0237299f,0.0222806f,0.0322314f},{-0.0267542f,0.0154851f,0.0340958f}, -{-0.0251237f,0.01883f,0.0322314f},{-0.0267544f,0.0154848f,0.0322314f},{-0.0286161f,0.0122577f,0.0340958f}, -{-0.0251236f,0.0188302f,0.0340958f},{-0.0286162f,0.0122575f,0.0322314f},{-0.0307038f,0.00916071f,0.0340958f}, -{-0.0307038f,0.00916071f,0.0322314f},{-0.0206381f,0.0442701f,0.0340958f},{-0.0206381f,0.0442699f,0.0322314f}, -{-0.021027f,0.0479754f,0.0322314f},{-0.021027f,0.0479757f,0.0340958f},{-0.0216751f,0.0516542f,0.0340958f}, -{-0.0216749f,0.0516532f,0.0322314f},{-0.0225785f,0.0552778f,0.0340958f},{-0.0225785f,0.0552777f,0.0322314f}, -{-0.0237299f,0.0588211f,0.0322314f},{-0.0237299f,0.0588212f,0.0340958f},{-0.0251237f,0.0622718f,0.0340958f}, -{-0.0251236f,0.0622716f,0.0322314f},{-0.0267544f,0.065617f,0.0340958f},{-0.0267542f,0.0656167f,0.0322314f}, -{-0.0286161f,0.0688441f,0.0322314f},{-0.0286162f,0.0688443f,0.0340958f},{-0.0307038f,0.0719411f,0.0322314f}, -{-0.0307038f,0.0719411f,0.0340958f},{-0.0465017f,0.00126733f,0.0340958f},{-0.044941f,0.00470215f,0.0322314f}, -{-0.0456552f,0.0036514f,0.0322314f},{-0.0449406f,0.00470266f,0.0340958f},{-0.0456542f,0.00365287f,0.0340958f}, -{-0.0461811f,0.00249326f,0.0322314f},{-0.046181f,0.00249363f,0.0340958f},{-0.0430341f,0.00636786f,0.0322314f}, -{-0.0418973f,0.00693419f,0.0340958f},{-0.0418979f,0.00693393f,0.0322314f},{-0.0440592f,0.00561614f,0.0340958f}, -{-0.0430328f,0.00636862f,0.0340958f},{-0.0440603f,0.00561515f,0.0322314f},{-0.0406822f,0.00729899f,0.0322314f}, -{-0.0394178f,0.00745289f,0.0340958f},{-0.0394182f,0.00745292f,0.0322314f},{-0.0406805f,0.00729943f,0.0340958f}, -{-0.0381522f,0.00739019f,0.0322314f},{-0.0381511f,0.00739011f,0.0340958f},{-0.0369109f,0.00711273f,0.0340958f}, -{-0.0369109f,0.00711273f,0.0322314f},{-0.046502f,0.00126624f,0.0322314f},{-0.021027f,-0.0479754f,0.0340958f}, -{-0.0206381f,-0.0442699f,0.0340958f},{-0.0206381f,-0.0442701f,0.0322314f},{-0.0205085f,-0.0405509f,0.0340958f}, -{-0.0205085f,-0.0405509f,0.0322314f},{-0.021027f,-0.0479757f,0.0322314f},{-0.0216751f,-0.0516542f,0.0322314f}, -{-0.0216749f,-0.0516532f,0.0340958f},{-0.0237299f,-0.0588211f,0.0340958f},{-0.0225785f,-0.0552777f,0.0340958f}, -{-0.0225785f,-0.0552778f,0.0322314f},{-0.0237299f,-0.0588212f,0.0322314f},{-0.0267542f,-0.0656167f,0.0340958f}, -{-0.0251237f,-0.0622718f,0.0322314f},{-0.0267544f,-0.065617f,0.0322314f},{-0.0286161f,-0.0688441f,0.0340958f}, -{-0.0251236f,-0.0622716f,0.0340958f},{-0.0286162f,-0.0688443f,0.0322314f},{-0.0307038f,-0.0719411f,0.0340958f}, -{-0.0307038f,-0.0719411f,0.0322314f},{-0.0206381f,-0.0368317f,0.0340958f},{-0.0206381f,-0.0368319f,0.0322314f}, -{-0.021027f,-0.0331264f,0.0322314f},{-0.021027f,-0.0331261f,0.0340958f},{-0.0216751f,-0.0294476f,0.0340958f}, -{-0.0216749f,-0.0294486f,0.0322314f},{-0.0225785f,-0.025824f,0.0340958f},{-0.0225785f,-0.0258241f,0.0322314f}, -{-0.0237299f,-0.0222807f,0.0322314f},{-0.0237299f,-0.0222806f,0.0340958f},{-0.0251237f,-0.01883f,0.0340958f}, -{-0.0251236f,-0.0188302f,0.0322314f},{-0.0267544f,-0.0154848f,0.0340958f},{-0.0267542f,-0.0154851f,0.0322314f}, -{-0.0286161f,-0.0122577f,0.0322314f},{-0.0286162f,-0.0122575f,0.0340958f},{-0.0307038f,-0.00916071f,0.0322314f}, -{-0.0307038f,-0.00916071f,0.0340958f},{-0.0463621f,-0.0830096f,0.0340958f},{-0.0464633f,-0.079629f,0.0340958f}, -{-0.0464637f,-0.0796309f,0.0322314f},{-0.0466021f,-0.0807558f,0.0340958f},{-0.0465681f,-0.0818927f,0.0340958f}, -{-0.0466023f,-0.0807574f,0.0322314f},{-0.046568f,-0.0818943f,0.0322314f},{-0.0450626f,-0.0765535f,0.0322314f}, -{-0.0456834f,-0.0775011f,0.0340958f},{-0.0450608f,-0.0765512f,0.0340958f},{-0.0461555f,-0.0785378f,0.0322314f}, -{-0.0461544f,-0.078535f,0.0340958f},{-0.0456844f,-0.0775029f,0.0322314f},{-0.0434222f,-0.0749873f,0.0340958f}, -{-0.0424429f,-0.0744094f,0.0340958f},{-0.0424456f,-0.0744108f,0.0322314f},{-0.0443005f,-0.075706f,0.0340958f}, -{-0.0434238f,-0.0749885f,0.0322314f},{-0.0443026f,-0.0757081f,0.0322314f},{-0.0413886f,-0.0739873f,0.0340958f}, -{-0.040283f,-0.0737303f,0.0340958f},{-0.0402846f,-0.0737307f,0.0322314f},{-0.0413904f,-0.0739879f,0.0322314f}, -{-0.0391504f,-0.0736443f,0.0322314f},{-0.0391489f,-0.0736442f,0.0340958f},{-0.0380175f,-0.073731f,0.0340958f}, -{-0.0380181f,-0.073731f,0.0322314f},{-0.0369109f,-0.0739891f,0.0340958f},{-0.0369109f,-0.0739891f,0.0322314f}, -{-0.046362f,-0.0830101f,0.0322314f},{0.027361f,-0.0811018f,0.0340958f},{-0.027361f,-0.0811018f,0.0322314f}, -{0.027361f,-0.0811018f,0.0322314f},{-0.027361f,-0.0811018f,0.0340958f},{0.0457312f,-0.0846141f,0.0340958f}, -{0.0462025f,-0.0835337f,0.0322314f},{0.0462016f,-0.0835364f,0.0340958f},{0.0464965f,-0.0823992f,0.0340958f}, -{0.0464969f,-0.0823973f,0.0322314f},{0.0466091f,-0.0812265f,0.0322314f},{0.046609f,-0.0812289f,0.0340958f}, -{0.0465364f,-0.0800555f,0.0340958f},{0.0465363f,-0.0800543f,0.0322314f},{0.0462804f,-0.0789085f,0.0322314f}, -{0.0462805f,-0.0789088f,0.0340958f},{0.0458466f,-0.0778144f,0.0322314f},{0.0458468f,-0.0778149f,0.0340958f}, -{0.0452483f,-0.0768055f,0.0340958f},{0.0452473f,-0.0768041f,0.0322314f},{0.0444974f,-0.075901f,0.0340958f}, -{0.0444957f,-0.0758994f,0.0322314f},{0.0436125f,-0.0751248f,0.0322314f},{0.0436142f,-0.075126f,0.0340958f}, -{0.0426206f,-0.0744997f,0.0340958f},{0.0426177f,-0.0744982f,0.0322314f},{0.0415373f,-0.0740358f,0.0322314f}, -{0.0415395f,-0.0740365f,0.0340958f},{0.0403988f,-0.073749f,0.0322314f},{0.0404009f,-0.0737495f,0.0340958f}, -{0.0392293f,-0.0736447f,0.0340958f},{0.0392271f,-0.0736446f,0.0322314f},{0.0380562f,-0.0737252f,0.0322314f}, -{0.038057f,-0.0737251f,0.0340958f},{0.0369109f,-0.0739891f,0.0322314f},{0.0369109f,-0.0739891f,0.0340958f}, -{0.0457326f,-0.0846116f,0.0322314f},{0.0450987f,-0.085603f,0.0340958f},{0.0450998f,-0.0856014f,0.0322314f}, -{0.044317f,-0.0864818f,0.0340958f},{0.0443187f,-0.0864801f,0.0322314f},{0.0434083f,-0.0872259f,0.0340958f}, -{0.0434093f,-0.0872252f,0.0322314f},{0.0423947f,-0.0878178f,0.0322314f},{0.0423945f,-0.087818f,0.0340958f}, -{0.0412975f,-0.0882443f,0.0340958f},{0.041298f,-0.0882442f,0.0322314f},{0.0401493f,-0.0884924f,0.0340958f}, -{0.040151f,-0.0884923f,0.0322314f},{0.0389749f,-0.0885572f,0.0340958f},{0.0389772f,-0.0885573f,0.0322314f}, -{0.0378083f,-0.0884373f,0.0322314f},{0.0378063f,-0.0884369f,0.0340958f},{0.0366703f,-0.088134f,0.0340958f}, -{0.0366734f,-0.0881351f,0.0322314f},{0.0355984f,-0.087658f,0.0322314f},{0.0355963f,-0.0876568f,0.0340958f}, -{0.0346116f,-0.0870176f,0.0340958f},{0.0346134f,-0.0870188f,0.0322314f},{0.0337379f,-0.0862299f,0.0340958f}, -{0.0337395f,-0.0862314f,0.0322314f},{0.0330008f,-0.0853175f,0.0322314f},{0.0330004f,-0.0853169f,0.0340958f}, -{0.0324146f,-0.0842979f,0.0340958f},{0.0324146f,-0.0842979f,0.0322314f},{0.02064f,-0.0442971f,0.0340958f}, -{0.0206399f,-0.0442969f,0.0322314f},{0.0225785f,-0.0552777f,0.0340958f},{0.0225785f,-0.0552776f,0.0322314f}, -{0.0216792f,-0.0516735f,0.0340958f},{0.0216792f,-0.0516732f,0.0322314f},{0.0210316f,-0.0480087f,0.0322314f}, -{0.0210317f,-0.048009f,0.0340958f},{0.0267447f,-0.0655989f,0.0322314f},{0.0251156f,-0.0622535f,0.0340958f}, -{0.0267448f,-0.0655992f,0.0340958f},{0.0237253f,-0.0588085f,0.0322314f},{0.0237254f,-0.0588086f,0.0340958f}, -{0.0251155f,-0.0622533f,0.0322314f},{0.028609f,-0.0688327f,0.0340958f},{0.0286089f,-0.0688325f,0.0322314f}, -{0.0307038f,-0.0719411f,0.0340958f},{0.0307038f,-0.0719411f,0.0322314f},{0.0206235f,-0.00372882f,0.0322314f}, -{0.0206235f,-0.00372882f,0.0340958f},{0.0466102f,3.97423e-017f,0.0340958f},{0.0466102f,3.97423e-017f,0.0322314f}, -{0.0465018f,0.00126639f,0.0322314f},{0.0461802f,0.00249579f,0.0322314f},{0.0465022f,0.00126441f,0.0340958f}, -{0.0456552f,0.00365135f,0.0322314f},{0.0461804f,0.00249531f,0.0340958f},{0.0456558f,0.00365019f,0.0340958f}, -{0.0449402f,0.00470316f,0.0322314f},{0.0440587f,0.00561661f,0.0322314f},{0.0449409f,0.00470218f,0.0340958f}, -{0.043034f,0.00636795f,0.0322314f},{0.0440594f,0.00561601f,0.0340958f},{0.0430353f,0.00636709f,0.0340958f}, -{0.0418963f,0.00693455f,0.0322314f},{0.040681f,0.00729936f,0.0322314f},{0.0418969f,0.00693434f,0.0340958f}, -{0.0394182f,0.00745287f,0.0322314f},{0.0406822f,0.00729903f,0.0340958f},{0.0394186f,0.0074529f,0.0340958f}, -{0.0381506f,0.00739003f,0.0322314f},{0.0369109f,0.00711273f,0.0322314f},{0.0381517f,0.00739014f,0.0340958f}, -{0.0369109f,0.00711273f,0.0340958f},{0.0465018f,-0.00126639f,0.0340958f},{0.0465022f,-0.00126441f,0.0322314f}, -{0.0461802f,-0.00249579f,0.0340958f},{0.0456552f,-0.00365135f,0.0340958f},{0.0461804f,-0.00249531f,0.0322314f}, -{0.0449402f,-0.00470316f,0.0340958f},{0.0456558f,-0.00365019f,0.0322314f},{0.0449409f,-0.00470218f,0.0322314f}, -{0.0440587f,-0.00561661f,0.0340958f},{0.043034f,-0.00636795f,0.0340958f},{0.0440594f,-0.00561601f,0.0322314f}, -{0.0418963f,-0.00693455f,0.0340958f},{0.0430353f,-0.00636709f,0.0322314f},{0.0418969f,-0.00693434f,0.0322314f}, -{0.040681f,-0.00729936f,0.0340958f},{0.0394182f,-0.00745287f,0.0340958f},{0.0406822f,-0.00729903f,0.0322314f}, -{0.0381506f,-0.00739003f,0.0340958f},{0.0394186f,-0.0074529f,0.0322314f},{0.0381517f,-0.00739014f,0.0322314f}, -{0.0369109f,-0.00711273f,0.0340958f},{0.0369109f,-0.00711273f,0.0322314f},{0.0195103f,0.0755086f,0.0322314f}, -{0.0195103f,0.0755086f,0.0340958f},{0.0418944f,0.000544649f,0.0340958f},{-0.0396981f,0.00274259f,0.0340958f}, -{-0.0346445f,-0.00688452f,0.0340958f},{-0.033477f,-0.00713571f,0.0340958f},{0.0417351f,0.00106869f,0.0340958f}, -{-0.0323894f,-0.0734732f,0.0340958f},{-0.033477f,-0.0739661f,0.0340958f},{-0.029784f,-0.081654f,0.0340958f}, -{0.0396989f,-0.0783596f,0.0340958f},{0.0402234f,-0.0785201f,0.0340958f},{0.038082f,0.0836861f,0.0340958f}, -{0.0386071f,0.0838444f,0.0340958f},{0.041477f,0.00155172f,0.0340958f},{0.041477f,-0.0795501f,0.0340958f}, -{0.0411295f,-0.0791268f,0.0340958f},{0.0417351f,-0.0800331f,0.0340958f},{0.0411295f,0.00197505f,0.0340958f}, -{0.0418944f,-0.0805572f,0.0340958f},{0.0407062f,0.00232262f,0.0340958f},{0.0402234f,0.00258168f,0.0340958f}, -{0.0396989f,0.00274216f,0.0340958f},{0.0391526f,0.00279661f,0.0340958f},{0.0386071f,0.00274259f,0.0340958f}, -{0.038082f,0.00258432f,0.0340958f},{0.0358134f,0.00688407f,0.0340958f},{0.0375977f,0.00232618f,0.0340958f}, -{0.0364081f,0.000545524f,0.0340958f},{0.0236456f,0.00527349f,0.0340958f},{0.0365672f,0.00107021f,0.0340958f}, -{0.033477f,0.00713571f,0.0340958f},{0.0371735f,0.00197799f,0.0340958f},{0.0346445f,0.00688452f,0.0340958f}, -{0.0346482f,-0.00688511f,0.0340958f},{0.0241643f,0.0086281f,0.0340958f},{0.0243399f,0.00776655f,0.0340958f}, -{0.0230511f,-0.00462716f,0.0340958f},{0.023646f,-0.00527393f,0.0340958f},{-0.0396981f,0.0838444f,0.0340958f}, -{-0.0402232f,0.0836861f,0.0340958f},{-0.0386063f,0.083844f,0.0340958f},{-0.0380818f,0.0836835f,0.0340958f}, -{-0.0346445f,0.0742173f,0.0340958f},{-0.0308772f,0.0823454f,0.0340958f},{0.0211824f,0.075113f,0.0340958f}, -{0.0219051f,0.0746381f,0.0340958f},{0.0358165f,0.0742161f,0.0340958f},{0.0323894f,0.0734732f,0.0340958f}, -{0.033477f,0.0739661f,0.0340958f},{0.029784f,0.081654f,0.0340958f},{0.03177f,0.0832527f,0.0340958f}, -{0.0364081f,0.0816473f,0.0340958f},{0.0375977f,0.083428f,0.0340958f},{0.0371735f,0.0830798f,0.0340958f}, -{0.0407062f,0.0834244f,0.0340958f},{0.0417351f,0.0821705f,0.0340958f},{0.0418944f,0.0816464f,0.0340958f}, -{0.041477f,0.0826535f,0.0340958f},{0.0411295f,0.0830768f,0.0340958f},{0.0396989f,0.083844f,0.0340958f}, -{0.0402234f,0.0836835f,0.0340958f},{0.0391526f,0.0838984f,0.0340958f},{0.0365672f,0.082172f,0.0340958f}, -{0.0368257f,0.0826556f,0.0340958f},{0.0346482f,0.0742167f,0.0340958f},{0.0308757f,0.0823441f,0.0340958f}, -{0.0285789f,0.0812367f,0.0340958f},{0.0314497f,0.072778f,0.0340958f},{0.0224988f,0.0740097f,0.0340958f}, -{0.0229321f,0.0732614f,0.0340958f},{0.0203695f,0.0754087f,0.0340958f},{-0.0314481f,0.0727748f,0.0340958f}, -{-0.0285817f,0.0812363f,0.0340958f},{-0.0231141f,0.0708224f,0.0340958f},{-0.0407075f,0.083428f,0.0340958f}, -{-0.0411317f,0.0830798f,0.0340958f},{-0.0417379f,0.082172f,0.0340958f},{-0.0418971f,0.0816473f,0.0340958f}, -{-0.0414795f,0.0826556f,0.0340958f},{-0.0391526f,0.0838984f,0.0340958f},{-0.0358134f,0.0742177f,0.0340958f}, -{-0.037599f,0.0834244f,0.0340958f},{-0.033477f,0.0739661f,0.0340958f},{-0.0418971f,0.000545524f,0.0340958f}, -{-0.0371757f,0.0830768f,0.0340958f},{-0.0368282f,0.0826535f,0.0340958f},{-0.0365701f,0.0821705f,0.0340958f}, -{-0.0323867f,0.0734705f,0.0340958f},{-0.0297859f,0.0816548f,0.0340958f},{-0.0231106f,0.0727502f,0.0340958f}, -{-0.0241967f,-0.00852371f,0.0340958f},{-0.0323867f,-0.00763125f,0.0340958f},{-0.0314481f,-0.00832702f,0.0340958f}, -{-0.033477f,0.00713571f,0.0340958f},{-0.0365701f,0.00106869f,0.0340958f},{-0.0364108f,0.000544649f,0.0340958f}, -{-0.0323894f,0.00762858f,0.0340958f},{-0.0386063f,0.00274216f,0.0340958f},{-0.0391526f,0.00279661f,0.0340958f}, -{-0.0368282f,0.00155172f,0.0340958f},{-0.0417379f,0.00107021f,0.0340958f},{-0.0414795f,0.0015538f,0.0340958f}, -{-0.0411317f,0.00197799f,0.0340958f},{-0.0407075f,0.00232618f,0.0340958f},{-0.0402232f,0.00258432f,0.0340958f}, -{-0.0418971f,-0.0805563f,0.0340958f},{-0.0417379f,-0.0800316f,0.0340958f},{-0.0358134f,-0.00688407f,0.0340958f}, -{-0.0225127f,0.00424291f,0.0340958f},{-0.0380818f,0.00258168f,0.0340958f},{-0.0358165f,0.00688568f,0.0340958f}, -{0.0214967f,-0.00383203f,0.0340958f},{0.0223196f,0.0041374f,0.0340958f},{0.0214955f,0.00383263f,0.0340958f}, -{-0.0216024f,0.00385961f,0.0340958f},{-0.024244f,-0.0065653f,0.0340958f},{0.0314497f,-0.00832383f,0.0340958f}, -{0.0243085f,-0.00688932f,0.0340958f},{0.0364081f,-0.0805563f,0.0340958f},{0.0308772f,-0.0823454f,0.0340958f}, -{0.0314481f,-0.0727748f,0.0340958f},{0.0285817f,-0.0812363f,0.0340958f},{0.0230854f,-0.0707188f,0.0340958f}, -{-0.0285788f,-0.0812367f,0.0340958f},{-0.0213716f,-0.0750107f,0.0340958f},{-0.022144f,-0.0744194f,0.0340958f}, -{-0.0365701f,-0.0800331f,0.0340958f},{-0.0391526f,-0.0783052f,0.0340958f},{-0.03177f,-0.0832527f,0.0340958f}, -{-0.0308757f,-0.0823441f,0.0340958f},{-0.0364108f,-0.0805572f,0.0340958f},{-0.0414795f,-0.079548f,0.0340958f}, -{-0.0411317f,-0.0791238f,0.0340958f},{-0.0407075f,-0.0787756f,0.0340958f},{-0.0402232f,-0.0785175f,0.0340958f}, -{-0.0396981f,-0.0783592f,0.0340958f},{-0.0386063f,-0.0783596f,0.0340958f},{-0.0368282f,-0.0795501f,0.0340958f}, -{-0.0371757f,-0.0791268f,0.0340958f},{-0.0346482f,-0.0742167f,0.0340958f},{-0.0358165f,-0.0742161f,0.0340958f}, -{0.0386071f,-0.0783592f,0.0340958f},{0.038082f,-0.0785175f,0.0340958f},{-0.0314497f,-0.072778f,0.0340958f}, -{0.0391526f,-0.0783052f,0.0340958f},{0.0407062f,-0.0787792f,0.0340958f},{0.0358134f,-0.0742177f,0.0340958f}, -{0.0375977f,-0.0787756f,0.0340958f},{0.0368257f,-0.079548f,0.0340958f},{0.0346445f,-0.0742173f,0.0340958f}, -{0.0365672f,-0.0800316f,0.0340958f},{0.0371735f,-0.0791238f,0.0340958f},{0.0297859f,-0.0816548f,0.0340958f}, -{0.033477f,-0.0739661f,0.0340958f},{0.0317708f,-0.0832554f,0.0340958f},{0.0323867f,-0.0734706f,0.0340958f}, -{0.0229318f,-0.0732619f,0.0340958f},{0.0223212f,-0.0041373f,0.0340958f},{0.0240731f,-0.00604206f,0.0340958f}, -{0.0323894f,-0.00762858f,0.0340958f},{0.0243087f,0.00688805f,0.0340958f},{0.0314481f,0.00832702f,0.0340958f}, -{0.0323867f,0.00763125f,0.0340958f},{0.0358165f,-0.00688568f,0.0340958f},{-0.023239f,0.071786f,0.0340958f}, -{0.0232328f,0.0715697f,0.0340958f},{0.0230844f,0.0707181f,0.0340958f},{0.0231812f,0.072433f,0.0340958f}, -{0.0240729f,0.00604156f,0.0340958f},{0.02305f,0.00462664f,0.0340958f},{0.033477f,-0.00713571f,0.0340958f}, -{0.024339f,-0.00776783f,0.0340958f},{0.0241632f,-0.00862874f,0.0340958f},{-0.0314497f,0.00832383f,0.0340958f}, -{-0.0346482f,0.00688511f,0.0340958f},{0.0231813f,-0.0724342f,0.0340958f},{0.0232336f,-0.071571f,0.0340958f}, -{0.021904f,-0.0746385f,0.0340958f},{0.0224985f,-0.0740101f,0.0340958f},{0.0203684f,-0.0754081f,0.0340958f}, -{0.0211809f,-0.0751129f,0.0340958f},{-0.0204736f,-0.075382f,0.0340958f},{-0.0243511f,-0.0075482f,0.0340958f}, -{-0.0232912f,0.00485238f,0.0340958f},{-0.0380818f,-0.0785201f,0.0340958f},{-0.037599f,-0.0787792f,0.0340958f}, -{-0.0364108f,0.0816464f,0.0340958f},{-0.0317708f,0.0832554f,0.0340958f},{0.0368257f,0.0015538f,0.0340958f}, -{-0.037599f,0.00232262f,0.0340958f},{-0.0371757f,0.00197505f,0.0340958f},{0.0314481f,0.0727748f,0.0322314f}, -{0.0229318f,0.0732619f,0.0322314f},{-0.0358134f,-0.0742177f,0.0322314f},{-0.0375977f,-0.0787756f,0.0322314f}, -{-0.038082f,-0.0785175f,0.0322314f},{-0.0391526f,-0.0783052f,0.0322314f},{0.0243399f,-0.00776655f,0.0322314f}, -{0.0243087f,-0.00688805f,0.0322314f},{0.0358165f,0.00688568f,0.0322314f},{0.0380818f,0.00258168f,0.0322314f}, -{0.037599f,0.00232262f,0.0322314f},{0.0241643f,-0.0086281f,0.0322314f},{0.033477f,-0.00713571f,0.0322314f}, -{0.0323867f,-0.00763125f,0.0322314f},{0.0396981f,0.00274259f,0.0322314f},{0.0391526f,0.00279661f,0.0322314f}, -{0.0407075f,0.00232618f,0.0322314f},{0.0402232f,0.00258432f,0.0322314f},{0.0417379f,0.00107021f,0.0322314f}, -{0.0358134f,-0.00688407f,0.0322314f},{0.0346445f,-0.00688452f,0.0322314f},{0.0417379f,0.082172f,0.0322314f}, -{0.0407075f,0.083428f,0.0322314f},{0.0402232f,0.0836861f,0.0322314f},{0.0396981f,0.0838444f,0.0322314f}, -{0.0418971f,0.000545524f,0.0322314f},{0.0414795f,0.0015538f,0.0322314f},{0.0411317f,0.00197799f,0.0322314f}, -{0.0386063f,0.00274216f,0.0322314f},{0.033477f,0.00713571f,0.0322314f},{0.0364108f,0.000544649f,0.0322314f}, -{0.0323894f,0.00762858f,0.0322314f},{0.0240729f,-0.00604156f,0.0322314f},{0.0236456f,-0.00527349f,0.0322314f}, -{0.0223212f,0.0041373f,0.0322314f},{0.0230511f,0.00462716f,0.0322314f},{0.0223196f,-0.0041374f,0.0322314f}, -{0.0346482f,0.00688511f,0.0322314f},{0.0368282f,0.00155172f,0.0322314f},{0.0365701f,0.00106869f,0.0322314f}, -{-0.0346445f,-0.0742173f,0.0322314f},{-0.0371735f,-0.0791238f,0.0322314f},{-0.0386071f,-0.0783592f,0.0322314f}, -{-0.0396989f,-0.0783596f,0.0322314f},{-0.0402234f,-0.0785201f,0.0322314f},{-0.0417351f,-0.0800331f,0.0322314f}, -{-0.0407062f,-0.0787792f,0.0322314f},{-0.0411295f,-0.0791268f,0.0322314f},{-0.041477f,-0.0795501f,0.0322314f}, -{-0.0285817f,-0.0812363f,0.0322314f},{-0.0323867f,-0.0734706f,0.0322314f},{-0.0314481f,-0.0727748f,0.0322314f}, -{-0.0365672f,-0.0800316f,0.0322314f},{-0.0308772f,-0.0823454f,0.0322314f},{-0.0364081f,-0.0805563f,0.0322314f}, -{0.029784f,-0.081654f,0.0322314f},{0.0323894f,-0.0734732f,0.0322314f},{0.033477f,-0.0739661f,0.0322314f}, -{0.0219051f,-0.0746381f,0.0322314f},{0.0211824f,-0.075113f,0.0322314f},{0.0391526f,-0.0783052f,0.0322314f}, -{0.0396981f,-0.0783592f,0.0322314f},{0.0386063f,-0.0783596f,0.0322314f},{0.0411317f,-0.0791238f,0.0322314f}, -{0.0407075f,-0.0787756f,0.0322314f},{0.0414795f,-0.079548f,0.0322314f},{0.0365701f,-0.0800331f,0.0322314f}, -{0.0417379f,-0.0800316f,0.0322314f},{0.0418971f,-0.0805563f,0.0322314f},{0.03177f,-0.0832527f,0.0322314f}, -{0.0308757f,-0.0823441f,0.0322314f},{0.0364108f,-0.0805572f,0.0322314f},{0.0402232f,-0.0785175f,0.0322314f}, -{0.0380818f,-0.0785201f,0.0322314f},{0.0346482f,-0.0742167f,0.0322314f},{0.0368282f,-0.0795501f,0.0322314f}, -{0.0371757f,-0.0791268f,0.0322314f},{0.0285789f,-0.0812367f,0.0322314f},{0.0314497f,-0.072778f,0.0322314f}, -{0.0224988f,-0.0740097f,0.0322314f},{0.0229321f,-0.0732614f,0.0322314f},{0.0230844f,-0.0707181f,0.0322314f}, -{-0.0418944f,-0.0805572f,0.0322314f},{-0.033477f,-0.0739661f,0.0322314f},{-0.0297859f,-0.0816548f,0.0322314f}, -{-0.0317708f,-0.0832554f,0.0322314f},{-0.0243512f,-0.00754595f,0.0322314f},{-0.0242437f,-0.00656417f,0.0322314f}, -{-0.0216035f,0.00385992f,0.0322314f},{-0.024197f,-0.00852259f,0.0322314f},{-0.0323867f,0.00763125f,0.0322314f}, -{-0.0364081f,0.000545524f,0.0322314f},{-0.0418944f,0.000544649f,0.0322314f},{-0.0411295f,0.00197505f,0.0322314f}, -{-0.0407062f,0.00232262f,0.0322314f},{-0.0386071f,0.00274259f,0.0322314f},{-0.0391526f,0.00279661f,0.0322314f}, -{-0.0358134f,0.00688407f,0.0322314f},{-0.0375977f,0.00232618f,0.0322314f},{-0.038082f,0.00258432f,0.0322314f}, -{-0.041477f,0.00155172f,0.0322314f},{-0.0417351f,0.00106869f,0.0322314f},{-0.0402234f,0.00258168f,0.0322314f}, -{-0.0371735f,0.00197799f,0.0322314f},{-0.0346445f,0.00688452f,0.0322314f},{-0.0396989f,0.00274216f,0.0322314f}, -{-0.0358165f,-0.00688568f,0.0322314f},{-0.033477f,0.00713571f,0.0322314f},{-0.023292f,0.00485321f,0.0322314f}, -{-0.0346482f,-0.00688511f,0.0322314f},{0.0314497f,0.00832383f,0.0322314f},{0.0243085f,0.00688932f,0.0322314f}, -{0.0230854f,0.0707188f,0.0322314f},{-0.0346482f,0.0742167f,0.0322314f},{-0.033477f,0.0739661f,0.0322314f}, -{-0.0231144f,0.0708235f,0.0322314f},{-0.0368257f,0.0826556f,0.0322314f},{-0.0396989f,0.083844f,0.0322314f}, -{-0.0391526f,0.0838984f,0.0322314f},{-0.0375977f,0.083428f,0.0322314f},{-0.038082f,0.0836861f,0.0322314f}, -{-0.0411295f,0.0830768f,0.0322314f},{-0.041477f,0.0826535f,0.0322314f},{-0.0371735f,0.0830798f,0.0322314f}, -{-0.0418944f,0.0816464f,0.0322314f},{-0.0417351f,0.0821705f,0.0322314f},{-0.0402234f,0.0836835f,0.0322314f}, -{-0.0386071f,0.0838444f,0.0322314f},{-0.0407062f,0.0834244f,0.0322314f},{-0.0364081f,0.0816473f,0.0322314f}, -{-0.0365672f,0.082172f,0.0322314f},{-0.03177f,0.0832527f,0.0322314f},{-0.0308757f,0.0823441f,0.0322314f}, -{-0.0358165f,0.0742161f,0.0322314f},{-0.029784f,0.081654f,0.0322314f},{-0.0323894f,0.0734732f,0.0322314f}, -{-0.0285788f,0.0812367f,0.0322314f},{-0.0314497f,0.072778f,0.0322314f},{-0.0231103f,0.0727513f,0.0322314f}, -{0.0391526f,0.0838984f,0.0322314f},{0.0380818f,0.0836835f,0.0322314f},{0.0386063f,0.083844f,0.0322314f}, -{0.0414795f,0.0826556f,0.0322314f},{0.0411317f,0.0830798f,0.0322314f},{0.0418971f,0.0816473f,0.0322314f}, -{0.0358134f,0.0742177f,0.0322314f},{0.0346445f,0.0742173f,0.0322314f},{0.033477f,0.0739661f,0.0322314f}, -{0.0371757f,0.0830768f,0.0322314f},{0.037599f,0.0834244f,0.0322314f},{0.0368282f,0.0826535f,0.0322314f}, -{0.0308772f,0.0823454f,0.0322314f},{0.0323867f,0.0734705f,0.0322314f},{0.0297859f,0.0816548f,0.0322314f}, -{0.0285817f,0.0812363f,0.0322314f},{0.0187991f,0.0422603f,0.0322314f},{0.0232336f,0.071571f,0.0322314f}, -{0.0231813f,0.0724342f,0.0322314f},{0.021904f,0.0746385f,0.0322314f},{0.0224985f,0.0740101f,0.0322314f}, -{0.0203684f,0.0754081f,0.0322314f},{0.0211809f,0.0751129f,0.0322314f},{-0.023239f,0.0717882f,0.0322314f}, -{0.024339f,0.00776783f,0.0322314f},{0.0241632f,0.00862874f,0.0322314f},{-0.0314481f,0.00832702f,0.0322314f}, -{-0.0225146f,0.00424405f,0.0322314f},{-0.0323894f,-0.00762858f,0.0322314f},{-0.0314497f,-0.00832383f,0.0322314f}, -{0.023646f,0.00527393f,0.0322314f},{0.0240731f,0.00604206f,0.0322314f},{0.0314481f,-0.00832702f,0.0322314f}, -{0.02305f,-0.00462664f,0.0322314f},{0.0214955f,-0.00383263f,0.0322314f},{0.0214967f,0.00383203f,0.0322314f}, -{-0.033477f,-0.00713571f,0.0322314f},{-0.0213735f,-0.0750096f,0.0322314f},{-0.0221448f,-0.0744186f,0.0322314f}, -{-0.0204747f,-0.0753817f,0.0322314f},{0.0232328f,-0.0715697f,0.0322314f},{0.0231812f,-0.072433f,0.0322314f}, -{0.0203695f,-0.0754087f,0.0322314f},{-0.0368257f,-0.079548f,0.0322314f},{0.0358165f,-0.0742161f,0.0322314f}, -{0.037599f,-0.0787792f,0.0322314f},{0.0365701f,0.0821705f,0.0322314f},{0.0364108f,0.0816464f,0.0322314f}, -{0.0317708f,0.0832554f,0.0322314f},{0.0371757f,0.00197505f,0.0322314f},{-0.0368257f,0.0015538f,0.0322314f}, -{-0.0365672f,0.00107021f,0.0322314f},{-0.285968f,-0.0125242f,0.0900281f},{-0.286022f,-0.0130723f,0.0918925f}, -{-0.285968f,-0.0125242f,0.0918925f},{-0.286181f,-0.011454f,0.0918925f},{-0.286181f,-0.011454f,0.0900281f}, -{-0.286022f,-0.0119761f,0.0918925f},{-0.286022f,-0.0119761f,0.0900281f},{-0.286438f,-0.0109726f,0.0900281f}, -{-0.286787f,-0.0105467f,0.0900281f},{-0.286787f,-0.0105467f,0.0918925f},{-0.287213f,-0.0101975f,0.0900281f}, -{-0.287213f,-0.0101975f,0.0918925f},{-0.286438f,-0.0109726f,0.0918925f},{-0.288764f,-0.00972758f,0.0900281f}, -{-0.288216f,-0.00978182f,0.0900281f},{-0.288216f,-0.00978182f,0.0918925f},{-0.287694f,-0.00994047f,0.0918925f}, -{-0.287694f,-0.00994047f,0.0900281f},{-0.288764f,-0.00972758f,0.0918925f},{-0.286022f,-0.0130723f,0.0900281f}, -{-0.286181f,-0.0135944f,0.0918925f},{-0.286181f,-0.0135944f,0.0900281f},{-0.286438f,-0.0140758f,0.0900281f}, -{-0.286438f,-0.0140758f,0.0918925f},{-0.286787f,-0.0145017f,0.0900281f},{-0.286787f,-0.0145017f,0.0918925f}, -{-0.287213f,-0.0148509f,0.0918925f},{-0.287213f,-0.0148509f,0.0900281f},{-0.287694f,-0.0151079f,0.0900281f}, -{-0.287694f,-0.0151079f,0.0918925f},{-0.288216f,-0.0152666f,0.0900281f},{-0.288216f,-0.0152666f,0.0918925f}, -{-0.288764f,-0.0153208f,0.0918925f},{-0.288764f,-0.0153208f,0.0900281f},{-0.311016f,0.0125242f,0.0900281f}, -{-0.31107f,0.0119761f,0.0918925f},{-0.311016f,0.0125242f,0.0918925f},{-0.311229f,0.0135944f,0.0918925f}, -{-0.311229f,0.0135944f,0.0900281f},{-0.31107f,0.0130723f,0.0918925f},{-0.31107f,0.0130723f,0.0900281f}, -{-0.311486f,0.0140758f,0.0900281f},{-0.311835f,0.0145017f,0.0900281f},{-0.311835f,0.0145017f,0.0918925f}, -{-0.312261f,0.0148509f,0.0900281f},{-0.312261f,0.0148509f,0.0918925f},{-0.311486f,0.0140758f,0.0918925f}, -{-0.313813f,0.0153208f,0.0900281f},{-0.313265f,0.0152666f,0.0900281f},{-0.313265f,0.0152666f,0.0918925f}, -{-0.312743f,0.0151079f,0.0918925f},{-0.312743f,0.0151079f,0.0900281f},{-0.313813f,0.0153208f,0.0918925f}, -{-0.31107f,0.0119761f,0.0900281f},{-0.311229f,0.011454f,0.0918925f},{-0.311229f,0.011454f,0.0900281f}, -{-0.311486f,0.0109726f,0.0900281f},{-0.311486f,0.0109726f,0.0918925f},{-0.311835f,0.0105467f,0.0900281f}, -{-0.311835f,0.0105467f,0.0918925f},{-0.312261f,0.0101975f,0.0918925f},{-0.312261f,0.0101975f,0.0900281f}, -{-0.312743f,0.00994047f,0.0900281f},{-0.312743f,0.00994047f,0.0918925f},{-0.313265f,0.00978182f,0.0900281f}, -{-0.313265f,0.00978182f,0.0918925f},{-0.313813f,0.00972758f,0.0918925f},{-0.313813f,0.00972758f,0.0900281f}, -{-0.284736f,-0.0073455f,0.0900281f},{-0.285954f,-0.00738926f,0.0918925f},{-0.284736f,-0.00734538f,0.0918925f}, -{-0.283556f,-0.00703877f,0.0900281f},{-0.283555f,-0.0070384f,0.0918925f},{-0.28247f,-0.00648281f,0.0900281f}, -{-0.28247f,-0.00648282f,0.0918925f},{-0.285956f,-0.00738915f,0.0900281f},{-0.287154f,-0.00716427f,0.0918925f}, -{-0.287154f,-0.00716427f,0.0900281f},{-0.309858f,0.00856857f,0.0918925f},{-0.310706f,0.0078732f,0.0918925f}, -{-0.309857f,0.00856991f,0.0900281f},{-0.310705f,0.00787361f,0.0900281f},{-0.311673f,0.0073566f,0.0918925f}, -{-0.312722f,0.00703838f,0.0918925f},{-0.311672f,0.00735691f,0.0900281f},{-0.313813f,0.00693097f,0.0918925f}, -{-0.312721f,0.00703853f,0.0900281f},{-0.313813f,0.00693097f,0.0900281f},{-0.309162f,0.00941743f,0.0900281f}, -{-0.308645f,0.0103841f,0.0900281f},{-0.309162f,0.00941663f,0.0918925f},{-0.308327f,0.0114331f,0.0900281f}, -{-0.308645f,0.0103834f,0.0918925f},{-0.308327f,0.0114326f,0.0918925f},{-0.30822f,0.0125242f,0.0900281f}, -{-0.30822f,0.0125242f,0.0918925f},{-0.401959f,-0.065917f,0.0918925f},{-0.398048f,-0.0617984f,0.0918925f}, -{-0.40196f,-0.0659174f,0.0900281f},{-0.405692f,-0.07019f,0.0900281f},{-0.405691f,-0.0701898f,0.0918925f}, -{-0.409237f,-0.0746077f,0.0900281f},{-0.409237f,-0.0746076f,0.0918925f},{-0.412592f,-0.0791643f,0.0918925f}, -{-0.412592f,-0.0791644f,0.0900281f},{-0.415754f,-0.0838538f,0.0900281f},{-0.415754f,-0.0838537f,0.0918925f}, -{-0.418717f,-0.0886696f,0.0900281f},{-0.418717f,-0.0886696f,0.0918925f},{-0.421479f,-0.0936056f,0.0918925f}, -{-0.421479f,-0.0936057f,0.0900281f},{-0.424035f,-0.0986557f,0.0900281f},{-0.424035f,-0.0986556f,0.0918925f}, -{-0.426382f,-0.103813f,0.0900281f},{-0.426382f,-0.103813f,0.0918925f},{-0.428515f,-0.109072f,0.0918925f}, -{-0.428515f,-0.109073f,0.0900281f},{-0.430428f,-0.11442f,0.0900281f},{-0.430428f,-0.11442f,0.0918925f}, -{-0.432114f,-0.119834f,0.0900281f},{-0.432114f,-0.119834f,0.0918925f},{-0.433572f,-0.125306f,0.0918925f}, -{-0.433572f,-0.125307f,0.0900281f},{-0.4348f,-0.130829f,0.0900281f},{-0.4348f,-0.130829f,0.0918925f}, -{-0.435797f,-0.136396f,0.0900281f},{-0.435797f,-0.136396f,0.0918925f},{-0.436561f,-0.141999f,0.0918925f}, -{-0.436561f,-0.141999f,0.0900281f},{-0.437093f,-0.147631f,0.0900281f},{-0.437093f,-0.147631f,0.0918925f}, -{-0.437391f,-0.153284f,0.0900281f},{-0.437391f,-0.153284f,0.0918925f},{-0.437453f,-0.158952f,0.0918925f}, -{-0.437453f,-0.158952f,0.0900281f},{-0.437279f,-0.164627f,0.0900281f},{-0.437279f,-0.164627f,0.0918925f}, -{-0.398048f,-0.0617987f,0.0900281f},{-0.393973f,-0.0578515f,0.0900281f},{-0.393973f,-0.0578514f,0.0918925f}, -{-0.389744f,-0.054083f,0.0918925f},{-0.389744f,-0.0540831f,0.0900281f},{-0.385366f,-0.0504973f,0.0918925f}, -{-0.385366f,-0.0504974f,0.0900281f},{-0.380846f,-0.0470986f,0.0900281f},{-0.380846f,-0.0470985f,0.0918925f}, -{-0.376189f,-0.0438908f,0.0918925f},{-0.376189f,-0.0438908f,0.0900281f},{-0.371402f,-0.0408784f,0.0918925f}, -{-0.371402f,-0.0408785f,0.0900281f},{-0.36649f,-0.0380656f,0.0900281f},{-0.36649f,-0.0380655f,0.0918925f}, -{-0.36146f,-0.0354565f,0.0918925f},{-0.36146f,-0.0354565f,0.0900281f},{-0.356317f,-0.0330551f,0.0918925f}, -{-0.356318f,-0.0330554f,0.0900281f},{-0.351076f,-0.0308688f,0.0900281f},{-0.351076f,-0.0308688f,0.0918925f}, -{-0.345756f,-0.0289059f,0.0918925f},{-0.345756f,-0.0289059f,0.0900281f},{-0.340366f,-0.0271683f,0.0918925f}, -{-0.340366f,-0.0271684f,0.0900281f},{-0.334914f,-0.0256577f,0.0900281f},{-0.334914f,-0.0256577f,0.0918925f}, -{-0.329406f,-0.0243753f,0.0918925f},{-0.329406f,-0.0243754f,0.0900281f},{-0.32385f,-0.0233228f,0.0918925f}, -{-0.32385f,-0.0233228f,0.0900281f},{-0.318253f,-0.0225016f,0.0900281f},{-0.318253f,-0.0225016f,0.0918925f}, -{-0.312622f,-0.0219132f,0.0918925f},{-0.312623f,-0.0219132f,0.0900281f},{-0.306965f,-0.0215591f,0.0918925f}, -{-0.306965f,-0.0215591f,0.0900281f},{-0.301289f,-0.0214407f,0.0918925f},{-0.301289f,-0.0214407f,0.0900281f}, -{-0.300061f,-0.0214056f,0.0918925f},{-0.300061f,-0.0214056f,0.0900281f},{-0.298838f,-0.0213002f,0.0900281f}, -{-0.298838f,-0.0213002f,0.0918925f},{-0.29272f,-0.00857005f,0.0900281f},{-0.293362f,-0.00933952f,0.0900281f}, -{-0.292718f,-0.00856812f,0.0918925f},{-0.293856f,-0.0102104f,0.0918925f},{-0.293362f,-0.00933867f,0.0918925f}, -{-0.293857f,-0.010212f,0.0900281f},{-0.294188f,-0.0111572f,0.0918925f},{-0.294188f,-0.0111588f,0.0900281f}, -{-0.294345f,-0.0121484f,0.0918925f},{-0.294322f,-0.0131504f,0.0918925f},{-0.294345f,-0.0121494f,0.0900281f}, -{-0.294121f,-0.0141339f,0.0900281f},{-0.294322f,-0.0131516f,0.0900281f},{-0.294121f,-0.0141339f,0.0918925f}, -{-0.291949f,-0.00792586f,0.0918925f},{-0.29195f,-0.00792654f,0.0900281f},{-0.291078f,-0.00743177f,0.0900281f}, -{-0.290131f,-0.00710074f,0.0900281f},{-0.291076f,-0.00743116f,0.0918925f},{-0.290129f,-0.00710007f,0.0918925f}, -{-0.28914f,-0.00694354f,0.0900281f},{-0.289139f,-0.00694356f,0.0918925f},{-0.288138f,-0.00696625f,0.0900281f}, -{-0.288136f,-0.00696632f,0.0918925f},{-0.283634f,0.0121669f,0.0900281f},{-0.282482f,0.0102959f,0.0900281f}, -{-0.282482f,0.0102961f,0.0918925f},{-0.283634f,0.012167f,0.0918925f},{-0.284976f,0.013914f,0.0900281f}, -{-0.281528f,0.008319f,0.0918925f},{-0.281527f,0.00831882f,0.0900281f},{-0.280779f,0.00625128f,0.0918925f}, -{-0.280779f,0.00625078f,0.0900281f},{-0.280246f,0.00411456f,0.0918925f},{-0.280246f,0.00411435f,0.0900281f}, -{-0.279936f,0.00194003f,0.0900281f},{-0.279936f,0.0019402f,0.0918925f},{-0.279849f,-0.000253827f,0.0918925f}, -{-0.279988f,-0.00245022f,0.0918925f},{-0.279849f,-0.00025393f,0.0900281f},{-0.279988f,-0.00245022f,0.0900281f}, -{-0.286486f,0.0155106f,0.0900281f},{-0.284976f,0.0139141f,0.0918925f},{-0.286486f,0.0155107f,0.0918925f}, -{-0.288149f,0.016943f,0.0900281f},{-0.28815f,0.0169431f,0.0918925f},{-0.289954f,0.0181996f,0.0900281f}, -{-0.29188f,0.0192663f,0.0900281f},{-0.289954f,0.0181999f,0.0918925f},{-0.291881f,0.0192664f,0.0918925f}, -{-0.293901f,0.0201277f,0.0900281f},{-0.293901f,0.0201278f,0.0918925f},{-0.295998f,0.0207778f,0.0900281f}, -{-0.298156f,0.0212106f,0.0900281f},{-0.295998f,0.0207778f,0.0918925f},{-0.298156f,0.0212106f,0.0918925f}, -{-0.303955f,0.0200545f,0.0900281f},{-0.302604f,0.0207145f,0.0918925f},{-0.303956f,0.020054f,0.0918925f}, -{-0.305176f,0.0191712f,0.0900281f},{-0.302603f,0.0207149f,0.0900281f},{-0.301156f,0.0211353f,0.0918925f}, -{-0.305176f,0.0191712f,0.0918925f},{-0.301155f,0.0211356f,0.0900281f},{-0.29966f,0.021302f,0.0918925f}, -{-0.299659f,0.0213021f,0.0900281f},{-0.306228f,0.0180928f,0.0900281f},{-0.306229f,0.018092f,0.0918925f}, -{-0.307079f,0.0168512f,0.0918925f},{-0.307079f,0.0168521f,0.0900281f},{-0.307707f,0.0154797f,0.0918925f}, -{-0.307707f,0.0154807f,0.0900281f},{-0.30809f,0.0140259f,0.0900281f},{-0.30809f,0.014025f,0.0918925f}, -{-0.314904f,0.00703853f,0.0918925f},{-0.317768f,0.00856991f,0.0918925f},{-0.31692f,0.0078732f,0.0900281f}, -{-0.31692f,0.00787361f,0.0918925f},{-0.315954f,0.00735691f,0.0918925f},{-0.315953f,0.0073566f,0.0900281f}, -{-0.314904f,0.00703838f,0.0900281f},{-0.31898f,0.0103834f,0.0900281f},{-0.31898f,0.0103841f,0.0918925f}, -{-0.319299f,0.0114331f,0.0918925f},{-0.317767f,0.00856857f,0.0900281f},{-0.318464f,0.00941743f,0.0918925f}, -{-0.318463f,0.00941663f,0.0900281f},{-0.319406f,0.0125242f,0.0918925f},{-0.319298f,0.0114326f,0.0900281f}, -{-0.319406f,0.0125242f,0.0900281f},{-0.32063f,0.017806f,0.0900281f},{-0.32063f,0.0178073f,0.0918925f}, -{-0.321554f,0.0193785f,0.0900281f},{-0.321554f,0.0193787f,0.0918925f},{-0.319955f,0.0161135f,0.0918925f}, -{-0.319955f,0.0161128f,0.0900281f},{-0.319544f,0.0143418f,0.0900281f},{-0.319544f,0.0143423f,0.0918925f}, -{-0.322701f,0.0207886f,0.0900281f},{-0.324052f,0.0220123f,0.0900281f},{-0.322701f,0.0207888f,0.0918925f}, -{-0.324053f,0.0220132f,0.0918925f},{-0.325573f,0.023018f,0.0900281f},{-0.325573f,0.0230183f,0.0918925f}, -{-0.327224f,0.02378f,0.0900281f},{-0.328976f,0.0242851f,0.0900281f},{-0.327224f,0.0237802f,0.0918925f}, -{-0.328976f,0.0242851f,0.0918925f},{-0.409092f,0.0744192f,0.0918925f},{-0.409092f,0.0744192f,0.0900281f}, -{-0.405539f,0.0700077f,0.0900281f},{-0.401803f,0.065746f,0.0900281f},{-0.405539f,0.0700077f,0.0918925f}, -{-0.397891f,0.06164f,0.0900281f},{-0.401803f,0.0657461f,0.0918925f},{-0.397891f,0.0616401f,0.0918925f}, -{-0.393805f,0.0576956f,0.0900281f},{-0.389551f,0.0539185f,0.0900281f},{-0.393805f,0.0576957f,0.0918925f}, -{-0.385134f,0.0503158f,0.0900281f},{-0.389551f,0.0539186f,0.0918925f},{-0.385135f,0.050316f,0.0918925f}, -{-0.380577f,0.0469052f,0.0900281f},{-0.375889f,0.0436939f,0.0900281f},{-0.380577f,0.0469052f,0.0918925f}, -{-0.371079f,0.0406851f,0.0900281f},{-0.375889f,0.0436939f,0.0918925f},{-0.371079f,0.0406851f,0.0918925f}, -{-0.366152f,0.0378819f,0.0900281f},{-0.361116f,0.0352877f,0.0900281f},{-0.366152f,0.037882f,0.0918925f}, -{-0.355977f,0.0329054f,0.0900281f},{-0.361116f,0.0352877f,0.0918925f},{-0.355977f,0.0329055f,0.0918925f}, -{-0.350742f,0.0307383f,0.0900281f},{-0.345418f,0.0287896f,0.0900281f},{-0.350742f,0.0307384f,0.0918925f}, -{-0.340011f,0.0270624f,0.0900281f},{-0.345418f,0.0287897f,0.0918925f},{-0.340011f,0.0270624f,0.0918925f}, -{-0.334528f,0.0255598f,0.0900281f},{-0.334528f,0.0255599f,0.0918925f},{-0.412458f,0.0789746f,0.0918925f}, -{-0.412458f,0.0789746f,0.0900281f},{-0.415634f,0.0836681f,0.0918925f},{-0.418614f,0.0884938f,0.0918925f}, -{-0.415634f,0.083668f,0.0900281f},{-0.421394f,0.0934459f,0.0918925f},{-0.418614f,0.0884937f,0.0900281f}, -{-0.421394f,0.0934458f,0.0900281f},{-0.423969f,0.0985185f,0.0918925f},{-0.426335f,0.103704f,0.0918925f}, -{-0.423969f,0.0985183f,0.0900281f},{-0.428478f,0.108978f,0.0918925f},{-0.426334f,0.103704f,0.0900281f}, -{-0.428478f,0.108977f,0.0900281f},{-0.430397f,0.114326f,0.0918925f},{-0.432088f,0.119742f,0.0918925f}, -{-0.430397f,0.114326f,0.0900281f},{-0.43355f,0.125218f,0.0918925f},{-0.432088f,0.119742f,0.0900281f}, -{-0.43355f,0.125218f,0.0900281f},{-0.434783f,0.130747f,0.0918925f},{-0.435785f,0.136322f,0.0918925f}, -{-0.434783f,0.130747f,0.0900281f},{-0.436554f,0.141936f,0.0918925f},{-0.435785f,0.136322f,0.0900281f}, -{-0.436554f,0.141935f,0.0900281f},{-0.43709f,0.14758f,0.0918925f},{-0.43739f,0.153248f,0.0918925f}, -{-0.43709f,0.14758f,0.0900281f},{-0.437453f,0.158933f,0.0918925f},{-0.43739f,0.153248f,0.0900281f}, -{-0.437453f,0.158933f,0.0900281f},{-0.437279f,0.164627f,0.0918925f},{-0.437279f,0.164627f,0.0900281f}, -{-0.445352f,0.169288f,0.0900281f},{-0.445352f,0.169288f,0.0918925f},{-0.489867f,0.0239114f,0.0918925f}, -{-0.490408f,0.0143525f,0.0918925f},{-0.490408f,0.0143527f,0.0900281f},{-0.490679f,-0.00478512f,0.0900281f}, -{-0.490679f,0.00478519f,0.0900281f},{-0.490679f,0.00478512f,0.0918925f},{-0.489867f,0.0239115f,0.0900281f}, -{-0.489056f,0.0334558f,0.0918925f},{-0.489056f,0.0334558f,0.0900281f},{-0.487973f,0.0429801f,0.0900281f}, -{-0.487973f,0.04298f,0.0918925f},{-0.486621f,0.0524782f,0.0918925f},{-0.486621f,0.0524784f,0.0900281f}, -{-0.484998f,0.0619436f,0.0900281f},{-0.484998f,0.0619434f,0.0918925f},{-0.480955f,0.0806965f,0.0900281f}, -{-0.47854f,0.089968f,0.0900281f},{-0.47854f,0.0899679f,0.0918925f},{-0.483109f,0.0713532f,0.0918925f}, -{-0.483109f,0.0713532f,0.0900281f},{-0.480955f,0.0806964f,0.0918925f},{-0.475866f,0.0991622f,0.0918925f}, -{-0.475866f,0.0991623f,0.0900281f},{-0.472933f,0.108274f,0.0900281f},{-0.472933f,0.108274f,0.0918925f}, -{-0.469745f,0.117298f,0.0918925f},{-0.469745f,0.117298f,0.0900281f},{-0.466302f,0.126228f,0.0918925f}, -{-0.458664f,0.143787f,0.0900281f},{-0.458664f,0.143786f,0.0918925f},{-0.462608f,0.135059f,0.0900281f}, -{-0.462608f,0.135059f,0.0918925f},{-0.466302f,0.126228f,0.0900281f},{-0.454472f,0.152404f,0.0900281f}, -{-0.454472f,0.152404f,0.0918925f},{-0.450034f,0.160907f,0.0900281f},{-0.450034f,0.160906f,0.0918925f}, -{-0.490679f,-0.00478519f,0.0918925f},{-0.490408f,-0.0143525f,0.0900281f},{-0.490408f,-0.0143527f,0.0918925f}, -{-0.489867f,-0.0239114f,0.0900281f},{-0.489056f,-0.0334558f,0.0900281f},{-0.489867f,-0.0239115f,0.0918925f}, -{-0.489056f,-0.0334558f,0.0918925f},{-0.487973f,-0.04298f,0.0900281f},{-0.487973f,-0.0429801f,0.0918925f}, -{-0.486621f,-0.0524782f,0.0900281f},{-0.484998f,-0.0619434f,0.0900281f},{-0.486621f,-0.0524784f,0.0918925f}, -{-0.484998f,-0.0619436f,0.0918925f},{-0.483109f,-0.0713532f,0.0900281f},{-0.483109f,-0.0713532f,0.0918925f}, -{-0.480955f,-0.0806964f,0.0900281f},{-0.47854f,-0.0899679f,0.0900281f},{-0.480955f,-0.0806965f,0.0918925f}, -{-0.47854f,-0.089968f,0.0918925f},{-0.475866f,-0.0991622f,0.0900281f},{-0.475866f,-0.0991623f,0.0918925f}, -{-0.472933f,-0.108274f,0.0900281f},{-0.469745f,-0.117298f,0.0900281f},{-0.472933f,-0.108274f,0.0918925f}, -{-0.469745f,-0.117298f,0.0918925f},{-0.466302f,-0.126228f,0.0900281f},{-0.466302f,-0.126228f,0.0918925f}, -{-0.462608f,-0.135059f,0.0900281f},{-0.458664f,-0.143786f,0.0900281f},{-0.462608f,-0.135059f,0.0918925f}, -{-0.458664f,-0.143787f,0.0918925f},{-0.454472f,-0.152404f,0.0900281f},{-0.454472f,-0.152404f,0.0918925f}, -{-0.450034f,-0.160906f,0.0900281f},{-0.445352f,-0.169288f,0.0900281f},{-0.450034f,-0.160907f,0.0918925f}, -{-0.445352f,-0.169288f,0.0918925f},{-0.427553f,0.169776f,0.0918925f},{-0.448656f,0.18196f,0.0900281f}, -{-0.448656f,0.18196f,0.0918925f},{-0.427553f,0.169776f,0.0900281f},{-0.400468f,0.0785294f,0.0900281f}, -{-0.403757f,0.0828396f,0.0900281f},{-0.403757f,0.0828395f,0.0918925f},{-0.396993f,0.0743574f,0.0900281f}, -{-0.396993f,0.074357f,0.0918925f},{-0.393337f,0.0703325f,0.0900281f},{-0.406855f,0.0872815f,0.0918925f}, -{-0.400468f,0.0785292f,0.0918925f},{-0.406855f,0.0872816f,0.0900281f},{-0.409759f,0.0918488f,0.0918925f}, -{-0.409759f,0.091849f,0.0900281f},{-0.412465f,0.0965352f,0.0900281f},{-0.412465f,0.0965352f,0.0918925f}, -{-0.41497f,0.101334f,0.0918925f},{-0.41497f,0.101334f,0.0900281f},{-0.417269f,0.106239f,0.0900281f}, -{-0.419359f,0.111243f,0.0918925f},{-0.417269f,0.106239f,0.0918925f},{-0.419359f,0.111243f,0.0900281f}, -{-0.421236f,0.116342f,0.0900281f},{-0.421236f,0.116341f,0.0918925f},{-0.425533f,0.132038f,0.0918925f}, -{-0.424327f,0.126754f,0.0900281f},{-0.425533f,0.132038f,0.0900281f},{-0.422894f,0.121519f,0.0918925f}, -{-0.422894f,0.121519f,0.0900281f},{-0.424327f,0.126754f,0.0918925f},{-0.426511f,0.137363f,0.0918925f}, -{-0.427261f,0.142723f,0.0918925f},{-0.426511f,0.137364f,0.0900281f},{-0.427261f,0.142723f,0.0900281f}, -{-0.427781f,0.14811f,0.0900281f},{-0.428071f,0.153516f,0.0900281f},{-0.428071f,0.153516f,0.0918925f}, -{-0.427781f,0.14811f,0.0918925f},{-0.428131f,0.158934f,0.0900281f},{-0.428131f,0.158934f,0.0918925f}, -{-0.427958f,0.164357f,0.0900281f},{-0.427958f,0.164356f,0.0918925f},{-0.389518f,0.0664729f,0.0900281f}, -{-0.393337f,0.0703321f,0.0918925f},{-0.389518f,0.0664728f,0.0918925f},{-0.385543f,0.0627861f,0.0900281f}, -{-0.385543f,0.0627861f,0.0918925f},{-0.381418f,0.0592762f,0.0900281f},{-0.37715f,0.0559475f,0.0900281f}, -{-0.381418f,0.0592761f,0.0918925f},{-0.37715f,0.0559474f,0.0918925f},{-0.372745f,0.0528044f,0.0900281f}, -{-0.372745f,0.0528044f,0.0918925f},{-0.368209f,0.0498513f,0.0900281f},{-0.363547f,0.0470924f,0.0900281f}, -{-0.368209f,0.0498511f,0.0918925f},{-0.363547f,0.0470923f,0.0918925f},{-0.358766f,0.0445321f,0.0900281f}, -{-0.358766f,0.0445321f,0.0918925f},{-0.353872f,0.042175f,0.0900281f},{-0.348877f,0.0400276f,0.0900281f}, -{-0.353871f,0.0421746f,0.0918925f},{-0.348877f,0.0400276f,0.0918925f},{-0.343803f,0.0380996f,0.0900281f}, -{-0.343803f,0.0380996f,0.0918925f},{-0.338659f,0.0363926f,0.0900281f},{-0.333452f,0.0349082f,0.0900281f}, -{-0.338659f,0.0363926f,0.0918925f},{-0.333452f,0.0349082f,0.0918925f},{-0.328189f,0.033648f,0.0900281f}, -{-0.328189f,0.0336479f,0.0918925f},{-0.322877f,0.0326134f,0.0900281f},{-0.317524f,0.031806f,0.0900281f}, -{-0.322877f,0.0326134f,0.0918925f},{-0.317524f,0.031806f,0.0918925f},{-0.312137f,0.0312275f,0.0900281f}, -{-0.312136f,0.0312274f,0.0918925f},{-0.306722f,0.0308792f,0.0900281f},{-0.301289f,0.0307628f,0.0900281f}, -{-0.306722f,0.0308792f,0.0918925f},{-0.301289f,0.0307628f,0.0918925f},{-0.270526f,-2.46733e-016f,0.0918925f}, -{-0.270526f,-1.77184e-016f,0.0900281f},{-0.270571f,0.00166887f,0.0900281f},{-0.270707f,0.0033296f,0.0900281f}, -{-0.270571f,0.00166875f,0.0918925f},{-0.270931f,0.00497861f,0.0900281f},{-0.270706f,0.00332938f,0.0918925f}, -{-0.270931f,0.00497832f,0.0918925f},{-0.271245f,0.00661229f,0.0900281f},{-0.271646f,0.00822706f,0.0900281f}, -{-0.271245f,0.00661197f,0.0918925f},{-0.272135f,0.00981931f,0.0900281f},{-0.271646f,0.00822672f,0.0918925f}, -{-0.272135f,0.009819f,0.0918925f},{-0.27271f,0.0113858f,0.0900281f},{-0.27337f,0.0129196f,0.0900281f}, -{-0.27271f,0.0113852f,0.0918925f},{-0.274111f,0.0144128f,0.0900281f},{-0.27337f,0.0129192f,0.0918925f}, -{-0.274111f,0.0144127f,0.0918925f},{-0.27493f,0.0158618f,0.0900281f},{-0.275826f,0.0172635f,0.0900281f}, -{-0.27493f,0.0158617f,0.0918925f},{-0.276797f,0.0186148f,0.0900281f},{-0.275826f,0.0172633f,0.0918925f}, -{-0.276797f,0.0186146f,0.0918925f},{-0.27784f,0.0199127f,0.0900281f},{-0.278954f,0.0211544f,0.0900281f}, -{-0.27784f,0.0199124f,0.0918925f},{-0.280135f,0.0223352f,0.0900281f},{-0.278953f,0.0211538f,0.0918925f}, -{-0.280134f,0.0223347f,0.0918925f},{-0.281376f,0.0234487f,0.0900281f},{-0.282674f,0.0244917f,0.0900281f}, -{-0.281376f,0.0234485f,0.0918925f},{-0.284025f,0.0254622f,0.0900281f},{-0.282674f,0.0244916f,0.0918925f}, -{-0.284025f,0.0254621f,0.0918925f},{-0.285427f,0.0263582f,0.0900281f},{-0.286876f,0.0271776f,0.0900281f}, -{-0.285427f,0.0263581f,0.0918925f},{-0.288369f,0.0279185f,0.0900281f},{-0.286876f,0.0271775f,0.0918925f}, -{-0.288369f,0.0279183f,0.0918925f},{-0.289903f,0.0285784f,0.0900281f},{-0.29147f,0.0291536f,0.0900281f}, -{-0.289903f,0.0285781f,0.0918925f},{-0.293062f,0.0296423f,0.0900281f},{-0.291469f,0.0291535f,0.0918925f}, -{-0.293061f,0.0296423f,0.0918925f},{-0.294677f,0.0300438f,0.0900281f},{-0.29631f,0.0303573f,0.0900281f}, -{-0.294676f,0.0300437f,0.0918925f},{-0.297959f,0.0305821f,0.0900281f},{-0.29631f,0.0303572f,0.0918925f}, -{-0.297959f,0.030582f,0.0918925f},{-0.29962f,0.0307175f,0.0900281f},{-0.29962f,0.0307174f,0.0918925f}, -{-0.270571f,-0.00166887f,0.0918925f},{-0.270571f,-0.00166875f,0.0900281f},{-0.270707f,-0.0033296f,0.0918925f}, -{-0.270931f,-0.00497861f,0.0918925f},{-0.270706f,-0.00332938f,0.0900281f},{-0.271245f,-0.00661229f,0.0918925f}, -{-0.270931f,-0.00497832f,0.0900281f},{-0.271245f,-0.00661197f,0.0900281f},{-0.271646f,-0.00822706f,0.0918925f}, -{-0.272135f,-0.00981931f,0.0918925f},{-0.271646f,-0.00822672f,0.0900281f},{-0.27271f,-0.0113858f,0.0918925f}, -{-0.272135f,-0.009819f,0.0900281f},{-0.27271f,-0.0113852f,0.0900281f},{-0.27337f,-0.0129196f,0.0918925f}, -{-0.274111f,-0.0144128f,0.0918925f},{-0.27337f,-0.0129192f,0.0900281f},{-0.27493f,-0.0158618f,0.0918925f}, -{-0.274111f,-0.0144127f,0.0900281f},{-0.27493f,-0.0158617f,0.0900281f},{-0.275826f,-0.0172635f,0.0918925f}, -{-0.276797f,-0.0186148f,0.0918925f},{-0.275826f,-0.0172633f,0.0900281f},{-0.27784f,-0.0199127f,0.0918925f}, -{-0.276797f,-0.0186146f,0.0900281f},{-0.27784f,-0.0199124f,0.0900281f},{-0.278954f,-0.0211544f,0.0918925f}, -{-0.280135f,-0.0223352f,0.0918925f},{-0.278953f,-0.0211538f,0.0900281f},{-0.281376f,-0.0234487f,0.0918925f}, -{-0.280134f,-0.0223347f,0.0900281f},{-0.281376f,-0.0234485f,0.0900281f},{-0.282674f,-0.0244917f,0.0918925f}, -{-0.284025f,-0.0254622f,0.0918925f},{-0.282674f,-0.0244916f,0.0900281f},{-0.285427f,-0.0263582f,0.0918925f}, -{-0.284025f,-0.0254621f,0.0900281f},{-0.285427f,-0.0263581f,0.0900281f},{-0.286876f,-0.0271776f,0.0918925f}, -{-0.288369f,-0.0279185f,0.0918925f},{-0.286876f,-0.0271775f,0.0900281f},{-0.289903f,-0.0285784f,0.0918925f}, -{-0.288369f,-0.0279183f,0.0900281f},{-0.289903f,-0.0285781f,0.0900281f},{-0.29147f,-0.0291536f,0.0918925f}, -{-0.293062f,-0.0296423f,0.0918925f},{-0.291469f,-0.0291535f,0.0900281f},{-0.294677f,-0.0300438f,0.0918925f}, -{-0.293061f,-0.0296423f,0.0900281f},{-0.294676f,-0.0300437f,0.0900281f},{-0.29631f,-0.0303573f,0.0918925f}, -{-0.297959f,-0.0305821f,0.0918925f},{-0.29631f,-0.0303572f,0.0900281f},{-0.29962f,-0.0307175f,0.0918925f}, -{-0.297959f,-0.030582f,0.0900281f},{-0.29962f,-0.0307174f,0.0900281f},{-0.301289f,-0.0307628f,0.0918925f}, -{-0.301289f,-0.0307628f,0.0900281f},{-0.389518f,-0.0664728f,0.0900281f},{-0.385543f,-0.0627861f,0.0900281f}, -{-0.385543f,-0.0627861f,0.0918925f},{-0.393337f,-0.0703321f,0.0900281f},{-0.393337f,-0.0703325f,0.0918925f}, -{-0.396993f,-0.074357f,0.0900281f},{-0.381418f,-0.0592762f,0.0918925f},{-0.389518f,-0.0664729f,0.0918925f}, -{-0.381418f,-0.0592761f,0.0900281f},{-0.37715f,-0.0559475f,0.0918925f},{-0.37715f,-0.0559474f,0.0900281f}, -{-0.372745f,-0.0528044f,0.0900281f},{-0.372745f,-0.0528044f,0.0918925f},{-0.368209f,-0.0498513f,0.0918925f}, -{-0.368209f,-0.0498511f,0.0900281f},{-0.363547f,-0.0470923f,0.0900281f},{-0.358766f,-0.0445321f,0.0918925f}, -{-0.363547f,-0.0470924f,0.0918925f},{-0.358766f,-0.0445321f,0.0900281f},{-0.353871f,-0.0421746f,0.0900281f}, -{-0.353872f,-0.042175f,0.0918925f},{-0.338659f,-0.0363926f,0.0918925f},{-0.343803f,-0.0380996f,0.0900281f}, -{-0.338659f,-0.0363926f,0.0900281f},{-0.348877f,-0.0400276f,0.0918925f},{-0.348877f,-0.0400276f,0.0900281f}, -{-0.343803f,-0.0380996f,0.0918925f},{-0.333452f,-0.0349082f,0.0918925f},{-0.328189f,-0.033648f,0.0918925f}, -{-0.333452f,-0.0349082f,0.0900281f},{-0.328189f,-0.0336479f,0.0900281f},{-0.322877f,-0.0326134f,0.0900281f}, -{-0.317524f,-0.031806f,0.0900281f},{-0.317524f,-0.031806f,0.0918925f},{-0.322877f,-0.0326134f,0.0918925f}, -{-0.312136f,-0.0312274f,0.0900281f},{-0.312137f,-0.0312275f,0.0918925f},{-0.306722f,-0.0308792f,0.0900281f}, -{-0.306722f,-0.0308792f,0.0918925f},{-0.400468f,-0.0785292f,0.0900281f},{-0.396993f,-0.0743574f,0.0918925f}, -{-0.400468f,-0.0785294f,0.0918925f},{-0.403757f,-0.0828395f,0.0900281f},{-0.403757f,-0.0828396f,0.0918925f}, -{-0.406855f,-0.0872815f,0.0900281f},{-0.409759f,-0.0918488f,0.0900281f},{-0.406855f,-0.0872816f,0.0918925f}, -{-0.409759f,-0.091849f,0.0918925f},{-0.412465f,-0.0965352f,0.0900281f},{-0.412465f,-0.0965352f,0.0918925f}, -{-0.41497f,-0.101334f,0.0900281f},{-0.417269f,-0.106239f,0.0900281f},{-0.41497f,-0.101334f,0.0918925f}, -{-0.417269f,-0.106239f,0.0918925f},{-0.419359f,-0.111243f,0.0900281f},{-0.419359f,-0.111243f,0.0918925f}, -{-0.421236f,-0.116341f,0.0900281f},{-0.422894f,-0.121519f,0.0900281f},{-0.421236f,-0.116342f,0.0918925f}, -{-0.422894f,-0.121519f,0.0918925f},{-0.424327f,-0.126754f,0.0900281f},{-0.424327f,-0.126754f,0.0918925f}, -{-0.425533f,-0.132038f,0.0900281f},{-0.426511f,-0.137363f,0.0900281f},{-0.425533f,-0.132038f,0.0918925f}, -{-0.426511f,-0.137364f,0.0918925f},{-0.427261f,-0.142723f,0.0900281f},{-0.427261f,-0.142723f,0.0918925f}, -{-0.427781f,-0.14811f,0.0900281f},{-0.428071f,-0.153516f,0.0900281f},{-0.427781f,-0.14811f,0.0918925f}, -{-0.428071f,-0.153516f,0.0918925f},{-0.428131f,-0.158934f,0.0900281f},{-0.428131f,-0.158934f,0.0918925f}, -{-0.427958f,-0.164356f,0.0900281f},{-0.427553f,-0.169776f,0.0900281f},{-0.427958f,-0.164357f,0.0918925f}, -{-0.427553f,-0.169776f,0.0918925f},{-0.448656f,-0.18196f,0.0918925f},{-0.448656f,-0.18196f,0.0900281f}, -{-0.5f,-0.0049028f,0.0918925f},{-0.5f,0.00490289f,0.0918925f},{-0.5f,-0.00490289f,0.0900281f}, -{-0.499724f,-0.0147057f,0.0900281f},{-0.499724f,-0.0147055f,0.0918925f},{-0.499171f,-0.0244996f,0.0900281f}, -{-0.499171f,-0.0244996f,0.0918925f},{-0.498342f,-0.0342788f,0.0918925f},{-0.498342f,-0.034279f,0.0900281f}, -{-0.497236f,-0.0440377f,0.0900281f},{-0.497236f,-0.0440376f,0.0918925f},{-0.495854f,-0.05377f,0.0900281f}, -{-0.495854f,-0.05377f,0.0918925f},{-0.494196f,-0.0634697f,0.0918925f},{-0.494196f,-0.0634706f,0.0900281f}, -{-0.492264f,-0.0731194f,0.0900281f},{-0.492264f,-0.0731193f,0.0918925f},{-0.490062f,-0.0826996f,0.0900281f}, -{-0.490062f,-0.0826996f,0.0918925f},{-0.487593f,-0.0922052f,0.0918925f},{-0.487593f,-0.0922054f,0.0900281f}, -{-0.484859f,-0.101631f,0.0900281f},{-0.484859f,-0.101631f,0.0918925f},{-0.481861f,-0.110971f,0.0900281f}, -{-0.481861f,-0.110971f,0.0918925f},{-0.478603f,-0.120221f,0.0918925f},{-0.478602f,-0.120221f,0.0900281f}, -{-0.475085f,-0.129374f,0.0900281f},{-0.475085f,-0.129374f,0.0918925f},{-0.47131f,-0.138425f,0.0900281f}, -{-0.47131f,-0.138425f,0.0918925f},{-0.46728f,-0.147368f,0.0918925f},{-0.46728f,-0.147369f,0.0900281f}, -{-0.462998f,-0.156199f,0.0900281f},{-0.462998f,-0.156199f,0.0918925f},{-0.458465f,-0.164912f,0.0900281f}, -{-0.458465f,-0.164912f,0.0918925f},{-0.453684f,-0.173501f,0.0918925f},{-0.453684f,-0.173501f,0.0900281f}, -{-0.5f,0.0049028f,0.0900281f},{-0.499724f,0.0147055f,0.0900281f},{-0.499724f,0.0147057f,0.0918925f}, -{-0.499171f,0.0244996f,0.0918925f},{-0.499171f,0.0244996f,0.0900281f},{-0.498342f,0.034279f,0.0918925f}, -{-0.498342f,0.0342788f,0.0900281f},{-0.497236f,0.0440376f,0.0900281f},{-0.497236f,0.0440377f,0.0918925f}, -{-0.495854f,0.05377f,0.0918925f},{-0.495854f,0.05377f,0.0900281f},{-0.494196f,0.0634706f,0.0918925f}, -{-0.494196f,0.0634697f,0.0900281f},{-0.492264f,0.0731193f,0.0900281f},{-0.492264f,0.0731194f,0.0918925f}, -{-0.490062f,0.0826996f,0.0918925f},{-0.490062f,0.0826996f,0.0900281f},{-0.487593f,0.0922054f,0.0918925f}, -{-0.487593f,0.0922052f,0.0900281f},{-0.484859f,0.101631f,0.0900281f},{-0.484859f,0.101631f,0.0918925f}, -{-0.481861f,0.110971f,0.0918925f},{-0.481861f,0.110971f,0.0900281f},{-0.478602f,0.120221f,0.0918925f}, -{-0.478603f,0.120221f,0.0900281f},{-0.475085f,0.129374f,0.0900281f},{-0.475085f,0.129374f,0.0918925f}, -{-0.47131f,0.138425f,0.0918925f},{-0.47131f,0.138425f,0.0900281f},{-0.46728f,0.147369f,0.0918925f}, -{-0.46728f,0.147368f,0.0900281f},{-0.462998f,0.156199f,0.0900281f},{-0.462998f,0.156199f,0.0918925f}, -{-0.458465f,0.164912f,0.0918925f},{-0.458465f,0.164912f,0.0900281f},{-0.453684f,0.173501f,0.0918925f}, -{-0.453684f,0.173501f,0.0900281f},{-0.295886f,-0.0200317f,0.0918925f},{-0.280259f,-0.0036392f,0.0918925f}, -{-0.280781f,-0.00474168f,0.0918925f},{-0.28931f,-0.0152687f,0.0918925f},{-0.29453f,-0.0183517f,0.0918925f}, -{-0.28153f,-0.0057053f,0.0918925f},{-0.291507f,-0.0130697f,0.0918925f},{-0.289835f,-0.0151095f,0.0918925f}, -{-0.294119f,-0.0173478f,0.0918925f},{-0.291087f,-0.0109706f,0.0918925f},{-0.290739f,-0.0105473f,0.0918925f}, -{-0.295126f,-0.0192577f,0.0918925f},{-0.296782f,-0.0206442f,0.0918925f},{-0.297778f,-0.0210723f,0.0918925f}, -{-0.290316f,-0.0101998f,0.0918925f},{-0.291091f,-0.0140791f,0.0918925f},{-0.293911f,-0.0151984f,0.0918925f}, -{-0.290742f,-0.0145033f,0.0918925f},{-0.315791f,0.0105451f,0.0918925f},{-0.315367f,0.0101973f,0.0918925f}, -{-0.316139f,0.0109693f,0.0918925f},{-0.314358f,0.00977971f,0.0918925f},{-0.314883f,0.00993885f,0.0918925f}, -{-0.314881f,0.0151067f,0.0918925f},{-0.316555f,0.0119787f,0.0918925f},{-0.316397f,0.0114536f,0.0918925f}, -{-0.316609f,0.0125242f,0.0918925f},{-0.316394f,0.013595f,0.0918925f},{-0.316135f,0.0140778f,0.0918925f}, -{-0.315788f,0.0145011f,0.0918925f},{-0.315364f,0.0148486f,0.0918925f},{-0.314357f,0.015266f,0.0918925f}, -{-0.290318f,-0.0148511f,0.0918925f},{-0.29391f,-0.0162833f,0.0918925f},{-0.291506f,-0.0119779f,0.0918925f}, -{-0.291561f,-0.0125242f,0.0918925f},{-0.291346f,-0.0114534f,0.0918925f},{-0.291349f,-0.0135948f,0.0918925f}, -{-0.289833f,-0.00994166f,0.0918925f},{-0.316555f,0.0130705f,0.0918925f},{-0.289309f,-0.00978241f,0.0918925f}, -{-0.280782f,-0.00474296f,0.0900281f},{-0.297777f,-0.0210725f,0.0900281f},{-0.296781f,-0.020644f,0.0900281f}, -{-0.290742f,-0.0105451f,0.0900281f},{-0.280259f,-0.00364027f,0.0900281f},{-0.289835f,-0.00993885f,0.0900281f}, -{-0.295886f,-0.0200312f,0.0900281f},{-0.295126f,-0.0192574f,0.0900281f},{-0.29391f,-0.0162822f,0.0900281f}, -{-0.290739f,-0.0145011f,0.0900281f},{-0.290316f,-0.0148486f,0.0900281f},{-0.291561f,-0.0125242f,0.0900281f}, -{-0.28931f,-0.00977971f,0.0900281f},{-0.291091f,-0.0109693f,0.0900281f},{-0.290318f,-0.0101973f,0.0900281f}, -{-0.291349f,-0.0114536f,0.0900281f},{-0.315791f,0.0145033f,0.0900281f},{-0.316139f,0.0140791f,0.0900281f}, -{-0.314357f,0.00978241f,0.0900281f},{-0.314881f,0.00994166f,0.0900281f},{-0.294529f,-0.0183513f,0.0900281f}, -{-0.294119f,-0.0173468f,0.0900281f},{-0.289833f,-0.0151067f,0.0900281f},{-0.289309f,-0.015266f,0.0900281f}, -{-0.291087f,-0.0140778f,0.0900281f},{-0.293911f,-0.0151976f,0.0900281f},{-0.291346f,-0.013595f,0.0900281f}, -{-0.28153f,-0.00570553f,0.0900281f},{-0.316555f,0.0119779f,0.0900281f},{-0.315364f,0.0101998f,0.0900281f}, -{-0.316609f,0.0125242f,0.0900281f},{-0.316555f,0.0130697f,0.0900281f},{-0.316397f,0.0135948f,0.0900281f}, -{-0.315367f,0.0148511f,0.0900281f},{-0.314883f,0.0151095f,0.0900281f},{-0.316135f,0.0109706f,0.0900281f}, -{-0.314358f,0.0152687f,0.0900281f},{-0.316394f,0.0114534f,0.0900281f},{-0.315788f,0.0105473f,0.0900281f}, -{-0.291507f,-0.0119787f,0.0900281f},{-0.291506f,-0.0130705f,0.0900281f},{0.285968f,0.0125242f,0.0900281f}, -{0.286022f,0.0130723f,0.0918925f},{0.285968f,0.0125242f,0.0918925f},{0.286181f,0.011454f,0.0918925f}, -{0.286181f,0.011454f,0.0900281f},{0.286022f,0.0119761f,0.0918925f},{0.286022f,0.0119761f,0.0900281f}, -{0.286438f,0.0109726f,0.0900281f},{0.286787f,0.0105467f,0.0900281f},{0.286787f,0.0105467f,0.0918925f}, -{0.287213f,0.0101975f,0.0900281f},{0.287213f,0.0101975f,0.0918925f},{0.286438f,0.0109726f,0.0918925f}, -{0.288764f,0.00972758f,0.0900281f},{0.288216f,0.00978182f,0.0900281f},{0.288216f,0.00978182f,0.0918925f}, -{0.287694f,0.00994047f,0.0918925f},{0.287694f,0.00994047f,0.0900281f},{0.288764f,0.00972758f,0.0918925f}, -{0.286022f,0.0130723f,0.0900281f},{0.286181f,0.0135944f,0.0918925f},{0.286181f,0.0135944f,0.0900281f}, -{0.286438f,0.0140758f,0.0900281f},{0.286438f,0.0140758f,0.0918925f},{0.286787f,0.0145017f,0.0900281f}, -{0.286787f,0.0145017f,0.0918925f},{0.287213f,0.0148509f,0.0918925f},{0.287213f,0.0148509f,0.0900281f}, -{0.287694f,0.0151079f,0.0900281f},{0.287694f,0.0151079f,0.0918925f},{0.288216f,0.0152666f,0.0900281f}, -{0.288216f,0.0152666f,0.0918925f},{0.288764f,0.0153208f,0.0918925f},{0.288764f,0.0153208f,0.0900281f}, -{0.311016f,-0.0125242f,0.0900281f},{0.31107f,-0.0119761f,0.0918925f},{0.311016f,-0.0125242f,0.0918925f}, -{0.311229f,-0.0135944f,0.0918925f},{0.311229f,-0.0135944f,0.0900281f},{0.31107f,-0.0130723f,0.0918925f}, -{0.31107f,-0.0130723f,0.0900281f},{0.311486f,-0.0140758f,0.0900281f},{0.311835f,-0.0145017f,0.0900281f}, -{0.311835f,-0.0145017f,0.0918925f},{0.312261f,-0.0148509f,0.0900281f},{0.312261f,-0.0148509f,0.0918925f}, -{0.311486f,-0.0140758f,0.0918925f},{0.313813f,-0.0153208f,0.0900281f},{0.313265f,-0.0152666f,0.0900281f}, -{0.313265f,-0.0152666f,0.0918925f},{0.312743f,-0.0151079f,0.0918925f},{0.312743f,-0.0151079f,0.0900281f}, -{0.313813f,-0.0153208f,0.0918925f},{0.31107f,-0.0119761f,0.0900281f},{0.311229f,-0.011454f,0.0918925f}, -{0.311229f,-0.011454f,0.0900281f},{0.311486f,-0.0109726f,0.0900281f},{0.311486f,-0.0109726f,0.0918925f}, -{0.311835f,-0.0105467f,0.0900281f},{0.311835f,-0.0105467f,0.0918925f},{0.312261f,-0.0101975f,0.0918925f}, -{0.312261f,-0.0101975f,0.0900281f},{0.312743f,-0.00994047f,0.0900281f},{0.312743f,-0.00994047f,0.0918925f}, -{0.313265f,-0.00978182f,0.0900281f},{0.313265f,-0.00978182f,0.0918925f},{0.313813f,-0.00972758f,0.0918925f}, -{0.313813f,-0.00972758f,0.0900281f},{0.284736f,0.0073455f,0.0900281f},{0.285954f,0.00738926f,0.0918925f}, -{0.284736f,0.00734538f,0.0918925f},{0.283556f,0.00703877f,0.0900281f},{0.283555f,0.0070384f,0.0918925f}, -{0.28247f,0.00648281f,0.0900281f},{0.28247f,0.00648282f,0.0918925f},{0.285956f,0.00738915f,0.0900281f}, -{0.287154f,0.00716427f,0.0918925f},{0.287154f,0.00716427f,0.0900281f},{0.309858f,-0.00856857f,0.0918925f}, -{0.310706f,-0.0078732f,0.0918925f},{0.309857f,-0.00856991f,0.0900281f},{0.310705f,-0.00787361f,0.0900281f}, -{0.311673f,-0.0073566f,0.0918925f},{0.312722f,-0.00703838f,0.0918925f},{0.311672f,-0.00735691f,0.0900281f}, -{0.313813f,-0.00693097f,0.0918925f},{0.312721f,-0.00703853f,0.0900281f},{0.313813f,-0.00693097f,0.0900281f}, -{0.309162f,-0.00941743f,0.0900281f},{0.308645f,-0.0103841f,0.0900281f},{0.309162f,-0.00941663f,0.0918925f}, -{0.308327f,-0.0114331f,0.0900281f},{0.308645f,-0.0103834f,0.0918925f},{0.308327f,-0.0114326f,0.0918925f}, -{0.30822f,-0.0125242f,0.0900281f},{0.30822f,-0.0125242f,0.0918925f},{0.401959f,0.065917f,0.0918925f}, -{0.398048f,0.0617984f,0.0918925f},{0.40196f,0.0659174f,0.0900281f},{0.405692f,0.07019f,0.0900281f}, -{0.405691f,0.0701898f,0.0918925f},{0.409237f,0.0746077f,0.0900281f},{0.409237f,0.0746076f,0.0918925f}, -{0.412592f,0.0791643f,0.0918925f},{0.412592f,0.0791644f,0.0900281f},{0.415754f,0.0838538f,0.0900281f}, -{0.415754f,0.0838537f,0.0918925f},{0.418717f,0.0886696f,0.0900281f},{0.418717f,0.0886696f,0.0918925f}, -{0.421479f,0.0936056f,0.0918925f},{0.421479f,0.0936057f,0.0900281f},{0.424035f,0.0986557f,0.0900281f}, -{0.424035f,0.0986556f,0.0918925f},{0.426382f,0.103813f,0.0900281f},{0.426382f,0.103813f,0.0918925f}, -{0.428515f,0.109072f,0.0918925f},{0.428515f,0.109073f,0.0900281f},{0.430428f,0.11442f,0.0900281f}, -{0.430428f,0.11442f,0.0918925f},{0.432114f,0.119834f,0.0900281f},{0.432114f,0.119834f,0.0918925f}, -{0.433572f,0.125306f,0.0918925f},{0.433572f,0.125307f,0.0900281f},{0.4348f,0.130829f,0.0900281f}, -{0.4348f,0.130829f,0.0918925f},{0.435797f,0.136396f,0.0900281f},{0.435797f,0.136396f,0.0918925f}, -{0.436561f,0.141999f,0.0918925f},{0.436561f,0.141999f,0.0900281f},{0.437093f,0.147631f,0.0900281f}, -{0.437093f,0.147631f,0.0918925f},{0.437391f,0.153284f,0.0900281f},{0.437391f,0.153284f,0.0918925f}, -{0.437453f,0.158952f,0.0918925f},{0.437453f,0.158952f,0.0900281f},{0.437279f,0.164627f,0.0900281f}, -{0.437279f,0.164627f,0.0918925f},{0.398048f,0.0617987f,0.0900281f},{0.393973f,0.0578515f,0.0900281f}, -{0.393973f,0.0578514f,0.0918925f},{0.389744f,0.054083f,0.0918925f},{0.389744f,0.0540831f,0.0900281f}, -{0.385366f,0.0504973f,0.0918925f},{0.385366f,0.0504974f,0.0900281f},{0.380846f,0.0470986f,0.0900281f}, -{0.380846f,0.0470985f,0.0918925f},{0.376189f,0.0438908f,0.0918925f},{0.376189f,0.0438908f,0.0900281f}, -{0.371402f,0.0408784f,0.0918925f},{0.371402f,0.0408785f,0.0900281f},{0.36649f,0.0380656f,0.0900281f}, -{0.36649f,0.0380655f,0.0918925f},{0.36146f,0.0354565f,0.0918925f},{0.36146f,0.0354565f,0.0900281f}, -{0.356317f,0.0330551f,0.0918925f},{0.356318f,0.0330554f,0.0900281f},{0.351076f,0.0308688f,0.0900281f}, -{0.351076f,0.0308688f,0.0918925f},{0.345756f,0.0289059f,0.0918925f},{0.345756f,0.0289059f,0.0900281f}, -{0.340366f,0.0271683f,0.0918925f},{0.340366f,0.0271684f,0.0900281f},{0.334914f,0.0256577f,0.0900281f}, -{0.334914f,0.0256577f,0.0918925f},{0.329406f,0.0243753f,0.0918925f},{0.329406f,0.0243754f,0.0900281f}, -{0.32385f,0.0233228f,0.0918925f},{0.32385f,0.0233228f,0.0900281f},{0.318253f,0.0225016f,0.0900281f}, -{0.318253f,0.0225016f,0.0918925f},{0.312622f,0.0219132f,0.0918925f},{0.312623f,0.0219132f,0.0900281f}, -{0.306965f,0.0215591f,0.0918925f},{0.306965f,0.0215591f,0.0900281f},{0.301289f,0.0214407f,0.0918925f}, -{0.301289f,0.0214407f,0.0900281f},{0.300061f,0.0214056f,0.0918925f},{0.300061f,0.0214056f,0.0900281f}, -{0.298838f,0.0213002f,0.0900281f},{0.298838f,0.0213002f,0.0918925f},{0.29272f,0.00857005f,0.0900281f}, -{0.293362f,0.00933952f,0.0900281f},{0.292718f,0.00856812f,0.0918925f},{0.293856f,0.0102104f,0.0918925f}, -{0.293362f,0.00933867f,0.0918925f},{0.293857f,0.010212f,0.0900281f},{0.294188f,0.0111572f,0.0918925f}, -{0.294188f,0.0111588f,0.0900281f},{0.294345f,0.0121484f,0.0918925f},{0.294322f,0.0131504f,0.0918925f}, -{0.294345f,0.0121494f,0.0900281f},{0.294121f,0.0141339f,0.0900281f},{0.294322f,0.0131516f,0.0900281f}, -{0.294121f,0.0141339f,0.0918925f},{0.291949f,0.00792586f,0.0918925f},{0.29195f,0.00792654f,0.0900281f}, -{0.291078f,0.00743177f,0.0900281f},{0.290131f,0.00710074f,0.0900281f},{0.291076f,0.00743116f,0.0918925f}, -{0.290129f,0.00710007f,0.0918925f},{0.28914f,0.00694354f,0.0900281f},{0.289139f,0.00694356f,0.0918925f}, -{0.288138f,0.00696625f,0.0900281f},{0.288136f,0.00696632f,0.0918925f},{0.283634f,-0.0121669f,0.0900281f}, -{0.282482f,-0.0102959f,0.0900281f},{0.282482f,-0.0102961f,0.0918925f},{0.283634f,-0.012167f,0.0918925f}, -{0.284976f,-0.013914f,0.0900281f},{0.281528f,-0.008319f,0.0918925f},{0.281527f,-0.00831882f,0.0900281f}, -{0.280779f,-0.00625128f,0.0918925f},{0.280779f,-0.00625078f,0.0900281f},{0.280246f,-0.00411456f,0.0918925f}, -{0.280246f,-0.00411435f,0.0900281f},{0.279936f,-0.00194003f,0.0900281f},{0.279936f,-0.0019402f,0.0918925f}, -{0.279849f,0.000253827f,0.0918925f},{0.279988f,0.00245022f,0.0918925f},{0.279849f,0.00025393f,0.0900281f}, -{0.279988f,0.00245022f,0.0900281f},{0.286486f,-0.0155106f,0.0900281f},{0.284976f,-0.0139141f,0.0918925f}, -{0.286486f,-0.0155107f,0.0918925f},{0.288149f,-0.016943f,0.0900281f},{0.28815f,-0.0169431f,0.0918925f}, -{0.289954f,-0.0181996f,0.0900281f},{0.29188f,-0.0192663f,0.0900281f},{0.289954f,-0.0181999f,0.0918925f}, -{0.291881f,-0.0192664f,0.0918925f},{0.293901f,-0.0201277f,0.0900281f},{0.293901f,-0.0201278f,0.0918925f}, -{0.295998f,-0.0207778f,0.0900281f},{0.298156f,-0.0212106f,0.0900281f},{0.295998f,-0.0207778f,0.0918925f}, -{0.298156f,-0.0212106f,0.0918925f},{0.303955f,-0.0200545f,0.0900281f},{0.302604f,-0.0207145f,0.0918925f}, -{0.303956f,-0.020054f,0.0918925f},{0.305176f,-0.0191712f,0.0900281f},{0.302603f,-0.0207149f,0.0900281f}, -{0.301156f,-0.0211353f,0.0918925f},{0.305176f,-0.0191712f,0.0918925f},{0.301155f,-0.0211356f,0.0900281f}, -{0.29966f,-0.021302f,0.0918925f},{0.299659f,-0.0213021f,0.0900281f},{0.306228f,-0.0180928f,0.0900281f}, -{0.306229f,-0.018092f,0.0918925f},{0.307079f,-0.0168512f,0.0918925f},{0.307079f,-0.0168521f,0.0900281f}, -{0.307707f,-0.0154797f,0.0918925f},{0.307707f,-0.0154807f,0.0900281f},{0.30809f,-0.0140259f,0.0900281f}, -{0.30809f,-0.014025f,0.0918925f},{0.314904f,-0.00703853f,0.0918925f},{0.317768f,-0.00856991f,0.0918925f}, -{0.31692f,-0.0078732f,0.0900281f},{0.31692f,-0.00787361f,0.0918925f},{0.315954f,-0.00735691f,0.0918925f}, -{0.315953f,-0.0073566f,0.0900281f},{0.314904f,-0.00703838f,0.0900281f},{0.31898f,-0.0103834f,0.0900281f}, -{0.31898f,-0.0103841f,0.0918925f},{0.319299f,-0.0114331f,0.0918925f},{0.317767f,-0.00856857f,0.0900281f}, -{0.318464f,-0.00941743f,0.0918925f},{0.318463f,-0.00941663f,0.0900281f},{0.319406f,-0.0125242f,0.0918925f}, -{0.319298f,-0.0114326f,0.0900281f},{0.319406f,-0.0125242f,0.0900281f},{0.32063f,-0.017806f,0.0900281f}, -{0.32063f,-0.0178073f,0.0918925f},{0.321554f,-0.0193785f,0.0900281f},{0.321554f,-0.0193787f,0.0918925f}, -{0.319955f,-0.0161135f,0.0918925f},{0.319955f,-0.0161128f,0.0900281f},{0.319544f,-0.0143418f,0.0900281f}, -{0.319544f,-0.0143423f,0.0918925f},{0.322701f,-0.0207886f,0.0900281f},{0.324052f,-0.0220123f,0.0900281f}, -{0.322701f,-0.0207888f,0.0918925f},{0.324053f,-0.0220132f,0.0918925f},{0.325573f,-0.023018f,0.0900281f}, -{0.325573f,-0.0230183f,0.0918925f},{0.327224f,-0.02378f,0.0900281f},{0.328976f,-0.0242851f,0.0900281f}, -{0.327224f,-0.0237802f,0.0918925f},{0.328976f,-0.0242851f,0.0918925f},{0.409092f,-0.0744192f,0.0918925f}, -{0.409092f,-0.0744192f,0.0900281f},{0.405539f,-0.0700077f,0.0900281f},{0.401803f,-0.065746f,0.0900281f}, -{0.405539f,-0.0700077f,0.0918925f},{0.397891f,-0.06164f,0.0900281f},{0.401803f,-0.0657461f,0.0918925f}, -{0.397891f,-0.0616401f,0.0918925f},{0.393805f,-0.0576956f,0.0900281f},{0.389551f,-0.0539185f,0.0900281f}, -{0.393805f,-0.0576957f,0.0918925f},{0.385134f,-0.0503158f,0.0900281f},{0.389551f,-0.0539186f,0.0918925f}, -{0.385135f,-0.050316f,0.0918925f},{0.380577f,-0.0469052f,0.0900281f},{0.375889f,-0.0436939f,0.0900281f}, -{0.380577f,-0.0469052f,0.0918925f},{0.371079f,-0.0406851f,0.0900281f},{0.375889f,-0.0436939f,0.0918925f}, -{0.371079f,-0.0406851f,0.0918925f},{0.366152f,-0.0378819f,0.0900281f},{0.361116f,-0.0352877f,0.0900281f}, -{0.366152f,-0.037882f,0.0918925f},{0.355977f,-0.0329054f,0.0900281f},{0.361116f,-0.0352877f,0.0918925f}, -{0.355977f,-0.0329055f,0.0918925f},{0.350742f,-0.0307383f,0.0900281f},{0.345418f,-0.0287896f,0.0900281f}, -{0.350742f,-0.0307384f,0.0918925f},{0.340011f,-0.0270624f,0.0900281f},{0.345418f,-0.0287897f,0.0918925f}, -{0.340011f,-0.0270624f,0.0918925f},{0.334528f,-0.0255598f,0.0900281f},{0.334528f,-0.0255599f,0.0918925f}, -{0.412458f,-0.0789746f,0.0918925f},{0.412458f,-0.0789746f,0.0900281f},{0.415634f,-0.0836681f,0.0918925f}, -{0.418614f,-0.0884938f,0.0918925f},{0.415634f,-0.083668f,0.0900281f},{0.421394f,-0.0934459f,0.0918925f}, -{0.418614f,-0.0884937f,0.0900281f},{0.421394f,-0.0934458f,0.0900281f},{0.423969f,-0.0985185f,0.0918925f}, -{0.426335f,-0.103704f,0.0918925f},{0.423969f,-0.0985183f,0.0900281f},{0.428478f,-0.108978f,0.0918925f}, -{0.426334f,-0.103704f,0.0900281f},{0.428478f,-0.108977f,0.0900281f},{0.430397f,-0.114326f,0.0918925f}, -{0.432088f,-0.119742f,0.0918925f},{0.430397f,-0.114326f,0.0900281f},{0.43355f,-0.125218f,0.0918925f}, -{0.432088f,-0.119742f,0.0900281f},{0.43355f,-0.125218f,0.0900281f},{0.434783f,-0.130747f,0.0918925f}, -{0.435785f,-0.136322f,0.0918925f},{0.434783f,-0.130747f,0.0900281f},{0.436554f,-0.141936f,0.0918925f}, -{0.435785f,-0.136322f,0.0900281f},{0.436554f,-0.141935f,0.0900281f},{0.43709f,-0.14758f,0.0918925f}, -{0.43739f,-0.153248f,0.0918925f},{0.43709f,-0.14758f,0.0900281f},{0.437453f,-0.158933f,0.0918925f}, -{0.43739f,-0.153248f,0.0900281f},{0.437453f,-0.158933f,0.0900281f},{0.437279f,-0.164627f,0.0918925f}, -{0.437279f,-0.164627f,0.0900281f},{0.445352f,-0.169288f,0.0900281f},{0.445352f,-0.169288f,0.0918925f}, -{0.489867f,-0.0239114f,0.0918925f},{0.490408f,-0.0143525f,0.0918925f},{0.490408f,-0.0143527f,0.0900281f}, -{0.490679f,0.00478512f,0.0900281f},{0.490679f,-0.00478519f,0.0900281f},{0.490679f,-0.00478512f,0.0918925f}, -{0.489867f,-0.0239115f,0.0900281f},{0.489056f,-0.0334558f,0.0918925f},{0.489056f,-0.0334558f,0.0900281f}, -{0.487973f,-0.0429801f,0.0900281f},{0.487973f,-0.04298f,0.0918925f},{0.486621f,-0.0524782f,0.0918925f}, -{0.486621f,-0.0524784f,0.0900281f},{0.484998f,-0.0619436f,0.0900281f},{0.484998f,-0.0619434f,0.0918925f}, -{0.480955f,-0.0806965f,0.0900281f},{0.47854f,-0.089968f,0.0900281f},{0.47854f,-0.0899679f,0.0918925f}, -{0.483109f,-0.0713532f,0.0918925f},{0.483109f,-0.0713532f,0.0900281f},{0.480955f,-0.0806964f,0.0918925f}, -{0.475866f,-0.0991622f,0.0918925f},{0.475866f,-0.0991623f,0.0900281f},{0.472933f,-0.108274f,0.0900281f}, -{0.472933f,-0.108274f,0.0918925f},{0.469745f,-0.117298f,0.0918925f},{0.469745f,-0.117298f,0.0900281f}, -{0.466302f,-0.126228f,0.0918925f},{0.458664f,-0.143787f,0.0900281f},{0.458664f,-0.143786f,0.0918925f}, -{0.462608f,-0.135059f,0.0900281f},{0.462608f,-0.135059f,0.0918925f},{0.466302f,-0.126228f,0.0900281f}, -{0.454472f,-0.152404f,0.0900281f},{0.454472f,-0.152404f,0.0918925f},{0.450034f,-0.160907f,0.0900281f}, -{0.450034f,-0.160906f,0.0918925f},{0.490679f,0.00478519f,0.0918925f},{0.490408f,0.0143525f,0.0900281f}, -{0.490408f,0.0143527f,0.0918925f},{0.489867f,0.0239114f,0.0900281f},{0.489056f,0.0334558f,0.0900281f}, -{0.489867f,0.0239115f,0.0918925f},{0.489056f,0.0334558f,0.0918925f},{0.487973f,0.04298f,0.0900281f}, -{0.487973f,0.0429801f,0.0918925f},{0.486621f,0.0524782f,0.0900281f},{0.484998f,0.0619434f,0.0900281f}, -{0.486621f,0.0524784f,0.0918925f},{0.484998f,0.0619436f,0.0918925f},{0.483109f,0.0713532f,0.0900281f}, -{0.483109f,0.0713532f,0.0918925f},{0.480955f,0.0806964f,0.0900281f},{0.47854f,0.0899679f,0.0900281f}, -{0.480955f,0.0806965f,0.0918925f},{0.47854f,0.089968f,0.0918925f},{0.475866f,0.0991622f,0.0900281f}, -{0.475866f,0.0991623f,0.0918925f},{0.472933f,0.108274f,0.0900281f},{0.469745f,0.117298f,0.0900281f}, -{0.472933f,0.108274f,0.0918925f},{0.469745f,0.117298f,0.0918925f},{0.466302f,0.126228f,0.0900281f}, -{0.466302f,0.126228f,0.0918925f},{0.462608f,0.135059f,0.0900281f},{0.458664f,0.143786f,0.0900281f}, -{0.462608f,0.135059f,0.0918925f},{0.458664f,0.143787f,0.0918925f},{0.454472f,0.152404f,0.0900281f}, -{0.454472f,0.152404f,0.0918925f},{0.450034f,0.160906f,0.0900281f},{0.445352f,0.169288f,0.0900281f}, -{0.450034f,0.160907f,0.0918925f},{0.445352f,0.169288f,0.0918925f},{0.427553f,-0.169776f,0.0918925f}, -{0.448656f,-0.18196f,0.0900281f},{0.448656f,-0.18196f,0.0918925f},{0.427553f,-0.169776f,0.0900281f}, -{0.400468f,-0.0785294f,0.0900281f},{0.403757f,-0.0828396f,0.0900281f},{0.403757f,-0.0828395f,0.0918925f}, -{0.396993f,-0.0743574f,0.0900281f},{0.396993f,-0.074357f,0.0918925f},{0.393337f,-0.0703325f,0.0900281f}, -{0.406855f,-0.0872815f,0.0918925f},{0.400468f,-0.0785292f,0.0918925f},{0.406855f,-0.0872816f,0.0900281f}, -{0.409759f,-0.0918488f,0.0918925f},{0.409759f,-0.091849f,0.0900281f},{0.412465f,-0.0965352f,0.0900281f}, -{0.412465f,-0.0965352f,0.0918925f},{0.41497f,-0.101334f,0.0918925f},{0.41497f,-0.101334f,0.0900281f}, -{0.417269f,-0.106239f,0.0900281f},{0.419359f,-0.111243f,0.0918925f},{0.417269f,-0.106239f,0.0918925f}, -{0.419359f,-0.111243f,0.0900281f},{0.421236f,-0.116342f,0.0900281f},{0.421236f,-0.116341f,0.0918925f}, -{0.425533f,-0.132038f,0.0918925f},{0.424327f,-0.126754f,0.0900281f},{0.425533f,-0.132038f,0.0900281f}, -{0.422894f,-0.121519f,0.0918925f},{0.422894f,-0.121519f,0.0900281f},{0.424327f,-0.126754f,0.0918925f}, -{0.426511f,-0.137363f,0.0918925f},{0.427261f,-0.142723f,0.0918925f},{0.426511f,-0.137364f,0.0900281f}, -{0.427261f,-0.142723f,0.0900281f},{0.427781f,-0.14811f,0.0900281f},{0.428071f,-0.153516f,0.0900281f}, -{0.428071f,-0.153516f,0.0918925f},{0.427781f,-0.14811f,0.0918925f},{0.428131f,-0.158934f,0.0900281f}, -{0.428131f,-0.158934f,0.0918925f},{0.427958f,-0.164357f,0.0900281f},{0.427958f,-0.164356f,0.0918925f}, -{0.389518f,-0.0664729f,0.0900281f},{0.393337f,-0.0703321f,0.0918925f},{0.389518f,-0.0664728f,0.0918925f}, -{0.385543f,-0.0627861f,0.0900281f},{0.385543f,-0.0627861f,0.0918925f},{0.381418f,-0.0592762f,0.0900281f}, -{0.37715f,-0.0559475f,0.0900281f},{0.381418f,-0.0592761f,0.0918925f},{0.37715f,-0.0559474f,0.0918925f}, -{0.372745f,-0.0528044f,0.0900281f},{0.372745f,-0.0528044f,0.0918925f},{0.368209f,-0.0498513f,0.0900281f}, -{0.363547f,-0.0470924f,0.0900281f},{0.368209f,-0.0498511f,0.0918925f},{0.363547f,-0.0470923f,0.0918925f}, -{0.358766f,-0.0445321f,0.0900281f},{0.358766f,-0.0445321f,0.0918925f},{0.353872f,-0.042175f,0.0900281f}, -{0.348877f,-0.0400276f,0.0900281f},{0.353871f,-0.0421746f,0.0918925f},{0.348877f,-0.0400276f,0.0918925f}, -{0.343803f,-0.0380996f,0.0900281f},{0.343803f,-0.0380996f,0.0918925f},{0.338659f,-0.0363926f,0.0900281f}, -{0.333452f,-0.0349082f,0.0900281f},{0.338659f,-0.0363926f,0.0918925f},{0.333452f,-0.0349082f,0.0918925f}, -{0.328189f,-0.033648f,0.0900281f},{0.328189f,-0.0336479f,0.0918925f},{0.322877f,-0.0326134f,0.0900281f}, -{0.317524f,-0.031806f,0.0900281f},{0.322877f,-0.0326134f,0.0918925f},{0.317524f,-0.031806f,0.0918925f}, -{0.312137f,-0.0312275f,0.0900281f},{0.312136f,-0.0312274f,0.0918925f},{0.306722f,-0.0308792f,0.0900281f}, -{0.301289f,-0.0307628f,0.0900281f},{0.306722f,-0.0308792f,0.0918925f},{0.301289f,-0.0307628f,0.0918925f}, -{0.270526f,-1.77184e-016f,0.0918925f},{0.270526f,-2.46733e-016f,0.0900281f},{0.270571f,-0.00166887f,0.0900281f}, -{0.270707f,-0.0033296f,0.0900281f},{0.270571f,-0.00166875f,0.0918925f},{0.270931f,-0.00497861f,0.0900281f}, -{0.270706f,-0.00332938f,0.0918925f},{0.270931f,-0.00497832f,0.0918925f},{0.271245f,-0.00661229f,0.0900281f}, -{0.271646f,-0.00822706f,0.0900281f},{0.271245f,-0.00661197f,0.0918925f},{0.272135f,-0.00981931f,0.0900281f}, -{0.271646f,-0.00822672f,0.0918925f},{0.272135f,-0.009819f,0.0918925f},{0.27271f,-0.0113858f,0.0900281f}, -{0.27337f,-0.0129196f,0.0900281f},{0.27271f,-0.0113852f,0.0918925f},{0.274111f,-0.0144128f,0.0900281f}, -{0.27337f,-0.0129192f,0.0918925f},{0.274111f,-0.0144127f,0.0918925f},{0.27493f,-0.0158618f,0.0900281f}, -{0.275826f,-0.0172635f,0.0900281f},{0.27493f,-0.0158617f,0.0918925f},{0.276797f,-0.0186148f,0.0900281f}, -{0.275826f,-0.0172633f,0.0918925f},{0.276797f,-0.0186146f,0.0918925f},{0.27784f,-0.0199127f,0.0900281f}, -{0.278954f,-0.0211544f,0.0900281f},{0.27784f,-0.0199124f,0.0918925f},{0.280135f,-0.0223352f,0.0900281f}, -{0.278953f,-0.0211538f,0.0918925f},{0.280134f,-0.0223347f,0.0918925f},{0.281376f,-0.0234487f,0.0900281f}, -{0.282674f,-0.0244917f,0.0900281f},{0.281376f,-0.0234485f,0.0918925f},{0.284025f,-0.0254622f,0.0900281f}, -{0.282674f,-0.0244916f,0.0918925f},{0.284025f,-0.0254621f,0.0918925f},{0.285427f,-0.0263582f,0.0900281f}, -{0.286876f,-0.0271776f,0.0900281f},{0.285427f,-0.0263581f,0.0918925f},{0.288369f,-0.0279185f,0.0900281f}, -{0.286876f,-0.0271775f,0.0918925f},{0.288369f,-0.0279183f,0.0918925f},{0.289903f,-0.0285784f,0.0900281f}, -{0.29147f,-0.0291536f,0.0900281f},{0.289903f,-0.0285781f,0.0918925f},{0.293062f,-0.0296423f,0.0900281f}, -{0.291469f,-0.0291535f,0.0918925f},{0.293061f,-0.0296423f,0.0918925f},{0.294677f,-0.0300438f,0.0900281f}, -{0.29631f,-0.0303573f,0.0900281f},{0.294676f,-0.0300437f,0.0918925f},{0.297959f,-0.0305821f,0.0900281f}, -{0.29631f,-0.0303572f,0.0918925f},{0.297959f,-0.030582f,0.0918925f},{0.29962f,-0.0307175f,0.0900281f}, -{0.29962f,-0.0307174f,0.0918925f},{0.270571f,0.00166887f,0.0918925f},{0.270571f,0.00166875f,0.0900281f}, -{0.270707f,0.0033296f,0.0918925f},{0.270931f,0.00497861f,0.0918925f},{0.270706f,0.00332938f,0.0900281f}, -{0.271245f,0.00661229f,0.0918925f},{0.270931f,0.00497832f,0.0900281f},{0.271245f,0.00661197f,0.0900281f}, -{0.271646f,0.00822706f,0.0918925f},{0.272135f,0.00981931f,0.0918925f},{0.271646f,0.00822672f,0.0900281f}, -{0.27271f,0.0113858f,0.0918925f},{0.272135f,0.009819f,0.0900281f},{0.27271f,0.0113852f,0.0900281f}, -{0.27337f,0.0129196f,0.0918925f},{0.274111f,0.0144128f,0.0918925f},{0.27337f,0.0129192f,0.0900281f}, -{0.27493f,0.0158618f,0.0918925f},{0.274111f,0.0144127f,0.0900281f},{0.27493f,0.0158617f,0.0900281f}, -{0.275826f,0.0172635f,0.0918925f},{0.276797f,0.0186148f,0.0918925f},{0.275826f,0.0172633f,0.0900281f}, -{0.27784f,0.0199127f,0.0918925f},{0.276797f,0.0186146f,0.0900281f},{0.27784f,0.0199124f,0.0900281f}, -{0.278954f,0.0211544f,0.0918925f},{0.280135f,0.0223352f,0.0918925f},{0.278953f,0.0211538f,0.0900281f}, -{0.281376f,0.0234487f,0.0918925f},{0.280134f,0.0223347f,0.0900281f},{0.281376f,0.0234485f,0.0900281f}, -{0.282674f,0.0244917f,0.0918925f},{0.284025f,0.0254622f,0.0918925f},{0.282674f,0.0244916f,0.0900281f}, -{0.285427f,0.0263582f,0.0918925f},{0.284025f,0.0254621f,0.0900281f},{0.285427f,0.0263581f,0.0900281f}, -{0.286876f,0.0271776f,0.0918925f},{0.288369f,0.0279185f,0.0918925f},{0.286876f,0.0271775f,0.0900281f}, -{0.289903f,0.0285784f,0.0918925f},{0.288369f,0.0279183f,0.0900281f},{0.289903f,0.0285781f,0.0900281f}, -{0.29147f,0.0291536f,0.0918925f},{0.293062f,0.0296423f,0.0918925f},{0.291469f,0.0291535f,0.0900281f}, -{0.294677f,0.0300438f,0.0918925f},{0.293061f,0.0296423f,0.0900281f},{0.294676f,0.0300437f,0.0900281f}, -{0.29631f,0.0303573f,0.0918925f},{0.297959f,0.0305821f,0.0918925f},{0.29631f,0.0303572f,0.0900281f}, -{0.29962f,0.0307175f,0.0918925f},{0.297959f,0.030582f,0.0900281f},{0.29962f,0.0307174f,0.0900281f}, -{0.301289f,0.0307628f,0.0918925f},{0.301289f,0.0307628f,0.0900281f},{0.389518f,0.0664728f,0.0900281f}, -{0.385543f,0.0627861f,0.0900281f},{0.385543f,0.0627861f,0.0918925f},{0.393337f,0.0703321f,0.0900281f}, -{0.393337f,0.0703325f,0.0918925f},{0.396993f,0.074357f,0.0900281f},{0.381418f,0.0592762f,0.0918925f}, -{0.389518f,0.0664729f,0.0918925f},{0.381418f,0.0592761f,0.0900281f},{0.37715f,0.0559475f,0.0918925f}, -{0.37715f,0.0559474f,0.0900281f},{0.372745f,0.0528044f,0.0900281f},{0.372745f,0.0528044f,0.0918925f}, -{0.368209f,0.0498513f,0.0918925f},{0.368209f,0.0498511f,0.0900281f},{0.363547f,0.0470923f,0.0900281f}, -{0.358766f,0.0445321f,0.0918925f},{0.363547f,0.0470924f,0.0918925f},{0.358766f,0.0445321f,0.0900281f}, -{0.353871f,0.0421746f,0.0900281f},{0.353872f,0.042175f,0.0918925f},{0.338659f,0.0363926f,0.0918925f}, -{0.343803f,0.0380996f,0.0900281f},{0.338659f,0.0363926f,0.0900281f},{0.348877f,0.0400276f,0.0918925f}, -{0.348877f,0.0400276f,0.0900281f},{0.343803f,0.0380996f,0.0918925f},{0.333452f,0.0349082f,0.0918925f}, -{0.328189f,0.033648f,0.0918925f},{0.333452f,0.0349082f,0.0900281f},{0.328189f,0.0336479f,0.0900281f}, -{0.322877f,0.0326134f,0.0900281f},{0.317524f,0.031806f,0.0900281f},{0.317524f,0.031806f,0.0918925f}, -{0.322877f,0.0326134f,0.0918925f},{0.312136f,0.0312274f,0.0900281f},{0.312137f,0.0312275f,0.0918925f}, -{0.306722f,0.0308792f,0.0900281f},{0.306722f,0.0308792f,0.0918925f},{0.400468f,0.0785292f,0.0900281f}, -{0.396993f,0.0743574f,0.0918925f},{0.400468f,0.0785294f,0.0918925f},{0.403757f,0.0828395f,0.0900281f}, -{0.403757f,0.0828396f,0.0918925f},{0.406855f,0.0872815f,0.0900281f},{0.409759f,0.0918488f,0.0900281f}, -{0.406855f,0.0872816f,0.0918925f},{0.409759f,0.091849f,0.0918925f},{0.412465f,0.0965352f,0.0900281f}, -{0.412465f,0.0965352f,0.0918925f},{0.41497f,0.101334f,0.0900281f},{0.417269f,0.106239f,0.0900281f}, -{0.41497f,0.101334f,0.0918925f},{0.417269f,0.106239f,0.0918925f},{0.419359f,0.111243f,0.0900281f}, -{0.419359f,0.111243f,0.0918925f},{0.421236f,0.116341f,0.0900281f},{0.422894f,0.121519f,0.0900281f}, -{0.421236f,0.116342f,0.0918925f},{0.422894f,0.121519f,0.0918925f},{0.424327f,0.126754f,0.0900281f}, -{0.424327f,0.126754f,0.0918925f},{0.425533f,0.132038f,0.0900281f},{0.426511f,0.137363f,0.0900281f}, -{0.425533f,0.132038f,0.0918925f},{0.426511f,0.137364f,0.0918925f},{0.427261f,0.142723f,0.0900281f}, -{0.427261f,0.142723f,0.0918925f},{0.427781f,0.14811f,0.0900281f},{0.428071f,0.153516f,0.0900281f}, -{0.427781f,0.14811f,0.0918925f},{0.428071f,0.153516f,0.0918925f},{0.428131f,0.158934f,0.0900281f}, -{0.428131f,0.158934f,0.0918925f},{0.427958f,0.164356f,0.0900281f},{0.427553f,0.169776f,0.0900281f}, -{0.427958f,0.164357f,0.0918925f},{0.427553f,0.169776f,0.0918925f},{0.448656f,0.18196f,0.0918925f}, -{0.448656f,0.18196f,0.0900281f},{0.5f,0.0049028f,0.0918925f},{0.5f,-0.00490289f,0.0918925f}, -{0.5f,0.00490289f,0.0900281f},{0.499724f,0.0147057f,0.0900281f},{0.499724f,0.0147055f,0.0918925f}, -{0.499171f,0.0244996f,0.0900281f},{0.499171f,0.0244996f,0.0918925f},{0.498342f,0.0342788f,0.0918925f}, -{0.498342f,0.034279f,0.0900281f},{0.497236f,0.0440377f,0.0900281f},{0.497236f,0.0440376f,0.0918925f}, -{0.495854f,0.05377f,0.0900281f},{0.495854f,0.05377f,0.0918925f},{0.494196f,0.0634697f,0.0918925f}, -{0.494196f,0.0634706f,0.0900281f},{0.492264f,0.0731194f,0.0900281f},{0.492264f,0.0731193f,0.0918925f}, -{0.490062f,0.0826996f,0.0900281f},{0.490062f,0.0826996f,0.0918925f},{0.487593f,0.0922052f,0.0918925f}, -{0.487593f,0.0922054f,0.0900281f},{0.484859f,0.101631f,0.0900281f},{0.484859f,0.101631f,0.0918925f}, -{0.481861f,0.110971f,0.0900281f},{0.481861f,0.110971f,0.0918925f},{0.478603f,0.120221f,0.0918925f}, -{0.478602f,0.120221f,0.0900281f},{0.475085f,0.129374f,0.0900281f},{0.475085f,0.129374f,0.0918925f}, -{0.47131f,0.138425f,0.0900281f},{0.47131f,0.138425f,0.0918925f},{0.46728f,0.147368f,0.0918925f}, -{0.46728f,0.147369f,0.0900281f},{0.462998f,0.156199f,0.0900281f},{0.462998f,0.156199f,0.0918925f}, -{0.458465f,0.164912f,0.0900281f},{0.458465f,0.164912f,0.0918925f},{0.453684f,0.173501f,0.0918925f}, -{0.453684f,0.173501f,0.0900281f},{0.5f,-0.0049028f,0.0900281f},{0.499724f,-0.0147055f,0.0900281f}, -{0.499724f,-0.0147057f,0.0918925f},{0.499171f,-0.0244996f,0.0918925f},{0.499171f,-0.0244996f,0.0900281f}, -{0.498342f,-0.034279f,0.0918925f},{0.498342f,-0.0342788f,0.0900281f},{0.497236f,-0.0440376f,0.0900281f}, -{0.497236f,-0.0440377f,0.0918925f},{0.495854f,-0.05377f,0.0918925f},{0.495854f,-0.05377f,0.0900281f}, -{0.494196f,-0.0634706f,0.0918925f},{0.494196f,-0.0634697f,0.0900281f},{0.492264f,-0.0731193f,0.0900281f}, -{0.492264f,-0.0731194f,0.0918925f},{0.490062f,-0.0826996f,0.0918925f},{0.490062f,-0.0826996f,0.0900281f}, -{0.487593f,-0.0922054f,0.0918925f},{0.487593f,-0.0922052f,0.0900281f},{0.484859f,-0.101631f,0.0900281f}, -{0.484859f,-0.101631f,0.0918925f},{0.481861f,-0.110971f,0.0918925f},{0.481861f,-0.110971f,0.0900281f}, -{0.478602f,-0.120221f,0.0918925f},{0.478603f,-0.120221f,0.0900281f},{0.475085f,-0.129374f,0.0900281f}, -{0.475085f,-0.129374f,0.0918925f},{0.47131f,-0.138425f,0.0918925f},{0.47131f,-0.138425f,0.0900281f}, -{0.46728f,-0.147369f,0.0918925f},{0.46728f,-0.147368f,0.0900281f},{0.462998f,-0.156199f,0.0900281f}, -{0.462998f,-0.156199f,0.0918925f},{0.458465f,-0.164912f,0.0918925f},{0.458465f,-0.164912f,0.0900281f}, -{0.453684f,-0.173501f,0.0918925f},{0.453684f,-0.173501f,0.0900281f},{0.295886f,0.0200317f,0.0918925f}, -{0.280259f,0.0036392f,0.0918925f},{0.280781f,0.00474168f,0.0918925f},{0.28931f,0.0152687f,0.0918925f}, -{0.29453f,0.0183517f,0.0918925f},{0.28153f,0.0057053f,0.0918925f},{0.291507f,0.0130697f,0.0918925f}, -{0.289835f,0.0151095f,0.0918925f},{0.294119f,0.0173478f,0.0918925f},{0.291087f,0.0109706f,0.0918925f}, -{0.290739f,0.0105473f,0.0918925f},{0.295126f,0.0192577f,0.0918925f},{0.296782f,0.0206442f,0.0918925f}, -{0.297778f,0.0210723f,0.0918925f},{0.290316f,0.0101998f,0.0918925f},{0.291091f,0.0140791f,0.0918925f}, -{0.293911f,0.0151984f,0.0918925f},{0.290742f,0.0145033f,0.0918925f},{0.315791f,-0.0105451f,0.0918925f}, -{0.315367f,-0.0101973f,0.0918925f},{0.316139f,-0.0109693f,0.0918925f},{0.314358f,-0.00977971f,0.0918925f}, -{0.314883f,-0.00993885f,0.0918925f},{0.314881f,-0.0151067f,0.0918925f},{0.316555f,-0.0119787f,0.0918925f}, -{0.316397f,-0.0114536f,0.0918925f},{0.316609f,-0.0125242f,0.0918925f},{0.316394f,-0.013595f,0.0918925f}, -{0.316135f,-0.0140778f,0.0918925f},{0.315788f,-0.0145011f,0.0918925f},{0.315364f,-0.0148486f,0.0918925f}, -{0.314357f,-0.015266f,0.0918925f},{0.290318f,0.0148511f,0.0918925f},{0.29391f,0.0162833f,0.0918925f}, -{0.291506f,0.0119779f,0.0918925f},{0.291561f,0.0125242f,0.0918925f},{0.291346f,0.0114534f,0.0918925f}, -{0.291349f,0.0135948f,0.0918925f},{0.289833f,0.00994166f,0.0918925f},{0.316555f,-0.0130705f,0.0918925f}, -{0.289309f,0.00978241f,0.0918925f},{0.280782f,0.00474296f,0.0900281f},{0.297777f,0.0210725f,0.0900281f}, -{0.296781f,0.020644f,0.0900281f},{0.290742f,0.0105451f,0.0900281f},{0.280259f,0.00364027f,0.0900281f}, -{0.289835f,0.00993885f,0.0900281f},{0.295886f,0.0200312f,0.0900281f},{0.295126f,0.0192574f,0.0900281f}, -{0.29391f,0.0162822f,0.0900281f},{0.290739f,0.0145011f,0.0900281f},{0.290316f,0.0148486f,0.0900281f}, -{0.291561f,0.0125242f,0.0900281f},{0.28931f,0.00977971f,0.0900281f},{0.291091f,0.0109693f,0.0900281f}, -{0.290318f,0.0101973f,0.0900281f},{0.291349f,0.0114536f,0.0900281f},{0.315791f,-0.0145033f,0.0900281f}, -{0.316139f,-0.0140791f,0.0900281f},{0.314357f,-0.00978241f,0.0900281f},{0.314881f,-0.00994166f,0.0900281f}, -{0.294529f,0.0183513f,0.0900281f},{0.294119f,0.0173468f,0.0900281f},{0.289833f,0.0151067f,0.0900281f}, -{0.289309f,0.015266f,0.0900281f},{0.291087f,0.0140778f,0.0900281f},{0.293911f,0.0151976f,0.0900281f}, -{0.291346f,0.013595f,0.0900281f},{0.28153f,0.00570553f,0.0900281f},{0.316555f,-0.0119779f,0.0900281f}, -{0.315364f,-0.0101998f,0.0900281f},{0.316609f,-0.0125242f,0.0900281f},{0.316555f,-0.0130697f,0.0900281f}, -{0.316397f,-0.0135948f,0.0900281f},{0.315367f,-0.0148511f,0.0900281f},{0.314883f,-0.0151095f,0.0900281f}, -{0.316135f,-0.0109706f,0.0900281f},{0.314358f,-0.0152687f,0.0900281f},{0.316394f,-0.0114534f,0.0900281f}, -{0.315788f,-0.0105473f,0.0900281f},{0.291507f,0.0119787f,0.0900281f},{0.291506f,0.0130705f,0.0900281f}, -{-0.0125242f,0.285968f,0.0900281f},{-0.0130723f,0.286022f,0.0918925f},{-0.0125242f,0.285968f,0.0918925f}, -{-0.011454f,0.286181f,0.0918925f},{-0.011454f,0.286181f,0.0900281f},{-0.0119761f,0.286022f,0.0918925f}, -{-0.0119761f,0.286022f,0.0900281f},{-0.0109726f,0.286438f,0.0900281f},{-0.0105467f,0.286787f,0.0900281f}, -{-0.0105467f,0.286787f,0.0918925f},{-0.0101975f,0.287213f,0.0900281f},{-0.0101975f,0.287213f,0.0918925f}, -{-0.0109726f,0.286438f,0.0918925f},{-0.00972758f,0.288764f,0.0900281f},{-0.00978182f,0.288216f,0.0900281f}, -{-0.00978182f,0.288216f,0.0918925f},{-0.00994047f,0.287694f,0.0918925f},{-0.00994047f,0.287694f,0.0900281f}, -{-0.00972758f,0.288764f,0.0918925f},{-0.0130723f,0.286022f,0.0900281f},{-0.0135944f,0.286181f,0.0918925f}, -{-0.0135944f,0.286181f,0.0900281f},{-0.0140758f,0.286438f,0.0900281f},{-0.0140758f,0.286438f,0.0918925f}, -{-0.0145017f,0.286787f,0.0900281f},{-0.0145017f,0.286787f,0.0918925f},{-0.0148509f,0.287213f,0.0918925f}, -{-0.0148509f,0.287213f,0.0900281f},{-0.0151079f,0.287694f,0.0900281f},{-0.0151079f,0.287694f,0.0918925f}, -{-0.0152666f,0.288216f,0.0900281f},{-0.0152666f,0.288216f,0.0918925f},{-0.0153208f,0.288764f,0.0918925f}, -{-0.0153208f,0.288764f,0.0900281f},{0.0125242f,0.311016f,0.0900281f},{0.0119761f,0.31107f,0.0918925f}, -{0.0125242f,0.311016f,0.0918925f},{0.0135944f,0.311229f,0.0918925f},{0.0135944f,0.311229f,0.0900281f}, -{0.0130723f,0.31107f,0.0918925f},{0.0130723f,0.31107f,0.0900281f},{0.0140758f,0.311486f,0.0900281f}, -{0.0145017f,0.311835f,0.0900281f},{0.0145017f,0.311835f,0.0918925f},{0.0148509f,0.312261f,0.0900281f}, -{0.0148509f,0.312261f,0.0918925f},{0.0140758f,0.311486f,0.0918925f},{0.0153208f,0.313813f,0.0900281f}, -{0.0152666f,0.313265f,0.0900281f},{0.0152666f,0.313265f,0.0918925f},{0.0151079f,0.312743f,0.0918925f}, -{0.0151079f,0.312743f,0.0900281f},{0.0153208f,0.313813f,0.0918925f},{0.0119761f,0.31107f,0.0900281f}, -{0.011454f,0.311229f,0.0918925f},{0.011454f,0.311229f,0.0900281f},{0.0109726f,0.311486f,0.0900281f}, -{0.0109726f,0.311486f,0.0918925f},{0.0105467f,0.311835f,0.0900281f},{0.0105467f,0.311835f,0.0918925f}, -{0.0101975f,0.312261f,0.0918925f},{0.0101975f,0.312261f,0.0900281f},{0.00994047f,0.312743f,0.0900281f}, -{0.00994047f,0.312743f,0.0918925f},{0.00978182f,0.313265f,0.0900281f},{0.00978182f,0.313265f,0.0918925f}, -{0.00972758f,0.313813f,0.0918925f},{0.00972758f,0.313813f,0.0900281f},{-0.0073455f,0.284736f,0.0900281f}, -{-0.00738926f,0.285954f,0.0918925f},{-0.00734538f,0.284736f,0.0918925f},{-0.00703877f,0.283556f,0.0900281f}, -{-0.0070384f,0.283555f,0.0918925f},{-0.00648281f,0.28247f,0.0900281f},{-0.00648282f,0.28247f,0.0918925f}, -{-0.00738915f,0.285956f,0.0900281f},{-0.00716427f,0.287154f,0.0918925f},{-0.00716427f,0.287154f,0.0900281f}, -{0.00856857f,0.309858f,0.0918925f},{0.0078732f,0.310706f,0.0918925f},{0.00856991f,0.309857f,0.0900281f}, -{0.00787361f,0.310705f,0.0900281f},{0.0073566f,0.311673f,0.0918925f},{0.00703838f,0.312722f,0.0918925f}, -{0.00735691f,0.311672f,0.0900281f},{0.00693097f,0.313813f,0.0918925f},{0.00703853f,0.312721f,0.0900281f}, -{0.00693097f,0.313813f,0.0900281f},{0.00941743f,0.309162f,0.0900281f},{0.0103841f,0.308645f,0.0900281f}, -{0.00941663f,0.309162f,0.0918925f},{0.0114331f,0.308327f,0.0900281f},{0.0103834f,0.308645f,0.0918925f}, -{0.0114326f,0.308327f,0.0918925f},{0.0125242f,0.30822f,0.0900281f},{0.0125242f,0.30822f,0.0918925f}, -{-0.065917f,0.401959f,0.0918925f},{-0.0617984f,0.398048f,0.0918925f},{-0.0659174f,0.40196f,0.0900281f}, -{-0.07019f,0.405692f,0.0900281f},{-0.0701898f,0.405691f,0.0918925f},{-0.0746077f,0.409237f,0.0900281f}, -{-0.0746076f,0.409237f,0.0918925f},{-0.0791643f,0.412592f,0.0918925f},{-0.0791644f,0.412592f,0.0900281f}, -{-0.0838538f,0.415754f,0.0900281f},{-0.0838537f,0.415754f,0.0918925f},{-0.0886696f,0.418717f,0.0900281f}, -{-0.0886696f,0.418717f,0.0918925f},{-0.0936056f,0.421479f,0.0918925f},{-0.0936057f,0.421479f,0.0900281f}, -{-0.0986557f,0.424035f,0.0900281f},{-0.0986556f,0.424035f,0.0918925f},{-0.103813f,0.426382f,0.0900281f}, -{-0.103813f,0.426382f,0.0918925f},{-0.109072f,0.428515f,0.0918925f},{-0.109073f,0.428515f,0.0900281f}, -{-0.11442f,0.430428f,0.0900281f},{-0.11442f,0.430428f,0.0918925f},{-0.119834f,0.432114f,0.0900281f}, -{-0.119834f,0.432114f,0.0918925f},{-0.125306f,0.433572f,0.0918925f},{-0.125307f,0.433572f,0.0900281f}, -{-0.130829f,0.4348f,0.0900281f},{-0.130829f,0.4348f,0.0918925f},{-0.136396f,0.435797f,0.0900281f}, -{-0.136396f,0.435797f,0.0918925f},{-0.141999f,0.436561f,0.0918925f},{-0.141999f,0.436561f,0.0900281f}, -{-0.147631f,0.437093f,0.0900281f},{-0.147631f,0.437093f,0.0918925f},{-0.153284f,0.437391f,0.0900281f}, -{-0.153284f,0.437391f,0.0918925f},{-0.158952f,0.437453f,0.0918925f},{-0.158952f,0.437453f,0.0900281f}, -{-0.164627f,0.437279f,0.0900281f},{-0.164627f,0.437279f,0.0918925f},{-0.0617987f,0.398048f,0.0900281f}, -{-0.0578515f,0.393973f,0.0900281f},{-0.0578514f,0.393973f,0.0918925f},{-0.054083f,0.389744f,0.0918925f}, -{-0.0540831f,0.389744f,0.0900281f},{-0.0504973f,0.385366f,0.0918925f},{-0.0504974f,0.385366f,0.0900281f}, -{-0.0470986f,0.380846f,0.0900281f},{-0.0470985f,0.380846f,0.0918925f},{-0.0438908f,0.376189f,0.0918925f}, -{-0.0438908f,0.376189f,0.0900281f},{-0.0408784f,0.371402f,0.0918925f},{-0.0408785f,0.371402f,0.0900281f}, -{-0.0380656f,0.36649f,0.0900281f},{-0.0380655f,0.36649f,0.0918925f},{-0.0354565f,0.36146f,0.0918925f}, -{-0.0354565f,0.36146f,0.0900281f},{-0.0330551f,0.356317f,0.0918925f},{-0.0330554f,0.356318f,0.0900281f}, -{-0.0308688f,0.351076f,0.0900281f},{-0.0308688f,0.351076f,0.0918925f},{-0.0289059f,0.345756f,0.0918925f}, -{-0.0289059f,0.345756f,0.0900281f},{-0.0271683f,0.340366f,0.0918925f},{-0.0271684f,0.340366f,0.0900281f}, -{-0.0256577f,0.334914f,0.0900281f},{-0.0256577f,0.334914f,0.0918925f},{-0.0243753f,0.329406f,0.0918925f}, -{-0.0243754f,0.329406f,0.0900281f},{-0.0233228f,0.32385f,0.0918925f},{-0.0233228f,0.32385f,0.0900281f}, -{-0.0225016f,0.318253f,0.0900281f},{-0.0225016f,0.318253f,0.0918925f},{-0.0219132f,0.312622f,0.0918925f}, -{-0.0219132f,0.312623f,0.0900281f},{-0.0215591f,0.306965f,0.0918925f},{-0.0215591f,0.306965f,0.0900281f}, -{-0.0214407f,0.301289f,0.0918925f},{-0.0214407f,0.301289f,0.0900281f},{-0.0214056f,0.300061f,0.0918925f}, -{-0.0214056f,0.300061f,0.0900281f},{-0.0213002f,0.298838f,0.0900281f},{-0.0213002f,0.298838f,0.0918925f}, -{-0.00857005f,0.29272f,0.0900281f},{-0.00933952f,0.293362f,0.0900281f},{-0.00856812f,0.292718f,0.0918925f}, -{-0.0102104f,0.293856f,0.0918925f},{-0.00933867f,0.293362f,0.0918925f},{-0.010212f,0.293857f,0.0900281f}, -{-0.0111572f,0.294188f,0.0918925f},{-0.0111588f,0.294188f,0.0900281f},{-0.0121484f,0.294345f,0.0918925f}, -{-0.0131504f,0.294322f,0.0918925f},{-0.0121494f,0.294345f,0.0900281f},{-0.0141339f,0.294121f,0.0900281f}, -{-0.0131516f,0.294322f,0.0900281f},{-0.0141339f,0.294121f,0.0918925f},{-0.00792586f,0.291949f,0.0918925f}, -{-0.00792654f,0.29195f,0.0900281f},{-0.00743177f,0.291078f,0.0900281f},{-0.00710074f,0.290131f,0.0900281f}, -{-0.00743116f,0.291076f,0.0918925f},{-0.00710007f,0.290129f,0.0918925f},{-0.00694354f,0.28914f,0.0900281f}, -{-0.00694356f,0.289139f,0.0918925f},{-0.00696625f,0.288138f,0.0900281f},{-0.00696632f,0.288136f,0.0918925f}, -{0.0121669f,0.283634f,0.0900281f},{0.0102959f,0.282482f,0.0900281f},{0.0102961f,0.282482f,0.0918925f}, -{0.012167f,0.283634f,0.0918925f},{0.013914f,0.284976f,0.0900281f},{0.008319f,0.281528f,0.0918925f}, -{0.00831882f,0.281527f,0.0900281f},{0.00625128f,0.280779f,0.0918925f},{0.00625078f,0.280779f,0.0900281f}, -{0.00411456f,0.280246f,0.0918925f},{0.00411435f,0.280246f,0.0900281f},{0.00194003f,0.279936f,0.0900281f}, -{0.0019402f,0.279936f,0.0918925f},{-0.000253827f,0.279849f,0.0918925f},{-0.00245022f,0.279988f,0.0918925f}, -{-0.00025393f,0.279849f,0.0900281f},{-0.00245022f,0.279988f,0.0900281f},{0.0155106f,0.286486f,0.0900281f}, -{0.0139141f,0.284976f,0.0918925f},{0.0155107f,0.286486f,0.0918925f},{0.016943f,0.288149f,0.0900281f}, -{0.0169431f,0.28815f,0.0918925f},{0.0181996f,0.289954f,0.0900281f},{0.0192663f,0.29188f,0.0900281f}, -{0.0181999f,0.289954f,0.0918925f},{0.0192664f,0.291881f,0.0918925f},{0.0201277f,0.293901f,0.0900281f}, -{0.0201278f,0.293901f,0.0918925f},{0.0207778f,0.295998f,0.0900281f},{0.0212106f,0.298156f,0.0900281f}, -{0.0207778f,0.295998f,0.0918925f},{0.0212106f,0.298156f,0.0918925f},{0.0200545f,0.303955f,0.0900281f}, -{0.0207145f,0.302604f,0.0918925f},{0.020054f,0.303956f,0.0918925f},{0.0191712f,0.305176f,0.0900281f}, -{0.0207149f,0.302603f,0.0900281f},{0.0211353f,0.301156f,0.0918925f},{0.0191712f,0.305176f,0.0918925f}, -{0.0211356f,0.301155f,0.0900281f},{0.021302f,0.29966f,0.0918925f},{0.0213021f,0.299659f,0.0900281f}, -{0.0180928f,0.306228f,0.0900281f},{0.018092f,0.306229f,0.0918925f},{0.0168512f,0.307079f,0.0918925f}, -{0.0168521f,0.307079f,0.0900281f},{0.0154797f,0.307707f,0.0918925f},{0.0154807f,0.307707f,0.0900281f}, -{0.0140259f,0.30809f,0.0900281f},{0.014025f,0.30809f,0.0918925f},{0.00703853f,0.314904f,0.0918925f}, -{0.00856991f,0.317768f,0.0918925f},{0.0078732f,0.31692f,0.0900281f},{0.00787361f,0.31692f,0.0918925f}, -{0.00735691f,0.315954f,0.0918925f},{0.0073566f,0.315953f,0.0900281f},{0.00703838f,0.314904f,0.0900281f}, -{0.0103834f,0.31898f,0.0900281f},{0.0103841f,0.31898f,0.0918925f},{0.0114331f,0.319299f,0.0918925f}, -{0.00856857f,0.317767f,0.0900281f},{0.00941743f,0.318464f,0.0918925f},{0.00941663f,0.318463f,0.0900281f}, -{0.0125242f,0.319406f,0.0918925f},{0.0114326f,0.319298f,0.0900281f},{0.0125242f,0.319406f,0.0900281f}, -{0.017806f,0.32063f,0.0900281f},{0.0178073f,0.32063f,0.0918925f},{0.0193785f,0.321554f,0.0900281f}, -{0.0193787f,0.321554f,0.0918925f},{0.0161135f,0.319955f,0.0918925f},{0.0161128f,0.319955f,0.0900281f}, -{0.0143418f,0.319544f,0.0900281f},{0.0143423f,0.319544f,0.0918925f},{0.0207886f,0.322701f,0.0900281f}, -{0.0220123f,0.324052f,0.0900281f},{0.0207888f,0.322701f,0.0918925f},{0.0220132f,0.324053f,0.0918925f}, -{0.023018f,0.325573f,0.0900281f},{0.0230183f,0.325573f,0.0918925f},{0.02378f,0.327224f,0.0900281f}, -{0.0242851f,0.328976f,0.0900281f},{0.0237802f,0.327224f,0.0918925f},{0.0242851f,0.328976f,0.0918925f}, -{0.0744192f,0.409092f,0.0918925f},{0.0744192f,0.409092f,0.0900281f},{0.0700077f,0.405539f,0.0900281f}, -{0.065746f,0.401803f,0.0900281f},{0.0700077f,0.405539f,0.0918925f},{0.06164f,0.397891f,0.0900281f}, -{0.0657461f,0.401803f,0.0918925f},{0.0616401f,0.397891f,0.0918925f},{0.0576956f,0.393805f,0.0900281f}, -{0.0539185f,0.389551f,0.0900281f},{0.0576957f,0.393805f,0.0918925f},{0.0503158f,0.385134f,0.0900281f}, -{0.0539186f,0.389551f,0.0918925f},{0.050316f,0.385135f,0.0918925f},{0.0469052f,0.380577f,0.0900281f}, -{0.0436939f,0.375889f,0.0900281f},{0.0469052f,0.380577f,0.0918925f},{0.0406851f,0.371079f,0.0900281f}, -{0.0436939f,0.375889f,0.0918925f},{0.0406851f,0.371079f,0.0918925f},{0.0378819f,0.366152f,0.0900281f}, -{0.0352877f,0.361116f,0.0900281f},{0.037882f,0.366152f,0.0918925f},{0.0329054f,0.355977f,0.0900281f}, -{0.0352877f,0.361116f,0.0918925f},{0.0329055f,0.355977f,0.0918925f},{0.0307383f,0.350742f,0.0900281f}, -{0.0287896f,0.345418f,0.0900281f},{0.0307384f,0.350742f,0.0918925f},{0.0270624f,0.340011f,0.0900281f}, -{0.0287897f,0.345418f,0.0918925f},{0.0270624f,0.340011f,0.0918925f},{0.0255598f,0.334528f,0.0900281f}, -{0.0255599f,0.334528f,0.0918925f},{0.0789746f,0.412458f,0.0918925f},{0.0789746f,0.412458f,0.0900281f}, -{0.0836681f,0.415634f,0.0918925f},{0.0884938f,0.418614f,0.0918925f},{0.083668f,0.415634f,0.0900281f}, -{0.0934459f,0.421394f,0.0918925f},{0.0884937f,0.418614f,0.0900281f},{0.0934458f,0.421394f,0.0900281f}, -{0.0985185f,0.423969f,0.0918925f},{0.103704f,0.426335f,0.0918925f},{0.0985183f,0.423969f,0.0900281f}, -{0.108978f,0.428478f,0.0918925f},{0.103704f,0.426334f,0.0900281f},{0.108977f,0.428478f,0.0900281f}, -{0.114326f,0.430397f,0.0918925f},{0.119742f,0.432088f,0.0918925f},{0.114326f,0.430397f,0.0900281f}, -{0.125218f,0.43355f,0.0918925f},{0.119742f,0.432088f,0.0900281f},{0.125218f,0.43355f,0.0900281f}, -{0.130747f,0.434783f,0.0918925f},{0.136322f,0.435785f,0.0918925f},{0.130747f,0.434783f,0.0900281f}, -{0.141936f,0.436554f,0.0918925f},{0.136322f,0.435785f,0.0900281f},{0.141935f,0.436554f,0.0900281f}, -{0.14758f,0.43709f,0.0918925f},{0.153248f,0.43739f,0.0918925f},{0.14758f,0.43709f,0.0900281f}, -{0.158933f,0.437453f,0.0918925f},{0.153248f,0.43739f,0.0900281f},{0.158933f,0.437453f,0.0900281f}, -{0.164627f,0.437279f,0.0918925f},{0.164627f,0.437279f,0.0900281f},{0.169288f,0.445352f,0.0900281f}, -{0.169288f,0.445352f,0.0918925f},{0.0239114f,0.489867f,0.0918925f},{0.0143525f,0.490408f,0.0918925f}, -{0.0143527f,0.490408f,0.0900281f},{-0.00478512f,0.490679f,0.0900281f},{0.00478519f,0.490679f,0.0900281f}, -{0.00478512f,0.490679f,0.0918925f},{0.0239115f,0.489867f,0.0900281f},{0.0334558f,0.489056f,0.0918925f}, -{0.0334558f,0.489056f,0.0900281f},{0.0429801f,0.487973f,0.0900281f},{0.04298f,0.487973f,0.0918925f}, -{0.0524782f,0.486621f,0.0918925f},{0.0524784f,0.486621f,0.0900281f},{0.0619436f,0.484998f,0.0900281f}, -{0.0619434f,0.484998f,0.0918925f},{0.0806965f,0.480955f,0.0900281f},{0.089968f,0.47854f,0.0900281f}, -{0.0899679f,0.47854f,0.0918925f},{0.0713532f,0.483109f,0.0918925f},{0.0713532f,0.483109f,0.0900281f}, -{0.0806964f,0.480955f,0.0918925f},{0.0991622f,0.475866f,0.0918925f},{0.0991623f,0.475866f,0.0900281f}, -{0.108274f,0.472933f,0.0900281f},{0.108274f,0.472933f,0.0918925f},{0.117298f,0.469745f,0.0918925f}, -{0.117298f,0.469745f,0.0900281f},{0.126228f,0.466302f,0.0918925f},{0.143787f,0.458664f,0.0900281f}, -{0.143786f,0.458664f,0.0918925f},{0.135059f,0.462608f,0.0900281f},{0.135059f,0.462608f,0.0918925f}, -{0.126228f,0.466302f,0.0900281f},{0.152404f,0.454472f,0.0900281f},{0.152404f,0.454472f,0.0918925f}, -{0.160907f,0.450034f,0.0900281f},{0.160906f,0.450034f,0.0918925f},{-0.00478519f,0.490679f,0.0918925f}, -{-0.0143525f,0.490408f,0.0900281f},{-0.0143527f,0.490408f,0.0918925f},{-0.0239114f,0.489867f,0.0900281f}, -{-0.0334558f,0.489056f,0.0900281f},{-0.0239115f,0.489867f,0.0918925f},{-0.0334558f,0.489056f,0.0918925f}, -{-0.04298f,0.487973f,0.0900281f},{-0.0429801f,0.487973f,0.0918925f},{-0.0524782f,0.486621f,0.0900281f}, -{-0.0619434f,0.484998f,0.0900281f},{-0.0524784f,0.486621f,0.0918925f},{-0.0619436f,0.484998f,0.0918925f}, -{-0.0713532f,0.483109f,0.0900281f},{-0.0713532f,0.483109f,0.0918925f},{-0.0806964f,0.480955f,0.0900281f}, -{-0.0899679f,0.47854f,0.0900281f},{-0.0806965f,0.480955f,0.0918925f},{-0.089968f,0.47854f,0.0918925f}, -{-0.0991622f,0.475866f,0.0900281f},{-0.0991623f,0.475866f,0.0918925f},{-0.108274f,0.472933f,0.0900281f}, -{-0.117298f,0.469745f,0.0900281f},{-0.108274f,0.472933f,0.0918925f},{-0.117298f,0.469745f,0.0918925f}, -{-0.126228f,0.466302f,0.0900281f},{-0.126228f,0.466302f,0.0918925f},{-0.135059f,0.462608f,0.0900281f}, -{-0.143786f,0.458664f,0.0900281f},{-0.135059f,0.462608f,0.0918925f},{-0.143787f,0.458664f,0.0918925f}, -{-0.152404f,0.454472f,0.0900281f},{-0.152404f,0.454472f,0.0918925f},{-0.160906f,0.450034f,0.0900281f}, -{-0.169288f,0.445352f,0.0900281f},{-0.160907f,0.450034f,0.0918925f},{-0.169288f,0.445352f,0.0918925f}, -{0.169776f,0.427553f,0.0918925f},{0.18196f,0.448656f,0.0900281f},{0.18196f,0.448656f,0.0918925f}, -{0.169776f,0.427553f,0.0900281f},{0.0785294f,0.400468f,0.0900281f},{0.0828396f,0.403757f,0.0900281f}, -{0.0828395f,0.403757f,0.0918925f},{0.0743574f,0.396993f,0.0900281f},{0.074357f,0.396993f,0.0918925f}, -{0.0703325f,0.393337f,0.0900281f},{0.0872815f,0.406855f,0.0918925f},{0.0785292f,0.400468f,0.0918925f}, -{0.0872816f,0.406855f,0.0900281f},{0.0918488f,0.409759f,0.0918925f},{0.091849f,0.409759f,0.0900281f}, -{0.0965352f,0.412465f,0.0900281f},{0.0965352f,0.412465f,0.0918925f},{0.101334f,0.41497f,0.0918925f}, -{0.101334f,0.41497f,0.0900281f},{0.106239f,0.417269f,0.0900281f},{0.111243f,0.419359f,0.0918925f}, -{0.106239f,0.417269f,0.0918925f},{0.111243f,0.419359f,0.0900281f},{0.116342f,0.421236f,0.0900281f}, -{0.116341f,0.421236f,0.0918925f},{0.132038f,0.425533f,0.0918925f},{0.126754f,0.424327f,0.0900281f}, -{0.132038f,0.425533f,0.0900281f},{0.121519f,0.422894f,0.0918925f},{0.121519f,0.422894f,0.0900281f}, -{0.126754f,0.424327f,0.0918925f},{0.137363f,0.426511f,0.0918925f},{0.142723f,0.427261f,0.0918925f}, -{0.137364f,0.426511f,0.0900281f},{0.142723f,0.427261f,0.0900281f},{0.14811f,0.427781f,0.0900281f}, -{0.153516f,0.428071f,0.0900281f},{0.153516f,0.428071f,0.0918925f},{0.14811f,0.427781f,0.0918925f}, -{0.158934f,0.428131f,0.0900281f},{0.158934f,0.428131f,0.0918925f},{0.164357f,0.427958f,0.0900281f}, -{0.164356f,0.427958f,0.0918925f},{0.0664729f,0.389518f,0.0900281f},{0.0703321f,0.393337f,0.0918925f}, -{0.0664728f,0.389518f,0.0918925f},{0.0627861f,0.385543f,0.0900281f},{0.0627861f,0.385543f,0.0918925f}, -{0.0592762f,0.381418f,0.0900281f},{0.0559475f,0.37715f,0.0900281f},{0.0592761f,0.381418f,0.0918925f}, -{0.0559474f,0.37715f,0.0918925f},{0.0528044f,0.372745f,0.0900281f},{0.0528044f,0.372745f,0.0918925f}, -{0.0498513f,0.368209f,0.0900281f},{0.0470924f,0.363547f,0.0900281f},{0.0498511f,0.368209f,0.0918925f}, -{0.0470923f,0.363547f,0.0918925f},{0.0445321f,0.358766f,0.0900281f},{0.0445321f,0.358766f,0.0918925f}, -{0.042175f,0.353872f,0.0900281f},{0.0400276f,0.348877f,0.0900281f},{0.0421746f,0.353871f,0.0918925f}, -{0.0400276f,0.348877f,0.0918925f},{0.0380996f,0.343803f,0.0900281f},{0.0380996f,0.343803f,0.0918925f}, -{0.0363926f,0.338659f,0.0900281f},{0.0349082f,0.333452f,0.0900281f},{0.0363926f,0.338659f,0.0918925f}, -{0.0349082f,0.333452f,0.0918925f},{0.033648f,0.328189f,0.0900281f},{0.0336479f,0.328189f,0.0918925f}, -{0.0326134f,0.322877f,0.0900281f},{0.031806f,0.317524f,0.0900281f},{0.0326134f,0.322877f,0.0918925f}, -{0.031806f,0.317524f,0.0918925f},{0.0312275f,0.312137f,0.0900281f},{0.0312274f,0.312136f,0.0918925f}, -{0.0308792f,0.306722f,0.0900281f},{0.0307628f,0.301289f,0.0900281f},{0.0308792f,0.306722f,0.0918925f}, -{0.0307628f,0.301289f,0.0918925f},{3.36153e-016f,0.270526f,0.0918925f},{4.05702e-016f,0.270526f,0.0900281f}, -{0.00166887f,0.270571f,0.0900281f},{0.0033296f,0.270707f,0.0900281f},{0.00166875f,0.270571f,0.0918925f}, -{0.00497861f,0.270931f,0.0900281f},{0.00332938f,0.270706f,0.0918925f},{0.00497832f,0.270931f,0.0918925f}, -{0.00661229f,0.271245f,0.0900281f},{0.00822706f,0.271646f,0.0900281f},{0.00661197f,0.271245f,0.0918925f}, -{0.00981931f,0.272135f,0.0900281f},{0.00822672f,0.271646f,0.0918925f},{0.009819f,0.272135f,0.0918925f}, -{0.0113858f,0.27271f,0.0900281f},{0.0129196f,0.27337f,0.0900281f},{0.0113852f,0.27271f,0.0918925f}, -{0.0144128f,0.274111f,0.0900281f},{0.0129192f,0.27337f,0.0918925f},{0.0144127f,0.274111f,0.0918925f}, -{0.0158618f,0.27493f,0.0900281f},{0.0172635f,0.275826f,0.0900281f},{0.0158617f,0.27493f,0.0918925f}, -{0.0186148f,0.276797f,0.0900281f},{0.0172633f,0.275826f,0.0918925f},{0.0186146f,0.276797f,0.0918925f}, -{0.0199127f,0.27784f,0.0900281f},{0.0211544f,0.278954f,0.0900281f},{0.0199124f,0.27784f,0.0918925f}, -{0.0223352f,0.280135f,0.0900281f},{0.0211538f,0.278953f,0.0918925f},{0.0223347f,0.280134f,0.0918925f}, -{0.0234487f,0.281376f,0.0900281f},{0.0244917f,0.282674f,0.0900281f},{0.0234485f,0.281376f,0.0918925f}, -{0.0254622f,0.284025f,0.0900281f},{0.0244916f,0.282674f,0.0918925f},{0.0254621f,0.284025f,0.0918925f}, -{0.0263582f,0.285427f,0.0900281f},{0.0271776f,0.286876f,0.0900281f},{0.0263581f,0.285427f,0.0918925f}, -{0.0279185f,0.288369f,0.0900281f},{0.0271775f,0.286876f,0.0918925f},{0.0279183f,0.288369f,0.0918925f}, -{0.0285784f,0.289903f,0.0900281f},{0.0291536f,0.29147f,0.0900281f},{0.0285781f,0.289903f,0.0918925f}, -{0.0296423f,0.293062f,0.0900281f},{0.0291535f,0.291469f,0.0918925f},{0.0296423f,0.293061f,0.0918925f}, -{0.0300438f,0.294677f,0.0900281f},{0.0303573f,0.29631f,0.0900281f},{0.0300437f,0.294676f,0.0918925f}, -{0.0305821f,0.297959f,0.0900281f},{0.0303572f,0.29631f,0.0918925f},{0.030582f,0.297959f,0.0918925f}, -{0.0307175f,0.29962f,0.0900281f},{0.0307174f,0.29962f,0.0918925f},{-0.00166887f,0.270571f,0.0918925f}, -{-0.00166875f,0.270571f,0.0900281f},{-0.0033296f,0.270707f,0.0918925f},{-0.00497861f,0.270931f,0.0918925f}, -{-0.00332938f,0.270706f,0.0900281f},{-0.00661229f,0.271245f,0.0918925f},{-0.00497832f,0.270931f,0.0900281f}, -{-0.00661197f,0.271245f,0.0900281f},{-0.00822706f,0.271646f,0.0918925f},{-0.00981931f,0.272135f,0.0918925f}, -{-0.00822672f,0.271646f,0.0900281f},{-0.0113858f,0.27271f,0.0918925f},{-0.009819f,0.272135f,0.0900281f}, -{-0.0113852f,0.27271f,0.0900281f},{-0.0129196f,0.27337f,0.0918925f},{-0.0144128f,0.274111f,0.0918925f}, -{-0.0129192f,0.27337f,0.0900281f},{-0.0158618f,0.27493f,0.0918925f},{-0.0144127f,0.274111f,0.0900281f}, -{-0.0158617f,0.27493f,0.0900281f},{-0.0172635f,0.275826f,0.0918925f},{-0.0186148f,0.276797f,0.0918925f}, -{-0.0172633f,0.275826f,0.0900281f},{-0.0199127f,0.27784f,0.0918925f},{-0.0186146f,0.276797f,0.0900281f}, -{-0.0199124f,0.27784f,0.0900281f},{-0.0211544f,0.278954f,0.0918925f},{-0.0223352f,0.280135f,0.0918925f}, -{-0.0211538f,0.278953f,0.0900281f},{-0.0234487f,0.281376f,0.0918925f},{-0.0223347f,0.280134f,0.0900281f}, -{-0.0234485f,0.281376f,0.0900281f},{-0.0244917f,0.282674f,0.0918925f},{-0.0254622f,0.284025f,0.0918925f}, -{-0.0244916f,0.282674f,0.0900281f},{-0.0263582f,0.285427f,0.0918925f},{-0.0254621f,0.284025f,0.0900281f}, -{-0.0263581f,0.285427f,0.0900281f},{-0.0271776f,0.286876f,0.0918925f},{-0.0279185f,0.288369f,0.0918925f}, -{-0.0271775f,0.286876f,0.0900281f},{-0.0285784f,0.289903f,0.0918925f},{-0.0279183f,0.288369f,0.0900281f}, -{-0.0285781f,0.289903f,0.0900281f},{-0.0291536f,0.29147f,0.0918925f},{-0.0296423f,0.293062f,0.0918925f}, -{-0.0291535f,0.291469f,0.0900281f},{-0.0300438f,0.294677f,0.0918925f},{-0.0296423f,0.293061f,0.0900281f}, -{-0.0300437f,0.294676f,0.0900281f},{-0.0303573f,0.29631f,0.0918925f},{-0.0305821f,0.297959f,0.0918925f}, -{-0.0303572f,0.29631f,0.0900281f},{-0.0307175f,0.29962f,0.0918925f},{-0.030582f,0.297959f,0.0900281f}, -{-0.0307174f,0.29962f,0.0900281f},{-0.0307628f,0.301289f,0.0918925f},{-0.0307628f,0.301289f,0.0900281f}, -{-0.0664728f,0.389518f,0.0900281f},{-0.0627861f,0.385543f,0.0900281f},{-0.0627861f,0.385543f,0.0918925f}, -{-0.0703321f,0.393337f,0.0900281f},{-0.0703325f,0.393337f,0.0918925f},{-0.074357f,0.396993f,0.0900281f}, -{-0.0592762f,0.381418f,0.0918925f},{-0.0664729f,0.389518f,0.0918925f},{-0.0592761f,0.381418f,0.0900281f}, -{-0.0559475f,0.37715f,0.0918925f},{-0.0559474f,0.37715f,0.0900281f},{-0.0528044f,0.372745f,0.0900281f}, -{-0.0528044f,0.372745f,0.0918925f},{-0.0498513f,0.368209f,0.0918925f},{-0.0498511f,0.368209f,0.0900281f}, -{-0.0470923f,0.363547f,0.0900281f},{-0.0445321f,0.358766f,0.0918925f},{-0.0470924f,0.363547f,0.0918925f}, -{-0.0445321f,0.358766f,0.0900281f},{-0.0421746f,0.353871f,0.0900281f},{-0.042175f,0.353872f,0.0918925f}, -{-0.0363926f,0.338659f,0.0918925f},{-0.0380996f,0.343803f,0.0900281f},{-0.0363926f,0.338659f,0.0900281f}, -{-0.0400276f,0.348877f,0.0918925f},{-0.0400276f,0.348877f,0.0900281f},{-0.0380996f,0.343803f,0.0918925f}, -{-0.0349082f,0.333452f,0.0918925f},{-0.033648f,0.328189f,0.0918925f},{-0.0349082f,0.333452f,0.0900281f}, -{-0.0336479f,0.328189f,0.0900281f},{-0.0326134f,0.322877f,0.0900281f},{-0.031806f,0.317524f,0.0900281f}, -{-0.031806f,0.317524f,0.0918925f},{-0.0326134f,0.322877f,0.0918925f},{-0.0312274f,0.312136f,0.0900281f}, -{-0.0312275f,0.312137f,0.0918925f},{-0.0308792f,0.306722f,0.0900281f},{-0.0308792f,0.306722f,0.0918925f}, -{-0.0785292f,0.400468f,0.0900281f},{-0.0743574f,0.396993f,0.0918925f},{-0.0785294f,0.400468f,0.0918925f}, -{-0.0828395f,0.403757f,0.0900281f},{-0.0828396f,0.403757f,0.0918925f},{-0.0872815f,0.406855f,0.0900281f}, -{-0.0918488f,0.409759f,0.0900281f},{-0.0872816f,0.406855f,0.0918925f},{-0.091849f,0.409759f,0.0918925f}, -{-0.0965352f,0.412465f,0.0900281f},{-0.0965352f,0.412465f,0.0918925f},{-0.101334f,0.41497f,0.0900281f}, -{-0.106239f,0.417269f,0.0900281f},{-0.101334f,0.41497f,0.0918925f},{-0.106239f,0.417269f,0.0918925f}, -{-0.111243f,0.419359f,0.0900281f},{-0.111243f,0.419359f,0.0918925f},{-0.116341f,0.421236f,0.0900281f}, -{-0.121519f,0.422894f,0.0900281f},{-0.116342f,0.421236f,0.0918925f},{-0.121519f,0.422894f,0.0918925f}, -{-0.126754f,0.424327f,0.0900281f},{-0.126754f,0.424327f,0.0918925f},{-0.132038f,0.425533f,0.0900281f}, -{-0.137363f,0.426511f,0.0900281f},{-0.132038f,0.425533f,0.0918925f},{-0.137364f,0.426511f,0.0918925f}, -{-0.142723f,0.427261f,0.0900281f},{-0.142723f,0.427261f,0.0918925f},{-0.14811f,0.427781f,0.0900281f}, -{-0.153516f,0.428071f,0.0900281f},{-0.14811f,0.427781f,0.0918925f},{-0.153516f,0.428071f,0.0918925f}, -{-0.158934f,0.428131f,0.0900281f},{-0.158934f,0.428131f,0.0918925f},{-0.164356f,0.427958f,0.0900281f}, -{-0.169776f,0.427553f,0.0900281f},{-0.164357f,0.427958f,0.0918925f},{-0.169776f,0.427553f,0.0918925f}, -{-0.18196f,0.448656f,0.0918925f},{-0.18196f,0.448656f,0.0900281f},{-0.0049028f,0.5f,0.0918925f}, -{0.00490289f,0.5f,0.0918925f},{-0.00490289f,0.5f,0.0900281f},{-0.0147057f,0.499724f,0.0900281f}, -{-0.0147055f,0.499724f,0.0918925f},{-0.0244996f,0.499171f,0.0900281f},{-0.0244996f,0.499171f,0.0918925f}, -{-0.0342788f,0.498342f,0.0918925f},{-0.034279f,0.498342f,0.0900281f},{-0.0440377f,0.497236f,0.0900281f}, -{-0.0440376f,0.497236f,0.0918925f},{-0.05377f,0.495854f,0.0900281f},{-0.05377f,0.495854f,0.0918925f}, -{-0.0634697f,0.494196f,0.0918925f},{-0.0634706f,0.494196f,0.0900281f},{-0.0731194f,0.492264f,0.0900281f}, -{-0.0731193f,0.492264f,0.0918925f},{-0.0826996f,0.490062f,0.0900281f},{-0.0826996f,0.490062f,0.0918925f}, -{-0.0922052f,0.487593f,0.0918925f},{-0.0922054f,0.487593f,0.0900281f},{-0.101631f,0.484859f,0.0900281f}, -{-0.101631f,0.484859f,0.0918925f},{-0.110971f,0.481861f,0.0900281f},{-0.110971f,0.481861f,0.0918925f}, -{-0.120221f,0.478603f,0.0918925f},{-0.120221f,0.478602f,0.0900281f},{-0.129374f,0.475085f,0.0900281f}, -{-0.129374f,0.475085f,0.0918925f},{-0.138425f,0.47131f,0.0900281f},{-0.138425f,0.47131f,0.0918925f}, -{-0.147368f,0.46728f,0.0918925f},{-0.147369f,0.46728f,0.0900281f},{-0.156199f,0.462998f,0.0900281f}, -{-0.156199f,0.462998f,0.0918925f},{-0.164912f,0.458465f,0.0900281f},{-0.164912f,0.458465f,0.0918925f}, -{-0.173501f,0.453684f,0.0918925f},{-0.173501f,0.453684f,0.0900281f},{0.0049028f,0.5f,0.0900281f}, -{0.0147055f,0.499724f,0.0900281f},{0.0147057f,0.499724f,0.0918925f},{0.0244996f,0.499171f,0.0918925f}, -{0.0244996f,0.499171f,0.0900281f},{0.034279f,0.498342f,0.0918925f},{0.0342788f,0.498342f,0.0900281f}, -{0.0440376f,0.497236f,0.0900281f},{0.0440377f,0.497236f,0.0918925f},{0.05377f,0.495854f,0.0918925f}, -{0.05377f,0.495854f,0.0900281f},{0.0634706f,0.494196f,0.0918925f},{0.0634697f,0.494196f,0.0900281f}, -{0.0731193f,0.492264f,0.0900281f},{0.0731194f,0.492264f,0.0918925f},{0.0826996f,0.490062f,0.0918925f}, -{0.0826996f,0.490062f,0.0900281f},{0.0922054f,0.487593f,0.0918925f},{0.0922052f,0.487593f,0.0900281f}, -{0.101631f,0.484859f,0.0900281f},{0.101631f,0.484859f,0.0918925f},{0.110971f,0.481861f,0.0918925f}, -{0.110971f,0.481861f,0.0900281f},{0.120221f,0.478602f,0.0918925f},{0.120221f,0.478603f,0.0900281f}, -{0.129374f,0.475085f,0.0900281f},{0.129374f,0.475085f,0.0918925f},{0.138425f,0.47131f,0.0918925f}, -{0.138425f,0.47131f,0.0900281f},{0.147369f,0.46728f,0.0918925f},{0.147368f,0.46728f,0.0900281f}, -{0.156199f,0.462998f,0.0900281f},{0.156199f,0.462998f,0.0918925f},{0.164912f,0.458465f,0.0918925f}, -{0.164912f,0.458465f,0.0900281f},{0.173501f,0.453684f,0.0918925f},{0.173501f,0.453684f,0.0900281f}, -{-0.0200317f,0.295886f,0.0918925f},{-0.0036392f,0.280259f,0.0918925f},{-0.00474168f,0.280781f,0.0918925f}, -{-0.0152687f,0.28931f,0.0918925f},{-0.0183517f,0.29453f,0.0918925f},{-0.0057053f,0.28153f,0.0918925f}, -{-0.0130697f,0.291507f,0.0918925f},{-0.0151095f,0.289835f,0.0918925f},{-0.0173478f,0.294119f,0.0918925f}, -{-0.0109706f,0.291087f,0.0918925f},{-0.0105473f,0.290739f,0.0918925f},{-0.0192577f,0.295126f,0.0918925f}, -{-0.0206442f,0.296782f,0.0918925f},{-0.0210723f,0.297778f,0.0918925f},{-0.0101998f,0.290316f,0.0918925f}, -{-0.0140791f,0.291091f,0.0918925f},{-0.0151984f,0.293911f,0.0918925f},{-0.0145033f,0.290742f,0.0918925f}, -{0.0105451f,0.315791f,0.0918925f},{0.0101973f,0.315367f,0.0918925f},{0.0109693f,0.316139f,0.0918925f}, -{0.00977971f,0.314358f,0.0918925f},{0.00993885f,0.314883f,0.0918925f},{0.0151067f,0.314881f,0.0918925f}, -{0.0119787f,0.316555f,0.0918925f},{0.0114536f,0.316397f,0.0918925f},{0.0125242f,0.316609f,0.0918925f}, -{0.013595f,0.316394f,0.0918925f},{0.0140778f,0.316135f,0.0918925f},{0.0145011f,0.315788f,0.0918925f}, -{0.0148486f,0.315364f,0.0918925f},{0.015266f,0.314357f,0.0918925f},{-0.0148511f,0.290318f,0.0918925f}, -{-0.0162833f,0.29391f,0.0918925f},{-0.0119779f,0.291506f,0.0918925f},{-0.0125242f,0.291561f,0.0918925f}, -{-0.0114534f,0.291346f,0.0918925f},{-0.0135948f,0.291349f,0.0918925f},{-0.00994166f,0.289833f,0.0918925f}, -{0.0130705f,0.316555f,0.0918925f},{-0.00978241f,0.289309f,0.0918925f},{-0.00474296f,0.280782f,0.0900281f}, -{-0.0210725f,0.297777f,0.0900281f},{-0.020644f,0.296781f,0.0900281f},{-0.0105451f,0.290742f,0.0900281f}, -{-0.00364027f,0.280259f,0.0900281f},{-0.00993885f,0.289835f,0.0900281f},{-0.0200312f,0.295886f,0.0900281f}, -{-0.0192574f,0.295126f,0.0900281f},{-0.0162822f,0.29391f,0.0900281f},{-0.0145011f,0.290739f,0.0900281f}, -{-0.0148486f,0.290316f,0.0900281f},{-0.0125242f,0.291561f,0.0900281f},{-0.00977971f,0.28931f,0.0900281f}, -{-0.0109693f,0.291091f,0.0900281f},{-0.0101973f,0.290318f,0.0900281f},{-0.0114536f,0.291349f,0.0900281f}, -{0.0145033f,0.315791f,0.0900281f},{0.0140791f,0.316139f,0.0900281f},{0.00978241f,0.314357f,0.0900281f}, -{0.00994166f,0.314881f,0.0900281f},{-0.0183513f,0.294529f,0.0900281f},{-0.0173468f,0.294119f,0.0900281f}, -{-0.0151067f,0.289833f,0.0900281f},{-0.015266f,0.289309f,0.0900281f},{-0.0140778f,0.291087f,0.0900281f}, -{-0.0151976f,0.293911f,0.0900281f},{-0.013595f,0.291346f,0.0900281f},{-0.00570553f,0.28153f,0.0900281f}, -{0.0119779f,0.316555f,0.0900281f},{0.0101998f,0.315364f,0.0900281f},{0.0125242f,0.316609f,0.0900281f}, -{0.0130697f,0.316555f,0.0900281f},{0.0135948f,0.316397f,0.0900281f},{0.0148511f,0.315367f,0.0900281f}, -{0.0151095f,0.314883f,0.0900281f},{0.0109706f,0.316135f,0.0900281f},{0.0152687f,0.314358f,0.0900281f}, -{0.0114534f,0.316394f,0.0900281f},{0.0105473f,0.315788f,0.0900281f},{-0.0119787f,0.291507f,0.0900281f}, -{-0.0130705f,0.291506f,0.0900281f},{0.0125242f,-0.285968f,0.0900281f},{0.0130723f,-0.286022f,0.0918925f}, -{0.0125242f,-0.285968f,0.0918925f},{0.011454f,-0.286181f,0.0918925f},{0.011454f,-0.286181f,0.0900281f}, -{0.0119761f,-0.286022f,0.0918925f},{0.0119761f,-0.286022f,0.0900281f},{0.0109726f,-0.286438f,0.0900281f}, -{0.0105467f,-0.286787f,0.0900281f},{0.0105467f,-0.286787f,0.0918925f},{0.0101975f,-0.287213f,0.0900281f}, -{0.0101975f,-0.287213f,0.0918925f},{0.0109726f,-0.286438f,0.0918925f},{0.00972758f,-0.288764f,0.0900281f}, -{0.00978182f,-0.288216f,0.0900281f},{0.00978182f,-0.288216f,0.0918925f},{0.00994047f,-0.287694f,0.0918925f}, -{0.00994047f,-0.287694f,0.0900281f},{0.00972758f,-0.288764f,0.0918925f},{0.0130723f,-0.286022f,0.0900281f}, -{0.0135944f,-0.286181f,0.0918925f},{0.0135944f,-0.286181f,0.0900281f},{0.0140758f,-0.286438f,0.0900281f}, -{0.0140758f,-0.286438f,0.0918925f},{0.0145017f,-0.286787f,0.0900281f},{0.0145017f,-0.286787f,0.0918925f}, -{0.0148509f,-0.287213f,0.0918925f},{0.0148509f,-0.287213f,0.0900281f},{0.0151079f,-0.287694f,0.0900281f}, -{0.0151079f,-0.287694f,0.0918925f},{0.0152666f,-0.288216f,0.0900281f},{0.0152666f,-0.288216f,0.0918925f}, -{0.0153208f,-0.288764f,0.0918925f},{0.0153208f,-0.288764f,0.0900281f},{-0.0125242f,-0.311016f,0.0900281f}, -{-0.0119761f,-0.31107f,0.0918925f},{-0.0125242f,-0.311016f,0.0918925f},{-0.0135944f,-0.311229f,0.0918925f}, -{-0.0135944f,-0.311229f,0.0900281f},{-0.0130723f,-0.31107f,0.0918925f},{-0.0130723f,-0.31107f,0.0900281f}, -{-0.0140758f,-0.311486f,0.0900281f},{-0.0145017f,-0.311835f,0.0900281f},{-0.0145017f,-0.311835f,0.0918925f}, -{-0.0148509f,-0.312261f,0.0900281f},{-0.0148509f,-0.312261f,0.0918925f},{-0.0140758f,-0.311486f,0.0918925f}, -{-0.0153208f,-0.313813f,0.0900281f},{-0.0152666f,-0.313265f,0.0900281f},{-0.0152666f,-0.313265f,0.0918925f}, -{-0.0151079f,-0.312743f,0.0918925f},{-0.0151079f,-0.312743f,0.0900281f},{-0.0153208f,-0.313813f,0.0918925f}, -{-0.0119761f,-0.31107f,0.0900281f},{-0.011454f,-0.311229f,0.0918925f},{-0.011454f,-0.311229f,0.0900281f}, -{-0.0109726f,-0.311486f,0.0900281f},{-0.0109726f,-0.311486f,0.0918925f},{-0.0105467f,-0.311835f,0.0900281f}, -{-0.0105467f,-0.311835f,0.0918925f},{-0.0101975f,-0.312261f,0.0918925f},{-0.0101975f,-0.312261f,0.0900281f}, -{-0.00994047f,-0.312743f,0.0900281f},{-0.00994047f,-0.312743f,0.0918925f},{-0.00978182f,-0.313265f,0.0900281f}, -{-0.00978182f,-0.313265f,0.0918925f},{-0.00972758f,-0.313813f,0.0918925f},{-0.00972758f,-0.313813f,0.0900281f}, -{0.0073455f,-0.284736f,0.0900281f},{0.00738926f,-0.285954f,0.0918925f},{0.00734538f,-0.284736f,0.0918925f}, -{0.00703877f,-0.283556f,0.0900281f},{0.0070384f,-0.283555f,0.0918925f},{0.00648281f,-0.28247f,0.0900281f}, -{0.00648282f,-0.28247f,0.0918925f},{0.00738915f,-0.285956f,0.0900281f},{0.00716427f,-0.287154f,0.0918925f}, -{0.00716427f,-0.287154f,0.0900281f},{-0.00856857f,-0.309858f,0.0918925f},{-0.0078732f,-0.310706f,0.0918925f}, -{-0.00856991f,-0.309857f,0.0900281f},{-0.00787361f,-0.310705f,0.0900281f},{-0.0073566f,-0.311673f,0.0918925f}, -{-0.00703838f,-0.312722f,0.0918925f},{-0.00735691f,-0.311672f,0.0900281f},{-0.00693097f,-0.313813f,0.0918925f}, -{-0.00703853f,-0.312721f,0.0900281f},{-0.00693097f,-0.313813f,0.0900281f},{-0.00941743f,-0.309162f,0.0900281f}, -{-0.0103841f,-0.308645f,0.0900281f},{-0.00941663f,-0.309162f,0.0918925f},{-0.0114331f,-0.308327f,0.0900281f}, -{-0.0103834f,-0.308645f,0.0918925f},{-0.0114326f,-0.308327f,0.0918925f},{-0.0125242f,-0.30822f,0.0900281f}, -{-0.0125242f,-0.30822f,0.0918925f},{0.065917f,-0.401959f,0.0918925f},{0.0617984f,-0.398048f,0.0918925f}, -{0.0659174f,-0.40196f,0.0900281f},{0.07019f,-0.405692f,0.0900281f},{0.0701898f,-0.405691f,0.0918925f}, -{0.0746077f,-0.409237f,0.0900281f},{0.0746076f,-0.409237f,0.0918925f},{0.0791643f,-0.412592f,0.0918925f}, -{0.0791644f,-0.412592f,0.0900281f},{0.0838538f,-0.415754f,0.0900281f},{0.0838537f,-0.415754f,0.0918925f}, -{0.0886696f,-0.418717f,0.0900281f},{0.0886696f,-0.418717f,0.0918925f},{0.0936056f,-0.421479f,0.0918925f}, -{0.0936057f,-0.421479f,0.0900281f},{0.0986557f,-0.424035f,0.0900281f},{0.0986556f,-0.424035f,0.0918925f}, -{0.103813f,-0.426382f,0.0900281f},{0.103813f,-0.426382f,0.0918925f},{0.109072f,-0.428515f,0.0918925f}, -{0.109073f,-0.428515f,0.0900281f},{0.11442f,-0.430428f,0.0900281f},{0.11442f,-0.430428f,0.0918925f}, -{0.119834f,-0.432114f,0.0900281f},{0.119834f,-0.432114f,0.0918925f},{0.125306f,-0.433572f,0.0918925f}, -{0.125307f,-0.433572f,0.0900281f},{0.130829f,-0.4348f,0.0900281f},{0.130829f,-0.4348f,0.0918925f}, -{0.136396f,-0.435797f,0.0900281f},{0.136396f,-0.435797f,0.0918925f},{0.141999f,-0.436561f,0.0918925f}, -{0.141999f,-0.436561f,0.0900281f},{0.147631f,-0.437093f,0.0900281f},{0.147631f,-0.437093f,0.0918925f}, -{0.153284f,-0.437391f,0.0900281f},{0.153284f,-0.437391f,0.0918925f},{0.158952f,-0.437453f,0.0918925f}, -{0.158952f,-0.437453f,0.0900281f},{0.164627f,-0.437279f,0.0900281f},{0.164627f,-0.437279f,0.0918925f}, -{0.0617987f,-0.398048f,0.0900281f},{0.0578515f,-0.393973f,0.0900281f},{0.0578514f,-0.393973f,0.0918925f}, -{0.054083f,-0.389744f,0.0918925f},{0.0540831f,-0.389744f,0.0900281f},{0.0504973f,-0.385366f,0.0918925f}, -{0.0504974f,-0.385366f,0.0900281f},{0.0470986f,-0.380846f,0.0900281f},{0.0470985f,-0.380846f,0.0918925f}, -{0.0438908f,-0.376189f,0.0918925f},{0.0438908f,-0.376189f,0.0900281f},{0.0408784f,-0.371402f,0.0918925f}, -{0.0408785f,-0.371402f,0.0900281f},{0.0380656f,-0.36649f,0.0900281f},{0.0380655f,-0.36649f,0.0918925f}, -{0.0354565f,-0.36146f,0.0918925f},{0.0354565f,-0.36146f,0.0900281f},{0.0330551f,-0.356317f,0.0918925f}, -{0.0330554f,-0.356318f,0.0900281f},{0.0308688f,-0.351076f,0.0900281f},{0.0308688f,-0.351076f,0.0918925f}, -{0.0289059f,-0.345756f,0.0918925f},{0.0289059f,-0.345756f,0.0900281f},{0.0271683f,-0.340366f,0.0918925f}, -{0.0271684f,-0.340366f,0.0900281f},{0.0256577f,-0.334914f,0.0900281f},{0.0256577f,-0.334914f,0.0918925f}, -{0.0243753f,-0.329406f,0.0918925f},{0.0243754f,-0.329406f,0.0900281f},{0.0233228f,-0.32385f,0.0918925f}, -{0.0233228f,-0.32385f,0.0900281f},{0.0225016f,-0.318253f,0.0900281f},{0.0225016f,-0.318253f,0.0918925f}, -{0.0219132f,-0.312622f,0.0918925f},{0.0219132f,-0.312623f,0.0900281f},{0.0215591f,-0.306965f,0.0918925f}, -{0.0215591f,-0.306965f,0.0900281f},{0.0214407f,-0.301289f,0.0918925f},{0.0214407f,-0.301289f,0.0900281f}, -{0.0214056f,-0.300061f,0.0918925f},{0.0214056f,-0.300061f,0.0900281f},{0.0213002f,-0.298838f,0.0900281f}, -{0.0213002f,-0.298838f,0.0918925f},{0.00857005f,-0.29272f,0.0900281f},{0.00933952f,-0.293362f,0.0900281f}, -{0.00856812f,-0.292718f,0.0918925f},{0.0102104f,-0.293856f,0.0918925f},{0.00933867f,-0.293362f,0.0918925f}, -{0.010212f,-0.293857f,0.0900281f},{0.0111572f,-0.294188f,0.0918925f},{0.0111588f,-0.294188f,0.0900281f}, -{0.0121484f,-0.294345f,0.0918925f},{0.0131504f,-0.294322f,0.0918925f},{0.0121494f,-0.294345f,0.0900281f}, -{0.0141339f,-0.294121f,0.0900281f},{0.0131516f,-0.294322f,0.0900281f},{0.0141339f,-0.294121f,0.0918925f}, -{0.00792586f,-0.291949f,0.0918925f},{0.00792654f,-0.29195f,0.0900281f},{0.00743177f,-0.291078f,0.0900281f}, -{0.00710074f,-0.290131f,0.0900281f},{0.00743116f,-0.291076f,0.0918925f},{0.00710007f,-0.290129f,0.0918925f}, -{0.00694354f,-0.28914f,0.0900281f},{0.00694356f,-0.289139f,0.0918925f},{0.00696625f,-0.288138f,0.0900281f}, -{0.00696632f,-0.288136f,0.0918925f},{-0.0121669f,-0.283634f,0.0900281f},{-0.0102959f,-0.282482f,0.0900281f}, -{-0.0102961f,-0.282482f,0.0918925f},{-0.012167f,-0.283634f,0.0918925f},{-0.013914f,-0.284976f,0.0900281f}, -{-0.008319f,-0.281528f,0.0918925f},{-0.00831882f,-0.281527f,0.0900281f},{-0.00625128f,-0.280779f,0.0918925f}, -{-0.00625078f,-0.280779f,0.0900281f},{-0.00411456f,-0.280246f,0.0918925f},{-0.00411435f,-0.280246f,0.0900281f}, -{-0.00194003f,-0.279936f,0.0900281f},{-0.0019402f,-0.279936f,0.0918925f},{0.000253827f,-0.279849f,0.0918925f}, -{0.00245022f,-0.279988f,0.0918925f},{0.00025393f,-0.279849f,0.0900281f},{0.00245022f,-0.279988f,0.0900281f}, -{-0.0155106f,-0.286486f,0.0900281f},{-0.0139141f,-0.284976f,0.0918925f},{-0.0155107f,-0.286486f,0.0918925f}, -{-0.016943f,-0.288149f,0.0900281f},{-0.0169431f,-0.28815f,0.0918925f},{-0.0181996f,-0.289954f,0.0900281f}, -{-0.0192663f,-0.29188f,0.0900281f},{-0.0181999f,-0.289954f,0.0918925f},{-0.0192664f,-0.291881f,0.0918925f}, -{-0.0201277f,-0.293901f,0.0900281f},{-0.0201278f,-0.293901f,0.0918925f},{-0.0207778f,-0.295998f,0.0900281f}, -{-0.0212106f,-0.298156f,0.0900281f},{-0.0207778f,-0.295998f,0.0918925f},{-0.0212106f,-0.298156f,0.0918925f}, -{-0.0200545f,-0.303955f,0.0900281f},{-0.0207145f,-0.302604f,0.0918925f},{-0.020054f,-0.303956f,0.0918925f}, -{-0.0191712f,-0.305176f,0.0900281f},{-0.0207149f,-0.302603f,0.0900281f},{-0.0211353f,-0.301156f,0.0918925f}, -{-0.0191712f,-0.305176f,0.0918925f},{-0.0211356f,-0.301155f,0.0900281f},{-0.021302f,-0.29966f,0.0918925f}, -{-0.0213021f,-0.299659f,0.0900281f},{-0.0180928f,-0.306228f,0.0900281f},{-0.018092f,-0.306229f,0.0918925f}, -{-0.0168512f,-0.307079f,0.0918925f},{-0.0168521f,-0.307079f,0.0900281f},{-0.0154797f,-0.307707f,0.0918925f}, -{-0.0154807f,-0.307707f,0.0900281f},{-0.0140259f,-0.30809f,0.0900281f},{-0.014025f,-0.30809f,0.0918925f}, -{-0.00703853f,-0.314904f,0.0918925f},{-0.00856991f,-0.317768f,0.0918925f},{-0.0078732f,-0.31692f,0.0900281f}, -{-0.00787361f,-0.31692f,0.0918925f},{-0.00735691f,-0.315954f,0.0918925f},{-0.0073566f,-0.315953f,0.0900281f}, -{-0.00703838f,-0.314904f,0.0900281f},{-0.0103834f,-0.31898f,0.0900281f},{-0.0103841f,-0.31898f,0.0918925f}, -{-0.0114331f,-0.319299f,0.0918925f},{-0.00856857f,-0.317767f,0.0900281f},{-0.00941743f,-0.318464f,0.0918925f}, -{-0.00941663f,-0.318463f,0.0900281f},{-0.0125242f,-0.319406f,0.0918925f},{-0.0114326f,-0.319298f,0.0900281f}, -{-0.0125242f,-0.319406f,0.0900281f},{-0.017806f,-0.32063f,0.0900281f},{-0.0178073f,-0.32063f,0.0918925f}, -{-0.0193785f,-0.321554f,0.0900281f},{-0.0193787f,-0.321554f,0.0918925f},{-0.0161135f,-0.319955f,0.0918925f}, -{-0.0161128f,-0.319955f,0.0900281f},{-0.0143418f,-0.319544f,0.0900281f},{-0.0143423f,-0.319544f,0.0918925f}, -{-0.0207886f,-0.322701f,0.0900281f},{-0.0220123f,-0.324052f,0.0900281f},{-0.0207888f,-0.322701f,0.0918925f}, -{-0.0220132f,-0.324053f,0.0918925f},{-0.023018f,-0.325573f,0.0900281f},{-0.0230183f,-0.325573f,0.0918925f}, -{-0.02378f,-0.327224f,0.0900281f},{-0.0242851f,-0.328976f,0.0900281f},{-0.0237802f,-0.327224f,0.0918925f}, -{-0.0242851f,-0.328976f,0.0918925f},{-0.0744192f,-0.409092f,0.0918925f},{-0.0744192f,-0.409092f,0.0900281f}, -{-0.0700077f,-0.405539f,0.0900281f},{-0.065746f,-0.401803f,0.0900281f},{-0.0700077f,-0.405539f,0.0918925f}, -{-0.06164f,-0.397891f,0.0900281f},{-0.0657461f,-0.401803f,0.0918925f},{-0.0616401f,-0.397891f,0.0918925f}, -{-0.0576956f,-0.393805f,0.0900281f},{-0.0539185f,-0.389551f,0.0900281f},{-0.0576957f,-0.393805f,0.0918925f}, -{-0.0503158f,-0.385134f,0.0900281f},{-0.0539186f,-0.389551f,0.0918925f},{-0.050316f,-0.385135f,0.0918925f}, -{-0.0469052f,-0.380577f,0.0900281f},{-0.0436939f,-0.375889f,0.0900281f},{-0.0469052f,-0.380577f,0.0918925f}, -{-0.0406851f,-0.371079f,0.0900281f},{-0.0436939f,-0.375889f,0.0918925f},{-0.0406851f,-0.371079f,0.0918925f}, -{-0.0378819f,-0.366152f,0.0900281f},{-0.0352877f,-0.361116f,0.0900281f},{-0.037882f,-0.366152f,0.0918925f}, -{-0.0329054f,-0.355977f,0.0900281f},{-0.0352877f,-0.361116f,0.0918925f},{-0.0329055f,-0.355977f,0.0918925f}, -{-0.0307383f,-0.350742f,0.0900281f},{-0.0287896f,-0.345418f,0.0900281f},{-0.0307384f,-0.350742f,0.0918925f}, -{-0.0270624f,-0.340011f,0.0900281f},{-0.0287897f,-0.345418f,0.0918925f},{-0.0270624f,-0.340011f,0.0918925f}, -{-0.0255598f,-0.334528f,0.0900281f},{-0.0255599f,-0.334528f,0.0918925f},{-0.0789746f,-0.412458f,0.0918925f}, -{-0.0789746f,-0.412458f,0.0900281f},{-0.0836681f,-0.415634f,0.0918925f},{-0.0884938f,-0.418614f,0.0918925f}, -{-0.083668f,-0.415634f,0.0900281f},{-0.0934459f,-0.421394f,0.0918925f},{-0.0884937f,-0.418614f,0.0900281f}, -{-0.0934458f,-0.421394f,0.0900281f},{-0.0985185f,-0.423969f,0.0918925f},{-0.103704f,-0.426335f,0.0918925f}, -{-0.0985183f,-0.423969f,0.0900281f},{-0.108978f,-0.428478f,0.0918925f},{-0.103704f,-0.426334f,0.0900281f}, -{-0.108977f,-0.428478f,0.0900281f},{-0.114326f,-0.430397f,0.0918925f},{-0.119742f,-0.432088f,0.0918925f}, -{-0.114326f,-0.430397f,0.0900281f},{-0.125218f,-0.43355f,0.0918925f},{-0.119742f,-0.432088f,0.0900281f}, -{-0.125218f,-0.43355f,0.0900281f},{-0.130747f,-0.434783f,0.0918925f},{-0.136322f,-0.435785f,0.0918925f}, -{-0.130747f,-0.434783f,0.0900281f},{-0.141936f,-0.436554f,0.0918925f},{-0.136322f,-0.435785f,0.0900281f}, -{-0.141935f,-0.436554f,0.0900281f},{-0.14758f,-0.43709f,0.0918925f},{-0.153248f,-0.43739f,0.0918925f}, -{-0.14758f,-0.43709f,0.0900281f},{-0.158933f,-0.437453f,0.0918925f},{-0.153248f,-0.43739f,0.0900281f}, -{-0.158933f,-0.437453f,0.0900281f},{-0.164627f,-0.437279f,0.0918925f},{-0.164627f,-0.437279f,0.0900281f}, -{-0.169288f,-0.445352f,0.0900281f},{-0.169288f,-0.445352f,0.0918925f},{-0.0239114f,-0.489867f,0.0918925f}, -{-0.0143525f,-0.490408f,0.0918925f},{-0.0143527f,-0.490408f,0.0900281f},{0.00478512f,-0.490679f,0.0900281f}, -{-0.00478519f,-0.490679f,0.0900281f},{-0.00478512f,-0.490679f,0.0918925f},{-0.0239115f,-0.489867f,0.0900281f}, -{-0.0334558f,-0.489056f,0.0918925f},{-0.0334558f,-0.489056f,0.0900281f},{-0.0429801f,-0.487973f,0.0900281f}, -{-0.04298f,-0.487973f,0.0918925f},{-0.0524782f,-0.486621f,0.0918925f},{-0.0524784f,-0.486621f,0.0900281f}, -{-0.0619436f,-0.484998f,0.0900281f},{-0.0619434f,-0.484998f,0.0918925f},{-0.0806965f,-0.480955f,0.0900281f}, -{-0.089968f,-0.47854f,0.0900281f},{-0.0899679f,-0.47854f,0.0918925f},{-0.0713532f,-0.483109f,0.0918925f}, -{-0.0713532f,-0.483109f,0.0900281f},{-0.0806964f,-0.480955f,0.0918925f},{-0.0991622f,-0.475866f,0.0918925f}, -{-0.0991623f,-0.475866f,0.0900281f},{-0.108274f,-0.472933f,0.0900281f},{-0.108274f,-0.472933f,0.0918925f}, -{-0.117298f,-0.469745f,0.0918925f},{-0.117298f,-0.469745f,0.0900281f},{-0.126228f,-0.466302f,0.0918925f}, -{-0.143787f,-0.458664f,0.0900281f},{-0.143786f,-0.458664f,0.0918925f},{-0.135059f,-0.462608f,0.0900281f}, -{-0.135059f,-0.462608f,0.0918925f},{-0.126228f,-0.466302f,0.0900281f},{-0.152404f,-0.454472f,0.0900281f}, -{-0.152404f,-0.454472f,0.0918925f},{-0.160907f,-0.450034f,0.0900281f},{-0.160906f,-0.450034f,0.0918925f}, -{0.00478519f,-0.490679f,0.0918925f},{0.0143525f,-0.490408f,0.0900281f},{0.0143527f,-0.490408f,0.0918925f}, -{0.0239114f,-0.489867f,0.0900281f},{0.0334558f,-0.489056f,0.0900281f},{0.0239115f,-0.489867f,0.0918925f}, -{0.0334558f,-0.489056f,0.0918925f},{0.04298f,-0.487973f,0.0900281f},{0.0429801f,-0.487973f,0.0918925f}, -{0.0524782f,-0.486621f,0.0900281f},{0.0619434f,-0.484998f,0.0900281f},{0.0524784f,-0.486621f,0.0918925f}, -{0.0619436f,-0.484998f,0.0918925f},{0.0713532f,-0.483109f,0.0900281f},{0.0713532f,-0.483109f,0.0918925f}, -{0.0806964f,-0.480955f,0.0900281f},{0.0899679f,-0.47854f,0.0900281f},{0.0806965f,-0.480955f,0.0918925f}, -{0.089968f,-0.47854f,0.0918925f},{0.0991622f,-0.475866f,0.0900281f},{0.0991623f,-0.475866f,0.0918925f}, -{0.108274f,-0.472933f,0.0900281f},{0.117298f,-0.469745f,0.0900281f},{0.108274f,-0.472933f,0.0918925f}, -{0.117298f,-0.469745f,0.0918925f},{0.126228f,-0.466302f,0.0900281f},{0.126228f,-0.466302f,0.0918925f}, -{0.135059f,-0.462608f,0.0900281f},{0.143786f,-0.458664f,0.0900281f},{0.135059f,-0.462608f,0.0918925f}, -{0.143787f,-0.458664f,0.0918925f},{0.152404f,-0.454472f,0.0900281f},{0.152404f,-0.454472f,0.0918925f}, -{0.160906f,-0.450034f,0.0900281f},{0.169288f,-0.445352f,0.0900281f},{0.160907f,-0.450034f,0.0918925f}, -{0.169288f,-0.445352f,0.0918925f},{-0.169776f,-0.427553f,0.0918925f},{-0.18196f,-0.448656f,0.0900281f}, -{-0.18196f,-0.448656f,0.0918925f},{-0.169776f,-0.427553f,0.0900281f},{-0.0785294f,-0.400468f,0.0900281f}, -{-0.0828396f,-0.403757f,0.0900281f},{-0.0828395f,-0.403757f,0.0918925f},{-0.0743574f,-0.396993f,0.0900281f}, -{-0.074357f,-0.396993f,0.0918925f},{-0.0703325f,-0.393337f,0.0900281f},{-0.0872815f,-0.406855f,0.0918925f}, -{-0.0785292f,-0.400468f,0.0918925f},{-0.0872816f,-0.406855f,0.0900281f},{-0.0918488f,-0.409759f,0.0918925f}, -{-0.091849f,-0.409759f,0.0900281f},{-0.0965352f,-0.412465f,0.0900281f},{-0.0965352f,-0.412465f,0.0918925f}, -{-0.101334f,-0.41497f,0.0918925f},{-0.101334f,-0.41497f,0.0900281f},{-0.106239f,-0.417269f,0.0900281f}, -{-0.111243f,-0.419359f,0.0918925f},{-0.106239f,-0.417269f,0.0918925f},{-0.111243f,-0.419359f,0.0900281f}, -{-0.116342f,-0.421236f,0.0900281f},{-0.116341f,-0.421236f,0.0918925f},{-0.132038f,-0.425533f,0.0918925f}, -{-0.126754f,-0.424327f,0.0900281f},{-0.132038f,-0.425533f,0.0900281f},{-0.121519f,-0.422894f,0.0918925f}, -{-0.121519f,-0.422894f,0.0900281f},{-0.126754f,-0.424327f,0.0918925f},{-0.137363f,-0.426511f,0.0918925f}, -{-0.142723f,-0.427261f,0.0918925f},{-0.137364f,-0.426511f,0.0900281f},{-0.142723f,-0.427261f,0.0900281f}, -{-0.14811f,-0.427781f,0.0900281f},{-0.153516f,-0.428071f,0.0900281f},{-0.153516f,-0.428071f,0.0918925f}, -{-0.14811f,-0.427781f,0.0918925f},{-0.158934f,-0.428131f,0.0900281f},{-0.158934f,-0.428131f,0.0918925f}, -{-0.164357f,-0.427958f,0.0900281f},{-0.164356f,-0.427958f,0.0918925f},{-0.0664729f,-0.389518f,0.0900281f}, -{-0.0703321f,-0.393337f,0.0918925f},{-0.0664728f,-0.389518f,0.0918925f},{-0.0627861f,-0.385543f,0.0900281f}, -{-0.0627861f,-0.385543f,0.0918925f},{-0.0592762f,-0.381418f,0.0900281f},{-0.0559475f,-0.37715f,0.0900281f}, -{-0.0592761f,-0.381418f,0.0918925f},{-0.0559474f,-0.37715f,0.0918925f},{-0.0528044f,-0.372745f,0.0900281f}, -{-0.0528044f,-0.372745f,0.0918925f},{-0.0498513f,-0.368209f,0.0900281f},{-0.0470924f,-0.363547f,0.0900281f}, -{-0.0498511f,-0.368209f,0.0918925f},{-0.0470923f,-0.363547f,0.0918925f},{-0.0445321f,-0.358766f,0.0900281f}, -{-0.0445321f,-0.358766f,0.0918925f},{-0.042175f,-0.353872f,0.0900281f},{-0.0400276f,-0.348877f,0.0900281f}, -{-0.0421746f,-0.353871f,0.0918925f},{-0.0400276f,-0.348877f,0.0918925f},{-0.0380996f,-0.343803f,0.0900281f}, -{-0.0380996f,-0.343803f,0.0918925f},{-0.0363926f,-0.338659f,0.0900281f},{-0.0349082f,-0.333452f,0.0900281f}, -{-0.0363926f,-0.338659f,0.0918925f},{-0.0349082f,-0.333452f,0.0918925f},{-0.033648f,-0.328189f,0.0900281f}, -{-0.0336479f,-0.328189f,0.0918925f},{-0.0326134f,-0.322877f,0.0900281f},{-0.031806f,-0.317524f,0.0900281f}, -{-0.0326134f,-0.322877f,0.0918925f},{-0.031806f,-0.317524f,0.0918925f},{-0.0312275f,-0.312137f,0.0900281f}, -{-0.0312274f,-0.312136f,0.0918925f},{-0.0308792f,-0.306722f,0.0900281f},{-0.0307628f,-0.301289f,0.0900281f}, -{-0.0308792f,-0.306722f,0.0918925f},{-0.0307628f,-0.301289f,0.0918925f},{-2.84358e-015f,-0.270526f,0.0918925f}, -{-2.91313e-015f,-0.270526f,0.0900281f},{-0.00166887f,-0.270571f,0.0900281f},{-0.0033296f,-0.270707f,0.0900281f}, -{-0.00166875f,-0.270571f,0.0918925f},{-0.00497861f,-0.270931f,0.0900281f},{-0.00332938f,-0.270706f,0.0918925f}, -{-0.00497832f,-0.270931f,0.0918925f},{-0.00661229f,-0.271245f,0.0900281f},{-0.00822706f,-0.271646f,0.0900281f}, -{-0.00661197f,-0.271245f,0.0918925f},{-0.00981931f,-0.272135f,0.0900281f},{-0.00822672f,-0.271646f,0.0918925f}, -{-0.009819f,-0.272135f,0.0918925f},{-0.0113858f,-0.27271f,0.0900281f},{-0.0129196f,-0.27337f,0.0900281f}, -{-0.0113852f,-0.27271f,0.0918925f},{-0.0144128f,-0.274111f,0.0900281f},{-0.0129192f,-0.27337f,0.0918925f}, -{-0.0144127f,-0.274111f,0.0918925f},{-0.0158618f,-0.27493f,0.0900281f},{-0.0172635f,-0.275826f,0.0900281f}, -{-0.0158617f,-0.27493f,0.0918925f},{-0.0186148f,-0.276797f,0.0900281f},{-0.0172633f,-0.275826f,0.0918925f}, -{-0.0186146f,-0.276797f,0.0918925f},{-0.0199127f,-0.27784f,0.0900281f},{-0.0211544f,-0.278954f,0.0900281f}, -{-0.0199124f,-0.27784f,0.0918925f},{-0.0223352f,-0.280135f,0.0900281f},{-0.0211538f,-0.278953f,0.0918925f}, -{-0.0223347f,-0.280134f,0.0918925f},{-0.0234487f,-0.281376f,0.0900281f},{-0.0244917f,-0.282674f,0.0900281f}, -{-0.0234485f,-0.281376f,0.0918925f},{-0.0254622f,-0.284025f,0.0900281f},{-0.0244916f,-0.282674f,0.0918925f}, -{-0.0254621f,-0.284025f,0.0918925f},{-0.0263582f,-0.285427f,0.0900281f},{-0.0271776f,-0.286876f,0.0900281f}, -{-0.0263581f,-0.285427f,0.0918925f},{-0.0279185f,-0.288369f,0.0900281f},{-0.0271775f,-0.286876f,0.0918925f}, -{-0.0279183f,-0.288369f,0.0918925f},{-0.0285784f,-0.289903f,0.0900281f},{-0.0291536f,-0.29147f,0.0900281f}, -{-0.0285781f,-0.289903f,0.0918925f},{-0.0296423f,-0.293062f,0.0900281f},{-0.0291535f,-0.291469f,0.0918925f}, -{-0.0296423f,-0.293061f,0.0918925f},{-0.0300438f,-0.294677f,0.0900281f},{-0.0303573f,-0.29631f,0.0900281f}, -{-0.0300437f,-0.294676f,0.0918925f},{-0.0305821f,-0.297959f,0.0900281f},{-0.0303572f,-0.29631f,0.0918925f}, -{-0.030582f,-0.297959f,0.0918925f},{-0.0307175f,-0.29962f,0.0900281f},{-0.0307174f,-0.29962f,0.0918925f}, -{0.00166887f,-0.270571f,0.0918925f},{0.00166875f,-0.270571f,0.0900281f},{0.0033296f,-0.270707f,0.0918925f}, -{0.00497861f,-0.270931f,0.0918925f},{0.00332938f,-0.270706f,0.0900281f},{0.00661229f,-0.271245f,0.0918925f}, -{0.00497832f,-0.270931f,0.0900281f},{0.00661197f,-0.271245f,0.0900281f},{0.00822706f,-0.271646f,0.0918925f}, -{0.00981931f,-0.272135f,0.0918925f},{0.00822672f,-0.271646f,0.0900281f},{0.0113858f,-0.27271f,0.0918925f}, -{0.009819f,-0.272135f,0.0900281f},{0.0113852f,-0.27271f,0.0900281f},{0.0129196f,-0.27337f,0.0918925f}, -{0.0144128f,-0.274111f,0.0918925f},{0.0129192f,-0.27337f,0.0900281f},{0.0158618f,-0.27493f,0.0918925f}, -{0.0144127f,-0.274111f,0.0900281f},{0.0158617f,-0.27493f,0.0900281f},{0.0172635f,-0.275826f,0.0918925f}, -{0.0186148f,-0.276797f,0.0918925f},{0.0172633f,-0.275826f,0.0900281f},{0.0199127f,-0.27784f,0.0918925f}, -{0.0186146f,-0.276797f,0.0900281f},{0.0199124f,-0.27784f,0.0900281f},{0.0211544f,-0.278954f,0.0918925f}, -{0.0223352f,-0.280135f,0.0918925f},{0.0211538f,-0.278953f,0.0900281f},{0.0234487f,-0.281376f,0.0918925f}, -{0.0223347f,-0.280134f,0.0900281f},{0.0234485f,-0.281376f,0.0900281f},{0.0244917f,-0.282674f,0.0918925f}, -{0.0254622f,-0.284025f,0.0918925f},{0.0244916f,-0.282674f,0.0900281f},{0.0263582f,-0.285427f,0.0918925f}, -{0.0254621f,-0.284025f,0.0900281f},{0.0263581f,-0.285427f,0.0900281f},{0.0271776f,-0.286876f,0.0918925f}, -{0.0279185f,-0.288369f,0.0918925f},{0.0271775f,-0.286876f,0.0900281f},{0.0285784f,-0.289903f,0.0918925f}, -{0.0279183f,-0.288369f,0.0900281f},{0.0285781f,-0.289903f,0.0900281f},{0.0291536f,-0.29147f,0.0918925f}, -{0.0296423f,-0.293062f,0.0918925f},{0.0291535f,-0.291469f,0.0900281f},{0.0300438f,-0.294677f,0.0918925f}, -{0.0296423f,-0.293061f,0.0900281f},{0.0300437f,-0.294676f,0.0900281f},{0.0303573f,-0.29631f,0.0918925f}, -{0.0305821f,-0.297959f,0.0918925f},{0.0303572f,-0.29631f,0.0900281f},{0.0307175f,-0.29962f,0.0918925f}, -{0.030582f,-0.297959f,0.0900281f},{0.0307174f,-0.29962f,0.0900281f},{0.0307628f,-0.301289f,0.0918925f}, -{0.0307628f,-0.301289f,0.0900281f},{0.0664728f,-0.389518f,0.0900281f},{0.0627861f,-0.385543f,0.0900281f}, -{0.0627861f,-0.385543f,0.0918925f},{0.0703321f,-0.393337f,0.0900281f},{0.0703325f,-0.393337f,0.0918925f}, -{0.074357f,-0.396993f,0.0900281f},{0.0592762f,-0.381418f,0.0918925f},{0.0664729f,-0.389518f,0.0918925f}, -{0.0592761f,-0.381418f,0.0900281f},{0.0559475f,-0.37715f,0.0918925f},{0.0559474f,-0.37715f,0.0900281f}, -{0.0528044f,-0.372745f,0.0900281f},{0.0528044f,-0.372745f,0.0918925f},{0.0498513f,-0.368209f,0.0918925f}, -{0.0498511f,-0.368209f,0.0900281f},{0.0470923f,-0.363547f,0.0900281f},{0.0445321f,-0.358766f,0.0918925f}, -{0.0470924f,-0.363547f,0.0918925f},{0.0445321f,-0.358766f,0.0900281f},{0.0421746f,-0.353871f,0.0900281f}, -{0.042175f,-0.353872f,0.0918925f},{0.0363926f,-0.338659f,0.0918925f},{0.0380996f,-0.343803f,0.0900281f}, -{0.0363926f,-0.338659f,0.0900281f},{0.0400276f,-0.348877f,0.0918925f},{0.0400276f,-0.348877f,0.0900281f}, -{0.0380996f,-0.343803f,0.0918925f},{0.0349082f,-0.333452f,0.0918925f},{0.033648f,-0.328189f,0.0918925f}, -{0.0349082f,-0.333452f,0.0900281f},{0.0336479f,-0.328189f,0.0900281f},{0.0326134f,-0.322877f,0.0900281f}, -{0.031806f,-0.317524f,0.0900281f},{0.031806f,-0.317524f,0.0918925f},{0.0326134f,-0.322877f,0.0918925f}, -{0.0312274f,-0.312136f,0.0900281f},{0.0312275f,-0.312137f,0.0918925f},{0.0308792f,-0.306722f,0.0900281f}, -{0.0308792f,-0.306722f,0.0918925f},{0.0785292f,-0.400468f,0.0900281f},{0.0743574f,-0.396993f,0.0918925f}, -{0.0785294f,-0.400468f,0.0918925f},{0.0828395f,-0.403757f,0.0900281f},{0.0828396f,-0.403757f,0.0918925f}, -{0.0872815f,-0.406855f,0.0900281f},{0.0918488f,-0.409759f,0.0900281f},{0.0872816f,-0.406855f,0.0918925f}, -{0.091849f,-0.409759f,0.0918925f},{0.0965352f,-0.412465f,0.0900281f},{0.0965352f,-0.412465f,0.0918925f}, -{0.101334f,-0.41497f,0.0900281f},{0.106239f,-0.417269f,0.0900281f},{0.101334f,-0.41497f,0.0918925f}, -{0.106239f,-0.417269f,0.0918925f},{0.111243f,-0.419359f,0.0900281f},{0.111243f,-0.419359f,0.0918925f}, -{0.116341f,-0.421236f,0.0900281f},{0.121519f,-0.422894f,0.0900281f},{0.116342f,-0.421236f,0.0918925f}, -{0.121519f,-0.422894f,0.0918925f},{0.126754f,-0.424327f,0.0900281f},{0.126754f,-0.424327f,0.0918925f}, -{0.132038f,-0.425533f,0.0900281f},{0.137363f,-0.426511f,0.0900281f},{0.132038f,-0.425533f,0.0918925f}, -{0.137364f,-0.426511f,0.0918925f},{0.142723f,-0.427261f,0.0900281f},{0.142723f,-0.427261f,0.0918925f}, -{0.14811f,-0.427781f,0.0900281f},{0.153516f,-0.428071f,0.0900281f},{0.14811f,-0.427781f,0.0918925f}, -{0.153516f,-0.428071f,0.0918925f},{0.158934f,-0.428131f,0.0900281f},{0.158934f,-0.428131f,0.0918925f}, -{0.164356f,-0.427958f,0.0900281f},{0.169776f,-0.427553f,0.0900281f},{0.164357f,-0.427958f,0.0918925f}, -{0.169776f,-0.427553f,0.0918925f},{0.18196f,-0.448656f,0.0918925f},{0.18196f,-0.448656f,0.0900281f}, -{0.0049028f,-0.5f,0.0918925f},{-0.00490289f,-0.5f,0.0918925f},{0.00490289f,-0.5f,0.0900281f}, -{0.0147057f,-0.499724f,0.0900281f},{0.0147055f,-0.499724f,0.0918925f},{0.0244996f,-0.499171f,0.0900281f}, -{0.0244996f,-0.499171f,0.0918925f},{0.0342788f,-0.498342f,0.0918925f},{0.034279f,-0.498342f,0.0900281f}, -{0.0440377f,-0.497236f,0.0900281f},{0.0440376f,-0.497236f,0.0918925f},{0.05377f,-0.495854f,0.0900281f}, -{0.05377f,-0.495854f,0.0918925f},{0.0634697f,-0.494196f,0.0918925f},{0.0634706f,-0.494196f,0.0900281f}, -{0.0731194f,-0.492264f,0.0900281f},{0.0731193f,-0.492264f,0.0918925f},{0.0826996f,-0.490062f,0.0900281f}, -{0.0826996f,-0.490062f,0.0918925f},{0.0922052f,-0.487593f,0.0918925f},{0.0922054f,-0.487593f,0.0900281f}, -{0.101631f,-0.484859f,0.0900281f},{0.101631f,-0.484859f,0.0918925f},{0.110971f,-0.481861f,0.0900281f}, -{0.110971f,-0.481861f,0.0918925f},{0.120221f,-0.478603f,0.0918925f},{0.120221f,-0.478602f,0.0900281f}, -{0.129374f,-0.475085f,0.0900281f},{0.129374f,-0.475085f,0.0918925f},{0.138425f,-0.47131f,0.0900281f}, -{0.138425f,-0.47131f,0.0918925f},{0.147368f,-0.46728f,0.0918925f},{0.147369f,-0.46728f,0.0900281f}, -{0.156199f,-0.462998f,0.0900281f},{0.156199f,-0.462998f,0.0918925f},{0.164912f,-0.458465f,0.0900281f}, -{0.164912f,-0.458465f,0.0918925f},{0.173501f,-0.453684f,0.0918925f},{0.173501f,-0.453684f,0.0900281f}, -{-0.0049028f,-0.5f,0.0900281f},{-0.0147055f,-0.499724f,0.0900281f},{-0.0147057f,-0.499724f,0.0918925f}, -{-0.0244996f,-0.499171f,0.0918925f},{-0.0244996f,-0.499171f,0.0900281f},{-0.034279f,-0.498342f,0.0918925f}, -{-0.0342788f,-0.498342f,0.0900281f},{-0.0440376f,-0.497236f,0.0900281f},{-0.0440377f,-0.497236f,0.0918925f}, -{-0.05377f,-0.495854f,0.0918925f},{-0.05377f,-0.495854f,0.0900281f},{-0.0634706f,-0.494196f,0.0918925f}, -{-0.0634697f,-0.494196f,0.0900281f},{-0.0731193f,-0.492264f,0.0900281f},{-0.0731194f,-0.492264f,0.0918925f}, -{-0.0826996f,-0.490062f,0.0918925f},{-0.0826996f,-0.490062f,0.0900281f},{-0.0922054f,-0.487593f,0.0918925f}, -{-0.0922052f,-0.487593f,0.0900281f},{-0.101631f,-0.484859f,0.0900281f},{-0.101631f,-0.484859f,0.0918925f}, -{-0.110971f,-0.481861f,0.0918925f},{-0.110971f,-0.481861f,0.0900281f},{-0.120221f,-0.478602f,0.0918925f}, -{-0.120221f,-0.478603f,0.0900281f},{-0.129374f,-0.475085f,0.0900281f},{-0.129374f,-0.475085f,0.0918925f}, -{-0.138425f,-0.47131f,0.0918925f},{-0.138425f,-0.47131f,0.0900281f},{-0.147369f,-0.46728f,0.0918925f}, -{-0.147368f,-0.46728f,0.0900281f},{-0.156199f,-0.462998f,0.0900281f},{-0.156199f,-0.462998f,0.0918925f}, -{-0.164912f,-0.458465f,0.0918925f},{-0.164912f,-0.458465f,0.0900281f},{-0.173501f,-0.453684f,0.0918925f}, -{-0.173501f,-0.453684f,0.0900281f},{0.0200317f,-0.295886f,0.0918925f},{0.0036392f,-0.280259f,0.0918925f}, -{0.00474168f,-0.280781f,0.0918925f},{0.0152687f,-0.28931f,0.0918925f},{0.0183517f,-0.29453f,0.0918925f}, -{0.0057053f,-0.28153f,0.0918925f},{0.0130697f,-0.291507f,0.0918925f},{0.0151095f,-0.289835f,0.0918925f}, -{0.0173478f,-0.294119f,0.0918925f},{0.0109706f,-0.291087f,0.0918925f},{0.0105473f,-0.290739f,0.0918925f}, -{0.0192577f,-0.295126f,0.0918925f},{0.0206442f,-0.296782f,0.0918925f},{0.0210723f,-0.297778f,0.0918925f}, -{0.0101998f,-0.290316f,0.0918925f},{0.0140791f,-0.291091f,0.0918925f},{0.0151984f,-0.293911f,0.0918925f}, -{0.0145033f,-0.290742f,0.0918925f},{-0.0105451f,-0.315791f,0.0918925f},{-0.0101973f,-0.315367f,0.0918925f}, -{-0.0109693f,-0.316139f,0.0918925f},{-0.00977971f,-0.314358f,0.0918925f},{-0.00993885f,-0.314883f,0.0918925f}, -{-0.0151067f,-0.314881f,0.0918925f},{-0.0119787f,-0.316555f,0.0918925f},{-0.0114536f,-0.316397f,0.0918925f}, -{-0.0125242f,-0.316609f,0.0918925f},{-0.013595f,-0.316394f,0.0918925f},{-0.0140778f,-0.316135f,0.0918925f}, -{-0.0145011f,-0.315788f,0.0918925f},{-0.0148486f,-0.315364f,0.0918925f},{-0.015266f,-0.314357f,0.0918925f}, -{0.0148511f,-0.290318f,0.0918925f},{0.0162833f,-0.29391f,0.0918925f},{0.0119779f,-0.291506f,0.0918925f}, -{0.0125242f,-0.291561f,0.0918925f},{0.0114534f,-0.291346f,0.0918925f},{0.0135948f,-0.291349f,0.0918925f}, -{0.00994166f,-0.289833f,0.0918925f},{-0.0130705f,-0.316555f,0.0918925f},{0.00978241f,-0.289309f,0.0918925f}, -{0.00474296f,-0.280782f,0.0900281f},{0.0210725f,-0.297777f,0.0900281f},{0.020644f,-0.296781f,0.0900281f}, -{0.0105451f,-0.290742f,0.0900281f},{0.00364027f,-0.280259f,0.0900281f},{0.00993885f,-0.289835f,0.0900281f}, -{0.0200312f,-0.295886f,0.0900281f},{0.0192574f,-0.295126f,0.0900281f},{0.0162822f,-0.29391f,0.0900281f}, -{0.0145011f,-0.290739f,0.0900281f},{0.0148486f,-0.290316f,0.0900281f},{0.0125242f,-0.291561f,0.0900281f}, -{0.00977971f,-0.28931f,0.0900281f},{0.0109693f,-0.291091f,0.0900281f},{0.0101973f,-0.290318f,0.0900281f}, -{0.0114536f,-0.291349f,0.0900281f},{-0.0145033f,-0.315791f,0.0900281f},{-0.0140791f,-0.316139f,0.0900281f}, -{-0.00978241f,-0.314357f,0.0900281f},{-0.00994166f,-0.314881f,0.0900281f},{0.0183513f,-0.294529f,0.0900281f}, -{0.0173468f,-0.294119f,0.0900281f},{0.0151067f,-0.289833f,0.0900281f},{0.015266f,-0.289309f,0.0900281f}, -{0.0140778f,-0.291087f,0.0900281f},{0.0151976f,-0.293911f,0.0900281f},{0.013595f,-0.291346f,0.0900281f}, -{0.00570553f,-0.28153f,0.0900281f},{-0.0119779f,-0.316555f,0.0900281f},{-0.0101998f,-0.315364f,0.0900281f}, -{-0.0125242f,-0.316609f,0.0900281f},{-0.0130697f,-0.316555f,0.0900281f},{-0.0135948f,-0.316397f,0.0900281f}, -{-0.0148511f,-0.315367f,0.0900281f},{-0.0151095f,-0.314883f,0.0900281f},{-0.0109706f,-0.316135f,0.0900281f}, -{-0.0152687f,-0.314358f,0.0900281f},{-0.0114534f,-0.316394f,0.0900281f},{-0.0105473f,-0.315788f,0.0900281f}, -{0.0119787f,-0.291507f,0.0900281f},{0.0130705f,-0.291506f,0.0900281f},{-0.301289f,0.00279661f,0.127503f}, -{-0.301289f,0.00279661f,0.13496f},{-0.3008f,0.00275356f,0.13496f},{-0.300331f,0.00262748f,0.13496f}, -{-0.300801f,0.00275376f,0.127503f},{-0.300332f,0.00262801f,0.127503f},{-0.299893f,0.00242333f,0.127503f}, -{-0.299493f,0.00214411f,0.127503f},{-0.299891f,0.00242266f,0.13496f},{-0.299491f,0.00214219f,0.13496f}, -{-0.299146f,0.00179767f,0.127503f},{-0.299144f,0.00179504f,0.13496f},{-0.298866f,0.00139727f,0.127503f}, -{-0.298661f,0.000957717f,0.127503f},{-0.298865f,0.00139564f,0.13496f},{-0.298661f,0.000956449f,0.13496f}, -{-0.298535f,0.000488516f,0.127503f},{-0.298535f,0.000488516f,0.13496f},{-0.298492f,3.42486e-019f,0.13496f}, -{-0.298492f,3.42486e-019f,0.127503f},{-0.301777f,0.00275356f,0.127503f},{-0.302246f,0.00262748f,0.127503f}, -{-0.301776f,0.00275376f,0.13496f},{-0.302684f,0.00242333f,0.13496f},{-0.302245f,0.00262801f,0.13496f}, -{-0.302686f,0.00242266f,0.127503f},{-0.303084f,0.00214411f,0.13496f},{-0.303086f,0.00214219f,0.127503f}, -{-0.303431f,0.00179767f,0.13496f},{-0.303711f,0.00139727f,0.13496f},{-0.303433f,0.00179504f,0.127503f}, -{-0.303712f,0.00139564f,0.127503f},{-0.303916f,0.000957717f,0.13496f},{-0.303917f,0.000956449f,0.127503f}, -{-0.304042f,0.000488516f,0.13496f},{-0.304042f,0.000488516f,0.127503f},{-0.304085f,0.0f,0.127503f}, -{-0.304085f,0.0f,0.13496f},{-0.301289f,0.00466102f,0.125638f},{-0.301289f,0.00466102f,0.127503f}, -{-0.300676f,0.00462052f,0.127503f},{-0.300079f,0.00450127f,0.127503f},{-0.300676f,0.00462066f,0.125638f}, -{-0.299505f,0.00430621f,0.127503f},{-0.300079f,0.00450141f,0.125638f},{-0.299505f,0.00430621f,0.125638f}, -{-0.298961f,0.00403818f,0.127503f},{-0.298454f,0.00370041f,0.127503f},{-0.298961f,0.00403832f,0.125638f}, -{-0.297993f,0.00329584f,0.127503f},{-0.298455f,0.00370055f,0.125638f},{-0.297993f,0.00329584f,0.125638f}, -{-0.297588f,0.00283386f,0.127503f},{-0.29725f,0.00232743f,0.127503f},{-0.297588f,0.0028342f,0.125638f}, -{-0.296982f,0.00178369f,0.127503f},{-0.29725f,0.00232777f,0.125638f},{-0.296787f,0.00120978f,0.125638f}, -{-0.296982f,0.00178369f,0.125638f},{-0.296787f,0.00120944f,0.127503f},{-0.296668f,0.000612842f,0.125638f}, -{-0.296668f,0.000612502f,0.127503f},{-0.296628f,5.70811e-019f,0.125638f},{-0.296628f,5.70811e-019f,0.127503f}, -{-0.301901f,0.00462052f,0.125638f},{-0.302498f,0.00450127f,0.125638f},{-0.301901f,0.00462066f,0.127503f}, -{-0.302498f,0.00450141f,0.127503f},{-0.303072f,0.00430621f,0.125638f},{-0.303616f,0.00403818f,0.125638f}, -{-0.303072f,0.00430621f,0.127503f},{-0.304123f,0.00370041f,0.125638f},{-0.303616f,0.00403832f,0.127503f}, -{-0.304122f,0.00370055f,0.127503f},{-0.304584f,0.00329584f,0.125638f},{-0.304989f,0.00283386f,0.125638f}, -{-0.304584f,0.00329584f,0.127503f},{-0.305327f,0.00232743f,0.125638f},{-0.304989f,0.0028342f,0.127503f}, -{-0.305327f,0.00232777f,0.127503f},{-0.305595f,0.00178369f,0.125638f},{-0.30579f,0.00120978f,0.127503f}, -{-0.305595f,0.00178369f,0.127503f},{-0.30579f,0.00120944f,0.125638f},{-0.305909f,0.000612842f,0.127503f}, -{-0.30595f,0.0f,0.127503f},{-0.305909f,0.000612502f,0.125638f},{-0.30595f,0.0f,0.125638f}, -{-0.29833f,-0.00883211f,0.125638f},{-0.298135f,-0.00916975f,0.125638f},{-0.298136f,-0.00916839f,0.121909f}, -{-0.298331f,-0.00883048f,0.121909f},{-0.298451f,-0.00846133f,0.125638f},{-0.298451f,-0.00845974f,0.121909f}, -{-0.298492f,-0.0080728f,0.121909f},{-0.298451f,-0.00768692f,0.125638f},{-0.298492f,-0.00807384f,0.125638f}, -{-0.298451f,-0.00768446f,0.121909f},{-0.298331f,-0.00731545f,0.125638f},{-0.29833f,-0.00731401f,0.121909f}, -{-0.298136f,-0.00697763f,0.125638f},{-0.298136f,-0.00697682f,0.121909f},{-0.297876f,-0.00668858f,0.125638f}, -{-0.297875f,-0.0066878f,0.121909f},{-0.29756f,-0.0064585f,0.121909f},{-0.29756f,-0.0064585f,0.125638f}, -{-0.297876f,-0.00945833f,0.121909f},{-0.29756f,-0.00968734f,0.121909f},{-0.297874f,-0.00945929f,0.125638f}, -{-0.297559f,-0.00968796f,0.125638f},{-0.297205f,-0.00984564f,0.121909f},{-0.297203f,-0.00984651f,0.125638f}, -{-0.296823f,-0.00992724f,0.121909f},{-0.296433f,-0.00992738f,0.121909f},{-0.296822f,-0.00992734f,0.125638f}, -{-0.296432f,-0.00992724f,0.125638f},{-0.296053f,-0.00984657f,0.121909f},{-0.296052f,-0.00984636f,0.125638f}, -{-0.295695f,-0.00968775f,0.121909f},{-0.295695f,-0.00968775f,0.125638f},{-0.293346f,-0.00814348f,0.125638f}, -{-0.293065f,-0.00862894f,0.125638f},{-0.293067f,-0.00862571f,0.121909f},{-0.29355f,-0.00762194f,0.125638f}, -{-0.293347f,-0.00813961f,0.121909f},{-0.29355f,-0.00762066f,0.121909f},{-0.293673f,-0.00708133f,0.125638f}, -{-0.293673f,-0.00708043f,0.121909f},{-0.293715f,-0.0065271f,0.121909f},{-0.293715f,-0.00652944f,0.125638f}, -{-0.293674f,-0.00597413f,0.125638f},{-0.293344f,-0.00490426f,0.121909f},{-0.293067f,-0.00442484f,0.125638f}, -{-0.293344f,-0.00490499f,0.125638f},{-0.293673f,-0.00596985f,0.121909f},{-0.293549f,-0.00542656f,0.125638f}, -{-0.293548f,-0.00542408f,0.121909f},{-0.293066f,-0.00442313f,0.121909f},{-0.292722f,-0.00399173f,0.125638f}, -{-0.29272f,-0.00398963f,0.121909f},{-0.292314f,-0.00361295f,0.121909f},{-0.291851f,-0.00329618f,0.125638f}, -{-0.292314f,-0.00361295f,0.125638f},{-0.291851f,-0.00329618f,0.121909f},{-0.292718f,-0.00906373f,0.121909f}, -{-0.292311f,-0.00944065f,0.121909f},{-0.292717f,-0.00906452f,0.125638f},{-0.29231f,-0.00944121f,0.125638f}, -{-0.291854f,-0.00975253f,0.121909f},{-0.291852f,-0.00975397f,0.125638f},{-0.291352f,-0.00999456f,0.121909f}, -{-0.290816f,-0.0101607f,0.121909f},{-0.291349f,-0.0099963f,0.125638f},{-0.290813f,-0.010161f,0.125638f}, -{-0.290262f,-0.010244f,0.121909f},{-0.290261f,-0.0102441f,0.125638f},{-0.289707f,-0.0102439f,0.121909f}, -{-0.28916f,-0.0101614f,0.121909f},{-0.289705f,-0.0102436f,0.125638f},{-0.289157f,-0.010161f,0.125638f}, -{-0.288628f,-0.0099979f,0.121909f},{-0.288628f,-0.0099979f,0.125638f},{-0.288122f,-0.00975468f,0.121909f}, -{-0.288122f,-0.00975468f,0.125638f},{-0.307458f,-0.00697787f,0.125638f},{-0.307653f,-0.00731578f,0.125638f}, -{-0.307652f,-0.00731414f,0.121909f},{-0.307457f,-0.0069765f,0.121909f},{-0.307198f,-0.00668793f,0.125638f}, -{-0.307196f,-0.00668696f,0.121909f},{-0.306881f,-0.0064583f,0.121909f},{-0.306527f,-0.00630061f,0.125638f}, -{-0.306882f,-0.00645891f,0.125638f},{-0.306525f,-0.00629975f,0.121909f},{-0.306145f,-0.00621902f,0.125638f}, -{-0.306144f,-0.00621892f,0.121909f},{-0.305755f,-0.00621887f,0.125638f},{-0.305754f,-0.00621902f,0.121909f}, -{-0.305375f,-0.00629969f,0.125638f},{-0.305374f,-0.0062999f,0.121909f},{-0.305017f,-0.0064585f,0.121909f}, -{-0.305017f,-0.0064585f,0.125638f},{-0.307773f,-0.00768493f,0.121909f},{-0.307814f,-0.00807242f,0.121909f}, -{-0.307773f,-0.00768652f,0.125638f},{-0.307814f,-0.00807346f,0.125638f},{-0.307773f,-0.00845934f,0.121909f}, -{-0.307773f,-0.0084618f,0.125638f},{-0.307653f,-0.0088308f,0.121909f},{-0.307458f,-0.00916863f,0.121909f}, -{-0.307652f,-0.00883225f,0.125638f},{-0.307458f,-0.00916944f,0.125638f},{-0.307198f,-0.00945768f,0.121909f}, -{-0.307197f,-0.00945846f,0.125638f},{-0.306882f,-0.00968775f,0.121909f},{-0.306882f,-0.00968775f,0.125638f}, -{-0.304369f,-0.0109506f,0.125638f},{-0.304649f,-0.0114367f,0.125638f},{-0.304648f,-0.0114328f,0.121909f}, -{-0.30402f,-0.0105126f,0.125638f},{-0.304367f,-0.0109474f,0.121909f},{-0.304019f,-0.0105118f,0.121909f}, -{-0.303614f,-0.0101356f,0.125638f},{-0.303613f,-0.0101351f,0.121909f},{-0.303154f,-0.00982233f,0.121909f}, -{-0.303156f,-0.00982376f,0.125638f},{-0.302655f,-0.00958174f,0.125638f},{-0.301564f,-0.00933222f,0.121909f}, -{-0.30101f,-0.00933241f,0.125638f},{-0.301564f,-0.00933231f,0.125638f},{-0.302651f,-0.00958f,0.121909f}, -{-0.302118f,-0.00941561f,0.125638f},{-0.302116f,-0.00941532f,0.121909f},{-0.301008f,-0.0093327f,0.121909f}, -{-0.300462f,-0.00941491f,0.125638f},{-0.300459f,-0.00941526f,0.121909f},{-0.29993f,-0.0095784f,0.121909f}, -{-0.299424f,-0.00982161f,0.125638f},{-0.29993f,-0.0095784f,0.125638f},{-0.299424f,-0.00982161f,0.121909f}, -{-0.304853f,-0.0119544f,0.121909f},{-0.304976f,-0.012495f,0.121909f},{-0.304853f,-0.0119556f,0.125638f}, -{-0.304976f,-0.0124959f,0.125638f},{-0.305017f,-0.0130469f,0.121909f},{-0.305017f,-0.0130492f,0.125638f}, -{-0.304976f,-0.0136022f,0.121909f},{-0.304852f,-0.0141497f,0.121909f},{-0.304976f,-0.0136064f,0.125638f}, -{-0.304851f,-0.0141522f,0.125638f},{-0.304647f,-0.0146713f,0.121909f},{-0.304646f,-0.014672f,0.125638f}, -{-0.304369f,-0.0151515f,0.121909f},{-0.304024f,-0.0155846f,0.121909f},{-0.304368f,-0.0151532f,0.125638f}, -{-0.304023f,-0.0155867f,0.125638f},{-0.303617f,-0.0159633f,0.121909f},{-0.303617f,-0.0159633f,0.125638f}, -{-0.303153f,-0.0162801f,0.121909f},{-0.303153f,-0.0162801f,0.125638f},{-0.310416f,0.00185425f,0.125638f}, -{-0.310806f,0.00185398f,0.125638f},{-0.310805f,0.00185425f,0.121909f},{-0.310415f,0.00185398f,0.121909f}, -{-0.310035f,0.0017734f,0.125638f},{-0.310034f,0.00177278f,0.121909f},{-0.309678f,0.0016145f,0.121909f}, -{-0.309364f,0.0013863f,0.125638f},{-0.309679f,0.00161492f,0.125638f},{-0.309362f,0.00138471f,0.121909f}, -{-0.309103f,0.00109643f,0.125638f},{-0.309102f,0.00109509f,0.121909f},{-0.308908f,0.000758756f,0.125638f}, -{-0.308907f,0.000757801f,0.121909f},{-0.308787f,0.000388892f,0.125638f},{-0.308787f,0.000387896f,0.121909f}, -{-0.308746f,3.69669e-018f,0.121909f},{-0.308746f,3.69669e-018f,0.125638f},{-0.311186f,0.0017734f,0.121909f}, -{-0.311542f,0.00161492f,0.121909f},{-0.311188f,0.00177278f,0.125638f},{-0.311543f,0.0016145f,0.125638f}, -{-0.311857f,0.0013863f,0.121909f},{-0.311859f,0.00138471f,0.125638f},{-0.312119f,0.00109643f,0.121909f}, -{-0.312314f,0.000758756f,0.121909f},{-0.312119f,0.00109509f,0.125638f},{-0.312314f,0.000757801f,0.125638f}, -{-0.312434f,0.000388892f,0.121909f},{-0.312434f,0.000387896f,0.125638f},{-0.312475f,4.75298e-018f,0.121909f}, -{-0.312475f,4.75298e-018f,0.125638f},{-0.312313f,-0.00280711f,0.125638f},{-0.312873f,-0.00280775f,0.125638f}, -{-0.312869f,-0.00280711f,0.121909f},{-0.311758f,-0.00289062f,0.125638f},{-0.312308f,-0.00280775f,0.121909f}, -{-0.311757f,-0.00289112f,0.121909f},{-0.311229f,-0.00305432f,0.125638f},{-0.311228f,-0.00305467f,0.121909f}, -{-0.310728f,-0.00329522f,0.121909f},{-0.31073f,-0.00329432f,0.125638f},{-0.31027f,-0.00360761f,0.125638f}, -{-0.309508f,-0.00442796f,0.121909f},{-0.309231f,-0.00490757f,0.125638f},{-0.309508f,-0.00442732f,0.125638f}, -{-0.310266f,-0.00361015f,0.121909f},{-0.309858f,-0.00398905f,0.125638f},{-0.309856f,-0.00399124f,0.121909f}, -{-0.30923f,-0.00490957f,0.121909f},{-0.309029f,-0.00542319f,0.125638f},{-0.309028f,-0.00542563f,0.121909f}, -{-0.308905f,-0.00596545f,0.121909f},{-0.308862f,-0.00652543f,0.125638f},{-0.308905f,-0.00596545f,0.125638f}, -{-0.308862f,-0.00652543f,0.121909f},{-0.313423f,-0.00289062f,0.121909f},{-0.313953f,-0.00305432f,0.121909f}, -{-0.313425f,-0.00289112f,0.125638f},{-0.313954f,-0.00305467f,0.125638f},{-0.314452f,-0.00329432f,0.121909f}, -{-0.314454f,-0.00329522f,0.125638f},{-0.314912f,-0.00360761f,0.121909f},{-0.315324f,-0.00398905f,0.121909f}, -{-0.314916f,-0.00361015f,0.125638f},{-0.315326f,-0.00399124f,0.125638f},{-0.315673f,-0.00442732f,0.121909f}, -{-0.315674f,-0.00442796f,0.125638f},{-0.315951f,-0.00490757f,0.121909f},{-0.316153f,-0.00542319f,0.121909f}, -{-0.315951f,-0.00490957f,0.125638f},{-0.316154f,-0.00542563f,0.125638f},{-0.316277f,-0.00596545f,0.121909f}, -{-0.316277f,-0.00596545f,0.125638f},{-0.31632f,-0.00652543f,0.121909f},{-0.31632f,-0.00652543f,0.125638f}, -{-0.304247f,0.00883211f,0.125638f},{-0.304442f,0.00916975f,0.125638f},{-0.304441f,0.00916839f,0.121909f}, -{-0.304246f,0.00883048f,0.121909f},{-0.304126f,0.00846133f,0.125638f},{-0.304126f,0.00845974f,0.121909f}, -{-0.304085f,0.0080728f,0.121909f},{-0.304126f,0.00768692f,0.125638f},{-0.304085f,0.00807384f,0.125638f}, -{-0.304126f,0.00768446f,0.121909f},{-0.304246f,0.00731545f,0.125638f},{-0.304247f,0.00731401f,0.121909f}, -{-0.304441f,0.00697763f,0.125638f},{-0.304442f,0.00697682f,0.121909f},{-0.304701f,0.00668858f,0.125638f}, -{-0.304702f,0.0066878f,0.121909f},{-0.305017f,0.0064585f,0.121909f},{-0.305017f,0.0064585f,0.125638f}, -{-0.304702f,0.00945833f,0.121909f},{-0.305017f,0.00968734f,0.121909f},{-0.304703f,0.00945929f,0.125638f}, -{-0.305018f,0.00968796f,0.125638f},{-0.305372f,0.00984564f,0.121909f},{-0.305375f,0.00984651f,0.125638f}, -{-0.305754f,0.00992724f,0.121909f},{-0.306144f,0.00992738f,0.121909f},{-0.305756f,0.00992734f,0.125638f}, -{-0.306145f,0.00992724f,0.125638f},{-0.306524f,0.00984657f,0.121909f},{-0.306525f,0.00984636f,0.125638f}, -{-0.306882f,0.00968775f,0.121909f},{-0.306882f,0.00968775f,0.125638f},{-0.309232f,0.00814348f,0.125638f}, -{-0.309513f,0.00862894f,0.125638f},{-0.30951f,0.00862571f,0.121909f},{-0.309027f,0.00762194f,0.125638f}, -{-0.30923f,0.00813961f,0.121909f},{-0.309027f,0.00762066f,0.121909f},{-0.308904f,0.00708133f,0.125638f}, -{-0.308904f,0.00708043f,0.121909f},{-0.308862f,0.0065271f,0.121909f},{-0.308862f,0.00652944f,0.125638f}, -{-0.308903f,0.00597413f,0.125638f},{-0.309233f,0.00490426f,0.121909f},{-0.30951f,0.00442484f,0.125638f}, -{-0.309233f,0.00490499f,0.125638f},{-0.308904f,0.00596985f,0.121909f},{-0.309028f,0.00542656f,0.125638f}, -{-0.309029f,0.00542408f,0.121909f},{-0.309511f,0.00442313f,0.121909f},{-0.309855f,0.00399173f,0.125638f}, -{-0.309857f,0.00398963f,0.121909f},{-0.310263f,0.00361295f,0.121909f},{-0.310726f,0.00329618f,0.125638f}, -{-0.310263f,0.00361295f,0.125638f},{-0.310726f,0.00329618f,0.121909f},{-0.309859f,0.00906373f,0.121909f}, -{-0.310266f,0.00944065f,0.121909f},{-0.30986f,0.00906452f,0.125638f},{-0.310267f,0.00944121f,0.125638f}, -{-0.310723f,0.00975253f,0.121909f},{-0.310725f,0.00975397f,0.125638f},{-0.311225f,0.00999456f,0.121909f}, -{-0.311761f,0.0101607f,0.121909f},{-0.311229f,0.0099963f,0.125638f},{-0.311764f,0.010161f,0.125638f}, -{-0.312315f,0.010244f,0.121909f},{-0.312316f,0.0102441f,0.125638f},{-0.31287f,0.0102439f,0.121909f}, -{-0.313417f,0.0101614f,0.121909f},{-0.312872f,0.0102436f,0.125638f},{-0.31342f,0.010161f,0.125638f}, -{-0.313949f,0.0099979f,0.121909f},{-0.313949f,0.0099979f,0.125638f},{-0.314455f,0.00975468f,0.121909f}, -{-0.314455f,0.00975468f,0.125638f},{-0.295119f,0.00697787f,0.125638f},{-0.294924f,0.00731578f,0.125638f}, -{-0.294925f,0.00731414f,0.121909f},{-0.29512f,0.0069765f,0.121909f},{-0.29538f,0.00668793f,0.125638f}, -{-0.295381f,0.00668696f,0.121909f},{-0.295696f,0.0064583f,0.121909f},{-0.29605f,0.00630061f,0.125638f}, -{-0.295695f,0.00645891f,0.125638f},{-0.296052f,0.00629975f,0.121909f},{-0.296432f,0.00621902f,0.125638f}, -{-0.296434f,0.00621892f,0.121909f},{-0.296822f,0.00621887f,0.125638f},{-0.296823f,0.00621902f,0.121909f}, -{-0.297202f,0.00629969f,0.125638f},{-0.297203f,0.0062999f,0.121909f},{-0.29756f,0.0064585f,0.121909f}, -{-0.29756f,0.0064585f,0.125638f},{-0.294804f,0.00768493f,0.121909f},{-0.294763f,0.00807242f,0.121909f}, -{-0.294804f,0.00768652f,0.125638f},{-0.294763f,0.00807346f,0.125638f},{-0.294804f,0.00845934f,0.121909f}, -{-0.294804f,0.0084618f,0.125638f},{-0.294924f,0.0088308f,0.121909f},{-0.295119f,0.00916863f,0.121909f}, -{-0.294925f,0.00883225f,0.125638f},{-0.29512f,0.00916944f,0.125638f},{-0.295379f,0.00945768f,0.121909f}, -{-0.29538f,0.00945846f,0.125638f},{-0.295695f,0.00968775f,0.121909f},{-0.295695f,0.00968775f,0.125638f}, -{-0.298208f,0.0109506f,0.125638f},{-0.297928f,0.0114367f,0.125638f},{-0.297929f,0.0114328f,0.121909f}, -{-0.298557f,0.0105126f,0.125638f},{-0.29821f,0.0109474f,0.121909f},{-0.298558f,0.0105118f,0.121909f}, -{-0.298964f,0.0101356f,0.125638f},{-0.298964f,0.0101351f,0.121909f},{-0.299423f,0.00982233f,0.121909f}, -{-0.299421f,0.00982376f,0.125638f},{-0.299922f,0.00958174f,0.125638f},{-0.301014f,0.00933222f,0.121909f}, -{-0.301567f,0.00933241f,0.125638f},{-0.301013f,0.00933231f,0.125638f},{-0.299926f,0.00958f,0.121909f}, -{-0.300459f,0.00941561f,0.125638f},{-0.300461f,0.00941532f,0.121909f},{-0.301569f,0.0093327f,0.121909f}, -{-0.302115f,0.00941491f,0.125638f},{-0.302118f,0.00941526f,0.121909f},{-0.302647f,0.0095784f,0.121909f}, -{-0.303153f,0.00982161f,0.125638f},{-0.302647f,0.0095784f,0.125638f},{-0.303153f,0.00982161f,0.121909f}, -{-0.297725f,0.0119544f,0.121909f},{-0.297601f,0.012495f,0.121909f},{-0.297724f,0.0119556f,0.125638f}, -{-0.297601f,0.0124959f,0.125638f},{-0.29756f,0.0130469f,0.121909f},{-0.29756f,0.0130492f,0.125638f}, -{-0.297601f,0.0136022f,0.121909f},{-0.297725f,0.0141497f,0.121909f},{-0.297601f,0.0136064f,0.125638f}, -{-0.297726f,0.0141522f,0.125638f},{-0.29793f,0.0146713f,0.121909f},{-0.297931f,0.014672f,0.125638f}, -{-0.298208f,0.0151515f,0.121909f},{-0.298553f,0.0155846f,0.121909f},{-0.298209f,0.0151532f,0.125638f}, -{-0.298555f,0.0155867f,0.125638f},{-0.29896f,0.0159633f,0.121909f},{-0.29896f,0.0159633f,0.125638f}, -{-0.299424f,0.0162801f,0.121909f},{-0.299424f,0.0162801f,0.125638f},{-0.292161f,-0.00185425f,0.125638f}, -{-0.291771f,-0.00185398f,0.125638f},{-0.291772f,-0.00185425f,0.121909f},{-0.292162f,-0.00185398f,0.121909f}, -{-0.292542f,-0.0017734f,0.125638f},{-0.292544f,-0.00177278f,0.121909f},{-0.292899f,-0.0016145f,0.121909f}, -{-0.293213f,-0.0013863f,0.125638f},{-0.292898f,-0.00161492f,0.125638f},{-0.293215f,-0.00138471f,0.121909f}, -{-0.293474f,-0.00109643f,0.125638f},{-0.293475f,-0.00109509f,0.121909f},{-0.29367f,-0.000758756f,0.125638f}, -{-0.29367f,-0.000757801f,0.121909f},{-0.29379f,-0.000388892f,0.125638f},{-0.29379f,-0.000387896f,0.121909f}, -{-0.293831f,1.53975e-019f,0.121909f},{-0.293831f,1.53975e-019f,0.125638f},{-0.291391f,-0.0017734f,0.121909f}, -{-0.291035f,-0.00161492f,0.121909f},{-0.291389f,-0.00177278f,0.125638f},{-0.291034f,-0.0016145f,0.125638f}, -{-0.29072f,-0.0013863f,0.121909f},{-0.290718f,-0.00138471f,0.125638f},{-0.290459f,-0.00109643f,0.121909f}, -{-0.290263f,-0.000758756f,0.121909f},{-0.290458f,-0.00109509f,0.125638f},{-0.290263f,-0.000757801f,0.125638f}, -{-0.290143f,-0.000388892f,0.121909f},{-0.290143f,-0.000387896f,0.125638f},{-0.290102f,-7.4349e-020f,0.121909f}, -{-0.290102f,-7.4349e-020f,0.125638f},{-0.290265f,0.00280711f,0.125638f},{-0.289704f,0.00280775f,0.125638f}, -{-0.289708f,0.00280711f,0.121909f},{-0.290819f,0.00289062f,0.125638f},{-0.290269f,0.00280775f,0.121909f}, -{-0.29082f,0.00289112f,0.121909f},{-0.291348f,0.00305432f,0.125638f},{-0.291349f,0.00305467f,0.121909f}, -{-0.291849f,0.00329522f,0.121909f},{-0.291847f,0.00329432f,0.125638f},{-0.292307f,0.00360761f,0.125638f}, -{-0.293069f,0.00442796f,0.121909f},{-0.293346f,0.00490757f,0.125638f},{-0.293069f,0.00442732f,0.125638f}, -{-0.292311f,0.00361015f,0.121909f},{-0.292719f,0.00398905f,0.125638f},{-0.292721f,0.00399124f,0.121909f}, -{-0.293347f,0.00490957f,0.121909f},{-0.293548f,0.00542319f,0.125638f},{-0.293549f,0.00542563f,0.121909f}, -{-0.293673f,0.00596545f,0.121909f},{-0.293715f,0.00652543f,0.125638f},{-0.293673f,0.00596545f,0.125638f}, -{-0.293715f,0.00652543f,0.121909f},{-0.289154f,0.00289062f,0.121909f},{-0.288624f,0.00305432f,0.121909f}, -{-0.289153f,0.00289112f,0.125638f},{-0.288623f,0.00305467f,0.125638f},{-0.288125f,0.00329432f,0.121909f}, -{-0.288123f,0.00329522f,0.125638f},{-0.287665f,0.00360761f,0.121909f},{-0.287253f,0.00398905f,0.121909f}, -{-0.287661f,0.00361015f,0.125638f},{-0.287251f,0.00399124f,0.125638f},{-0.286904f,0.00442732f,0.121909f}, -{-0.286903f,0.00442796f,0.125638f},{-0.286627f,0.00490757f,0.121909f},{-0.286424f,0.00542319f,0.121909f}, -{-0.286626f,0.00490957f,0.125638f},{-0.286423f,0.00542563f,0.125638f},{-0.2863f,0.00596545f,0.121909f}, -{-0.2863f,0.00596545f,0.125638f},{-0.286257f,0.00652543f,0.121909f},{-0.286257f,0.00652543f,0.125638f}, -{-0.301289f,0.00279661f,0.100469f},{-0.301289f,0.00279661f,0.0986044f},{-0.301777f,0.00275356f,0.0986044f}, -{-0.302246f,0.00262748f,0.0986044f},{-0.301776f,0.00275376f,0.100469f},{-0.302245f,0.00262801f,0.100469f}, -{-0.302684f,0.00242333f,0.100469f},{-0.303084f,0.00214411f,0.100469f},{-0.302686f,0.00242266f,0.0986044f}, -{-0.303086f,0.00214219f,0.0986044f},{-0.303431f,0.00179767f,0.100469f},{-0.303433f,0.00179504f,0.0986044f}, -{-0.303711f,0.00139727f,0.100469f},{-0.303916f,0.000957717f,0.100469f},{-0.303712f,0.00139564f,0.0986044f}, -{-0.303917f,0.000956449f,0.0986044f},{-0.304042f,0.000488516f,0.100469f},{-0.304042f,0.000488516f,0.0986044f}, -{-0.304085f,3.42486e-019f,0.0986044f},{-0.304085f,3.42486e-019f,0.100469f},{-0.3008f,0.00275356f,0.100469f}, -{-0.300331f,0.00262748f,0.100469f},{-0.300801f,0.00275376f,0.0986044f},{-0.299893f,0.00242333f,0.0986044f}, -{-0.300332f,0.00262801f,0.0986044f},{-0.299891f,0.00242266f,0.100469f},{-0.299493f,0.00214411f,0.0986044f}, -{-0.299491f,0.00214219f,0.100469f},{-0.299146f,0.00179767f,0.0986044f},{-0.298866f,0.00139727f,0.0986044f}, -{-0.299144f,0.00179504f,0.100469f},{-0.298865f,0.00139564f,0.100469f},{-0.298661f,0.000957717f,0.0986044f}, -{-0.298661f,0.000956449f,0.100469f},{-0.298535f,0.000488516f,0.0986044f},{-0.298535f,0.000488516f,0.100469f}, -{-0.298492f,0.0f,0.100469f},{-0.298492f,0.0f,0.0986044f},{-0.301289f,0.00745764f,0.100469f}, -{-0.302026f,0.00742114f,0.100469f},{-0.301289f,0.00745764f,0.101401f},{-0.302026f,0.00742114f,0.101401f}, -{-0.30275f,0.00731301f,0.100469f},{-0.303457f,0.00713527f,0.100469f},{-0.30275f,0.00731301f,0.101401f}, -{-0.304142f,0.00688994f,0.100469f},{-0.303457f,0.00713527f,0.101401f},{-0.304142f,0.00688994f,0.101401f}, -{-0.3048f,0.00657906f,0.100469f},{-0.305426f,0.00620465f,0.100469f},{-0.3048f,0.00657906f,0.101401f}, -{-0.306015f,0.00576874f,0.100469f},{-0.305426f,0.00620465f,0.101401f},{-0.306015f,0.00576874f,0.101401f}, -{-0.306562f,0.00527335f,0.100469f},{-0.307057f,0.00472635f,0.100469f},{-0.306562f,0.00527335f,0.101401f}, -{-0.307493f,0.00413751f,0.100469f},{-0.307057f,0.00472635f,0.101401f},{-0.307493f,0.00413751f,0.101401f}, -{-0.307868f,0.00351173f,0.100469f},{-0.308178f,0.00285391f,0.100469f},{-0.307868f,0.00351173f,0.101401f}, -{-0.308424f,0.00216893f,0.100469f},{-0.308178f,0.00285391f,0.101401f},{-0.308424f,0.00216893f,0.101401f}, -{-0.308602f,0.00146169f,0.100469f},{-0.30871f,0.000737081f,0.100469f},{-0.308602f,0.00146169f,0.101401f}, -{-0.308746f,9.13297e-019f,0.100469f},{-0.30871f,0.000737081f,0.101401f},{-0.308746f,9.13297e-019f,0.101401f}, -{-0.300551f,0.00742114f,0.101401f},{-0.299827f,0.00731301f,0.101401f},{-0.300551f,0.00742114f,0.100469f}, -{-0.29912f,0.00713527f,0.101401f},{-0.299827f,0.00731301f,0.100469f},{-0.29912f,0.00713527f,0.100469f}, -{-0.298435f,0.00688994f,0.101401f},{-0.297777f,0.00657906f,0.101401f},{-0.298435f,0.00688994f,0.100469f}, -{-0.297151f,0.00620465f,0.101401f},{-0.297777f,0.00657906f,0.100469f},{-0.297151f,0.00620465f,0.100469f}, -{-0.296562f,0.00576874f,0.101401f},{-0.296015f,0.00527335f,0.101401f},{-0.296562f,0.00576874f,0.100469f}, -{-0.29552f,0.00472635f,0.101401f},{-0.296015f,0.00527335f,0.100469f},{-0.29552f,0.00472635f,0.100469f}, -{-0.295084f,0.00413751f,0.101401f},{-0.294709f,0.00351173f,0.101401f},{-0.295084f,0.00413751f,0.100469f}, -{-0.294399f,0.00285391f,0.101401f},{-0.294709f,0.00351173f,0.100469f},{-0.294399f,0.00285391f,0.100469f}, -{-0.294153f,0.00216893f,0.101401f},{-0.293976f,0.00146169f,0.101401f},{-0.294153f,0.00216893f,0.100469f}, -{-0.293867f,0.000737081f,0.101401f},{-0.293976f,0.00146169f,0.100469f},{-0.293867f,0.000737081f,0.100469f}, -{-0.293831f,0.0f,0.101401f},{-0.293831f,0.0f,0.100469f},{-0.305909f,0.0173925f,0.101401f}, -{-0.305909f,0.0173922f,0.104198f},{-0.30595f,0.0167797f,0.101401f},{-0.305909f,0.0161668f,0.104198f}, -{-0.305909f,0.0161672f,0.101401f},{-0.30595f,0.0167797f,0.104198f},{-0.305595f,0.014996f,0.101401f}, -{-0.305595f,0.014996f,0.104198f},{-0.305327f,0.0144523f,0.101401f},{-0.30579f,0.0155699f,0.104198f}, -{-0.30579f,0.0155702f,0.101401f},{-0.305327f,0.0144519f,0.104198f},{-0.304989f,0.0139455f,0.104198f}, -{-0.304989f,0.0139458f,0.101401f},{-0.304584f,0.0134838f,0.101401f},{-0.304584f,0.0134838f,0.104198f}, -{-0.304122f,0.0130791f,0.104198f},{-0.304123f,0.0130793f,0.101401f},{-0.303616f,0.0127415f,0.101401f}, -{-0.303616f,0.0127414f,0.104198f},{-0.303072f,0.0124735f,0.101401f},{-0.303072f,0.0124735f,0.104198f}, -{-0.302498f,0.0122783f,0.104198f},{-0.302498f,0.0122784f,0.101401f},{-0.301289f,0.0121187f,0.101401f}, -{-0.301901f,0.0121592f,0.101401f},{-0.301901f,0.012159f,0.104198f},{-0.301289f,0.0121187f,0.104198f}, -{-0.30579f,0.0179891f,0.104198f},{-0.30579f,0.0179895f,0.101401f},{-0.305595f,0.0185634f,0.104198f}, -{-0.305327f,0.0191071f,0.104198f},{-0.305595f,0.0185634f,0.101401f},{-0.305327f,0.0191075f,0.101401f}, -{-0.304989f,0.0196135f,0.104198f},{-0.304989f,0.0196139f,0.101401f},{-0.304584f,0.0200755f,0.104198f}, -{-0.304123f,0.0204801f,0.104198f},{-0.304584f,0.0200755f,0.101401f},{-0.304122f,0.0204802f,0.101401f}, -{-0.303616f,0.0208179f,0.104198f},{-0.303616f,0.020818f,0.101401f},{-0.303072f,0.0210859f,0.104198f}, -{-0.302498f,0.0212809f,0.104198f},{-0.303072f,0.0210859f,0.101401f},{-0.302498f,0.0212811f,0.101401f}, -{-0.301901f,0.0214002f,0.104198f},{-0.301901f,0.0214003f,0.101401f},{-0.301289f,0.0214407f,0.104198f}, -{-0.301289f,0.0214407f,0.101401f},{-0.283896f,0.00462066f,0.101401f},{-0.284509f,0.00466102f,0.101401f}, -{-0.283896f,0.00462066f,0.104198f},{-0.285122f,0.00462052f,0.104198f},{-0.284509f,0.00466102f,0.104198f}, -{-0.285122f,0.00462052f,0.101401f},{-0.286293f,0.00430621f,0.101401f},{-0.286837f,0.00403818f,0.101401f}, -{-0.286293f,0.00430621f,0.104198f},{-0.285719f,0.00450127f,0.104198f},{-0.285719f,0.00450127f,0.101401f}, -{-0.286837f,0.00403818f,0.104198f},{-0.287343f,0.00370041f,0.101401f},{-0.287343f,0.00370041f,0.104198f}, -{-0.287805f,0.00329584f,0.101401f},{-0.287805f,0.00329584f,0.104198f},{-0.288209f,0.00283386f,0.101401f}, -{-0.288209f,0.00283386f,0.104198f},{-0.288547f,0.00232743f,0.101401f},{-0.288815f,0.00178369f,0.101401f}, -{-0.288547f,0.00232743f,0.104198f},{-0.288815f,0.00178369f,0.104198f},{-0.28901f,0.00120944f,0.101401f}, -{-0.28901f,0.00120944f,0.104198f},{-0.28917f,-2.05485e-018f,0.101401f},{-0.28913f,0.000612502f,0.104198f}, -{-0.28913f,0.000612502f,0.101401f},{-0.28917f,-2.05485e-018f,0.104198f},{-0.283299f,0.00450141f,0.104198f}, -{-0.282725f,0.00430621f,0.104198f},{-0.283299f,0.00450141f,0.101401f},{-0.282181f,0.00403832f,0.104198f}, -{-0.282725f,0.00430621f,0.101401f},{-0.282181f,0.00403832f,0.101401f},{-0.281675f,0.00370055f,0.104198f}, -{-0.281213f,0.00329584f,0.104198f},{-0.281675f,0.00370055f,0.101401f},{-0.280808f,0.0028342f,0.104198f}, -{-0.281213f,0.00329584f,0.101401f},{-0.280808f,0.0028342f,0.101401f},{-0.280471f,0.00232777f,0.104198f}, -{-0.280203f,0.00178369f,0.104198f},{-0.280471f,0.00232777f,0.101401f},{-0.280008f,0.00120978f,0.104198f}, -{-0.280203f,0.00178369f,0.101401f},{-0.280008f,0.00120978f,0.101401f},{-0.279888f,0.000612842f,0.104198f}, -{-0.279848f,-1.48404e-018f,0.104198f},{-0.279888f,0.000612842f,0.101401f},{-0.279848f,-1.48404e-018f,0.101401f}, -{-0.296668f,-0.0173922f,0.104198f},{-0.296628f,-0.0167797f,0.104198f},{-0.296641f,-0.0171394f,0.101401f}, -{-0.2967f,-0.0159621f,0.101401f},{-0.296633f,-0.0165489f,0.101401f},{-0.296668f,-0.0161668f,0.104198f}, -{-0.296982f,-0.014996f,0.104198f},{-0.29725f,-0.0144519f,0.104198f},{-0.297052f,-0.0148373f,0.101401f}, -{-0.29684f,-0.0153885f,0.101401f},{-0.296787f,-0.0155699f,0.104198f},{-0.297588f,-0.0139455f,0.104198f}, -{-0.297675f,-0.0138368f,0.101401f},{-0.297331f,-0.0143174f,0.101401f},{-0.297993f,-0.0134838f,0.104198f}, -{-0.298455f,-0.0130791f,0.104198f},{-0.298528f,-0.0130241f,0.101401f},{-0.298076f,-0.0134033f,0.101401f}, -{-0.298961f,-0.0127414f,0.104198f},{-0.299505f,-0.0124735f,0.104198f},{-0.299025f,-0.0127048f,0.101401f}, -{-0.300079f,-0.0122783f,0.104198f},{-0.30012f,-0.0122704f,0.101401f},{-0.299559f,-0.0124544f,0.101401f}, -{-0.300699f,-0.0121554f,0.101401f},{-0.300676f,-0.012159f,0.104198f},{-0.301289f,-0.0121187f,0.104198f}, -{-0.301289f,-0.0121187f,0.101401f},{-0.296724f,-0.0177242f,0.101401f},{-0.29688f,-0.018294f,0.101401f}, -{-0.296787f,-0.0179891f,0.104198f},{-0.296982f,-0.0185634f,0.104198f},{-0.297107f,-0.0188393f,0.101401f}, -{-0.297401f,-0.0193514f,0.101401f},{-0.29725f,-0.0191071f,0.104198f},{-0.297757f,-0.0198223f,0.101401f}, -{-0.297588f,-0.0196135f,0.104198f},{-0.297993f,-0.0200755f,0.104198f},{-0.29817f,-0.0202443f,0.101401f}, -{-0.298633f,-0.0206107f,0.101401f},{-0.298454f,-0.0204801f,0.104198f},{-0.299139f,-0.0209155f,0.101401f}, -{-0.298961f,-0.0208179f,0.104198f},{-0.299505f,-0.0210859f,0.104198f},{-0.299679f,-0.0211542f,0.101401f}, -{-0.300248f,-0.0213103f,0.101401f},{-0.300079f,-0.0212809f,0.104198f},{-0.300827f,-0.0214362f,0.101401f}, -{-0.300676f,-0.0214002f,0.104198f},{-0.301289f,-0.0214407f,0.104198f},{-0.301289f,-0.0214407f,0.101401f}, -{-0.315677f,0.0125242f,0.110723f},{-0.315667f,0.01233f,0.101401f},{-0.315667f,0.0127201f,0.101401f}, -{-0.315586f,0.0131013f,0.101401f},{-0.315641f,0.0128878f,0.110723f},{-0.315536f,0.0132379f,0.110723f}, -{-0.315197f,0.0137725f,0.101401f},{-0.315363f,0.0135608f,0.110723f},{-0.315427f,0.0134567f,0.101401f}, -{-0.314908f,0.014033f,0.101401f},{-0.315131f,0.0138436f,0.110723f},{-0.314849f,0.0140755f,0.110723f}, -{-0.314571f,0.0142276f,0.101401f},{-0.314201f,0.0143478f,0.101401f},{-0.314526f,0.0142478f,0.110723f}, -{-0.313813f,0.0143886f,0.101401f},{-0.313813f,0.0143886f,0.110723f},{-0.314176f,0.0143539f,0.110723f}, -{-0.315641f,0.01216f,0.110723f},{-0.315586f,0.0119486f,0.101401f},{-0.315534f,0.0118103f,0.110723f}, -{-0.315361f,0.0114885f,0.110723f},{-0.315428f,0.0115926f,0.101401f},{-0.315129f,0.0112063f,0.110723f}, -{-0.315199f,0.0112779f,0.101401f},{-0.314909f,0.0110163f,0.101401f},{-0.314847f,0.0109746f,0.110723f}, -{-0.314525f,0.0108025f,0.110723f},{-0.314571f,0.0108212f,0.101401f},{-0.314176f,0.0106963f,0.110723f}, -{-0.314202f,0.0107009f,0.101401f},{-0.313813f,0.0106598f,0.101401f},{-0.313813f,0.0106598f,0.110723f}, -{-0.313813f,0.0125242f,0.111843f},{-0.292606f,0.0105467f,0.110723f},{-0.292596f,0.0103525f,0.101401f}, -{-0.292596f,0.0107426f,0.101401f},{-0.292515f,0.0111238f,0.101401f},{-0.29257f,0.0109103f,0.110723f}, -{-0.292465f,0.0112604f,0.110723f},{-0.292127f,0.011795f,0.101401f},{-0.292293f,0.0115833f,0.110723f}, -{-0.292356f,0.0114792f,0.101401f},{-0.291837f,0.0120555f,0.101401f},{-0.29206f,0.0118661f,0.110723f}, -{-0.291778f,0.012098f,0.110723f},{-0.2915f,0.0122501f,0.101401f},{-0.29113f,0.0123703f,0.101401f}, -{-0.291455f,0.0122703f,0.110723f},{-0.290742f,0.0124111f,0.101401f},{-0.290742f,0.0124111f,0.110723f}, -{-0.291106f,0.0123763f,0.110723f},{-0.29257f,0.0101825f,0.110723f},{-0.292515f,0.00997107f,0.101401f}, -{-0.292463f,0.00983283f,0.110723f},{-0.29229f,0.00951095f,0.110723f},{-0.292357f,0.00961513f,0.101401f}, -{-0.292059f,0.00922876f,0.110723f},{-0.292128f,0.00930035f,0.101401f},{-0.291838f,0.00903878f,0.101401f}, -{-0.291776f,0.0089971f,0.110723f},{-0.291454f,0.008825f,0.110723f},{-0.291501f,0.00884365f,0.101401f}, -{-0.291105f,0.00871884f,0.110723f},{-0.291131f,0.00872342f,0.101401f},{-0.290742f,0.00868228f,0.101401f}, -{-0.290742f,0.00868228f,0.110723f},{-0.290742f,0.0105467f,0.111843f},{-0.290629f,-0.0125242f,0.110723f}, -{-0.290619f,-0.0127183f,0.101401f},{-0.290618f,-0.0123283f,0.101401f},{-0.290537f,-0.0119471f,0.101401f}, -{-0.290593f,-0.0121606f,0.110723f},{-0.290487f,-0.0118105f,0.110723f},{-0.290149f,-0.0112759f,0.101401f}, -{-0.290315f,-0.0114876f,0.110723f},{-0.290379f,-0.0115917f,0.101401f},{-0.289859f,-0.0110154f,0.101401f}, -{-0.290083f,-0.0112048f,0.110723f},{-0.2898f,-0.0109729f,0.110723f},{-0.289522f,-0.0108208f,0.101401f}, -{-0.289152f,-0.0107006f,0.101401f},{-0.289478f,-0.0108006f,0.110723f},{-0.288764f,-0.0106598f,0.101401f}, -{-0.288764f,-0.0106598f,0.110723f},{-0.289128f,-0.0106945f,0.110723f},{-0.290592f,-0.0128884f,0.110723f}, -{-0.290538f,-0.0130998f,0.101401f},{-0.290485f,-0.0132381f,0.110723f},{-0.290313f,-0.0135599f,0.110723f}, -{-0.290379f,-0.0134558f,0.101401f},{-0.290081f,-0.0138421f,0.110723f},{-0.290151f,-0.0137705f,0.101401f}, -{-0.289861f,-0.0140321f,0.101401f},{-0.289799f,-0.0140738f,0.110723f},{-0.289477f,-0.0142459f,0.110723f}, -{-0.289523f,-0.0142272f,0.101401f},{-0.289127f,-0.0143521f,0.110723f},{-0.289153f,-0.0143475f,0.101401f}, -{-0.288764f,-0.0143886f,0.101401f},{-0.288764f,-0.0143886f,0.110723f},{-0.288764f,-0.0125242f,0.111843f}, -{-0.3137f,-0.0105467f,0.110723f},{-0.313689f,-0.0107408f,0.101401f},{-0.313689f,-0.0103508f,0.101401f}, -{-0.313608f,-0.0099696f,0.101401f},{-0.313664f,-0.010183f,0.110723f},{-0.313558f,-0.00983297f,0.110723f}, -{-0.31322f,-0.00929843f,0.101401f},{-0.313386f,-0.00951009f,0.110723f},{-0.31345f,-0.00961418f,0.101401f}, -{-0.31293f,-0.00903788f,0.101401f},{-0.313154f,-0.0092273f,0.110723f},{-0.312871f,-0.00899543f,0.110723f}, -{-0.312593f,-0.00884326f,0.101401f},{-0.312223f,-0.0087231f,0.101401f},{-0.312549f,-0.00882313f,0.110723f}, -{-0.311835f,-0.00868228f,0.101401f},{-0.311835f,-0.00868228f,0.110723f},{-0.312199f,-0.00871703f,0.110723f}, -{-0.313663f,-0.0109109f,0.110723f},{-0.313609f,-0.0111223f,0.101401f},{-0.313556f,-0.0112606f,0.110723f}, -{-0.313384f,-0.0115824f,0.110723f},{-0.31345f,-0.0114782f,0.101401f},{-0.313152f,-0.0118646f,0.110723f}, -{-0.313222f,-0.011793f,0.101401f},{-0.312932f,-0.0120546f,0.101401f},{-0.31287f,-0.0120963f,0.110723f}, -{-0.312548f,-0.0122684f,0.110723f},{-0.312594f,-0.0122497f,0.101401f},{-0.312198f,-0.0123745f,0.110723f}, -{-0.312224f,-0.01237f,0.101401f},{-0.311835f,-0.0124111f,0.101401f},{-0.311835f,-0.0124111f,0.110723f}, -{-0.311835f,-0.0105467f,0.111843f},{-0.318681f,-0.00462052f,0.101401f},{-0.318681f,-0.00462066f,0.104198f}, -{-0.318068f,-0.00466102f,0.101401f},{-0.317455f,-0.00462052f,0.104198f},{-0.317456f,-0.00462066f,0.101401f}, -{-0.318068f,-0.00466102f,0.104198f},{-0.316285f,-0.00430621f,0.101401f},{-0.316285f,-0.00430621f,0.104198f}, -{-0.315741f,-0.00403832f,0.101401f},{-0.316858f,-0.00450127f,0.104198f},{-0.316859f,-0.00450141f,0.101401f}, -{-0.31574f,-0.00403818f,0.104198f},{-0.315234f,-0.00370041f,0.104198f},{-0.315234f,-0.00370055f,0.101401f}, -{-0.314772f,-0.00329584f,0.101401f},{-0.314772f,-0.00329584f,0.104198f},{-0.314368f,-0.00283386f,0.104198f}, -{-0.314368f,-0.0028342f,0.101401f},{-0.31403f,-0.00232777f,0.101401f},{-0.31403f,-0.00232743f,0.104198f}, -{-0.313762f,-0.00178369f,0.101401f},{-0.313762f,-0.00178369f,0.104198f},{-0.313567f,-0.00120944f,0.104198f}, -{-0.313567f,-0.00120978f,0.101401f},{-0.313407f,5.70811e-019f,0.101401f},{-0.313448f,-0.000612842f,0.101401f}, -{-0.313448f,-0.000612502f,0.104198f},{-0.313407f,5.70811e-019f,0.104198f},{-0.319278f,-0.00450141f,0.104198f}, -{-0.319278f,-0.00450127f,0.101401f},{-0.319852f,-0.00430621f,0.104198f},{-0.320396f,-0.00403832f,0.104198f}, -{-0.319852f,-0.00430621f,0.101401f},{-0.320396f,-0.00403818f,0.101401f},{-0.320902f,-0.00370055f,0.104198f}, -{-0.320902f,-0.00370041f,0.101401f},{-0.321364f,-0.00329584f,0.104198f},{-0.321769f,-0.0028342f,0.104198f}, -{-0.321364f,-0.00329584f,0.101401f},{-0.321769f,-0.00283386f,0.101401f},{-0.322106f,-0.00232777f,0.104198f}, -{-0.322107f,-0.00232743f,0.101401f},{-0.322374f,-0.00178369f,0.104198f},{-0.322569f,-0.00120978f,0.104198f}, -{-0.322374f,-0.00178369f,0.101401f},{-0.32257f,-0.00120944f,0.101401f},{-0.322689f,-0.000612842f,0.104198f}, -{-0.322689f,-0.000612502f,0.101401f},{-0.322729f,1.4722e-032f,0.104198f},{-0.322729f,1.4722e-032f,0.101401f}, -{-0.275798f,0.00272711f,0.121909f},{-0.27569f,0.00137858f,0.120045f},{-0.2758f,0.00274679f,0.120045f}, -{-0.276233f,0.00542344f,0.121909f},{-0.276237f,0.00544141f,0.120045f},{-0.276561f,0.00676244f,0.120045f}, -{-0.275689f,0.00136573f,0.121909f},{-0.275653f,3.13946e-018f,0.120045f},{-0.275653f,1.34638e-013f,0.121909f}, -{-0.27598f,0.0040808f,0.121909f},{-0.275983f,0.00410196f,0.120045f},{-0.277098f,0.00848488f,0.121909f}, -{-0.276634f,0.00696342f,0.121909f},{-0.276954f,0.00806238f,0.120045f},{-0.279087f,0.0128178f,0.121909f}, -{-0.278335f,0.0114155f,0.121909f},{-0.278535f,0.0118088f,0.120045f},{-0.277671f,0.00996949f,0.121909f}, -{-0.277414f,0.00933854f,0.120045f},{-0.277942f,0.0105882f,0.120045f},{-0.280696f,0.0152688f,0.120045f}, -{-0.28154f,0.0163461f,0.120045f},{-0.280846f,0.0154686f,0.121909f},{-0.279192f,0.0129975f,0.120045f}, -{-0.279913f,0.0141518f,0.120045f},{-0.279925f,0.0141704f,0.121909f},{-0.283407f,0.0183698f,0.120045f}, -{-0.284064f,0.0189869f,0.121909f},{-0.282925f,0.017875f,0.121909f},{-0.282445f,0.0173811f,0.120045f}, -{-0.281845f,0.0167072f,0.121909f},{-0.287538f,0.0216356f,0.121909f},{-0.285747f,0.0203871f,0.121909f}, -{-0.286574f,0.0209918f,0.120045f},{-0.28442f,0.0193037f,0.120045f},{-0.290086f,0.0230585f,0.120045f}, -{-0.291322f,0.0236188f,0.120045f},{-0.291403f,0.0236531f,0.121909f},{-0.288881f,0.0224332f,0.120045f}, -{-0.289427f,0.0227263f,0.121909f},{-0.295184f,0.0248983f,0.120045f},{-0.295163f,0.024878f,0.121909f}, -{-0.293873f,0.0245398f,0.120045f},{-0.293458f,0.0244103f,0.121909f},{-0.292585f,0.0241129f,0.120045f}, -{-0.298641f,0.0254985f,0.121909f},{-0.297863f,0.0254058f,0.120045f},{-0.299225f,0.0255525f,0.120045f}, -{-0.296515f,0.0251874f,0.120045f},{-0.296889f,0.0252555f,0.121909f},{-0.300404f,0.0256204f,0.121909f}, -{-0.301979f,0.0256263f,0.120045f},{-0.302172f,0.0256204f,0.121909f},{-0.300599f,0.0256264f,0.120045f}, -{-0.304715f,0.0254057f,0.120045f},{-0.306062f,0.0251873f,0.120045f},{-0.305688f,0.0252554f,0.121909f}, -{-0.303936f,0.0254985f,0.121909f},{-0.303353f,0.0255524f,0.120045f},{-0.309992f,0.0241129f,0.120045f}, -{-0.309119f,0.0244103f,0.121909f},{-0.308704f,0.0245398f,0.120045f},{-0.307416f,0.0248864f,0.121909f}, -{-0.307393f,0.0248983f,0.120045f},{-0.31315f,0.0227264f,0.121909f},{-0.311173f,0.0236533f,0.121909f}, -{-0.312491f,0.0230584f,0.120045f},{-0.311255f,0.0236187f,0.120045f},{-0.315039f,0.0216357f,0.121909f}, -{-0.314868f,0.0217438f,0.120045f},{-0.316004f,0.0209917f,0.120045f},{-0.313696f,0.0224331f,0.120045f}, -{-0.318157f,0.0193036f,0.120045f},{-0.31917f,0.0183692f,0.120045f},{-0.318513f,0.0189869f,0.121909f}, -{-0.31683f,0.0203873f,0.121909f},{-0.317101f,0.020178f,0.120045f},{-0.320133f,0.0173806f,0.120045f}, -{-0.321037f,0.016346f,0.120045f},{-0.320732f,0.0167073f,0.121909f},{-0.319646f,0.0178697f,0.121909f}, -{-0.321731f,0.0154687f,0.121909f},{-0.321881f,0.0152688f,0.120045f},{-0.322664f,0.0141517f,0.120045f}, -{-0.322652f,0.0141707f,0.121909f},{-0.323385f,0.0129974f,0.120045f},{-0.32349f,0.0128178f,0.121909f}, -{-0.324042f,0.0118086f,0.120045f},{-0.324242f,0.0114158f,0.121909f},{-0.324906f,0.0099697f,0.121909f}, -{-0.324635f,0.010588f,0.120045f},{-0.325163f,0.00933828f,0.120045f},{-0.325479f,0.00848516f,0.121909f}, -{-0.325623f,0.00806211f,0.120045f},{-0.32595f,0.00696571f,0.121909f},{-0.326344f,0.00542344f,0.121909f}, -{-0.326016f,0.00676218f,0.120045f},{-0.326594f,0.00410176f,0.120045f},{-0.32634f,0.00544117f,0.120045f}, -{-0.326777f,0.00274665f,0.120045f},{-0.326597f,0.00408095f,0.121909f},{-0.326779f,0.00272732f,0.121909f}, -{-0.326887f,0.0013785f,0.120045f},{-0.326924f,0.0f,0.120045f},{-0.326888f,0.00136552f,0.121909f}, -{-0.326924f,-1.34635e-013f,0.121909f},{-0.28771f,0.0217439f,0.120045f},{-0.285476f,0.0201781f,0.120045f}, -{-0.276585f,-3.95917e-017f,0.104011f},{-0.275187f,-8.69362e-018f,0.10513f},{-0.275244f,-0.00172399f,0.10513f}, -{-0.286411f,0.0173288f,0.10252f},{-0.287162f,0.0161291f,0.101401f},{-0.288252f,0.0170222f,0.101401f}, -{-0.286128f,0.0151609f,0.101401f},{-0.2881f,0.0186467f,0.10252f},{-0.286807f,0.0217163f,0.10513f}, -{-0.288937f,0.0213938f,0.104011f},{-0.288254f,0.0226142f,0.10513f},{-0.289393f,0.0178384f,0.101401f}, -{-0.289869f,0.0197792f,0.10252f},{-0.289753f,0.0234144f,0.10513f},{-0.291813f,0.0192333f,0.101401f}, -{-0.2913f,0.0241148f,0.10513f},{-0.293084f,0.0198086f,0.101401f},{-0.292889f,0.0247131f,0.10513f}, -{-0.294389f,0.0203001f,0.101401f},{-0.295724f,0.0207061f,0.101401f},{-0.294514f,0.0252074f,0.10513f}, -{-0.297086f,0.0210249f,0.101401f},{-0.296173f,0.0255955f,0.10513f},{-0.297858f,0.0258753f,0.10513f}, -{-0.29847f,0.0212548f,0.101401f},{-0.299565f,0.0260447f,0.10513f},{-0.299873f,0.021394f,0.101401f}, -{-0.301289f,0.0261017f,0.10513f},{-0.284828f,0.0158329f,0.10252f},{-0.285159f,0.0141266f,0.101401f}, -{-0.283379f,0.0141734f,0.10252f},{-0.284266f,0.0130367f,0.101401f},{-0.28345f,0.0118953f,0.101401f}, -{-0.282089f,0.0123685f,0.10252f},{-0.282713f,0.010707f,0.101401f},{-0.280977f,0.0104425f,0.10252f}, -{-0.282055f,0.00947547f,0.101401f},{-0.280059f,0.00842229f,0.10252f},{-0.28148f,0.00820499f,0.101401f}, -{-0.276081f,0.00677384f,0.10513f},{-0.275693f,0.00511591f,0.10513f},{-0.27701f,0.0045642f,0.104011f}, -{-0.279347f,0.00633756f,0.10252f},{-0.280988f,0.0069f,0.101401f},{-0.278843f,0.00421935f,0.10252f}, -{-0.280582f,0.00556442f,0.101401f},{-0.280264f,0.00420236f,0.101401f},{-0.278546f,0.00209692f,0.10252f}, -{-0.280034f,0.00281829f,0.101401f},{-0.275244f,0.00172376f,0.10513f},{-0.27845f,-3.77853e-017f,0.10252f}, -{-0.279895f,0.00141614f,0.101401f},{-0.280042f,-0.00288015f,0.101401f},{-0.279896f,-0.00144343f,0.101401f}, -{-0.275413f,-0.00343096f,0.10513f},{-0.281053f,-0.00708591f,0.101401f},{-0.280622f,-0.00570761f,0.101401f}, -{-0.276575f,-0.0084f,0.10513f},{-0.280284f,-0.00430368f,0.101401f},{-0.275693f,-0.00511591f,0.10513f}, -{-0.276081f,-0.00677408f,0.10513f},{-0.282188f,-0.00973971f,0.101401f},{-0.278674f,-0.0130346f,0.10513f}, -{-0.282887f,-0.0110032f,0.101401f},{-0.277174f,-0.00998868f,0.10513f},{-0.277874f,-0.0115354f,0.10513f}, -{-0.281576f,-0.00843197f,0.101401f},{-0.280566f,-0.0158708f,0.10513f},{-0.281653f,-0.0171976f,0.10513f}, -{-0.284531f,-0.0133753f,0.101401f},{-0.283669f,-0.012217f,0.101401f},{-0.279572f,-0.0144813f,0.10513f}, -{-0.285418f,-0.0207227f,0.10513f},{-0.287557f,-0.0164663f,0.101401f},{-0.284091f,-0.0196355f,0.10513f}, -{-0.28648f,-0.0155046f,0.101401f},{-0.28547f,-0.0144728f,0.101401f},{-0.282832f,-0.0184567f,0.10513f}, -{-0.291141f,-0.0188871f,0.101401f},{-0.289893f,-0.0181615f,0.101401f},{-0.289869f,-0.0197792f,0.10252f}, -{-0.288696f,-0.0173533f,0.101401f},{-0.288937f,-0.0213938f,0.104011f},{-0.288254f,-0.0226143f,0.10513f}, -{-0.290308f,-0.0221291f,0.104011f},{-0.291745f,-0.0227855f,0.104011f},{-0.2913f,-0.0241148f,0.10513f}, -{-0.29324f,-0.0233556f,0.104011f},{-0.289753f,-0.0234145f,0.10513f},{-0.294786f,-0.0238322f,0.104011f}, -{-0.294515f,-0.0252075f,0.10513f},{-0.296374f,-0.0242096f,0.104011f},{-0.292889f,-0.0247132f,0.10513f}, -{-0.297994f,-0.0244827f,0.104011f},{-0.296173f,-0.0255955f,0.10513f},{-0.297858f,-0.0258754f,0.10513f}, -{-0.299565f,-0.0260448f,0.10513f},{-0.299636f,-0.0246481f,0.104011f},{-0.301289f,-0.0261017f,0.10513f}, -{-0.301289f,-0.0247034f,0.104011f},{-0.286807f,-0.0217163f,0.10513f},{-0.296745f,-0.0223824f,0.10252f}, -{-0.296535f,-0.0209041f,0.101401f},{-0.295277f,-0.0220336f,0.10252f},{-0.298242f,-0.022635f,0.10252f}, -{-0.297953f,-0.0211784f,0.101401f},{-0.299386f,-0.0213558f,0.101401f},{-0.29976f,-0.0227878f,0.10252f}, -{-0.301289f,-0.022839f,0.10252f},{-0.295138f,-0.0205399f,0.101401f},{-0.29377f,-0.0200791f,0.101401f}, -{-0.292465f,-0.0210659f,0.10252f},{-0.293848f,-0.0215929f,0.10252f},{-0.292435f,-0.0195273f,0.101401f}, -{-0.291137f,-0.0204589f,0.10252f},{-0.287025f,0.0201691f,0.104011f},{-0.290582f,0.018576f,0.101401f}, -{-0.285197f,0.0187435f,0.104011f},{-0.285418f,0.0207226f,0.10513f},{-0.282832f,0.0184567f,0.10513f}, -{-0.284091f,0.0196354f,0.10513f},{-0.283485f,0.017126f,0.104011f},{-0.281918f,0.015331f,0.104011f}, -{-0.281653f,0.0171974f,0.10513f},{-0.279572f,0.0144813f,0.10513f},{-0.280566f,0.0158706f,0.10513f}, -{-0.280522f,0.0133791f,0.104011f},{-0.279319f,0.011296f,0.104011f},{-0.278674f,0.0130343f,0.10513f}, -{-0.277874f,0.0115351f,0.10513f},{-0.278326f,0.00911062f,0.104011f},{-0.277174f,0.00998868f,0.10513f}, -{-0.277555f,0.00685616f,0.104011f},{-0.276575f,0.00839976f,0.10513f},{-0.276689f,0.00226928f,0.104011f}, -{-0.275413f,0.00343072f,0.10513f},{-0.279848f,3.60164e-017f,0.10513f},{-0.279848f,-9.52159e-018f,0.106062f}, -{-0.279885f,-0.00125938f,0.106062f},{-0.279995f,-0.00250813f,0.106062f},{-0.279885f,-0.00125925f,0.10513f}, -{-0.280177f,-0.00374334f,0.106062f},{-0.279995f,-0.00250793f,0.10513f},{-0.280177f,-0.00374312f,0.10513f}, -{-0.28043f,-0.00496208f,0.106062f},{-0.280752f,-0.00616144f,0.106062f},{-0.28043f,-0.00496191f,0.10513f}, -{-0.281143f,-0.00733859f,0.106062f},{-0.280752f,-0.00616138f,0.10513f},{-0.281143f,-0.0073385f,0.10513f}, -{-0.281601f,-0.00849054f,0.106062f},{-0.282124f,-0.0096143f,0.106062f},{-0.281601f,-0.00849036f,0.10513f}, -{-0.282713f,-0.010707f,0.106062f},{-0.282124f,-0.00961408f,0.10513f},{-0.282713f,-0.0107068f,0.10513f}, -{-0.283364f,-0.0117656f,0.106062f},{-0.284078f,-0.0127873f,0.106062f},{-0.283364f,-0.0117655f,0.10513f}, -{-0.284853f,-0.0137693f,0.106062f},{-0.284078f,-0.0127873f,0.10513f},{-0.284853f,-0.0137691f,0.10513f}, -{-0.285689f,-0.0147088f,0.106062f},{-0.28658f,-0.0156004f,0.106062f},{-0.285688f,-0.0147082f,0.10513f}, -{-0.287519f,-0.0164352f,0.106062f},{-0.28658f,-0.0155998f,0.10513f},{-0.287519f,-0.0164352f,0.10513f}, -{-0.288501f,-0.0172102f,0.106062f},{-0.289523f,-0.0179243f,0.106062f},{-0.288501f,-0.0172102f,0.10513f}, -{-0.290582f,-0.018576f,0.106062f},{-0.289523f,-0.0179242f,0.10513f},{-0.290582f,-0.018576f,0.10513f}, -{-0.291674f,-0.0191643f,0.106062f},{-0.292798f,-0.019688f,0.106062f},{-0.291674f,-0.0191643f,0.10513f}, -{-0.29395f,-0.0201457f,0.106062f},{-0.292798f,-0.0196879f,0.10513f},{-0.29395f,-0.0201457f,0.10513f}, -{-0.295127f,-0.0205363f,0.106062f},{-0.296327f,-0.0208587f,0.106062f},{-0.295127f,-0.0205363f,0.10513f}, -{-0.296326f,-0.0208586f,0.10513f},{-0.297545f,-0.0211114f,0.10513f},{-0.29878f,-0.0212935f,0.10513f}, -{-0.297545f,-0.0211115f,0.106062f},{-0.300029f,-0.0214037f,0.106062f},{-0.298781f,-0.0212936f,0.106062f}, -{-0.301289f,-0.0214407f,0.106062f},{-0.300029f,-0.0214037f,0.10513f},{-0.301289f,-0.0214407f,0.10513f}, -{-0.279885f,0.00125938f,0.10513f},{-0.279995f,0.00250813f,0.10513f},{-0.279885f,0.00125925f,0.106062f}, -{-0.279995f,0.00250793f,0.106062f},{-0.280177f,0.00374334f,0.10513f},{-0.28043f,0.00496208f,0.10513f}, -{-0.280177f,0.00374312f,0.106062f},{-0.280752f,0.00616144f,0.10513f},{-0.28043f,0.00496191f,0.106062f}, -{-0.280752f,0.00616138f,0.106062f},{-0.281143f,0.00733859f,0.10513f},{-0.281601f,0.00849054f,0.10513f}, -{-0.281143f,0.0073385f,0.106062f},{-0.282124f,0.0096143f,0.10513f},{-0.281601f,0.00849036f,0.106062f}, -{-0.282124f,0.00961408f,0.106062f},{-0.282713f,0.010707f,0.10513f},{-0.283364f,0.0117656f,0.10513f}, -{-0.282713f,0.0107068f,0.106062f},{-0.284078f,0.0127873f,0.10513f},{-0.283364f,0.0117655f,0.106062f}, -{-0.284078f,0.0127873f,0.106062f},{-0.284853f,0.0137693f,0.10513f},{-0.285689f,0.0147088f,0.10513f}, -{-0.284853f,0.0137691f,0.106062f},{-0.28658f,0.0156004f,0.10513f},{-0.285688f,0.0147082f,0.106062f}, -{-0.28658f,0.0155998f,0.106062f},{-0.287519f,0.0164352f,0.10513f},{-0.288501f,0.0172102f,0.10513f}, -{-0.287519f,0.0164352f,0.106062f},{-0.289523f,0.0179243f,0.10513f},{-0.288501f,0.0172102f,0.106062f}, -{-0.289523f,0.0179242f,0.106062f},{-0.290582f,0.018576f,0.10513f},{-0.291674f,0.0191643f,0.10513f}, -{-0.290582f,0.018576f,0.106062f},{-0.292798f,0.019688f,0.10513f},{-0.291674f,0.0191643f,0.106062f}, -{-0.292798f,0.0196879f,0.106062f},{-0.29395f,0.0201457f,0.10513f},{-0.295127f,0.0205363f,0.10513f}, -{-0.29395f,0.0201457f,0.106062f},{-0.296327f,0.0208587f,0.10513f},{-0.295127f,0.0205363f,0.106062f}, -{-0.297545f,0.0211114f,0.106062f},{-0.296326f,0.0208586f,0.106062f},{-0.297545f,0.0211115f,0.10513f}, -{-0.29878f,0.0212935f,0.106062f},{-0.298781f,0.0212936f,0.10513f},{-0.300029f,0.0214037f,0.10513f}, -{-0.300029f,0.0214037f,0.106062f},{-0.301289f,0.0214407f,0.10513f},{-0.301289f,0.0214407f,0.106062f}, -{-0.275187f,1.78012e-017f,0.106062f},{-0.275187f,2.1941e-017f,0.120045f},{-0.275223f,-0.00138032f,0.120045f}, -{-0.275332f,-0.00275048f,0.120045f},{-0.275223f,-0.00138025f,0.106062f},{-0.275512f,-0.0041079f,0.120045f}, -{-0.275332f,-0.00275036f,0.106062f},{-0.275512f,-0.00410773f,0.106062f},{-0.275762f,-0.00544996f,0.120045f}, -{-0.276081f,-0.00677408f,0.120045f},{-0.275762f,-0.00544975f,0.106062f},{-0.276468f,-0.00807765f,0.120045f}, -{-0.276081f,-0.00677384f,0.106062f},{-0.276468f,-0.0080774f,0.106062f},{-0.276922f,-0.00935809f,0.120045f}, -{-0.277442f,-0.0106128f,0.120045f},{-0.276922f,-0.00935782f,0.106062f},{-0.278026f,-0.0118391f,0.120045f}, -{-0.277442f,-0.0106125f,0.106062f},{-0.278026f,-0.0118389f,0.106062f},{-0.278674f,-0.0130346f,0.120045f}, -{-0.279385f,-0.0141964f,0.120045f},{-0.278674f,-0.0130343f,0.106062f},{-0.280157f,-0.0153222f,0.120045f}, -{-0.279385f,-0.0141962f,0.106062f},{-0.280157f,-0.015322f,0.106062f},{-0.28099f,-0.0164092f,0.120045f}, -{-0.281882f,-0.0174549f,0.120045f},{-0.28099f,-0.0164091f,0.106062f},{-0.282832f,-0.0184567f,0.120045f}, -{-0.281882f,-0.0174549f,0.106062f},{-0.282832f,-0.0184567f,0.106062f},{-0.283834f,-0.0194069f,0.120045f}, -{-0.284879f,-0.0202989f,0.120045f},{-0.283834f,-0.0194069f,0.106062f},{-0.285967f,-0.0211315f,0.120045f}, -{-0.284879f,-0.0202988f,0.106062f},{-0.285966f,-0.0211314f,0.106062f},{-0.287092f,-0.0219036f,0.120045f}, -{-0.288254f,-0.0226143f,0.120045f},{-0.287092f,-0.0219036f,0.106062f},{-0.28945f,-0.0232624f,0.120045f}, -{-0.288254f,-0.0226142f,0.106062f},{-0.289449f,-0.0232623f,0.106062f},{-0.290676f,-0.0238468f,0.120045f}, -{-0.291931f,-0.0243666f,0.120045f},{-0.290676f,-0.0238467f,0.106062f},{-0.293211f,-0.0248205f,0.120045f}, -{-0.29193f,-0.0243664f,0.106062f},{-0.293211f,-0.0248204f,0.106062f},{-0.294515f,-0.0252075f,0.120045f}, -{-0.295839f,-0.0255265f,0.120045f},{-0.294514f,-0.0252074f,0.106062f},{-0.297181f,-0.0257766f,0.120045f}, -{-0.295839f,-0.0255265f,0.106062f},{-0.297181f,-0.0257765f,0.106062f},{-0.298538f,-0.0259565f,0.120045f}, -{-0.299908f,-0.0260653f,0.120045f},{-0.298538f,-0.0259565f,0.106062f},{-0.301289f,-0.0261017f,0.120045f}, -{-0.299908f,-0.0260652f,0.106062f},{-0.301289f,-0.0261017f,0.106062f},{-0.275223f,0.00138032f,0.106062f}, -{-0.275332f,0.00275048f,0.106062f},{-0.275223f,0.00138025f,0.120045f},{-0.275332f,0.00275036f,0.120045f}, -{-0.275512f,0.0041079f,0.106062f},{-0.275762f,0.00544996f,0.106062f},{-0.275512f,0.00410773f,0.120045f}, -{-0.276081f,0.00677408f,0.106062f},{-0.275762f,0.00544975f,0.120045f},{-0.276081f,0.00677384f,0.120045f}, -{-0.276468f,0.00807765f,0.106062f},{-0.276922f,0.00935809f,0.106062f},{-0.276468f,0.0080774f,0.120045f}, -{-0.277442f,0.0106128f,0.106062f},{-0.276922f,0.00935782f,0.120045f},{-0.277442f,0.0106125f,0.120045f}, -{-0.278026f,0.0118391f,0.106062f},{-0.278674f,0.0130346f,0.106062f},{-0.278026f,0.0118389f,0.120045f}, -{-0.279385f,0.0141964f,0.106062f},{-0.278674f,0.0130343f,0.120045f},{-0.279385f,0.0141962f,0.120045f}, -{-0.280157f,0.0153222f,0.106062f},{-0.28099f,0.0164092f,0.106062f},{-0.280157f,0.015322f,0.120045f}, -{-0.281882f,0.0174549f,0.106062f},{-0.28099f,0.0164091f,0.120045f},{-0.281882f,0.0174549f,0.120045f}, -{-0.282832f,0.0184567f,0.106062f},{-0.283834f,0.0194069f,0.106062f},{-0.282832f,0.0184567f,0.120045f}, -{-0.284879f,0.0202989f,0.106062f},{-0.283834f,0.0194069f,0.120045f},{-0.284879f,0.0202988f,0.120045f}, -{-0.285967f,0.0211315f,0.106062f},{-0.287092f,0.0219036f,0.106062f},{-0.285966f,0.0211314f,0.120045f}, -{-0.288254f,0.0226143f,0.106062f},{-0.287092f,0.0219036f,0.120045f},{-0.288254f,0.0226142f,0.120045f}, -{-0.28945f,0.0232624f,0.106062f},{-0.290676f,0.0238468f,0.106062f},{-0.289449f,0.0232623f,0.120045f}, -{-0.291931f,0.0243666f,0.106062f},{-0.290676f,0.0238467f,0.120045f},{-0.29193f,0.0243664f,0.120045f}, -{-0.293211f,0.0248205f,0.106062f},{-0.294515f,0.0252075f,0.106062f},{-0.293211f,0.0248204f,0.120045f}, -{-0.295839f,0.0255265f,0.106062f},{-0.294514f,0.0252074f,0.120045f},{-0.295839f,0.0255265f,0.120045f}, -{-0.297181f,0.0257766f,0.106062f},{-0.298538f,0.0259565f,0.106062f},{-0.297181f,0.0257765f,0.120045f}, -{-0.299908f,0.0260653f,0.106062f},{-0.298538f,0.0259565f,0.120045f},{-0.299908f,0.0260652f,0.120045f}, -{-0.301289f,0.0261017f,0.106062f},{-0.301289f,0.0261017f,0.120045f},{-0.289155f,-0.00289006f,0.125638f}, -{-0.316278f,0.00596973f,0.125638f},{-0.316319f,0.00652514f,0.125638f},{-0.320415f,0.00374099f,0.125638f}, -{-0.309396f,-0.0152805f,0.125638f},{-0.309911f,0.0149353f,0.125638f},{-0.305018f,0.0130513f,0.125638f}, -{-0.309397f,0.0152802f,0.125638f},{-0.313508f,0.0144863f,0.125638f},{-0.314092f,0.0146944f,0.125638f}, -{-0.314299f,0.0103166f,0.125638f},{-0.296052f,0.00984656f,0.125638f},{-0.296433f,0.00992732f,0.125638f}, -{-0.303153f,0.0162797f,0.125638f},{-0.305069f,0.0215779f,0.125638f},{-0.307586f,0.019053f,0.125638f}, -{-0.29185f,0.00975506f,0.125638f},{-0.29211f,0.0146618f,0.125638f},{-0.292666f,0.0149353f,0.125638f}, -{-0.292311f,0.00944145f,0.125638f},{-0.284043f,9.3146e-019f,0.125638f},{-0.284001f,0.000618856f,0.125638f}, -{-0.290295f,0.0143109f,0.125638f},{-0.290264f,0.0102438f,0.125638f},{-0.289707f,0.0102437f,0.125638f}, -{-0.28049f,-0.00452954f,0.125638f},{-0.280243f,-0.00608354f,0.125638f},{-0.279878f,-0.00463457f,0.125638f}, -{-0.283879f,-0.00122583f,0.125638f},{-0.284002f,-0.000618365f,0.125638f},{-0.287661f,-0.00361044f,0.125638f}, -{-0.282163f,-0.00374099f,0.125638f},{-0.286299f,-0.00596973f,0.125638f},{-0.286258f,-0.00652514f,0.125638f}, -{-0.281077f,-0.00433369f,0.125638f},{-0.286299f,-0.00708106f,0.125638f},{-0.286424f,-0.00762403f,0.125638f}, -{-0.28128f,-0.00891935f,0.125638f},{-0.291348f,-0.00305413f,0.125638f},{-0.290815f,-0.00288693f,0.125638f}, -{-0.286907f,-0.00862484f,0.125638f},{-0.282708f,-0.0116055f,0.125638f},{-0.281947f,-0.0102864f,0.125638f}, -{-0.280711f,-0.00751463f,0.125638f},{-0.281639f,-0.00407246f,0.125638f},{-0.284491f,-0.0140624f,0.125638f}, -{-0.287935f,-0.0149788f,0.125638f},{-0.285497f,-0.0151839f,0.125638f},{-0.287661f,-0.00944085f,0.125638f}, -{-0.287426f,-0.015333f,0.125638f},{-0.286967f,-0.0157495f,0.125638f},{-0.286569f,-0.0162251f,0.125638f}, -{-0.286629f,-0.00814252f,0.125638f},{-0.286299f,0.00708097f,0.125638f},{-0.280711f,0.00751594f,0.125638f}, -{-0.286423f,-0.00542663f,0.125638f},{-0.282634f,-0.00333905f,0.125638f},{-0.283048f,-0.00287783f,0.125638f}, -{-0.283398f,-0.0023656f,0.125638f},{-0.286905f,-0.00442541f,0.125638f},{-0.286626f,-0.00490799f,0.125638f}, -{-0.29072f,0.0013863f,0.125638f},{-0.290459f,0.00109643f,0.125638f},{-0.283878f,0.00122657f,0.125638f}, -{-0.291035f,0.00161492f,0.125638f},{-0.293181f,0.0152805f,0.125638f},{-0.293646f,0.0156909f,0.125638f}, -{-0.282161f,0.00374048f,0.125638f},{-0.287937f,0.0149805f,0.125638f},{-0.285497f,0.0151839f,0.125638f}, -{-0.28743f,0.0153371f,0.125638f},{-0.286966f,0.0157476f,0.125638f},{-0.286569f,0.0162251f,0.125638f}, -{-0.288624f,0.00999629f,0.125638f},{-0.288486f,0.0146931f,0.125638f},{-0.28907f,0.0144856f,0.125638f}, -{-0.289676f,0.0143575f,0.125638f},{-0.289156f,0.0101606f,0.125638f},{-0.287254f,0.00906122f,0.125638f}, -{-0.28356f,0.0128683f,0.125638f},{-0.287662f,0.00944057f,0.125638f},{-0.288122f,0.00975455f,0.125638f}, -{-0.281948f,0.0102881f,0.125638f},{-0.28271f,0.0116071f,0.125638f},{-0.286629f,0.00814199f,0.125638f}, -{-0.284492f,0.0140632f,0.125638f},{-0.281639f,0.00407552f,0.125638f},{-0.281079f,0.00433883f,0.125638f}, -{-0.280243f,0.00608354f,0.125638f},{-0.280488f,0.0045282f,0.125638f},{-0.279878f,0.00463457f,0.125638f}, -{-0.286907f,0.00862459f,0.125638f},{-0.28128f,0.008921f,0.125638f},{-0.286424f,0.00762395f,0.125638f}, -{-0.307641f,0.0196708f,0.125638f},{-0.306543f,0.0212675f,0.125638f},{-0.307765f,0.0202771f,0.125638f}, -{-0.294052f,0.0161593f,0.125638f},{-0.294392f,0.0166773f,0.125638f},{-0.282634f,0.00333893f,0.125638f}, -{-0.294964f,0.0184349f,0.125638f},{-0.294853f,0.0178252f,0.125638f},{-0.283397f,0.00236609f,0.125638f}, -{-0.283048f,0.00287783f,0.125638f},{-0.311664f,0.0143468f,0.125638f},{-0.312283f,0.0143112f,0.125638f}, -{-0.309678f,-0.0016145f,0.125638f},{-0.304976f,0.0136072f,0.125638f},{-0.304852f,0.0141506f,0.125638f}, -{-0.308932f,0.0156903f,0.125638f},{-0.307612f,0.0184341f,0.125638f},{-0.307724f,0.0178247f,0.125638f}, -{-0.303613f,0.015966f,0.125638f},{-0.302118f,0.0166853f,0.125638f},{-0.303568f,0.0217877f,0.125638f}, -{-0.302651f,0.0165216f,0.125638f},{-0.307916f,0.0172353f,0.125638f},{-0.304022f,0.0155872f,0.125638f}, -{-0.297509f,0.0215784f,0.125638f},{-0.299926f,0.0165218f,0.125638f},{-0.30101f,0.0167668f,0.125638f}, -{-0.300528f,0.0218936f,0.125638f},{-0.301567f,0.0167671f,0.125638f},{-0.294994f,0.0190544f,0.125638f}, -{-0.296034f,0.0212675f,0.125638f},{-0.30798f,0.0208597f,0.125638f},{-0.294941f,0.0196718f,0.125638f}, -{-0.29481f,0.0202777f,0.125638f},{-0.294597f,0.0208597f,0.125638f},{-0.304369f,0.0151517f,0.125638f}, -{-0.308185f,0.0166765f,0.125638f},{-0.304648f,0.0146693f,0.125638f},{-0.29901f,0.0217881f,0.125638f}, -{-0.300459f,0.0166848f,0.125638f},{-0.315951f,0.00490799f,0.125638f},{-0.319179f,0.0023656f,0.125638f}, -{-0.315672f,0.00442541f,0.125638f},{-0.297205f,0.00984589f,0.125638f},{-0.296823f,0.00992719f,0.125638f}, -{-0.310468f,0.0146616f,0.125638f},{-0.314299f,-0.00115727f,0.125638f},{-0.307613f,-0.0184349f,0.125638f}, -{-0.307724f,-0.0178252f,0.125638f},{-0.311056f,0.0144643f,0.125638f},{-0.321866f,0.00751463f,0.125638f}, -{-0.322334f,0.00608354f,0.125638f},{-0.320938f,0.00407246f,0.125638f},{-0.314916f,0.00944085f,0.125638f}, -{-0.319018f,0.0128671f,0.125638f},{-0.315323f,0.00906082f,0.125638f},{-0.307198f,0.00945782f,0.125638f}, -{-0.322087f,0.00452954f,0.125638f},{-0.322699f,0.00463457f,0.125638f},{-0.315325f,0.00398966f,0.125638f}, -{-0.318698f,0.00122583f,0.125638f},{-0.314916f,0.00361044f,0.125638f},{-0.319529f,0.00287783f,0.125638f}, -{-0.316154f,0.00542663f,0.125638f},{-0.319943f,0.00333905f,0.125638f},{-0.3215f,0.00433369f,0.125638f}, -{-0.316278f,0.00708106f,0.125638f},{-0.316153f,0.00762403f,0.125638f},{-0.321297f,0.00891935f,0.125638f}, -{-0.32063f,0.0102864f,0.125638f},{-0.31567f,0.00862484f,0.125638f},{-0.319869f,0.0116055f,0.125638f}, -{-0.315948f,0.00814252f,0.125638f},{-0.314643f,0.0149788f,0.125638f},{-0.31708f,0.0151839f,0.125638f}, -{-0.318086f,0.0140624f,0.125638f},{-0.315151f,0.015333f,0.125638f},{-0.311055f,-0.0144645f,0.125638f}, -{-0.310468f,-0.0146618f,0.125638f},{-0.311229f,-0.00999677f,0.125638f},{-0.31561f,0.0157495f,0.125638f}, -{-0.316008f,0.0162251f,0.125638f},{-0.307653f,0.00883069f,0.125638f},{-0.307773f,0.00845974f,0.125638f}, -{-0.318901f,-0.00181243f,0.125638f},{-0.31918f,-0.00236609f,0.125638f},{-0.312901f,0.014358f,0.125638f}, -{-0.309911f,-0.0149353f,0.125638f},{-0.310727f,-0.00975506f,0.125638f},{-0.304441f,-0.00916839f,0.125638f}, -{-0.304246f,-0.00883048f,0.125638f},{-0.311762f,-0.0101609f,0.125638f},{-0.320938f,-0.00407552f,0.125638f}, -{-0.321866f,-0.00751594f,0.125638f},{-0.318085f,-0.0140632f,0.125638f},{-0.31708f,-0.0151839f,0.125638f}, -{-0.314299f,-0.0126311f,0.125638f},{-0.313507f,-0.0144856f,0.125638f},{-0.312901f,-0.0143575f,0.125638f}, -{-0.318576f,0.000618365f,0.125638f},{-0.318699f,-0.00122657f,0.125638f},{-0.318534f,4.85606e-018f,0.125638f}, -{-0.308525f,-0.0161593f,0.125638f},{-0.308185f,-0.0166773f,0.125638f},{-0.315148f,-0.0153371f,0.125638f}, -{-0.31464f,-0.0149805f,0.125638f},{-0.31287f,-0.0102437f,0.125638f},{-0.313421f,-0.0101606f,0.125638f}, -{-0.315324f,-0.00906122f,0.125638f},{-0.319017f,-0.0128683f,0.125638f},{-0.314916f,-0.00944057f,0.125638f}, -{-0.31567f,-0.00862459f,0.125638f},{-0.319868f,-0.0116071f,0.125638f},{-0.320629f,-0.0102881f,0.125638f}, -{-0.315948f,-0.00814199f,0.125638f},{-0.316278f,-0.00708097f,0.125638f},{-0.314455f,-0.00975455f,0.125638f}, -{-0.313953f,-0.00999629f,0.125638f},{-0.322334f,-0.00608354f,0.125638f},{-0.315611f,-0.0157476f,0.125638f}, -{-0.321499f,-0.00433883f,0.125638f},{-0.322089f,-0.0045282f,0.125638f},{-0.316008f,-0.0162251f,0.125638f}, -{-0.322699f,-0.00463457f,0.125638f},{-0.312313f,-0.0102438f,0.125638f},{-0.292544f,0.00177278f,0.125638f}, -{-0.292899f,0.0016145f,0.125638f},{-0.306524f,-0.00984657f,0.125638f},{-0.306144f,-0.00992738f,0.125638f}, -{-0.294925f,-0.00731413f,0.125638f},{-0.29512f,-0.00697672f,0.125638f},{-0.307584f,-0.0190544f,0.125638f}, -{-0.305068f,-0.0215784f,0.125638f},{-0.291351f,-0.0126311f,0.125638f},{-0.290294f,-0.0143112f,0.125638f}, -{-0.289676f,-0.014358f,0.125638f},{-0.297726f,-0.0141506f,0.125638f},{-0.293645f,-0.0156903f,0.125638f}, -{-0.297601f,-0.0136072f,0.125638f},{-0.291521f,-0.0144643f,0.125638f},{-0.292109f,-0.0146616f,0.125638f}, -{-0.294853f,-0.0178247f,0.125638f},{-0.298964f,-0.015966f,0.125638f},{-0.294965f,-0.0184341f,0.125638f}, -{-0.293181f,-0.0152802f,0.125638f},{-0.292666f,-0.0149353f,0.125638f},{-0.29756f,-0.0130513f,0.125638f}, -{-0.297508f,-0.0215779f,0.125638f},{-0.294991f,-0.019053f,0.125638f},{-0.299424f,-0.0162797f,0.125638f}, -{-0.290143f,0.000388892f,0.125638f},{-0.290263f,0.000758756f,0.125638f},{-0.321297f,-0.008921f,0.125638f}, -{-0.316153f,-0.00762395f,0.125638f},{-0.312283f,-0.0143109f,0.125638f},{-0.293552f,0.00762671f,0.125638f}, -{-0.312314f,-0.000758756f,0.125638f},{-0.312434f,-0.000388892f,0.125638f},{-0.308931f,-0.0156909f,0.125638f}, -{-0.311857f,-0.0013863f,0.125638f},{-0.293215f,0.00138471f,0.125638f},{-0.302118f,-0.0166848f,0.125638f}, -{-0.302651f,-0.0165218f,0.125638f},{-0.303567f,-0.0217881f,0.125638f},{-0.301567f,-0.0167668f,0.125638f}, -{-0.302049f,-0.0218936f,0.125638f},{-0.30101f,-0.0167671f,0.125638f},{-0.300459f,-0.0166853f,0.125638f}, -{-0.299009f,-0.0217877f,0.125638f},{-0.299926f,-0.0165216f,0.125638f},{-0.306543f,-0.0212675f,0.125638f}, -{-0.307636f,-0.0196718f,0.125638f},{-0.307767f,-0.0202777f,0.125638f},{-0.30798f,-0.0208597f,0.125638f}, -{-0.297929f,-0.0146693f,0.125638f},{-0.298208f,-0.0151517f,0.125638f},{-0.294392f,-0.0166765f,0.125638f}, -{-0.298555f,-0.0155872f,0.125638f},{-0.294661f,-0.0172353f,0.125638f},{-0.296034f,-0.0212675f,0.125638f}, -{-0.294936f,-0.0196708f,0.125638f},{-0.294597f,-0.0208597f,0.125638f},{-0.294812f,-0.0202771f,0.125638f}, -{-0.283676f,0.00181243f,0.125638f},{-0.291348f,0.00999677f,0.125638f},{-0.290913f,0.0143468f,0.125638f}, -{-0.291522f,0.0144645f,0.125638f},{-0.290815f,0.0101609f,0.125638f},{-0.292162f,0.00185398f,0.125638f}, -{-0.291772f,0.00185425f,0.125638f},{-0.291391f,0.0017734f,0.125638f},{-0.287252f,-0.00398966f,0.125638f}, -{-0.290264f,-0.00281666f,0.125638f},{-0.283559f,-0.0128671f,0.125638f},{-0.287254f,-0.00906082f,0.125638f}, -{-0.293062f,0.00862453f,0.125638f},{-0.305373f,0.00630002f,0.125638f},{-0.305754f,0.00621904f,0.125638f}, -{-0.319944f,-0.00333893f,0.125638f},{-0.320416f,-0.00374048f,0.125638f},{-0.298136f,0.00916836f,0.125638f}, -{-0.298331f,0.00883081f,0.125638f},{-0.297875f,0.0066875f,0.125638f},{-0.29379f,0.000387896f,0.125638f}, -{-0.29367f,0.000757801f,0.125638f},{-0.288623f,-0.00305438f,0.125638f},{-0.288121f,-0.00329623f,0.125638f}, -{-0.289706f,-0.00281186f,0.125638f},{-0.289069f,-0.0144863f,0.125638f},{-0.288486f,-0.0146944f,0.125638f}, -{-0.295379f,-0.00945782f,0.125638f},{-0.294924f,-0.00883069f,0.125638f},{-0.294804f,-0.00845974f,0.125638f}, -{-0.305372f,-0.00984564f,0.125638f},{-0.305754f,-0.00992724f,0.125638f},{-0.309362f,-0.00138471f,0.125638f}, -{-0.305592f,-0.00178272f,0.125638f},{-0.298451f,-0.00369829f,0.125638f},{-0.297204f,-0.00630002f,0.125638f}, -{-0.296823f,-0.00621904f,0.125638f},{-0.310034f,-0.00177278f,0.125638f},{-0.318576f,-0.000618856f,0.125638f}, -{-0.293673f,0.00708155f,0.125638f},{-0.292719f,0.00906268f,0.125638f},{-0.308526f,0.0161585f,0.125638f}, -{-0.302051f,0.0218934f,0.125638f},{-0.29466f,0.0172358f,0.125638f},{-0.297876f,0.00945796f,0.125638f}, -{-0.29756f,0.00968738f,0.125638f},{-0.298492f,0.00807261f,0.125638f},{-0.298451f,0.00845965f,0.125638f}, -{-0.298451f,0.00768455f,0.125638f},{-0.304644f,0.0114364f,0.125638f},{-0.293337f,0.00813915f,0.125638f}, -{-0.304986f,-0.00283697f,0.125638f},{-0.29833f,0.00731409f,0.125638f},{-0.298135f,0.00697679f,0.125638f}, -{-0.306525f,0.00629974f,0.125638f},{-0.307457f,0.00697672f,0.125638f},{-0.307652f,0.00731413f,0.125638f}, -{-0.304025f,0.0105136f,0.125638f},{-0.303614f,0.0101357f,0.125638f},{-0.304852f,0.0119527f,0.125638f}, -{-0.314456f,0.00329623f,0.125638f},{-0.318901f,0.00181168f,0.125638f},{-0.307458f,0.00916838f,0.125638f}, -{-0.307773f,0.00768456f,0.125638f},{-0.307814f,0.00807245f,0.125638f},{-0.306881f,0.00645825f,0.125638f}, -{-0.307196f,0.00668694f,0.125638f},{-0.306144f,0.00621891f,0.125638f},{-0.304361f,0.0109558f,0.125638f}, -{-0.312313f,0.00281666f,0.125638f},{-0.310805f,-0.00185425f,0.125638f},{-0.304976f,0.0124958f,0.125638f}, -{-0.310266f,-0.00944145f,0.125638f},{-0.311664f,-0.0143468f,0.125638f},{-0.314091f,-0.0146931f,0.125638f}, -{-0.319529f,-0.00287783f,0.125638f},{-0.312119f,-0.00109643f,0.125638f},{-0.311542f,-0.00161492f,0.125638f}, -{-0.310415f,-0.00185398f,0.125638f},{-0.311186f,-0.0017734f,0.125638f},{-0.312871f,0.00281186f,0.125638f}, -{-0.313422f,0.00289006f,0.125638f},{-0.311762f,0.00288693f,0.125638f},{-0.311229f,0.00305413f,0.125638f}, -{-0.30591f,-0.0006084f,0.125638f},{-0.308907f,-0.000757801f,0.125638f},{-0.305788f,-0.00120559f,0.125638f}, -{-0.308787f,-0.000387896f,0.125638f},{-0.308904f,-0.00708155f,0.125638f},{-0.309858f,-0.00906268f,0.125638f}, -{-0.309515f,-0.00862453f,0.125638f},{-0.309025f,-0.00762671f,0.125638f},{-0.305326f,-0.00233026f,0.125638f}, -{-0.313954f,0.00305438f,0.125638f},{-0.295696f,-0.00645825f,0.125638f},{-0.294051f,-0.0161585f,0.125638f}, -{-0.300526f,-0.0218934f,0.125638f},{-0.307917f,-0.0172358f,0.125638f},{-0.304702f,-0.00945833f,0.125638f}, -{-0.305017f,-0.00968734f,0.125638f},{-0.304085f,-0.0080728f,0.125638f},{-0.304126f,-0.00845974f,0.125638f}, -{-0.304126f,-0.00768446f,0.125638f},{-0.300083f,-0.00450236f,0.125638f},{-0.30924f,-0.00813915f,0.125638f}, -{-0.297591f,-0.00283787f,0.125638f},{-0.297992f,-0.00329614f,0.125638f},{-0.296433f,-0.00621891f,0.125638f}, -{-0.296052f,-0.00629974f,0.125638f},{-0.293475f,0.00109509f,0.125638f},{-0.296982f,-0.00178435f,0.125638f}, -{-0.297725f,-0.0119527f,0.125638f},{-0.304126f,-0.00369728f,0.125638f},{-0.304584f,-0.00329545f,0.125638f}, -{-0.299505f,-0.00430656f,0.125638f},{-0.30068f,-0.00462115f,0.125638f},{-0.301289f,-0.00466102f,0.125638f}, -{-0.304702f,-0.0066878f,0.125638f},{-0.303619f,-0.00403597f,0.125638f},{-0.304247f,-0.00731401f,0.125638f}, -{-0.302495f,-0.00450189f,0.125638f},{-0.304442f,-0.00697682f,0.125638f},{-0.283676f,-0.00181168f,0.125638f}, -{-0.290913f,-0.0143468f,0.125638f},{-0.295119f,-0.00916838f,0.125638f},{-0.294804f,-0.00768456f,0.125638f}, -{-0.294763f,-0.00807245f,0.125638f},{-0.296793f,-0.00120563f,0.125638f},{-0.295381f,-0.00668694f,0.125638f}, -{-0.298552f,-0.0105136f,0.125638f},{-0.297933f,-0.0114364f,0.125638f},{-0.298963f,-0.0101357f,0.125638f}, -{-0.298216f,-0.0109558f,0.125638f},{-0.296671f,-0.00060826f,0.125638f},{-0.297252f,-0.002331f,0.125638f}, -{-0.297601f,-0.0124958f,0.125638f},{-0.298958f,-0.00403701f,0.125638f},{-0.301897f,-0.00462104f,0.125638f}, -{-0.303073f,-0.00430572f,0.125638f},{-0.309102f,-0.00109509f,0.125638f},{-0.279665f,-0.00625082f,0.12559f}, -{-0.280145f,-0.00772125f,0.12559f},{-0.279565f,-0.00793332f,0.125434f},{-0.281997f,-0.0161504f,0.12373f}, -{-0.280926f,-0.0147775f,0.12373f},{-0.281237f,-0.0145522f,0.12429f},{-0.280275f,-0.0131254f,0.12429f}, -{-0.27995f,-0.0133286f,0.12373f},{-0.282662f,-0.0155937f,0.124775f},{-0.283091f,-0.0152344f,0.125161f}, -{-0.283778f,-0.0168374f,0.124775f},{-0.284618f,-0.0160299f,0.125434f},{-0.285432f,-0.0174787f,0.125232f}, -{-0.284181f,-0.0164494f,0.125161f},{-0.286175f,-0.0166602f,0.125592f},{-0.285793f,-0.0170806f,0.125455f}, -{-0.285063f,-0.0156014f,0.12559f},{-0.279414f,-0.0116335f,0.12429f},{-0.279075f,-0.0118136f,0.12373f}, -{-0.278659f,-0.0100875f,0.12429f},{-0.27972f,-0.013472f,0.123126f},{-0.279587f,-0.0135551f,0.122512f}, -{-0.278836f,-0.0119407f,0.123126f},{-0.279926f,-0.0141705f,0.121909f},{-0.279088f,-0.0128179f,0.121909f}, -{-0.28058f,-0.0150287f,0.122512f},{-0.280846f,-0.0154687f,0.121909f},{-0.281669f,-0.0164249f,0.122512f}, -{-0.278698f,-0.0120144f,0.122512f},{-0.278335f,-0.0114156f,0.121909f},{-0.282919f,-0.0178815f,0.121909f}, -{-0.281845f,-0.0167073f,0.121909f},{-0.282845f,-0.0177348f,0.122512f},{-0.284064f,-0.0189869f,0.121909f}, -{-0.284095f,-0.0189523f,0.122497f},{-0.277919f,-0.0104178f,0.122512f},{-0.277671f,-0.00996957f,0.121909f}, -{-0.277254f,-0.00877706f,0.122512f},{-0.277098f,-0.00848485f,0.121909f},{-0.276617f,-0.0069676f,0.121909f}, -{-0.276708f,-0.00710556f,0.122512f},{-0.276279f,-0.00541355f,0.122497f},{-0.276413f,-0.00538462f,0.123065f}, -{-0.278309f,-0.0102436f,0.12373f},{-0.283153f,-0.0174384f,0.12373f},{-0.282291f,-0.0159041f,0.12429f}, -{-0.276233f,-0.00542344f,0.121909f},{-0.278062f,-0.0103538f,0.123126f},{-0.277952f,-0.006746f,0.124775f}, -{-0.277739f,-0.00509752f,0.124929f},{-0.278489f,-0.00659057f,0.125161f},{-0.277301f,-0.00519238f,0.124546f}, -{-0.277487f,-0.00688027f,0.12429f},{-0.280335f,-0.0111437f,0.125161f},{-0.279612f,-0.00966271f,0.125161f}, -{-0.280165f,-0.00941631f,0.125434f},{-0.279303f,-0.00475885f,0.125592f},{-0.276859f,-0.00706195f,0.123126f}, -{-0.27663f,-0.00533751f,0.123602f},{-0.277119f,-0.0069868f,0.12373f},{-0.277402f,-0.00872319f,0.123126f}, -{-0.280707f,-0.0149364f,0.123126f},{-0.281789f,-0.0163241f,0.123126f},{-0.282958f,-0.0176259f,0.123126f}, -{-0.284187f,-0.0188517f,0.123062f},{-0.276929f,-0.00527292f,0.1241f},{-0.277656f,-0.00863036f,0.12373f}, -{-0.284336f,-0.0186868f,0.1236f},{-0.279071f,-0.0064225f,0.125434f},{-0.278226f,-0.00499215f,0.125233f}, -{-0.278016f,-0.00849877f,0.12429f},{-0.281628f,-0.0142682f,0.124775f},{-0.283429f,-0.0171725f,0.12429f}, -{-0.284541f,-0.0184612f,0.124098f},{-0.279101f,-0.0098906f,0.124775f},{-0.27847f,-0.00833292f,0.124775f}, -{-0.279841f,-0.0114065f,0.124775f},{-0.280685f,-0.0128692f,0.124775f},{-0.284798f,-0.018178f,0.124546f}, -{-0.278996f,-0.00814092f,0.125161f},{-0.28116f,-0.0125727f,0.125161f},{-0.282081f,-0.0139394f,0.125161f}, -{-0.285098f,-0.0178475f,0.124927f},{-0.278751f,-0.00487843f,0.125456f},{-0.280869f,-0.0108595f,0.125434f}, -{-0.281673f,-0.0122521f,0.125434f},{-0.282571f,-0.013584f,0.125434f},{-0.284029f,-0.0144491f,0.12559f}, -{-0.283555f,-0.014846f,0.125434f},{-0.28073f,-0.00916459f,0.12559f},{-0.281415f,-0.0105692f,0.12559f}, -{-0.282198f,-0.0119246f,0.12559f},{-0.283071f,-0.0132209f,0.12559f},{-0.300403f,-0.0254145f,0.123126f}, -{-0.29867f,-0.0250226f,0.12373f},{-0.300413f,-0.0251441f,0.12373f},{-0.296873f,-0.0252029f,0.122512f}, -{-0.298626f,-0.0254479f,0.122512f},{-0.298641f,-0.0254985f,0.121909f},{-0.29871f,-0.0246411f,0.12429f}, -{-0.300404f,-0.0256204f,0.121909f},{-0.295189f,-0.0246879f,0.123126f},{-0.295152f,-0.0248403f,0.122512f}, -{-0.293514f,-0.0242356f,0.123065f},{-0.295163f,-0.024878f,0.121909f},{-0.293472f,-0.0243658f,0.122497f}, -{-0.29589f,-0.0218522f,0.12559f},{-0.297404f,-0.0221712f,0.12559f},{-0.297297f,-0.0227801f,0.125434f}, -{-0.293458f,-0.0244103f,0.121909f},{-0.296889f,-0.0252555f,0.121909f},{-0.293791f,-0.0233704f,0.124546f}, -{-0.295462f,-0.0235834f,0.124775f},{-0.295346f,-0.0240528f,0.12429f},{-0.298819f,-0.0236035f,0.125161f}, -{-0.298882f,-0.0230016f,0.125434f},{-0.300462f,-0.0237181f,0.125161f},{-0.295597f,-0.02304f,0.125161f}, -{-0.293928f,-0.0229434f,0.124929f},{-0.300398f,-0.0255715f,0.122512f},{-0.298642f,-0.0252917f,0.123126f}, -{-0.305563f,-0.0244044f,0.12429f},{-0.307323f,-0.0244252f,0.12373f},{-0.305629f,-0.0247822f,0.12373f}, -{-0.294417f,-0.0214191f,0.125592f},{-0.302149f,-0.0247609f,0.12429f},{-0.303905f,-0.0250231f,0.12373f}, -{-0.302162f,-0.0251442f,0.12373f},{-0.300426f,-0.0247607f,0.12429f},{-0.307115f,-0.0235834f,0.124775f}, -{-0.30548f,-0.0239281f,0.124775f},{-0.305383f,-0.0233768f,0.125161f},{-0.306835f,-0.0224524f,0.125434f}, -{-0.308497f,-0.0224714f,0.125232f},{-0.306981f,-0.02304f,0.125161f},{-0.303865f,-0.0246415f,0.12429f}, -{-0.30816f,-0.0214191f,0.125592f},{-0.308333f,-0.0219595f,0.125455f},{-0.306687f,-0.0218522f,0.12559f}, -{-0.302177f,-0.0255716f,0.122512f},{-0.302171f,-0.0254147f,0.123126f},{-0.302172f,-0.0256204f,0.121909f}, -{-0.30395f,-0.0254484f,0.122512f},{-0.303936f,-0.0254985f,0.121909f},{-0.305703f,-0.0252035f,0.122512f}, -{-0.305688f,-0.0252554f,0.121909f},{-0.307416f,-0.0248864f,0.121909f},{-0.307425f,-0.0248403f,0.122512f}, -{-0.309119f,-0.0244103f,0.121909f},{-0.293582f,-0.0240236f,0.123602f},{-0.295254f,-0.0244252f,0.12373f}, -{-0.2969f,-0.0250482f,0.123126f},{-0.303933f,-0.0252922f,0.123126f},{-0.307388f,-0.0246879f,0.123126f}, -{-0.305676f,-0.0250488f,0.123126f},{-0.309105f,-0.0243658f,0.122497f},{-0.309064f,-0.0242365f,0.123062f}, -{-0.293675f,-0.0237329f,0.1241f},{-0.296946f,-0.0247816f,0.12373f},{-0.308996f,-0.0240245f,0.1236f}, -{-0.295742f,-0.0224524f,0.125434f},{-0.29408f,-0.0224691f,0.125233f},{-0.297013f,-0.0244038f,0.12429f}, -{-0.303815f,-0.0241606f,0.124775f},{-0.307231f,-0.0240528f,0.12429f},{-0.308903f,-0.0237345f,0.124098f}, -{-0.29876f,-0.0241602f,0.124775f},{-0.297096f,-0.0239275f,0.124775f},{-0.300443f,-0.0242775f,0.124775f}, -{-0.302132f,-0.0242776f,0.124775f},{-0.308786f,-0.0233704f,0.124546f},{-0.297193f,-0.0233762f,0.125161f}, -{-0.302113f,-0.0237183f,0.125161f},{-0.303757f,-0.023604f,0.125161f},{-0.308649f,-0.0229455f,0.124927f}, -{-0.294245f,-0.0219573f,0.125456f},{-0.300484f,-0.0231133f,0.125434f},{-0.302091f,-0.0231134f,0.125434f}, -{-0.303694f,-0.023002f,0.125434f},{-0.305172f,-0.0221717f,0.12559f},{-0.305279f,-0.0227807f,0.125434f}, -{-0.298946f,-0.0223867f,0.12559f},{-0.300505f,-0.0224954f,0.12559f},{-0.30207f,-0.0224956f,0.12559f}, -{-0.303629f,-0.0223872f,0.12559f},{-0.322989f,-0.013557f,0.122512f},{-0.321869f,-0.0149379f,0.123126f}, -{-0.322856f,-0.0134738f,0.123126f},{-0.321996f,-0.0150302f,0.122512f},{-0.322651f,-0.0141709f,0.121909f}, -{-0.321731f,-0.0154689f,0.121909f},{-0.32165f,-0.0147789f,0.12373f},{-0.322626f,-0.0133304f,0.12373f}, -{-0.321339f,-0.0145536f,0.12429f},{-0.319619f,-0.0176259f,0.123126f},{-0.319733f,-0.0177348f,0.122512f}, -{-0.31839f,-0.0188513f,0.123063f},{-0.318239f,-0.0186852f,0.123604f},{-0.318547f,-0.0144499f,0.12559f}, -{-0.319021f,-0.0148468f,0.125434f},{-0.317514f,-0.0156014f,0.12559f},{-0.318482f,-0.0189527f,0.122494f}, -{-0.319658f,-0.0178817f,0.121909f},{-0.318513f,-0.0189869f,0.121909f},{-0.320907f,-0.0164258f,0.122512f}, -{-0.320732f,-0.0167075f,0.121909f},{-0.318396f,-0.0164494f,0.125161f},{-0.318799f,-0.0168374f,0.124775f}, -{-0.31748f,-0.0178479f,0.124927f},{-0.321416f,-0.0125744f,0.125161f},{-0.320495f,-0.0139408f,0.125161f}, -{-0.320005f,-0.0135853f,0.125434f},{-0.3164f,-0.0166578f,0.125592f},{-0.319148f,-0.0171725f,0.12429f}, -{-0.317779f,-0.018178f,0.124546f},{-0.324561f,-0.00850026f,0.12429f},{-0.325458f,-0.0069868f,0.12373f}, -{-0.324921f,-0.00863187f,0.12373f},{-0.322301f,-0.0131272f,0.12429f},{-0.323506f,-0.0064225f,0.125434f}, -{-0.324354f,-0.00499264f,0.125232f},{-0.324088f,-0.00659057f,0.125161f},{-0.32374f,-0.0119427f,0.123126f}, -{-0.323878f,-0.0120165f,0.122512f},{-0.324625f,-0.006746f,0.124775f},{-0.324106f,-0.00833438f,0.124775f}, -{-0.323581f,-0.00814234f,0.125161f},{-0.324267f,-0.0102456f,0.12373f},{-0.323917f,-0.0100893f,0.12429f}, -{-0.323162f,-0.0116355f,0.12429f},{-0.323501f,-0.0118156f,0.12373f},{-0.323274f,-0.00475885f,0.125592f}, -{-0.323828f,-0.00487893f,0.125455f},{-0.322912f,-0.00625082f,0.12559f},{-0.32349f,-0.012818f,0.121909f}, -{-0.324658f,-0.0104197f,0.122512f},{-0.324242f,-0.011416f,0.121909f},{-0.325323f,-0.0087786f,0.122512f}, -{-0.324906f,-0.00996985f,0.121909f},{-0.325477f,-0.00848443f,0.121909f},{-0.325869f,-0.00710556f,0.122512f}, -{-0.325951f,-0.00696541f,0.121909f},{-0.326344f,-0.00542344f,0.121909f},{-0.326298f,-0.00541355f,0.122497f}, -{-0.319424f,-0.0174384f,0.12373f},{-0.320786f,-0.016325f,0.123126f},{-0.324515f,-0.0103558f,0.123126f}, -{-0.325175f,-0.00872472f,0.123126f},{-0.325718f,-0.00706195f,0.123126f},{-0.326165f,-0.00538482f,0.123062f}, -{-0.318034f,-0.0184588f,0.124102f},{-0.320579f,-0.0161513f,0.12373f},{-0.325948f,-0.00533772f,0.1236f}, -{-0.31796f,-0.0160299f,0.125434f},{-0.317144f,-0.0174779f,0.125233f},{-0.320285f,-0.015905f,0.12429f}, -{-0.323475f,-0.00989244f,0.124775f},{-0.32509f,-0.00688027f,0.12429f},{-0.32565f,-0.00527328f,0.124098f}, -{-0.320948f,-0.0142696f,0.124775f},{-0.319914f,-0.0155946f,0.124775f},{-0.321891f,-0.012871f,0.124775f}, -{-0.322735f,-0.0114084f,0.124775f},{-0.325276f,-0.00519238f,0.124546f},{-0.319485f,-0.0152353f,0.125161f}, -{-0.322241f,-0.0111456f,0.125161f},{-0.322964f,-0.00966451f,0.125161f},{-0.32484f,-0.005098f,0.124927f}, -{-0.316781f,-0.0170773f,0.125456f},{-0.320903f,-0.0122538f,0.125434f},{-0.321707f,-0.0108613f,0.125434f}, -{-0.322411f,-0.00941806f,0.125434f},{-0.322432f,-0.0077226f,0.12559f},{-0.323012f,-0.00793471f,0.125434f}, -{-0.319505f,-0.0132221f,0.12559f},{-0.320378f,-0.0119262f,0.12559f},{-0.321161f,-0.010571f,0.12559f}, -{-0.321847f,-0.0091663f,0.12559f},{-0.323879f,0.0120144f,0.122512f},{-0.324515f,0.0103538f,0.123126f}, -{-0.323741f,0.0119407f,0.123126f},{-0.324659f,0.0104178f,0.122512f},{-0.324268f,0.0102436f,0.12373f}, -{-0.323502f,0.0118136f,0.12373f},{-0.323918f,0.0100875f,0.12429f},{-0.325718f,0.00706195f,0.123126f}, -{-0.325869f,0.00710556f,0.122512f},{-0.326165f,0.00538462f,0.123065f},{-0.325947f,0.00533751f,0.123602f}, -{-0.322432f,0.00772125f,0.12559f},{-0.323012f,0.00793332f,0.125434f},{-0.322912f,0.00625082f,0.12559f}, -{-0.326298f,0.00541355f,0.122497f},{-0.325323f,0.00877706f,0.122512f},{-0.324088f,0.00659057f,0.125161f}, -{-0.324625f,0.006746f,0.124775f},{-0.324838f,0.00509752f,0.124929f},{-0.322242f,0.0111437f,0.125161f}, -{-0.322965f,0.00966271f,0.125161f},{-0.322412f,0.00941631f,0.125434f},{-0.323274f,0.00475885f,0.125592f}, -{-0.32509f,0.00688027f,0.12429f},{-0.325276f,0.00519238f,0.124546f},{-0.320286f,0.0159041f,0.12429f}, -{-0.319424f,0.0174384f,0.12373f},{-0.32058f,0.0161504f,0.12373f},{-0.323163f,0.0116335f,0.12429f}, -{-0.31796f,0.0160299f,0.125434f},{-0.317146f,0.0174801f,0.125231f},{-0.318396f,0.0164494f,0.125161f}, -{-0.322857f,0.013472f,0.123126f},{-0.32299f,0.0135551f,0.122512f},{-0.318799f,0.0168374f,0.124775f}, -{-0.319915f,0.0155937f,0.124775f},{-0.319486f,0.0152344f,0.125161f},{-0.321651f,0.0147775f,0.12373f}, -{-0.32134f,0.0145522f,0.12429f},{-0.322302f,0.0131254f,0.12429f},{-0.322627f,0.0133286f,0.12373f}, -{-0.3164f,0.0166578f,0.125592f},{-0.316783f,0.0170797f,0.125455f},{-0.317514f,0.0156014f,0.12559f}, -{-0.321997f,0.0150287f,0.122512f},{-0.320908f,0.0164249f,0.122512f},{-0.319733f,0.0177348f,0.122512f}, -{-0.318482f,0.0189527f,0.122494f},{-0.325458f,0.0069868f,0.12373f},{-0.325175f,0.00872319f,0.123126f}, -{-0.32187f,0.0149364f,0.123126f},{-0.320788f,0.0163241f,0.123126f},{-0.319619f,0.0176259f,0.123126f}, -{-0.318391f,0.018852f,0.12306f},{-0.325649f,0.00527292f,0.1241f},{-0.324921f,0.00863036f,0.12373f}, -{-0.31824f,0.0186863f,0.123601f},{-0.323506f,0.0064225f,0.125434f},{-0.324351f,0.00499215f,0.125233f}, -{-0.324561f,0.00849877f,0.12429f},{-0.320949f,0.0142682f,0.124775f},{-0.319148f,0.0171725f,0.12429f}, -{-0.318035f,0.0184598f,0.1241f},{-0.323476f,0.0098906f,0.124775f},{-0.324107f,0.00833292f,0.124775f}, -{-0.322736f,0.0114065f,0.124775f},{-0.321892f,0.0128692f,0.124775f},{-0.317779f,0.018178f,0.124546f}, -{-0.323581f,0.00814092f,0.125161f},{-0.321417f,0.0125727f,0.125161f},{-0.320496f,0.0139394f,0.125161f}, -{-0.317481f,0.0178492f,0.124925f},{-0.323826f,0.00487843f,0.125456f},{-0.321708f,0.0108595f,0.125434f}, -{-0.320904f,0.0122521f,0.125434f},{-0.320006f,0.013584f,0.125434f},{-0.318548f,0.0144491f,0.12559f}, -{-0.319022f,0.014846f,0.125434f},{-0.321847f,0.00916459f,0.12559f},{-0.321162f,0.0105692f,0.12559f}, -{-0.32038f,0.0119246f,0.12559f},{-0.319506f,0.0132209f,0.12559f},{-0.302174f,0.0254145f,0.123126f}, -{-0.303907f,0.0250226f,0.12373f},{-0.302164f,0.0251441f,0.12373f},{-0.305705f,0.0252029f,0.122512f}, -{-0.303952f,0.0254479f,0.122512f},{-0.303867f,0.0246411f,0.12429f},{-0.307388f,0.0246879f,0.123126f}, -{-0.307425f,0.0248403f,0.122512f},{-0.309063f,0.0242356f,0.123065f},{-0.309105f,0.0243658f,0.122497f}, -{-0.306687f,0.0218522f,0.12559f},{-0.305173f,0.0221712f,0.12559f},{-0.30528f,0.0227801f,0.125434f}, -{-0.308786f,0.0233704f,0.124546f},{-0.307115f,0.0235834f,0.124775f},{-0.307231f,0.0240528f,0.12429f}, -{-0.303759f,0.0236035f,0.125161f},{-0.303695f,0.0230016f,0.125434f},{-0.302115f,0.0237181f,0.125161f}, -{-0.306981f,0.02304f,0.125161f},{-0.308649f,0.0229434f,0.124929f},{-0.302179f,0.0255715f,0.122512f}, -{-0.303935f,0.0252917f,0.123126f},{-0.297014f,0.0244044f,0.12429f},{-0.295254f,0.0244252f,0.12373f}, -{-0.296948f,0.0247822f,0.12373f},{-0.30816f,0.0214191f,0.125592f},{-0.300428f,0.0247609f,0.12429f}, -{-0.298672f,0.0250231f,0.12373f},{-0.300415f,0.0251442f,0.12373f},{-0.302151f,0.0247607f,0.12429f}, -{-0.295462f,0.0235834f,0.124775f},{-0.297097f,0.0239281f,0.124775f},{-0.297194f,0.0233768f,0.125161f}, -{-0.295742f,0.0224524f,0.125434f},{-0.29408f,0.0224714f,0.125232f},{-0.295597f,0.02304f,0.125161f}, -{-0.298712f,0.0246415f,0.12429f},{-0.294417f,0.0214191f,0.125592f},{-0.294244f,0.0219595f,0.125455f}, -{-0.29589f,0.0218522f,0.12559f},{-0.3004f,0.0255716f,0.122512f},{-0.300406f,0.0254147f,0.123126f}, -{-0.298628f,0.0254484f,0.122512f},{-0.296874f,0.0252035f,0.122512f},{-0.295152f,0.0248403f,0.122512f}, -{-0.308995f,0.0240236f,0.123602f},{-0.307323f,0.0244252f,0.12373f},{-0.305677f,0.0250482f,0.123126f}, -{-0.298644f,0.0252922f,0.123126f},{-0.295189f,0.0246879f,0.123126f},{-0.296901f,0.0250488f,0.123126f}, -{-0.293472f,0.0243658f,0.122497f},{-0.293513f,0.0242365f,0.123062f},{-0.308902f,0.0237329f,0.1241f}, -{-0.305631f,0.0247816f,0.12373f},{-0.293581f,0.0240245f,0.1236f},{-0.306835f,0.0224524f,0.125434f}, -{-0.308497f,0.0224691f,0.125233f},{-0.305565f,0.0244038f,0.12429f},{-0.298762f,0.0241606f,0.124775f}, -{-0.295346f,0.0240528f,0.12429f},{-0.293674f,0.0237345f,0.124098f},{-0.303817f,0.0241602f,0.124775f}, -{-0.305481f,0.0239275f,0.124775f},{-0.302134f,0.0242775f,0.124775f},{-0.300445f,0.0242776f,0.124775f}, -{-0.293791f,0.0233704f,0.124546f},{-0.305384f,0.0233762f,0.125161f},{-0.300465f,0.0237183f,0.125161f}, -{-0.29882f,0.023604f,0.125161f},{-0.293928f,0.0229455f,0.124927f},{-0.308332f,0.0219573f,0.125456f}, -{-0.302094f,0.0231133f,0.125434f},{-0.300486f,0.0231134f,0.125434f},{-0.298883f,0.023002f,0.125434f}, -{-0.297405f,0.0221717f,0.12559f},{-0.297298f,0.0227807f,0.125434f},{-0.303631f,0.0223867f,0.12559f}, -{-0.302072f,0.0224954f,0.12559f},{-0.300507f,0.0224956f,0.12559f},{-0.298948f,0.0223872f,0.12559f}, -{-0.279588f,0.013557f,0.122512f},{-0.280709f,0.0149379f,0.123126f},{-0.279721f,0.0134738f,0.123126f}, -{-0.280581f,0.0150302f,0.122512f},{-0.280928f,0.0147789f,0.12373f},{-0.279951f,0.0133304f,0.12373f}, -{-0.281238f,0.0145536f,0.12429f},{-0.282958f,0.0176259f,0.123126f},{-0.282845f,0.0177348f,0.122512f}, -{-0.284187f,0.018851f,0.123065f},{-0.284337f,0.0186861f,0.123602f},{-0.28403f,0.0144499f,0.12559f}, -{-0.283556f,0.0148468f,0.125434f},{-0.285063f,0.0156014f,0.12559f},{-0.284095f,0.0189523f,0.122497f}, -{-0.28167f,0.0164258f,0.122512f},{-0.284181f,0.0164494f,0.125161f},{-0.283778f,0.0168374f,0.124775f}, -{-0.285099f,0.0178459f,0.124929f},{-0.281161f,0.0125744f,0.125161f},{-0.282082f,0.0139408f,0.125161f}, -{-0.282572f,0.0135853f,0.125434f},{-0.286175f,0.0166602f,0.125592f},{-0.283429f,0.0171725f,0.12429f}, -{-0.284798f,0.018178f,0.124546f},{-0.278016f,0.00850026f,0.12429f},{-0.277119f,0.0069868f,0.12373f}, -{-0.277656f,0.00863187f,0.12373f},{-0.280276f,0.0131272f,0.12429f},{-0.279071f,0.0064225f,0.125434f}, -{-0.278223f,0.00499264f,0.125232f},{-0.278489f,0.00659057f,0.125161f},{-0.278837f,0.0119427f,0.123126f}, -{-0.278699f,0.0120165f,0.122512f},{-0.277952f,0.006746f,0.124775f},{-0.278471f,0.00833438f,0.124775f}, -{-0.278996f,0.00814234f,0.125161f},{-0.27831f,0.0102456f,0.12373f},{-0.27866f,0.0100893f,0.12429f}, -{-0.279415f,0.0116355f,0.12429f},{-0.279076f,0.0118156f,0.12373f},{-0.279303f,0.00475885f,0.125592f}, -{-0.278749f,0.00487893f,0.125455f},{-0.279665f,0.00625082f,0.12559f},{-0.277919f,0.0104197f,0.122512f}, -{-0.277254f,0.0087786f,0.122512f},{-0.276708f,0.00710556f,0.122512f},{-0.276279f,0.00541355f,0.122497f}, -{-0.283153f,0.0174384f,0.12373f},{-0.281791f,0.016325f,0.123126f},{-0.278063f,0.0103558f,0.123126f}, -{-0.277402f,0.00872472f,0.123126f},{-0.276859f,0.00706195f,0.123126f},{-0.276412f,0.00538482f,0.123062f}, -{-0.284542f,0.0184599f,0.1241f},{-0.281998f,0.0161513f,0.12373f},{-0.276629f,0.00533772f,0.1236f}, -{-0.284618f,0.0160299f,0.125434f},{-0.285434f,0.017477f,0.125233f},{-0.282292f,0.015905f,0.12429f}, -{-0.279102f,0.00989244f,0.124775f},{-0.277487f,0.00688027f,0.12429f},{-0.276927f,0.00527328f,0.124098f}, -{-0.281629f,0.0142696f,0.124775f},{-0.282663f,0.0155946f,0.124775f},{-0.280686f,0.012871f,0.124775f}, -{-0.279842f,0.0114084f,0.124775f},{-0.277301f,0.00519238f,0.124546f},{-0.283092f,0.0152353f,0.125161f}, -{-0.280336f,0.0111456f,0.125161f},{-0.279613f,0.00966451f,0.125161f},{-0.277737f,0.005098f,0.124927f}, -{-0.285795f,0.0170789f,0.125456f},{-0.281674f,0.0122538f,0.125434f},{-0.28087f,0.0108613f,0.125434f}, -{-0.280166f,0.00941806f,0.125434f},{-0.280146f,0.0077226f,0.12559f},{-0.279565f,0.00793471f,0.125434f}, -{-0.283072f,0.0132221f,0.12559f},{-0.282199f,0.0119262f,0.12559f},{-0.281416f,0.010571f,0.12559f}, -{-0.28073f,0.0091663f,0.12559f},{-0.297145f,-0.00620072f,0.100469f},{-0.299891f,-0.00241971f,0.100469f}, -{-0.299492f,-0.00214016f,0.100469f},{-0.298434f,-0.00688999f,0.100469f},{-0.297772f,-0.00657676f,0.100469f}, -{-0.299123f,-0.00713669f,0.100469f},{-0.300332f,-0.00262702f,0.100469f},{-0.296557f,-0.00576486f,0.100469f}, -{-0.296014f,-0.00527335f,0.100469f},{-0.299834f,-0.00731445f,0.100469f},{-0.300803f,-0.00275405f,0.100469f}, -{-0.299147f,-0.00179629f,0.100469f},{-0.295523f,-0.004731f,0.100469f},{-0.300558f,-0.00742168f,0.100469f}, -{-0.301289f,-0.00279661f,0.100469f},{-0.295087f,-0.00414307f,0.100469f},{-0.298867f,-0.00139723f,0.100469f}, -{-0.301289f,-0.00745764f,0.100469f},{-0.30202f,-0.0074216f,0.100469f},{-0.302744f,-0.00731392f,0.100469f}, -{-0.301774f,-0.00275426f,0.100469f},{-0.303454f,-0.00713585f,0.100469f},{-0.302244f,-0.0026284f,0.100469f}, -{-0.294398f,-0.0028536f,0.100469f},{-0.294711f,-0.00351526f,0.100469f},{-0.304805f,-0.00657672f,0.100469f}, -{-0.304143f,-0.0068893f,0.100469f},{-0.294152f,-0.00216444f,0.100469f},{-0.298661f,-0.000955369f,0.100469f}, -{-0.298535f,-0.000484912f,0.100469f},{-0.302684f,-0.00241949f,0.100469f},{-0.293866f,-0.000730865f,0.100469f}, -{-0.293974f,-0.00145464f,0.100469f},{-0.303432f,-0.0018009f,0.100469f},{-0.303078f,-0.00213198f,0.100469f}, -{-0.306562f,-0.00527224f,0.100469f},{-0.307865f,-0.00351451f,0.100469f},{-0.308178f,-0.00285307f,0.100469f}, -{-0.303917f,-0.000957231f,0.100469f},{-0.304044f,-0.000485989f,0.100469f},{-0.30871f,-0.000730708f,0.100469f}, -{-0.308425f,-0.00216422f,0.100469f},{-0.308603f,-0.00145452f,0.100469f},{-0.30602f,-0.00576389f,0.100469f}, -{-0.305432f,-0.00620014f,0.100469f},{-0.307489f,-0.00414214f,0.100469f},{-0.303711f,-0.00139896f,0.100469f}, -{-0.307053f,-0.00472993f,0.100469f},{-0.30068f,0.0121618f,0.101401f},{-0.299504f,0.0124736f,0.101401f}, -{-0.298958f,0.0127432f,0.101401f},{-0.299123f,-0.00713585f,0.101401f},{-0.295928f,-0.0107204f,0.101401f}, -{-0.293867f,-0.000730708f,0.101401f},{-0.289127f,-0.00060826f,0.101401f},{-0.294152f,-0.00216422f,0.101401f}, -{-0.288545f,-0.002331f,0.101401f},{-0.294399f,-0.00285307f,0.101401f},{-0.297252f,0.0144494f,0.101401f}, -{-0.296983f,0.0185639f,0.101401f},{-0.286992f,-0.0131013f,0.101401f},{-0.304087f,0.021256f,0.101401f}, -{-0.279887f,-0.0006084f,0.101401f},{-0.308181f,0.0203028f,0.101401f},{-0.309493f,0.0198085f,0.101401f}, -{-0.280009f,-0.00120559f,0.101401f},{-0.280205f,-0.00178272f,0.101401f},{-0.287805f,-0.00329614f,0.101401f}, -{-0.294712f,-0.00351451f,0.101401f},{-0.288207f,-0.00283787f,0.101401f},{-0.310221f,-0.0114792f,0.101401f}, -{-0.305015f,-0.0139787f,0.101401f},{-0.305351f,-0.0144948f,0.101401f},{-0.280472f,-0.00233026f,0.101401f}, -{-0.281213f,-0.00329545f,0.101401f},{-0.280811f,-0.00283697f,0.101401f},{-0.281671f,-0.00369728f,0.101401f}, -{-0.287378f,-0.0112779f,0.101401f},{-0.287149f,-0.0115926f,0.101401f},{-0.303454f,-0.00713669f,0.101401f}, -{-0.303642f,-0.0127563f,0.101401f},{-0.304143f,-0.00688999f,0.101401f},{-0.282178f,-0.00403597f,0.101401f}, -{-0.282725f,-0.00430572f,0.101401f},{-0.284509f,-0.00466102f,0.101401f},{-0.2839f,-0.00462104f,0.101401f}, -{-0.283302f,-0.00450189f,0.101401f},{-0.315425f,0.0161201f,0.101401f},{-0.310771f,0.0192295f,0.101401f}, -{-0.302507f,-0.0122874f,0.101401f},{-0.302744f,-0.00731445f,0.101401f},{-0.302019f,-0.00742168f,0.101401f}, -{-0.285117f,-0.00462115f,0.101401f},{-0.303091f,-0.0124812f,0.101401f},{-0.295088f,-0.00414214f,0.101401f}, -{-0.304152f,-0.0131016f,0.101401f},{-0.28691f,-0.01233f,0.101401f},{-0.31204f,0.0119471f,0.101401f}, -{-0.312198f,0.0115917f,0.101401f},{-0.302691f,0.0213951f,0.101401f},{-0.297993f,0.0200754f,0.101401f}, -{-0.297591f,0.0196172f,0.101401f},{-0.295524f,-0.00472993f,0.101401f},{-0.296628f,0.0167797f,0.101401f}, -{-0.296667f,0.0173884f,0.101401f},{-0.293974f,-0.00145452f,0.101401f},{-0.288815f,-0.00178435f,0.101401f}, -{-0.289127f,0.00961418f,0.101401f},{-0.290354f,0.0087231f,0.101401f},{-0.289984f,0.00884326f,0.101401f}, -{-0.288969f,0.0099696f,0.101401f},{-0.289647f,0.00903788f,0.101401f},{-0.289357f,0.00929843f,0.101401f}, -{-0.287668f,-0.0110163f,0.101401f},{-0.287669f,-0.014033f,0.101401f},{-0.288007f,-0.0142276f,0.101401f}, -{-0.288006f,-0.0108212f,0.101401f},{-0.285715f,-0.00450236f,0.101401f},{-0.296557f,-0.00576389f,0.101401f}, -{-0.296015f,-0.00527224f,0.101401f},{-0.318298f,0.0130525f,0.101401f},{-0.308808f,-0.0200792f,0.101401f}, -{-0.310142f,-0.0195277f,0.101401f},{-0.305898f,-0.0174727f,0.101401f},{-0.298434f,-0.0068893f,0.101401f}, -{-0.297772f,-0.00657672f,0.101401f},{-0.300557f,-0.0074216f,0.101401f},{-0.299833f,-0.00731392f,0.101401f}, -{-0.316449f,0.0151611f,0.101401f},{-0.317408f,0.0141371f,0.101401f},{-0.313762f,0.00178435f,0.101401f}, -{-0.313573f,0.00120563f,0.101401f},{-0.301289f,-0.00745764f,0.101401f},{-0.305617f,-0.0150508f,0.101401f}, -{-0.310451f,-0.011795f,0.101401f},{-0.312009f,0.00536018f,0.101401f},{-0.309981f,-0.0107426f,0.101401f}, -{-0.304612f,-0.0135115f,0.101401f},{-0.319116f,0.0119121f,0.101401f},{-0.308603f,-0.00145464f,0.101401f}, -{-0.308426f,-0.00216444f,0.101401f},{-0.308711f,-0.000730865f,0.101401f},{-0.320906f,0.00369728f,0.101401f}, -{-0.321364f,0.00329545f,0.101401f},{-0.322317f,0.00418323f,0.101401f},{-0.317108f,-0.0144727f,0.101401f}, -{-0.318046f,-0.0133751f,0.101401f},{-0.318908f,-0.0122169f,0.101401f},{-0.305919f,-0.0162427f,0.101401f}, -{-0.311436f,-0.0188874f,0.101401f},{-0.313881f,-0.0173532f,0.101401f},{-0.315021f,-0.0164664f,0.101401f}, -{-0.305949f,-0.0168584f,0.101401f},{-0.305556f,-0.018654f,0.101401f},{-0.307439f,-0.0205396f,0.101401f}, -{-0.305766f,-0.0180747f,0.101401f},{-0.302944f,-0.0211335f,0.101401f},{-0.303192f,-0.0213586f,0.101401f}, -{-0.303505f,-0.0208805f,0.101401f},{-0.304917f,-0.0197045f,0.101401f},{-0.306043f,-0.0209071f,0.101401f}, -{-0.305271f,-0.0192003f,0.101401f},{-0.304499f,-0.0201577f,0.101401f},{-0.304026f,-0.0205519f,0.101401f}, -{-0.304622f,-0.0211663f,0.101401f},{-0.302355f,-0.0213146f,0.101401f},{-0.301748f,-0.021419f,0.101401f}, -{-0.311447f,-0.0123703f,0.101401f},{-0.312685f,-0.0181614f,0.101401f},{-0.316098f,-0.0155048f,0.101401f}, -{-0.319691f,-0.0110032f,0.101401f},{-0.322535f,-0.00287961f,0.101401f},{-0.322293f,-0.00430325f,0.101401f}, -{-0.321956f,-0.00570752f,0.101401f},{-0.289004f,-0.00120563f,0.101401f},{-0.30602f,-0.00576486f,0.101401f}, -{-0.31022f,-0.00961513f,0.101401f},{-0.310449f,-0.00930035f,0.101401f},{-0.32039f,-0.00973944f,0.101401f}, -{-0.311077f,-0.0122501f,0.101401f},{-0.322681f,-0.00144304f,0.101401f},{-0.312428f,0.0112759f,0.101401f}, -{-0.312718f,0.0110154f,0.101401f},{-0.307054f,-0.004731f,0.101401f},{-0.306563f,-0.00527335f,0.101401f}, -{-0.310739f,-0.00903878f,0.101401f},{-0.311076f,-0.00884365f,0.101401f},{-0.311446f,-0.00872342f,0.101401f}, -{-0.30749f,-0.00414307f,0.101401f},{-0.310062f,-0.00997107f,0.101401f},{-0.305432f,-0.00620072f,0.101401f}, -{-0.304805f,-0.00657676f,0.101401f},{-0.305807f,-0.0156368f,0.101401f},{-0.31074f,-0.0120555f,0.101401f}, -{-0.301903f,-0.0121629f,0.101401f},{-0.287346f,-0.00369829f,0.101401f},{-0.297145f,-0.00620014f,0.101401f}, -{-0.286839f,-0.00403701f,0.101401f},{-0.288888f,0.0107408f,0.101401f},{-0.289356f,0.011793f,0.101401f}, -{-0.296982f,0.0149963f,0.101401f},{-0.299506f,0.0210836f,0.101401f},{-0.305471f,0.0210266f,0.101401f}, -{-0.311959f,0.0123283f,0.101401f},{-0.306838f,0.0207091f,0.101401f},{-0.31437f,0.00283787f,0.101401f}, -{-0.314772f,0.00329614f,0.101401f},{-0.314341f,0.0170101f,0.101401f},{-0.319856f,0.0107207f,0.101401f}, -{-0.321591f,0.00689212f,0.101401f},{-0.319852f,0.00430572f,0.101401f},{-0.321998f,0.00554954f,0.101401f}, -{-0.308179f,-0.0028536f,0.101401f},{-0.3132f,0.0178274f,0.101401f},{-0.313054f,0.0142272f,0.101401f}, -{-0.313424f,0.0143475f,0.101401f},{-0.320518f,0.00948339f,0.101401f},{-0.316285f,0.00430656f,0.101401f}, -{-0.31345f,0.00060826f,0.101401f},{-0.312198f,0.0134558f,0.101401f},{-0.312426f,0.0137705f,0.101401f}, -{-0.311958f,0.0127183f,0.101401f},{-0.312009f,0.0185682f,0.101401f},{-0.312716f,0.0140321f,0.101401f}, -{-0.300083f,0.0122844f,0.101401f},{-0.289645f,0.0120546f,0.101401f},{-0.289983f,0.0122497f,0.101401f}, -{-0.288888f,0.0103508f,0.101401f},{-0.296667f,0.0161715f,0.101401f},{-0.298451f,0.0130817f,0.101401f}, -{-0.297992f,0.0134836f,0.101401f},{-0.29759f,0.0139422f,0.101401f},{-0.288968f,0.0111223f,0.101401f}, -{-0.289127f,0.0114782f,0.101401f},{-0.290353f,0.01237f,0.101401f},{-0.286292f,-0.00430656f,0.101401f}, -{-0.288375f,-0.0107009f,0.101401f},{-0.288376f,-0.0143478f,0.101401f},{-0.28738f,-0.0137725f,0.101401f}, -{-0.28715f,-0.0134567f,0.101401f},{-0.28691f,-0.0127201f,0.101401f},{-0.286991f,-0.0119486f,0.101401f}, -{-0.321525f,-0.00708565f,0.101401f},{-0.321002f,-0.00843163f,0.101401f},{-0.309981f,-0.0103525f,0.101401f}, -{-0.310062f,-0.0111238f,0.101401f},{-0.307866f,-0.00351526f,0.101401f},{-0.312039f,0.0130998f,0.101401f}, -{-0.296786f,0.0155736f,0.101401f},{-0.296787f,0.0179866f,0.101401f},{-0.297253f,0.0191105f,0.101401f}, -{-0.298452f,0.0204775f,0.101401f},{-0.298958f,0.0208166f,0.101401f},{-0.30068f,0.0214014f,0.101401f}, -{-0.300083f,0.021279f,0.101401f},{-0.322372f,0.00178272f,0.101401f},{-0.322683f,0.00140253f,0.101401f}, -{-0.322546f,0.00279893f,0.101401f},{-0.321097f,0.00820537f,0.101401f},{-0.318068f,0.00466102f,0.101401f}, -{-0.318677f,0.00462104f,0.101401f},{-0.31746f,0.00462115f,0.101401f},{-0.314032f,0.002331f,0.101401f}, -{-0.316862f,0.00450236f,0.101401f},{-0.315231f,0.00369829f,0.101401f},{-0.315738f,0.00403701f,0.101401f}, -{-0.313425f,0.0107006f,0.101401f},{-0.313055f,0.0108208f,0.101401f},{-0.319275f,0.00450189f,0.101401f}, -{-0.320399f,0.00403597f,0.101401f},{-0.321766f,0.00283697f,0.101401f},{-0.322105f,0.00233026f,0.101401f}, -{-0.32269f,0.0006084f,0.101401f},{-0.322568f,0.00120559f,0.101401f},{-0.279202f,-0.0130142f,0.120045f}, -{-0.281553f,-0.0163617f,0.120045f},{-0.317715f,0.0202853f,0.120045f},{-0.318754f,0.0193978f,0.120045f}, -{-0.27854f,-0.0118202f,0.120045f},{-0.314339f,0.0226051f,0.120045f},{-0.315504f,0.0218911f,0.120045f}, -{-0.27695f,-0.00805156f,0.120045f},{-0.310642f,0.0243682f,0.120045f},{-0.311905f,0.0238452f,0.120045f}, -{-0.275979f,-0.0040778f,0.120045f},{-0.306715f,0.0255314f,0.120045f},{-0.305372f,0.0257805f,0.120045f}, -{-0.308044f,0.0252126f,0.120045f},{-0.309354f,0.0248245f,0.120045f},{-0.302654f,0.0260573f,0.120045f}, -{-0.304017f,0.0259588f,0.120045f},{-0.275698f,-0.00136419f,0.120045f},{-0.275798f,-0.00272502f,0.120045f}, -{-0.313138f,0.023257f,0.120045f},{-0.276556f,-0.00674482f,0.120045f},{-0.276232f,-0.00541896f,0.120045f}, -{-0.316631f,0.0211172f,0.120045f},{-0.277944f,-0.0105928f,0.120045f},{-0.277413f,-0.00933541f,0.120045f}, -{-0.319745f,0.0184571f,0.120045f},{-0.320686f,0.0174659f,0.120045f},{-0.279926f,-0.0141713f,0.120045f}, -{-0.321573f,0.0164267f,0.120045f},{-0.322405f,0.0153425f,0.120045f},{-0.323179f,0.0142163f,0.120045f}, -{-0.28071f,-0.0152881f,0.120045f},{-0.323893f,0.0130512f,0.120045f},{-0.324545f,0.0118502f,0.120045f}, -{-0.282452f,-0.0173888f,0.120045f},{-0.325134f,0.0106168f,0.120045f},{-0.283404f,-0.0183667f,0.120045f}, -{-0.325657f,0.00935425f,0.120045f},{-0.284407f,-0.0192925f,0.120045f},{-0.326113f,0.00806608f,0.120045f}, -{-0.285457f,-0.0201635f,0.120045f},{-0.326501f,0.00675581f,0.120045f},{-0.286553f,-0.0209774f,0.120045f}, -{-0.32682f,0.00542697f,0.120045f},{-0.28769f,-0.021732f,0.120045f},{-0.327069f,0.00408325f,0.120045f}, -{-0.288866f,-0.022425f,0.120045f},{-0.327247f,0.00272836f,0.120045f},{-0.290078f,-0.0230545f,0.120045f}, -{-0.327354f,0.00136603f,0.120045f},{-0.291321f,-0.0236185f,0.120045f},{-0.32739f,5.19219e-017f,0.120045f}, -{-0.292592f,-0.0241155f,0.120045f},{-0.326879f,-0.00136408f,0.120045f},{-0.327354f,-0.0013662f,0.120045f}, -{-0.293888f,-0.0245441f,0.120045f},{-0.326779f,-0.00272485f,0.120045f},{-0.327247f,-0.00272864f,0.120045f}, -{-0.295204f,-0.0249032f,0.120045f},{-0.326598f,-0.0040775f,0.120045f},{-0.327069f,-0.00408356f,0.120045f}, -{-0.296539f,-0.0251918f,0.120045f},{-0.297886f,-0.0254089f,0.120045f},{-0.300606f,-0.0256265f,0.120045f}, -{-0.326345f,-0.00541865f,0.120045f},{-0.32682f,-0.00542725f,0.120045f},{-0.304017f,-0.025959f,0.120045f}, -{-0.304691f,-0.0254087f,0.120045f},{-0.305372f,-0.0257802f,0.120045f},{-0.325164f,-0.00933492f,0.120045f}, -{-0.325627f,-0.00805103f,0.120045f},{-0.325656f,-0.00935456f,0.120045f},{-0.308044f,-0.0252123f,0.120045f}, -{-0.30869f,-0.0245439f,0.120045f},{-0.309354f,-0.0248241f,0.120045f},{-0.323893f,-0.0130514f,0.120045f}, -{-0.324037f,-0.0118198f,0.120045f},{-0.324545f,-0.0118505f,0.120045f},{-0.313138f,-0.0232571f,0.120045f}, -{-0.311905f,-0.0238453f,0.120045f},{-0.3125f,-0.0230539f,0.120045f},{-0.321573f,-0.0164269f,0.120045f}, -{-0.321867f,-0.0152875f,0.120045f},{-0.322405f,-0.0153428f,0.120045f},{-0.317714f,-0.0202852f,0.120045f}, -{-0.31817f,-0.019292f,0.120045f},{-0.318753f,-0.0193978f,0.120045f},{-0.314339f,-0.022605f,0.120045f}, -{-0.313711f,-0.0224246f,0.120045f},{-0.320125f,-0.0173882f,0.120045f},{-0.320685f,-0.017466f,0.120045f}, -{-0.319745f,-0.0184572f,0.120045f},{-0.319173f,-0.0183661f,0.120045f},{-0.31663f,-0.021117f,0.120045f}, -{-0.315504f,-0.021891f,0.120045f},{-0.316024f,-0.0209773f,0.120045f},{-0.314887f,-0.0217317f,0.120045f}, -{-0.321024f,-0.016361f,0.120045f},{-0.31712f,-0.0201633f,0.120045f},{-0.309986f,-0.0241152f,0.120045f}, -{-0.310642f,-0.024368f,0.120045f},{-0.311257f,-0.023618f,0.120045f},{-0.323375f,-0.0130136f,0.120045f}, -{-0.323179f,-0.0142166f,0.120045f},{-0.322651f,-0.0141706f,0.120045f},{-0.306039f,-0.0251915f,0.120045f}, -{-0.306715f,-0.0255313f,0.120045f},{-0.307373f,-0.024903f,0.120045f},{-0.324633f,-0.0105924f,0.120045f}, -{-0.325133f,-0.0106171f,0.120045f},{-0.301971f,-0.0256265f,0.120045f},{-0.302654f,-0.0260568f,0.120045f}, -{-0.303334f,-0.0255538f,0.120045f},{-0.326501f,-0.00675606f,0.120045f},{-0.326021f,-0.00674437f,0.120045f}, -{-0.326113f,-0.00806637f,0.120045f},{-0.299243f,-0.0255539f,0.120045f},{-0.306738f,-0.0255265f,0.106062f}, -{-0.305396f,-0.0257766f,0.106062f},{-0.304039f,-0.0259565f,0.106062f},{-0.310646f,-0.0243666f,0.106062f}, -{-0.308062f,-0.0252075f,0.106062f},{-0.315485f,-0.0219036f,0.106062f},{-0.314323f,-0.0226143f,0.106062f}, -{-0.313127f,-0.0232624f,0.106062f},{-0.311901f,-0.0238468f,0.106062f},{-0.318743f,-0.0194069f,0.106062f}, -{-0.316611f,-0.0211315f,0.106062f},{-0.32242f,-0.0153222f,0.106062f},{-0.321587f,-0.0164092f,0.106062f}, -{-0.320695f,-0.0174549f,0.106062f},{-0.319745f,-0.0184567f,0.106062f},{-0.324551f,-0.0118391f,0.106062f}, -{-0.323192f,-0.0141964f,0.106062f},{-0.326496f,-0.00677408f,0.106062f},{-0.326109f,-0.00807765f,0.106062f}, -{-0.325655f,-0.00935809f,0.106062f},{-0.325135f,-0.0106128f,0.106062f},{-0.327065f,-0.0041079f,0.106062f}, -{-0.327245f,-0.00275048f,0.106062f},{-0.326815f,-0.00544996f,0.106062f},{-0.327354f,0.00138025f,0.106062f}, -{-0.32739f,2.06991e-018f,0.106062f},{-0.327354f,-0.00138032f,0.106062f},{-0.326815f,0.00544975f,0.106062f}, -{-0.327065f,0.00410773f,0.106062f},{-0.327245f,0.00275036f,0.106062f},{-0.326109f,0.0080774f,0.106062f}, -{-0.326496f,0.00677384f,0.106062f},{-0.325135f,0.0106125f,0.106062f},{-0.324551f,0.0118389f,0.106062f}, -{-0.325655f,0.00935782f,0.106062f},{-0.323192f,0.0141962f,0.106062f},{-0.323903f,0.0130343f,0.106062f}, -{-0.321587f,0.0164091f,0.106062f},{-0.32242f,0.015322f,0.106062f},{-0.319745f,0.0184567f,0.106062f}, -{-0.320695f,0.0174549f,0.106062f},{-0.318743f,0.0194069f,0.106062f},{-0.317698f,0.0202988f,0.106062f}, -{-0.316611f,0.0211314f,0.106062f},{-0.315485f,0.0219036f,0.106062f},{-0.314323f,0.0226142f,0.106062f}, -{-0.313128f,0.0232623f,0.106062f},{-0.311901f,0.0238467f,0.106062f},{-0.310647f,0.0243664f,0.106062f}, -{-0.309366f,0.0248204f,0.106062f},{-0.308063f,0.0252074f,0.106062f},{-0.306739f,0.0255265f,0.106062f}, -{-0.305396f,0.0257765f,0.106062f},{-0.304039f,0.0259565f,0.106062f},{-0.302669f,0.0260652f,0.106062f}, -{-0.323903f,-0.0130346f,0.106062f},{-0.317698f,-0.0202989f,0.106062f},{-0.309366f,-0.0248205f,0.106062f}, -{-0.302669f,-0.0260653f,0.106062f},{-0.317713f,-0.013782f,0.106062f},{-0.314092f,-0.0171983f,0.106062f}, -{-0.30978f,-0.0196871f,0.106062f},{-0.305011f,-0.0211136f,0.106062f},{-0.302535f,-0.0214048f,0.106062f}, -{-0.303778f,-0.0212945f,0.106062f},{-0.308622f,-0.0201477f,0.106062f},{-0.310911f,-0.01916f,0.106062f}, -{-0.312009f,-0.0185682f,0.106062f},{-0.31307f,-0.0179136f,0.106062f},{-0.316884f,-0.0147136f,0.106062f}, -{-0.316002f,-0.0155955f,0.106062f},{-0.31507f,-0.0164247f,0.106062f},{-0.319856f,-0.0107207f,0.106062f}, -{-0.319202f,-0.0117822f,0.106062f},{-0.318486f,-0.0128038f,0.106062f},{-0.320448f,-0.00962296f,0.106062f}, -{-0.320975f,-0.00849262f,0.106062f},{-0.321436f,-0.00733354f,0.106062f},{-0.321828f,-0.00614966f,0.106062f}, -{-0.322151f,-0.00494495f,0.106062f},{-0.322403f,-0.00372348f,0.106062f},{-0.322584f,-0.00248937f,0.106062f}, -{-0.322693f,-0.00124681f,0.106062f},{-0.322729f,-1.73872e-017f,0.106062f},{-0.322693f,0.00124661f,0.106062f}, -{-0.322584f,0.00248903f,0.106062f},{-0.322404f,0.00372306f,0.106062f},{-0.322151f,0.0049445f,0.106062f}, -{-0.321829f,0.00614923f,0.106062f},{-0.321436f,0.00733314f,0.106062f},{-0.320976f,0.00849224f,0.106062f}, -{-0.319857f,0.0107204f,0.106062f},{-0.303778f,0.0212927f,0.106062f},{-0.302536f,0.0214054f,0.106062f}, -{-0.317713f,0.013782f,0.106062f},{-0.306234f,0.0208628f,0.106062f},{-0.307438f,0.0205399f,0.106062f}, -{-0.31507f,0.0164248f,0.106062f},{-0.316002f,0.0155957f,0.106062f},{-0.312009f,0.0185682f,0.106062f}, -{-0.31307f,0.0179135f,0.106062f},{-0.314092f,0.0171982f,0.106062f},{-0.309781f,0.0196873f,0.106062f}, -{-0.308622f,0.0201477f,0.106062f},{-0.310911f,0.0191602f,0.106062f},{-0.305011f,0.0211056f,0.106062f}, -{-0.316884f,0.0147138f,0.106062f},{-0.319202f,0.011782f,0.106062f},{-0.318487f,0.0128037f,0.106062f}, -{-0.320449f,0.0096226f,0.106062f},{-0.306233f,-0.02086f,0.106062f},{-0.307438f,-0.0205402f,0.106062f}, -{-0.30625f,-0.0208587f,0.10513f},{-0.305032f,-0.0211115f,0.10513f},{-0.303796f,-0.0212936f,0.10513f}, -{-0.309779f,-0.019688f,0.10513f},{-0.30745f,-0.0205363f,0.10513f},{-0.314076f,-0.0172102f,0.10513f}, -{-0.313054f,-0.0179243f,0.10513f},{-0.311995f,-0.018576f,0.10513f},{-0.310903f,-0.0191643f,0.10513f}, -{-0.316888f,-0.0147088f,0.10513f},{-0.315058f,-0.0164352f,0.10513f},{-0.319865f,-0.010707f,0.10513f}, -{-0.319213f,-0.0117656f,0.10513f},{-0.318499f,-0.0127873f,0.10513f},{-0.321434f,-0.00733859f,0.10513f}, -{-0.320976f,-0.00849054f,0.10513f},{-0.320453f,-0.0096143f,0.10513f},{-0.322582f,-0.00250813f,0.10513f}, -{-0.3224f,-0.00374334f,0.10513f},{-0.322147f,-0.00496208f,0.10513f},{-0.321825f,-0.00616144f,0.10513f}, -{-0.322729f,-2.2769e-017f,0.10513f},{-0.322692f,0.00125925f,0.10513f},{-0.322692f,-0.00125938f,0.10513f}, -{-0.3224f,0.00374312f,0.10513f},{-0.322582f,0.00250793f,0.10513f},{-0.321434f,0.0073385f,0.10513f}, -{-0.321825f,0.00616138f,0.10513f},{-0.322147f,0.00496191f,0.10513f},{-0.320453f,0.00961408f,0.10513f}, -{-0.320976f,0.00849036f,0.10513f},{-0.318499f,0.0127873f,0.10513f},{-0.319213f,0.0117655f,0.10513f}, -{-0.319865f,0.0107068f,0.10513f},{-0.316889f,0.0147082f,0.10513f},{-0.317724f,0.0137691f,0.10513f}, -{-0.315997f,0.0155998f,0.10513f},{-0.315058f,0.0164352f,0.10513f},{-0.314076f,0.0172102f,0.10513f}, -{-0.313054f,0.0179242f,0.10513f},{-0.311996f,0.018576f,0.10513f},{-0.310903f,0.0191643f,0.10513f}, -{-0.309779f,0.0196879f,0.10513f},{-0.308627f,0.0201457f,0.10513f},{-0.30745f,0.0205363f,0.10513f}, -{-0.305032f,0.0211114f,0.10513f},{-0.306251f,0.0208586f,0.10513f},{-0.303797f,0.0212935f,0.10513f}, -{-0.302548f,0.0214037f,0.10513f},{-0.317724f,-0.0137693f,0.10513f},{-0.315997f,-0.0156004f,0.10513f}, -{-0.308627f,-0.0201457f,0.10513f},{-0.302548f,-0.0214037f,0.10513f},{-0.317178f,-0.0207081f,0.10513f}, -{-0.32739f,2.25963e-017f,0.10513f},{-0.327334f,-0.00170747f,0.10513f},{-0.325403f,-0.0099892f,0.10513f}, -{-0.326889f,-0.00509254f,0.10513f},{-0.326501f,-0.00675606f,0.10513f},{-0.324698f,-0.0115449f,0.10513f}, -{-0.322991f,-0.0145019f,0.10513f},{-0.321996f,-0.0158902f,0.10513f},{-0.308044f,-0.0252123f,0.10513f}, -{-0.30638f,-0.0256001f,0.10513f},{-0.302995f,-0.0260375f,0.10513f},{-0.314339f,-0.022605f,0.10513f}, -{-0.312833f,-0.0234101f,0.10513f},{-0.311277f,-0.0241149f,0.10513f},{-0.309678f,-0.0247164f,0.10513f}, -{-0.315789f,-0.0217031f,0.10513f},{-0.319745f,-0.0184572f,0.10513f},{-0.318498f,-0.0196247f,0.10513f}, -{-0.304695f,-0.0258794f,0.10513f},{-0.320912f,-0.0172106f,0.10513f},{-0.323893f,-0.0130514f,0.10513f}, -{-0.326005f,-0.00839068f,0.10513f},{-0.327167f,-0.00340738f,0.10513f},{-0.327334f,0.00170697f,0.10513f}, -{-0.327167f,0.0034068f,0.10513f},{-0.326005f,0.00839024f,0.10513f},{-0.326501f,0.00675581f,0.10513f}, -{-0.326889f,0.00509225f,0.10513f},{-0.325404f,0.00998889f,0.10513f},{-0.324699f,0.0115449f,0.10513f}, -{-0.323893f,0.0130512f,0.10513f},{-0.321996f,0.0158901f,0.10513f},{-0.322991f,0.0145016f,0.10513f}, -{-0.320913f,0.0172105f,0.10513f},{-0.318498f,0.0196248f,0.10513f},{-0.31579f,0.0217032f,0.10513f}, -{-0.317178f,0.0207084f,0.10513f},{-0.314339f,0.0226051f,0.10513f},{-0.312833f,0.0234102f,0.10513f}, -{-0.304696f,0.0258786f,0.10513f},{-0.302996f,0.0260403f,0.10513f},{-0.306381f,0.0256003f,0.10513f}, -{-0.308044f,0.0252126f,0.10513f},{-0.309679f,0.0247167f,0.10513f},{-0.319745f,0.0184571f,0.10513f}, -{-0.311277f,0.024115f,0.10513f},{-0.312708f,0.0197792f,0.10252f},{-0.314476f,0.0186469f,0.10252f}, -{-0.31364f,0.0213938f,0.104011f},{-0.319197f,0.0141739f,0.10252f},{-0.317748f,0.0158335f,0.10252f}, -{-0.316165f,0.0173289f,0.10252f},{-0.323734f,0.00421973f,0.10252f},{-0.32323f,0.00633871f,0.10252f}, -{-0.322518f,0.00842303f,0.10252f},{-0.324128f,4.29036e-018f,0.10252f},{-0.324031f,0.00209801f,0.10252f}, -{-0.31364f,-0.0213938f,0.104011f},{-0.312708f,-0.0197792f,0.10252f},{-0.31144f,-0.0204589f,0.10252f}, -{-0.310112f,-0.0210659f,0.10252f},{-0.308729f,-0.0215929f,0.10252f},{-0.3073f,-0.0220336f,0.10252f}, -{-0.305832f,-0.0223824f,0.10252f},{-0.304335f,-0.022635f,0.10252f},{-0.302817f,-0.0227878f,0.10252f}, -{-0.307791f,-0.0238322f,0.104011f},{-0.306203f,-0.0242096f,0.104011f},{-0.312269f,-0.0221291f,0.104011f}, -{-0.304583f,-0.0244827f,0.104011f},{-0.302942f,-0.0246481f,0.104011f},{-0.309337f,-0.0233556f,0.104011f}, -{-0.310832f,-0.0227855f,0.104011f},{-0.320488f,0.0123693f,0.10252f},{-0.3216f,0.0104434f,0.10252f}, -{-0.31738f,0.0187434f,0.104011f},{-0.325992f,6.69898e-018f,0.104011f},{-0.325887f,0.00226809f,0.104011f}, -{-0.325567f,0.00456378f,0.104011f},{-0.325022f,0.00685491f,0.104011f},{-0.324251f,0.00910982f,0.104011f}, -{-0.323259f,0.011295f,0.104011f},{-0.322056f,0.0133782f,0.104011f},{-0.32066f,0.0153304f,0.104011f}, -{-0.319093f,0.0171254f,0.104011f},{-0.315553f,0.0201689f,0.104011f},{-0.275689f,-0.00136552f,0.121909f}, -{-0.275798f,-0.00272732f,0.121909f},{-0.287538f,-0.0216357f,0.121909f},{-0.285747f,-0.0203873f,0.121909f}, -{-0.289427f,-0.0227264f,0.121909f},{-0.291404f,-0.0236533f,0.121909f},{-0.311174f,-0.0236531f,0.121909f}, -{-0.31315f,-0.0227263f,0.121909f},{-0.316831f,-0.0203871f,0.121909f},{-0.315039f,-0.0216356f,0.121909f}, -{-0.326597f,-0.0040808f,0.121909f},{-0.326779f,-0.00272711f,0.121909f},{-0.326888f,-0.00136573f,0.121909f}, -{-0.27598f,-0.00408095f,0.121909f},{-0.313448f,0.000612842f,0.104198f},{-0.31403f,0.00232777f,0.104198f}, -{-0.313762f,0.00178369f,0.104198f},{-0.313567f,0.00120978f,0.104198f},{-0.315234f,0.00370055f,0.104198f}, -{-0.314368f,0.0028342f,0.104198f},{-0.314772f,0.00329584f,0.104198f},{-0.317456f,0.00462066f,0.104198f}, -{-0.316859f,0.00450141f,0.104198f},{-0.316285f,0.00430621f,0.104198f},{-0.318681f,0.00462052f,0.104198f}, -{-0.319278f,0.00450127f,0.104198f},{-0.318068f,0.00466102f,0.104198f},{-0.320396f,0.00403818f,0.104198f}, -{-0.319852f,0.00430621f,0.104198f},{-0.321364f,0.00329584f,0.104198f},{-0.320902f,0.00370041f,0.104198f}, -{-0.321769f,0.00283386f,0.104198f},{-0.322107f,0.00232743f,0.104198f},{-0.322374f,0.00178369f,0.104198f}, -{-0.32257f,0.00120944f,0.104198f},{-0.322689f,0.000612502f,0.104198f},{-0.315741f,0.00403832f,0.104198f}, -{-0.311076f,-0.00884266f,0.110723f},{-0.310739f,-0.00903773f,0.110723f},{-0.311447f,-0.00872205f,0.110723f}, -{-0.310449f,-0.00929879f,0.110723f},{-0.31022f,-0.00961469f,0.110723f},{-0.310062f,-0.00997137f,0.110723f}, -{-0.309981f,-0.0103527f,0.110723f},{-0.309981f,-0.0107427f,0.110723f},{-0.310223f,-0.0114796f,0.110723f}, -{-0.310063f,-0.011124f,0.110723f},{-0.310741f,-0.0120547f,0.110723f},{-0.310452f,-0.0117943f,0.110723f}, -{-0.311448f,-0.0123696f,0.110723f},{-0.311078f,-0.0122492f,0.110723f},{-0.288006f,-0.0108202f,0.110723f}, -{-0.287668f,-0.0110152f,0.110723f},{-0.288376f,-0.0106996f,0.110723f},{-0.287378f,-0.0112763f,0.110723f}, -{-0.287149f,-0.0115922f,0.110723f},{-0.286991f,-0.0119489f,0.110723f},{-0.28691f,-0.0123302f,0.110723f}, -{-0.286911f,-0.0127202f,0.110723f},{-0.287152f,-0.0134571f,0.110723f},{-0.286993f,-0.0131015f,0.110723f}, -{-0.28767f,-0.0140322f,0.110723f},{-0.287381f,-0.0137718f,0.110723f},{-0.288378f,-0.0143471f,0.110723f}, -{-0.288007f,-0.0142268f,0.110723f},{-0.289983f,0.0122507f,0.110723f},{-0.289645f,0.0120557f,0.110723f}, -{-0.290354f,0.0123713f,0.110723f},{-0.289355f,0.0117946f,0.110723f},{-0.289126f,0.0114787f,0.110723f}, -{-0.288968f,0.011122f,0.110723f},{-0.288888f,0.0107407f,0.110723f},{-0.288888f,0.0103507f,0.110723f}, -{-0.289129f,0.00961383f,0.110723f},{-0.28897f,0.00996936f,0.110723f},{-0.289648f,0.00903866f,0.110723f}, -{-0.289358f,0.00929907f,0.110723f},{-0.290355f,0.00872375f,0.110723f},{-0.289985f,0.00884413f,0.110723f}, -{-0.313054f,0.0142282f,0.110723f},{-0.312716f,0.0140332f,0.110723f},{-0.313425f,0.0143488f,0.110723f}, -{-0.312426f,0.0137721f,0.110723f},{-0.312197f,0.0134562f,0.110723f},{-0.312039f,0.0130995f,0.110723f}, -{-0.311959f,0.0127182f,0.110723f},{-0.311959f,0.0123282f,0.110723f},{-0.3122f,0.0115913f,0.110723f}, -{-0.312041f,0.0119469f,0.110723f},{-0.312719f,0.0110162f,0.110723f},{-0.312429f,0.0112766f,0.110723f}, -{-0.313426f,0.0107013f,0.110723f},{-0.313056f,0.0108216f,0.110723f},{-0.301901f,-0.0121592f,0.104198f}, -{-0.303616f,-0.0127415f,0.104198f},{-0.302498f,-0.0122784f,0.104198f},{-0.303072f,-0.0124735f,0.104198f}, -{-0.304989f,-0.0139458f,0.104198f},{-0.305327f,-0.0144523f,0.104198f},{-0.304584f,-0.0134838f,0.104198f}, -{-0.305909f,-0.0161672f,0.104198f},{-0.305595f,-0.014996f,0.104198f},{-0.30579f,-0.0155702f,0.104198f}, -{-0.30579f,-0.0179895f,0.104198f},{-0.30595f,-0.0167797f,0.104198f},{-0.305909f,-0.0173925f,0.104198f}, -{-0.305327f,-0.0191075f,0.104198f},{-0.304989f,-0.0196139f,0.104198f},{-0.305595f,-0.0185634f,0.104198f}, -{-0.304584f,-0.0200755f,0.104198f},{-0.304122f,-0.0204802f,0.104198f},{-0.303616f,-0.020818f,0.104198f}, -{-0.303072f,-0.0210859f,0.104198f},{-0.302498f,-0.0212811f,0.104198f},{-0.301901f,-0.0214003f,0.104198f}, -{-0.304123f,-0.0130793f,0.104198f},{-0.289129f,-0.000612842f,0.104198f},{-0.288547f,-0.00232777f,0.104198f}, -{-0.288815f,-0.00178369f,0.104198f},{-0.28901f,-0.00120978f,0.104198f},{-0.287343f,-0.00370055f,0.104198f}, -{-0.288209f,-0.0028342f,0.104198f},{-0.287805f,-0.00329584f,0.104198f},{-0.285121f,-0.00462066f,0.104198f}, -{-0.285718f,-0.00450141f,0.104198f},{-0.286293f,-0.00430621f,0.104198f},{-0.283299f,-0.00450127f,0.104198f}, -{-0.283896f,-0.00462052f,0.104198f},{-0.284509f,-0.00466102f,0.104198f},{-0.282181f,-0.00403818f,0.104198f}, -{-0.282725f,-0.00430621f,0.104198f},{-0.281213f,-0.00329584f,0.104198f},{-0.281675f,-0.00370041f,0.104198f}, -{-0.280808f,-0.00283386f,0.104198f},{-0.280471f,-0.00232743f,0.104198f},{-0.280203f,-0.00178369f,0.104198f}, -{-0.280007f,-0.00120944f,0.104198f},{-0.279888f,-0.000612502f,0.104198f},{-0.286836f,-0.00403832f,0.104198f}, -{-0.300676f,0.0121592f,0.104198f},{-0.298961f,0.0127415f,0.104198f},{-0.299505f,0.0124735f,0.104198f}, -{-0.300079f,0.0122784f,0.104198f},{-0.297588f,0.0139458f,0.104198f},{-0.298454f,0.0130793f,0.104198f}, -{-0.297993f,0.0134838f,0.104198f},{-0.296668f,0.0161672f,0.104198f},{-0.296787f,0.0155702f,0.104198f}, -{-0.296982f,0.014996f,0.104198f},{-0.296668f,0.0173925f,0.104198f},{-0.296787f,0.0179895f,0.104198f}, -{-0.296628f,0.0167797f,0.104198f},{-0.29725f,0.0191075f,0.104198f},{-0.296982f,0.0185634f,0.104198f}, -{-0.297993f,0.0200755f,0.104198f},{-0.297588f,0.0196139f,0.104198f},{-0.298455f,0.0204802f,0.104198f}, -{-0.298961f,0.020818f,0.104198f},{-0.299505f,0.0210859f,0.104198f},{-0.300079f,0.0212811f,0.104198f}, -{-0.300676f,0.0214003f,0.104198f},{-0.29725f,0.0144523f,0.104198f},{-0.289869f,-0.0197792f,0.104198f}, -{-0.291807f,-0.0207778f,0.104198f},{-0.298032f,-0.0226057f,0.104198f},{-0.293823f,-0.0215843f,0.104198f}, -{-0.304545f,-0.0226056f,0.104198f},{-0.300198f,-0.022813f,0.104198f},{-0.30238f,-0.0228129f,0.104198f}, -{-0.308755f,-0.0215842f,0.104198f},{-0.306675f,-0.0221948f,0.104198f},{-0.310771f,-0.0207777f,0.104198f}, -{-0.312708f,-0.0197792f,0.104198f},{-0.295903f,-0.0221949f,0.104198f},{-0.288937f,-0.0213938f,0.104198f}, -{-0.31364f,-0.0213938f,0.104198f},{-0.311544f,-0.022474f,0.104198f},{-0.304811f,-0.0244511f,0.104198f}, -{-0.309364f,-0.0233463f,0.104198f},{-0.297766f,-0.024451f,0.104198f},{-0.302468f,-0.0246752f,0.104198f}, -{-0.300108f,-0.0246752f,0.104198f},{-0.293213f,-0.0233462f,0.104198f},{-0.291032f,-0.0224738f,0.104198f}, -{-0.295463f,-0.0240066f,0.104198f},{-0.307114f,-0.0240067f,0.104198f},{-0.288035f,0.0186002f,0.104198f}, -{-0.289869f,0.0197792f,0.104198f},{-0.28334f,0.0141228f,0.104198f},{-0.28476f,0.0157616f,0.104198f}, -{-0.286329f,0.0172577f,0.104198f},{-0.280986f,0.0104612f,0.104198f},{-0.280083f,0.00848256f,0.104198f}, -{-0.282077f,0.0123508f,0.104198f},{-0.278863f,0.00432634f,0.104198f},{-0.279374f,0.00643279f,0.104198f}, -{-0.278553f,0.00217707f,0.104198f},{-0.27845f,-1.74881e-017f,0.104198f},{-0.288937f,0.0213938f,0.104198f}, -{-0.276585f,-1.89158e-017f,0.104198f},{-0.276698f,0.00235542f,0.104198f},{-0.278352f,0.00917539f,0.104198f}, -{-0.277585f,0.0069585f,0.104198f},{-0.277032f,0.00467972f,0.104198f},{-0.28051f,0.01336f,0.104198f}, -{-0.281875f,0.015276f,0.104198f},{-0.279329f,0.0113162f,0.104198f},{-0.283411f,0.0170487f,0.104198f}, -{-0.285108f,0.0186667f,0.104198f},{-0.286954f,0.020119f,0.104198f},{-0.324023f,0.00217765f,0.104198f}, -{-0.324128f,0.0f,0.104198f},{-0.322494f,0.00848291f,0.104198f},{-0.323203f,0.00643333f,0.104198f}, -{-0.323714f,0.00432654f,0.104198f},{-0.320499f,0.0123517f,0.104198f},{-0.319237f,0.0141231f,0.104198f}, -{-0.32159f,0.0104622f,0.104198f},{-0.316248f,0.0172579f,0.104198f},{-0.317817f,0.015762f,0.104198f}, -{-0.314541f,0.0186006f,0.104198f},{-0.312708f,0.0197792f,0.104198f},{-0.325992f,8.08559e-018f,0.104198f}, -{-0.31364f,0.0213938f,0.104198f},{-0.315624f,0.0201186f,0.104198f},{-0.320703f,0.0152757f,0.104198f}, -{-0.319166f,0.0170482f,0.104198f},{-0.317469f,0.0186665f,0.104198f},{-0.323248f,0.0113151f,0.104198f}, -{-0.324225f,0.00917501f,0.104198f},{-0.322068f,0.013359f,0.104198f},{-0.324992f,0.00695792f,0.104198f}, -{-0.325545f,0.00467951f,0.104198f},{-0.32588f,0.00235479f,0.104198f},{-0.304042f,-0.000488516f,0.0986044f}, -{-0.303431f,-0.00179767f,0.0986044f},{-0.303711f,-0.00139727f,0.0986044f},{-0.303916f,-0.000957717f,0.0986044f}, -{-0.302245f,-0.00262801f,0.0986044f},{-0.301776f,-0.00275376f,0.0986044f},{-0.303084f,-0.00214411f,0.0986044f}, -{-0.302684f,-0.00242333f,0.0986044f},{-0.300331f,-0.00262748f,0.0986044f},{-0.3008f,-0.00275356f,0.0986044f}, -{-0.301289f,-0.00279661f,0.0986044f},{-0.299491f,-0.00214219f,0.0986044f},{-0.299891f,-0.00242266f,0.0986044f}, -{-0.299144f,-0.00179504f,0.0986044f},{-0.298865f,-0.00139564f,0.0986044f},{-0.298661f,-0.000956449f,0.0986044f}, -{-0.298535f,-0.000488516f,0.0986044f},{-0.283879f,-0.00122594f,0.121909f},{-0.284001f,-0.00061944f,0.121909f}, -{-0.284043f,-1.93104e-018f,0.121909f},{-0.283676f,-0.0018111f,0.121909f},{-0.283048f,-0.00287862f,0.121909f}, -{-0.283397f,-0.00236645f,0.121909f},{-0.282634f,-0.00333866f,0.121909f},{-0.282162f,-0.00374077f,0.121909f}, -{-0.28164f,-0.00407752f,0.121909f},{-0.281079f,-0.00434093f,0.121909f},{-0.280489f,-0.00452747f,0.121909f}, -{-0.279878f,-0.00463457f,0.121909f},{-0.284001f,0.000619763f,0.121909f},{-0.283879f,0.00122605f,0.121909f}, -{-0.283676f,0.00181151f,0.121909f},{-0.283397f,0.00236685f,0.121909f},{-0.283047f,0.00287881f,0.121909f}, -{-0.282634f,0.00333885f,0.121909f},{-0.282162f,0.00374104f,0.121909f},{-0.281639f,0.00407771f,0.121909f}, -{-0.281079f,0.00434097f,0.121909f},{-0.280489f,0.00452758f,0.121909f},{-0.279878f,0.00463457f,0.121909f}, -{-0.293673f,0.00708542f,0.121909f},{-0.293069f,0.00862355f,0.121909f},{-0.293346f,0.0081433f,0.121909f}, -{-0.293548f,0.00762768f,0.121909f},{-0.291847f,0.00975654f,0.121909f},{-0.292719f,0.00906182f,0.121909f}, -{-0.292307f,0.00944325f,0.121909f},{-0.289704f,0.0102431f,0.121909f},{-0.290265f,0.0102438f,0.121909f}, -{-0.290819f,0.0101602f,0.121909f},{-0.288623f,0.0099962f,0.121909f},{-0.289153f,0.0101597f,0.121909f}, -{-0.287661f,0.00944071f,0.121909f},{-0.287251f,0.00905963f,0.121909f},{-0.288123f,0.00975564f,0.121909f}, -{-0.286903f,0.00862291f,0.121909f},{-0.286626f,0.0081413f,0.121909f},{-0.286423f,0.00762524f,0.121909f}, -{-0.2863f,0.00708542f,0.121909f},{-0.291348f,0.00999655f,0.121909f},{-0.29379f,0.000388892f,0.121909f}, -{-0.293213f,0.0013863f,0.121909f},{-0.29367f,0.000758756f,0.121909f},{-0.292161f,0.00185425f,0.121909f}, -{-0.292898f,0.00161492f,0.121909f},{-0.292542f,0.0017734f,0.121909f},{-0.291389f,0.00177278f,0.121909f}, -{-0.291034f,0.0016145f,0.121909f},{-0.291771f,0.00185398f,0.121909f},{-0.290718f,0.00138471f,0.121909f}, -{-0.290458f,0.00109509f,0.121909f},{-0.290263f,0.000757801f,0.121909f},{-0.290143f,0.000387896f,0.121909f}, -{-0.293474f,0.00109643f,0.121909f},{-0.294965f,0.0184341f,0.121909f},{-0.294991f,0.019053f,0.121909f}, -{-0.294936f,0.0196708f,0.121909f},{-0.294853f,0.0178247f,0.121909f},{-0.294661f,0.0172353f,0.121909f}, -{-0.294392f,0.0166765f,0.121909f},{-0.294051f,0.0161585f,0.121909f},{-0.292666f,0.0149353f,0.121909f}, -{-0.292109f,0.0146616f,0.121909f},{-0.293645f,0.0156903f,0.121909f},{-0.293181f,0.0152802f,0.121909f}, -{-0.290913f,0.0143468f,0.121909f},{-0.290294f,0.0143112f,0.121909f},{-0.286967f,0.0157495f,0.121909f}, -{-0.287426f,0.015333f,0.121909f},{-0.289069f,0.0144863f,0.121909f},{-0.288486f,0.0146944f,0.121909f}, -{-0.287935f,0.0149788f,0.121909f},{-0.286569f,0.0162251f,0.121909f},{-0.289676f,0.014358f,0.121909f}, -{-0.291521f,0.0144643f,0.121909f},{-0.294812f,0.0202771f,0.121909f},{-0.294597f,0.0208597f,0.121909f}, -{-0.303617f,0.0101384f,0.121909f},{-0.304647f,0.0114304f,0.121909f},{-0.304369f,0.0109503f,0.121909f}, -{-0.304024f,0.0105172f,0.121909f},{-0.305017f,0.0130549f,0.121909f},{-0.304852f,0.011952f,0.121909f}, -{-0.304976f,0.0124996f,0.121909f},{-0.304367f,0.0151544f,0.121909f},{-0.304648f,0.0146689f,0.121909f}, -{-0.304853f,0.0141474f,0.121909f},{-0.303613f,0.0159666f,0.121909f},{-0.304019f,0.01559f,0.121909f}, -{-0.302651f,0.0165217f,0.121909f},{-0.302116f,0.0166864f,0.121909f},{-0.303154f,0.0162794f,0.121909f}, -{-0.301564f,0.0167695f,0.121909f},{-0.301008f,0.016769f,0.121909f},{-0.300459f,0.0166865f,0.121909f}, -{-0.29993f,0.0165233f,0.121909f},{-0.304976f,0.0136068f,0.121909f},{-0.297876f,0.00668844f,0.121909f}, -{-0.298451f,0.00768651f,0.121909f},{-0.298136f,0.00697788f,0.121909f},{-0.29833f,0.00883213f,0.121909f}, -{-0.298492f,0.00807381f,0.121909f},{-0.298451f,0.0084617f,0.121909f},{-0.297874f,0.00945932f,0.121909f}, -{-0.297559f,0.00968801f,0.121909f},{-0.298135f,0.00916954f,0.121909f},{-0.297203f,0.00984652f,0.121909f}, -{-0.296822f,0.00992735f,0.121909f},{-0.296432f,0.00992722f,0.121909f},{-0.296051f,0.00984624f,0.121909f}, -{-0.298331f,0.00731557f,0.121909f},{-0.31464f,0.0149805f,0.121909f},{-0.315148f,0.0153371f,0.121909f}, -{-0.308931f,0.0156909f,0.121909f},{-0.309396f,0.0152805f,0.121909f},{-0.308525f,0.0161593f,0.121909f}, -{-0.309911f,0.0149353f,0.121909f},{-0.308185f,0.0166773f,0.121909f},{-0.307917f,0.0172358f,0.121909f}, -{-0.307724f,0.0178252f,0.121909f},{-0.310468f,0.0146618f,0.121909f},{-0.311055f,0.0144645f,0.121909f}, -{-0.307613f,0.0184349f,0.121909f},{-0.311664f,0.0143468f,0.121909f},{-0.307584f,0.0190544f,0.121909f}, -{-0.307767f,0.0202777f,0.121909f},{-0.307636f,0.0196718f,0.121909f},{-0.312283f,0.0143109f,0.121909f}, -{-0.30798f,0.0208597f,0.121909f},{-0.312901f,0.0143575f,0.121909f},{-0.314091f,0.0146931f,0.121909f}, -{-0.313507f,0.0144856f,0.121909f},{-0.315611f,0.0157476f,0.121909f},{-0.316008f,0.0162251f,0.121909f}, -{-0.311233f,0.00305297f,0.121909f},{-0.312867f,0.00280688f,0.121909f},{-0.312312f,0.00280698f,0.121909f}, -{-0.311764f,0.00288948f,0.121909f},{-0.314459f,0.00329833f,0.121909f},{-0.313421f,0.00289017f,0.121909f}, -{-0.313957f,0.00305631f,0.121909f},{-0.315952f,0.00491125f,0.121909f},{-0.315672f,0.00442515f,0.121909f}, -{-0.315323f,0.00398713f,0.121909f},{-0.316278f,0.00597044f,0.121909f},{-0.316155f,0.00543021f,0.121909f}, -{-0.316278f,0.00708102f,0.121909f},{-0.316153f,0.00762679f,0.121909f},{-0.31632f,0.00652376f,0.121909f}, -{-0.315949f,0.0081466f,0.121909f},{-0.315671f,0.00862774f,0.121909f},{-0.315325f,0.00906124f,0.121909f}, -{-0.314919f,0.00943791f,0.121909f},{-0.314916f,0.00361021f,0.121909f},{-0.305375f,0.0062997f,0.121909f}, -{-0.306527f,0.00630037f,0.121909f},{-0.305755f,0.00621894f,0.121909f},{-0.307458f,0.0069779f,0.121909f}, -{-0.306882f,0.00645888f,0.121909f},{-0.307198f,0.0066883f,0.121909f},{-0.307773f,0.00768661f,0.121909f}, -{-0.307814f,0.00807365f,0.121909f},{-0.307653f,0.00731544f,0.121909f},{-0.307773f,0.00846171f,0.121909f}, -{-0.307652f,0.00883217f,0.121909f},{-0.307458f,0.00916947f,0.121909f},{-0.307197f,0.00945876f,0.121909f}, -{-0.306145f,0.00621907f,0.121909f},{-0.319179f,-0.0023656f,0.121909f},{-0.318901f,-0.00181168f,0.121909f}, -{-0.319529f,-0.00287783f,0.121909f},{-0.319943f,-0.00333905f,0.121909f},{-0.320415f,-0.00374099f,0.121909f}, -{-0.318698f,-0.00122583f,0.121909f},{-0.320938f,-0.00407246f,0.121909f},{-0.318576f,-0.000618365f,0.121909f}, -{-0.318534f,4.86429e-018f,0.121909f},{-0.318576f,0.000618856f,0.121909f},{-0.318699f,0.00122657f,0.121909f}, -{-0.318901f,0.00181243f,0.121909f},{-0.31918f,0.00236609f,0.121909f},{-0.319529f,0.00287783f,0.121909f}, -{-0.319944f,0.00333893f,0.121909f},{-0.320416f,0.00374048f,0.121909f},{-0.320938f,0.00407552f,0.121909f}, -{-0.321499f,0.00433883f,0.121909f},{-0.322089f,0.0045282f,0.121909f},{-0.322699f,0.00463457f,0.121909f}, -{-0.322087f,-0.00452954f,0.121909f},{-0.3215f,-0.00433369f,0.121909f},{-0.322699f,-0.00463457f,0.121909f}, -{-0.308905f,-0.00708542f,0.121909f},{-0.309508f,-0.00862355f,0.121909f},{-0.309231f,-0.0081433f,0.121909f}, -{-0.309029f,-0.00762768f,0.121909f},{-0.31073f,-0.00975654f,0.121909f},{-0.309858f,-0.00906182f,0.121909f}, -{-0.31027f,-0.00944325f,0.121909f},{-0.312873f,-0.0102431f,0.121909f},{-0.312313f,-0.0102438f,0.121909f}, -{-0.311758f,-0.0101602f,0.121909f},{-0.313954f,-0.0099962f,0.121909f},{-0.313425f,-0.0101597f,0.121909f}, -{-0.314916f,-0.00944071f,0.121909f},{-0.315326f,-0.00905963f,0.121909f},{-0.314454f,-0.00975564f,0.121909f}, -{-0.315674f,-0.00862291f,0.121909f},{-0.315951f,-0.0081413f,0.121909f},{-0.316154f,-0.00762524f,0.121909f}, -{-0.316277f,-0.00708542f,0.121909f},{-0.311229f,-0.00999655f,0.121909f},{-0.308787f,-0.000388892f,0.121909f}, -{-0.309364f,-0.0013863f,0.121909f},{-0.308908f,-0.000758756f,0.121909f},{-0.310416f,-0.00185425f,0.121909f}, -{-0.309679f,-0.00161492f,0.121909f},{-0.310035f,-0.0017734f,0.121909f},{-0.311188f,-0.00177278f,0.121909f}, -{-0.311543f,-0.0016145f,0.121909f},{-0.310806f,-0.00185398f,0.121909f},{-0.311859f,-0.00138471f,0.121909f}, -{-0.312119f,-0.00109509f,0.121909f},{-0.312314f,-0.000757801f,0.121909f},{-0.312434f,-0.000387896f,0.121909f}, -{-0.309103f,-0.00109643f,0.121909f},{-0.307586f,-0.019053f,0.121909f},{-0.307612f,-0.0184341f,0.121909f}, -{-0.316008f,-0.0162251f,0.121909f},{-0.307724f,-0.0178247f,0.121909f},{-0.307641f,-0.0196708f,0.121909f}, -{-0.307916f,-0.0172353f,0.121909f},{-0.308185f,-0.0166765f,0.121909f},{-0.308932f,-0.0156903f,0.121909f}, -{-0.309397f,-0.0152802f,0.121909f},{-0.308526f,-0.0161585f,0.121909f},{-0.311664f,-0.0143468f,0.121909f}, -{-0.312283f,-0.0143112f,0.121909f},{-0.309911f,-0.0149353f,0.121909f},{-0.310468f,-0.0146616f,0.121909f}, -{-0.31561f,-0.0157495f,0.121909f},{-0.315151f,-0.015333f,0.121909f},{-0.313508f,-0.0144863f,0.121909f}, -{-0.314092f,-0.0146944f,0.121909f},{-0.314643f,-0.0149788f,0.121909f},{-0.312901f,-0.014358f,0.121909f}, -{-0.311056f,-0.0144643f,0.121909f},{-0.307765f,-0.0202771f,0.121909f},{-0.30798f,-0.0208597f,0.121909f}, -{-0.29896f,-0.0101384f,0.121909f},{-0.29793f,-0.0114304f,0.121909f},{-0.298208f,-0.0109503f,0.121909f}, -{-0.298553f,-0.0105172f,0.121909f},{-0.29756f,-0.0130549f,0.121909f},{-0.297725f,-0.011952f,0.121909f}, -{-0.297601f,-0.0124996f,0.121909f},{-0.29821f,-0.0151544f,0.121909f},{-0.297929f,-0.0146689f,0.121909f}, -{-0.297725f,-0.0141474f,0.121909f},{-0.298964f,-0.0159666f,0.121909f},{-0.298558f,-0.01559f,0.121909f}, -{-0.299926f,-0.0165217f,0.121909f},{-0.300461f,-0.0166864f,0.121909f},{-0.299423f,-0.0162794f,0.121909f}, -{-0.301014f,-0.0167695f,0.121909f},{-0.301569f,-0.016769f,0.121909f},{-0.302118f,-0.0166865f,0.121909f}, -{-0.302647f,-0.0165233f,0.121909f},{-0.297601f,-0.0136068f,0.121909f},{-0.304701f,-0.00668858f,0.121909f}, -{-0.304126f,-0.00768692f,0.121909f},{-0.304441f,-0.00697763f,0.121909f},{-0.304247f,-0.00883211f,0.121909f}, -{-0.304085f,-0.00807384f,0.121909f},{-0.304126f,-0.00846133f,0.121909f},{-0.304703f,-0.00945929f,0.121909f}, -{-0.305018f,-0.00968796f,0.121909f},{-0.304442f,-0.00916975f,0.121909f},{-0.305375f,-0.00984651f,0.121909f}, -{-0.305756f,-0.00992734f,0.121909f},{-0.306145f,-0.00992724f,0.121909f},{-0.306525f,-0.00984636f,0.121909f}, -{-0.304246f,-0.00731545f,0.121909f},{-0.293646f,-0.0156909f,0.121909f},{-0.294052f,-0.0161593f,0.121909f}, -{-0.293181f,-0.0152805f,0.121909f},{-0.292666f,-0.0149353f,0.121909f},{-0.294392f,-0.0166773f,0.121909f}, -{-0.29466f,-0.0172358f,0.121909f},{-0.294853f,-0.0178252f,0.121909f},{-0.29211f,-0.0146618f,0.121909f}, -{-0.294964f,-0.0184349f,0.121909f},{-0.294994f,-0.0190544f,0.121909f},{-0.291522f,-0.0144645f,0.121909f}, -{-0.294941f,-0.0196718f,0.121909f},{-0.290913f,-0.0143468f,0.121909f},{-0.290295f,-0.0143109f,0.121909f}, -{-0.29481f,-0.0202777f,0.121909f},{-0.294597f,-0.0208597f,0.121909f},{-0.289676f,-0.0143575f,0.121909f}, -{-0.288486f,-0.0146931f,0.121909f},{-0.28907f,-0.0144856f,0.121909f},{-0.287937f,-0.0149805f,0.121909f}, -{-0.28743f,-0.0153371f,0.121909f},{-0.286966f,-0.0157476f,0.121909f},{-0.286569f,-0.0162251f,0.121909f}, -{-0.291344f,-0.00305297f,0.121909f},{-0.28971f,-0.00280688f,0.121909f},{-0.290265f,-0.00280698f,0.121909f}, -{-0.290813f,-0.00288948f,0.121909f},{-0.288118f,-0.00329833f,0.121909f},{-0.289156f,-0.00289017f,0.121909f}, -{-0.28862f,-0.00305631f,0.121909f},{-0.286625f,-0.00491125f,0.121909f},{-0.286905f,-0.00442515f,0.121909f}, -{-0.287255f,-0.00398713f,0.121909f},{-0.286299f,-0.00597044f,0.121909f},{-0.286422f,-0.00543021f,0.121909f}, -{-0.286299f,-0.00708102f,0.121909f},{-0.286424f,-0.00762679f,0.121909f},{-0.286257f,-0.00652376f,0.121909f}, -{-0.286628f,-0.0081466f,0.121909f},{-0.286907f,-0.00862774f,0.121909f},{-0.287252f,-0.00906124f,0.121909f}, -{-0.287658f,-0.00943791f,0.121909f},{-0.287661f,-0.00361021f,0.121909f},{-0.297203f,-0.0062997f,0.121909f}, -{-0.29605f,-0.00630037f,0.121909f},{-0.296822f,-0.00621894f,0.121909f},{-0.295119f,-0.0069779f,0.121909f}, -{-0.295695f,-0.00645888f,0.121909f},{-0.295379f,-0.0066883f,0.121909f},{-0.294804f,-0.00768661f,0.121909f}, -{-0.294763f,-0.00807365f,0.121909f},{-0.294924f,-0.00731544f,0.121909f},{-0.294804f,-0.00846171f,0.121909f}, -{-0.294925f,-0.00883217f,0.121909f},{-0.29512f,-0.00916947f,0.121909f},{-0.29538f,-0.00945876f,0.121909f}, -{-0.296432f,-0.00621907f,0.121909f},{-0.296668f,-0.000612842f,0.127503f},{-0.29725f,-0.00232777f,0.127503f}, -{-0.296787f,-0.00120978f,0.127503f},{-0.298455f,-0.00370055f,0.127503f},{-0.298961f,-0.00403832f,0.127503f}, -{-0.297993f,-0.00329584f,0.127503f},{-0.300676f,-0.00462066f,0.127503f},{-0.299505f,-0.00430621f,0.127503f}, -{-0.300079f,-0.00450141f,0.127503f},{-0.302498f,-0.00450127f,0.127503f},{-0.301289f,-0.00466102f,0.127503f}, -{-0.301901f,-0.00462052f,0.127503f},{-0.303616f,-0.00403818f,0.127503f},{-0.304123f,-0.00370041f,0.127503f}, -{-0.303072f,-0.00430621f,0.127503f},{-0.304584f,-0.00329584f,0.127503f},{-0.304989f,-0.00283386f,0.127503f}, -{-0.305327f,-0.00232743f,0.127503f},{-0.305595f,-0.00178369f,0.127503f},{-0.30579f,-0.00120944f,0.127503f}, -{-0.305909f,-0.000612502f,0.127503f},{-0.297588f,-0.0028342f,0.127503f},{-0.296982f,-0.00178369f,0.127503f}, -{-0.302686f,-0.00241971f,0.127503f},{-0.304042f,-0.000484912f,0.127503f},{-0.30371f,-0.00139723f,0.127503f}, -{-0.30343f,-0.00179629f,0.127503f},{-0.303916f,-0.000955369f,0.127503f},{-0.303085f,-0.00214016f,0.127503f}, -{-0.302245f,-0.00262702f,0.127503f},{-0.301774f,-0.00275405f,0.127503f},{-0.301289f,-0.00279661f,0.127503f}, -{-0.300333f,-0.0026284f,0.127503f},{-0.300803f,-0.00275426f,0.127503f},{-0.299894f,-0.00241949f,0.127503f}, -{-0.298533f,-0.000485989f,0.127503f},{-0.299499f,-0.00213198f,0.127503f},{-0.29866f,-0.000957231f,0.127503f}, -{-0.298866f,-0.00139896f,0.127503f},{-0.299145f,-0.0018009f,0.127503f},{-0.304044f,-0.000485989f,0.13496f}, -{-0.303917f,-0.000957231f,0.13496f},{-0.303711f,-0.00139896f,0.13496f},{-0.303432f,-0.0018009f,0.13496f}, -{-0.303078f,-0.00213198f,0.13496f},{-0.302684f,-0.00241949f,0.13496f},{-0.302244f,-0.0026284f,0.13496f}, -{-0.301774f,-0.00275426f,0.13496f},{-0.301289f,-0.00279661f,0.13496f},{-0.300803f,-0.00275405f,0.13496f}, -{-0.299492f,-0.00214016f,0.13496f},{-0.298661f,-0.000955369f,0.13496f},{-0.300332f,-0.00262702f,0.13496f}, -{-0.299891f,-0.00241971f,0.13496f},{-0.299147f,-0.00179629f,0.13496f},{-0.298867f,-0.00139723f,0.13496f}, -{-0.298535f,-0.000484912f,0.13496f},{-2.55212e-017f,0.304085f,0.127503f},{-2.89175e-017f,0.304085f,0.13496f}, -{0.000488516f,0.304042f,0.13496f},{0.000957717f,0.303916f,0.13496f},{0.00048723f,0.304042f,0.127503f}, -{0.000956449f,0.303917f,0.127503f},{0.00139564f,0.303712f,0.127503f},{0.00179504f,0.303433f,0.127503f}, -{0.00139727f,0.303711f,0.13496f},{0.00179767f,0.303431f,0.13496f},{0.00214219f,0.303086f,0.127503f}, -{0.00214411f,0.303084f,0.13496f},{0.00242266f,0.302686f,0.127503f},{0.00262748f,0.302246f,0.127503f}, -{0.00242333f,0.302684f,0.13496f},{0.00262801f,0.302245f,0.13496f},{0.00275356f,0.301777f,0.127503f}, -{0.00275356f,0.301777f,0.13496f},{0.00279661f,0.301289f,0.13496f},{0.00279661f,0.301289f,0.127503f}, -{-0.000488516f,0.304042f,0.127503f},{-0.000957717f,0.303916f,0.127503f},{-0.00048723f,0.304042f,0.13496f}, -{-0.00139564f,0.303712f,0.13496f},{-0.000956449f,0.303917f,0.13496f},{-0.00139727f,0.303711f,0.127503f}, -{-0.00179504f,0.303433f,0.13496f},{-0.00179767f,0.303431f,0.127503f},{-0.00214219f,0.303086f,0.13496f}, -{-0.00242266f,0.302686f,0.13496f},{-0.00214411f,0.303084f,0.127503f},{-0.00242333f,0.302684f,0.127503f}, -{-0.00262748f,0.302246f,0.13496f},{-0.00262801f,0.302245f,0.127503f},{-0.00275356f,0.301777f,0.13496f}, -{-0.00275356f,0.301777f,0.127503f},{-0.00279661f,0.301289f,0.127503f},{-0.00279661f,0.301289f,0.13496f}, -{-3.14626e-017f,0.30595f,0.125638f},{-2.85648e-017f,0.30595f,0.127503f},{0.000612842f,0.305909f,0.127503f}, -{0.00120978f,0.30579f,0.127503f},{0.000612502f,0.305909f,0.125638f},{0.00178369f,0.305595f,0.127503f}, -{0.00120944f,0.30579f,0.125638f},{0.00178369f,0.305595f,0.125638f},{0.00232777f,0.305327f,0.127503f}, -{0.0028342f,0.304989f,0.127503f},{0.00232743f,0.305327f,0.125638f},{0.00329584f,0.304584f,0.127503f}, -{0.00283386f,0.304989f,0.125638f},{0.00329584f,0.304584f,0.125638f},{0.00370055f,0.304122f,0.127503f}, -{0.00403832f,0.303616f,0.127503f},{0.00370041f,0.304123f,0.125638f},{0.00430621f,0.303072f,0.127503f}, -{0.00403818f,0.303616f,0.125638f},{0.00450127f,0.302498f,0.125638f},{0.00430621f,0.303072f,0.125638f}, -{0.00450141f,0.302498f,0.127503f},{0.00462052f,0.301901f,0.125638f},{0.00462066f,0.301901f,0.127503f}, -{0.00466102f,0.301289f,0.125638f},{0.00466102f,0.301289f,0.127503f},{-0.000612842f,0.305909f,0.125638f}, -{-0.00120978f,0.30579f,0.125638f},{-0.000612502f,0.305909f,0.127503f},{-0.00120944f,0.30579f,0.127503f}, -{-0.00178369f,0.305595f,0.125638f},{-0.00232777f,0.305327f,0.125638f},{-0.00178369f,0.305595f,0.127503f}, -{-0.0028342f,0.304989f,0.125638f},{-0.00232743f,0.305327f,0.127503f},{-0.00283386f,0.304989f,0.127503f}, -{-0.00329584f,0.304584f,0.125638f},{-0.00370055f,0.304122f,0.125638f},{-0.00329584f,0.304584f,0.127503f}, -{-0.00403832f,0.303616f,0.125638f},{-0.00370041f,0.304123f,0.127503f},{-0.00403818f,0.303616f,0.127503f}, -{-0.00430621f,0.303072f,0.125638f},{-0.00450127f,0.302498f,0.127503f},{-0.00430621f,0.303072f,0.127503f}, -{-0.00450141f,0.302498f,0.125638f},{-0.00462052f,0.301901f,0.127503f},{-0.00466102f,0.301289f,0.127503f}, -{-0.00462066f,0.301901f,0.125638f},{-0.00466102f,0.301289f,0.125638f},{0.00295812f,0.292456f,0.125638f}, -{0.00315337f,0.292119f,0.125638f},{0.00315227f,0.29212f,0.121909f},{0.00295749f,0.292458f,0.121909f}, -{0.0028374f,0.292827f,0.125638f},{0.00283721f,0.292829f,0.121909f},{0.00279657f,0.293216f,0.121909f}, -{0.00283728f,0.293602f,0.125638f},{0.00279668f,0.293215f,0.125638f},{0.0028377f,0.293604f,0.121909f}, -{0.00295753f,0.293973f,0.125638f},{0.00295825f,0.293975f,0.121909f},{0.0031524f,0.294311f,0.125638f}, -{0.00315303f,0.294312f,0.121909f},{0.0034126f,0.2946f,0.125638f},{0.0034133f,0.294601f,0.121909f}, -{0.00372882f,0.29483f,0.121909f},{0.00372882f,0.29483f,0.125638f},{0.00341302f,0.29183f,0.121909f}, -{0.00372824f,0.291601f,0.121909f},{0.0034143f,0.291829f,0.125638f},{0.00372908f,0.291601f,0.125638f}, -{0.00408362f,0.291443f,0.121909f},{0.00408596f,0.291442f,0.125638f},{0.00446544f,0.291361f,0.121909f}, -{0.00485544f,0.291361f,0.121909f},{0.00446705f,0.291361f,0.125638f},{0.00485646f,0.291361f,0.125638f}, -{0.00523587f,0.291442f,0.121909f},{0.00523689f,0.291442f,0.125638f},{0.00559323f,0.291601f,0.121909f}, -{0.00559323f,0.291601f,0.125638f},{0.00794301f,0.293145f,0.125638f},{0.00822403f,0.29266f,0.125638f}, -{0.00822143f,0.292663f,0.121909f},{0.00773834f,0.293667f,0.125638f},{0.00794151f,0.293149f,0.121909f}, -{0.00773817f,0.293668f,0.121909f},{0.00761523f,0.294207f,0.125638f},{0.00761511f,0.294208f,0.121909f}, -{0.00757342f,0.294761f,0.121909f},{0.00757373f,0.294759f,0.125638f},{0.00761488f,0.295314f,0.125638f}, -{0.00794445f,0.296384f,0.121909f},{0.00822146f,0.296864f,0.125638f},{0.00794412f,0.296384f,0.125638f}, -{0.00761534f,0.295319f,0.121909f},{0.00773918f,0.295862f,0.125638f},{0.00774028f,0.295864f,0.121909f}, -{0.00822277f,0.296865f,0.121909f},{0.00856678f,0.297297f,0.125638f},{0.00856839f,0.297299f,0.121909f}, -{0.00897424f,0.297676f,0.121909f},{0.00943797f,0.297992f,0.125638f},{0.00897424f,0.297676f,0.125638f}, -{0.00943797f,0.297992f,0.121909f},{0.00857075f,0.292225f,0.121909f},{0.00897738f,0.291848f,0.121909f}, -{0.00857178f,0.292224f,0.125638f},{0.00897811f,0.291847f,0.125638f},{0.00943459f,0.291536f,0.121909f}, -{0.00943645f,0.291535f,0.125638f},{0.00993607f,0.291294f,0.121909f},{0.0104724f,0.291128f,0.121909f}, -{0.00994001f,0.291292f,0.125638f},{0.0104751f,0.291128f,0.125638f},{0.0110266f,0.291045f,0.121909f}, -{0.0110274f,0.291044f,0.125638f},{0.0115811f,0.291045f,0.121909f},{0.0121288f,0.291127f,0.121909f}, -{0.0115832f,0.291045f,0.125638f},{0.0121315f,0.291128f,0.125638f},{0.0126606f,0.291291f,0.121909f}, -{0.0126606f,0.291291f,0.125638f},{0.0131668f,0.291534f,0.121909f},{0.0131668f,0.291534f,0.125638f}, -{-0.00616977f,0.294311f,0.125638f},{-0.00636455f,0.293973f,0.125638f},{-0.00636392f,0.293974f,0.121909f}, -{-0.00616867f,0.294312f,0.121909f},{-0.00590902f,0.294601f,0.125638f},{-0.00590775f,0.294602f,0.121909f}, -{-0.00559297f,0.29483f,0.121909f},{-0.00523843f,0.294988f,0.125638f},{-0.00559381f,0.29483f,0.125638f}, -{-0.00523609f,0.294989f,0.121909f},{-0.00485661f,0.29507f,0.125638f},{-0.00485499f,0.29507f,0.121909f}, -{-0.0044666f,0.29507f,0.125638f},{-0.00446558f,0.29507f,0.121909f},{-0.00408618f,0.294989f,0.125638f}, -{-0.00408515f,0.294989f,0.121909f},{-0.00372882f,0.29483f,0.121909f},{-0.00372882f,0.29483f,0.125638f}, -{-0.00648464f,0.293604f,0.121909f},{-0.00652537f,0.293216f,0.121909f},{-0.00648484f,0.293602f,0.125638f}, -{-0.00652548f,0.293215f,0.125638f},{-0.00648477f,0.292829f,0.121909f},{-0.00648435f,0.292827f,0.125638f}, -{-0.00636452f,0.292458f,0.121909f},{-0.00616965f,0.29212f,0.121909f},{-0.0063638f,0.292456f,0.125638f}, -{-0.00616901f,0.292119f,0.125638f},{-0.00590945f,0.291831f,0.121909f},{-0.00590875f,0.29183f,0.125638f}, -{-0.00559323f,0.291601f,0.121909f},{-0.00559323f,0.291601f,0.125638f},{-0.00308095f,0.290338f,0.125638f}, -{-0.00336087f,0.289852f,0.125638f},{-0.00335937f,0.289856f,0.121909f},{-0.00273163f,0.290776f,0.125638f}, -{-0.00307835f,0.290341f,0.121909f},{-0.0027306f,0.290777f,0.121909f},{-0.002325f,0.291153f,0.125638f}, -{-0.00232427f,0.291153f,0.121909f},{-0.00186593f,0.291466f,0.121909f},{-0.00186779f,0.291465f,0.125638f}, -{-0.00136631f,0.291707f,0.125638f},{-0.000274996f,0.291956f,0.121909f},{0.0002787f,0.291956f,0.125638f}, -{-0.000275788f,0.291956f,0.125638f},{-0.00136237f,0.291709f,0.121909f},{-0.000829945f,0.291873f,0.125638f}, -{-0.000827251f,0.291873f,0.121909f},{0.000280844f,0.291956f,0.121909f},{0.000826454f,0.291874f,0.125638f}, -{0.000829073f,0.291873f,0.121909f},{0.00135821f,0.29171f,0.121909f},{0.00186441f,0.291467f,0.125638f}, -{0.00135821f,0.29171f,0.125638f},{0.00186441f,0.291467f,0.121909f},{-0.00356405f,0.289334f,0.121909f}, -{-0.00368715f,0.288794f,0.121909f},{-0.00356421f,0.289333f,0.125638f},{-0.00368727f,0.288793f,0.125638f}, -{-0.00372865f,0.288242f,0.121909f},{-0.00372896f,0.288239f,0.125638f},{-0.00368751f,0.287686f,0.121909f}, -{-0.0035632f,0.287139f,0.121909f},{-0.00368704f,0.287682f,0.125638f},{-0.0035621f,0.287136f,0.125638f}, -{-0.00335826f,0.286617f,0.121909f},{-0.00335794f,0.286617f,0.125638f},{-0.00308092f,0.286137f,0.121909f}, -{-0.0027356f,0.285704f,0.121909f},{-0.00307961f,0.286135f,0.125638f},{-0.00273399f,0.285702f,0.125638f}, -{-0.00232814f,0.285325f,0.121909f},{-0.00232814f,0.285325f,0.125638f},{-0.00186441f,0.285008f,0.121909f}, -{-0.00186441f,0.285008f,0.125638f},{-0.0091279f,0.303143f,0.125638f},{-0.00951793f,0.303143f,0.125638f}, -{-0.0095162f,0.303143f,0.121909f},{-0.00912617f,0.303143f,0.121909f},{-0.00874642f,0.303062f,0.125638f}, -{-0.00874495f,0.303061f,0.121909f},{-0.00838954f,0.302903f,0.121909f},{-0.0080757f,0.302675f,0.125638f}, -{-0.00839049f,0.302903f,0.125638f},{-0.00807379f,0.302673f,0.121909f},{-0.00781413f,0.302385f,0.125638f}, -{-0.00781324f,0.302384f,0.121909f},{-0.007619f,0.302047f,0.125638f},{-0.00761862f,0.302046f,0.121909f}, -{-0.00749878f,0.301677f,0.125638f},{-0.00749845f,0.301676f,0.121909f},{-0.00745764f,0.301289f,0.121909f}, -{-0.00745764f,0.301289f,0.125638f},{-0.00989767f,0.303062f,0.121909f},{-0.0102536f,0.302903f,0.121909f}, -{-0.00989914f,0.303061f,0.125638f},{-0.0102546f,0.302903f,0.125638f},{-0.0105684f,0.302675f,0.121909f}, -{-0.0105703f,0.302673f,0.125638f},{-0.01083f,0.302385f,0.121909f},{-0.0110251f,0.302047f,0.121909f}, -{-0.0108309f,0.302384f,0.125638f},{-0.0110255f,0.302046f,0.125638f},{-0.0111453f,0.301677f,0.121909f}, -{-0.0111456f,0.301676f,0.125638f},{-0.0111865f,0.301289f,0.121909f},{-0.0111865f,0.301289f,0.125638f}, -{-0.011024f,0.298481f,0.125638f},{-0.0115849f,0.298481f,0.125638f},{-0.0115808f,0.298481f,0.121909f}, -{-0.01047f,0.298398f,0.125638f},{-0.0110199f,0.298481f,0.121909f},{-0.0104688f,0.298397f,0.121909f}, -{-0.00994023f,0.298234f,0.125638f},{-0.00993938f,0.298234f,0.121909f},{-0.00943935f,0.297993f,0.121909f}, -{-0.00944153f,0.297994f,0.125638f},{-0.00898119f,0.297681f,0.125638f},{-0.00821944f,0.296861f,0.121909f}, -{-0.00794276f,0.296381f,0.125638f},{-0.00821991f,0.296861f,0.125638f},{-0.00897771f,0.297678f,0.121909f}, -{-0.00856913f,0.297299f,0.125638f},{-0.00856753f,0.297297f,0.121909f},{-0.00794193f,0.296379f,0.121909f}, -{-0.00774033f,0.295865f,0.125638f},{-0.00773931f,0.295863f,0.121909f},{-0.00761603f,0.295323f,0.121909f}, -{-0.00757356f,0.294763f,0.125638f},{-0.00761603f,0.295323f,0.125638f},{-0.00757356f,0.294763f,0.121909f}, -{-0.0121348f,0.298398f,0.121909f},{-0.0126645f,0.298234f,0.121909f},{-0.012136f,0.298397f,0.125638f}, -{-0.0126654f,0.298234f,0.125638f},{-0.0131632f,0.297994f,0.121909f},{-0.0131654f,0.297993f,0.125638f}, -{-0.0136236f,0.297681f,0.121909f},{-0.0140356f,0.297299f,0.121909f},{-0.0136271f,0.297678f,0.125638f}, -{-0.0140372f,0.297297f,0.125638f},{-0.0143849f,0.296861f,0.121909f},{-0.0143853f,0.296861f,0.125638f}, -{-0.014662f,0.296381f,0.121909f},{-0.0148644f,0.295865f,0.121909f},{-0.0146628f,0.296379f,0.125638f}, -{-0.0148654f,0.295863f,0.125638f},{-0.0149887f,0.295323f,0.121909f},{-0.0149887f,0.295323f,0.125638f}, -{-0.0150312f,0.294763f,0.121909f},{-0.0150312f,0.294763f,0.125638f},{-0.00295812f,0.310121f,0.125638f}, -{-0.00315337f,0.310458f,0.125638f},{-0.00315227f,0.310457f,0.121909f},{-0.00295749f,0.310119f,0.121909f}, -{-0.0028374f,0.30975f,0.125638f},{-0.00283721f,0.309748f,0.121909f},{-0.00279657f,0.309361f,0.121909f}, -{-0.00283728f,0.308975f,0.125638f},{-0.00279668f,0.309362f,0.125638f},{-0.0028377f,0.308973f,0.121909f}, -{-0.00295753f,0.308604f,0.125638f},{-0.00295825f,0.308603f,0.121909f},{-0.0031524f,0.308266f,0.125638f}, -{-0.00315303f,0.308265f,0.121909f},{-0.0034126f,0.307977f,0.125638f},{-0.0034133f,0.307976f,0.121909f}, -{-0.00372882f,0.307747f,0.121909f},{-0.00372882f,0.307747f,0.125638f},{-0.00341302f,0.310747f,0.121909f}, -{-0.00372824f,0.310976f,0.121909f},{-0.0034143f,0.310748f,0.125638f},{-0.00372908f,0.310977f,0.125638f}, -{-0.00408362f,0.311134f,0.121909f},{-0.00408596f,0.311135f,0.125638f},{-0.00446544f,0.311216f,0.121909f}, -{-0.00485544f,0.311216f,0.121909f},{-0.00446705f,0.311216f,0.125638f},{-0.00485646f,0.311216f,0.125638f}, -{-0.00523587f,0.311135f,0.121909f},{-0.00523689f,0.311135f,0.125638f},{-0.00559323f,0.310976f,0.121909f}, -{-0.00559323f,0.310976f,0.125638f},{-0.00794301f,0.309432f,0.125638f},{-0.00822403f,0.309917f,0.125638f}, -{-0.00822143f,0.309914f,0.121909f},{-0.00773834f,0.30891f,0.125638f},{-0.00794151f,0.309428f,0.121909f}, -{-0.00773817f,0.308909f,0.121909f},{-0.00761523f,0.30837f,0.125638f},{-0.00761511f,0.308369f,0.121909f}, -{-0.00757342f,0.307816f,0.121909f},{-0.00757373f,0.307818f,0.125638f},{-0.00761488f,0.307263f,0.125638f}, -{-0.00794445f,0.306193f,0.121909f},{-0.00822146f,0.305713f,0.125638f},{-0.00794412f,0.306194f,0.125638f}, -{-0.00761534f,0.307258f,0.121909f},{-0.00773918f,0.306715f,0.125638f},{-0.00774028f,0.306713f,0.121909f}, -{-0.00822277f,0.305712f,0.121909f},{-0.00856678f,0.30528f,0.125638f},{-0.00856839f,0.305278f,0.121909f}, -{-0.00897424f,0.304902f,0.121909f},{-0.00943797f,0.304585f,0.125638f},{-0.00897424f,0.304902f,0.125638f}, -{-0.00943797f,0.304585f,0.121909f},{-0.00857075f,0.310352f,0.121909f},{-0.00897738f,0.310729f,0.121909f}, -{-0.00857178f,0.310353f,0.125638f},{-0.00897811f,0.31073f,0.125638f},{-0.00943459f,0.311041f,0.121909f}, -{-0.00943645f,0.311043f,0.125638f},{-0.00993607f,0.311283f,0.121909f},{-0.0104724f,0.311449f,0.121909f}, -{-0.00994001f,0.311285f,0.125638f},{-0.0104751f,0.31145f,0.125638f},{-0.0110266f,0.311533f,0.121909f}, -{-0.0110274f,0.311533f,0.125638f},{-0.0115811f,0.311532f,0.121909f},{-0.0121288f,0.31145f,0.121909f}, -{-0.0115832f,0.311532f,0.125638f},{-0.0121315f,0.31145f,0.125638f},{-0.0126606f,0.311286f,0.121909f}, -{-0.0126606f,0.311286f,0.125638f},{-0.0131668f,0.311043f,0.121909f},{-0.0131668f,0.311043f,0.125638f}, -{0.00616977f,0.308266f,0.125638f},{0.00636455f,0.308604f,0.125638f},{0.00636392f,0.308603f,0.121909f}, -{0.00616867f,0.308265f,0.121909f},{0.00590902f,0.307976f,0.125638f},{0.00590775f,0.307976f,0.121909f}, -{0.00559297f,0.307747f,0.121909f},{0.00523843f,0.307589f,0.125638f},{0.00559381f,0.307747f,0.125638f}, -{0.00523609f,0.307588f,0.121909f},{0.00485661f,0.307508f,0.125638f},{0.00485499f,0.307507f,0.121909f}, -{0.0044666f,0.307507f,0.125638f},{0.00446558f,0.307508f,0.121909f},{0.00408618f,0.307588f,0.125638f}, -{0.00408515f,0.307588f,0.121909f},{0.00372882f,0.307747f,0.121909f},{0.00372882f,0.307747f,0.125638f}, -{0.00648464f,0.308973f,0.121909f},{0.00652537f,0.309361f,0.121909f},{0.00648484f,0.308975f,0.125638f}, -{0.00652548f,0.309362f,0.125638f},{0.00648477f,0.309748f,0.121909f},{0.00648435f,0.30975f,0.125638f}, -{0.00636452f,0.310119f,0.121909f},{0.00616965f,0.310457f,0.121909f},{0.0063638f,0.310121f,0.125638f}, -{0.00616901f,0.310458f,0.125638f},{0.00590945f,0.310746f,0.121909f},{0.00590875f,0.310747f,0.125638f}, -{0.00559323f,0.310976f,0.121909f},{0.00559323f,0.310976f,0.125638f},{0.00308095f,0.312239f,0.125638f}, -{0.00336087f,0.312725f,0.125638f},{0.00335937f,0.312721f,0.121909f},{0.00273163f,0.311801f,0.125638f}, -{0.00307835f,0.312236f,0.121909f},{0.0027306f,0.3118f,0.121909f},{0.002325f,0.311424f,0.125638f}, -{0.00232427f,0.311424f,0.121909f},{0.00186593f,0.311111f,0.121909f},{0.00186779f,0.311112f,0.125638f}, -{0.00136631f,0.31087f,0.125638f},{0.000274996f,0.310621f,0.121909f},{-0.0002787f,0.310621f,0.125638f}, -{0.000275788f,0.310621f,0.125638f},{0.00136237f,0.310869f,0.121909f},{0.000829945f,0.310704f,0.125638f}, -{0.000827251f,0.310704f,0.121909f},{-0.000280844f,0.310621f,0.121909f},{-0.000826454f,0.310703f,0.125638f}, -{-0.000829073f,0.310704f,0.121909f},{-0.00135821f,0.310867f,0.121909f},{-0.00186441f,0.31111f,0.125638f}, -{-0.00135821f,0.310867f,0.125638f},{-0.00186441f,0.31111f,0.121909f},{0.00356405f,0.313243f,0.121909f}, -{0.00368715f,0.313783f,0.121909f},{0.00356421f,0.313244f,0.125638f},{0.00368727f,0.313784f,0.125638f}, -{0.00372865f,0.314335f,0.121909f},{0.00372896f,0.314338f,0.125638f},{0.00368751f,0.314891f,0.121909f}, -{0.0035632f,0.315438f,0.121909f},{0.00368704f,0.314895f,0.125638f},{0.0035621f,0.315441f,0.125638f}, -{0.00335826f,0.31596f,0.121909f},{0.00335794f,0.315961f,0.125638f},{0.00308092f,0.31644f,0.121909f}, -{0.0027356f,0.316873f,0.121909f},{0.00307961f,0.316442f,0.125638f},{0.00273399f,0.316875f,0.125638f}, -{0.00232814f,0.317252f,0.121909f},{0.00232814f,0.317252f,0.125638f},{0.00186441f,0.317569f,0.121909f}, -{0.00186441f,0.317569f,0.125638f},{0.0091279f,0.299434f,0.125638f},{0.00951793f,0.299435f,0.125638f}, -{0.0095162f,0.299434f,0.121909f},{0.00912617f,0.299435f,0.121909f},{0.00874642f,0.299515f,0.125638f}, -{0.00874495f,0.299516f,0.121909f},{0.00838954f,0.299674f,0.121909f},{0.0080757f,0.299902f,0.125638f}, -{0.00839049f,0.299674f,0.125638f},{0.00807379f,0.299904f,0.121909f},{0.00781413f,0.300192f,0.125638f}, -{0.00781324f,0.300193f,0.121909f},{0.007619f,0.30053f,0.125638f},{0.00761862f,0.300531f,0.121909f}, -{0.00749878f,0.3009f,0.125638f},{0.00749845f,0.300901f,0.121909f},{0.00745764f,0.301289f,0.121909f}, -{0.00745764f,0.301289f,0.125638f},{0.00989767f,0.299515f,0.121909f},{0.0102536f,0.299674f,0.121909f}, -{0.00989914f,0.299516f,0.125638f},{0.0102546f,0.299674f,0.125638f},{0.0105684f,0.299902f,0.121909f}, -{0.0105703f,0.299904f,0.125638f},{0.01083f,0.300192f,0.121909f},{0.0110251f,0.30053f,0.121909f}, -{0.0108309f,0.300193f,0.125638f},{0.0110255f,0.300531f,0.125638f},{0.0111453f,0.3009f,0.121909f}, -{0.0111456f,0.300901f,0.125638f},{0.0111865f,0.301289f,0.121909f},{0.0111865f,0.301289f,0.125638f}, -{0.011024f,0.304096f,0.125638f},{0.0115849f,0.304096f,0.125638f},{0.0115808f,0.304096f,0.121909f}, -{0.01047f,0.304179f,0.125638f},{0.0110199f,0.304096f,0.121909f},{0.0104688f,0.30418f,0.121909f}, -{0.00994023f,0.304343f,0.125638f},{0.00993938f,0.304343f,0.121909f},{0.00943935f,0.304584f,0.121909f}, -{0.00944153f,0.304583f,0.125638f},{0.00898119f,0.304896f,0.125638f},{0.00821944f,0.305716f,0.121909f}, -{0.00794276f,0.306196f,0.125638f},{0.00821991f,0.305716f,0.125638f},{0.00897771f,0.304899f,0.121909f}, -{0.00856913f,0.305278f,0.125638f},{0.00856753f,0.30528f,0.121909f},{0.00794193f,0.306198f,0.121909f}, -{0.00774033f,0.306712f,0.125638f},{0.00773931f,0.306714f,0.121909f},{0.00761603f,0.307254f,0.121909f}, -{0.00757356f,0.307814f,0.125638f},{0.00761603f,0.307254f,0.125638f},{0.00757356f,0.307814f,0.121909f}, -{0.0121348f,0.304179f,0.121909f},{0.0126645f,0.304343f,0.121909f},{0.012136f,0.30418f,0.125638f}, -{0.0126654f,0.304343f,0.125638f},{0.0131632f,0.304583f,0.121909f},{0.0131654f,0.304584f,0.125638f}, -{0.0136236f,0.304896f,0.121909f},{0.0140356f,0.305278f,0.121909f},{0.0136271f,0.304899f,0.125638f}, -{0.0140372f,0.30528f,0.125638f},{0.0143849f,0.305716f,0.121909f},{0.0143853f,0.305716f,0.125638f}, -{0.014662f,0.306196f,0.121909f},{0.0148644f,0.306712f,0.121909f},{0.0146628f,0.306198f,0.125638f}, -{0.0148654f,0.306714f,0.125638f},{0.0149887f,0.307254f,0.121909f},{0.0149887f,0.307254f,0.125638f}, -{0.0150312f,0.307814f,0.121909f},{0.0150312f,0.307814f,0.125638f},{-2.74685e-017f,0.304085f,0.100469f}, -{-2.69701e-017f,0.304085f,0.0986044f},{-0.000488516f,0.304042f,0.0986044f},{-0.000957717f,0.303916f,0.0986044f}, -{-0.00048723f,0.304042f,0.100469f},{-0.000956449f,0.303917f,0.100469f},{-0.00139564f,0.303712f,0.100469f}, -{-0.00179504f,0.303433f,0.100469f},{-0.00139727f,0.303711f,0.0986044f},{-0.00179767f,0.303431f,0.0986044f}, -{-0.00214219f,0.303086f,0.100469f},{-0.00214411f,0.303084f,0.0986044f},{-0.00242266f,0.302686f,0.100469f}, -{-0.00262748f,0.302246f,0.100469f},{-0.00242333f,0.302684f,0.0986044f},{-0.00262801f,0.302245f,0.0986044f}, -{-0.00275356f,0.301777f,0.100469f},{-0.00275356f,0.301777f,0.0986044f},{-0.00279661f,0.301289f,0.0986044f}, -{-0.00279661f,0.301289f,0.100469f},{0.000488516f,0.304042f,0.100469f},{0.000957717f,0.303916f,0.100469f}, -{0.00048723f,0.304042f,0.0986044f},{0.00139564f,0.303712f,0.0986044f},{0.000956449f,0.303917f,0.0986044f}, -{0.00139727f,0.303711f,0.100469f},{0.00179504f,0.303433f,0.0986044f},{0.00179767f,0.303431f,0.100469f}, -{0.00214219f,0.303086f,0.0986044f},{0.00242266f,0.302686f,0.0986044f},{0.00214411f,0.303084f,0.100469f}, -{0.00242333f,0.302684f,0.100469f},{0.00262748f,0.302246f,0.0986044f},{0.00262801f,0.302245f,0.100469f}, -{0.00275356f,0.301777f,0.0986044f},{0.00275356f,0.301777f,0.100469f},{0.00279661f,0.301289f,0.100469f}, -{0.00279661f,0.301289f,0.0986044f},{-3.06347e-017f,0.308746f,0.100469f},{-0.000737081f,0.30871f,0.100469f}, -{-2.81508e-017f,0.308746f,0.101401f},{-0.000737081f,0.30871f,0.101401f},{-0.00146169f,0.308602f,0.100469f}, -{-0.00216893f,0.308424f,0.100469f},{-0.00146169f,0.308602f,0.101401f},{-0.00285391f,0.308178f,0.100469f}, -{-0.00216893f,0.308424f,0.101401f},{-0.00285391f,0.308178f,0.101401f},{-0.00351173f,0.307868f,0.100469f}, -{-0.00413751f,0.307493f,0.100469f},{-0.00351173f,0.307868f,0.101401f},{-0.00472635f,0.307057f,0.100469f}, -{-0.00413751f,0.307493f,0.101401f},{-0.00472635f,0.307057f,0.101401f},{-0.00527335f,0.306562f,0.100469f}, -{-0.00576874f,0.306015f,0.100469f},{-0.00527335f,0.306562f,0.101401f},{-0.00620465f,0.305426f,0.100469f}, -{-0.00576874f,0.306015f,0.101401f},{-0.00620465f,0.305426f,0.101401f},{-0.00657906f,0.3048f,0.100469f}, -{-0.00688994f,0.304142f,0.100469f},{-0.00657906f,0.3048f,0.101401f},{-0.00713527f,0.303457f,0.100469f}, -{-0.00688994f,0.304142f,0.101401f},{-0.00713527f,0.303457f,0.101401f},{-0.00731301f,0.30275f,0.100469f}, -{-0.00742114f,0.302026f,0.100469f},{-0.00731301f,0.30275f,0.101401f},{-0.00745764f,0.301289f,0.100469f}, -{-0.00742114f,0.302026f,0.101401f},{-0.00745764f,0.301289f,0.101401f},{0.000737081f,0.30871f,0.101401f}, -{0.00146169f,0.308602f,0.101401f},{0.000737081f,0.30871f,0.100469f},{0.00216893f,0.308424f,0.101401f}, -{0.00146169f,0.308602f,0.100469f},{0.00216893f,0.308424f,0.100469f},{0.00285391f,0.308178f,0.101401f}, -{0.00351173f,0.307868f,0.101401f},{0.00285391f,0.308178f,0.100469f},{0.00413751f,0.307493f,0.101401f}, -{0.00351173f,0.307868f,0.100469f},{0.00413751f,0.307493f,0.100469f},{0.00472635f,0.307057f,0.101401f}, -{0.00527335f,0.306562f,0.101401f},{0.00472635f,0.307057f,0.100469f},{0.00576874f,0.306015f,0.101401f}, -{0.00527335f,0.306562f,0.100469f},{0.00576874f,0.306015f,0.100469f},{0.00620465f,0.305426f,0.101401f}, -{0.00657906f,0.3048f,0.101401f},{0.00620465f,0.305426f,0.100469f},{0.00688994f,0.304142f,0.101401f}, -{0.00657906f,0.3048f,0.100469f},{0.00688994f,0.304142f,0.100469f},{0.00713527f,0.303457f,0.101401f}, -{0.00731301f,0.30275f,0.101401f},{0.00713527f,0.303457f,0.100469f},{0.00742114f,0.302026f,0.101401f}, -{0.00731301f,0.30275f,0.100469f},{0.00742114f,0.302026f,0.100469f},{0.00745764f,0.301289f,0.101401f}, -{0.00745764f,0.301289f,0.100469f},{-0.00462052f,0.318681f,0.101401f},{-0.00462066f,0.318681f,0.104198f}, -{-0.00466102f,0.318068f,0.101401f},{-0.00462052f,0.317455f,0.104198f},{-0.00462066f,0.317456f,0.101401f}, -{-0.00466102f,0.318068f,0.104198f},{-0.00430621f,0.316285f,0.101401f},{-0.00430621f,0.316285f,0.104198f}, -{-0.00403832f,0.315741f,0.101401f},{-0.00450127f,0.316858f,0.104198f},{-0.00450141f,0.316859f,0.101401f}, -{-0.00403818f,0.31574f,0.104198f},{-0.00370041f,0.315234f,0.104198f},{-0.00370055f,0.315234f,0.101401f}, -{-0.00329584f,0.314772f,0.101401f},{-0.00329584f,0.314772f,0.104198f},{-0.00283386f,0.314368f,0.104198f}, -{-0.0028342f,0.314368f,0.101401f},{-0.00232777f,0.31403f,0.101401f},{-0.00232743f,0.31403f,0.104198f}, -{-0.00178369f,0.313762f,0.101401f},{-0.00178369f,0.313762f,0.104198f},{-0.00120944f,0.313567f,0.104198f}, -{-0.00120978f,0.313567f,0.101401f},{-2.25564e-017f,0.313407f,0.101401f},{-0.000612842f,0.313448f,0.101401f}, -{-0.000612502f,0.313448f,0.104198f},{-2.25564e-017f,0.313407f,0.104198f},{-0.00450141f,0.319278f,0.104198f}, -{-0.00450127f,0.319278f,0.101401f},{-0.00430621f,0.319852f,0.104198f},{-0.00403832f,0.320396f,0.104198f}, -{-0.00430621f,0.319852f,0.101401f},{-0.00403818f,0.320396f,0.101401f},{-0.00370055f,0.320902f,0.104198f}, -{-0.00370041f,0.320902f,0.101401f},{-0.00329584f,0.321364f,0.104198f},{-0.0028342f,0.321769f,0.104198f}, -{-0.00329584f,0.321364f,0.101401f},{-0.00283386f,0.321769f,0.101401f},{-0.00232777f,0.322106f,0.104198f}, -{-0.00232743f,0.322107f,0.101401f},{-0.00178369f,0.322374f,0.104198f},{-0.00120978f,0.322569f,0.104198f}, -{-0.00178369f,0.322374f,0.101401f},{-0.00120944f,0.32257f,0.101401f},{-0.000612842f,0.322689f,0.104198f}, -{-0.000612502f,0.322689f,0.101401f},{-2.3698e-017f,0.322729f,0.104198f},{-2.3698e-017f,0.322729f,0.101401f}, -{0.0173922f,0.305909f,0.101401f},{0.0167797f,0.30595f,0.101401f},{0.0173922f,0.305909f,0.104198f}, -{0.0161668f,0.305909f,0.104198f},{0.0167797f,0.30595f,0.104198f},{0.0161668f,0.305909f,0.101401f}, -{0.014996f,0.305595f,0.101401f},{0.0144519f,0.305327f,0.101401f},{0.014996f,0.305595f,0.104198f}, -{0.0155699f,0.30579f,0.104198f},{0.0155699f,0.30579f,0.101401f},{0.0144519f,0.305327f,0.104198f}, -{0.0139455f,0.304989f,0.101401f},{0.0139455f,0.304989f,0.104198f},{0.0134838f,0.304584f,0.101401f}, -{0.0134838f,0.304584f,0.104198f},{0.0130791f,0.304122f,0.101401f},{0.0130791f,0.304122f,0.104198f}, -{0.0127414f,0.303616f,0.101401f},{0.0124735f,0.303072f,0.101401f},{0.0127414f,0.303616f,0.104198f}, -{0.0124735f,0.303072f,0.104198f},{0.0122783f,0.302498f,0.101401f},{0.0122783f,0.302498f,0.104198f}, -{0.0121187f,0.301289f,0.101401f},{0.012159f,0.301901f,0.104198f},{0.012159f,0.301901f,0.101401f}, -{0.0121187f,0.301289f,0.104198f},{0.0179891f,0.30579f,0.104198f},{0.0185634f,0.305595f,0.104198f}, -{0.0179891f,0.30579f,0.101401f},{0.0191071f,0.305327f,0.104198f},{0.0185634f,0.305595f,0.101401f}, -{0.0191071f,0.305327f,0.101401f},{0.0196135f,0.304989f,0.104198f},{0.0200755f,0.304584f,0.104198f}, -{0.0196135f,0.304989f,0.101401f},{0.0204801f,0.304123f,0.104198f},{0.0200755f,0.304584f,0.101401f}, -{0.0204801f,0.304123f,0.101401f},{0.0208179f,0.303616f,0.104198f},{0.0210859f,0.303072f,0.104198f}, -{0.0208179f,0.303616f,0.101401f},{0.0212809f,0.302498f,0.104198f},{0.0210859f,0.303072f,0.101401f}, -{0.0212809f,0.302498f,0.101401f},{0.0214002f,0.301901f,0.104198f},{0.0214407f,0.301289f,0.104198f}, -{0.0214002f,0.301901f,0.101401f},{0.0214407f,0.301289f,0.101401f},{0.00462066f,0.283896f,0.104198f}, -{0.00466102f,0.284509f,0.104198f},{0.00464709f,0.284149f,0.101401f},{0.00458867f,0.285326f,0.101401f}, -{0.00465528f,0.28474f,0.101401f},{0.00462052f,0.285122f,0.104198f},{0.00430621f,0.286293f,0.104198f}, -{0.00403818f,0.286837f,0.104198f},{0.00423671f,0.286451f,0.101401f},{0.00444837f,0.2859f,0.101401f}, -{0.00450127f,0.285719f,0.104198f},{0.00370041f,0.287343f,0.104198f},{0.00361392f,0.287452f,0.101401f}, -{0.00395712f,0.286971f,0.101401f},{0.00329584f,0.287805f,0.104198f},{0.00283386f,0.288209f,0.104198f}, -{0.00276013f,0.288264f,0.101401f},{0.00321274f,0.287885f,0.101401f},{0.00232743f,0.288547f,0.104198f}, -{0.00178369f,0.288815f,0.104198f},{0.00226347f,0.288584f,0.101401f},{0.00120944f,0.28901f,0.104198f}, -{0.00116855f,0.289018f,0.101401f},{0.00172931f,0.288834f,0.101401f},{0.000589403f,0.289133f,0.101401f}, -{0.000612502f,0.28913f,0.104198f},{-2.78077e-017f,0.28917f,0.104198f},{-2.78077e-017f,0.28917f,0.101401f}, -{0.00456433f,0.283564f,0.101401f},{0.00440833f,0.282995f,0.101401f},{0.00450141f,0.283299f,0.104198f}, -{0.00430621f,0.282725f,0.104198f},{0.00418158f,0.282449f,0.101401f},{0.00388773f,0.281937f,0.101401f}, -{0.00403832f,0.282181f,0.104198f},{0.00353147f,0.281466f,0.101401f},{0.00370055f,0.281675f,0.104198f}, -{0.00329584f,0.281213f,0.104198f},{0.0031185f,0.281044f,0.101401f},{0.00265541f,0.280678f,0.101401f}, -{0.0028342f,0.280808f,0.104198f},{0.00214963f,0.280373f,0.101401f},{0.00232777f,0.280471f,0.104198f}, -{0.00178369f,0.280203f,0.104198f},{0.00160952f,0.280134f,0.101401f},{0.00104053f,0.279978f,0.101401f}, -{0.00120978f,0.280008f,0.104198f},{0.000461185f,0.279852f,0.101401f},{0.000612842f,0.279888f,0.104198f}, -{-2.66661e-017f,0.279848f,0.104198f},{-2.66661e-017f,0.279848f,0.101401f},{-0.0143886f,0.313813f,0.110723f}, -{-0.0143784f,0.313619f,0.101401f},{-0.0143782f,0.314009f,0.101401f},{-0.014297f,0.31439f,0.101401f}, -{-0.0143526f,0.314176f,0.110723f},{-0.0142471f,0.314526f,0.110723f},{-0.0139089f,0.315061f,0.101401f}, -{-0.014075f,0.314849f,0.110723f},{-0.0141387f,0.314745f,0.101401f},{-0.0136193f,0.315322f,0.101401f}, -{-0.0138429f,0.315132f,0.110723f},{-0.0135601f,0.315364f,0.110723f},{-0.013282f,0.315516f,0.101401f}, -{-0.0129121f,0.315636f,0.101401f},{-0.0132377f,0.315536f,0.110723f},{-0.0125242f,0.315677f,0.101401f}, -{-0.0125242f,0.315677f,0.110723f},{-0.0128879f,0.315642f,0.110723f},{-0.0143523f,0.313449f,0.110723f}, -{-0.0142976f,0.313237f,0.101401f},{-0.0142453f,0.313099f,0.110723f},{-0.0140726f,0.312777f,0.110723f}, -{-0.0141391f,0.312881f,0.101401f},{-0.0138409f,0.312495f,0.110723f},{-0.0139105f,0.312566f,0.101401f}, -{-0.0136206f,0.312305f,0.101401f},{-0.0135587f,0.312263f,0.110723f},{-0.0132367f,0.312091f,0.110723f}, -{-0.013283f,0.31211f,0.101401f},{-0.0128873f,0.311985f,0.110723f},{-0.0129131f,0.311989f,0.101401f}, -{-0.0125242f,0.311948f,0.101401f},{-0.0125242f,0.311948f,0.110723f},{-0.0125242f,0.313813f,0.111843f}, -{0.00868228f,0.311835f,0.110723f},{0.00869244f,0.311641f,0.101401f},{0.00869272f,0.312031f,0.101401f}, -{0.00877392f,0.312412f,0.101401f},{0.0087183f,0.312199f,0.110723f},{0.00882381f,0.312549f,0.110723f}, -{0.00916198f,0.313083f,0.101401f},{0.00899591f,0.312872f,0.110723f},{0.00893219f,0.312768f,0.101401f}, -{0.0094516f,0.313344f,0.101401f},{0.00922803f,0.313155f,0.110723f},{0.00951082f,0.313386f,0.110723f}, -{0.00978889f,0.313539f,0.101401f},{0.0101588f,0.313659f,0.101401f},{0.00983322f,0.313559f,0.110723f}, -{0.0105467f,0.3137f,0.101401f},{0.0105467f,0.3137f,0.110723f},{0.010183f,0.313665f,0.110723f}, -{0.00871859f,0.311471f,0.110723f},{0.00877329f,0.31126f,0.101401f},{0.00882557f,0.311121f,0.110723f}, -{0.00899828f,0.3108f,0.110723f},{0.00893177f,0.310904f,0.101401f},{0.00922999f,0.310517f,0.110723f}, -{0.00916039f,0.310589f,0.101401f},{0.00945026f,0.310327f,0.101401f},{0.00951221f,0.310286f,0.110723f}, -{0.00983423f,0.310114f,0.110723f},{0.00978794f,0.310132f,0.101401f},{0.0101836f,0.310007f,0.110723f}, -{0.0101578f,0.310012f,0.101401f},{0.0105467f,0.309971f,0.101401f},{0.0105467f,0.309971f,0.110723f}, -{0.0105467f,0.311835f,0.111843f},{0.0106598f,0.288764f,0.110723f},{0.0106699f,0.28857f,0.101401f}, -{0.0106702f,0.28896f,0.101401f},{0.0107514f,0.289341f,0.101401f},{0.0106958f,0.289128f,0.110723f}, -{0.0108013f,0.289478f,0.110723f},{0.0111395f,0.290013f,0.101401f},{0.0109734f,0.289801f,0.110723f}, -{0.0109097f,0.289697f,0.101401f},{0.0114291f,0.290273f,0.101401f},{0.0112055f,0.290084f,0.110723f}, -{0.0114883f,0.290316f,0.110723f},{0.0117664f,0.290468f,0.101401f},{0.0121363f,0.290588f,0.101401f}, -{0.0118107f,0.290488f,0.110723f},{0.0125242f,0.290629f,0.101401f},{0.0125242f,0.290629f,0.110723f}, -{0.0121605f,0.290594f,0.110723f},{0.0106961f,0.2884f,0.110723f},{0.0107508f,0.288189f,0.101401f}, -{0.0108031f,0.288051f,0.110723f},{0.0109758f,0.287729f,0.110723f},{0.0109093f,0.287833f,0.101401f}, -{0.0112075f,0.287446f,0.110723f},{0.0111379f,0.287518f,0.101401f},{0.0114278f,0.287256f,0.101401f}, -{0.0114897f,0.287215f,0.110723f},{0.0118117f,0.287043f,0.110723f},{0.0117654f,0.287061f,0.101401f}, -{0.0121611f,0.286936f,0.110723f},{0.0121353f,0.286941f,0.101401f},{0.0125242f,0.2869f,0.101401f}, -{0.0125242f,0.2869f,0.110723f},{0.0125242f,0.288764f,0.111843f},{-0.0124111f,0.290742f,0.110723f}, -{-0.0124009f,0.290548f,0.101401f},{-0.0124007f,0.290938f,0.101401f},{-0.0123195f,0.291319f,0.101401f}, -{-0.0123751f,0.291105f,0.110723f},{-0.0122696f,0.291456f,0.110723f},{-0.0119314f,0.29199f,0.101401f}, -{-0.0120975f,0.291778f,0.110723f},{-0.0121612f,0.291674f,0.101401f},{-0.0116418f,0.292251f,0.101401f}, -{-0.0118654f,0.292061f,0.110723f},{-0.0115826f,0.292293f,0.110723f},{-0.0113045f,0.292445f,0.101401f}, -{-0.0109346f,0.292565f,0.101401f},{-0.0112602f,0.292465f,0.110723f},{-0.0105467f,0.292606f,0.101401f}, -{-0.0105467f,0.292606f,0.110723f},{-0.0109104f,0.292571f,0.110723f},{-0.0123748f,0.290378f,0.110723f}, -{-0.0123201f,0.290166f,0.101401f},{-0.0122678f,0.290028f,0.110723f},{-0.0120951f,0.289706f,0.110723f}, -{-0.0121616f,0.28981f,0.101401f},{-0.0118634f,0.289424f,0.110723f},{-0.011933f,0.289496f,0.101401f}, -{-0.0116431f,0.289234f,0.101401f},{-0.0115812f,0.289192f,0.110723f},{-0.0112592f,0.28902f,0.110723f}, -{-0.0113054f,0.289039f,0.101401f},{-0.0109098f,0.288914f,0.110723f},{-0.0109356f,0.288919f,0.101401f}, -{-0.0105467f,0.288877f,0.101401f},{-0.0105467f,0.288877f,0.110723f},{-0.0105467f,0.290742f,0.111843f}, -{-0.0173925f,0.296668f,0.101401f},{-0.0173922f,0.296668f,0.104198f},{-0.0167797f,0.296628f,0.101401f}, -{-0.0161668f,0.296668f,0.104198f},{-0.0161672f,0.296668f,0.101401f},{-0.0167797f,0.296628f,0.104198f}, -{-0.014996f,0.296982f,0.101401f},{-0.014996f,0.296982f,0.104198f},{-0.0144523f,0.29725f,0.101401f}, -{-0.0155699f,0.296787f,0.104198f},{-0.0155702f,0.296787f,0.101401f},{-0.0144519f,0.29725f,0.104198f}, -{-0.0139455f,0.297588f,0.104198f},{-0.0139458f,0.297588f,0.101401f},{-0.0134838f,0.297993f,0.101401f}, -{-0.0134838f,0.297993f,0.104198f},{-0.0130791f,0.298455f,0.104198f},{-0.0130793f,0.298454f,0.101401f}, -{-0.0127415f,0.298961f,0.101401f},{-0.0127414f,0.298961f,0.104198f},{-0.0124735f,0.299505f,0.101401f}, -{-0.0124735f,0.299505f,0.104198f},{-0.0122783f,0.300079f,0.104198f},{-0.0122784f,0.300079f,0.101401f}, -{-0.0121187f,0.301289f,0.101401f},{-0.0121592f,0.300676f,0.101401f},{-0.012159f,0.300676f,0.104198f}, -{-0.0121187f,0.301289f,0.104198f},{-0.0179891f,0.296787f,0.104198f},{-0.0179895f,0.296787f,0.101401f}, -{-0.0185634f,0.296982f,0.104198f},{-0.0191071f,0.29725f,0.104198f},{-0.0185634f,0.296982f,0.101401f}, -{-0.0191075f,0.29725f,0.101401f},{-0.0196135f,0.297588f,0.104198f},{-0.0196139f,0.297588f,0.101401f}, -{-0.0200755f,0.297993f,0.104198f},{-0.0204801f,0.298454f,0.104198f},{-0.0200755f,0.297993f,0.101401f}, -{-0.0204802f,0.298455f,0.101401f},{-0.0208179f,0.298961f,0.104198f},{-0.020818f,0.298961f,0.101401f}, -{-0.0210859f,0.299505f,0.104198f},{-0.0212809f,0.300079f,0.104198f},{-0.0210859f,0.299505f,0.101401f}, -{-0.0212811f,0.300079f,0.101401f},{-0.0214002f,0.300676f,0.104198f},{-0.0214003f,0.300676f,0.101401f}, -{-0.0214407f,0.301289f,0.104198f},{-0.0214407f,0.301289f,0.101401f},{0.0254902f,0.304016f,0.121909f}, -{0.0255985f,0.302667f,0.120045f},{0.0254881f,0.304035f,0.120045f},{0.0250554f,0.306712f,0.121909f}, -{0.0250515f,0.30673f,0.120045f},{0.0247276f,0.308051f,0.120045f},{0.0255992f,0.302654f,0.121909f}, -{0.0256356f,0.301289f,0.120045f},{0.0256356f,0.301289f,0.121909f},{0.0253087f,0.305369f,0.121909f}, -{0.0253054f,0.305391f,0.120045f},{0.0241907f,0.309773f,0.121909f},{0.0246545f,0.308252f,0.121909f}, -{0.0243348f,0.309351f,0.120045f},{0.0222011f,0.314106f,0.121909f},{0.0229537f,0.312704f,0.121909f}, -{0.0227538f,0.313097f,0.120045f},{0.0236177f,0.311258f,0.121909f},{0.0238741f,0.310627f,0.120045f}, -{0.0233468f,0.311877f,0.120045f},{0.0205925f,0.316557f,0.120045f},{0.0197483f,0.317635f,0.120045f}, -{0.0204428f,0.316757f,0.121909f},{0.0220964f,0.314286f,0.120045f},{0.0213756f,0.31544f,0.120045f}, -{0.0213632f,0.315459f,0.121909f},{0.0178811f,0.319658f,0.120045f},{0.0172245f,0.320275f,0.121909f}, -{0.0183635f,0.319164f,0.121909f},{0.0188436f,0.31867f,0.120045f},{0.0194437f,0.317996f,0.121909f}, -{0.0137508f,0.322924f,0.121909f},{0.015542f,0.321676f,0.121909f},{0.014715f,0.32228f,0.120045f}, -{0.0168687f,0.320592f,0.120045f},{0.0112022f,0.324347f,0.120045f},{0.00996671f,0.324907f,0.120045f}, -{0.00988506f,0.324942f,0.121909f},{0.0124072f,0.323722f,0.120045f},{0.0118618f,0.324015f,0.121909f}, -{0.00610419f,0.326187f,0.120045f},{0.00612578f,0.326167f,0.121909f},{0.00741505f,0.325828f,0.120045f}, -{0.00783085f,0.325699f,0.121909f},{0.00870345f,0.325401f,0.120045f},{0.00264799f,0.326787f,0.121909f}, -{0.00342595f,0.326694f,0.120045f},{0.00206394f,0.326841f,0.120045f},{0.00477359f,0.326476f,0.120045f}, -{0.00439916f,0.326544f,0.121909f},{0.000884103f,0.326909f,0.121909f},{-0.000690516f,0.326915f,0.120045f}, -{-0.000883894f,0.326909f,0.121909f},{0.000689447f,0.326915f,0.120045f},{-0.00342617f,0.326694f,0.120045f}, -{-0.00477376f,0.326476f,0.120045f},{-0.00439897f,0.326544f,0.121909f},{-0.00264771f,0.326787f,0.121909f}, -{-0.00206419f,0.326841f,0.120045f},{-0.0087035f,0.325401f,0.120045f},{-0.00783085f,0.325699f,0.121909f}, -{-0.00741509f,0.325828f,0.120045f},{-0.00612769f,0.326175f,0.121909f},{-0.0061043f,0.326187f,0.120045f}, -{-0.0118616f,0.324015f,0.121909f},{-0.00988475f,0.324942f,0.121909f},{-0.0112024f,0.324347f,0.120045f}, -{-0.00996683f,0.324907f,0.120045f},{-0.0137506f,0.322924f,0.121909f},{-0.0135792f,0.323032f,0.120045f}, -{-0.0147152f,0.32228f,0.120045f},{-0.0124074f,0.323722f,0.120045f},{-0.016869f,0.320592f,0.120045f}, -{-0.0178817f,0.319658f,0.120045f},{-0.0172245f,0.320275f,0.121909f},{-0.0155417f,0.321676f,0.121909f}, -{-0.0158127f,0.321466f,0.120045f},{-0.0188441f,0.318669f,0.120045f},{-0.0197483f,0.317635f,0.120045f}, -{-0.0194435f,0.317996f,0.121909f},{-0.0183577f,0.319158f,0.121909f},{-0.0204427f,0.316757f,0.121909f}, -{-0.0205925f,0.316557f,0.120045f},{-0.0213756f,0.31544f,0.120045f},{-0.021363f,0.315459f,0.121909f}, -{-0.0220965f,0.314286f,0.120045f},{-0.0222011f,0.314106f,0.121909f},{-0.0227539f,0.313097f,0.120045f}, -{-0.0229535f,0.312704f,0.121909f},{-0.0236176f,0.311258f,0.121909f},{-0.0233469f,0.311877f,0.120045f}, -{-0.0238742f,0.310627f,0.120045f},{-0.0241907f,0.309774f,0.121909f},{-0.0243349f,0.309351f,0.120045f}, -{-0.0246619f,0.308254f,0.121909f},{-0.0250554f,0.306712f,0.121909f},{-0.0247277f,0.308051f,0.120045f}, -{-0.0253055f,0.30539f,0.120045f},{-0.0250516f,0.30673f,0.120045f},{-0.0254882f,0.304035f,0.120045f}, -{-0.0253087f,0.305369f,0.121909f},{-0.0254901f,0.304016f,0.121909f},{-0.0255986f,0.302667f,0.120045f}, -{-0.0256356f,0.301289f,0.120045f},{-0.0255992f,0.302654f,0.121909f},{-0.0256356f,0.301289f,0.121909f}, -{0.013579f,0.323032f,0.120045f},{0.0158124f,0.321467f,0.120045f},{0.0247034f,0.301289f,0.104011f}, -{0.0261017f,0.301289f,0.10513f},{0.0260447f,0.299565f,0.10513f},{0.0148773f,0.318617f,0.10252f}, -{0.0141264f,0.317418f,0.101401f},{0.0130365f,0.318311f,0.101401f},{0.0151609f,0.316449f,0.101401f}, -{0.0131883f,0.319935f,0.10252f},{0.0144813f,0.323005f,0.10513f},{0.0123517f,0.322682f,0.104011f}, -{0.0130346f,0.323903f,0.10513f},{0.0118953f,0.319127f,0.101401f},{0.0114195f,0.321068f,0.10252f}, -{0.0115354f,0.324703f,0.10513f},{0.00947527f,0.320522f,0.101401f},{0.00998868f,0.325403f,0.10513f}, -{0.00820499f,0.321097f,0.101401f},{0.0084f,0.326002f,0.10513f},{0.00689981f,0.321589f,0.101401f}, -{0.00556423f,0.321995f,0.101401f},{0.00677408f,0.326496f,0.10513f},{0.00420236f,0.322313f,0.101401f}, -{0.00511591f,0.326884f,0.10513f},{0.00343096f,0.327164f,0.10513f},{0.0028181f,0.322543f,0.101401f}, -{0.00172399f,0.327333f,0.10513f},{0.00141594f,0.322683f,0.101401f},{-2.32983e-017f,0.32739f,0.10513f}, -{0.0164604f,0.317121f,0.10252f},{0.016129f,0.315415f,0.101401f},{0.0179091f,0.315462f,0.10252f}, -{0.0170221f,0.314325f,0.101401f},{0.0178384f,0.313184f,0.101401f},{0.0192f,0.313657f,0.10252f}, -{0.018576f,0.311996f,0.101401f},{0.0203119f,0.311731f,0.10252f},{0.0192333f,0.310764f,0.101401f}, -{0.0212292f,0.309711f,0.10252f},{0.0198086f,0.309494f,0.101401f},{0.0252075f,0.308062f,0.10513f}, -{0.0255955f,0.306404f,0.10513f},{0.0242782f,0.305853f,0.104011f},{0.021942f,0.307626f,0.10252f}, -{0.0203001f,0.308189f,0.101401f},{0.0224458f,0.305508f,0.10252f},{0.0207061f,0.306853f,0.101401f}, -{0.0210249f,0.305491f,0.101401f},{0.0227423f,0.303385f,0.10252f},{0.0212547f,0.304107f,0.101401f}, -{0.0260448f,0.303012f,0.10513f},{0.022839f,0.301289f,0.10252f},{0.0213939f,0.302705f,0.101401f}, -{0.0212463f,0.298408f,0.101401f},{0.021392f,0.299845f,0.101401f},{0.0258753f,0.297858f,0.10513f}, -{0.0202358f,0.294203f,0.101401f},{0.0206669f,0.295581f,0.101401f},{0.0247131f,0.292889f,0.10513f}, -{0.0210042f,0.296985f,0.101401f},{0.0255955f,0.296173f,0.10513f},{0.0252074f,0.294514f,0.10513f}, -{0.0191008f,0.291549f,0.101401f},{0.0226142f,0.288254f,0.10513f},{0.0184019f,0.290285f,0.101401f}, -{0.0241148f,0.2913f,0.10513f},{0.0234144f,0.289753f,0.10513f},{0.019713f,0.292857f,0.101401f}, -{0.0207226f,0.285418f,0.10513f},{0.0196354f,0.284091f,0.10513f},{0.0167571f,0.287913f,0.101401f}, -{0.0176194f,0.289072f,0.101401f},{0.0217163f,0.286807f,0.10513f},{0.0158706f,0.280566f,0.10513f}, -{0.0137317f,0.284822f,0.101401f},{0.0171974f,0.281653f,0.10513f},{0.0148089f,0.285784f,0.101401f}, -{0.0158188f,0.286816f,0.101401f},{0.0184567f,0.282832f,0.10513f},{0.0101475f,0.282401f,0.101401f}, -{0.0113957f,0.283127f,0.101401f},{0.0114195f,0.281509f,0.10252f},{0.0125922f,0.283935f,0.101401f}, -{0.0123517f,0.279895f,0.104011f},{0.0130343f,0.278674f,0.10513f},{0.0109801f,0.279159f,0.104011f}, -{0.00954347f,0.278503f,0.104011f},{0.00998868f,0.277174f,0.10513f},{0.00804836f,0.277933f,0.104011f}, -{0.0115351f,0.277874f,0.10513f},{0.00650255f,0.277456f,0.104011f},{0.00677384f,0.276081f,0.10513f}, -{0.00491482f,0.277079f,0.104011f},{0.00839976f,0.276575f,0.10513f},{0.00329485f,0.276806f,0.104011f}, -{0.00511591f,0.275693f,0.10513f},{0.00343072f,0.275413f,0.10513f},{0.00172376f,0.275244f,0.10513f}, -{0.00165296f,0.276641f,0.104011f},{-2.64948e-017f,0.275187f,0.10513f},{-2.64948e-017f,0.276585f,0.104011f}, -{0.0144813f,0.279572f,0.10513f},{0.00454389f,0.278906f,0.10252f},{0.00475341f,0.280385f,0.101401f}, -{0.00601179f,0.279255f,0.10252f},{0.00304618f,0.278654f,0.10252f},{0.00333561f,0.28011f,0.101401f}, -{0.00190254f,0.279933f,0.101401f},{0.00152821f,0.278501f,0.10252f},{-2.64948e-017f,0.27845f,0.10252f}, -{0.00615037f,0.280749f,0.101401f},{0.00751875f,0.281209f,0.101401f},{0.00882321f,0.280223f,0.10252f}, -{0.00744093f,0.279696f,0.10252f},{0.00885315f,0.281761f,0.101401f},{0.0101514f,0.28083f,0.10252f}, -{0.0142636f,0.321458f,0.104011f},{0.0107068f,0.319865f,0.101401f},{0.0160914f,0.320032f,0.104011f}, -{0.0158708f,0.322011f,0.10513f},{0.0184567f,0.319745f,0.10513f},{0.0171976f,0.320924f,0.10513f}, -{0.0178031f,0.318415f,0.104011f},{0.0193705f,0.31662f,0.104011f},{0.0196355f,0.318486f,0.10513f}, -{0.0217163f,0.31577f,0.10513f},{0.0207227f,0.317159f,0.10513f},{0.0207667f,0.314668f,0.104011f}, -{0.0219695f,0.312585f,0.104011f},{0.0226143f,0.314323f,0.10513f},{0.0234145f,0.312824f,0.10513f}, -{0.0229621f,0.310399f,0.104011f},{0.0241148f,0.311277f,0.10513f},{0.0237331f,0.308145f,0.104011f}, -{0.0247132f,0.309688f,0.10513f},{0.0245992f,0.303558f,0.104011f},{0.0258754f,0.304719f,0.10513f}, -{0.0214407f,0.301289f,0.10513f},{0.0214407f,0.301289f,0.106062f},{0.0214037f,0.300029f,0.106062f}, -{0.0212935f,0.29878f,0.106062f},{0.0214037f,0.300029f,0.10513f},{0.0211114f,0.297545f,0.106062f}, -{0.0212936f,0.298781f,0.10513f},{0.0211115f,0.297545f,0.10513f},{0.0208586f,0.296326f,0.106062f}, -{0.0205363f,0.295127f,0.106062f},{0.0208587f,0.296327f,0.10513f},{0.0201457f,0.29395f,0.106062f}, -{0.0205363f,0.295127f,0.10513f},{0.0201457f,0.29395f,0.10513f},{0.0196879f,0.292798f,0.106062f}, -{0.0191643f,0.291674f,0.106062f},{0.019688f,0.292798f,0.10513f},{0.018576f,0.290582f,0.106062f}, -{0.0191643f,0.291674f,0.10513f},{0.018576f,0.290582f,0.10513f},{0.0179242f,0.289523f,0.106062f}, -{0.0172102f,0.288501f,0.106062f},{0.0179243f,0.289523f,0.10513f},{0.0164352f,0.287519f,0.106062f}, -{0.0172102f,0.288501f,0.10513f},{0.0164352f,0.287519f,0.10513f},{0.0155998f,0.28658f,0.106062f}, -{0.0147082f,0.285688f,0.106062f},{0.0156004f,0.28658f,0.10513f},{0.0137691f,0.284853f,0.106062f}, -{0.0147088f,0.285689f,0.10513f},{0.0137693f,0.284853f,0.10513f},{0.0127873f,0.284078f,0.106062f}, -{0.0117655f,0.283364f,0.106062f},{0.0127873f,0.284078f,0.10513f},{0.0107068f,0.282713f,0.106062f}, -{0.0117656f,0.283364f,0.10513f},{0.010707f,0.282713f,0.10513f},{0.00961408f,0.282124f,0.106062f}, -{0.00849036f,0.281601f,0.106062f},{0.0096143f,0.282124f,0.10513f},{0.0073385f,0.281143f,0.106062f}, -{0.00849054f,0.281601f,0.10513f},{0.00733859f,0.281143f,0.10513f},{0.00616138f,0.280752f,0.106062f}, -{0.00496191f,0.28043f,0.106062f},{0.00616144f,0.280752f,0.10513f},{0.00496208f,0.28043f,0.10513f}, -{0.00374334f,0.280177f,0.10513f},{0.00250813f,0.279995f,0.10513f},{0.00374312f,0.280177f,0.106062f}, -{0.00125925f,0.279885f,0.106062f},{0.00250793f,0.279995f,0.106062f},{-2.38691e-017f,0.279848f,0.106062f}, -{0.00125938f,0.279885f,0.10513f},{-2.38691e-017f,0.279848f,0.10513f},{0.0214037f,0.302548f,0.10513f}, -{0.0212935f,0.303797f,0.10513f},{0.0214037f,0.302548f,0.106062f},{0.0212936f,0.303796f,0.106062f}, -{0.0211114f,0.305032f,0.10513f},{0.0208586f,0.306251f,0.10513f},{0.0211115f,0.305032f,0.106062f}, -{0.0205363f,0.30745f,0.10513f},{0.0208587f,0.30625f,0.106062f},{0.0205363f,0.30745f,0.106062f}, -{0.0201457f,0.308627f,0.10513f},{0.0196879f,0.309779f,0.10513f},{0.0201457f,0.308627f,0.106062f}, -{0.0191643f,0.310903f,0.10513f},{0.019688f,0.309779f,0.106062f},{0.0191643f,0.310903f,0.106062f}, -{0.018576f,0.311996f,0.10513f},{0.0179242f,0.313054f,0.10513f},{0.018576f,0.311995f,0.106062f}, -{0.0172102f,0.314076f,0.10513f},{0.0179243f,0.313054f,0.106062f},{0.0172102f,0.314076f,0.106062f}, -{0.0164352f,0.315058f,0.10513f},{0.0155998f,0.315997f,0.10513f},{0.0164352f,0.315058f,0.106062f}, -{0.0147082f,0.316889f,0.10513f},{0.0156004f,0.315997f,0.106062f},{0.0147088f,0.316888f,0.106062f}, -{0.0137691f,0.317724f,0.10513f},{0.0127873f,0.318499f,0.10513f},{0.0137693f,0.317724f,0.106062f}, -{0.0117655f,0.319213f,0.10513f},{0.0127873f,0.318499f,0.106062f},{0.0117656f,0.319213f,0.106062f}, -{0.0107068f,0.319865f,0.10513f},{0.00961408f,0.320453f,0.10513f},{0.010707f,0.319865f,0.106062f}, -{0.00849036f,0.320976f,0.10513f},{0.0096143f,0.320453f,0.106062f},{0.00849054f,0.320976f,0.106062f}, -{0.0073385f,0.321434f,0.10513f},{0.00616138f,0.321825f,0.10513f},{0.00733859f,0.321434f,0.106062f}, -{0.00496191f,0.322147f,0.10513f},{0.00616144f,0.321825f,0.106062f},{0.00374334f,0.3224f,0.106062f}, -{0.00496208f,0.322147f,0.106062f},{0.00374312f,0.3224f,0.10513f},{0.00250813f,0.322582f,0.106062f}, -{0.00250793f,0.322582f,0.10513f},{0.00125925f,0.322692f,0.10513f},{0.00125938f,0.322692f,0.106062f}, -{-2.64948e-017f,0.322729f,0.10513f},{-2.64948e-017f,0.322729f,0.106062f},{0.0261017f,0.301289f,0.106062f}, -{0.0261017f,0.301289f,0.120045f},{0.0260652f,0.299908f,0.120045f},{0.0259565f,0.298538f,0.120045f}, -{0.0260653f,0.299908f,0.106062f},{0.0257765f,0.297181f,0.120045f},{0.0259565f,0.298538f,0.106062f}, -{0.0257766f,0.297181f,0.106062f},{0.0255265f,0.295839f,0.120045f},{0.0252074f,0.294514f,0.120045f}, -{0.0255265f,0.295839f,0.106062f},{0.0248204f,0.293211f,0.120045f},{0.0252075f,0.294515f,0.106062f}, -{0.0248205f,0.293211f,0.106062f},{0.0243664f,0.29193f,0.120045f},{0.0238467f,0.290676f,0.120045f}, -{0.0243666f,0.291931f,0.106062f},{0.0232623f,0.289449f,0.120045f},{0.0238468f,0.290676f,0.106062f}, -{0.0232624f,0.28945f,0.106062f},{0.0226142f,0.288254f,0.120045f},{0.0219036f,0.287092f,0.120045f}, -{0.0226143f,0.288254f,0.106062f},{0.0211314f,0.285966f,0.120045f},{0.0219036f,0.287092f,0.106062f}, -{0.0211315f,0.285967f,0.106062f},{0.0202988f,0.284879f,0.120045f},{0.0194069f,0.283834f,0.120045f}, -{0.0202989f,0.284879f,0.106062f},{0.0184567f,0.282832f,0.120045f},{0.0194069f,0.283834f,0.106062f}, -{0.0184567f,0.282832f,0.106062f},{0.0174549f,0.281882f,0.120045f},{0.0164091f,0.28099f,0.120045f}, -{0.0174549f,0.281882f,0.106062f},{0.015322f,0.280157f,0.120045f},{0.0164092f,0.28099f,0.106062f}, -{0.0153222f,0.280157f,0.106062f},{0.0141962f,0.279385f,0.120045f},{0.0130343f,0.278674f,0.120045f}, -{0.0141964f,0.279385f,0.106062f},{0.0118389f,0.278026f,0.120045f},{0.0130346f,0.278674f,0.106062f}, -{0.0118391f,0.278026f,0.106062f},{0.0106125f,0.277442f,0.120045f},{0.00935782f,0.276922f,0.120045f}, -{0.0106128f,0.277442f,0.106062f},{0.0080774f,0.276468f,0.120045f},{0.00935809f,0.276922f,0.106062f}, -{0.00807765f,0.276468f,0.106062f},{0.00677384f,0.276081f,0.120045f},{0.00544975f,0.275762f,0.120045f}, -{0.00677408f,0.276081f,0.106062f},{0.00410773f,0.275512f,0.120045f},{0.00544996f,0.275762f,0.106062f}, -{0.0041079f,0.275512f,0.106062f},{0.00275036f,0.275332f,0.120045f},{0.00138025f,0.275223f,0.120045f}, -{0.00275048f,0.275332f,0.106062f},{-2.32983e-017f,0.275187f,0.120045f},{0.00138032f,0.275223f,0.106062f}, -{-2.32983e-017f,0.275187f,0.106062f},{0.0260652f,0.302669f,0.106062f},{0.0259565f,0.304039f,0.106062f}, -{0.0260653f,0.302669f,0.120045f},{0.0259565f,0.304039f,0.120045f},{0.0257765f,0.305396f,0.106062f}, -{0.0255265f,0.306739f,0.106062f},{0.0257766f,0.305396f,0.120045f},{0.0252074f,0.308063f,0.106062f}, -{0.0255265f,0.306738f,0.120045f},{0.0252075f,0.308062f,0.120045f},{0.0248204f,0.309366f,0.106062f}, -{0.0243664f,0.310647f,0.106062f},{0.0248205f,0.309366f,0.120045f},{0.0238467f,0.311901f,0.106062f}, -{0.0243666f,0.310646f,0.120045f},{0.0238468f,0.311901f,0.120045f},{0.0232623f,0.313128f,0.106062f}, -{0.0226142f,0.314323f,0.106062f},{0.0232624f,0.313127f,0.120045f},{0.0219036f,0.315485f,0.106062f}, -{0.0226143f,0.314323f,0.120045f},{0.0219036f,0.315485f,0.120045f},{0.0211314f,0.316611f,0.106062f}, -{0.0202988f,0.317698f,0.106062f},{0.0211315f,0.316611f,0.120045f},{0.0194069f,0.318743f,0.106062f}, -{0.0202989f,0.317698f,0.120045f},{0.0194069f,0.318743f,0.120045f},{0.0184567f,0.319745f,0.106062f}, -{0.0174549f,0.320695f,0.106062f},{0.0184567f,0.319745f,0.120045f},{0.0164091f,0.321587f,0.106062f}, -{0.0174549f,0.320695f,0.120045f},{0.0164092f,0.321587f,0.120045f},{0.015322f,0.32242f,0.106062f}, -{0.0141962f,0.323192f,0.106062f},{0.0153222f,0.32242f,0.120045f},{0.0130343f,0.323903f,0.106062f}, -{0.0141964f,0.323192f,0.120045f},{0.0130346f,0.323903f,0.120045f},{0.0118389f,0.324551f,0.106062f}, -{0.0106125f,0.325135f,0.106062f},{0.0118391f,0.324551f,0.120045f},{0.00935782f,0.325655f,0.106062f}, -{0.0106128f,0.325135f,0.120045f},{0.00935809f,0.325655f,0.120045f},{0.0080774f,0.326109f,0.106062f}, -{0.00677384f,0.326496f,0.106062f},{0.00807765f,0.326109f,0.120045f},{0.00544975f,0.326815f,0.106062f}, -{0.00677408f,0.326496f,0.120045f},{0.00544996f,0.326815f,0.120045f},{0.00410773f,0.327065f,0.106062f}, -{0.00275036f,0.327245f,0.106062f},{0.0041079f,0.327065f,0.120045f},{0.00138025f,0.327354f,0.106062f}, -{0.00275048f,0.327245f,0.120045f},{0.00138032f,0.327354f,0.120045f},{-2.64948e-017f,0.32739f,0.106062f}, -{-2.64948e-017f,0.32739f,0.120045f},{0.0121333f,0.298398f,0.125638f},{-0.0149893f,0.307258f,0.125638f}, -{-0.0150309f,0.307814f,0.125638f},{-0.019126f,0.30503f,0.125638f},{-0.00810759f,0.286008f,0.125638f}, -{-0.00862289f,0.316224f,0.125638f},{-0.00372901f,0.31434f,0.125638f},{-0.00810797f,0.316569f,0.125638f}, -{-0.0122191f,0.315775f,0.125638f},{-0.012803f,0.315983f,0.125638f},{-0.0130106f,0.311605f,0.125638f}, -{0.00523604f,0.311135f,0.125638f},{0.00485519f,0.311216f,0.125638f},{-0.0018645f,0.317568f,0.125638f}, -{-0.00378085f,0.322866f,0.125638f},{-0.00629776f,0.320341f,0.125638f},{0.00943824f,0.311044f,0.125638f}, -{0.00917901f,0.31595f,0.125638f},{0.00862289f,0.316224f,0.125638f},{0.00897792f,0.31073f,0.125638f}, -{0.0172458f,0.301289f,0.125638f},{0.0172871f,0.301907f,0.125638f},{0.010994f,0.3156f,0.125638f}, -{0.0110243f,0.311532f,0.125638f},{0.0115815f,0.311532f,0.125638f},{0.0207988f,0.296759f,0.125638f}, -{0.0210452f,0.295205f,0.125638f},{0.021411f,0.296654f,0.125638f},{0.0174099f,0.300063f,0.125638f}, -{0.017287f,0.30067f,0.125638f},{0.0136278f,0.297678f,0.125638f},{0.019126f,0.297548f,0.125638f}, -{0.0149893f,0.295319f,0.125638f},{0.0150309f,0.294763f,0.125638f},{0.0202118f,0.296955f,0.125638f}, -{0.0149893f,0.294207f,0.125638f},{0.0148647f,0.293665f,0.125638f},{0.0200086f,0.292369f,0.125638f}, -{0.00994038f,0.298234f,0.125638f},{0.0104733f,0.298402f,0.125638f},{0.0143811f,0.292664f,0.125638f}, -{0.0185801f,0.289683f,0.125638f},{0.0193415f,0.291002f,0.125638f},{0.0205774f,0.293774f,0.125638f}, -{0.0196492f,0.297216f,0.125638f},{0.0167976f,0.287226f,0.125638f},{0.013354f,0.28631f,0.125638f}, -{0.0157911f,0.286105f,0.125638f},{0.0136271f,0.291848f,0.125638f},{0.0138626f,0.285956f,0.125638f}, -{0.0143217f,0.285539f,0.125638f},{0.0147191f,0.285063f,0.125638f},{0.0146599f,0.293146f,0.125638f}, -{0.0149896f,0.308369f,0.125638f},{0.0205772f,0.308804f,0.125638f},{0.0148655f,0.295862f,0.125638f}, -{0.0186543f,0.297949f,0.125638f},{0.0182401f,0.298411f,0.125638f},{0.0178906f,0.298923f,0.125638f}, -{0.0143836f,0.296863f,0.125638f},{0.0146621f,0.296381f,0.125638f},{0.0105684f,0.302675f,0.125638f}, -{0.01083f,0.302385f,0.125638f},{0.0174101f,0.302515f,0.125638f},{0.0102536f,0.302903f,0.125638f}, -{0.00810759f,0.316569f,0.125638f},{0.00764282f,0.316979f,0.125638f},{0.0191272f,0.305029f,0.125638f}, -{0.0133515f,0.316269f,0.125638f},{0.0157911f,0.316472f,0.125638f},{0.013859f,0.316626f,0.125638f}, -{0.0143221f,0.317036f,0.125638f},{0.0147191f,0.317514f,0.125638f},{0.0126646f,0.311285f,0.125638f}, -{0.0128028f,0.315982f,0.125638f},{0.0122189f,0.315774f,0.125638f},{0.0116123f,0.315646f,0.125638f}, -{0.0121324f,0.311449f,0.125638f},{0.014035f,0.31035f,0.125638f},{0.0177287f,0.314157f,0.125638f}, -{0.013627f,0.310729f,0.125638f},{0.0131664f,0.311043f,0.125638f},{0.0193407f,0.311577f,0.125638f}, -{0.018579f,0.312896f,0.125638f},{0.0146599f,0.309431f,0.125638f},{0.0167966f,0.315352f,0.125638f}, -{0.0196491f,0.305364f,0.125638f},{0.02021f,0.305627f,0.125638f},{0.0210452f,0.307372f,0.125638f}, -{0.0208003f,0.305817f,0.125638f},{0.021411f,0.305923f,0.125638f},{0.0143816f,0.309913f,0.125638f}, -{0.0200082f,0.31021f,0.125638f},{0.0148642f,0.308912f,0.125638f},{-0.00635281f,0.320959f,0.125638f}, -{-0.00525411f,0.322556f,0.125638f},{-0.00647672f,0.321566f,0.125638f},{0.00723674f,0.317448f,0.125638f}, -{0.00689651f,0.317966f,0.125638f},{0.018655f,0.304627f,0.125638f},{0.00632427f,0.319723f,0.125638f}, -{0.00643592f,0.319114f,0.125638f},{0.0178912f,0.303655f,0.125638f},{0.0182407f,0.304166f,0.125638f}, -{-0.010376f,0.315635f,0.125638f},{-0.0109947f,0.3156f,0.125638f},{-0.00838954f,0.299674f,0.125638f}, -{-0.00368715f,0.314896f,0.125638f},{-0.00356297f,0.315439f,0.125638f},{-0.00764334f,0.316979f,0.125638f}, -{-0.00632322f,0.319723f,0.125638f},{-0.00643547f,0.319113f,0.125638f},{-0.00232474f,0.317255f,0.125638f}, -{-0.000829763f,0.317974f,0.125638f},{-0.00227994f,0.323076f,0.125638f},{-0.00136226f,0.31781f,0.125638f}, -{-0.00662778f,0.318524f,0.125638f},{-0.00273315f,0.316876f,0.125638f},{0.00377962f,0.322867f,0.125638f}, -{0.00136248f,0.31781f,0.125638f},{0.00027877f,0.318055f,0.125638f},{0.000760576f,0.323182f,0.125638f}, -{-0.000278327f,0.318056f,0.125638f},{0.00629503f,0.320343f,0.125638f},{0.00525411f,0.322556f,0.125638f}, -{-0.00669182f,0.322148f,0.125638f},{0.00634749f,0.32096f,0.125638f},{0.0064786f,0.321566f,0.125638f}, -{0.00669182f,0.322148f,0.125638f},{-0.0030806f,0.31644f,0.125638f},{-0.00689664f,0.317965f,0.125638f}, -{-0.00335928f,0.315958f,0.125638f},{0.00227826f,0.323077f,0.125638f},{0.000829582f,0.317973f,0.125638f}, -{-0.0146621f,0.306197f,0.125638f},{-0.0178906f,0.303654f,0.125638f},{-0.0143836f,0.305714f,0.125638f}, -{0.00408395f,0.311134f,0.125638f},{0.00446533f,0.311216f,0.125638f},{-0.00917948f,0.31595f,0.125638f}, -{-0.0130106f,0.300131f,0.125638f},{-0.00632427f,0.282854f,0.125638f},{-0.00643592f,0.283463f,0.125638f}, -{-0.0097673f,0.315753f,0.125638f},{-0.0205774f,0.308803f,0.125638f},{-0.0210452f,0.307372f,0.125638f}, -{-0.0196492f,0.305361f,0.125638f},{-0.0136271f,0.310729f,0.125638f},{-0.0177299f,0.314156f,0.125638f}, -{-0.0140346f,0.310349f,0.125638f},{-0.00590935f,0.310746f,0.125638f},{-0.0207988f,0.305818f,0.125638f}, -{-0.021411f,0.305923f,0.125638f},{-0.0140362f,0.305278f,0.125638f},{-0.0174099f,0.302514f,0.125638f}, -{-0.0136278f,0.304899f,0.125638f},{-0.0182401f,0.304166f,0.125638f},{-0.0148655f,0.306715f,0.125638f}, -{-0.0186543f,0.304628f,0.125638f},{-0.0202118f,0.305622f,0.125638f},{-0.0149893f,0.30837f,0.125638f}, -{-0.0148647f,0.308913f,0.125638f},{-0.0200086f,0.310208f,0.125638f},{-0.0193415f,0.311575f,0.125638f}, -{-0.0143811f,0.309913f,0.125638f},{-0.0185801f,0.312894f,0.125638f},{-0.0146599f,0.309431f,0.125638f}, -{-0.013354f,0.316267f,0.125638f},{-0.0157911f,0.316472f,0.125638f},{-0.0167976f,0.315351f,0.125638f}, -{-0.0138626f,0.316622f,0.125638f},{-0.00976653f,0.286824f,0.125638f},{-0.00917901f,0.286627f,0.125638f}, -{-0.00994062f,0.291292f,0.125638f},{-0.0143217f,0.317038f,0.125638f},{-0.0147191f,0.317514f,0.125638f}, -{-0.00636453f,0.310119f,0.125638f},{-0.00648481f,0.309748f,0.125638f},{-0.0176127f,0.299476f,0.125638f}, -{-0.0178912f,0.298922f,0.125638f},{-0.0116126f,0.315647f,0.125638f},{-0.00862289f,0.286353f,0.125638f}, -{-0.00943824f,0.291533f,0.125638f},{-0.00315227f,0.29212f,0.125638f},{-0.00295749f,0.292458f,0.125638f}, -{-0.0104733f,0.291128f,0.125638f},{-0.0196491f,0.297213f,0.125638f},{-0.0205772f,0.293773f,0.125638f}, -{-0.0167966f,0.287225f,0.125638f},{-0.0157911f,0.286105f,0.125638f},{-0.0130106f,0.288657f,0.125638f}, -{-0.0122189f,0.286803f,0.125638f},{-0.0116123f,0.286931f,0.125638f},{-0.017287f,0.301907f,0.125638f}, -{-0.0174101f,0.300062f,0.125638f},{-0.0172458f,0.301289f,0.125638f},{-0.00723674f,0.285129f,0.125638f}, -{-0.00689651f,0.284611f,0.125638f},{-0.013859f,0.285951f,0.125638f},{-0.0133515f,0.286308f,0.125638f}, -{-0.0115815f,0.291045f,0.125638f},{-0.0121324f,0.291128f,0.125638f},{-0.014035f,0.292227f,0.125638f}, -{-0.0177287f,0.28842f,0.125638f},{-0.013627f,0.291848f,0.125638f},{-0.0143816f,0.292664f,0.125638f}, -{-0.018579f,0.289681f,0.125638f},{-0.0193407f,0.291f,0.125638f},{-0.0146599f,0.293147f,0.125638f}, -{-0.0149896f,0.294208f,0.125638f},{-0.0131664f,0.291534f,0.125638f},{-0.0126646f,0.291292f,0.125638f}, -{-0.0210452f,0.295205f,0.125638f},{-0.0143221f,0.285541f,0.125638f},{-0.02021f,0.29695f,0.125638f}, -{-0.0208003f,0.29676f,0.125638f},{-0.0147191f,0.285063f,0.125638f},{-0.021411f,0.296654f,0.125638f}, -{-0.0110243f,0.291045f,0.125638f},{0.00874495f,0.303061f,0.125638f},{0.00838954f,0.302903f,0.125638f}, -{-0.00523587f,0.291442f,0.125638f},{-0.00485544f,0.291361f,0.125638f},{0.0063639f,0.293974f,0.125638f}, -{0.00616894f,0.294312f,0.125638f},{-0.00629503f,0.282234f,0.125638f},{-0.00377962f,0.27971f,0.125638f}, -{0.0099371f,0.288657f,0.125638f},{0.0109947f,0.286977f,0.125638f},{0.0116126f,0.286931f,0.125638f}, -{0.00356297f,0.287138f,0.125638f},{0.00764334f,0.285598f,0.125638f},{0.00368715f,0.287681f,0.125638f}, -{0.0097673f,0.286824f,0.125638f},{0.00917948f,0.286627f,0.125638f},{0.00643547f,0.283464f,0.125638f}, -{0.00232474f,0.285323f,0.125638f},{0.00632322f,0.282854f,0.125638f},{0.00810797f,0.286008f,0.125638f}, -{0.00862289f,0.286353f,0.125638f},{0.00372901f,0.288237f,0.125638f},{0.00378085f,0.279711f,0.125638f}, -{0.00629776f,0.282236f,0.125638f},{0.0018645f,0.285009f,0.125638f},{0.0111453f,0.301677f,0.125638f}, -{0.0110251f,0.302047f,0.125638f},{-0.0200082f,0.292368f,0.125638f},{-0.0148642f,0.293665f,0.125638f}, -{-0.010994f,0.286978f,0.125638f},{0.00773683f,0.308915f,0.125638f},{-0.0110251f,0.30053f,0.125638f}, -{-0.0111453f,0.3009f,0.125638f},{-0.00764282f,0.285598f,0.125638f},{-0.0105684f,0.299902f,0.125638f}, -{0.00807379f,0.302673f,0.125638f},{-0.000829582f,0.284604f,0.125638f},{-0.00136248f,0.284767f,0.125638f}, -{-0.00227826f,0.2795f,0.125638f},{-0.00027877f,0.284522f,0.125638f},{-0.000760576f,0.279395f,0.125638f}, -{0.000278327f,0.284521f,0.125638f},{0.000829763f,0.284603f,0.125638f},{0.00227994f,0.279501f,0.125638f}, -{0.00136226f,0.284767f,0.125638f},{-0.00525411f,0.280021f,0.125638f},{-0.00634749f,0.281617f,0.125638f}, -{-0.0064786f,0.281011f,0.125638f},{-0.00669182f,0.280429f,0.125638f},{0.00335928f,0.286619f,0.125638f}, -{0.0030806f,0.286137f,0.125638f},{0.00689664f,0.284612f,0.125638f},{0.00273315f,0.285701f,0.125638f}, -{0.00662778f,0.284053f,0.125638f},{0.00525411f,0.280021f,0.125638f},{0.00635281f,0.281618f,0.125638f}, -{0.00669182f,0.280429f,0.125638f},{0.00647672f,0.281011f,0.125638f},{0.0176127f,0.303101f,0.125638f}, -{0.00994062f,0.311285f,0.125638f},{0.0103751f,0.315635f,0.125638f},{0.00976653f,0.315753f,0.125638f}, -{0.0104733f,0.311449f,0.125638f},{0.00912617f,0.303143f,0.125638f},{0.0095162f,0.303143f,0.125638f}, -{0.00989767f,0.303062f,0.125638f},{0.0140362f,0.297299f,0.125638f},{0.0110245f,0.298472f,0.125638f}, -{0.0177299f,0.288421f,0.125638f},{0.0140346f,0.292228f,0.125638f},{0.00822623f,0.309913f,0.125638f}, -{-0.00408474f,0.307589f,0.125638f},{-0.00446554f,0.307508f,0.125638f},{-0.018655f,0.29795f,0.125638f}, -{-0.0191272f,0.297548f,0.125638f},{0.00315227f,0.310457f,0.125638f},{0.00295755f,0.310119f,0.125638f}, -{0.00341361f,0.307976f,0.125638f},{0.00749845f,0.301676f,0.125638f},{0.00761862f,0.302046f,0.125638f}, -{0.0126655f,0.298234f,0.125638f},{0.0131672f,0.297992f,0.125638f},{0.0115822f,0.298477f,0.125638f}, -{0.0122191f,0.286802f,0.125638f},{0.012803f,0.286594f,0.125638f},{0.00590935f,0.291831f,0.125638f}, -{0.00636453f,0.292458f,0.125638f},{0.00648481f,0.292829f,0.125638f},{-0.00408362f,0.291443f,0.125638f}, -{-0.00446544f,0.291361f,0.125638f},{-0.00807379f,0.299904f,0.125638f},{-0.00430393f,0.299506f,0.125638f}, -{0.00283746f,0.29759f,0.125638f},{0.00408474f,0.294989f,0.125638f},{0.00446554f,0.29507f,0.125638f}, -{-0.00874495f,0.299516f,0.125638f},{-0.0172871f,0.30067f,0.125638f},{0.00761515f,0.30837f,0.125638f}, -{0.0085695f,0.310351f,0.125638f},{-0.00723717f,0.317447f,0.125638f},{-0.000762504f,0.323182f,0.125638f}, -{0.00662806f,0.318524f,0.125638f},{0.00341281f,0.310746f,0.125638f},{0.00372825f,0.310976f,0.125638f}, -{0.00279662f,0.309361f,0.125638f},{0.00283723f,0.309748f,0.125638f},{0.00283764f,0.308973f,0.125638f}, -{-0.00335595f,0.312725f,0.125638f},{0.00795154f,0.309428f,0.125638f},{-0.00369782f,0.298452f,0.125638f}, -{0.00295819f,0.308603f,0.125638f},{0.00315308f,0.308265f,0.125638f},{-0.00523619f,0.307588f,0.125638f}, -{-0.00616894f,0.308265f,0.125638f},{-0.0063639f,0.308603f,0.125638f},{-0.00273651f,0.311802f,0.125638f}, -{-0.00232523f,0.311424f,0.125638f},{-0.00356376f,0.313241f,0.125638f},{-0.0131672f,0.304585f,0.125638f}, -{-0.0176123f,0.3031f,0.125638f},{-0.00616972f,0.310457f,0.125638f},{-0.00648443f,0.308973f,0.125638f}, -{-0.00652539f,0.309361f,0.125638f},{-0.00559278f,0.307747f,0.125638f},{-0.00590766f,0.307976f,0.125638f}, -{-0.0048551f,0.307507f,0.125638f},{-0.00307294f,0.312244f,0.125638f},{-0.0110245f,0.304105f,0.125638f}, -{-0.0095162f,0.299434f,0.125638f},{-0.00368758f,0.313784f,0.125638f},{-0.00897792f,0.291847f,0.125638f}, -{-0.0103751f,0.286942f,0.125638f},{-0.0128028f,0.286595f,0.125638f},{-0.0182407f,0.298411f,0.125638f}, -{-0.01083f,0.300192f,0.125638f},{-0.0102536f,0.299674f,0.125638f},{-0.00912617f,0.299435f,0.125638f}, -{-0.00989767f,0.299515f,0.125638f},{-0.0115822f,0.3041f,0.125638f},{-0.0121333f,0.304179f,0.125638f}, -{-0.0104733f,0.304175f,0.125638f},{-0.00994038f,0.304343f,0.125638f},{-0.00462174f,0.30068f,0.125638f}, -{-0.00761862f,0.300531f,0.125638f},{-0.00449935f,0.300083f,0.125638f},{-0.00749845f,0.300901f,0.125638f}, -{-0.00761515f,0.294207f,0.125638f},{-0.0085695f,0.292226f,0.125638f},{-0.00822623f,0.292664f,0.125638f}, -{-0.00773683f,0.293662f,0.125638f},{-0.00403697f,0.298958f,0.125638f},{-0.0126655f,0.304343f,0.125638f}, -{0.00559278f,0.29483f,0.125638f},{0.00723717f,0.28513f,0.125638f},{0.000762504f,0.279395f,0.125638f}, -{-0.00662806f,0.284053f,0.125638f},{-0.00341302f,0.29183f,0.125638f},{-0.00372824f,0.291601f,0.125638f}, -{-0.00279657f,0.293216f,0.125638f},{-0.00283721f,0.292829f,0.125638f},{-0.0028377f,0.293604f,0.125638f}, -{0.00120604f,0.296786f,0.125638f},{-0.00795154f,0.293149f,0.125638f},{0.003698f,0.298451f,0.125638f}, -{0.00329612f,0.297992f,0.125638f},{0.0048551f,0.29507f,0.125638f},{0.00523619f,0.294989f,0.125638f}, -{0.00781324f,0.302384f,0.125638f},{0.00430606f,0.299504f,0.125638f},{0.00356376f,0.289336f,0.125638f}, -{-0.00283752f,0.297591f,0.125638f},{-0.00329569f,0.297993f,0.125638f},{0.00178338f,0.296982f,0.125638f}, -{0.000608186f,0.296667f,0.125638f},{-2.76333e-017f,0.296628f,0.125638f},{-0.0034133f,0.294601f,0.125638f}, -{-0.00233082f,0.297253f,0.125638f},{-0.00295825f,0.293975f,0.125638f},{-0.00120688f,0.296787f,0.125638f}, -{-0.00315303f,0.294312f,0.125638f},{0.0176123f,0.299477f,0.125638f},{0.010376f,0.286942f,0.125638f}, -{0.00616972f,0.29212f,0.125638f},{0.00648443f,0.293604f,0.125638f},{0.00652539f,0.293216f,0.125638f}, -{0.00449528f,0.300083f,0.125638f},{0.00590766f,0.294602f,0.125638f},{0.00273651f,0.290775f,0.125638f}, -{0.00335595f,0.289852f,0.125638f},{0.00232523f,0.291153f,0.125638f},{0.00307294f,0.290333f,0.125638f}, -{0.00461789f,0.30068f,0.125638f},{0.00403651f,0.298958f,0.125638f},{0.00368758f,0.288793f,0.125638f}, -{0.00233031f,0.297252f,0.125638f},{-0.00060875f,0.296667f,0.125638f},{-0.00178418f,0.296983f,0.125638f}, -{-0.00781324f,0.300193f,0.125638f},{0.0216239f,0.295038f,0.12559f},{0.0211432f,0.293567f,0.12559f}, -{0.0217239f,0.293355f,0.125434f},{0.0192916f,0.285138f,0.12373f},{0.0203623f,0.286511f,0.12373f}, -{0.0200519f,0.286736f,0.12429f},{0.0210134f,0.288163f,0.12429f},{0.0213388f,0.28796f,0.12373f}, -{0.0186268f,0.285695f,0.124775f},{0.0181976f,0.286054f,0.125161f},{0.0175107f,0.284451f,0.124775f}, -{0.016671f,0.285259f,0.125434f},{0.0158563f,0.28381f,0.125232f},{0.0171072f,0.284839f,0.125161f}, -{0.0151138f,0.284628f,0.125592f},{0.0154952f,0.284208f,0.125455f},{0.0162253f,0.285687f,0.12559f}, -{0.0218746f,0.289655f,0.12429f},{0.0222133f,0.289475f,0.12373f},{0.0226291f,0.291201f,0.12429f}, -{0.0215683f,0.287817f,0.123126f},{0.0217015f,0.287733f,0.122512f},{0.0224522f,0.289348f,0.123126f}, -{0.021363f,0.287118f,0.121909f},{0.0222009f,0.288471f,0.121909f},{0.0207085f,0.28626f,0.122512f}, -{0.0204426f,0.28582f,0.121909f},{0.0196196f,0.284864f,0.122512f},{0.0225908f,0.289274f,0.122512f}, -{0.0229535f,0.289873f,0.121909f},{0.0183695f,0.283407f,0.121909f},{0.0194435f,0.284581f,0.121909f}, -{0.018444f,0.283554f,0.122512f},{0.0172245f,0.282302f,0.121909f},{0.0171931f,0.282336f,0.122497f}, -{0.02337f,0.290871f,0.122512f},{0.0236175f,0.291319f,0.121909f},{0.0240343f,0.292511f,0.122512f}, -{0.0241903f,0.292804f,0.121909f},{0.024671f,0.294321f,0.121909f},{0.0245807f,0.294183f,0.122512f}, -{0.0250097f,0.295875f,0.122497f},{0.024876f,0.295904f,0.123065f},{0.0229794f,0.291045f,0.12373f}, -{0.0181357f,0.28385f,0.12373f},{0.0189975f,0.285384f,0.12429f},{0.0250554f,0.295865f,0.121909f}, -{0.0232266f,0.290935f,0.123126f},{0.0233369f,0.294543f,0.124775f},{0.0235497f,0.296191f,0.124929f}, -{0.0227992f,0.294698f,0.125161f},{0.0239879f,0.296096f,0.124546f},{0.0238014f,0.294408f,0.12429f}, -{0.0209535f,0.290145f,0.125161f},{0.0216762f,0.291626f,0.125161f},{0.0211235f,0.291872f,0.125434f}, -{0.0219851f,0.29653f,0.125592f},{0.0244299f,0.294227f,0.123126f},{0.0246584f,0.295951f,0.123602f}, -{0.0241699f,0.294302f,0.12373f},{0.0238868f,0.292565f,0.123126f},{0.0205814f,0.286352f,0.123126f}, -{0.0194991f,0.284964f,0.123126f},{0.0183308f,0.283663f,0.123126f},{0.0171019f,0.282437f,0.123062f}, -{0.02436f,0.296016f,0.1241f},{0.0236326f,0.292658f,0.12373f},{0.0169523f,0.282602f,0.1236f}, -{0.0222178f,0.294866f,0.125434f},{0.0230629f,0.296296f,0.125233f},{0.0232723f,0.29279f,0.12429f}, -{0.0196606f,0.28702f,0.124775f},{0.0178592f,0.284116f,0.12429f},{0.0167476f,0.282827f,0.124098f}, -{0.0221874f,0.291398f,0.124775f},{0.0228181f,0.292956f,0.124775f},{0.0214477f,0.289882f,0.124775f}, -{0.0206034f,0.288419f,0.124775f},{0.0164907f,0.283111f,0.124546f},{0.0222924f,0.293148f,0.125161f}, -{0.0201286f,0.288716f,0.125161f},{0.0192076f,0.287349f,0.125161f},{0.0161909f,0.283441f,0.124927f}, -{0.0225375f,0.29641f,0.125456f},{0.0204192f,0.290429f,0.125434f},{0.0196153f,0.289036f,0.125434f}, -{0.0187178f,0.287705f,0.125434f},{0.0172595f,0.286839f,0.12559f},{0.0177335f,0.286443f,0.125434f}, -{0.0205588f,0.292124f,0.12559f},{0.0198733f,0.290719f,0.12559f},{0.019091f,0.289364f,0.12559f}, -{0.0182174f,0.288068f,0.12559f},{0.000885136f,0.275874f,0.123126f},{0.00261846f,0.276266f,0.12373f}, -{0.000875717f,0.276144f,0.12373f},{0.00441602f,0.276086f,0.122512f},{0.00266296f,0.275841f,0.122512f}, -{0.00264799f,0.27579f,0.121909f},{0.00257853f,0.276647f,0.12429f},{0.000884103f,0.275668f,0.121909f}, -{0.00609912f,0.276601f,0.123126f},{0.00613678f,0.276448f,0.122512f},{0.0077748f,0.277053f,0.123065f}, -{0.00612578f,0.276411f,0.121909f},{0.00781658f,0.276923f,0.122497f},{0.00539858f,0.279436f,0.12559f}, -{0.00388481f,0.279117f,0.12559f},{0.00399151f,0.278508f,0.125434f},{0.00783085f,0.276878f,0.121909f}, -{0.00439916f,0.276033f,0.121909f},{0.00749724f,0.277918f,0.124546f},{0.00582624f,0.277705f,0.124775f}, -{0.00594221f,0.277236f,0.12429f},{0.00246996f,0.277685f,0.125161f},{0.00240697f,0.278287f,0.125434f}, -{0.000826054f,0.27757f,0.125161f},{0.005692f,0.278249f,0.125161f},{0.00736026f,0.278345f,0.124929f}, -{0.000890602f,0.275717f,0.122512f},{0.00264662f,0.275997f,0.123126f},{-0.00427461f,0.276884f,0.12429f}, -{-0.00603421f,0.276863f,0.12373f},{-0.0043408f,0.276506f,0.12373f},{0.00687127f,0.279869f,0.125592f}, -{-0.000860185f,0.276528f,0.12429f},{-0.00261652f,0.276265f,0.12373f},{-0.000873503f,0.276144f,0.12373f}, -{0.000862365f,0.276528f,0.12429f},{-0.00582624f,0.277705f,0.124775f},{-0.00419119f,0.27736f,0.124775f}, -{-0.00409462f,0.277912f,0.125161f},{-0.00554685f,0.278836f,0.125434f},{-0.00720884f,0.278817f,0.125232f}, -{-0.005692f,0.278249f,0.125161f},{-0.00257663f,0.276647f,0.12429f},{-0.00687127f,0.279869f,0.125592f}, -{-0.00704464f,0.279329f,0.125455f},{-0.00539858f,0.279436f,0.12559f},{-0.00088835f,0.275717f,0.122512f}, -{-0.000882898f,0.275874f,0.123126f},{-0.000883894f,0.275668f,0.121909f},{-0.002661f,0.27584f,0.122512f}, -{-0.00264771f,0.27579f,0.121909f},{-0.00441458f,0.276085f,0.122512f},{-0.00439897f,0.276033f,0.121909f}, -{-0.00612769f,0.276402f,0.121909f},{-0.00613678f,0.276448f,0.122512f},{-0.00783085f,0.276878f,0.121909f}, -{0.00770679f,0.277265f,0.123602f},{0.00603421f,0.276863f,0.12373f},{0.00438891f,0.27624f,0.123126f}, -{-0.00264467f,0.275996f,0.123126f},{-0.00609912f,0.276601f,0.123126f},{-0.00438748f,0.27624f,0.123126f}, -{-0.00781658f,0.276923f,0.122497f},{-0.0077751f,0.277052f,0.123062f},{0.00761353f,0.277556f,0.1241f}, -{0.00434221f,0.276507f,0.12373f},{-0.00770709f,0.277264f,0.1236f},{0.00554685f,0.278836f,0.125434f}, -{0.00720812f,0.278819f,0.125233f},{0.004276f,0.276885f,0.12429f},{-0.00252634f,0.277128f,0.124775f}, -{-0.00594221f,0.277236f,0.12429f},{-0.00761404f,0.277554f,0.124098f},{0.00252821f,0.277128f,0.124775f}, -{0.00419255f,0.277361f,0.124775f},{0.000845536f,0.277011f,0.124775f},{-0.000843398f,0.277011f,0.124775f}, -{-0.00749724f,0.277918f,0.124546f},{0.00409595f,0.277912f,0.125161f},{-0.000823965f,0.27757f,0.125161f}, -{-0.00246814f,0.277685f,0.125161f},{-0.00736095f,0.278343f,0.124927f},{0.00704393f,0.279331f,0.125456f}, -{0.000804989f,0.278175f,0.125434f},{-0.000802953f,0.278175f,0.125434f},{-0.0024052f,0.278286f,0.125434f}, -{-0.00388354f,0.279117f,0.12559f},{-0.00399021f,0.278508f,0.125434f},{0.00234263f,0.278902f,0.12559f}, -{0.00078347f,0.278793f,0.12559f},{-0.000781489f,0.278793f,0.12559f},{-0.0023409f,0.278901f,0.12559f}, -{-0.0217002f,0.287732f,0.122512f},{-0.02058f,0.286351f,0.123126f},{-0.021567f,0.287815f,0.123126f}, -{-0.0207071f,0.286258f,0.122512f},{-0.0213629f,0.287118f,0.121909f},{-0.0204426f,0.28582f,0.121909f}, -{-0.020361f,0.28651f,0.12373f},{-0.0213375f,0.287958f,0.12373f},{-0.0200505f,0.286735f,0.12429f}, -{-0.0183308f,0.283663f,0.123126f},{-0.018444f,0.283554f,0.122512f},{-0.0171015f,0.282437f,0.123063f}, -{-0.0169508f,0.282603f,0.123604f},{-0.0172584f,0.286839f,0.12559f},{-0.0177324f,0.286442f,0.125434f}, -{-0.0162253f,0.285687f,0.12559f},{-0.0171936f,0.282336f,0.122494f},{-0.0183693f,0.283407f,0.121909f}, -{-0.0172245f,0.282302f,0.121909f},{-0.0196183f,0.284863f,0.122512f},{-0.0194434f,0.284581f,0.121909f}, -{-0.0171072f,0.284839f,0.125161f},{-0.0175107f,0.284451f,0.124775f},{-0.0161913f,0.283441f,0.124927f}, -{-0.0201275f,0.288714f,0.125161f},{-0.0192063f,0.287348f,0.125161f},{-0.0187165f,0.287703f,0.125434f}, -{-0.0151117f,0.284631f,0.125592f},{-0.0178592f,0.284116f,0.12429f},{-0.0164907f,0.283111f,0.124546f}, -{-0.0232721f,0.292788f,0.12429f},{-0.0241699f,0.294302f,0.12373f},{-0.0236324f,0.292657f,0.12373f}, -{-0.0210122f,0.288161f,0.12429f},{-0.0222178f,0.294866f,0.125434f},{-0.0230652f,0.296296f,0.125232f}, -{-0.0227992f,0.294698f,0.125161f},{-0.0224512f,0.289346f,0.123126f},{-0.0225899f,0.289272f,0.122512f}, -{-0.0233369f,0.294543f,0.124775f},{-0.0228179f,0.292954f,0.124775f},{-0.0222922f,0.293146f,0.125161f}, -{-0.0229789f,0.291043f,0.12373f},{-0.0226285f,0.291199f,0.12429f},{-0.0218736f,0.289653f,0.12429f}, -{-0.0222123f,0.289473f,0.12373f},{-0.0219851f,0.29653f,0.125592f},{-0.0225398f,0.29641f,0.125455f}, -{-0.0216239f,0.295038f,0.12559f},{-0.0222011f,0.288471f,0.121909f},{-0.0233694f,0.290869f,0.122512f}, -{-0.0229536f,0.289873f,0.121909f},{-0.0240341f,0.29251f,0.122512f},{-0.0236177f,0.291319f,0.121909f}, -{-0.0241882f,0.292804f,0.121909f},{-0.0245807f,0.294183f,0.122512f},{-0.0246627f,0.294323f,0.121909f}, -{-0.0250554f,0.295865f,0.121909f},{-0.0250097f,0.295875f,0.122497f},{-0.0181357f,0.28385f,0.12373f}, -{-0.0194979f,0.284964f,0.123126f},{-0.023226f,0.290933f,0.123126f},{-0.0238866f,0.292564f,0.123126f}, -{-0.0244299f,0.294227f,0.123126f},{-0.024877f,0.295904f,0.123062f},{-0.0167454f,0.28283f,0.124102f}, -{-0.0192904f,0.285137f,0.12373f},{-0.0246594f,0.295951f,0.1236f},{-0.016671f,0.285259f,0.125434f}, -{-0.0158556f,0.283811f,0.125233f},{-0.0189963f,0.285384f,0.12429f},{-0.0221869f,0.291396f,0.124775f}, -{-0.0238014f,0.294408f,0.12429f},{-0.0243617f,0.296015f,0.124098f},{-0.0196592f,0.287019f,0.124775f}, -{-0.0186256f,0.285694f,0.124775f},{-0.0206021f,0.288418f,0.124775f},{-0.0214468f,0.28988f,0.124775f}, -{-0.0239879f,0.296096f,0.124546f},{-0.0181964f,0.286053f,0.125161f},{-0.0209526f,0.290143f,0.125161f}, -{-0.0216757f,0.291624f,0.125161f},{-0.0235519f,0.296191f,0.124927f},{-0.0154922f,0.284211f,0.125456f}, -{-0.0196142f,0.289035f,0.125434f},{-0.0204183f,0.290427f,0.125434f},{-0.0211229f,0.291871f,0.125434f}, -{-0.021143f,0.293566f,0.12559f},{-0.0217237f,0.293354f,0.125434f},{-0.0182162f,0.288066f,0.12559f}, -{-0.0190899f,0.289362f,0.12559f},{-0.0198725f,0.290718f,0.12559f},{-0.0205583f,0.292122f,0.12559f}, -{-0.0225908f,0.313303f,0.122512f},{-0.0232266f,0.311642f,0.123126f},{-0.0224522f,0.313229f,0.123126f}, -{-0.02337f,0.311706f,0.122512f},{-0.0229794f,0.311532f,0.12373f},{-0.0222133f,0.313102f,0.12373f}, -{-0.0226291f,0.311376f,0.12429f},{-0.0244299f,0.308351f,0.123126f},{-0.0245807f,0.308394f,0.122512f}, -{-0.024876f,0.306673f,0.123065f},{-0.0246584f,0.306626f,0.123602f},{-0.0211432f,0.30901f,0.12559f}, -{-0.0217239f,0.309222f,0.125434f},{-0.0216239f,0.307539f,0.12559f},{-0.0250097f,0.306702f,0.122497f}, -{-0.0240343f,0.310066f,0.122512f},{-0.0227992f,0.307879f,0.125161f},{-0.0233369f,0.308035f,0.124775f}, -{-0.0235497f,0.306386f,0.124929f},{-0.0209535f,0.312432f,0.125161f},{-0.0216762f,0.310951f,0.125161f}, -{-0.0211235f,0.310705f,0.125434f},{-0.0219851f,0.306047f,0.125592f},{-0.0238014f,0.308169f,0.12429f}, -{-0.0239879f,0.306481f,0.124546f},{-0.0189975f,0.317193f,0.12429f},{-0.0181357f,0.318727f,0.12373f}, -{-0.0192916f,0.317439f,0.12373f},{-0.0218746f,0.312922f,0.12429f},{-0.016671f,0.317318f,0.125434f}, -{-0.0158576f,0.318769f,0.125231f},{-0.0171072f,0.317738f,0.125161f},{-0.0215683f,0.31476f,0.123126f}, -{-0.0217015f,0.314844f,0.122512f},{-0.0175107f,0.318126f,0.124775f},{-0.0186268f,0.316882f,0.124775f}, -{-0.0181976f,0.316523f,0.125161f},{-0.0203623f,0.316066f,0.12373f},{-0.0200519f,0.315841f,0.12429f}, -{-0.0210134f,0.314414f,0.12429f},{-0.0213388f,0.314617f,0.12373f},{-0.0151117f,0.317946f,0.125592f}, -{-0.0154943f,0.318368f,0.125455f},{-0.0162253f,0.31689f,0.12559f},{-0.0207085f,0.316317f,0.122512f}, -{-0.0196196f,0.317713f,0.122512f},{-0.018444f,0.319023f,0.122512f},{-0.0171936f,0.320241f,0.122494f}, -{-0.0241699f,0.308275f,0.12373f},{-0.0238868f,0.310012f,0.123126f},{-0.0205814f,0.316225f,0.123126f}, -{-0.0194991f,0.317613f,0.123126f},{-0.0183308f,0.318914f,0.123126f},{-0.0171022f,0.320141f,0.12306f}, -{-0.02436f,0.306561f,0.1241f},{-0.0236326f,0.309919f,0.12373f},{-0.0169519f,0.319975f,0.123601f}, -{-0.0222178f,0.307711f,0.125434f},{-0.0230629f,0.306281f,0.125233f},{-0.0232723f,0.309787f,0.12429f}, -{-0.0196606f,0.315557f,0.124775f},{-0.0178592f,0.318461f,0.12429f},{-0.0167464f,0.319748f,0.1241f}, -{-0.0221874f,0.311179f,0.124775f},{-0.0228181f,0.309621f,0.124775f},{-0.0214477f,0.312695f,0.124775f}, -{-0.0206034f,0.314158f,0.124775f},{-0.0164907f,0.319467f,0.124546f},{-0.0222924f,0.309429f,0.125161f}, -{-0.0201286f,0.313861f,0.125161f},{-0.0192076f,0.315228f,0.125161f},{-0.0161924f,0.319138f,0.124925f}, -{-0.0225375f,0.306167f,0.125456f},{-0.0204192f,0.312148f,0.125434f},{-0.0196153f,0.313541f,0.125434f}, -{-0.0187178f,0.314873f,0.125434f},{-0.0172595f,0.315738f,0.12559f},{-0.0177335f,0.316134f,0.125434f}, -{-0.0205588f,0.310453f,0.12559f},{-0.0198733f,0.311858f,0.12559f},{-0.019091f,0.313213f,0.12559f}, -{-0.0182174f,0.314509f,0.12559f},{-0.000885136f,0.326703f,0.123126f},{-0.00261846f,0.326311f,0.12373f}, -{-0.000875717f,0.326433f,0.12373f},{-0.00441602f,0.326491f,0.122512f},{-0.00266296f,0.326736f,0.122512f}, -{-0.00257853f,0.32593f,0.12429f},{-0.00609912f,0.325976f,0.123126f},{-0.00613678f,0.326129f,0.122512f}, -{-0.0077748f,0.325524f,0.123065f},{-0.00781658f,0.325654f,0.122497f},{-0.00539858f,0.323141f,0.12559f}, -{-0.00388481f,0.32346f,0.12559f},{-0.00399151f,0.324069f,0.125434f},{-0.00749724f,0.324659f,0.124546f}, -{-0.00582624f,0.324872f,0.124775f},{-0.00594221f,0.325341f,0.12429f},{-0.00246996f,0.324892f,0.125161f}, -{-0.00240697f,0.32429f,0.125434f},{-0.000826054f,0.325007f,0.125161f},{-0.005692f,0.324329f,0.125161f}, -{-0.00736026f,0.324232f,0.124929f},{-0.000890602f,0.32686f,0.122512f},{-0.00264662f,0.32658f,0.123126f}, -{0.00427461f,0.325693f,0.12429f},{0.00603421f,0.325714f,0.12373f},{0.0043408f,0.326071f,0.12373f}, -{-0.00687127f,0.322708f,0.125592f},{0.000860185f,0.326049f,0.12429f},{0.00261652f,0.326312f,0.12373f}, -{0.000873503f,0.326433f,0.12373f},{-0.000862365f,0.326049f,0.12429f},{0.00582624f,0.324872f,0.124775f}, -{0.00419119f,0.325217f,0.124775f},{0.00409462f,0.324665f,0.125161f},{0.00554685f,0.323741f,0.125434f}, -{0.00720884f,0.32376f,0.125232f},{0.005692f,0.324329f,0.125161f},{0.00257663f,0.32593f,0.12429f}, -{0.00687127f,0.322708f,0.125592f},{0.00704464f,0.323248f,0.125455f},{0.00539858f,0.323141f,0.12559f}, -{0.00088835f,0.32686f,0.122512f},{0.000882898f,0.326703f,0.123126f},{0.002661f,0.326737f,0.122512f}, -{0.00441458f,0.326492f,0.122512f},{0.00613678f,0.326129f,0.122512f},{-0.00770679f,0.325312f,0.123602f}, -{-0.00603421f,0.325714f,0.12373f},{-0.00438891f,0.326337f,0.123126f},{0.00264467f,0.326581f,0.123126f}, -{0.00609912f,0.325976f,0.123126f},{0.00438748f,0.326337f,0.123126f},{0.00781658f,0.325654f,0.122497f}, -{0.0077751f,0.325525f,0.123062f},{-0.00761353f,0.325021f,0.1241f},{-0.00434221f,0.32607f,0.12373f}, -{0.00770709f,0.325313f,0.1236f},{-0.00554685f,0.323741f,0.125434f},{-0.00720812f,0.323758f,0.125233f}, -{-0.004276f,0.325692f,0.12429f},{0.00252634f,0.325449f,0.124775f},{0.00594221f,0.325341f,0.12429f}, -{0.00761404f,0.325023f,0.124098f},{-0.00252821f,0.325449f,0.124775f},{-0.00419255f,0.325216f,0.124775f}, -{-0.000845536f,0.325566f,0.124775f},{0.000843398f,0.325566f,0.124775f},{0.00749724f,0.324659f,0.124546f}, -{-0.00409595f,0.324665f,0.125161f},{0.000823965f,0.325007f,0.125161f},{0.00246814f,0.324892f,0.125161f}, -{0.00736095f,0.324234f,0.124927f},{-0.00704393f,0.323246f,0.125456f},{-0.000804989f,0.324402f,0.125434f}, -{0.000802953f,0.324402f,0.125434f},{0.0024052f,0.324291f,0.125434f},{0.00388354f,0.32346f,0.12559f}, -{0.00399021f,0.324069f,0.125434f},{-0.00234263f,0.323675f,0.12559f},{-0.00078347f,0.323784f,0.12559f}, -{0.000781489f,0.323784f,0.12559f},{0.0023409f,0.323676f,0.12559f},{0.0217002f,0.314846f,0.122512f}, -{0.02058f,0.316226f,0.123126f},{0.021567f,0.314762f,0.123126f},{0.0207071f,0.316319f,0.122512f}, -{0.020361f,0.316067f,0.12373f},{0.0213375f,0.314619f,0.12373f},{0.0200505f,0.315842f,0.12429f}, -{0.0183308f,0.318914f,0.123126f},{0.018444f,0.319023f,0.122512f},{0.0171012f,0.320139f,0.123065f}, -{0.0169516f,0.319975f,0.123602f},{0.0172584f,0.315738f,0.12559f},{0.0177324f,0.316135f,0.125434f}, -{0.0162253f,0.31689f,0.12559f},{0.0171931f,0.320241f,0.122497f},{0.0196183f,0.317714f,0.122512f}, -{0.0171072f,0.317738f,0.125161f},{0.0175107f,0.318126f,0.124775f},{0.0161894f,0.319134f,0.124929f}, -{0.0201275f,0.313863f,0.125161f},{0.0192063f,0.315229f,0.125161f},{0.0187165f,0.314874f,0.125434f}, -{0.0151138f,0.317949f,0.125592f},{0.0178592f,0.318461f,0.12429f},{0.0164907f,0.319467f,0.124546f}, -{0.0232721f,0.309789f,0.12429f},{0.0241699f,0.308275f,0.12373f},{0.0236324f,0.30992f,0.12373f}, -{0.0210122f,0.314416f,0.12429f},{0.0222178f,0.307711f,0.125434f},{0.0230652f,0.306281f,0.125232f}, -{0.0227992f,0.307879f,0.125161f},{0.0224512f,0.313231f,0.123126f},{0.0225899f,0.313305f,0.122512f}, -{0.0233369f,0.308035f,0.124775f},{0.0228179f,0.309623f,0.124775f},{0.0222922f,0.309431f,0.125161f}, -{0.0229789f,0.311534f,0.12373f},{0.0226285f,0.311378f,0.12429f},{0.0218736f,0.312924f,0.12429f}, -{0.0222123f,0.313104f,0.12373f},{0.0219851f,0.306047f,0.125592f},{0.0225398f,0.306167f,0.125455f}, -{0.0216239f,0.307539f,0.12559f},{0.0233694f,0.311708f,0.122512f},{0.0240341f,0.310067f,0.122512f}, -{0.0245807f,0.308394f,0.122512f},{0.0250097f,0.306702f,0.122497f},{0.0181357f,0.318727f,0.12373f}, -{0.0194979f,0.317614f,0.123126f},{0.023226f,0.311644f,0.123126f},{0.0238866f,0.310013f,0.123126f}, -{0.0244299f,0.308351f,0.123126f},{0.024877f,0.306673f,0.123062f},{0.0167465f,0.319748f,0.1241f}, -{0.0192904f,0.31744f,0.12373f},{0.0246594f,0.306626f,0.1236f},{0.016671f,0.317318f,0.125434f}, -{0.0158548f,0.318766f,0.125233f},{0.0189963f,0.317194f,0.12429f},{0.0221869f,0.311181f,0.124775f}, -{0.0238014f,0.308169f,0.12429f},{0.0243617f,0.306562f,0.124098f},{0.0196592f,0.315558f,0.124775f}, -{0.0186256f,0.316883f,0.124775f},{0.0206021f,0.31416f,0.124775f},{0.0214468f,0.312697f,0.124775f}, -{0.0239879f,0.306481f,0.124546f},{0.0181964f,0.316524f,0.125161f},{0.0209526f,0.312434f,0.125161f}, -{0.0216757f,0.310953f,0.125161f},{0.0235519f,0.306387f,0.124927f},{0.0154936f,0.318367f,0.125456f}, -{0.0196142f,0.313542f,0.125434f},{0.0204183f,0.31215f,0.125434f},{0.0211229f,0.310707f,0.125434f}, -{0.021143f,0.309011f,0.12559f},{0.0217237f,0.309223f,0.125434f},{0.0182162f,0.314511f,0.12559f}, -{0.0190899f,0.313215f,0.12559f},{0.0198725f,0.31186f,0.12559f},{0.0205583f,0.310455f,0.12559f}, -{0.00414391f,0.295088f,0.100469f},{0.00139737f,0.298869f,0.100469f},{0.00179665f,0.299148f,0.100469f}, -{0.00285439f,0.294399f,0.100469f},{0.00351607f,0.294712f,0.100469f},{0.00216513f,0.294152f,0.100469f}, -{0.000956049f,0.298662f,0.100469f},{0.0047319f,0.295524f,0.100469f},{0.00527427f,0.296015f,0.100469f}, -{0.00145499f,0.293974f,0.100469f},{0.000485772f,0.298534f,0.100469f},{0.00214182f,0.299492f,0.100469f}, -{0.00576579f,0.296558f,0.100469f},{0.000730938f,0.293867f,0.100469f},{-2.55116e-017f,0.298492f,0.100469f}, -{0.00620174f,0.297145f,0.100469f},{0.00242194f,0.299891f,0.100469f},{-2.64948e-017f,0.293831f,0.100469f}, -{-0.000731236f,0.293867f,0.100469f},{-0.00145532f,0.293975f,0.100469f},{-0.000485107f,0.298534f,0.100469f}, -{-0.00216527f,0.294153f,0.100469f},{-0.000955564f,0.29866f,0.100469f},{0.00689072f,0.298435f,0.100469f}, -{0.00657793f,0.297773f,0.100469f},{-0.00351606f,0.294712f,0.100469f},{-0.00285433f,0.294399f,0.100469f}, -{0.00713697f,0.299124f,0.100469f},{0.00262754f,0.300333f,0.100469f},{0.00275363f,0.300804f,0.100469f}, -{-0.00139499f,0.298869f,0.100469f},{0.00742217f,0.300558f,0.100469f},{0.00731456f,0.299834f,0.100469f}, -{-0.00214373f,0.299488f,0.100469f},{-0.00178917f,0.299157f,0.100469f},{-0.00527358f,0.296016f,0.100469f}, -{-0.00657692f,0.297774f,0.100469f},{-0.00688983f,0.298435f,0.100469f},{-0.00262887f,0.300331f,0.100469f}, -{-0.00275512f,0.300803f,0.100469f},{-0.00742136f,0.300558f,0.100469f},{-0.0071365f,0.299124f,0.100469f}, -{-0.00731416f,0.299834f,0.100469f},{-0.00473148f,0.295525f,0.100469f},{-0.00414378f,0.295088f,0.100469f}, -{-0.00620074f,0.297146f,0.100469f},{-0.00242212f,0.29989f,0.100469f},{-0.0057649f,0.296559f,0.100469f}, -{0.00060826f,0.31345f,0.101401f},{0.00178435f,0.313762f,0.101401f},{0.002331f,0.314032f,0.101401f}, -{0.00216527f,0.294153f,0.101401f},{0.00536018f,0.290568f,0.101401f},{0.00742136f,0.300558f,0.101401f}, -{0.0121618f,0.30068f,0.101401f},{0.0071365f,0.299124f,0.101401f},{0.0127432f,0.298958f,0.101401f}, -{0.00688983f,0.298435f,0.101401f},{0.00403701f,0.315738f,0.101401f},{0.00430572f,0.319852f,0.101401f}, -{0.014297f,0.288187f,0.101401f},{-0.00279832f,0.322545f,0.101401f},{0.0214014f,0.30068f,0.101401f}, -{-0.00689197f,0.321591f,0.101401f},{-0.00820481f,0.321097f,0.101401f},{0.021279f,0.300083f,0.101401f}, -{0.0210836f,0.299506f,0.101401f},{0.0134836f,0.297992f,0.101401f},{0.00657692f,0.297774f,0.101401f}, -{0.0130817f,0.298451f,0.101401f},{-0.00893219f,0.289809f,0.101401f},{-0.00372602f,0.28731f,0.101401f}, -{-0.00406291f,0.286794f,0.101401f},{0.0208166f,0.298958f,0.101401f},{0.0200754f,0.297993f,0.101401f}, -{0.0204775f,0.298452f,0.101401f},{0.0196172f,0.297591f,0.101401f},{0.0139105f,0.290011f,0.101401f}, -{0.0141391f,0.289696f,0.101401f},{-0.00216513f,0.294152f,0.101401f},{-0.00235358f,0.288532f,0.101401f}, -{-0.00285439f,0.294399f,0.101401f},{0.0191105f,0.297253f,0.101401f},{0.0185639f,0.296983f,0.101401f}, -{0.0167797f,0.296628f,0.101401f},{0.0173884f,0.296667f,0.101401f},{0.0179866f,0.296787f,0.101401f}, -{-0.0141364f,0.317409f,0.101401f},{-0.00948265f,0.320518f,0.101401f},{-0.00121835f,0.289001f,0.101401f}, -{-0.00145499f,0.293974f,0.101401f},{-0.000730938f,0.293867f,0.101401f},{0.0161715f,0.296667f,0.101401f}, -{-0.00180244f,0.288807f,0.101401f},{0.00620074f,0.297146f,0.101401f},{-0.00286368f,0.288187f,0.101401f}, -{0.0143784f,0.288958f,0.101401f},{-0.0107514f,0.313236f,0.101401f},{-0.0109097f,0.31288f,0.101401f}, -{-0.00140229f,0.322684f,0.101401f},{0.00329545f,0.321364f,0.101401f},{0.00369728f,0.320906f,0.101401f}, -{0.0057649f,0.296559f,0.101401f},{0.00466102f,0.318068f,0.101401f},{0.00462104f,0.318677f,0.101401f}, -{0.00731416f,0.299834f,0.101401f},{0.0124736f,0.299504f,0.101401f},{0.0121612f,0.310903f,0.101401f}, -{0.0109346f,0.310012f,0.101401f},{0.0113045f,0.310132f,0.101401f},{0.0123195f,0.311258f,0.101401f}, -{0.0116418f,0.310326f,0.101401f},{0.0119314f,0.310587f,0.101401f},{0.0136206f,0.290272f,0.101401f}, -{0.0136193f,0.287256f,0.101401f},{0.013282f,0.287061f,0.101401f},{0.013283f,0.290467f,0.101401f}, -{0.0155736f,0.296786f,0.101401f},{0.00473148f,0.295525f,0.101401f},{0.00527358f,0.296016f,0.101401f}, -{-0.0170097f,0.314341f,0.101401f},{-0.00751912f,0.281209f,0.101401f},{-0.00885348f,0.281761f,0.101401f}, -{-0.00460913f,0.283816f,0.101401f},{0.00285433f,0.294399f,0.101401f},{0.00351606f,0.294712f,0.101401f}, -{0.000731236f,0.293867f,0.101401f},{0.00145532f,0.293975f,0.101401f},{-0.0151604f,0.31645f,0.101401f}, -{-0.0161195f,0.315426f,0.101401f},{-0.0124736f,0.303073f,0.101401f},{-0.0122844f,0.302494f,0.101401f}, -{-2.64948e-017f,0.293831f,0.101401f},{-0.0043287f,0.286238f,0.101401f},{-0.00916198f,0.289494f,0.101401f}, -{-0.0107204f,0.306649f,0.101401f},{-0.00869272f,0.290546f,0.101401f},{-0.00332386f,0.287777f,0.101401f}, -{-0.017827f,0.313201f,0.101401f},{-0.00731456f,0.299834f,0.101401f},{-0.00713697f,0.299124f,0.101401f}, -{-0.00742217f,0.300558f,0.101401f},{-0.0196172f,0.304986f,0.101401f},{-0.0200754f,0.304584f,0.101401f}, -{-0.0210285f,0.305472f,0.101401f},{-0.0158194f,0.286816f,0.101401f},{-0.0167576f,0.287913f,0.101401f}, -{-0.0176198f,0.289072f,0.101401f},{-0.00462997f,0.285046f,0.101401f},{-0.0101477f,0.282401f,0.101401f}, -{-0.0125926f,0.283935f,0.101401f},{-0.013732f,0.284822f,0.101401f},{-0.00466034f,0.28443f,0.101401f}, -{-0.00426727f,0.282635f,0.101401f},{-0.00615062f,0.280749f,0.101401f},{-0.00447731f,0.283214f,0.101401f}, -{-0.00165506f,0.280155f,0.101401f},{-0.00190339f,0.27993f,0.101401f},{-0.0022162f,0.280408f,0.101401f}, -{-0.00362862f,0.281584f,0.101401f},{-0.00475417f,0.280381f,0.101401f},{-0.00398274f,0.282088f,0.101401f}, -{-0.00321095f,0.281131f,0.101401f},{-0.00273734f,0.280737f,0.101401f},{-0.00333373f,0.280122f,0.101401f}, -{-0.00106651f,0.279974f,0.101401f},{-0.000459362f,0.27987f,0.101401f},{-0.0101588f,0.288918f,0.101401f}, -{-0.011396f,0.283127f,0.101401f},{-0.0148092f,0.285784f,0.101401f},{-0.0184021f,0.290285f,0.101401f}, -{-0.0212465f,0.298409f,0.101401f},{-0.0210045f,0.296985f,0.101401f},{-0.0206672f,0.295581f,0.101401f}, -{0.0122844f,0.300083f,0.101401f},{-0.0047319f,0.295524f,0.101401f},{-0.00893177f,0.291673f,0.101401f}, -{-0.00916039f,0.291988f,0.101401f},{-0.019101f,0.291549f,0.101401f},{-0.00978889f,0.289038f,0.101401f}, -{-0.0213921f,0.299845f,0.101401f},{-0.0111395f,0.312564f,0.101401f},{-0.0114291f,0.312304f,0.101401f}, -{-0.00576579f,0.296558f,0.101401f},{-0.00527427f,0.296015f,0.101401f},{-0.00945026f,0.29225f,0.101401f}, -{-0.00978794f,0.292445f,0.101401f},{-0.0101578f,0.292565f,0.101401f},{-0.00620174f,0.297145f,0.101401f}, -{-0.00877329f,0.291317f,0.101401f},{-0.00414391f,0.295088f,0.101401f},{-0.00351607f,0.294712f,0.101401f}, -{-0.0045188f,0.285652f,0.101401f},{-0.0094516f,0.289233f,0.101401f},{-0.000614697f,0.289126f,0.101401f}, -{0.0139422f,0.29759f,0.101401f},{0.00414378f,0.295088f,0.101401f},{0.0144494f,0.297252f,0.101401f}, -{0.0124009f,0.312029f,0.101401f},{0.011933f,0.313082f,0.101401f},{0.00430656f,0.316285f,0.101401f}, -{0.00178272f,0.322372f,0.101401f},{-0.00418236f,0.322315f,0.101401f},{-0.0106702f,0.313617f,0.101401f}, -{-0.00554911f,0.321998f,0.101401f},{-0.0130817f,0.304126f,0.101401f},{-0.0134836f,0.304585f,0.101401f}, -{-0.013052f,0.318299f,0.101401f},{-0.0185679f,0.312009f,0.101401f},{-0.0203026f,0.308181f,0.101401f}, -{-0.0185639f,0.305594f,0.101401f},{-0.0207099f,0.306838f,0.101401f},{-0.00689072f,0.298435f,0.101401f}, -{-0.0119116f,0.319116f,0.101401f},{-0.0117654f,0.315516f,0.101401f},{-0.0121353f,0.315636f,0.101401f}, -{-0.0192293f,0.310772f,0.101401f},{-0.0149963f,0.305595f,0.101401f},{-0.0121618f,0.301897f,0.101401f}, -{-0.0109093f,0.314744f,0.101401f},{-0.0111379f,0.315059f,0.101401f},{-0.0106699f,0.314007f,0.101401f}, -{-0.01072f,0.319857f,0.101401f},{-0.0114278f,0.315321f,0.101401f},{0.00120563f,0.313573f,0.101401f}, -{0.0116431f,0.313343f,0.101401f},{0.0113054f,0.313538f,0.101401f},{0.0124007f,0.311639f,0.101401f}, -{0.00462115f,0.31746f,0.101401f},{0.00283787f,0.31437f,0.101401f},{0.00329614f,0.314772f,0.101401f}, -{0.00369829f,0.315231f,0.101401f},{0.0123201f,0.312411f,0.101401f},{0.0121616f,0.312767f,0.101401f}, -{0.0109356f,0.313659f,0.101401f},{0.0149963f,0.296982f,0.101401f},{0.0129131f,0.290588f,0.101401f}, -{0.0129121f,0.286941f,0.101401f},{0.0139089f,0.287516f,0.101401f},{0.0141387f,0.287832f,0.101401f}, -{0.0143782f,0.288568f,0.101401f},{0.0142976f,0.28934f,0.101401f},{-0.0202361f,0.294203f,0.101401f}, -{-0.0197133f,0.292857f,0.101401f},{-0.00869244f,0.290936f,0.101401f},{-0.00877392f,0.290165f,0.101401f}, -{-0.00657793f,0.297773f,0.101401f},{-0.0107508f,0.314388f,0.101401f},{0.00450236f,0.316862f,0.101401f}, -{0.00450189f,0.319275f,0.101401f},{0.00403597f,0.320399f,0.101401f},{0.00283697f,0.321766f,0.101401f}, -{0.00233026f,0.322105f,0.101401f},{0.0006084f,0.32269f,0.101401f},{0.00120559f,0.322568f,0.101401f}, -{-0.0210836f,0.303071f,0.101401f},{-0.0213948f,0.302691f,0.101401f},{-0.0212572f,0.304087f,0.101401f}, -{-0.0198084f,0.309494f,0.101401f},{-0.0167797f,0.30595f,0.101401f},{-0.0173884f,0.30591f,0.101401f}, -{-0.0161715f,0.30591f,0.101401f},{-0.0127432f,0.30362f,0.101401f},{-0.0155736f,0.305791f,0.101401f}, -{-0.0139422f,0.304987f,0.101401f},{-0.0144494f,0.305326f,0.101401f},{-0.0121363f,0.311989f,0.101401f}, -{-0.0117664f,0.312109f,0.101401f},{-0.0179866f,0.30579f,0.101401f},{-0.0191105f,0.305324f,0.101401f}, -{-0.0204775f,0.304126f,0.101401f},{-0.0208166f,0.303619f,0.101401f},{-0.0214014f,0.301897f,0.101401f}, -{-0.021279f,0.302494f,0.101401f},{0.0220868f,0.288274f,0.120045f},{0.0197356f,0.284927f,0.120045f}, -{-0.0164263f,0.321574f,0.120045f},{-0.0174654f,0.320686f,0.120045f},{0.0227481f,0.289468f,0.120045f}, -{-0.0130507f,0.323894f,0.120045f},{-0.0142159f,0.32318f,0.120045f},{0.0243386f,0.293237f,0.120045f}, -{-0.00935393f,0.325657f,0.120045f},{-0.0106164f,0.325134f,0.120045f},{0.0253094f,0.297211f,0.120045f}, -{-0.00542685f,0.32682f,0.120045f},{-0.00408328f,0.327069f,0.120045f},{-0.0067556f,0.326501f,0.120045f}, -{-0.00806585f,0.326113f,0.120045f},{-0.00136583f,0.327346f,0.120045f},{-0.00272847f,0.327247f,0.120045f}, -{0.025591f,0.299924f,0.120045f},{0.0254905f,0.298564f,0.120045f},{-0.0118498f,0.324546f,0.120045f}, -{0.0247326f,0.294544f,0.120045f},{0.0250564f,0.29587f,0.120045f},{-0.0153421f,0.322406f,0.120045f}, -{0.0233448f,0.290696f,0.120045f},{0.0238755f,0.291953f,0.120045f},{-0.0184567f,0.319746f,0.120045f}, -{-0.0193973f,0.318754f,0.120045f},{0.0213629f,0.287117f,0.120045f},{-0.0202847f,0.317715f,0.120045f}, -{-0.0211166f,0.316631f,0.120045f},{-0.0218906f,0.315505f,0.120045f},{0.0205784f,0.286f,0.120045f}, -{-0.0226048f,0.31434f,0.120045f},{-0.0232569f,0.313139f,0.120045f},{0.0188369f,0.2839f,0.120045f}, -{-0.0238452f,0.311905f,0.120045f},{0.0178847f,0.282922f,0.120045f},{-0.0243681f,0.310643f,0.120045f}, -{0.0168818f,0.281996f,0.120045f},{-0.0248242f,0.309355f,0.120045f},{0.0158311f,0.281125f,0.120045f}, -{-0.0252123f,0.308044f,0.120045f},{0.0147355f,0.280311f,0.120045f},{-0.0255314f,0.306715f,0.120045f}, -{0.0135981f,0.279557f,0.120045f},{-0.0257804f,0.305372f,0.120045f},{0.0124222f,0.278863f,0.120045f}, -{-0.0259588f,0.304017f,0.120045f},{0.011211f,0.278234f,0.120045f},{-0.0260659f,0.302655f,0.120045f}, -{0.00996802f,0.27767f,0.120045f},{-0.0261017f,0.301289f,0.120045f},{0.00869678f,0.277173f,0.120045f}, -{-0.0255903f,0.299924f,0.120045f},{-0.0260659f,0.299922f,0.120045f},{0.00740092f,0.276744f,0.120045f}, -{-0.0254908f,0.298564f,0.120045f},{-0.0259586f,0.29856f,0.120045f},{0.00608407f,0.276385f,0.120045f}, -{-0.0253091f,0.297211f,0.120045f},{-0.0257802f,0.297205f,0.120045f},{0.00474994f,0.276097f,0.120045f}, -{0.00340235f,0.27588f,0.120045f},{0.000682229f,0.275662f,0.120045f},{-0.0250563f,0.29587f,0.120045f}, -{-0.0255311f,0.295861f,0.120045f},{-0.00272834f,0.27533f,0.120045f},{-0.00340291f,0.27588f,0.120045f}, -{-0.00408304f,0.275508f,0.120045f},{-0.0238754f,0.291954f,0.120045f},{-0.0243383f,0.293238f,0.120045f}, -{-0.0243677f,0.291934f,0.120045f},{-0.00675524f,0.276076f,0.120045f},{-0.00740123f,0.276745f,0.120045f}, -{-0.00806539f,0.276464f,0.120045f},{-0.0226042f,0.288237f,0.120045f},{-0.0227481f,0.289469f,0.120045f}, -{-0.0232562f,0.289438f,0.120045f},{-0.0118493f,0.278031f,0.120045f},{-0.010616f,0.277443f,0.120045f}, -{-0.011211f,0.278235f,0.120045f},{-0.0202843f,0.284862f,0.120045f},{-0.0205783f,0.286001f,0.120045f}, -{-0.0211162f,0.285946f,0.120045f},{-0.0164256f,0.281003f,0.120045f},{-0.0168818f,0.281997f,0.120045f}, -{-0.0174647f,0.281891f,0.120045f},{-0.0130502f,0.278684f,0.120045f},{-0.0124221f,0.278864f,0.120045f}, -{-0.0188368f,0.2839f,0.120045f},{-0.0193967f,0.283823f,0.120045f},{-0.018456f,0.282831f,0.120045f}, -{-0.0178847f,0.282922f,0.120045f},{-0.0153414f,0.280172f,0.120045f},{-0.0142153f,0.279398f,0.120045f}, -{-0.0147355f,0.280311f,0.120045f},{-0.0135981f,0.279557f,0.120045f},{-0.0197355f,0.284928f,0.120045f}, -{-0.0158312f,0.281125f,0.120045f},{-0.00869705f,0.277173f,0.120045f},{-0.00935349f,0.27692f,0.120045f}, -{-0.00996818f,0.277671f,0.120045f},{-0.0220867f,0.288275f,0.120045f},{-0.0218902f,0.287072f,0.120045f}, -{-0.0213628f,0.287118f,0.120045f},{-0.00475041f,0.276097f,0.120045f},{-0.00542662f,0.275757f,0.120045f}, -{-0.00608443f,0.276386f,0.120045f},{-0.0233449f,0.290696f,0.120045f},{-0.0238446f,0.290671f,0.120045f}, -{-0.000682695f,0.275662f,0.120045f},{-0.00136576f,0.275232f,0.120045f},{-0.00204572f,0.275735f,0.120045f}, -{-0.0252122f,0.294532f,0.120045f},{-0.0247324f,0.294544f,0.120045f},{-0.024824f,0.293222f,0.120045f}, -{0.00204515f,0.275735f,0.120045f},{-0.00544975f,0.275762f,0.106062f},{-0.00410773f,0.275512f,0.106062f}, -{-0.00275036f,0.275332f,0.106062f},{-0.00935782f,0.276922f,0.106062f},{-0.00677384f,0.276081f,0.106062f}, -{-0.0141962f,0.279385f,0.106062f},{-0.0130343f,0.278674f,0.106062f},{-0.0118389f,0.278026f,0.106062f}, -{-0.0106125f,0.277442f,0.106062f},{-0.0174549f,0.281882f,0.106062f},{-0.015322f,0.280157f,0.106062f}, -{-0.0211314f,0.285966f,0.106062f},{-0.0202988f,0.284879f,0.106062f},{-0.0194069f,0.283834f,0.106062f}, -{-0.0184567f,0.282832f,0.106062f},{-0.0232623f,0.289449f,0.106062f},{-0.0219036f,0.287092f,0.106062f}, -{-0.0252074f,0.294514f,0.106062f},{-0.0248204f,0.293211f,0.106062f},{-0.0243664f,0.29193f,0.106062f}, -{-0.0238467f,0.290676f,0.106062f},{-0.0257765f,0.297181f,0.106062f},{-0.0259565f,0.298538f,0.106062f}, -{-0.0255265f,0.295839f,0.106062f},{-0.0260653f,0.302669f,0.106062f},{-0.0261017f,0.301289f,0.106062f}, -{-0.0260652f,0.299908f,0.106062f},{-0.0255265f,0.306738f,0.106062f},{-0.0257766f,0.305396f,0.106062f}, -{-0.0259565f,0.304039f,0.106062f},{-0.0248205f,0.309366f,0.106062f},{-0.0252075f,0.308062f,0.106062f}, -{-0.0238468f,0.311901f,0.106062f},{-0.0232624f,0.313127f,0.106062f},{-0.0243666f,0.310646f,0.106062f}, -{-0.0219036f,0.315485f,0.106062f},{-0.0226143f,0.314323f,0.106062f},{-0.0202989f,0.317698f,0.106062f}, -{-0.0211315f,0.316611f,0.106062f},{-0.0184567f,0.319745f,0.106062f},{-0.0194069f,0.318743f,0.106062f}, -{-0.0174549f,0.320695f,0.106062f},{-0.0164092f,0.321587f,0.106062f},{-0.0153222f,0.32242f,0.106062f}, -{-0.0141964f,0.323192f,0.106062f},{-0.0130346f,0.323903f,0.106062f},{-0.0118391f,0.324551f,0.106062f}, -{-0.0106128f,0.325135f,0.106062f},{-0.00935809f,0.325655f,0.106062f},{-0.00807765f,0.326109f,0.106062f}, -{-0.00677408f,0.326496f,0.106062f},{-0.00544996f,0.326815f,0.106062f},{-0.0041079f,0.327065f,0.106062f}, -{-0.00275048f,0.327245f,0.106062f},{-0.00138032f,0.327354f,0.106062f},{-0.0226142f,0.288254f,0.106062f}, -{-0.0164091f,0.28099f,0.106062f},{-0.0080774f,0.276468f,0.106062f},{-0.00138025f,0.275223f,0.106062f}, -{-0.0164242f,0.287507f,0.106062f},{-0.0128032f,0.28409f,0.106062f},{-0.00849194f,0.281601f,0.106062f}, -{-0.00372282f,0.280175f,0.106062f},{-0.00124674f,0.279884f,0.106062f},{-0.00248901f,0.279994f,0.106062f}, -{-0.00733302f,0.281141f,0.106062f},{-0.00962222f,0.282129f,0.106062f},{-0.01072f,0.28272f,0.106062f}, -{-0.0117816f,0.283375f,0.106062f},{-0.0155951f,0.286575f,0.106062f},{-0.0147132f,0.285693f,0.106062f}, -{-0.0137815f,0.284864f,0.106062f},{-0.0185679f,0.290568f,0.106062f},{-0.0179131f,0.289506f,0.106062f}, -{-0.0171977f,0.288485f,0.106062f},{-0.0191599f,0.291666f,0.106062f},{-0.0196869f,0.292796f,0.106062f}, -{-0.0201474f,0.293955f,0.106062f},{-0.0205397f,0.295139f,0.106062f},{-0.0208625f,0.296344f,0.106062f}, -{-0.0211148f,0.297565f,0.106062f},{-0.0212956f,0.298799f,0.106062f},{-0.0214044f,0.300042f,0.106062f}, -{-0.0214407f,0.301289f,0.106062f},{-0.0214044f,0.302535f,0.106062f},{-0.0212958f,0.303778f,0.106062f}, -{-0.021115f,0.305012f,0.106062f},{-0.0208629f,0.306233f,0.106062f},{-0.0205401f,0.307438f,0.106062f}, -{-0.0201478f,0.308622f,0.106062f},{-0.0196872f,0.309781f,0.106062f},{-0.0185682f,0.312009f,0.106062f}, -{-0.00248899f,0.322581f,0.106062f},{-0.00124708f,0.322694f,0.106062f},{-0.0164246f,0.315071f,0.106062f}, -{-0.00494506f,0.322151f,0.106062f},{-0.00614966f,0.321828f,0.106062f},{-0.0137818f,0.317713f,0.106062f}, -{-0.0147135f,0.316884f,0.106062f},{-0.0107205f,0.319857f,0.106062f},{-0.0117819f,0.319202f,0.106062f}, -{-0.0128035f,0.318487f,0.106062f},{-0.00849255f,0.320976f,0.106062f},{-0.00733349f,0.321436f,0.106062f}, -{-0.00962282f,0.320449f,0.106062f},{-0.00372197f,0.322394f,0.106062f},{-0.0155954f,0.316002f,0.106062f}, -{-0.0179135f,0.313071f,0.106062f},{-0.0171982f,0.314092f,0.106062f},{-0.0191601f,0.310911f,0.106062f}, -{-0.00494408f,0.280428f,0.106062f},{-0.00614928f,0.280748f,0.106062f},{-0.00496191f,0.28043f,0.10513f}, -{-0.00374312f,0.280177f,0.10513f},{-0.00250793f,0.279995f,0.10513f},{-0.00849036f,0.281601f,0.10513f}, -{-0.00616138f,0.280752f,0.10513f},{-0.0127873f,0.284078f,0.10513f},{-0.0117655f,0.283364f,0.10513f}, -{-0.0107068f,0.282713f,0.10513f},{-0.00961408f,0.282124f,0.10513f},{-0.0155998f,0.28658f,0.10513f}, -{-0.0137691f,0.284853f,0.10513f},{-0.018576f,0.290582f,0.10513f},{-0.0179242f,0.289523f,0.10513f}, -{-0.0172102f,0.288501f,0.10513f},{-0.0201457f,0.29395f,0.10513f},{-0.0196879f,0.292798f,0.10513f}, -{-0.0191643f,0.291674f,0.10513f},{-0.0212935f,0.29878f,0.10513f},{-0.0211114f,0.297545f,0.10513f}, -{-0.0208586f,0.296326f,0.10513f},{-0.0205363f,0.295127f,0.10513f},{-0.0214407f,0.301289f,0.10513f}, -{-0.0214037f,0.302548f,0.10513f},{-0.0214037f,0.300029f,0.10513f},{-0.0211115f,0.305032f,0.10513f}, -{-0.0212936f,0.303796f,0.10513f},{-0.0201457f,0.308627f,0.10513f},{-0.0205363f,0.30745f,0.10513f}, -{-0.0208587f,0.30625f,0.10513f},{-0.0191643f,0.310903f,0.10513f},{-0.019688f,0.309779f,0.10513f}, -{-0.0172102f,0.314076f,0.10513f},{-0.0179243f,0.313054f,0.10513f},{-0.018576f,0.311995f,0.10513f}, -{-0.0156004f,0.315997f,0.10513f},{-0.0164352f,0.315058f,0.10513f},{-0.0147088f,0.316888f,0.10513f}, -{-0.0137693f,0.317724f,0.10513f},{-0.0127873f,0.318499f,0.10513f},{-0.0117656f,0.319213f,0.10513f}, -{-0.010707f,0.319865f,0.10513f},{-0.0096143f,0.320453f,0.10513f},{-0.00849054f,0.320976f,0.10513f}, -{-0.00733859f,0.321434f,0.10513f},{-0.00616144f,0.321825f,0.10513f},{-0.00374334f,0.3224f,0.10513f}, -{-0.00496208f,0.322147f,0.10513f},{-0.00250813f,0.322582f,0.10513f},{-0.00125938f,0.322692f,0.10513f}, -{-0.0164352f,0.287519f,0.10513f},{-0.0147082f,0.285688f,0.10513f},{-0.0073385f,0.281143f,0.10513f}, -{-0.00125925f,0.279885f,0.10513f},{-0.015889f,0.28058f,0.10513f},{-0.0261017f,0.301289f,0.10513f}, -{-0.0260458f,0.299581f,0.10513f},{-0.0241144f,0.291299f,0.10513f},{-0.0256f,0.296196f,0.10513f}, -{-0.0252122f,0.294532f,0.10513f},{-0.0234094f,0.289744f,0.10513f},{-0.0217023f,0.286787f,0.10513f}, -{-0.0207075f,0.285398f,0.10513f},{-0.00675524f,0.276076f,0.10513f},{-0.00509193f,0.275688f,0.10513f}, -{-0.00170673f,0.275251f,0.10513f},{-0.0130502f,0.278684f,0.10513f},{-0.011544f,0.277878f,0.10513f}, -{-0.00998811f,0.277174f,0.10513f},{-0.00838954f,0.276572f,0.10513f},{-0.0145006f,0.279585f,0.10513f}, -{-0.018456f,0.282831f,0.10513f},{-0.0172093f,0.281664f,0.10513f},{-0.00340673f,0.275409f,0.10513f}, -{-0.0196237f,0.284078f,0.10513f},{-0.0226042f,0.288237f,0.10513f},{-0.0247162f,0.292898f,0.10513f}, -{-0.0258783f,0.297881f,0.10513f},{-0.0260458f,0.302996f,0.10513f},{-0.0258785f,0.304695f,0.10513f}, -{-0.0247166f,0.309679f,0.10513f},{-0.0252123f,0.308044f,0.10513f},{-0.0256002f,0.306381f,0.10513f}, -{-0.024115f,0.311277f,0.10513f},{-0.02341f,0.312833f,0.10513f},{-0.0226048f,0.31434f,0.10513f}, -{-0.0207077f,0.317179f,0.10513f},{-0.0217027f,0.31579f,0.10513f},{-0.0196242f,0.318499f,0.10513f}, -{-0.01721f,0.320913f,0.10513f},{-0.0145012f,0.322992f,0.10513f},{-0.0158895f,0.321997f,0.10513f}, -{-0.0130507f,0.323894f,0.10513f},{-0.0115442f,0.324699f,0.10513f},{-0.00340717f,0.327167f,0.10513f}, -{-0.00170718f,0.327329f,0.10513f},{-0.00509216f,0.326889f,0.10513f},{-0.0067556f,0.326501f,0.10513f}, -{-0.00839014f,0.326005f,0.10513f},{-0.0184567f,0.319746f,0.10513f},{-0.00998851f,0.325404f,0.10513f}, -{-0.0114195f,0.321068f,0.10252f},{-0.0131871f,0.319936f,0.10252f},{-0.0123517f,0.322682f,0.104011f}, -{-0.0179085f,0.315462f,0.10252f},{-0.0164595f,0.317122f,0.10252f},{-0.0148769f,0.318617f,0.10252f}, -{-0.0224459f,0.305508f,0.10252f},{-0.0219419f,0.307627f,0.10252f},{-0.0212291f,0.309712f,0.10252f}, -{-0.022839f,0.301289f,0.10252f},{-0.0227427f,0.303387f,0.10252f},{-0.0123517f,0.279895f,0.104011f}, -{-0.0114195f,0.281509f,0.10252f},{-0.0101514f,0.28083f,0.10252f},{-0.00882321f,0.280223f,0.10252f}, -{-0.00744093f,0.279696f,0.10252f},{-0.00601179f,0.279255f,0.10252f},{-0.00454389f,0.278906f,0.10252f}, -{-0.00304618f,0.278654f,0.10252f},{-0.00152821f,0.278501f,0.10252f},{-0.00650255f,0.277456f,0.104011f}, -{-0.00491482f,0.277079f,0.104011f},{-0.0109801f,0.279159f,0.104011f},{-0.00329485f,0.276806f,0.104011f}, -{-0.00165296f,0.276641f,0.104011f},{-0.00804836f,0.277933f,0.104011f},{-0.00954347f,0.278503f,0.104011f}, -{-0.0191994f,0.313658f,0.10252f},{-0.0203114f,0.311732f,0.10252f},{-0.0160918f,0.320032f,0.104011f}, -{-0.0247034f,0.301289f,0.104011f},{-0.0245988f,0.303557f,0.104011f},{-0.0242781f,0.305852f,0.104011f}, -{-0.0237331f,0.308143f,0.104011f},{-0.0229622f,0.310398f,0.104011f},{-0.02197f,0.312584f,0.104011f}, -{-0.0207674f,0.314667f,0.104011f},{-0.0193711f,0.316619f,0.104011f},{-0.0178041f,0.318414f,0.104011f}, -{-0.0142649f,0.321457f,0.104011f},{0.0255992f,0.299923f,0.121909f},{0.0254901f,0.298561f,0.121909f}, -{0.0137506f,0.279653f,0.121909f},{0.0155417f,0.280901f,0.121909f},{0.0118616f,0.278562f,0.121909f}, -{0.00988475f,0.277635f,0.121909f},{-0.00988506f,0.277635f,0.121909f},{-0.0118618f,0.278562f,0.121909f}, -{-0.015542f,0.280901f,0.121909f},{-0.0137508f,0.279653f,0.121909f},{-0.0253087f,0.297208f,0.121909f}, -{-0.0254902f,0.298561f,0.121909f},{-0.0255992f,0.299923f,0.121909f},{0.0253087f,0.297208f,0.121909f}, -{-0.0121592f,0.301901f,0.104198f},{-0.0127415f,0.303616f,0.104198f},{-0.0124735f,0.303072f,0.104198f}, -{-0.0122784f,0.302498f,0.104198f},{-0.0139458f,0.304989f,0.104198f},{-0.0130793f,0.304123f,0.104198f}, -{-0.0134838f,0.304584f,0.104198f},{-0.0161672f,0.305909f,0.104198f},{-0.0155702f,0.30579f,0.104198f}, -{-0.014996f,0.305595f,0.104198f},{-0.0173925f,0.305909f,0.104198f},{-0.0179895f,0.30579f,0.104198f}, -{-0.0167797f,0.30595f,0.104198f},{-0.0191075f,0.305327f,0.104198f},{-0.0185634f,0.305595f,0.104198f}, -{-0.0200755f,0.304584f,0.104198f},{-0.0196139f,0.304989f,0.104198f},{-0.0204802f,0.304122f,0.104198f}, -{-0.020818f,0.303616f,0.104198f},{-0.0210859f,0.303072f,0.104198f},{-0.0212811f,0.302498f,0.104198f}, -{-0.0214003f,0.301901f,0.104198f},{-0.0144523f,0.305327f,0.104198f},{-0.00978795f,0.292446f,0.110723f}, -{-0.00945021f,0.292251f,0.110723f},{-0.0101588f,0.292566f,0.110723f},{-0.00916026f,0.29199f,0.110723f}, -{-0.00893114f,0.291674f,0.110723f},{-0.00877327f,0.291317f,0.110723f},{-0.00869249f,0.290936f,0.110723f}, -{-0.00869285f,0.290546f,0.110723f},{-0.00893415f,0.289809f,0.110723f},{-0.00877489f,0.290165f,0.110723f}, -{-0.00945258f,0.289234f,0.110723f},{-0.00916327f,0.289494f,0.110723f},{-0.0101599f,0.288919f,0.110723f}, -{-0.00978972f,0.289039f,0.110723f},{0.0132829f,0.290468f,0.110723f},{0.0136207f,0.290273f,0.110723f}, -{0.0129121f,0.290589f,0.110723f},{0.0139106f,0.290012f,0.110723f},{0.0141397f,0.289696f,0.110723f}, -{0.0142976f,0.28934f,0.110723f},{0.0143784f,0.288958f,0.110723f},{0.014378f,0.288568f,0.110723f}, -{0.0141367f,0.287831f,0.110723f},{0.014296f,0.288187f,0.110723f},{0.0136183f,0.287256f,0.110723f}, -{0.0139076f,0.287517f,0.110723f},{0.012911f,0.286941f,0.110723f},{0.0132812f,0.287062f,0.110723f}, -{0.0113054f,0.313539f,0.110723f},{0.0116432f,0.313344f,0.110723f},{0.0109345f,0.31366f,0.110723f}, -{0.0119331f,0.313083f,0.110723f},{0.0121622f,0.312767f,0.110723f},{0.0123201f,0.312411f,0.110723f}, -{0.0124009f,0.312029f,0.110723f},{0.0124005f,0.311639f,0.110723f},{0.0121592f,0.310902f,0.110723f}, -{0.0123185f,0.311258f,0.110723f},{0.0116408f,0.310327f,0.110723f},{0.0119301f,0.310588f,0.110723f}, -{0.0109335f,0.310012f,0.110723f},{0.0113037f,0.310133f,0.110723f},{-0.0117655f,0.315517f,0.110723f}, -{-0.0114277f,0.315322f,0.110723f},{-0.0121363f,0.315637f,0.110723f},{-0.0111378f,0.315061f,0.110723f}, -{-0.0109086f,0.314745f,0.110723f},{-0.0107508f,0.314388f,0.110723f},{-0.01067f,0.314007f,0.110723f}, -{-0.0106704f,0.313617f,0.110723f},{-0.0109117f,0.31288f,0.110723f},{-0.0107524f,0.313235f,0.110723f}, -{-0.0114301f,0.312305f,0.110723f},{-0.0111408f,0.312565f,0.110723f},{-0.0121374f,0.31199f,0.110723f}, -{-0.0117672f,0.31211f,0.110723f},{-0.000612842f,0.289129f,0.104198f},{-0.00232777f,0.288547f,0.104198f}, -{-0.00120978f,0.28901f,0.104198f},{-0.00178369f,0.288815f,0.104198f},{-0.00370055f,0.287343f,0.104198f}, -{-0.00403832f,0.286836f,0.104198f},{-0.00329584f,0.287805f,0.104198f},{-0.00462066f,0.285121f,0.104198f}, -{-0.00430621f,0.286293f,0.104198f},{-0.00450141f,0.285718f,0.104198f},{-0.00450127f,0.283299f,0.104198f}, -{-0.00466102f,0.284509f,0.104198f},{-0.00462052f,0.283896f,0.104198f},{-0.00403818f,0.282181f,0.104198f}, -{-0.00370041f,0.281675f,0.104198f},{-0.00430621f,0.282725f,0.104198f},{-0.00329584f,0.281213f,0.104198f}, -{-0.00283386f,0.280808f,0.104198f},{-0.00232743f,0.280471f,0.104198f},{-0.00178369f,0.280203f,0.104198f}, -{-0.00120944f,0.280007f,0.104198f},{-0.000612502f,0.279888f,0.104198f},{-0.0028342f,0.288209f,0.104198f}, -{0.0121592f,0.300676f,0.104198f},{0.0127415f,0.298961f,0.104198f},{0.0124735f,0.299505f,0.104198f}, -{0.0122784f,0.300079f,0.104198f},{0.0139458f,0.297588f,0.104198f},{0.0130793f,0.298454f,0.104198f}, -{0.0134838f,0.297993f,0.104198f},{0.0161672f,0.296668f,0.104198f},{0.0155702f,0.296787f,0.104198f}, -{0.014996f,0.296982f,0.104198f},{0.0179895f,0.296787f,0.104198f},{0.0173925f,0.296668f,0.104198f}, -{0.0167797f,0.296628f,0.104198f},{0.0191075f,0.29725f,0.104198f},{0.0185634f,0.296982f,0.104198f}, -{0.0200755f,0.297993f,0.104198f},{0.0196139f,0.297588f,0.104198f},{0.0204802f,0.298455f,0.104198f}, -{0.020818f,0.298961f,0.104198f},{0.0210859f,0.299505f,0.104198f},{0.0212811f,0.300079f,0.104198f}, -{0.0214003f,0.300676f,0.104198f},{0.0144523f,0.29725f,0.104198f},{0.000612842f,0.313448f,0.104198f}, -{0.00232777f,0.31403f,0.104198f},{0.00178369f,0.313762f,0.104198f},{0.00120978f,0.313567f,0.104198f}, -{0.00370055f,0.315234f,0.104198f},{0.0028342f,0.314368f,0.104198f},{0.00329584f,0.314772f,0.104198f}, -{0.00462066f,0.317456f,0.104198f},{0.00450141f,0.316859f,0.104198f},{0.00430621f,0.316285f,0.104198f}, -{0.00462052f,0.318681f,0.104198f},{0.00450127f,0.319278f,0.104198f},{0.00466102f,0.318068f,0.104198f}, -{0.00403818f,0.320396f,0.104198f},{0.00430621f,0.319852f,0.104198f},{0.00329584f,0.321364f,0.104198f}, -{0.00370041f,0.320902f,0.104198f},{0.00283386f,0.321769f,0.104198f},{0.00232743f,0.322107f,0.104198f}, -{0.00178369f,0.322374f,0.104198f},{0.00120944f,0.32257f,0.104198f},{0.000612502f,0.322689f,0.104198f}, -{0.00403832f,0.315741f,0.104198f},{0.0114195f,0.281509f,0.104198f},{0.00948155f,0.280511f,0.104198f}, -{0.0032562f,0.278683f,0.104198f},{0.00746583f,0.279704f,0.104198f},{-0.00325654f,0.278683f,0.104198f}, -{0.00109039f,0.278476f,0.104198f},{-0.00109151f,0.278476f,0.104198f},{-0.00746603f,0.279704f,0.104198f}, -{-0.00538621f,0.279094f,0.104198f},{-0.00948213f,0.280511f,0.104198f},{-0.0114195f,0.281509f,0.104198f}, -{0.00538567f,0.279094f,0.104198f},{0.0123517f,0.279895f,0.104198f},{-0.0123517f,0.279895f,0.104198f}, -{-0.0102556f,0.278815f,0.104198f},{-0.00352201f,0.276837f,0.104198f},{-0.00807529f,0.277942f,0.104198f}, -{0.00352238f,0.276838f,0.104198f},{-0.00117941f,0.276613f,0.104198f},{0.00118061f,0.276613f,0.104198f}, -{0.0080755f,0.277942f,0.104198f},{0.0102562f,0.278815f,0.104198f},{0.0058259f,0.277282f,0.104198f}, -{-0.00582532f,0.277282f,0.104198f},{0.0132534f,0.319889f,0.104198f},{0.0114195f,0.321068f,0.104198f}, -{0.017949f,0.315411f,0.104198f},{0.0165285f,0.31705f,0.104198f},{0.0149596f,0.318546f,0.104198f}, -{0.0203023f,0.31175f,0.104198f},{0.0212053f,0.309771f,0.104198f},{0.0192114f,0.313639f,0.104198f}, -{0.0224255f,0.305615f,0.104198f},{0.0219143f,0.307721f,0.104198f},{0.0227351f,0.303466f,0.104198f}, -{0.022839f,0.301289f,0.104198f},{0.0123517f,0.322682f,0.104198f},{0.0247034f,0.301289f,0.104198f}, -{0.0245908f,0.303644f,0.104198f},{0.0229363f,0.310464f,0.104198f},{0.0237031f,0.308247f,0.104198f}, -{0.0242561f,0.305968f,0.104198f},{0.020779f,0.314649f,0.104198f},{0.019414f,0.316565f,0.104198f}, -{0.0219591f,0.312605f,0.104198f},{0.0178774f,0.318337f,0.104198f},{0.0161807f,0.319955f,0.104198f}, -{0.0143348f,0.321408f,0.104198f},{-0.0227349f,0.303466f,0.104198f},{-0.022839f,0.301289f,0.104198f}, -{-0.0212052f,0.309771f,0.104198f},{-0.0219142f,0.307722f,0.104198f},{-0.0224254f,0.305615f,0.104198f}, -{-0.0192108f,0.31364f,0.104198f},{-0.0179488f,0.315412f,0.104198f},{-0.0203018f,0.311751f,0.104198f}, -{-0.0149595f,0.318546f,0.104198f},{-0.0165281f,0.317051f,0.104198f},{-0.0132529f,0.319889f,0.104198f}, -{-0.0114195f,0.321068f,0.104198f},{-0.0247034f,0.301289f,0.104198f},{-0.0123517f,0.322682f,0.104198f}, -{-0.0143353f,0.321407f,0.104198f},{-0.0194142f,0.316564f,0.104198f},{-0.0178778f,0.318337f,0.104198f}, -{-0.0161808f,0.319955f,0.104198f},{-0.0219596f,0.312604f,0.104198f},{-0.0229364f,0.310464f,0.104198f}, -{-0.0207797f,0.314648f,0.104198f},{-0.0237033f,0.308246f,0.104198f},{-0.0242561f,0.305968f,0.104198f}, -{-0.024591f,0.303643f,0.104198f},{-0.00275356f,0.3008f,0.0986044f},{-0.00214219f,0.299491f,0.0986044f}, -{-0.00242266f,0.299891f,0.0986044f},{-0.00262748f,0.300331f,0.0986044f},{-0.000956449f,0.298661f,0.0986044f}, -{-0.00048723f,0.298535f,0.0986044f},{-0.00179504f,0.299144f,0.0986044f},{-0.00139564f,0.298865f,0.0986044f}, -{0.000957717f,0.298661f,0.0986044f},{0.000488516f,0.298535f,0.0986044f},{-2.66406e-017f,0.298492f,0.0986044f}, -{0.00179767f,0.299146f,0.0986044f},{0.00139727f,0.298866f,0.0986044f},{0.00214411f,0.299493f,0.0986044f}, -{0.00242333f,0.299893f,0.0986044f},{0.00262801f,0.300332f,0.0986044f},{0.00275356f,0.3008f,0.0986044f}, -{0.0174099f,0.300063f,0.121909f},{0.0172871f,0.300669f,0.121909f},{0.0172458f,0.301289f,0.121909f}, -{0.0176121f,0.299477f,0.121909f},{0.0182409f,0.29841f,0.121909f},{0.0178912f,0.298922f,0.121909f}, -{0.0186544f,0.29795f,0.121909f},{0.0191262f,0.297548f,0.121909f},{0.0196487f,0.297211f,0.121909f}, -{0.0202093f,0.296948f,0.121909f},{0.0207991f,0.296761f,0.121909f},{0.021411f,0.296654f,0.121909f}, -{0.0172872f,0.301908f,0.121909f},{0.0174099f,0.302515f,0.121909f},{0.0176122f,0.3031f,0.121909f}, -{0.0178915f,0.303655f,0.121909f},{0.0182411f,0.304167f,0.121909f},{0.0186545f,0.304627f,0.121909f}, -{0.0191266f,0.30503f,0.121909f},{0.0196491f,0.305366f,0.121909f},{0.0202094f,0.305629f,0.121909f}, -{0.0207994f,0.305816f,0.121909f},{0.021411f,0.305923f,0.121909f},{0.00761603f,0.308374f,0.121909f}, -{0.00821991f,0.309912f,0.121909f},{0.00794276f,0.309432f,0.121909f},{0.00774033f,0.308916f,0.121909f}, -{0.00944153f,0.311045f,0.121909f},{0.00856913f,0.31035f,0.121909f},{0.00898119f,0.310732f,0.121909f}, -{0.0115849f,0.311532f,0.121909f},{0.011024f,0.311532f,0.121909f},{0.01047f,0.311449f,0.121909f}, -{0.0126654f,0.311285f,0.121909f},{0.012136f,0.311448f,0.121909f},{0.0136271f,0.310729f,0.121909f}, -{0.0140372f,0.310348f,0.121909f},{0.0131654f,0.311044f,0.121909f},{0.0143853f,0.309911f,0.121909f}, -{0.0146628f,0.30943f,0.121909f},{0.0148654f,0.308914f,0.121909f},{0.0149887f,0.308374f,0.121909f}, -{0.00994023f,0.311285f,0.121909f},{0.00749878f,0.301677f,0.121909f},{0.0080757f,0.302675f,0.121909f}, -{0.007619f,0.302047f,0.121909f},{0.0091279f,0.303143f,0.121909f},{0.00839049f,0.302903f,0.121909f}, -{0.00874642f,0.303062f,0.121909f},{0.00989914f,0.303061f,0.121909f},{0.0102546f,0.302903f,0.121909f}, -{0.00951793f,0.303143f,0.121909f},{0.0105703f,0.302673f,0.121909f},{0.0108309f,0.302384f,0.121909f}, -{0.0110255f,0.302046f,0.121909f},{0.0111456f,0.301676f,0.121909f},{0.00781413f,0.302385f,0.121909f}, -{0.00632322f,0.319723f,0.121909f},{0.00629776f,0.320341f,0.121909f},{0.00635281f,0.320959f,0.121909f}, -{0.00643547f,0.319113f,0.121909f},{0.00662778f,0.318524f,0.121909f},{0.00689664f,0.317965f,0.121909f}, -{0.00723717f,0.317447f,0.121909f},{0.00862289f,0.316224f,0.121909f},{0.00917948f,0.31595f,0.121909f}, -{0.00764334f,0.316979f,0.121909f},{0.00810797f,0.316569f,0.121909f},{0.010376f,0.315635f,0.121909f}, -{0.0109947f,0.3156f,0.121909f},{0.0143217f,0.317038f,0.121909f},{0.0138626f,0.316622f,0.121909f}, -{0.0122191f,0.315775f,0.121909f},{0.012803f,0.315983f,0.121909f},{0.013354f,0.316267f,0.121909f}, -{0.0147191f,0.317514f,0.121909f},{0.0116126f,0.315647f,0.121909f},{0.0097673f,0.315753f,0.121909f}, -{0.00647672f,0.321566f,0.121909f},{0.00669182f,0.322148f,0.121909f},{-0.00232814f,0.311427f,0.121909f}, -{-0.00335826f,0.312719f,0.121909f},{-0.00308092f,0.312239f,0.121909f},{-0.0027356f,0.311806f,0.121909f}, -{-0.00372865f,0.314343f,0.121909f},{-0.0035632f,0.313241f,0.121909f},{-0.00368751f,0.313788f,0.121909f}, -{-0.00307835f,0.316443f,0.121909f},{-0.00335937f,0.315957f,0.121909f},{-0.00356405f,0.315436f,0.121909f}, -{-0.00232427f,0.317255f,0.121909f},{-0.0027306f,0.316878f,0.121909f},{-0.00136237f,0.31781f,0.121909f}, -{-0.000827251f,0.317975f,0.121909f},{-0.00186593f,0.317568f,0.121909f},{-0.000274996f,0.318058f,0.121909f}, -{0.000280844f,0.318058f,0.121909f},{0.000829073f,0.317975f,0.121909f},{0.00135821f,0.317812f,0.121909f}, -{-0.00368715f,0.314895f,0.121909f},{0.0034127f,0.307977f,0.121909f},{0.00283723f,0.308975f,0.121909f}, -{0.00315233f,0.308266f,0.121909f},{0.00295815f,0.310121f,0.121909f},{0.00279666f,0.309362f,0.121909f}, -{0.00283762f,0.30975f,0.121909f},{0.00341439f,0.310748f,0.121909f},{0.00372927f,0.310977f,0.121909f}, -{0.00315311f,0.310458f,0.121909f},{0.00408585f,0.311135f,0.121909f},{0.00446695f,0.311216f,0.121909f}, -{0.0048565f,0.311216f,0.121909f},{0.00523731f,0.311135f,0.121909f},{0.00295751f,0.308604f,0.121909f}, -{-0.0133515f,0.316269f,0.121909f},{-0.013859f,0.316626f,0.121909f},{-0.00764282f,0.316979f,0.121909f}, -{-0.00810759f,0.316569f,0.121909f},{-0.00723674f,0.317448f,0.121909f},{-0.00862289f,0.316224f,0.121909f}, -{-0.00689651f,0.317966f,0.121909f},{-0.00662806f,0.318524f,0.121909f},{-0.00643592f,0.319114f,0.121909f}, -{-0.00917901f,0.31595f,0.121909f},{-0.00976653f,0.315753f,0.121909f},{-0.00632427f,0.319723f,0.121909f}, -{-0.0103751f,0.315635f,0.121909f},{-0.00629503f,0.320343f,0.121909f},{-0.0064786f,0.321566f,0.121909f}, -{-0.00634749f,0.32096f,0.121909f},{-0.010994f,0.3156f,0.121909f},{-0.00669182f,0.322148f,0.121909f}, -{-0.0116123f,0.315646f,0.121909f},{-0.0128028f,0.315982f,0.121909f},{-0.0122189f,0.315774f,0.121909f}, -{-0.0143221f,0.317036f,0.121909f},{-0.0147191f,0.317514f,0.121909f},{-0.00994417f,0.304342f,0.121909f}, -{-0.0115782f,0.304095f,0.121909f},{-0.0110237f,0.304096f,0.121909f},{-0.0104759f,0.304178f,0.121909f}, -{-0.0131702f,0.304587f,0.121909f},{-0.0121323f,0.304179f,0.121909f},{-0.0126687f,0.304345f,0.121909f}, -{-0.0146632f,0.3062f,0.121909f},{-0.0143833f,0.305714f,0.121909f},{-0.014034f,0.305276f,0.121909f}, -{-0.0149897f,0.307259f,0.121909f},{-0.0148666f,0.306719f,0.121909f},{-0.0149894f,0.30837f,0.121909f}, -{-0.0148645f,0.308915f,0.121909f},{-0.0150313f,0.307812f,0.121909f},{-0.0146603f,0.309435f,0.121909f}, -{-0.014382f,0.309916f,0.121909f},{-0.0140364f,0.31035f,0.121909f},{-0.0136305f,0.310726f,0.121909f}, -{-0.0136274f,0.304899f,0.121909f},{-0.00408601f,0.307588f,0.121909f},{-0.0052381f,0.307589f,0.121909f}, -{-0.00446686f,0.307507f,0.121909f},{-0.00616977f,0.308266f,0.121909f},{-0.00559379f,0.307747f,0.121909f}, -{-0.00590924f,0.307977f,0.121909f},{-0.00648482f,0.308975f,0.121909f},{-0.00652543f,0.309362f,0.121909f}, -{-0.0063645f,0.308604f,0.121909f},{-0.00648441f,0.30975f,0.121909f},{-0.00636386f,0.310121f,0.121909f}, -{-0.00616897f,0.310458f,0.121909f},{-0.00590844f,0.310747f,0.121909f},{-0.00485671f,0.307508f,0.121909f}, -{-0.0178906f,0.298923f,0.121909f},{-0.0176123f,0.299477f,0.121909f},{-0.0182401f,0.298411f,0.121909f}, -{-0.0186543f,0.297949f,0.121909f},{-0.019126f,0.297548f,0.121909f},{-0.0174099f,0.300063f,0.121909f}, -{-0.0196492f,0.297216f,0.121909f},{-0.017287f,0.30067f,0.121909f},{-0.0172458f,0.301289f,0.121909f}, -{-0.0172871f,0.301907f,0.121909f},{-0.0174101f,0.302515f,0.121909f},{-0.0176127f,0.303101f,0.121909f}, -{-0.0178912f,0.303655f,0.121909f},{-0.0182407f,0.304166f,0.121909f},{-0.018655f,0.304627f,0.121909f}, -{-0.0191272f,0.305029f,0.121909f},{-0.0196491f,0.305364f,0.121909f},{-0.02021f,0.305627f,0.121909f}, -{-0.0208003f,0.305817f,0.121909f},{-0.021411f,0.305923f,0.121909f},{-0.0207988f,0.296759f,0.121909f}, -{-0.0202118f,0.296955f,0.121909f},{-0.021411f,0.296654f,0.121909f},{-0.00761603f,0.294203f,0.121909f}, -{-0.00821991f,0.292665f,0.121909f},{-0.00794276f,0.293145f,0.121909f},{-0.00774033f,0.293661f,0.121909f}, -{-0.00944153f,0.291532f,0.121909f},{-0.00856913f,0.292227f,0.121909f},{-0.00898119f,0.291845f,0.121909f}, -{-0.0115849f,0.291045f,0.121909f},{-0.011024f,0.291045f,0.121909f},{-0.01047f,0.291128f,0.121909f}, -{-0.0126654f,0.291292f,0.121909f},{-0.012136f,0.291129f,0.121909f},{-0.0136271f,0.291848f,0.121909f}, -{-0.0140372f,0.292229f,0.121909f},{-0.0131654f,0.291533f,0.121909f},{-0.0143853f,0.292666f,0.121909f}, -{-0.0146628f,0.293147f,0.121909f},{-0.0148654f,0.293663f,0.121909f},{-0.0149887f,0.294203f,0.121909f}, -{-0.00994023f,0.291292f,0.121909f},{-0.00749878f,0.3009f,0.121909f},{-0.0080757f,0.299902f,0.121909f}, -{-0.007619f,0.30053f,0.121909f},{-0.0091279f,0.299434f,0.121909f},{-0.00839049f,0.299674f,0.121909f}, -{-0.00874642f,0.299515f,0.121909f},{-0.00989914f,0.299516f,0.121909f},{-0.0102546f,0.299674f,0.121909f}, -{-0.00951793f,0.299435f,0.121909f},{-0.0105703f,0.299904f,0.121909f},{-0.0108309f,0.300193f,0.121909f}, -{-0.0110255f,0.300531f,0.121909f},{-0.0111456f,0.300901f,0.121909f},{-0.00781413f,0.300192f,0.121909f}, -{-0.00629776f,0.282236f,0.121909f},{-0.00632322f,0.282854f,0.121909f},{-0.0147191f,0.285063f,0.121909f}, -{-0.00643547f,0.283464f,0.121909f},{-0.00635281f,0.281618f,0.121909f},{-0.00662778f,0.284053f,0.121909f}, -{-0.00689664f,0.284612f,0.121909f},{-0.00764334f,0.285598f,0.121909f},{-0.00810797f,0.286008f,0.121909f}, -{-0.00723717f,0.28513f,0.121909f},{-0.010376f,0.286942f,0.121909f},{-0.0109947f,0.286977f,0.121909f}, -{-0.00862289f,0.286353f,0.121909f},{-0.00917948f,0.286627f,0.121909f},{-0.0143217f,0.285539f,0.121909f}, -{-0.0138626f,0.285956f,0.121909f},{-0.0122191f,0.286802f,0.121909f},{-0.012803f,0.286594f,0.121909f}, -{-0.013354f,0.28631f,0.121909f},{-0.0116126f,0.286931f,0.121909f},{-0.0097673f,0.286824f,0.121909f}, -{-0.00647672f,0.281011f,0.121909f},{-0.00669182f,0.280429f,0.121909f},{0.00232814f,0.29115f,0.121909f}, -{0.00335826f,0.289858f,0.121909f},{0.00308092f,0.290338f,0.121909f},{0.0027356f,0.290771f,0.121909f}, -{0.00372865f,0.288234f,0.121909f},{0.0035632f,0.289337f,0.121909f},{0.00368751f,0.288789f,0.121909f}, -{0.00307835f,0.286134f,0.121909f},{0.00335937f,0.28662f,0.121909f},{0.00356405f,0.287141f,0.121909f}, -{0.00232427f,0.285322f,0.121909f},{0.0027306f,0.285699f,0.121909f},{0.00136237f,0.284767f,0.121909f}, -{0.000827251f,0.284602f,0.121909f},{0.00186593f,0.285009f,0.121909f},{0.000274996f,0.284519f,0.121909f}, -{-0.000280844f,0.284519f,0.121909f},{-0.000829073f,0.284602f,0.121909f},{-0.00135821f,0.284765f,0.121909f}, -{0.00368715f,0.287682f,0.121909f},{-0.0034126f,0.2946f,0.121909f},{-0.00283728f,0.293602f,0.121909f}, -{-0.0031524f,0.294311f,0.121909f},{-0.00295812f,0.292456f,0.121909f},{-0.00279668f,0.293215f,0.121909f}, -{-0.0028374f,0.292827f,0.121909f},{-0.0034143f,0.291829f,0.121909f},{-0.00372908f,0.291601f,0.121909f}, -{-0.00315337f,0.292119f,0.121909f},{-0.00408596f,0.291442f,0.121909f},{-0.00446705f,0.291361f,0.121909f}, -{-0.00485646f,0.291361f,0.121909f},{-0.00523689f,0.291442f,0.121909f},{-0.00295753f,0.293973f,0.121909f}, -{0.00764282f,0.285598f,0.121909f},{0.00723674f,0.285129f,0.121909f},{0.00810759f,0.286008f,0.121909f}, -{0.00862289f,0.286353f,0.121909f},{0.00689651f,0.284611f,0.121909f},{0.00662806f,0.284053f,0.121909f}, -{0.00643592f,0.283463f,0.121909f},{0.00917901f,0.286627f,0.121909f},{0.00632427f,0.282854f,0.121909f}, -{0.00629503f,0.282234f,0.121909f},{0.00976653f,0.286824f,0.121909f},{0.00634749f,0.281617f,0.121909f}, -{0.0103751f,0.286942f,0.121909f},{0.010994f,0.286978f,0.121909f},{0.0064786f,0.281011f,0.121909f}, -{0.00669182f,0.280429f,0.121909f},{0.0116123f,0.286931f,0.121909f},{0.0128028f,0.286595f,0.121909f}, -{0.0122189f,0.286803f,0.121909f},{0.0133515f,0.286308f,0.121909f},{0.013859f,0.285951f,0.121909f}, -{0.0143221f,0.285541f,0.121909f},{0.0147191f,0.285063f,0.121909f},{0.00994417f,0.298236f,0.121909f}, -{0.0115782f,0.298482f,0.121909f},{0.0110237f,0.298482f,0.121909f},{0.0104759f,0.298399f,0.121909f}, -{0.0131702f,0.29799f,0.121909f},{0.0121323f,0.298398f,0.121909f},{0.0126687f,0.298232f,0.121909f}, -{0.0146632f,0.296377f,0.121909f},{0.0143833f,0.296863f,0.121909f},{0.014034f,0.297301f,0.121909f}, -{0.0149897f,0.295318f,0.121909f},{0.0148666f,0.295858f,0.121909f},{0.0149894f,0.294208f,0.121909f}, -{0.0148645f,0.293662f,0.121909f},{0.0150313f,0.294765f,0.121909f},{0.0146603f,0.293142f,0.121909f}, -{0.014382f,0.292661f,0.121909f},{0.0140364f,0.292227f,0.121909f},{0.0136305f,0.291851f,0.121909f}, -{0.0136274f,0.297678f,0.121909f},{0.00408601f,0.294989f,0.121909f},{0.0052381f,0.294988f,0.121909f}, -{0.00446686f,0.29507f,0.121909f},{0.00616977f,0.294311f,0.121909f},{0.00559379f,0.29483f,0.121909f}, -{0.00590924f,0.2946f,0.121909f},{0.00648482f,0.293602f,0.121909f},{0.00652543f,0.293215f,0.121909f}, -{0.0063645f,0.293973f,0.121909f},{0.00648441f,0.292827f,0.121909f},{0.00636386f,0.292456f,0.121909f}, -{0.00616897f,0.292119f,0.121909f},{0.00590844f,0.29183f,0.121909f},{0.00485671f,0.295069f,0.121909f}, -{0.00462052f,0.300676f,0.127503f},{0.00403818f,0.298961f,0.127503f},{0.00450127f,0.300079f,0.127503f}, -{0.00283386f,0.297588f,0.127503f},{0.00232743f,0.29725f,0.127503f},{0.00329584f,0.297993f,0.127503f}, -{0.000612502f,0.296668f,0.127503f},{0.00178369f,0.296982f,0.127503f},{0.00120944f,0.296787f,0.127503f}, -{-0.00120978f,0.296787f,0.127503f},{-2.48389e-017f,0.296628f,0.127503f},{-0.000612842f,0.296668f,0.127503f}, -{-0.00232777f,0.29725f,0.127503f},{-0.0028342f,0.297588f,0.127503f},{-0.00178369f,0.296982f,0.127503f}, -{-0.00329584f,0.297993f,0.127503f},{-0.00370055f,0.298455f,0.127503f},{-0.00403832f,0.298961f,0.127503f}, -{-0.00430621f,0.299505f,0.127503f},{-0.00450141f,0.300079f,0.127503f},{-0.00462066f,0.300676f,0.127503f}, -{0.00370041f,0.298454f,0.127503f},{0.00430621f,0.299505f,0.127503f},{-0.00139737f,0.298869f,0.127503f}, -{-0.00275363f,0.300804f,0.127503f},{-0.00242194f,0.299891f,0.127503f},{-0.00214182f,0.299492f,0.127503f}, -{-0.00262754f,0.300333f,0.127503f},{-0.00179665f,0.299148f,0.127503f},{-0.000956049f,0.298662f,0.127503f}, -{-0.000485772f,0.298534f,0.127503f},{-2.74781e-017f,0.298492f,0.127503f},{0.000955564f,0.29866f,0.127503f}, -{0.000485107f,0.298534f,0.127503f},{0.00139499f,0.298869f,0.127503f},{0.00275512f,0.300803f,0.127503f}, -{0.00178917f,0.299157f,0.127503f},{0.00262887f,0.300331f,0.127503f},{0.00242212f,0.29989f,0.127503f}, -{0.00214373f,0.299488f,0.127503f},{-0.00275512f,0.300803f,0.13496f},{-0.00262887f,0.300331f,0.13496f}, -{-0.00242212f,0.29989f,0.13496f},{-0.00214373f,0.299488f,0.13496f},{-0.00178917f,0.299157f,0.13496f}, -{-0.00139499f,0.298869f,0.13496f},{-0.000955564f,0.29866f,0.13496f},{-0.000485107f,0.298534f,0.13496f}, -{-2.71676e-017f,0.298492f,0.13496f},{0.000485772f,0.298534f,0.13496f},{0.00179665f,0.299148f,0.13496f}, -{0.00262754f,0.300333f,0.13496f},{0.000956049f,0.298662f,0.13496f},{0.00139737f,0.298869f,0.13496f}, -{0.00214182f,0.299492f,0.13496f},{0.00242194f,0.299891f,0.13496f},{0.00275363f,0.300804f,0.13496f}, -{0.301289f,0.00279661f,0.126571f},{0.301289f,0.00279661f,0.134028f},{0.301777f,0.00275356f,0.134028f}, -{0.302246f,0.00262748f,0.134028f},{0.301776f,0.00275376f,0.126571f},{0.302245f,0.00262801f,0.126571f}, -{0.302684f,0.00242333f,0.126571f},{0.303084f,0.00214411f,0.126571f},{0.302686f,0.00242266f,0.134028f}, -{0.303086f,0.00214219f,0.134028f},{0.303431f,0.00179767f,0.126571f},{0.303433f,0.00179504f,0.134028f}, -{0.303711f,0.00139727f,0.126571f},{0.303916f,0.000957717f,0.126571f},{0.303712f,0.00139564f,0.134028f}, -{0.303917f,0.000956449f,0.134028f},{0.304042f,0.000488516f,0.126571f},{0.304042f,0.000488516f,0.134028f}, -{0.304085f,2.50765e-018f,0.134028f},{0.304085f,2.50765e-018f,0.126571f},{0.3008f,0.00275356f,0.126571f}, -{0.300331f,0.00262748f,0.126571f},{0.300801f,0.00275376f,0.134028f},{0.299893f,0.00242333f,0.134028f}, -{0.300332f,0.00262801f,0.134028f},{0.299891f,0.00242266f,0.126571f},{0.299493f,0.00214411f,0.134028f}, -{0.299491f,0.00214219f,0.126571f},{0.299146f,0.00179767f,0.134028f},{0.298866f,0.00139727f,0.134028f}, -{0.299144f,0.00179504f,0.126571f},{0.298865f,0.00139564f,0.126571f},{0.298661f,0.000957717f,0.134028f}, -{0.298661f,0.000956449f,0.126571f},{0.298535f,0.000488516f,0.134028f},{0.298535f,0.000488516f,0.126571f}, -{0.298492f,2.16517e-018f,0.126571f},{0.298492f,2.16517e-018f,0.134028f},{0.301289f,0.00466102f,0.124706f}, -{0.301289f,0.00466102f,0.126571f},{0.301901f,0.00462052f,0.126571f},{0.302498f,0.00450127f,0.126571f}, -{0.301901f,0.00462066f,0.124706f},{0.303072f,0.00430621f,0.126571f},{0.302498f,0.00450141f,0.124706f}, -{0.303072f,0.00430621f,0.124706f},{0.303616f,0.00403818f,0.126571f},{0.304123f,0.00370041f,0.126571f}, -{0.303616f,0.00403832f,0.124706f},{0.304584f,0.00329584f,0.126571f},{0.304122f,0.00370055f,0.124706f}, -{0.304584f,0.00329584f,0.124706f},{0.304989f,0.00283386f,0.126571f},{0.305327f,0.00232743f,0.126571f}, -{0.304989f,0.0028342f,0.124706f},{0.305595f,0.00178369f,0.126571f},{0.305327f,0.00232777f,0.124706f}, -{0.30579f,0.00120978f,0.124706f},{0.305595f,0.00178369f,0.124706f},{0.30579f,0.00120944f,0.126571f}, -{0.305909f,0.000612842f,0.124706f},{0.305909f,0.000612502f,0.126571f},{0.30595f,2.73598e-018f,0.124706f}, -{0.30595f,2.73598e-018f,0.126571f},{0.300676f,0.00462052f,0.124706f},{0.300079f,0.00450127f,0.124706f}, -{0.300676f,0.00462066f,0.126571f},{0.300079f,0.00450141f,0.126571f},{0.299505f,0.00430621f,0.124706f}, -{0.298961f,0.00403818f,0.124706f},{0.299505f,0.00430621f,0.126571f},{0.298454f,0.00370041f,0.124706f}, -{0.298961f,0.00403832f,0.126571f},{0.298455f,0.00370055f,0.126571f},{0.297993f,0.00329584f,0.124706f}, -{0.297588f,0.00283386f,0.124706f},{0.297993f,0.00329584f,0.126571f},{0.29725f,0.00232743f,0.124706f}, -{0.297588f,0.0028342f,0.126571f},{0.29725f,0.00232777f,0.126571f},{0.296982f,0.00178369f,0.124706f}, -{0.296787f,0.00120978f,0.126571f},{0.296982f,0.00178369f,0.126571f},{0.296787f,0.00120944f,0.124706f}, -{0.296668f,0.000612842f,0.126571f},{0.296628f,2.16517e-018f,0.126571f},{0.296668f,0.000612502f,0.124706f}, -{0.296628f,2.16517e-018f,0.124706f},{0.304247f,-0.00883211f,0.124706f},{0.304442f,-0.00916975f,0.124706f}, -{0.304441f,-0.00916839f,0.120977f},{0.304246f,-0.00883048f,0.120977f},{0.304126f,-0.00846133f,0.124706f}, -{0.304126f,-0.00845974f,0.120977f},{0.304085f,-0.0080728f,0.120977f},{0.304126f,-0.00768692f,0.124706f}, -{0.304085f,-0.00807384f,0.124706f},{0.304126f,-0.00768446f,0.120977f},{0.304246f,-0.00731545f,0.124706f}, -{0.304247f,-0.00731401f,0.120977f},{0.304441f,-0.00697763f,0.124706f},{0.304442f,-0.00697682f,0.120977f}, -{0.304701f,-0.00668858f,0.124706f},{0.304702f,-0.0066878f,0.120977f},{0.305017f,-0.0064585f,0.120977f}, -{0.305017f,-0.0064585f,0.124706f},{0.304702f,-0.00945833f,0.120977f},{0.305017f,-0.00968734f,0.120977f}, -{0.304703f,-0.00945929f,0.124706f},{0.305018f,-0.00968796f,0.124706f},{0.305372f,-0.00984564f,0.120977f}, -{0.305375f,-0.00984651f,0.124706f},{0.305754f,-0.00992724f,0.120977f},{0.306144f,-0.00992738f,0.120977f}, -{0.305756f,-0.00992734f,0.124706f},{0.306145f,-0.00992724f,0.124706f},{0.306524f,-0.00984657f,0.120977f}, -{0.306525f,-0.00984636f,0.124706f},{0.306882f,-0.00968775f,0.120977f},{0.306882f,-0.00968775f,0.124706f}, -{0.309232f,-0.00814348f,0.124706f},{0.309513f,-0.00862894f,0.124706f},{0.30951f,-0.00862571f,0.120977f}, -{0.309027f,-0.00762194f,0.124706f},{0.30923f,-0.00813961f,0.120977f},{0.309027f,-0.00762066f,0.120977f}, -{0.308904f,-0.00708133f,0.124706f},{0.308904f,-0.00708043f,0.120977f},{0.308862f,-0.0065271f,0.120977f}, -{0.308862f,-0.00652944f,0.124706f},{0.308903f,-0.00597413f,0.124706f},{0.309233f,-0.00490426f,0.120977f}, -{0.30951f,-0.00442484f,0.124706f},{0.309233f,-0.00490499f,0.124706f},{0.308904f,-0.00596985f,0.120977f}, -{0.309028f,-0.00542656f,0.124706f},{0.309029f,-0.00542408f,0.120977f},{0.309511f,-0.00442313f,0.120977f}, -{0.309855f,-0.00399173f,0.124706f},{0.309857f,-0.00398963f,0.120977f},{0.310263f,-0.00361295f,0.120977f}, -{0.310726f,-0.00329618f,0.124706f},{0.310263f,-0.00361295f,0.124706f},{0.310726f,-0.00329618f,0.120977f}, -{0.309859f,-0.00906373f,0.120977f},{0.310266f,-0.00944065f,0.120977f},{0.30986f,-0.00906452f,0.124706f}, -{0.310267f,-0.00944121f,0.124706f},{0.310723f,-0.00975253f,0.120977f},{0.310725f,-0.00975397f,0.124706f}, -{0.311225f,-0.00999456f,0.120977f},{0.311761f,-0.0101607f,0.120977f},{0.311229f,-0.0099963f,0.124706f}, -{0.311764f,-0.010161f,0.124706f},{0.312315f,-0.010244f,0.120977f},{0.312316f,-0.0102441f,0.124706f}, -{0.31287f,-0.0102439f,0.120977f},{0.313417f,-0.0101614f,0.120977f},{0.312872f,-0.0102436f,0.124706f}, -{0.31342f,-0.010161f,0.124706f},{0.313949f,-0.0099979f,0.120977f},{0.313949f,-0.0099979f,0.124706f}, -{0.314455f,-0.00975468f,0.120977f},{0.314455f,-0.00975468f,0.124706f},{0.295119f,-0.00697787f,0.124706f}, -{0.294924f,-0.00731578f,0.124706f},{0.294925f,-0.00731414f,0.120977f},{0.29512f,-0.0069765f,0.120977f}, -{0.29538f,-0.00668793f,0.124706f},{0.295381f,-0.00668696f,0.120977f},{0.295696f,-0.0064583f,0.120977f}, -{0.29605f,-0.00630061f,0.124706f},{0.295695f,-0.00645891f,0.124706f},{0.296052f,-0.00629975f,0.120977f}, -{0.296432f,-0.00621902f,0.124706f},{0.296434f,-0.00621892f,0.120977f},{0.296822f,-0.00621887f,0.124706f}, -{0.296823f,-0.00621902f,0.120977f},{0.297202f,-0.00629969f,0.124706f},{0.297203f,-0.0062999f,0.120977f}, -{0.29756f,-0.0064585f,0.120977f},{0.29756f,-0.0064585f,0.124706f},{0.294804f,-0.00768493f,0.120977f}, -{0.294763f,-0.00807242f,0.120977f},{0.294804f,-0.00768652f,0.124706f},{0.294763f,-0.00807346f,0.124706f}, -{0.294804f,-0.00845934f,0.120977f},{0.294804f,-0.0084618f,0.124706f},{0.294924f,-0.0088308f,0.120977f}, -{0.295119f,-0.00916863f,0.120977f},{0.294925f,-0.00883225f,0.124706f},{0.29512f,-0.00916944f,0.124706f}, -{0.295379f,-0.00945768f,0.120977f},{0.29538f,-0.00945846f,0.124706f},{0.295695f,-0.00968775f,0.120977f}, -{0.295695f,-0.00968775f,0.124706f},{0.298208f,-0.0109506f,0.124706f},{0.297928f,-0.0114367f,0.124706f}, -{0.297929f,-0.0114328f,0.120977f},{0.298557f,-0.0105126f,0.124706f},{0.29821f,-0.0109474f,0.120977f}, -{0.298558f,-0.0105118f,0.120977f},{0.298964f,-0.0101356f,0.124706f},{0.298964f,-0.0101351f,0.120977f}, -{0.299423f,-0.00982233f,0.120977f},{0.299421f,-0.00982376f,0.124706f},{0.299922f,-0.00958174f,0.124706f}, -{0.301014f,-0.00933222f,0.120977f},{0.301567f,-0.00933241f,0.124706f},{0.301013f,-0.00933231f,0.124706f}, -{0.299926f,-0.00958f,0.120977f},{0.300459f,-0.00941561f,0.124706f},{0.300461f,-0.00941532f,0.120977f}, -{0.301569f,-0.0093327f,0.120977f},{0.302115f,-0.00941491f,0.124706f},{0.302118f,-0.00941526f,0.120977f}, -{0.302647f,-0.0095784f,0.120977f},{0.303153f,-0.00982161f,0.124706f},{0.302647f,-0.0095784f,0.124706f}, -{0.303153f,-0.00982161f,0.120977f},{0.297725f,-0.0119544f,0.120977f},{0.297601f,-0.012495f,0.120977f}, -{0.297724f,-0.0119556f,0.124706f},{0.297601f,-0.0124959f,0.124706f},{0.29756f,-0.0130469f,0.120977f}, -{0.29756f,-0.0130492f,0.124706f},{0.297601f,-0.0136022f,0.120977f},{0.297725f,-0.0141497f,0.120977f}, -{0.297601f,-0.0136064f,0.124706f},{0.297726f,-0.0141522f,0.124706f},{0.29793f,-0.0146713f,0.120977f}, -{0.297931f,-0.014672f,0.124706f},{0.298208f,-0.0151515f,0.120977f},{0.298553f,-0.0155846f,0.120977f}, -{0.298209f,-0.0151532f,0.124706f},{0.298555f,-0.0155867f,0.124706f},{0.29896f,-0.0159633f,0.120977f}, -{0.29896f,-0.0159633f,0.124706f},{0.299424f,-0.0162801f,0.120977f},{0.299424f,-0.0162801f,0.124706f}, -{0.292161f,0.00185425f,0.124706f},{0.291771f,0.00185398f,0.124706f},{0.291772f,0.00185425f,0.120977f}, -{0.292162f,0.00185398f,0.120977f},{0.292542f,0.0017734f,0.124706f},{0.292544f,0.00177278f,0.120977f}, -{0.292899f,0.0016145f,0.120977f},{0.293213f,0.0013863f,0.124706f},{0.292898f,0.00161492f,0.124706f}, -{0.293215f,0.00138471f,0.120977f},{0.293474f,0.00109643f,0.124706f},{0.293475f,0.00109509f,0.120977f}, -{0.29367f,0.000758756f,0.124706f},{0.29367f,0.000757801f,0.120977f},{0.29379f,0.000388892f,0.124706f}, -{0.29379f,0.000387896f,0.120977f},{0.293831f,5.86186e-018f,0.120977f},{0.293831f,5.86186e-018f,0.124706f}, -{0.291391f,0.0017734f,0.120977f},{0.291035f,0.00161492f,0.120977f},{0.291389f,0.00177278f,0.124706f}, -{0.291034f,0.0016145f,0.124706f},{0.29072f,0.0013863f,0.120977f},{0.290718f,0.00138471f,0.124706f}, -{0.290459f,0.00109643f,0.120977f},{0.290263f,0.000758756f,0.120977f},{0.290458f,0.00109509f,0.124706f}, -{0.290263f,0.000757801f,0.124706f},{0.290143f,0.000388892f,0.120977f},{0.290143f,0.000387896f,0.124706f}, -{0.290102f,6.91815e-018f,0.120977f},{0.290102f,6.91815e-018f,0.124706f},{0.290265f,-0.00280711f,0.124706f}, -{0.289704f,-0.00280775f,0.124706f},{0.289708f,-0.00280711f,0.120977f},{0.290819f,-0.00289062f,0.124706f}, -{0.290269f,-0.00280775f,0.120977f},{0.29082f,-0.00289112f,0.120977f},{0.291348f,-0.00305432f,0.124706f}, -{0.291349f,-0.00305467f,0.120977f},{0.291849f,-0.00329522f,0.120977f},{0.291847f,-0.00329432f,0.124706f}, -{0.292307f,-0.00360761f,0.124706f},{0.293069f,-0.00442796f,0.120977f},{0.293346f,-0.00490757f,0.124706f}, -{0.293069f,-0.00442732f,0.124706f},{0.292311f,-0.00361015f,0.120977f},{0.292719f,-0.00398905f,0.124706f}, -{0.292721f,-0.00399124f,0.120977f},{0.293347f,-0.00490957f,0.120977f},{0.293548f,-0.00542319f,0.124706f}, -{0.293549f,-0.00542563f,0.120977f},{0.293673f,-0.00596545f,0.120977f},{0.293715f,-0.00652543f,0.124706f}, -{0.293673f,-0.00596545f,0.124706f},{0.293715f,-0.00652543f,0.120977f},{0.289154f,-0.00289062f,0.120977f}, -{0.288624f,-0.00305432f,0.120977f},{0.289153f,-0.00289112f,0.124706f},{0.288623f,-0.00305467f,0.124706f}, -{0.288125f,-0.00329432f,0.120977f},{0.288123f,-0.00329522f,0.124706f},{0.287665f,-0.00360761f,0.120977f}, -{0.287253f,-0.00398905f,0.120977f},{0.287661f,-0.00361015f,0.124706f},{0.287251f,-0.00399124f,0.124706f}, -{0.286904f,-0.00442732f,0.120977f},{0.286903f,-0.00442796f,0.124706f},{0.286627f,-0.00490757f,0.120977f}, -{0.286424f,-0.00542319f,0.120977f},{0.286626f,-0.00490957f,0.124706f},{0.286423f,-0.00542563f,0.124706f}, -{0.2863f,-0.00596545f,0.120977f},{0.2863f,-0.00596545f,0.124706f},{0.286257f,-0.00652543f,0.120977f}, -{0.286257f,-0.00652543f,0.124706f},{0.29833f,0.00883211f,0.124706f},{0.298135f,0.00916975f,0.124706f}, -{0.298136f,0.00916839f,0.120977f},{0.298331f,0.00883048f,0.120977f},{0.298451f,0.00846133f,0.124706f}, -{0.298451f,0.00845974f,0.120977f},{0.298492f,0.0080728f,0.120977f},{0.298451f,0.00768692f,0.124706f}, -{0.298492f,0.00807384f,0.124706f},{0.298451f,0.00768446f,0.120977f},{0.298331f,0.00731545f,0.124706f}, -{0.29833f,0.00731401f,0.120977f},{0.298136f,0.00697763f,0.124706f},{0.298136f,0.00697682f,0.120977f}, -{0.297876f,0.00668858f,0.124706f},{0.297875f,0.0066878f,0.120977f},{0.29756f,0.0064585f,0.120977f}, -{0.29756f,0.0064585f,0.124706f},{0.297876f,0.00945833f,0.120977f},{0.29756f,0.00968734f,0.120977f}, -{0.297874f,0.00945929f,0.124706f},{0.297559f,0.00968796f,0.124706f},{0.297205f,0.00984564f,0.120977f}, -{0.297203f,0.00984651f,0.124706f},{0.296823f,0.00992724f,0.120977f},{0.296433f,0.00992738f,0.120977f}, -{0.296822f,0.00992734f,0.124706f},{0.296432f,0.00992724f,0.124706f},{0.296053f,0.00984657f,0.120977f}, -{0.296052f,0.00984636f,0.124706f},{0.295695f,0.00968775f,0.120977f},{0.295695f,0.00968775f,0.124706f}, -{0.293346f,0.00814348f,0.124706f},{0.293065f,0.00862894f,0.124706f},{0.293067f,0.00862571f,0.120977f}, -{0.29355f,0.00762194f,0.124706f},{0.293347f,0.00813961f,0.120977f},{0.29355f,0.00762066f,0.120977f}, -{0.293673f,0.00708133f,0.124706f},{0.293673f,0.00708043f,0.120977f},{0.293715f,0.0065271f,0.120977f}, -{0.293715f,0.00652944f,0.124706f},{0.293674f,0.00597413f,0.124706f},{0.293344f,0.00490426f,0.120977f}, -{0.293067f,0.00442484f,0.124706f},{0.293344f,0.00490499f,0.124706f},{0.293673f,0.00596985f,0.120977f}, -{0.293549f,0.00542656f,0.124706f},{0.293548f,0.00542408f,0.120977f},{0.293066f,0.00442313f,0.120977f}, -{0.292722f,0.00399173f,0.124706f},{0.29272f,0.00398963f,0.120977f},{0.292314f,0.00361295f,0.120977f}, -{0.291851f,0.00329618f,0.124706f},{0.292314f,0.00361295f,0.124706f},{0.291851f,0.00329618f,0.120977f}, -{0.292718f,0.00906373f,0.120977f},{0.292311f,0.00944065f,0.120977f},{0.292717f,0.00906452f,0.124706f}, -{0.29231f,0.00944121f,0.124706f},{0.291854f,0.00975253f,0.120977f},{0.291852f,0.00975397f,0.124706f}, -{0.291352f,0.00999456f,0.120977f},{0.290816f,0.0101607f,0.120977f},{0.291349f,0.0099963f,0.124706f}, -{0.290813f,0.010161f,0.124706f},{0.290262f,0.010244f,0.120977f},{0.290261f,0.0102441f,0.124706f}, -{0.289707f,0.0102439f,0.120977f},{0.28916f,0.0101614f,0.120977f},{0.289705f,0.0102436f,0.124706f}, -{0.289157f,0.010161f,0.124706f},{0.288628f,0.0099979f,0.120977f},{0.288628f,0.0099979f,0.124706f}, -{0.288122f,0.00975468f,0.120977f},{0.288122f,0.00975468f,0.124706f},{0.307458f,0.00697787f,0.124706f}, -{0.307653f,0.00731578f,0.124706f},{0.307652f,0.00731414f,0.120977f},{0.307457f,0.0069765f,0.120977f}, -{0.307198f,0.00668793f,0.124706f},{0.307196f,0.00668696f,0.120977f},{0.306881f,0.0064583f,0.120977f}, -{0.306527f,0.00630061f,0.124706f},{0.306882f,0.00645891f,0.124706f},{0.306525f,0.00629975f,0.120977f}, -{0.306145f,0.00621902f,0.124706f},{0.306144f,0.00621892f,0.120977f},{0.305755f,0.00621887f,0.124706f}, -{0.305754f,0.00621902f,0.120977f},{0.305375f,0.00629969f,0.124706f},{0.305374f,0.0062999f,0.120977f}, -{0.305017f,0.0064585f,0.120977f},{0.305017f,0.0064585f,0.124706f},{0.307773f,0.00768493f,0.120977f}, -{0.307814f,0.00807242f,0.120977f},{0.307773f,0.00768652f,0.124706f},{0.307814f,0.00807346f,0.124706f}, -{0.307773f,0.00845934f,0.120977f},{0.307773f,0.0084618f,0.124706f},{0.307653f,0.0088308f,0.120977f}, -{0.307458f,0.00916863f,0.120977f},{0.307652f,0.00883225f,0.124706f},{0.307458f,0.00916944f,0.124706f}, -{0.307198f,0.00945768f,0.120977f},{0.307197f,0.00945846f,0.124706f},{0.306882f,0.00968775f,0.120977f}, -{0.306882f,0.00968775f,0.124706f},{0.304369f,0.0109506f,0.124706f},{0.304649f,0.0114367f,0.124706f}, -{0.304648f,0.0114328f,0.120977f},{0.30402f,0.0105126f,0.124706f},{0.304367f,0.0109474f,0.120977f}, -{0.304019f,0.0105118f,0.120977f},{0.303614f,0.0101356f,0.124706f},{0.303613f,0.0101351f,0.120977f}, -{0.303154f,0.00982233f,0.120977f},{0.303156f,0.00982376f,0.124706f},{0.302655f,0.00958174f,0.124706f}, -{0.301564f,0.00933222f,0.120977f},{0.30101f,0.00933241f,0.124706f},{0.301564f,0.00933231f,0.124706f}, -{0.302651f,0.00958f,0.120977f},{0.302118f,0.00941561f,0.124706f},{0.302116f,0.00941532f,0.120977f}, -{0.301008f,0.0093327f,0.120977f},{0.300462f,0.00941491f,0.124706f},{0.300459f,0.00941526f,0.120977f}, -{0.29993f,0.0095784f,0.120977f},{0.299424f,0.00982161f,0.124706f},{0.29993f,0.0095784f,0.124706f}, -{0.299424f,0.00982161f,0.120977f},{0.304853f,0.0119544f,0.120977f},{0.304976f,0.012495f,0.120977f}, -{0.304853f,0.0119556f,0.124706f},{0.304976f,0.0124959f,0.124706f},{0.305017f,0.0130469f,0.120977f}, -{0.305017f,0.0130492f,0.124706f},{0.304976f,0.0136022f,0.120977f},{0.304852f,0.0141497f,0.120977f}, -{0.304976f,0.0136064f,0.124706f},{0.304851f,0.0141522f,0.124706f},{0.304647f,0.0146713f,0.120977f}, -{0.304646f,0.014672f,0.124706f},{0.304369f,0.0151515f,0.120977f},{0.304024f,0.0155846f,0.120977f}, -{0.304368f,0.0151532f,0.124706f},{0.304023f,0.0155867f,0.124706f},{0.303617f,0.0159633f,0.120977f}, -{0.303617f,0.0159633f,0.124706f},{0.303153f,0.0162801f,0.120977f},{0.303153f,0.0162801f,0.124706f}, -{0.310416f,-0.00185425f,0.124706f},{0.310806f,-0.00185398f,0.124706f},{0.310805f,-0.00185425f,0.120977f}, -{0.310415f,-0.00185398f,0.120977f},{0.310035f,-0.0017734f,0.124706f},{0.310034f,-0.00177278f,0.120977f}, -{0.309678f,-0.0016145f,0.120977f},{0.309364f,-0.0013863f,0.124706f},{0.309679f,-0.00161492f,0.124706f}, -{0.309362f,-0.00138471f,0.120977f},{0.309103f,-0.00109643f,0.124706f},{0.309102f,-0.00109509f,0.120977f}, -{0.308908f,-0.000758756f,0.124706f},{0.308907f,-0.000757801f,0.120977f},{0.308787f,-0.000388892f,0.124706f}, -{0.308787f,-0.000387896f,0.120977f},{0.308746f,2.31914e-018f,0.120977f},{0.308746f,2.31914e-018f,0.124706f}, -{0.311186f,-0.0017734f,0.120977f},{0.311542f,-0.00161492f,0.120977f},{0.311188f,-0.00177278f,0.124706f}, -{0.311543f,-0.0016145f,0.124706f},{0.311857f,-0.0013863f,0.120977f},{0.311859f,-0.00138471f,0.124706f}, -{0.312119f,-0.00109643f,0.120977f},{0.312314f,-0.000758756f,0.120977f},{0.312119f,-0.00109509f,0.124706f}, -{0.312314f,-0.000757801f,0.124706f},{0.312434f,-0.000388892f,0.120977f},{0.312434f,-0.000387896f,0.124706f}, -{0.312475f,2.09082e-018f,0.120977f},{0.312475f,2.09082e-018f,0.124706f},{0.312313f,0.00280711f,0.124706f}, -{0.312873f,0.00280775f,0.124706f},{0.312869f,0.00280711f,0.120977f},{0.311758f,0.00289062f,0.124706f}, -{0.312308f,0.00280775f,0.120977f},{0.311757f,0.00289112f,0.120977f},{0.311229f,0.00305432f,0.124706f}, -{0.311228f,0.00305467f,0.120977f},{0.310728f,0.00329522f,0.120977f},{0.31073f,0.00329432f,0.124706f}, -{0.31027f,0.00360761f,0.124706f},{0.309508f,0.00442796f,0.120977f},{0.309231f,0.00490757f,0.124706f}, -{0.309508f,0.00442732f,0.124706f},{0.310266f,0.00361015f,0.120977f},{0.309858f,0.00398905f,0.124706f}, -{0.309856f,0.00399124f,0.120977f},{0.30923f,0.00490957f,0.120977f},{0.309029f,0.00542319f,0.124706f}, -{0.309028f,0.00542563f,0.120977f},{0.308905f,0.00596545f,0.120977f},{0.308862f,0.00652543f,0.124706f}, -{0.308905f,0.00596545f,0.124706f},{0.308862f,0.00652543f,0.120977f},{0.313423f,0.00289062f,0.120977f}, -{0.313953f,0.00305432f,0.120977f},{0.313425f,0.00289112f,0.124706f},{0.313954f,0.00305467f,0.124706f}, -{0.314452f,0.00329432f,0.120977f},{0.314454f,0.00329522f,0.124706f},{0.314912f,0.00360761f,0.120977f}, -{0.315324f,0.00398905f,0.120977f},{0.314916f,0.00361015f,0.124706f},{0.315326f,0.00399124f,0.124706f}, -{0.315673f,0.00442732f,0.120977f},{0.315674f,0.00442796f,0.124706f},{0.315951f,0.00490757f,0.120977f}, -{0.316153f,0.00542319f,0.120977f},{0.315951f,0.00490957f,0.124706f},{0.316154f,0.00542563f,0.124706f}, -{0.316277f,0.00596545f,0.120977f},{0.316277f,0.00596545f,0.124706f},{0.31632f,0.00652543f,0.120977f}, -{0.31632f,0.00652543f,0.124706f},{0.301289f,0.00279661f,0.0995366f},{0.301289f,0.00279661f,0.0976722f}, -{0.3008f,0.00275356f,0.0976722f},{0.300331f,0.00262748f,0.0976722f},{0.300801f,0.00275376f,0.0995366f}, -{0.300332f,0.00262801f,0.0995366f},{0.299893f,0.00242333f,0.0995366f},{0.299493f,0.00214411f,0.0995366f}, -{0.299891f,0.00242266f,0.0976722f},{0.299491f,0.00214219f,0.0976722f},{0.299146f,0.00179767f,0.0995366f}, -{0.299144f,0.00179504f,0.0976722f},{0.298866f,0.00139727f,0.0995366f},{0.298661f,0.000957717f,0.0995366f}, -{0.298865f,0.00139564f,0.0976722f},{0.298661f,0.000956449f,0.0976722f},{0.298535f,0.000488516f,0.0995366f}, -{0.298535f,0.000488516f,0.0976722f},{0.298492f,2.50765e-018f,0.0976722f},{0.298492f,2.50765e-018f,0.0995366f}, -{0.301777f,0.00275356f,0.0995366f},{0.302246f,0.00262748f,0.0995366f},{0.301776f,0.00275376f,0.0976722f}, -{0.302684f,0.00242333f,0.0976722f},{0.302245f,0.00262801f,0.0976722f},{0.302686f,0.00242266f,0.0995366f}, -{0.303084f,0.00214411f,0.0976722f},{0.303086f,0.00214219f,0.0995366f},{0.303431f,0.00179767f,0.0976722f}, -{0.303711f,0.00139727f,0.0976722f},{0.303433f,0.00179504f,0.0995366f},{0.303712f,0.00139564f,0.0995366f}, -{0.303916f,0.000957717f,0.0976722f},{0.303917f,0.000956449f,0.0995366f},{0.304042f,0.000488516f,0.0976722f}, -{0.304042f,0.000488516f,0.0995366f},{0.304085f,2.16517e-018f,0.0995366f},{0.304085f,2.16517e-018f,0.0976722f}, -{0.301289f,0.00745764f,0.0995366f},{0.300551f,0.00742114f,0.0995366f},{0.301289f,0.00745764f,0.100469f}, -{0.300551f,0.00742114f,0.100469f},{0.299827f,0.00731301f,0.0995366f},{0.29912f,0.00713527f,0.0995366f}, -{0.299827f,0.00731301f,0.100469f},{0.298435f,0.00688994f,0.0995366f},{0.29912f,0.00713527f,0.100469f}, -{0.298435f,0.00688994f,0.100469f},{0.297777f,0.00657906f,0.0995366f},{0.297151f,0.00620465f,0.0995366f}, -{0.297777f,0.00657906f,0.100469f},{0.296562f,0.00576874f,0.0995366f},{0.297151f,0.00620465f,0.100469f}, -{0.296562f,0.00576874f,0.100469f},{0.296015f,0.00527335f,0.0995366f},{0.29552f,0.00472635f,0.0995366f}, -{0.296015f,0.00527335f,0.100469f},{0.295084f,0.00413751f,0.0995366f},{0.29552f,0.00472635f,0.100469f}, -{0.295084f,0.00413751f,0.100469f},{0.294709f,0.00351173f,0.0995366f},{0.294399f,0.00285391f,0.0995366f}, -{0.294709f,0.00351173f,0.100469f},{0.294153f,0.00216893f,0.0995366f},{0.294399f,0.00285391f,0.100469f}, -{0.294153f,0.00216893f,0.100469f},{0.293976f,0.00146169f,0.0995366f},{0.293867f,0.000737081f,0.0995366f}, -{0.293976f,0.00146169f,0.100469f},{0.293831f,3.07846e-018f,0.0995366f},{0.293867f,0.000737081f,0.100469f}, -{0.293831f,3.07846e-018f,0.100469f},{0.302026f,0.00742114f,0.100469f},{0.30275f,0.00731301f,0.100469f}, -{0.302026f,0.00742114f,0.0995366f},{0.303457f,0.00713527f,0.100469f},{0.30275f,0.00731301f,0.0995366f}, -{0.303457f,0.00713527f,0.0995366f},{0.304142f,0.00688994f,0.100469f},{0.3048f,0.00657906f,0.100469f}, -{0.304142f,0.00688994f,0.0995366f},{0.305426f,0.00620465f,0.100469f},{0.3048f,0.00657906f,0.0995366f}, -{0.305426f,0.00620465f,0.0995366f},{0.306015f,0.00576874f,0.100469f},{0.306562f,0.00527335f,0.100469f}, -{0.306015f,0.00576874f,0.0995366f},{0.307057f,0.00472635f,0.100469f},{0.306562f,0.00527335f,0.0995366f}, -{0.307057f,0.00472635f,0.0995366f},{0.307493f,0.00413751f,0.100469f},{0.307868f,0.00351173f,0.100469f}, -{0.307493f,0.00413751f,0.0995366f},{0.308178f,0.00285391f,0.100469f},{0.307868f,0.00351173f,0.0995366f}, -{0.308178f,0.00285391f,0.0995366f},{0.308424f,0.00216893f,0.100469f},{0.308602f,0.00146169f,0.100469f}, -{0.308424f,0.00216893f,0.0995366f},{0.30871f,0.000737081f,0.100469f},{0.308602f,0.00146169f,0.0995366f}, -{0.30871f,0.000737081f,0.0995366f},{0.308746f,2.16517e-018f,0.100469f},{0.308746f,2.16517e-018f,0.0995366f}, -{0.296668f,0.0173925f,0.100469f},{0.296668f,0.0173922f,0.103265f},{0.296628f,0.0167797f,0.100469f}, -{0.296668f,0.0161668f,0.103265f},{0.296668f,0.0161672f,0.100469f},{0.296628f,0.0167797f,0.103265f}, -{0.296982f,0.014996f,0.100469f},{0.296982f,0.014996f,0.103265f},{0.29725f,0.0144523f,0.100469f}, -{0.296787f,0.0155699f,0.103265f},{0.296787f,0.0155702f,0.100469f},{0.29725f,0.0144519f,0.103265f}, -{0.297588f,0.0139455f,0.103265f},{0.297588f,0.0139458f,0.100469f},{0.297993f,0.0134838f,0.100469f}, -{0.297993f,0.0134838f,0.103265f},{0.298455f,0.0130791f,0.103265f},{0.298454f,0.0130793f,0.100469f}, -{0.298961f,0.0127415f,0.100469f},{0.298961f,0.0127414f,0.103265f},{0.299505f,0.0124735f,0.100469f}, -{0.299505f,0.0124735f,0.103265f},{0.300079f,0.0122783f,0.103265f},{0.300079f,0.0122784f,0.100469f}, -{0.301289f,0.0121187f,0.100469f},{0.300676f,0.0121592f,0.100469f},{0.300676f,0.012159f,0.103265f}, -{0.301289f,0.0121187f,0.103265f},{0.296787f,0.0179891f,0.103265f},{0.296787f,0.0179895f,0.100469f}, -{0.296982f,0.0185634f,0.103265f},{0.29725f,0.0191071f,0.103265f},{0.296982f,0.0185634f,0.100469f}, -{0.29725f,0.0191075f,0.100469f},{0.297588f,0.0196135f,0.103265f},{0.297588f,0.0196139f,0.100469f}, -{0.297993f,0.0200755f,0.103265f},{0.298454f,0.0204801f,0.103265f},{0.297993f,0.0200755f,0.100469f}, -{0.298455f,0.0204802f,0.100469f},{0.298961f,0.0208179f,0.103265f},{0.298961f,0.020818f,0.100469f}, -{0.299505f,0.0210859f,0.103265f},{0.300079f,0.0212809f,0.103265f},{0.299505f,0.0210859f,0.100469f}, -{0.300079f,0.0212811f,0.100469f},{0.300676f,0.0214002f,0.103265f},{0.300676f,0.0214003f,0.100469f}, -{0.301289f,0.0214407f,0.103265f},{0.301289f,0.0214407f,0.100469f},{0.318681f,0.00462066f,0.100469f}, -{0.318068f,0.00466102f,0.100469f},{0.318681f,0.00462066f,0.103265f},{0.317455f,0.00462052f,0.103265f}, -{0.318068f,0.00466102f,0.103265f},{0.317455f,0.00462052f,0.100469f},{0.316285f,0.00430621f,0.100469f}, -{0.31574f,0.00403818f,0.100469f},{0.316285f,0.00430621f,0.103265f},{0.316858f,0.00450127f,0.103265f}, -{0.316858f,0.00450127f,0.100469f},{0.31574f,0.00403818f,0.103265f},{0.315234f,0.00370041f,0.100469f}, -{0.315234f,0.00370041f,0.103265f},{0.314772f,0.00329584f,0.100469f},{0.314772f,0.00329584f,0.103265f}, -{0.314368f,0.00283386f,0.100469f},{0.314368f,0.00283386f,0.103265f},{0.31403f,0.00232743f,0.100469f}, -{0.313762f,0.00178369f,0.100469f},{0.31403f,0.00232743f,0.103265f},{0.313762f,0.00178369f,0.103265f}, -{0.313567f,0.00120944f,0.100469f},{0.313567f,0.00120944f,0.103265f},{0.313407f,1.10315e-019f,0.100469f}, -{0.313448f,0.000612502f,0.103265f},{0.313448f,0.000612502f,0.100469f},{0.313407f,1.10315e-019f,0.103265f}, -{0.319278f,0.00450141f,0.103265f},{0.319852f,0.00430621f,0.103265f},{0.319278f,0.00450141f,0.100469f}, -{0.320396f,0.00403832f,0.103265f},{0.319852f,0.00430621f,0.100469f},{0.320396f,0.00403832f,0.100469f}, -{0.320902f,0.00370055f,0.103265f},{0.321364f,0.00329584f,0.103265f},{0.320902f,0.00370055f,0.100469f}, -{0.321769f,0.0028342f,0.103265f},{0.321364f,0.00329584f,0.100469f},{0.321769f,0.0028342f,0.100469f}, -{0.322106f,0.00232777f,0.103265f},{0.322374f,0.00178369f,0.103265f},{0.322106f,0.00232777f,0.100469f}, -{0.322569f,0.00120978f,0.103265f},{0.322374f,0.00178369f,0.100469f},{0.322569f,0.00120978f,0.100469f}, -{0.322689f,0.000612842f,0.103265f},{0.322729f,6.81126e-019f,0.103265f},{0.322689f,0.000612842f,0.100469f}, -{0.322729f,6.81126e-019f,0.100469f},{0.305909f,-0.0173922f,0.103265f},{0.30595f,-0.0167797f,0.103265f}, -{0.305936f,-0.0171394f,0.100469f},{0.305877f,-0.0159621f,0.100469f},{0.305944f,-0.0165489f,0.100469f}, -{0.305909f,-0.0161668f,0.103265f},{0.305595f,-0.014996f,0.103265f},{0.305327f,-0.0144519f,0.103265f}, -{0.305525f,-0.0148373f,0.100469f},{0.305737f,-0.0153885f,0.100469f},{0.30579f,-0.0155699f,0.103265f}, -{0.304989f,-0.0139455f,0.103265f},{0.304902f,-0.0138368f,0.100469f},{0.305246f,-0.0143174f,0.100469f}, -{0.304584f,-0.0134838f,0.103265f},{0.304122f,-0.0130791f,0.103265f},{0.304049f,-0.0130241f,0.100469f}, -{0.304501f,-0.0134033f,0.100469f},{0.303616f,-0.0127414f,0.103265f},{0.303072f,-0.0124735f,0.103265f}, -{0.303552f,-0.0127048f,0.100469f},{0.302498f,-0.0122783f,0.103265f},{0.302457f,-0.0122704f,0.100469f}, -{0.303018f,-0.0124544f,0.100469f},{0.301878f,-0.0121554f,0.100469f},{0.301901f,-0.012159f,0.103265f}, -{0.301289f,-0.0121187f,0.103265f},{0.301289f,-0.0121187f,0.100469f},{0.305853f,-0.0177242f,0.100469f}, -{0.305697f,-0.018294f,0.100469f},{0.30579f,-0.0179891f,0.103265f},{0.305595f,-0.0185634f,0.103265f}, -{0.30547f,-0.0188393f,0.100469f},{0.305176f,-0.0193514f,0.100469f},{0.305327f,-0.0191071f,0.103265f}, -{0.30482f,-0.0198223f,0.100469f},{0.304989f,-0.0196135f,0.103265f},{0.304584f,-0.0200755f,0.103265f}, -{0.304407f,-0.0202443f,0.100469f},{0.303944f,-0.0206107f,0.100469f},{0.304123f,-0.0204801f,0.103265f}, -{0.303438f,-0.0209155f,0.100469f},{0.303616f,-0.0208179f,0.103265f},{0.303072f,-0.0210859f,0.103265f}, -{0.302898f,-0.0211542f,0.100469f},{0.302329f,-0.0213103f,0.100469f},{0.302498f,-0.0212809f,0.103265f}, -{0.30175f,-0.0214362f,0.100469f},{0.301901f,-0.0214002f,0.103265f},{0.301289f,-0.0214407f,0.103265f}, -{0.301289f,-0.0214407f,0.100469f},{0.2869f,0.0125242f,0.109791f},{0.28691f,0.01233f,0.100469f}, -{0.28691f,0.0127201f,0.100469f},{0.286992f,0.0131013f,0.100469f},{0.286936f,0.0128878f,0.109791f}, -{0.287041f,0.0132379f,0.109791f},{0.28738f,0.0137725f,0.100469f},{0.287214f,0.0135608f,0.109791f}, -{0.28715f,0.0134567f,0.100469f},{0.287669f,0.014033f,0.100469f},{0.287446f,0.0138436f,0.109791f}, -{0.287728f,0.0140755f,0.109791f},{0.288007f,0.0142276f,0.100469f},{0.288376f,0.0143478f,0.100469f}, -{0.288051f,0.0142478f,0.109791f},{0.288764f,0.0143886f,0.100469f},{0.288764f,0.0143886f,0.109791f}, -{0.288401f,0.0143539f,0.109791f},{0.286936f,0.01216f,0.109791f},{0.286991f,0.0119486f,0.100469f}, -{0.287043f,0.0118103f,0.109791f},{0.287216f,0.0114885f,0.109791f},{0.287149f,0.0115926f,0.100469f}, -{0.287448f,0.0112063f,0.109791f},{0.287378f,0.0112779f,0.100469f},{0.287668f,0.0110163f,0.100469f}, -{0.28773f,0.0109746f,0.109791f},{0.288052f,0.0108025f,0.109791f},{0.288006f,0.0108212f,0.100469f}, -{0.288401f,0.0106963f,0.109791f},{0.288375f,0.0107009f,0.100469f},{0.288764f,0.0106598f,0.100469f}, -{0.288764f,0.0106598f,0.109791f},{0.288764f,0.0125242f,0.110911f},{0.309971f,0.0105467f,0.109791f}, -{0.309981f,0.0103525f,0.100469f},{0.309981f,0.0107426f,0.100469f},{0.310062f,0.0111238f,0.100469f}, -{0.310007f,0.0109103f,0.109791f},{0.310112f,0.0112604f,0.109791f},{0.310451f,0.011795f,0.100469f}, -{0.310284f,0.0115833f,0.109791f},{0.310221f,0.0114792f,0.100469f},{0.31074f,0.0120555f,0.100469f}, -{0.310517f,0.0118661f,0.109791f},{0.310799f,0.012098f,0.109791f},{0.311077f,0.0122501f,0.100469f}, -{0.311447f,0.0123703f,0.100469f},{0.311122f,0.0122703f,0.109791f},{0.311835f,0.0124111f,0.100469f}, -{0.311835f,0.0124111f,0.109791f},{0.311472f,0.0123763f,0.109791f},{0.310007f,0.0101825f,0.109791f}, -{0.310062f,0.00997107f,0.100469f},{0.310114f,0.00983283f,0.109791f},{0.310287f,0.00951095f,0.109791f}, -{0.31022f,0.00961513f,0.100469f},{0.310519f,0.00922876f,0.109791f},{0.310449f,0.00930035f,0.100469f}, -{0.310739f,0.00903878f,0.100469f},{0.310801f,0.0089971f,0.109791f},{0.311123f,0.008825f,0.109791f}, -{0.311076f,0.00884365f,0.100469f},{0.311472f,0.00871884f,0.109791f},{0.311446f,0.00872342f,0.100469f}, -{0.311835f,0.00868228f,0.100469f},{0.311835f,0.00868228f,0.109791f},{0.311835f,0.0105467f,0.110911f}, -{0.311948f,-0.0125242f,0.109791f},{0.311958f,-0.0127183f,0.100469f},{0.311959f,-0.0123283f,0.100469f}, -{0.31204f,-0.0119471f,0.100469f},{0.311984f,-0.0121606f,0.109791f},{0.31209f,-0.0118105f,0.109791f}, -{0.312428f,-0.0112759f,0.100469f},{0.312262f,-0.0114876f,0.109791f},{0.312198f,-0.0115917f,0.100469f}, -{0.312718f,-0.0110154f,0.100469f},{0.312494f,-0.0112048f,0.109791f},{0.312777f,-0.0109729f,0.109791f}, -{0.313055f,-0.0108208f,0.100469f},{0.313425f,-0.0107006f,0.100469f},{0.313099f,-0.0108006f,0.109791f}, -{0.313813f,-0.0106598f,0.100469f},{0.313813f,-0.0106598f,0.109791f},{0.313449f,-0.0106945f,0.109791f}, -{0.311985f,-0.0128884f,0.109791f},{0.312039f,-0.0130998f,0.100469f},{0.312092f,-0.0132381f,0.109791f}, -{0.312264f,-0.0135599f,0.109791f},{0.312198f,-0.0134558f,0.100469f},{0.312496f,-0.0138421f,0.109791f}, -{0.312426f,-0.0137705f,0.100469f},{0.312716f,-0.0140321f,0.100469f},{0.312778f,-0.0140738f,0.109791f}, -{0.3131f,-0.0142459f,0.109791f},{0.313054f,-0.0142272f,0.100469f},{0.31345f,-0.0143521f,0.109791f}, -{0.313424f,-0.0143475f,0.100469f},{0.313813f,-0.0143886f,0.100469f},{0.313813f,-0.0143886f,0.109791f}, -{0.313813f,-0.0125242f,0.110911f},{0.288877f,-0.0105467f,0.109791f},{0.288888f,-0.0107408f,0.100469f}, -{0.288888f,-0.0103508f,0.100469f},{0.288969f,-0.0099696f,0.100469f},{0.288913f,-0.010183f,0.109791f}, -{0.289019f,-0.00983297f,0.109791f},{0.289357f,-0.00929843f,0.100469f},{0.289191f,-0.00951009f,0.109791f}, -{0.289127f,-0.00961418f,0.100469f},{0.289647f,-0.00903788f,0.100469f},{0.289423f,-0.0092273f,0.109791f}, -{0.289706f,-0.00899543f,0.109791f},{0.289984f,-0.00884326f,0.100469f},{0.290354f,-0.0087231f,0.100469f}, -{0.290028f,-0.00882313f,0.109791f},{0.290742f,-0.00868228f,0.100469f},{0.290742f,-0.00868228f,0.109791f}, -{0.290378f,-0.00871703f,0.109791f},{0.288914f,-0.0109109f,0.109791f},{0.288968f,-0.0111223f,0.100469f}, -{0.289021f,-0.0112606f,0.109791f},{0.289193f,-0.0115824f,0.109791f},{0.289127f,-0.0114782f,0.100469f}, -{0.289425f,-0.0118646f,0.109791f},{0.289356f,-0.011793f,0.100469f},{0.289645f,-0.0120546f,0.100469f}, -{0.289707f,-0.0120963f,0.109791f},{0.290029f,-0.0122684f,0.109791f},{0.289983f,-0.0122497f,0.100469f}, -{0.290379f,-0.0123745f,0.109791f},{0.290353f,-0.01237f,0.100469f},{0.290742f,-0.0124111f,0.100469f}, -{0.290742f,-0.0124111f,0.109791f},{0.290742f,-0.0105467f,0.110911f},{0.283896f,-0.00462052f,0.100469f}, -{0.283896f,-0.00462066f,0.103265f},{0.284509f,-0.00466102f,0.100469f},{0.285122f,-0.00462052f,0.103265f}, -{0.285121f,-0.00462066f,0.100469f},{0.284509f,-0.00466102f,0.103265f},{0.286293f,-0.00430621f,0.100469f}, -{0.286293f,-0.00430621f,0.103265f},{0.286836f,-0.00403832f,0.100469f},{0.285719f,-0.00450127f,0.103265f}, -{0.285718f,-0.00450141f,0.100469f},{0.286837f,-0.00403818f,0.103265f},{0.287343f,-0.00370041f,0.103265f}, -{0.287343f,-0.00370055f,0.100469f},{0.287805f,-0.00329584f,0.100469f},{0.287805f,-0.00329584f,0.103265f}, -{0.288209f,-0.00283386f,0.103265f},{0.288209f,-0.0028342f,0.100469f},{0.288547f,-0.00232777f,0.100469f}, -{0.288547f,-0.00232743f,0.103265f},{0.288815f,-0.00178369f,0.100469f},{0.288815f,-0.00178369f,0.103265f}, -{0.28901f,-0.00120944f,0.103265f},{0.28901f,-0.00120978f,0.100469f},{0.28917f,2.73598e-018f,0.100469f}, -{0.289129f,-0.000612842f,0.100469f},{0.28913f,-0.000612502f,0.103265f},{0.28917f,2.73598e-018f,0.103265f}, -{0.283299f,-0.00450141f,0.103265f},{0.283299f,-0.00450127f,0.100469f},{0.282725f,-0.00430621f,0.103265f}, -{0.282181f,-0.00403832f,0.103265f},{0.282725f,-0.00430621f,0.100469f},{0.282181f,-0.00403818f,0.100469f}, -{0.281675f,-0.00370055f,0.103265f},{0.281675f,-0.00370041f,0.100469f},{0.281213f,-0.00329584f,0.103265f}, -{0.280808f,-0.0028342f,0.103265f},{0.281213f,-0.00329584f,0.100469f},{0.280808f,-0.00283386f,0.100469f}, -{0.280471f,-0.00232777f,0.103265f},{0.280471f,-0.00232743f,0.100469f},{0.280203f,-0.00178369f,0.103265f}, -{0.280008f,-0.00120978f,0.103265f},{0.280203f,-0.00178369f,0.100469f},{0.280007f,-0.00120944f,0.100469f}, -{0.279888f,-0.000612842f,0.103265f},{0.279888f,-0.000612502f,0.100469f},{0.279848f,2.16517e-018f,0.103265f}, -{0.279848f,2.16517e-018f,0.100469f},{0.326779f,0.00272711f,0.120977f},{0.326887f,0.00137858f,0.119113f}, -{0.326777f,0.00274679f,0.119113f},{0.326344f,0.00542344f,0.120977f},{0.32634f,0.00544141f,0.119113f}, -{0.326016f,0.00676244f,0.119113f},{0.326888f,0.00136573f,0.120977f},{0.326924f,5.30462e-018f,0.119113f}, -{0.326924f,1.3464e-013f,0.120977f},{0.326597f,0.0040808f,0.120977f},{0.326594f,0.00410196f,0.119113f}, -{0.325479f,0.00848488f,0.120977f},{0.325943f,0.00696342f,0.120977f},{0.325623f,0.00806238f,0.119113f}, -{0.32349f,0.0128178f,0.120977f},{0.324242f,0.0114155f,0.120977f},{0.324042f,0.0118088f,0.119113f}, -{0.324906f,0.00996949f,0.120977f},{0.325163f,0.00933854f,0.119113f},{0.324635f,0.0105882f,0.119113f}, -{0.321881f,0.0152688f,0.119113f},{0.321037f,0.0163461f,0.119113f},{0.321731f,0.0154686f,0.120977f}, -{0.323385f,0.0129975f,0.119113f},{0.322664f,0.0141518f,0.119113f},{0.322652f,0.0141704f,0.120977f}, -{0.31917f,0.0183698f,0.119113f},{0.318513f,0.0189869f,0.120977f},{0.319652f,0.017875f,0.120977f}, -{0.320132f,0.0173811f,0.119113f},{0.320732f,0.0167072f,0.120977f},{0.315039f,0.0216356f,0.120977f}, -{0.316831f,0.0203871f,0.120977f},{0.316004f,0.0209918f,0.119113f},{0.318157f,0.0193037f,0.119113f}, -{0.312491f,0.0230585f,0.119113f},{0.311255f,0.0236188f,0.119113f},{0.311174f,0.0236531f,0.120977f}, -{0.313696f,0.0224332f,0.119113f},{0.31315f,0.0227263f,0.120977f},{0.307393f,0.0248983f,0.119113f}, -{0.307414f,0.024878f,0.120977f},{0.308704f,0.0245398f,0.119113f},{0.309119f,0.0244103f,0.120977f}, -{0.309992f,0.0241129f,0.119113f},{0.303937f,0.0254985f,0.120977f},{0.304714f,0.0254058f,0.119113f}, -{0.303352f,0.0255525f,0.119113f},{0.306062f,0.0251874f,0.119113f},{0.305688f,0.0252555f,0.120977f}, -{0.302173f,0.0256204f,0.120977f},{0.300598f,0.0256263f,0.119113f},{0.300405f,0.0256204f,0.120977f}, -{0.301978f,0.0256264f,0.119113f},{0.297862f,0.0254057f,0.119113f},{0.296515f,0.0251873f,0.119113f}, -{0.29689f,0.0252554f,0.120977f},{0.298641f,0.0254985f,0.120977f},{0.299224f,0.0255524f,0.119113f}, -{0.292585f,0.0241129f,0.119113f},{0.293458f,0.0244103f,0.120977f},{0.293873f,0.0245398f,0.119113f}, -{0.295161f,0.0248864f,0.120977f},{0.295184f,0.0248983f,0.119113f},{0.289427f,0.0227264f,0.120977f}, -{0.291404f,0.0236533f,0.120977f},{0.290086f,0.0230584f,0.119113f},{0.291322f,0.0236187f,0.119113f}, -{0.287538f,0.0216357f,0.120977f},{0.287709f,0.0217438f,0.119113f},{0.286573f,0.0209917f,0.119113f}, -{0.288881f,0.0224331f,0.119113f},{0.28442f,0.0193036f,0.119113f},{0.283407f,0.0183692f,0.119113f}, -{0.284064f,0.0189869f,0.120977f},{0.285747f,0.0203873f,0.120977f},{0.285476f,0.020178f,0.119113f}, -{0.282444f,0.0173806f,0.119113f},{0.28154f,0.016346f,0.119113f},{0.281845f,0.0167073f,0.120977f}, -{0.282931f,0.0178697f,0.120977f},{0.280846f,0.0154687f,0.120977f},{0.280696f,0.0152688f,0.119113f}, -{0.279913f,0.0141517f,0.119113f},{0.279926f,0.0141707f,0.120977f},{0.279192f,0.0129974f,0.119113f}, -{0.279087f,0.0128178f,0.120977f},{0.278535f,0.0118086f,0.119113f},{0.278335f,0.0114158f,0.120977f}, -{0.277671f,0.0099697f,0.120977f},{0.277942f,0.010588f,0.119113f},{0.277414f,0.00933828f,0.119113f}, -{0.277098f,0.00848516f,0.120977f},{0.276954f,0.00806211f,0.119113f},{0.276627f,0.00696571f,0.120977f}, -{0.276233f,0.00542344f,0.120977f},{0.276561f,0.00676218f,0.119113f},{0.275983f,0.00410176f,0.119113f}, -{0.276237f,0.00544117f,0.119113f},{0.2758f,0.00274665f,0.119113f},{0.27598f,0.00408095f,0.120977f}, -{0.275798f,0.00272732f,0.120977f},{0.27569f,0.0013785f,0.119113f},{0.275653f,2.16517e-018f,0.119113f}, -{0.275689f,0.00136552f,0.120977f},{0.275653f,-1.34633e-013f,0.120977f},{0.314868f,0.0217439f,0.119113f}, -{0.317101f,0.0201781f,0.119113f},{0.325992f,-3.74266e-017f,0.103079f},{0.32739f,-6.52846e-018f,0.104198f}, -{0.327333f,-0.00172399f,0.104198f},{0.316166f,0.0173288f,0.101587f},{0.315415f,0.0161291f,0.100469f}, -{0.314325f,0.0170222f,0.100469f},{0.316449f,0.0151609f,0.100469f},{0.314477f,0.0186467f,0.101587f}, -{0.31577f,0.0217163f,0.104198f},{0.31364f,0.0213938f,0.103079f},{0.314323f,0.0226142f,0.104198f}, -{0.313184f,0.0178384f,0.100469f},{0.312708f,0.0197792f,0.101587f},{0.312824f,0.0234144f,0.104198f}, -{0.310764f,0.0192333f,0.100469f},{0.311277f,0.0241148f,0.104198f},{0.309494f,0.0198086f,0.100469f}, -{0.309689f,0.0247131f,0.104198f},{0.308188f,0.0203001f,0.100469f},{0.306853f,0.0207061f,0.100469f}, -{0.308063f,0.0252074f,0.104198f},{0.305491f,0.0210249f,0.100469f},{0.306404f,0.0255955f,0.104198f}, -{0.30472f,0.0258753f,0.104198f},{0.304107f,0.0212548f,0.100469f},{0.303013f,0.0260447f,0.104198f}, -{0.302704f,0.021394f,0.100469f},{0.301289f,0.0261017f,0.104198f},{0.317749f,0.0158329f,0.101587f}, -{0.317418f,0.0141266f,0.100469f},{0.319198f,0.0141734f,0.101587f},{0.318311f,0.0130367f,0.100469f}, -{0.319127f,0.0118953f,0.100469f},{0.320489f,0.0123685f,0.101587f},{0.319865f,0.010707f,0.100469f}, -{0.3216f,0.0104425f,0.101587f},{0.320522f,0.00947547f,0.100469f},{0.322518f,0.00842229f,0.101587f}, -{0.321097f,0.00820499f,0.100469f},{0.326496f,0.00677384f,0.104198f},{0.326884f,0.00511591f,0.104198f}, -{0.325567f,0.0045642f,0.103079f},{0.323231f,0.00633756f,0.101587f},{0.321589f,0.0069f,0.100469f}, -{0.323734f,0.00421935f,0.101587f},{0.321995f,0.00556442f,0.100469f},{0.322313f,0.00420236f,0.100469f}, -{0.324031f,0.00209692f,0.101587f},{0.322543f,0.00281829f,0.100469f},{0.327333f,0.00172376f,0.104198f}, -{0.324128f,-3.56201e-017f,0.101587f},{0.322682f,0.00141614f,0.100469f},{0.322535f,-0.00288015f,0.100469f}, -{0.322681f,-0.00144343f,0.100469f},{0.327164f,-0.00343096f,0.104198f},{0.321524f,-0.00708591f,0.100469f}, -{0.321955f,-0.00570761f,0.100469f},{0.326002f,-0.0084f,0.104198f},{0.322293f,-0.00430368f,0.100469f}, -{0.326884f,-0.00511591f,0.104198f},{0.326496f,-0.00677408f,0.104198f},{0.320389f,-0.00973971f,0.100469f}, -{0.323903f,-0.0130346f,0.104198f},{0.31969f,-0.0110032f,0.100469f},{0.325403f,-0.00998868f,0.104198f}, -{0.324703f,-0.0115354f,0.104198f},{0.321002f,-0.00843197f,0.100469f},{0.322011f,-0.0158708f,0.104198f}, -{0.320924f,-0.0171976f,0.104198f},{0.318046f,-0.0133753f,0.100469f},{0.318908f,-0.012217f,0.100469f}, -{0.323005f,-0.0144813f,0.104198f},{0.317159f,-0.0207227f,0.104198f},{0.31502f,-0.0164663f,0.100469f}, -{0.318486f,-0.0196355f,0.104198f},{0.316097f,-0.0155046f,0.100469f},{0.317107f,-0.0144728f,0.100469f}, -{0.319745f,-0.0184567f,0.104198f},{0.311436f,-0.0188871f,0.100469f},{0.312684f,-0.0181615f,0.100469f}, -{0.312708f,-0.0197792f,0.101587f},{0.313881f,-0.0173533f,0.100469f},{0.31364f,-0.0213938f,0.103079f}, -{0.314323f,-0.0226143f,0.104198f},{0.312269f,-0.0221291f,0.103079f},{0.310832f,-0.0227855f,0.103079f}, -{0.311277f,-0.0241148f,0.104198f},{0.309337f,-0.0233556f,0.103079f},{0.312824f,-0.0234145f,0.104198f}, -{0.307791f,-0.0238322f,0.103079f},{0.308062f,-0.0252075f,0.104198f},{0.306203f,-0.0242096f,0.103079f}, -{0.309688f,-0.0247132f,0.104198f},{0.304583f,-0.0244827f,0.103079f},{0.306404f,-0.0255955f,0.104198f}, -{0.304719f,-0.0258754f,0.104198f},{0.303012f,-0.0260448f,0.104198f},{0.302942f,-0.0246481f,0.103079f}, -{0.301289f,-0.0261017f,0.104198f},{0.301289f,-0.0247034f,0.103079f},{0.31577f,-0.0217163f,0.104198f}, -{0.305832f,-0.0223824f,0.101587f},{0.306042f,-0.0209041f,0.100469f},{0.3073f,-0.0220336f,0.101587f}, -{0.304335f,-0.022635f,0.101587f},{0.304624f,-0.0211784f,0.100469f},{0.303191f,-0.0213558f,0.100469f}, -{0.302817f,-0.0227878f,0.101587f},{0.301289f,-0.022839f,0.101587f},{0.307439f,-0.0205399f,0.100469f}, -{0.308807f,-0.0200791f,0.100469f},{0.310112f,-0.0210659f,0.101587f},{0.308729f,-0.0215929f,0.101587f}, -{0.310142f,-0.0195273f,0.100469f},{0.31144f,-0.0204589f,0.101587f},{0.315552f,0.0201691f,0.103079f}, -{0.311995f,0.018576f,0.100469f},{0.31738f,0.0187435f,0.103079f},{0.317159f,0.0207226f,0.104198f}, -{0.319745f,0.0184567f,0.104198f},{0.318486f,0.0196354f,0.104198f},{0.319092f,0.017126f,0.103079f}, -{0.320659f,0.015331f,0.103079f},{0.320924f,0.0171974f,0.104198f},{0.323005f,0.0144813f,0.104198f}, -{0.322011f,0.0158706f,0.104198f},{0.322055f,0.0133791f,0.103079f},{0.323258f,0.011296f,0.103079f}, -{0.323903f,0.0130343f,0.104198f},{0.324703f,0.0115351f,0.104198f},{0.324251f,0.00911062f,0.103079f}, -{0.325403f,0.00998868f,0.104198f},{0.325022f,0.00685616f,0.103079f},{0.326002f,0.00839976f,0.104198f}, -{0.325888f,0.00226928f,0.103079f},{0.327164f,0.00343072f,0.104198f},{0.322729f,3.81816e-017f,0.104198f}, -{0.322729f,-7.35642e-018f,0.10513f},{0.322692f,-0.00125938f,0.10513f},{0.322582f,-0.00250813f,0.10513f}, -{0.322692f,-0.00125925f,0.104198f},{0.3224f,-0.00374334f,0.10513f},{0.322582f,-0.00250793f,0.104198f}, -{0.3224f,-0.00374312f,0.104198f},{0.322147f,-0.00496208f,0.10513f},{0.321825f,-0.00616144f,0.10513f}, -{0.322147f,-0.00496191f,0.104198f},{0.321434f,-0.00733859f,0.10513f},{0.321825f,-0.00616138f,0.104198f}, -{0.321434f,-0.0073385f,0.104198f},{0.320976f,-0.00849054f,0.10513f},{0.320453f,-0.0096143f,0.10513f}, -{0.320976f,-0.00849036f,0.104198f},{0.319865f,-0.010707f,0.10513f},{0.320453f,-0.00961408f,0.104198f}, -{0.319865f,-0.0107068f,0.104198f},{0.319213f,-0.0117656f,0.10513f},{0.318499f,-0.0127873f,0.10513f}, -{0.319213f,-0.0117655f,0.104198f},{0.317724f,-0.0137693f,0.10513f},{0.318499f,-0.0127873f,0.104198f}, -{0.317724f,-0.0137691f,0.104198f},{0.316888f,-0.0147088f,0.10513f},{0.315997f,-0.0156004f,0.10513f}, -{0.316889f,-0.0147082f,0.104198f},{0.315058f,-0.0164352f,0.10513f},{0.315997f,-0.0155998f,0.104198f}, -{0.315058f,-0.0164352f,0.104198f},{0.314076f,-0.0172102f,0.10513f},{0.313054f,-0.0179243f,0.10513f}, -{0.314076f,-0.0172102f,0.104198f},{0.311995f,-0.018576f,0.10513f},{0.313054f,-0.0179242f,0.104198f}, -{0.311996f,-0.018576f,0.104198f},{0.310903f,-0.0191643f,0.10513f},{0.309779f,-0.019688f,0.10513f}, -{0.310903f,-0.0191643f,0.104198f},{0.308627f,-0.0201457f,0.10513f},{0.309779f,-0.0196879f,0.104198f}, -{0.308627f,-0.0201457f,0.104198f},{0.30745f,-0.0205363f,0.10513f},{0.30625f,-0.0208587f,0.10513f}, -{0.30745f,-0.0205363f,0.104198f},{0.306251f,-0.0208586f,0.104198f},{0.305032f,-0.0211114f,0.104198f}, -{0.303797f,-0.0212935f,0.104198f},{0.305032f,-0.0211115f,0.10513f},{0.302548f,-0.0214037f,0.10513f}, -{0.303796f,-0.0212936f,0.10513f},{0.301289f,-0.0214407f,0.10513f},{0.302548f,-0.0214037f,0.104198f}, -{0.301289f,-0.0214407f,0.104198f},{0.322692f,0.00125938f,0.104198f},{0.322582f,0.00250813f,0.104198f}, -{0.322692f,0.00125925f,0.10513f},{0.322582f,0.00250793f,0.10513f},{0.3224f,0.00374334f,0.104198f}, -{0.322147f,0.00496208f,0.104198f},{0.3224f,0.00374312f,0.10513f},{0.321825f,0.00616144f,0.104198f}, -{0.322147f,0.00496191f,0.10513f},{0.321825f,0.00616138f,0.10513f},{0.321434f,0.00733859f,0.104198f}, -{0.320976f,0.00849054f,0.104198f},{0.321434f,0.0073385f,0.10513f},{0.320453f,0.0096143f,0.104198f}, -{0.320976f,0.00849036f,0.10513f},{0.320453f,0.00961408f,0.10513f},{0.319865f,0.010707f,0.104198f}, -{0.319213f,0.0117656f,0.104198f},{0.319865f,0.0107068f,0.10513f},{0.318499f,0.0127873f,0.104198f}, -{0.319213f,0.0117655f,0.10513f},{0.318499f,0.0127873f,0.10513f},{0.317724f,0.0137693f,0.104198f}, -{0.316888f,0.0147088f,0.104198f},{0.317724f,0.0137691f,0.10513f},{0.315997f,0.0156004f,0.104198f}, -{0.316889f,0.0147082f,0.10513f},{0.315997f,0.0155998f,0.10513f},{0.315058f,0.0164352f,0.104198f}, -{0.314076f,0.0172102f,0.104198f},{0.315058f,0.0164352f,0.10513f},{0.313054f,0.0179243f,0.104198f}, -{0.314076f,0.0172102f,0.10513f},{0.313054f,0.0179242f,0.10513f},{0.311995f,0.018576f,0.104198f}, -{0.310903f,0.0191643f,0.104198f},{0.311996f,0.018576f,0.10513f},{0.309779f,0.019688f,0.104198f}, -{0.310903f,0.0191643f,0.10513f},{0.309779f,0.0196879f,0.10513f},{0.308627f,0.0201457f,0.104198f}, -{0.30745f,0.0205363f,0.104198f},{0.308627f,0.0201457f,0.10513f},{0.30625f,0.0208587f,0.104198f}, -{0.30745f,0.0205363f,0.10513f},{0.305032f,0.0211114f,0.10513f},{0.306251f,0.0208586f,0.10513f}, -{0.305032f,0.0211115f,0.104198f},{0.303797f,0.0212935f,0.10513f},{0.303796f,0.0212936f,0.104198f}, -{0.302548f,0.0214037f,0.104198f},{0.302548f,0.0214037f,0.10513f},{0.301289f,0.0214407f,0.104198f}, -{0.301289f,0.0214407f,0.10513f},{0.32739f,1.99664e-017f,0.10513f},{0.32739f,2.41062e-017f,0.119113f}, -{0.327354f,-0.00138032f,0.119113f},{0.327245f,-0.00275048f,0.119113f},{0.327354f,-0.00138025f,0.10513f}, -{0.327065f,-0.0041079f,0.119113f},{0.327245f,-0.00275036f,0.10513f},{0.327065f,-0.00410773f,0.10513f}, -{0.326815f,-0.00544996f,0.119113f},{0.326496f,-0.00677408f,0.119113f},{0.326815f,-0.00544975f,0.10513f}, -{0.326109f,-0.00807765f,0.119113f},{0.326496f,-0.00677384f,0.10513f},{0.326109f,-0.0080774f,0.10513f}, -{0.325655f,-0.00935809f,0.119113f},{0.325135f,-0.0106128f,0.119113f},{0.325655f,-0.00935782f,0.10513f}, -{0.324551f,-0.0118391f,0.119113f},{0.325135f,-0.0106125f,0.10513f},{0.324551f,-0.0118389f,0.10513f}, -{0.323903f,-0.0130346f,0.119113f},{0.323192f,-0.0141964f,0.119113f},{0.323903f,-0.0130343f,0.10513f}, -{0.32242f,-0.0153222f,0.119113f},{0.323192f,-0.0141962f,0.10513f},{0.32242f,-0.015322f,0.10513f}, -{0.321587f,-0.0164092f,0.119113f},{0.320695f,-0.0174549f,0.119113f},{0.321587f,-0.0164091f,0.10513f}, -{0.319745f,-0.0184567f,0.119113f},{0.320695f,-0.0174549f,0.10513f},{0.319745f,-0.0184567f,0.10513f}, -{0.318743f,-0.0194069f,0.119113f},{0.317698f,-0.0202989f,0.119113f},{0.318743f,-0.0194069f,0.10513f}, -{0.316611f,-0.0211315f,0.119113f},{0.317698f,-0.0202988f,0.10513f},{0.316611f,-0.0211314f,0.10513f}, -{0.315485f,-0.0219036f,0.119113f},{0.314323f,-0.0226143f,0.119113f},{0.315485f,-0.0219036f,0.10513f}, -{0.313127f,-0.0232624f,0.119113f},{0.314323f,-0.0226142f,0.10513f},{0.313128f,-0.0232623f,0.10513f}, -{0.311901f,-0.0238468f,0.119113f},{0.310646f,-0.0243666f,0.119113f},{0.311901f,-0.0238467f,0.10513f}, -{0.309366f,-0.0248205f,0.119113f},{0.310647f,-0.0243664f,0.10513f},{0.309366f,-0.0248204f,0.10513f}, -{0.308062f,-0.0252075f,0.119113f},{0.306738f,-0.0255265f,0.119113f},{0.308063f,-0.0252074f,0.10513f}, -{0.305396f,-0.0257766f,0.119113f},{0.306739f,-0.0255265f,0.10513f},{0.305396f,-0.0257765f,0.10513f}, -{0.304039f,-0.0259565f,0.119113f},{0.302669f,-0.0260653f,0.119113f},{0.304039f,-0.0259565f,0.10513f}, -{0.301289f,-0.0261017f,0.119113f},{0.302669f,-0.0260652f,0.10513f},{0.301289f,-0.0261017f,0.10513f}, -{0.327354f,0.00138032f,0.10513f},{0.327245f,0.00275048f,0.10513f},{0.327354f,0.00138025f,0.119113f}, -{0.327245f,0.00275036f,0.119113f},{0.327065f,0.0041079f,0.10513f},{0.326815f,0.00544996f,0.10513f}, -{0.327065f,0.00410773f,0.119113f},{0.326496f,0.00677408f,0.10513f},{0.326815f,0.00544975f,0.119113f}, -{0.326496f,0.00677384f,0.119113f},{0.326109f,0.00807765f,0.10513f},{0.325655f,0.00935809f,0.10513f}, -{0.326109f,0.0080774f,0.119113f},{0.325135f,0.0106128f,0.10513f},{0.325655f,0.00935782f,0.119113f}, -{0.325135f,0.0106125f,0.119113f},{0.324551f,0.0118391f,0.10513f},{0.323903f,0.0130346f,0.10513f}, -{0.324551f,0.0118389f,0.119113f},{0.323192f,0.0141964f,0.10513f},{0.323903f,0.0130343f,0.119113f}, -{0.323192f,0.0141962f,0.119113f},{0.32242f,0.0153222f,0.10513f},{0.321587f,0.0164092f,0.10513f}, -{0.32242f,0.015322f,0.119113f},{0.320695f,0.0174549f,0.10513f},{0.321587f,0.0164091f,0.119113f}, -{0.320695f,0.0174549f,0.119113f},{0.319745f,0.0184567f,0.10513f},{0.318743f,0.0194069f,0.10513f}, -{0.319745f,0.0184567f,0.119113f},{0.317698f,0.0202989f,0.10513f},{0.318743f,0.0194069f,0.119113f}, -{0.317698f,0.0202988f,0.119113f},{0.316611f,0.0211315f,0.10513f},{0.315485f,0.0219036f,0.10513f}, -{0.316611f,0.0211314f,0.119113f},{0.314323f,0.0226143f,0.10513f},{0.315485f,0.0219036f,0.119113f}, -{0.314323f,0.0226142f,0.119113f},{0.313127f,0.0232624f,0.10513f},{0.311901f,0.0238468f,0.10513f}, -{0.313128f,0.0232623f,0.119113f},{0.310646f,0.0243666f,0.10513f},{0.311901f,0.0238467f,0.119113f}, -{0.310647f,0.0243664f,0.119113f},{0.309366f,0.0248205f,0.10513f},{0.308062f,0.0252075f,0.10513f}, -{0.309366f,0.0248204f,0.119113f},{0.306738f,0.0255265f,0.10513f},{0.308063f,0.0252074f,0.119113f}, -{0.306739f,0.0255265f,0.119113f},{0.305396f,0.0257766f,0.10513f},{0.304039f,0.0259565f,0.10513f}, -{0.305396f,0.0257765f,0.119113f},{0.302669f,0.0260653f,0.10513f},{0.304039f,0.0259565f,0.119113f}, -{0.302669f,0.0260652f,0.119113f},{0.301289f,0.0261017f,0.10513f},{0.301289f,0.0261017f,0.119113f}, -{0.313422f,-0.00289006f,0.124706f},{0.286299f,0.00596973f,0.124706f},{0.286258f,0.00652514f,0.124706f}, -{0.282163f,0.00374099f,0.124706f},{0.293181f,-0.0152805f,0.124706f},{0.292666f,0.0149353f,0.124706f}, -{0.29756f,0.0130513f,0.124706f},{0.293181f,0.0152802f,0.124706f},{0.289069f,0.0144863f,0.124706f}, -{0.288486f,0.0146944f,0.124706f},{0.288278f,0.0103166f,0.124706f},{0.306525f,0.00984656f,0.124706f}, -{0.306144f,0.00992732f,0.124706f},{0.299424f,0.0162797f,0.124706f},{0.297508f,0.0215779f,0.124706f}, -{0.294991f,0.019053f,0.124706f},{0.310727f,0.00975506f,0.124706f},{0.310468f,0.0146618f,0.124706f}, -{0.309911f,0.0149353f,0.124706f},{0.310266f,0.00944145f,0.124706f},{0.318534f,3.09663e-018f,0.124706f}, -{0.318576f,0.000618856f,0.124706f},{0.312283f,0.0143109f,0.124706f},{0.312313f,0.0102438f,0.124706f}, -{0.31287f,0.0102437f,0.124706f},{0.322087f,-0.00452954f,0.124706f},{0.322334f,-0.00608354f,0.124706f}, -{0.322699f,-0.00463457f,0.124706f},{0.318698f,-0.00122583f,0.124706f},{0.318576f,-0.000618365f,0.124706f}, -{0.314916f,-0.00361044f,0.124706f},{0.320415f,-0.00374099f,0.124706f},{0.316278f,-0.00596973f,0.124706f}, -{0.316319f,-0.00652514f,0.124706f},{0.3215f,-0.00433369f,0.124706f},{0.316278f,-0.00708106f,0.124706f}, -{0.316153f,-0.00762403f,0.124706f},{0.321297f,-0.00891935f,0.124706f},{0.311229f,-0.00305413f,0.124706f}, -{0.311762f,-0.00288693f,0.124706f},{0.31567f,-0.00862484f,0.124706f},{0.319869f,-0.0116055f,0.124706f}, -{0.32063f,-0.0102864f,0.124706f},{0.321866f,-0.00751463f,0.124706f},{0.320938f,-0.00407246f,0.124706f}, -{0.318086f,-0.0140624f,0.124706f},{0.314643f,-0.0149788f,0.124706f},{0.31708f,-0.0151839f,0.124706f}, -{0.314916f,-0.00944085f,0.124706f},{0.315151f,-0.015333f,0.124706f},{0.31561f,-0.0157495f,0.124706f}, -{0.316008f,-0.0162251f,0.124706f},{0.315948f,-0.00814252f,0.124706f},{0.316278f,0.00708097f,0.124706f}, -{0.321866f,0.00751594f,0.124706f},{0.316154f,-0.00542663f,0.124706f},{0.319943f,-0.00333905f,0.124706f}, -{0.319529f,-0.00287783f,0.124706f},{0.319179f,-0.0023656f,0.124706f},{0.315672f,-0.00442541f,0.124706f}, -{0.315951f,-0.00490799f,0.124706f},{0.311857f,0.0013863f,0.124706f},{0.312119f,0.00109643f,0.124706f}, -{0.318699f,0.00122657f,0.124706f},{0.311542f,0.00161492f,0.124706f},{0.309396f,0.0152805f,0.124706f}, -{0.308931f,0.0156909f,0.124706f},{0.320416f,0.00374048f,0.124706f},{0.31464f,0.0149805f,0.124706f}, -{0.31708f,0.0151839f,0.124706f},{0.315148f,0.0153371f,0.124706f},{0.315611f,0.0157476f,0.124706f}, -{0.316008f,0.0162251f,0.124706f},{0.313953f,0.00999629f,0.124706f},{0.314091f,0.0146931f,0.124706f}, -{0.313507f,0.0144856f,0.124706f},{0.312901f,0.0143575f,0.124706f},{0.313421f,0.0101606f,0.124706f}, -{0.315324f,0.00906122f,0.124706f},{0.319017f,0.0128683f,0.124706f},{0.314916f,0.00944057f,0.124706f}, -{0.314455f,0.00975455f,0.124706f},{0.320629f,0.0102881f,0.124706f},{0.319868f,0.0116071f,0.124706f}, -{0.315948f,0.00814199f,0.124706f},{0.318085f,0.0140632f,0.124706f},{0.320938f,0.00407552f,0.124706f}, -{0.321499f,0.00433883f,0.124706f},{0.322334f,0.00608354f,0.124706f},{0.322089f,0.0045282f,0.124706f}, -{0.322699f,0.00463457f,0.124706f},{0.31567f,0.00862459f,0.124706f},{0.321297f,0.008921f,0.124706f}, -{0.316153f,0.00762395f,0.124706f},{0.294936f,0.0196708f,0.124706f},{0.296034f,0.0212675f,0.124706f}, -{0.294812f,0.0202771f,0.124706f},{0.308525f,0.0161593f,0.124706f},{0.308185f,0.0166773f,0.124706f}, -{0.319944f,0.00333893f,0.124706f},{0.307613f,0.0184349f,0.124706f},{0.307724f,0.0178252f,0.124706f}, -{0.31918f,0.00236609f,0.124706f},{0.319529f,0.00287783f,0.124706f},{0.290913f,0.0143468f,0.124706f}, -{0.290294f,0.0143112f,0.124706f},{0.292899f,-0.0016145f,0.124706f},{0.297601f,0.0136072f,0.124706f}, -{0.297726f,0.0141506f,0.124706f},{0.293645f,0.0156903f,0.124706f},{0.294965f,0.0184341f,0.124706f}, -{0.294853f,0.0178247f,0.124706f},{0.298964f,0.015966f,0.124706f},{0.300459f,0.0166853f,0.124706f}, -{0.299009f,0.0217877f,0.124706f},{0.299926f,0.0165216f,0.124706f},{0.294661f,0.0172353f,0.124706f}, -{0.298555f,0.0155872f,0.124706f},{0.305068f,0.0215784f,0.124706f},{0.302651f,0.0165218f,0.124706f}, -{0.301567f,0.0167668f,0.124706f},{0.302049f,0.0218936f,0.124706f},{0.30101f,0.0167671f,0.124706f}, -{0.307584f,0.0190544f,0.124706f},{0.306543f,0.0212675f,0.124706f},{0.294597f,0.0208597f,0.124706f}, -{0.307636f,0.0196718f,0.124706f},{0.307767f,0.0202777f,0.124706f},{0.30798f,0.0208597f,0.124706f}, -{0.298208f,0.0151517f,0.124706f},{0.294392f,0.0166765f,0.124706f},{0.297929f,0.0146693f,0.124706f}, -{0.303567f,0.0217881f,0.124706f},{0.302118f,0.0166848f,0.124706f},{0.286626f,0.00490799f,0.124706f}, -{0.283398f,0.0023656f,0.124706f},{0.286905f,0.00442541f,0.124706f},{0.305373f,0.00984589f,0.124706f}, -{0.305754f,0.00992719f,0.124706f},{0.292109f,0.0146616f,0.124706f},{0.288278f,-0.00115727f,0.124706f}, -{0.294964f,-0.0184349f,0.124706f},{0.294853f,-0.0178252f,0.124706f},{0.291521f,0.0144643f,0.124706f}, -{0.280711f,0.00751463f,0.124706f},{0.280243f,0.00608354f,0.124706f},{0.281639f,0.00407246f,0.124706f}, -{0.287661f,0.00944085f,0.124706f},{0.283559f,0.0128671f,0.124706f},{0.287254f,0.00906082f,0.124706f}, -{0.295379f,0.00945782f,0.124706f},{0.28049f,0.00452954f,0.124706f},{0.279878f,0.00463457f,0.124706f}, -{0.287252f,0.00398966f,0.124706f},{0.283879f,0.00122583f,0.124706f},{0.287661f,0.00361044f,0.124706f}, -{0.283048f,0.00287783f,0.124706f},{0.286423f,0.00542663f,0.124706f},{0.282634f,0.00333905f,0.124706f}, -{0.281077f,0.00433369f,0.124706f},{0.286299f,0.00708106f,0.124706f},{0.286424f,0.00762403f,0.124706f}, -{0.28128f,0.00891935f,0.124706f},{0.281947f,0.0102864f,0.124706f},{0.286907f,0.00862484f,0.124706f}, -{0.282708f,0.0116055f,0.124706f},{0.286629f,0.00814252f,0.124706f},{0.287935f,0.0149788f,0.124706f}, -{0.285497f,0.0151839f,0.124706f},{0.284491f,0.0140624f,0.124706f},{0.287426f,0.015333f,0.124706f}, -{0.291522f,-0.0144645f,0.124706f},{0.29211f,-0.0146618f,0.124706f},{0.291348f,-0.00999677f,0.124706f}, -{0.286967f,0.0157495f,0.124706f},{0.286569f,0.0162251f,0.124706f},{0.294924f,0.00883069f,0.124706f}, -{0.294804f,0.00845974f,0.124706f},{0.283676f,-0.00181243f,0.124706f},{0.283397f,-0.00236609f,0.124706f}, -{0.289676f,0.014358f,0.124706f},{0.292666f,-0.0149353f,0.124706f},{0.29185f,-0.00975506f,0.124706f}, -{0.298136f,-0.00916839f,0.124706f},{0.298331f,-0.00883048f,0.124706f},{0.290815f,-0.0101609f,0.124706f}, -{0.281639f,-0.00407552f,0.124706f},{0.280711f,-0.00751594f,0.124706f},{0.284492f,-0.0140632f,0.124706f}, -{0.285497f,-0.0151839f,0.124706f},{0.288278f,-0.0126311f,0.124706f},{0.28907f,-0.0144856f,0.124706f}, -{0.289676f,-0.0143575f,0.124706f},{0.284002f,0.000618365f,0.124706f},{0.283878f,-0.00122657f,0.124706f}, -{0.284043f,7.02122e-018f,0.124706f},{0.294052f,-0.0161593f,0.124706f},{0.294392f,-0.0166773f,0.124706f}, -{0.28743f,-0.0153371f,0.124706f},{0.287937f,-0.0149805f,0.124706f},{0.289707f,-0.0102437f,0.124706f}, -{0.289156f,-0.0101606f,0.124706f},{0.287254f,-0.00906122f,0.124706f},{0.28356f,-0.0128683f,0.124706f}, -{0.287662f,-0.00944057f,0.124706f},{0.286907f,-0.00862459f,0.124706f},{0.28271f,-0.0116071f,0.124706f}, -{0.281948f,-0.0102881f,0.124706f},{0.286629f,-0.00814199f,0.124706f},{0.286299f,-0.00708097f,0.124706f}, -{0.288122f,-0.00975455f,0.124706f},{0.288624f,-0.00999629f,0.124706f},{0.280243f,-0.00608354f,0.124706f}, -{0.286966f,-0.0157476f,0.124706f},{0.281079f,-0.00433883f,0.124706f},{0.280488f,-0.0045282f,0.124706f}, -{0.286569f,-0.0162251f,0.124706f},{0.279878f,-0.00463457f,0.124706f},{0.290264f,-0.0102438f,0.124706f}, -{0.310034f,0.00177278f,0.124706f},{0.309678f,0.0016145f,0.124706f},{0.296053f,-0.00984657f,0.124706f}, -{0.296433f,-0.00992738f,0.124706f},{0.307652f,-0.00731413f,0.124706f},{0.307457f,-0.00697672f,0.124706f}, -{0.294994f,-0.0190544f,0.124706f},{0.297509f,-0.0215784f,0.124706f},{0.311226f,-0.0126311f,0.124706f}, -{0.312283f,-0.0143112f,0.124706f},{0.312901f,-0.014358f,0.124706f},{0.304852f,-0.0141506f,0.124706f}, -{0.308932f,-0.0156903f,0.124706f},{0.304976f,-0.0136072f,0.124706f},{0.311056f,-0.0144643f,0.124706f}, -{0.310468f,-0.0146616f,0.124706f},{0.307724f,-0.0178247f,0.124706f},{0.303613f,-0.015966f,0.124706f}, -{0.307612f,-0.0184341f,0.124706f},{0.309397f,-0.0152802f,0.124706f},{0.309911f,-0.0149353f,0.124706f}, -{0.305018f,-0.0130513f,0.124706f},{0.305069f,-0.0215779f,0.124706f},{0.307586f,-0.019053f,0.124706f}, -{0.303153f,-0.0162797f,0.124706f},{0.312434f,0.000388892f,0.124706f},{0.312314f,0.000758756f,0.124706f}, -{0.28128f,-0.008921f,0.124706f},{0.286424f,-0.00762395f,0.124706f},{0.290295f,-0.0143109f,0.124706f}, -{0.309025f,0.00762671f,0.124706f},{0.290263f,-0.000758756f,0.124706f},{0.290143f,-0.000388892f,0.124706f}, -{0.293646f,-0.0156909f,0.124706f},{0.29072f,-0.0013863f,0.124706f},{0.309362f,0.00138471f,0.124706f}, -{0.300459f,-0.0166848f,0.124706f},{0.299926f,-0.0165218f,0.124706f},{0.29901f,-0.0217881f,0.124706f}, -{0.30101f,-0.0167668f,0.124706f},{0.300528f,-0.0218936f,0.124706f},{0.301567f,-0.0167671f,0.124706f}, -{0.302118f,-0.0166853f,0.124706f},{0.303568f,-0.0217877f,0.124706f},{0.302651f,-0.0165216f,0.124706f}, -{0.296034f,-0.0212675f,0.124706f},{0.294941f,-0.0196718f,0.124706f},{0.29481f,-0.0202777f,0.124706f}, -{0.294597f,-0.0208597f,0.124706f},{0.304648f,-0.0146693f,0.124706f},{0.304369f,-0.0151517f,0.124706f}, -{0.308185f,-0.0166765f,0.124706f},{0.304022f,-0.0155872f,0.124706f},{0.307916f,-0.0172353f,0.124706f}, -{0.306543f,-0.0212675f,0.124706f},{0.307641f,-0.0196708f,0.124706f},{0.30798f,-0.0208597f,0.124706f}, -{0.307765f,-0.0202771f,0.124706f},{0.318901f,0.00181243f,0.124706f},{0.311229f,0.00999677f,0.124706f}, -{0.311664f,0.0143468f,0.124706f},{0.311055f,0.0144645f,0.124706f},{0.311762f,0.0101609f,0.124706f}, -{0.310415f,0.00185398f,0.124706f},{0.310805f,0.00185425f,0.124706f},{0.311186f,0.0017734f,0.124706f}, -{0.315325f,-0.00398966f,0.124706f},{0.312313f,-0.00281666f,0.124706f},{0.319018f,-0.0128671f,0.124706f}, -{0.315323f,-0.00906082f,0.124706f},{0.309515f,0.00862453f,0.124706f},{0.297204f,0.00630002f,0.124706f}, -{0.296823f,0.00621904f,0.124706f},{0.282634f,-0.00333893f,0.124706f},{0.282161f,-0.00374048f,0.124706f}, -{0.304441f,0.00916836f,0.124706f},{0.304246f,0.00883081f,0.124706f},{0.304702f,0.0066875f,0.124706f}, -{0.308787f,0.000387896f,0.124706f},{0.308907f,0.000757801f,0.124706f},{0.313954f,-0.00305438f,0.124706f}, -{0.314456f,-0.00329623f,0.124706f},{0.312871f,-0.00281186f,0.124706f},{0.313508f,-0.0144863f,0.124706f}, -{0.314092f,-0.0146944f,0.124706f},{0.307198f,-0.00945782f,0.124706f},{0.307653f,-0.00883069f,0.124706f}, -{0.307773f,-0.00845974f,0.124706f},{0.297205f,-0.00984564f,0.124706f},{0.296823f,-0.00992724f,0.124706f}, -{0.293215f,-0.00138471f,0.124706f},{0.296985f,-0.00178272f,0.124706f},{0.304126f,-0.00369829f,0.124706f}, -{0.305373f,-0.00630002f,0.124706f},{0.305754f,-0.00621904f,0.124706f},{0.292544f,-0.00177278f,0.124706f}, -{0.284001f,-0.000618856f,0.124706f},{0.308904f,0.00708155f,0.124706f},{0.309858f,0.00906268f,0.124706f}, -{0.294051f,0.0161585f,0.124706f},{0.300526f,0.0218934f,0.124706f},{0.307917f,0.0172358f,0.124706f}, -{0.304701f,0.00945796f,0.124706f},{0.305017f,0.00968738f,0.124706f},{0.304085f,0.00807261f,0.124706f}, -{0.304126f,0.00845965f,0.124706f},{0.304126f,0.00768455f,0.124706f},{0.297933f,0.0114364f,0.124706f}, -{0.30924f,0.00813915f,0.124706f},{0.297591f,-0.00283697f,0.124706f},{0.304247f,0.00731409f,0.124706f}, -{0.304442f,0.00697679f,0.124706f},{0.296052f,0.00629974f,0.124706f},{0.29512f,0.00697672f,0.124706f}, -{0.294925f,0.00731413f,0.124706f},{0.298552f,0.0105136f,0.124706f},{0.298963f,0.0101357f,0.124706f}, -{0.297725f,0.0119527f,0.124706f},{0.288121f,0.00329623f,0.124706f},{0.283676f,0.00181168f,0.124706f}, -{0.295119f,0.00916838f,0.124706f},{0.294804f,0.00768456f,0.124706f},{0.294763f,0.00807245f,0.124706f}, -{0.295696f,0.00645825f,0.124706f},{0.295381f,0.00668694f,0.124706f},{0.296433f,0.00621891f,0.124706f}, -{0.298216f,0.0109558f,0.124706f},{0.290264f,0.00281666f,0.124706f},{0.291772f,-0.00185425f,0.124706f}, -{0.297601f,0.0124958f,0.124706f},{0.292311f,-0.00944145f,0.124706f},{0.290913f,-0.0143468f,0.124706f}, -{0.288486f,-0.0146931f,0.124706f},{0.283048f,-0.00287783f,0.124706f},{0.290459f,-0.00109643f,0.124706f}, -{0.291035f,-0.00161492f,0.124706f},{0.292162f,-0.00185398f,0.124706f},{0.291391f,-0.0017734f,0.124706f}, -{0.289706f,0.00281186f,0.124706f},{0.289155f,0.00289006f,0.124706f},{0.290815f,0.00288693f,0.124706f}, -{0.291348f,0.00305413f,0.124706f},{0.296667f,-0.0006084f,0.124706f},{0.29367f,-0.000757801f,0.124706f}, -{0.296789f,-0.00120559f,0.124706f},{0.29379f,-0.000387896f,0.124706f},{0.293673f,-0.00708155f,0.124706f}, -{0.292719f,-0.00906268f,0.124706f},{0.293062f,-0.00862453f,0.124706f},{0.293552f,-0.00762671f,0.124706f}, -{0.297252f,-0.00233026f,0.124706f},{0.288623f,0.00305438f,0.124706f},{0.306881f,-0.00645825f,0.124706f}, -{0.308526f,-0.0161585f,0.124706f},{0.302051f,-0.0218934f,0.124706f},{0.29466f,-0.0172358f,0.124706f}, -{0.297876f,-0.00945833f,0.124706f},{0.29756f,-0.00968734f,0.124706f},{0.298492f,-0.0080728f,0.124706f}, -{0.298451f,-0.00845974f,0.124706f},{0.298451f,-0.00768446f,0.124706f},{0.302495f,-0.00450236f,0.124706f}, -{0.293337f,-0.00813915f,0.124706f},{0.304987f,-0.00283787f,0.124706f},{0.304585f,-0.00329614f,0.124706f}, -{0.306144f,-0.00621891f,0.124706f},{0.306525f,-0.00629974f,0.124706f},{0.309102f,0.00109509f,0.124706f}, -{0.305595f,-0.00178435f,0.124706f},{0.304852f,-0.0119527f,0.124706f},{0.298451f,-0.00369728f,0.124706f}, -{0.297993f,-0.00329545f,0.124706f},{0.303072f,-0.00430656f,0.124706f},{0.301897f,-0.00462115f,0.124706f}, -{0.301289f,-0.00466102f,0.124706f},{0.297875f,-0.0066878f,0.124706f},{0.298958f,-0.00403597f,0.124706f}, -{0.29833f,-0.00731401f,0.124706f},{0.300082f,-0.00450189f,0.124706f},{0.298136f,-0.00697682f,0.124706f}, -{0.318901f,-0.00181168f,0.124706f},{0.311664f,-0.0143468f,0.124706f},{0.307458f,-0.00916838f,0.124706f}, -{0.307773f,-0.00768456f,0.124706f},{0.307814f,-0.00807245f,0.124706f},{0.305784f,-0.00120563f,0.124706f}, -{0.307196f,-0.00668694f,0.124706f},{0.304025f,-0.0105136f,0.124706f},{0.304644f,-0.0114364f,0.124706f}, -{0.303614f,-0.0101357f,0.124706f},{0.304361f,-0.0109558f,0.124706f},{0.305906f,-0.00060826f,0.124706f}, -{0.305325f,-0.002331f,0.124706f},{0.304976f,-0.0124958f,0.124706f},{0.303619f,-0.00403701f,0.124706f}, -{0.30068f,-0.00462104f,0.124706f},{0.299504f,-0.00430572f,0.124706f},{0.293475f,-0.00109509f,0.124706f}, -{0.322912f,-0.00625082f,0.124658f},{0.322432f,-0.00772125f,0.124658f},{0.323012f,-0.00793332f,0.124501f}, -{0.32058f,-0.0161504f,0.122798f},{0.321651f,-0.0147775f,0.122798f},{0.32134f,-0.0145522f,0.123358f}, -{0.322302f,-0.0131254f,0.123358f},{0.322627f,-0.0133286f,0.122798f},{0.319915f,-0.0155937f,0.123843f}, -{0.319486f,-0.0152344f,0.124229f},{0.318799f,-0.0168374f,0.123843f},{0.31796f,-0.0160299f,0.124501f}, -{0.317145f,-0.0174787f,0.1243f},{0.318396f,-0.0164494f,0.124229f},{0.316402f,-0.0166602f,0.124659f}, -{0.316784f,-0.0170806f,0.124523f},{0.317514f,-0.0156014f,0.124658f},{0.323163f,-0.0116335f,0.123358f}, -{0.323502f,-0.0118136f,0.122798f},{0.323918f,-0.0100875f,0.123358f},{0.322857f,-0.013472f,0.122194f}, -{0.32299f,-0.0135551f,0.12158f},{0.323741f,-0.0119407f,0.122194f},{0.322652f,-0.0141705f,0.120977f}, -{0.323489f,-0.0128179f,0.120977f},{0.321997f,-0.0150287f,0.12158f},{0.321731f,-0.0154687f,0.120977f}, -{0.320908f,-0.0164249f,0.12158f},{0.323879f,-0.0120144f,0.12158f},{0.324242f,-0.0114156f,0.120977f}, -{0.319658f,-0.0178815f,0.120977f},{0.320732f,-0.0167073f,0.120977f},{0.319733f,-0.0177348f,0.12158f}, -{0.318513f,-0.0189869f,0.120977f},{0.318482f,-0.0189523f,0.121565f},{0.324659f,-0.0104178f,0.12158f}, -{0.324906f,-0.00996957f,0.120977f},{0.325323f,-0.00877706f,0.12158f},{0.325479f,-0.00848485f,0.120977f}, -{0.32596f,-0.0069676f,0.120977f},{0.325869f,-0.00710556f,0.12158f},{0.326298f,-0.00541355f,0.121565f}, -{0.326165f,-0.00538462f,0.122132f},{0.324268f,-0.0102436f,0.122798f},{0.319424f,-0.0174384f,0.122798f}, -{0.320286f,-0.0159041f,0.123358f},{0.326344f,-0.00542344f,0.120977f},{0.324515f,-0.0103538f,0.122194f}, -{0.324625f,-0.006746f,0.123843f},{0.324838f,-0.00509752f,0.123996f},{0.324088f,-0.00659057f,0.124229f}, -{0.325276f,-0.00519238f,0.123614f},{0.32509f,-0.00688027f,0.123358f},{0.322242f,-0.0111437f,0.124229f}, -{0.322965f,-0.00966271f,0.124229f},{0.322412f,-0.00941631f,0.124501f},{0.323274f,-0.00475885f,0.124659f}, -{0.325718f,-0.00706195f,0.122194f},{0.325947f,-0.00533751f,0.12267f},{0.325458f,-0.0069868f,0.122798f}, -{0.325175f,-0.00872319f,0.122194f},{0.32187f,-0.0149364f,0.122194f},{0.320788f,-0.0163241f,0.122194f}, -{0.319619f,-0.0176259f,0.122194f},{0.31839f,-0.0188517f,0.12213f},{0.325649f,-0.00527292f,0.123168f}, -{0.324921f,-0.00863036f,0.122798f},{0.318241f,-0.0186868f,0.122667f},{0.323506f,-0.0064225f,0.124501f}, -{0.324351f,-0.00499215f,0.124301f},{0.324561f,-0.00849877f,0.123358f},{0.320949f,-0.0142682f,0.123843f}, -{0.319148f,-0.0171725f,0.123358f},{0.318036f,-0.0184612f,0.123166f},{0.323476f,-0.0098906f,0.123843f}, -{0.324107f,-0.00833292f,0.123843f},{0.322736f,-0.0114065f,0.123843f},{0.321892f,-0.0128692f,0.123843f}, -{0.317779f,-0.018178f,0.123614f},{0.323581f,-0.00814092f,0.124229f},{0.321417f,-0.0125727f,0.124229f}, -{0.320496f,-0.0139394f,0.124229f},{0.317479f,-0.0178475f,0.123995f},{0.323826f,-0.00487843f,0.124524f}, -{0.321708f,-0.0108595f,0.124501f},{0.320904f,-0.0122521f,0.124501f},{0.320006f,-0.013584f,0.124501f}, -{0.318548f,-0.0144491f,0.124658f},{0.319022f,-0.014846f,0.124501f},{0.321847f,-0.00916459f,0.124658f}, -{0.321162f,-0.0105692f,0.124658f},{0.32038f,-0.0119246f,0.124658f},{0.319506f,-0.0132209f,0.124658f}, -{0.302174f,-0.0254145f,0.122194f},{0.303907f,-0.0250226f,0.122798f},{0.302164f,-0.0251441f,0.122798f}, -{0.305705f,-0.0252029f,0.12158f},{0.303952f,-0.0254479f,0.12158f},{0.303937f,-0.0254985f,0.120977f}, -{0.303867f,-0.0246411f,0.123358f},{0.302173f,-0.0256204f,0.120977f},{0.307388f,-0.0246879f,0.122194f}, -{0.307425f,-0.0248403f,0.12158f},{0.309063f,-0.0242356f,0.122132f},{0.307414f,-0.024878f,0.120977f}, -{0.309105f,-0.0243658f,0.121565f},{0.306687f,-0.0218522f,0.124658f},{0.305173f,-0.0221712f,0.124658f}, -{0.30528f,-0.0227801f,0.124501f},{0.309119f,-0.0244103f,0.120977f},{0.305688f,-0.0252555f,0.120977f}, -{0.308786f,-0.0233704f,0.123614f},{0.307115f,-0.0235834f,0.123843f},{0.307231f,-0.0240528f,0.123358f}, -{0.303759f,-0.0236035f,0.124229f},{0.303695f,-0.0230016f,0.124501f},{0.302115f,-0.0237181f,0.124229f}, -{0.306981f,-0.02304f,0.124229f},{0.308649f,-0.0229434f,0.123996f},{0.302179f,-0.0255715f,0.12158f}, -{0.303935f,-0.0252917f,0.122194f},{0.297014f,-0.0244044f,0.123358f},{0.295254f,-0.0244252f,0.122798f}, -{0.296948f,-0.0247822f,0.122798f},{0.30816f,-0.0214191f,0.124659f},{0.300428f,-0.0247609f,0.123358f}, -{0.298672f,-0.0250231f,0.122798f},{0.300415f,-0.0251442f,0.122798f},{0.302151f,-0.0247607f,0.123358f}, -{0.295462f,-0.0235834f,0.123843f},{0.297097f,-0.0239281f,0.123843f},{0.297194f,-0.0233768f,0.124229f}, -{0.295742f,-0.0224524f,0.124501f},{0.29408f,-0.0224714f,0.1243f},{0.295597f,-0.02304f,0.124229f}, -{0.298712f,-0.0246415f,0.123358f},{0.294417f,-0.0214191f,0.124659f},{0.294244f,-0.0219595f,0.124523f}, -{0.29589f,-0.0218522f,0.124658f},{0.3004f,-0.0255716f,0.12158f},{0.300406f,-0.0254147f,0.122194f}, -{0.300405f,-0.0256204f,0.120977f},{0.298628f,-0.0254484f,0.12158f},{0.298641f,-0.0254985f,0.120977f}, -{0.296874f,-0.0252035f,0.12158f},{0.29689f,-0.0252554f,0.120977f},{0.295161f,-0.0248864f,0.120977f}, -{0.295152f,-0.0248403f,0.12158f},{0.293458f,-0.0244103f,0.120977f},{0.308995f,-0.0240236f,0.12267f}, -{0.307323f,-0.0244252f,0.122798f},{0.305677f,-0.0250482f,0.122194f},{0.298644f,-0.0252922f,0.122194f}, -{0.295189f,-0.0246879f,0.122194f},{0.296901f,-0.0250488f,0.122194f},{0.293472f,-0.0243658f,0.121565f}, -{0.293513f,-0.0242365f,0.12213f},{0.308902f,-0.0237329f,0.123168f},{0.305631f,-0.0247816f,0.122798f}, -{0.293581f,-0.0240245f,0.122667f},{0.306835f,-0.0224524f,0.124501f},{0.308497f,-0.0224691f,0.124301f}, -{0.305565f,-0.0244038f,0.123358f},{0.298762f,-0.0241606f,0.123843f},{0.295346f,-0.0240528f,0.123358f}, -{0.293674f,-0.0237345f,0.123166f},{0.303817f,-0.0241602f,0.123843f},{0.305481f,-0.0239275f,0.123843f}, -{0.302134f,-0.0242775f,0.123843f},{0.300445f,-0.0242776f,0.123843f},{0.293791f,-0.0233704f,0.123614f}, -{0.305384f,-0.0233762f,0.124229f},{0.300465f,-0.0237183f,0.124229f},{0.29882f,-0.023604f,0.124229f}, -{0.293928f,-0.0229455f,0.123995f},{0.308332f,-0.0219573f,0.124524f},{0.302094f,-0.0231133f,0.124501f}, -{0.300486f,-0.0231134f,0.124501f},{0.298883f,-0.023002f,0.124501f},{0.297405f,-0.0221717f,0.124658f}, -{0.297298f,-0.0227807f,0.124501f},{0.303631f,-0.0223867f,0.124658f},{0.302072f,-0.0224954f,0.124658f}, -{0.300507f,-0.0224956f,0.124658f},{0.298948f,-0.0223872f,0.124658f},{0.279588f,-0.013557f,0.12158f}, -{0.280709f,-0.0149379f,0.122194f},{0.279721f,-0.0134738f,0.122194f},{0.280581f,-0.0150302f,0.12158f}, -{0.279926f,-0.0141709f,0.120977f},{0.280846f,-0.0154689f,0.120977f},{0.280928f,-0.0147789f,0.122798f}, -{0.279951f,-0.0133304f,0.122798f},{0.281238f,-0.0145536f,0.123358f},{0.282958f,-0.0176259f,0.122194f}, -{0.282845f,-0.0177348f,0.12158f},{0.284187f,-0.0188513f,0.122131f},{0.284338f,-0.0186852f,0.122672f}, -{0.28403f,-0.0144499f,0.124658f},{0.283556f,-0.0148468f,0.124501f},{0.285063f,-0.0156014f,0.124658f}, -{0.284095f,-0.0189527f,0.121561f},{0.282919f,-0.0178817f,0.120977f},{0.284064f,-0.0189869f,0.120977f}, -{0.28167f,-0.0164258f,0.12158f},{0.281845f,-0.0167075f,0.120977f},{0.284181f,-0.0164494f,0.124229f}, -{0.283778f,-0.0168374f,0.123843f},{0.285097f,-0.0178479f,0.123994f},{0.281161f,-0.0125744f,0.124229f}, -{0.282082f,-0.0139408f,0.124229f},{0.282572f,-0.0135853f,0.124501f},{0.286177f,-0.0166578f,0.12466f}, -{0.283429f,-0.0171725f,0.123358f},{0.284798f,-0.018178f,0.123614f},{0.278016f,-0.00850026f,0.123358f}, -{0.277119f,-0.0069868f,0.122798f},{0.277656f,-0.00863187f,0.122798f},{0.280276f,-0.0131272f,0.123358f}, -{0.279071f,-0.0064225f,0.124501f},{0.278223f,-0.00499264f,0.1243f},{0.278489f,-0.00659057f,0.124229f}, -{0.278837f,-0.0119427f,0.122194f},{0.278699f,-0.0120165f,0.12158f},{0.277952f,-0.006746f,0.123843f}, -{0.278471f,-0.00833438f,0.123843f},{0.278996f,-0.00814234f,0.124229f},{0.27831f,-0.0102456f,0.122798f}, -{0.27866f,-0.0100893f,0.123358f},{0.279415f,-0.0116355f,0.123358f},{0.279076f,-0.0118156f,0.122798f}, -{0.279303f,-0.00475885f,0.124659f},{0.278749f,-0.00487893f,0.124523f},{0.279665f,-0.00625082f,0.124658f}, -{0.279087f,-0.012818f,0.120977f},{0.277919f,-0.0104197f,0.12158f},{0.278335f,-0.011416f,0.120977f}, -{0.277254f,-0.0087786f,0.12158f},{0.277671f,-0.00996985f,0.120977f},{0.2771f,-0.00848443f,0.120977f}, -{0.276708f,-0.00710556f,0.12158f},{0.276626f,-0.00696541f,0.120977f},{0.276233f,-0.00542344f,0.120977f}, -{0.276279f,-0.00541355f,0.121565f},{0.283153f,-0.0174384f,0.122798f},{0.281791f,-0.016325f,0.122194f}, -{0.278063f,-0.0103558f,0.122194f},{0.277402f,-0.00872472f,0.122194f},{0.276859f,-0.00706195f,0.122194f}, -{0.276412f,-0.00538482f,0.12213f},{0.284543f,-0.0184588f,0.12317f},{0.281998f,-0.0161513f,0.122798f}, -{0.276629f,-0.00533772f,0.122667f},{0.284618f,-0.0160299f,0.124501f},{0.285433f,-0.0174779f,0.1243f}, -{0.282292f,-0.015905f,0.123358f},{0.279102f,-0.00989244f,0.123843f},{0.277487f,-0.00688027f,0.123358f}, -{0.276927f,-0.00527328f,0.123166f},{0.281629f,-0.0142696f,0.123843f},{0.282663f,-0.0155946f,0.123843f}, -{0.280686f,-0.012871f,0.123843f},{0.279842f,-0.0114084f,0.123843f},{0.277301f,-0.00519238f,0.123614f}, -{0.283092f,-0.0152353f,0.124229f},{0.280336f,-0.0111456f,0.124229f},{0.279613f,-0.00966451f,0.124229f}, -{0.277737f,-0.005098f,0.123995f},{0.285796f,-0.0170773f,0.124524f},{0.281674f,-0.0122538f,0.124501f}, -{0.28087f,-0.0108613f,0.124501f},{0.280166f,-0.00941806f,0.124501f},{0.280146f,-0.0077226f,0.124658f}, -{0.279565f,-0.00793471f,0.124501f},{0.283072f,-0.0132221f,0.124658f},{0.282199f,-0.0119262f,0.124658f}, -{0.281416f,-0.010571f,0.124658f},{0.28073f,-0.0091663f,0.124658f},{0.278698f,0.0120144f,0.12158f}, -{0.278062f,0.0103538f,0.122194f},{0.278836f,0.0119407f,0.122194f},{0.277919f,0.0104178f,0.12158f}, -{0.278309f,0.0102436f,0.122798f},{0.279075f,0.0118136f,0.122798f},{0.278659f,0.0100875f,0.123358f}, -{0.276859f,0.00706195f,0.122194f},{0.276708f,0.00710556f,0.12158f},{0.276413f,0.00538462f,0.122132f}, -{0.27663f,0.00533751f,0.12267f},{0.280145f,0.00772125f,0.124658f},{0.279565f,0.00793332f,0.124501f}, -{0.279665f,0.00625082f,0.124658f},{0.276279f,0.00541355f,0.121565f},{0.277254f,0.00877706f,0.12158f}, -{0.278489f,0.00659057f,0.124229f},{0.277952f,0.006746f,0.123843f},{0.277739f,0.00509752f,0.123996f}, -{0.280335f,0.0111437f,0.124229f},{0.279612f,0.00966271f,0.124229f},{0.280165f,0.00941631f,0.124501f}, -{0.279303f,0.00475885f,0.124659f},{0.277487f,0.00688027f,0.123358f},{0.277301f,0.00519238f,0.123614f}, -{0.282291f,0.0159041f,0.123358f},{0.283153f,0.0174384f,0.122798f},{0.281997f,0.0161504f,0.122798f}, -{0.279414f,0.0116335f,0.123358f},{0.284618f,0.0160299f,0.124501f},{0.285431f,0.0174801f,0.124299f}, -{0.284181f,0.0164494f,0.124229f},{0.27972f,0.013472f,0.122194f},{0.279587f,0.0135551f,0.12158f}, -{0.283778f,0.0168374f,0.123843f},{0.282662f,0.0155937f,0.123843f},{0.283091f,0.0152344f,0.124229f}, -{0.280926f,0.0147775f,0.122798f},{0.281237f,0.0145522f,0.123358f},{0.280275f,0.0131254f,0.123358f}, -{0.27995f,0.0133286f,0.122798f},{0.286177f,0.0166578f,0.12466f},{0.285794f,0.0170797f,0.124523f}, -{0.285063f,0.0156014f,0.124658f},{0.28058f,0.0150287f,0.12158f},{0.281669f,0.0164249f,0.12158f}, -{0.282845f,0.0177348f,0.12158f},{0.284095f,0.0189527f,0.121561f},{0.277119f,0.0069868f,0.122798f}, -{0.277402f,0.00872319f,0.122194f},{0.280707f,0.0149364f,0.122194f},{0.281789f,0.0163241f,0.122194f}, -{0.282958f,0.0176259f,0.122194f},{0.284186f,0.018852f,0.122128f},{0.276929f,0.00527292f,0.123168f}, -{0.277656f,0.00863036f,0.122798f},{0.284337f,0.0186863f,0.122669f},{0.279071f,0.0064225f,0.124501f}, -{0.278226f,0.00499215f,0.124301f},{0.278016f,0.00849877f,0.123358f},{0.281628f,0.0142682f,0.123843f}, -{0.283429f,0.0171725f,0.123358f},{0.284542f,0.0184598f,0.123168f},{0.279101f,0.0098906f,0.123843f}, -{0.27847f,0.00833292f,0.123843f},{0.279841f,0.0114065f,0.123843f},{0.280685f,0.0128692f,0.123843f}, -{0.284798f,0.018178f,0.123614f},{0.278996f,0.00814092f,0.124229f},{0.28116f,0.0125727f,0.124229f}, -{0.282081f,0.0139394f,0.124229f},{0.285096f,0.0178492f,0.123993f},{0.278751f,0.00487843f,0.124524f}, -{0.280869f,0.0108595f,0.124501f},{0.281673f,0.0122521f,0.124501f},{0.282571f,0.013584f,0.124501f}, -{0.284029f,0.0144491f,0.124658f},{0.283555f,0.014846f,0.124501f},{0.28073f,0.00916459f,0.124658f}, -{0.281415f,0.0105692f,0.124658f},{0.282198f,0.0119246f,0.124658f},{0.283071f,0.0132209f,0.124658f}, -{0.300403f,0.0254145f,0.122194f},{0.29867f,0.0250226f,0.122798f},{0.300413f,0.0251441f,0.122798f}, -{0.296873f,0.0252029f,0.12158f},{0.298626f,0.0254479f,0.12158f},{0.29871f,0.0246411f,0.123358f}, -{0.295189f,0.0246879f,0.122194f},{0.295152f,0.0248403f,0.12158f},{0.293514f,0.0242356f,0.122132f}, -{0.293472f,0.0243658f,0.121565f},{0.29589f,0.0218522f,0.124658f},{0.297404f,0.0221712f,0.124658f}, -{0.297297f,0.0227801f,0.124501f},{0.293791f,0.0233704f,0.123614f},{0.295462f,0.0235834f,0.123843f}, -{0.295346f,0.0240528f,0.123358f},{0.298819f,0.0236035f,0.124229f},{0.298882f,0.0230016f,0.124501f}, -{0.300462f,0.0237181f,0.124229f},{0.295597f,0.02304f,0.124229f},{0.293928f,0.0229434f,0.123996f}, -{0.300398f,0.0255715f,0.12158f},{0.298642f,0.0252917f,0.122194f},{0.305563f,0.0244044f,0.123358f}, -{0.307323f,0.0244252f,0.122798f},{0.305629f,0.0247822f,0.122798f},{0.294417f,0.0214191f,0.124659f}, -{0.302149f,0.0247609f,0.123358f},{0.303905f,0.0250231f,0.122798f},{0.302162f,0.0251442f,0.122798f}, -{0.300426f,0.0247607f,0.123358f},{0.307115f,0.0235834f,0.123843f},{0.30548f,0.0239281f,0.123843f}, -{0.305383f,0.0233768f,0.124229f},{0.306835f,0.0224524f,0.124501f},{0.308497f,0.0224714f,0.1243f}, -{0.306981f,0.02304f,0.124229f},{0.303865f,0.0246415f,0.123358f},{0.30816f,0.0214191f,0.124659f}, -{0.308333f,0.0219595f,0.124523f},{0.306687f,0.0218522f,0.124658f},{0.302177f,0.0255716f,0.12158f}, -{0.302171f,0.0254147f,0.122194f},{0.30395f,0.0254484f,0.12158f},{0.305703f,0.0252035f,0.12158f}, -{0.307425f,0.0248403f,0.12158f},{0.293582f,0.0240236f,0.12267f},{0.295254f,0.0244252f,0.122798f}, -{0.2969f,0.0250482f,0.122194f},{0.303933f,0.0252922f,0.122194f},{0.307388f,0.0246879f,0.122194f}, -{0.305676f,0.0250488f,0.122194f},{0.309105f,0.0243658f,0.121565f},{0.309064f,0.0242365f,0.12213f}, -{0.293675f,0.0237329f,0.123168f},{0.296946f,0.0247816f,0.122798f},{0.308996f,0.0240245f,0.122667f}, -{0.295742f,0.0224524f,0.124501f},{0.29408f,0.0224691f,0.124301f},{0.297013f,0.0244038f,0.123358f}, -{0.303815f,0.0241606f,0.123843f},{0.307231f,0.0240528f,0.123358f},{0.308903f,0.0237345f,0.123166f}, -{0.29876f,0.0241602f,0.123843f},{0.297096f,0.0239275f,0.123843f},{0.300443f,0.0242775f,0.123843f}, -{0.302132f,0.0242776f,0.123843f},{0.308786f,0.0233704f,0.123614f},{0.297193f,0.0233762f,0.124229f}, -{0.302113f,0.0237183f,0.124229f},{0.303757f,0.023604f,0.124229f},{0.308649f,0.0229455f,0.123995f}, -{0.294245f,0.0219573f,0.124524f},{0.300484f,0.0231133f,0.124501f},{0.302091f,0.0231134f,0.124501f}, -{0.303694f,0.023002f,0.124501f},{0.305172f,0.0221717f,0.124658f},{0.305279f,0.0227807f,0.124501f}, -{0.298946f,0.0223867f,0.124658f},{0.300505f,0.0224954f,0.124658f},{0.30207f,0.0224956f,0.124658f}, -{0.303629f,0.0223872f,0.124658f},{0.322989f,0.013557f,0.12158f},{0.321869f,0.0149379f,0.122194f}, -{0.322856f,0.0134738f,0.122194f},{0.321996f,0.0150302f,0.12158f},{0.32165f,0.0147789f,0.122798f}, -{0.322626f,0.0133304f,0.122798f},{0.321339f,0.0145536f,0.123358f},{0.319619f,0.0176259f,0.122194f}, -{0.319733f,0.0177348f,0.12158f},{0.31839f,0.018851f,0.122132f},{0.31824f,0.0186861f,0.12267f}, -{0.318547f,0.0144499f,0.124658f},{0.319021f,0.0148468f,0.124501f},{0.317514f,0.0156014f,0.124658f}, -{0.318482f,0.0189523f,0.121565f},{0.320907f,0.0164258f,0.12158f},{0.318396f,0.0164494f,0.124229f}, -{0.318799f,0.0168374f,0.123843f},{0.317478f,0.0178459f,0.123996f},{0.321416f,0.0125744f,0.124229f}, -{0.320495f,0.0139408f,0.124229f},{0.320005f,0.0135853f,0.124501f},{0.316402f,0.0166602f,0.124659f}, -{0.319148f,0.0171725f,0.123358f},{0.317779f,0.018178f,0.123614f},{0.324561f,0.00850026f,0.123358f}, -{0.325458f,0.0069868f,0.122798f},{0.324921f,0.00863187f,0.122798f},{0.322301f,0.0131272f,0.123358f}, -{0.323506f,0.0064225f,0.124501f},{0.324354f,0.00499264f,0.1243f},{0.324088f,0.00659057f,0.124229f}, -{0.32374f,0.0119427f,0.122194f},{0.323878f,0.0120165f,0.12158f},{0.324625f,0.006746f,0.123843f}, -{0.324106f,0.00833438f,0.123843f},{0.323581f,0.00814234f,0.124229f},{0.324267f,0.0102456f,0.122798f}, -{0.323917f,0.0100893f,0.123358f},{0.323162f,0.0116355f,0.123358f},{0.323501f,0.0118156f,0.122798f}, -{0.323274f,0.00475885f,0.124659f},{0.323828f,0.00487893f,0.124523f},{0.322912f,0.00625082f,0.124658f}, -{0.324658f,0.0104197f,0.12158f},{0.325323f,0.0087786f,0.12158f},{0.325869f,0.00710556f,0.12158f}, -{0.326298f,0.00541355f,0.121565f},{0.319424f,0.0174384f,0.122798f},{0.320786f,0.016325f,0.122194f}, -{0.324515f,0.0103558f,0.122194f},{0.325175f,0.00872472f,0.122194f},{0.325718f,0.00706195f,0.122194f}, -{0.326165f,0.00538482f,0.12213f},{0.318035f,0.0184599f,0.123168f},{0.320579f,0.0161513f,0.122798f}, -{0.325948f,0.00533772f,0.122667f},{0.31796f,0.0160299f,0.124501f},{0.317143f,0.017477f,0.124301f}, -{0.320285f,0.015905f,0.123358f},{0.323475f,0.00989244f,0.123843f},{0.32509f,0.00688027f,0.123358f}, -{0.32565f,0.00527328f,0.123166f},{0.320948f,0.0142696f,0.123843f},{0.319914f,0.0155946f,0.123843f}, -{0.321891f,0.012871f,0.123843f},{0.322735f,0.0114084f,0.123843f},{0.325276f,0.00519238f,0.123614f}, -{0.319485f,0.0152353f,0.124229f},{0.322241f,0.0111456f,0.124229f},{0.322964f,0.00966451f,0.124229f}, -{0.32484f,0.005098f,0.123995f},{0.316782f,0.0170789f,0.124524f},{0.320903f,0.0122538f,0.124501f}, -{0.321707f,0.0108613f,0.124501f},{0.322411f,0.00941806f,0.124501f},{0.322432f,0.0077226f,0.124658f}, -{0.323012f,0.00793471f,0.124501f},{0.319505f,0.0132221f,0.124658f},{0.320378f,0.0119262f,0.124658f}, -{0.321161f,0.010571f,0.124658f},{0.321847f,0.0091663f,0.124658f},{0.305432f,-0.00620072f,0.0995366f}, -{0.302686f,-0.00241971f,0.0995366f},{0.303085f,-0.00214016f,0.0995366f},{0.304143f,-0.00688999f,0.0995366f}, -{0.304805f,-0.00657676f,0.0995366f},{0.303454f,-0.00713669f,0.0995366f},{0.302245f,-0.00262702f,0.0995366f}, -{0.30602f,-0.00576486f,0.0995366f},{0.306563f,-0.00527335f,0.0995366f},{0.302744f,-0.00731445f,0.0995366f}, -{0.301774f,-0.00275405f,0.0995366f},{0.30343f,-0.00179629f,0.0995366f},{0.307054f,-0.004731f,0.0995366f}, -{0.302019f,-0.00742168f,0.0995366f},{0.301289f,-0.00279661f,0.0995366f},{0.30749f,-0.00414307f,0.0995366f}, -{0.30371f,-0.00139723f,0.0995366f},{0.301289f,-0.00745764f,0.0995366f},{0.300557f,-0.0074216f,0.0995366f}, -{0.299833f,-0.00731392f,0.0995366f},{0.300803f,-0.00275426f,0.0995366f},{0.299123f,-0.00713585f,0.0995366f}, -{0.300333f,-0.0026284f,0.0995366f},{0.308179f,-0.0028536f,0.0995366f},{0.307866f,-0.00351526f,0.0995366f}, -{0.297772f,-0.00657672f,0.0995366f},{0.298434f,-0.0068893f,0.0995366f},{0.308426f,-0.00216444f,0.0995366f}, -{0.303916f,-0.000955369f,0.0995366f},{0.304042f,-0.000484912f,0.0995366f},{0.299894f,-0.00241949f,0.0995366f}, -{0.308711f,-0.000730865f,0.0995366f},{0.308603f,-0.00145464f,0.0995366f},{0.299145f,-0.0018009f,0.0995366f}, -{0.299499f,-0.00213198f,0.0995366f},{0.296015f,-0.00527224f,0.0995366f},{0.294712f,-0.00351451f,0.0995366f}, -{0.294399f,-0.00285307f,0.0995366f},{0.29866f,-0.000957231f,0.0995366f},{0.298533f,-0.000485989f,0.0995366f}, -{0.293867f,-0.000730708f,0.0995366f},{0.294152f,-0.00216422f,0.0995366f},{0.293974f,-0.00145452f,0.0995366f}, -{0.296557f,-0.00576389f,0.0995366f},{0.297145f,-0.00620014f,0.0995366f},{0.295088f,-0.00414214f,0.0995366f}, -{0.298866f,-0.00139896f,0.0995366f},{0.295524f,-0.00472993f,0.0995366f},{0.301897f,0.0121618f,0.100469f}, -{0.303073f,0.0124736f,0.100469f},{0.30362f,0.0127432f,0.100469f},{0.303454f,-0.00713585f,0.100469f}, -{0.306649f,-0.0107204f,0.100469f},{0.30871f,-0.000730708f,0.100469f},{0.31345f,-0.00060826f,0.100469f}, -{0.308425f,-0.00216422f,0.100469f},{0.314032f,-0.002331f,0.100469f},{0.308178f,-0.00285307f,0.100469f}, -{0.305326f,0.0144494f,0.100469f},{0.305594f,0.0185639f,0.100469f},{0.315586f,-0.0131013f,0.100469f}, -{0.29849f,0.021256f,0.100469f},{0.32269f,-0.0006084f,0.100469f},{0.294397f,0.0203028f,0.100469f}, -{0.293084f,0.0198085f,0.100469f},{0.322568f,-0.00120559f,0.100469f},{0.322372f,-0.00178272f,0.100469f}, -{0.314772f,-0.00329614f,0.100469f},{0.307865f,-0.00351451f,0.100469f},{0.31437f,-0.00283787f,0.100469f}, -{0.292356f,-0.0114792f,0.100469f},{0.297563f,-0.0139787f,0.100469f},{0.297226f,-0.0144948f,0.100469f}, -{0.322105f,-0.00233026f,0.100469f},{0.321364f,-0.00329545f,0.100469f},{0.321766f,-0.00283697f,0.100469f}, -{0.320906f,-0.00369728f,0.100469f},{0.315199f,-0.0112779f,0.100469f},{0.315428f,-0.0115926f,0.100469f}, -{0.299123f,-0.00713669f,0.100469f},{0.298935f,-0.0127563f,0.100469f},{0.298434f,-0.00688999f,0.100469f}, -{0.320399f,-0.00403597f,0.100469f},{0.319852f,-0.00430572f,0.100469f},{0.318068f,-0.00466102f,0.100469f}, -{0.318677f,-0.00462104f,0.100469f},{0.319275f,-0.00450189f,0.100469f},{0.287152f,0.0161201f,0.100469f}, -{0.291806f,0.0192295f,0.100469f},{0.30007f,-0.0122874f,0.100469f},{0.299834f,-0.00731445f,0.100469f}, -{0.300558f,-0.00742168f,0.100469f},{0.31746f,-0.00462115f,0.100469f},{0.299486f,-0.0124812f,0.100469f}, -{0.307489f,-0.00414214f,0.100469f},{0.298425f,-0.0131016f,0.100469f},{0.315667f,-0.01233f,0.100469f}, -{0.290537f,0.0119471f,0.100469f},{0.290379f,0.0115917f,0.100469f},{0.299886f,0.0213951f,0.100469f}, -{0.304584f,0.0200754f,0.100469f},{0.304986f,0.0196172f,0.100469f},{0.307053f,-0.00472993f,0.100469f}, -{0.30595f,0.0167797f,0.100469f},{0.30591f,0.0173884f,0.100469f},{0.308603f,-0.00145452f,0.100469f}, -{0.313762f,-0.00178435f,0.100469f},{0.31345f,0.00961418f,0.100469f},{0.312223f,0.0087231f,0.100469f}, -{0.312593f,0.00884326f,0.100469f},{0.313608f,0.0099696f,0.100469f},{0.31293f,0.00903788f,0.100469f}, -{0.31322f,0.00929843f,0.100469f},{0.314909f,-0.0110163f,0.100469f},{0.314908f,-0.014033f,0.100469f}, -{0.314571f,-0.0142276f,0.100469f},{0.314571f,-0.0108212f,0.100469f},{0.316862f,-0.00450236f,0.100469f}, -{0.30602f,-0.00576389f,0.100469f},{0.306562f,-0.00527224f,0.100469f},{0.284279f,0.0130525f,0.100469f}, -{0.293769f,-0.0200792f,0.100469f},{0.292435f,-0.0195277f,0.100469f},{0.296679f,-0.0174727f,0.100469f}, -{0.304143f,-0.0068893f,0.100469f},{0.304805f,-0.00657672f,0.100469f},{0.30202f,-0.0074216f,0.100469f}, -{0.302744f,-0.00731392f,0.100469f},{0.286128f,0.0151611f,0.100469f},{0.285169f,0.0141371f,0.100469f}, -{0.288815f,0.00178435f,0.100469f},{0.289004f,0.00120563f,0.100469f},{0.301289f,-0.00745764f,0.100469f}, -{0.29696f,-0.0150508f,0.100469f},{0.292127f,-0.011795f,0.100469f},{0.290568f,0.00536018f,0.100469f}, -{0.292596f,-0.0107426f,0.100469f},{0.297965f,-0.0135115f,0.100469f},{0.283462f,0.0119121f,0.100469f}, -{0.293974f,-0.00145464f,0.100469f},{0.294152f,-0.00216444f,0.100469f},{0.293866f,-0.000730865f,0.100469f}, -{0.281671f,0.00369728f,0.100469f},{0.281213f,0.00329545f,0.100469f},{0.28026f,0.00418323f,0.100469f}, -{0.285469f,-0.0144727f,0.100469f},{0.284531f,-0.0133751f,0.100469f},{0.283669f,-0.0122169f,0.100469f}, -{0.296659f,-0.0162427f,0.100469f},{0.291141f,-0.0188874f,0.100469f},{0.288696f,-0.0173532f,0.100469f}, -{0.287556f,-0.0164664f,0.100469f},{0.296628f,-0.0168584f,0.100469f},{0.297021f,-0.018654f,0.100469f}, -{0.295138f,-0.0205396f,0.100469f},{0.296811f,-0.0180747f,0.100469f},{0.299634f,-0.0211335f,0.100469f}, -{0.299385f,-0.0213586f,0.100469f},{0.299072f,-0.0208805f,0.100469f},{0.29766f,-0.0197045f,0.100469f}, -{0.296534f,-0.0209071f,0.100469f},{0.297306f,-0.0192003f,0.100469f},{0.298078f,-0.0201577f,0.100469f}, -{0.298551f,-0.0205519f,0.100469f},{0.297955f,-0.0211663f,0.100469f},{0.300222f,-0.0213146f,0.100469f}, -{0.300829f,-0.021419f,0.100469f},{0.29113f,-0.0123703f,0.100469f},{0.289893f,-0.0181614f,0.100469f}, -{0.286479f,-0.0155048f,0.100469f},{0.282886f,-0.0110032f,0.100469f},{0.280042f,-0.00287961f,0.100469f}, -{0.280284f,-0.00430325f,0.100469f},{0.280621f,-0.00570752f,0.100469f},{0.313573f,-0.00120563f,0.100469f}, -{0.296557f,-0.00576486f,0.100469f},{0.292357f,-0.00961513f,0.100469f},{0.292128f,-0.00930035f,0.100469f}, -{0.282188f,-0.00973944f,0.100469f},{0.2915f,-0.0122501f,0.100469f},{0.279896f,-0.00144304f,0.100469f}, -{0.290149f,0.0112759f,0.100469f},{0.289859f,0.0110154f,0.100469f},{0.295523f,-0.004731f,0.100469f}, -{0.296014f,-0.00527335f,0.100469f},{0.291838f,-0.00903878f,0.100469f},{0.291501f,-0.00884365f,0.100469f}, -{0.291131f,-0.00872342f,0.100469f},{0.295087f,-0.00414307f,0.100469f},{0.292515f,-0.00997107f,0.100469f}, -{0.297145f,-0.00620072f,0.100469f},{0.297772f,-0.00657676f,0.100469f},{0.29677f,-0.0156368f,0.100469f}, -{0.291837f,-0.0120555f,0.100469f},{0.300674f,-0.0121629f,0.100469f},{0.315231f,-0.00369829f,0.100469f}, -{0.305432f,-0.00620014f,0.100469f},{0.315738f,-0.00403701f,0.100469f},{0.313689f,0.0107408f,0.100469f}, -{0.313222f,0.011793f,0.100469f},{0.305595f,0.0149963f,0.100469f},{0.303071f,0.0210836f,0.100469f}, -{0.297106f,0.0210266f,0.100469f},{0.290618f,0.0123283f,0.100469f},{0.295739f,0.0207091f,0.100469f}, -{0.288207f,0.00283787f,0.100469f},{0.287805f,0.00329614f,0.100469f},{0.288237f,0.0170101f,0.100469f}, -{0.282721f,0.0107207f,0.100469f},{0.280986f,0.00689212f,0.100469f},{0.282725f,0.00430572f,0.100469f}, -{0.280579f,0.00554954f,0.100469f},{0.294398f,-0.0028536f,0.100469f},{0.289377f,0.0178274f,0.100469f}, -{0.289523f,0.0142272f,0.100469f},{0.289153f,0.0143475f,0.100469f},{0.282059f,0.00948339f,0.100469f}, -{0.286292f,0.00430656f,0.100469f},{0.289127f,0.00060826f,0.100469f},{0.290379f,0.0134558f,0.100469f}, -{0.290151f,0.0137705f,0.100469f},{0.290619f,0.0127183f,0.100469f},{0.290569f,0.0185682f,0.100469f}, -{0.289861f,0.0140321f,0.100469f},{0.302494f,0.0122844f,0.100469f},{0.312932f,0.0120546f,0.100469f}, -{0.312594f,0.0122497f,0.100469f},{0.313689f,0.0103508f,0.100469f},{0.30591f,0.0161715f,0.100469f}, -{0.304126f,0.0130817f,0.100469f},{0.304585f,0.0134836f,0.100469f},{0.304987f,0.0139422f,0.100469f}, -{0.313609f,0.0111223f,0.100469f},{0.31345f,0.0114782f,0.100469f},{0.312224f,0.01237f,0.100469f}, -{0.316285f,-0.00430656f,0.100469f},{0.314202f,-0.0107009f,0.100469f},{0.314201f,-0.0143478f,0.100469f}, -{0.315197f,-0.0137725f,0.100469f},{0.315427f,-0.0134567f,0.100469f},{0.315667f,-0.0127201f,0.100469f}, -{0.315586f,-0.0119486f,0.100469f},{0.281052f,-0.00708565f,0.100469f},{0.281575f,-0.00843163f,0.100469f}, -{0.292596f,-0.0103525f,0.100469f},{0.292515f,-0.0111238f,0.100469f},{0.294711f,-0.00351526f,0.100469f}, -{0.290538f,0.0130998f,0.100469f},{0.305791f,0.0155736f,0.100469f},{0.30579f,0.0179866f,0.100469f}, -{0.305324f,0.0191105f,0.100469f},{0.304126f,0.0204775f,0.100469f},{0.303619f,0.0208166f,0.100469f}, -{0.301897f,0.0214014f,0.100469f},{0.302494f,0.021279f,0.100469f},{0.280205f,0.00178272f,0.100469f}, -{0.279894f,0.00140253f,0.100469f},{0.280031f,0.00279893f,0.100469f},{0.28148f,0.00820537f,0.100469f}, -{0.284509f,0.00466102f,0.100469f},{0.2839f,0.00462104f,0.100469f},{0.285117f,0.00462115f,0.100469f}, -{0.288545f,0.002331f,0.100469f},{0.285715f,0.00450236f,0.100469f},{0.287346f,0.00369829f,0.100469f}, -{0.286839f,0.00403701f,0.100469f},{0.289152f,0.0107006f,0.100469f},{0.289522f,0.0108208f,0.100469f}, -{0.283302f,0.00450189f,0.100469f},{0.282178f,0.00403597f,0.100469f},{0.280811f,0.00283697f,0.100469f}, -{0.280472f,0.00233026f,0.100469f},{0.279887f,0.0006084f,0.100469f},{0.280009f,0.00120559f,0.100469f}, -{0.323375f,-0.0130142f,0.119113f},{0.321024f,-0.0163617f,0.119113f},{0.284862f,0.0202853f,0.119113f}, -{0.283823f,0.0193978f,0.119113f},{0.324037f,-0.0118202f,0.119113f},{0.288238f,0.0226051f,0.119113f}, -{0.287073f,0.0218911f,0.119113f},{0.325627f,-0.00805156f,0.119113f},{0.291935f,0.0243682f,0.119113f}, -{0.290672f,0.0238452f,0.119113f},{0.326598f,-0.0040778f,0.119113f},{0.295862f,0.0255314f,0.119113f}, -{0.297205f,0.0257805f,0.119113f},{0.294533f,0.0252126f,0.119113f},{0.293223f,0.0248245f,0.119113f}, -{0.299923f,0.0260573f,0.119113f},{0.29856f,0.0259588f,0.119113f},{0.32688f,-0.00136419f,0.119113f}, -{0.326779f,-0.00272502f,0.119113f},{0.289439f,0.023257f,0.119113f},{0.326021f,-0.00674482f,0.119113f}, -{0.326345f,-0.00541896f,0.119113f},{0.285946f,0.0211172f,0.119113f},{0.324633f,-0.0105928f,0.119113f}, -{0.325164f,-0.00933541f,0.119113f},{0.282832f,0.0184571f,0.119113f},{0.281891f,0.0174659f,0.119113f}, -{0.322651f,-0.0141713f,0.119113f},{0.281004f,0.0164267f,0.119113f},{0.280172f,0.0153425f,0.119113f}, -{0.279398f,0.0142163f,0.119113f},{0.321867f,-0.0152881f,0.119113f},{0.278684f,0.0130512f,0.119113f}, -{0.278032f,0.0118502f,0.119113f},{0.320125f,-0.0173888f,0.119113f},{0.277443f,0.0106168f,0.119113f}, -{0.319173f,-0.0183667f,0.119113f},{0.27692f,0.00935425f,0.119113f},{0.31817f,-0.0192925f,0.119113f}, -{0.276464f,0.00806608f,0.119113f},{0.31712f,-0.0201635f,0.119113f},{0.276076f,0.00675581f,0.119113f}, -{0.316024f,-0.0209774f,0.119113f},{0.275757f,0.00542697f,0.119113f},{0.314887f,-0.021732f,0.119113f}, -{0.275508f,0.00408325f,0.119113f},{0.313711f,-0.022425f,0.119113f},{0.27533f,0.00272836f,0.119113f}, -{0.3125f,-0.0230545f,0.119113f},{0.275223f,0.00136603f,0.119113f},{0.311257f,-0.0236185f,0.119113f}, -{0.275187f,5.40871e-017f,0.119113f},{0.309985f,-0.0241155f,0.119113f},{0.275698f,-0.00136408f,0.119113f}, -{0.275223f,-0.0013662f,0.119113f},{0.308689f,-0.0245441f,0.119113f},{0.275798f,-0.00272485f,0.119113f}, -{0.27533f,-0.00272864f,0.119113f},{0.307373f,-0.0249032f,0.119113f},{0.275979f,-0.0040775f,0.119113f}, -{0.275508f,-0.00408356f,0.119113f},{0.306038f,-0.0251918f,0.119113f},{0.304691f,-0.0254089f,0.119113f}, -{0.301971f,-0.0256265f,0.119113f},{0.276232f,-0.00541865f,0.119113f},{0.275757f,-0.00542725f,0.119113f}, -{0.29856f,-0.025959f,0.119113f},{0.297886f,-0.0254087f,0.119113f},{0.297205f,-0.0257802f,0.119113f}, -{0.277413f,-0.00933492f,0.119113f},{0.27695f,-0.00805103f,0.119113f},{0.276921f,-0.00935456f,0.119113f}, -{0.294533f,-0.0252123f,0.119113f},{0.293887f,-0.0245439f,0.119113f},{0.293223f,-0.0248241f,0.119113f}, -{0.278684f,-0.0130514f,0.119113f},{0.27854f,-0.0118198f,0.119113f},{0.278032f,-0.0118505f,0.119113f}, -{0.289439f,-0.0232571f,0.119113f},{0.290673f,-0.0238453f,0.119113f},{0.290077f,-0.0230539f,0.119113f}, -{0.281004f,-0.0164269f,0.119113f},{0.28071f,-0.0152875f,0.119113f},{0.280172f,-0.0153428f,0.119113f}, -{0.284863f,-0.0202852f,0.119113f},{0.284407f,-0.019292f,0.119113f},{0.283824f,-0.0193978f,0.119113f}, -{0.288238f,-0.022605f,0.119113f},{0.288866f,-0.0224246f,0.119113f},{0.282452f,-0.0173882f,0.119113f}, -{0.281892f,-0.017466f,0.119113f},{0.282833f,-0.0184572f,0.119113f},{0.283404f,-0.0183661f,0.119113f}, -{0.285947f,-0.021117f,0.119113f},{0.287073f,-0.021891f,0.119113f},{0.286553f,-0.0209773f,0.119113f}, -{0.28769f,-0.0217317f,0.119113f},{0.281553f,-0.016361f,0.119113f},{0.285457f,-0.0201633f,0.119113f}, -{0.292591f,-0.0241152f,0.119113f},{0.291935f,-0.024368f,0.119113f},{0.29132f,-0.023618f,0.119113f}, -{0.279202f,-0.0130136f,0.119113f},{0.279398f,-0.0142166f,0.119113f},{0.279926f,-0.0141706f,0.119113f}, -{0.296538f,-0.0251915f,0.119113f},{0.295862f,-0.0255313f,0.119113f},{0.295204f,-0.024903f,0.119113f}, -{0.277944f,-0.0105924f,0.119113f},{0.277444f,-0.0106171f,0.119113f},{0.300606f,-0.0256265f,0.119113f}, -{0.299923f,-0.0260568f,0.119113f},{0.299243f,-0.0255538f,0.119113f},{0.276076f,-0.00675606f,0.119113f}, -{0.276556f,-0.00674437f,0.119113f},{0.276465f,-0.00806637f,0.119113f},{0.303334f,-0.0255539f,0.119113f}, -{0.295839f,-0.0255265f,0.10513f},{0.297181f,-0.0257766f,0.10513f},{0.298538f,-0.0259565f,0.10513f}, -{0.291931f,-0.0243666f,0.10513f},{0.294515f,-0.0252075f,0.10513f},{0.287092f,-0.0219036f,0.10513f}, -{0.288254f,-0.0226143f,0.10513f},{0.28945f,-0.0232624f,0.10513f},{0.290676f,-0.0238468f,0.10513f}, -{0.283834f,-0.0194069f,0.10513f},{0.285967f,-0.0211315f,0.10513f},{0.280157f,-0.0153222f,0.10513f}, -{0.28099f,-0.0164092f,0.10513f},{0.281882f,-0.0174549f,0.10513f},{0.282832f,-0.0184567f,0.10513f}, -{0.278026f,-0.0118391f,0.10513f},{0.279385f,-0.0141964f,0.10513f},{0.276081f,-0.00677408f,0.10513f}, -{0.276468f,-0.00807765f,0.10513f},{0.276922f,-0.00935809f,0.10513f},{0.277442f,-0.0106128f,0.10513f}, -{0.275512f,-0.0041079f,0.10513f},{0.275332f,-0.00275048f,0.10513f},{0.275762f,-0.00544996f,0.10513f}, -{0.275223f,0.00138025f,0.10513f},{0.275187f,4.23508e-018f,0.10513f},{0.275223f,-0.00138032f,0.10513f}, -{0.275762f,0.00544975f,0.10513f},{0.275512f,0.00410773f,0.10513f},{0.275332f,0.00275036f,0.10513f}, -{0.276468f,0.0080774f,0.10513f},{0.276081f,0.00677384f,0.10513f},{0.277442f,0.0106125f,0.10513f}, -{0.278026f,0.0118389f,0.10513f},{0.276922f,0.00935782f,0.10513f},{0.279385f,0.0141962f,0.10513f}, -{0.278674f,0.0130343f,0.10513f},{0.28099f,0.0164091f,0.10513f},{0.280157f,0.015322f,0.10513f}, -{0.282832f,0.0184567f,0.10513f},{0.281882f,0.0174549f,0.10513f},{0.283834f,0.0194069f,0.10513f}, -{0.284879f,0.0202988f,0.10513f},{0.285966f,0.0211314f,0.10513f},{0.287092f,0.0219036f,0.10513f}, -{0.288254f,0.0226142f,0.10513f},{0.289449f,0.0232623f,0.10513f},{0.290676f,0.0238467f,0.10513f}, -{0.29193f,0.0243664f,0.10513f},{0.293211f,0.0248204f,0.10513f},{0.294514f,0.0252074f,0.10513f}, -{0.295839f,0.0255265f,0.10513f},{0.297181f,0.0257765f,0.10513f},{0.298538f,0.0259565f,0.10513f}, -{0.299908f,0.0260652f,0.10513f},{0.278674f,-0.0130346f,0.10513f},{0.284879f,-0.0202989f,0.10513f}, -{0.293211f,-0.0248205f,0.10513f},{0.299908f,-0.0260653f,0.10513f},{0.284864f,-0.013782f,0.10513f}, -{0.288485f,-0.0171983f,0.10513f},{0.292797f,-0.0196871f,0.10513f},{0.297566f,-0.0211136f,0.10513f}, -{0.300042f,-0.0214048f,0.10513f},{0.2988f,-0.0212945f,0.10513f},{0.293956f,-0.0201477f,0.10513f}, -{0.291666f,-0.01916f,0.10513f},{0.290569f,-0.0185682f,0.10513f},{0.289507f,-0.0179136f,0.10513f}, -{0.285693f,-0.0147136f,0.10513f},{0.286575f,-0.0155955f,0.10513f},{0.287507f,-0.0164247f,0.10513f}, -{0.282721f,-0.0107207f,0.10513f},{0.283375f,-0.0117822f,0.10513f},{0.284091f,-0.0128038f,0.10513f}, -{0.282129f,-0.00962296f,0.10513f},{0.281602f,-0.00849262f,0.10513f},{0.281141f,-0.00733354f,0.10513f}, -{0.280749f,-0.00614966f,0.10513f},{0.280426f,-0.00494495f,0.10513f},{0.280174f,-0.00372348f,0.10513f}, -{0.279993f,-0.00248937f,0.10513f},{0.279884f,-0.00124681f,0.10513f},{0.279848f,-1.52221e-017f,0.10513f}, -{0.279884f,0.00124661f,0.10513f},{0.279993f,0.00248903f,0.10513f},{0.280174f,0.00372306f,0.10513f}, -{0.280426f,0.0049445f,0.10513f},{0.280748f,0.00614923f,0.10513f},{0.281141f,0.00733314f,0.10513f}, -{0.281601f,0.00849224f,0.10513f},{0.28272f,0.0107204f,0.10513f},{0.2988f,0.0212927f,0.10513f}, -{0.300041f,0.0214054f,0.10513f},{0.284864f,0.013782f,0.10513f},{0.296343f,0.0208628f,0.10513f}, -{0.295139f,0.0205399f,0.10513f},{0.287507f,0.0164248f,0.10513f},{0.286575f,0.0155957f,0.10513f}, -{0.290568f,0.0185682f,0.10513f},{0.289507f,0.0179135f,0.10513f},{0.288485f,0.0171982f,0.10513f}, -{0.292796f,0.0196873f,0.10513f},{0.293955f,0.0201477f,0.10513f},{0.291666f,0.0191602f,0.10513f}, -{0.297567f,0.0211056f,0.10513f},{0.285693f,0.0147138f,0.10513f},{0.283375f,0.011782f,0.10513f}, -{0.28409f,0.0128037f,0.10513f},{0.282128f,0.0096226f,0.10513f},{0.296344f,-0.02086f,0.10513f}, -{0.295139f,-0.0205402f,0.10513f},{0.296327f,-0.0208587f,0.104198f},{0.297545f,-0.0211115f,0.104198f}, -{0.298781f,-0.0212936f,0.104198f},{0.292798f,-0.019688f,0.104198f},{0.295127f,-0.0205363f,0.104198f}, -{0.288501f,-0.0172102f,0.104198f},{0.289523f,-0.0179243f,0.104198f},{0.290582f,-0.018576f,0.104198f}, -{0.291674f,-0.0191643f,0.104198f},{0.285689f,-0.0147088f,0.104198f},{0.287519f,-0.0164352f,0.104198f}, -{0.282713f,-0.010707f,0.104198f},{0.283364f,-0.0117656f,0.104198f},{0.284078f,-0.0127873f,0.104198f}, -{0.281143f,-0.00733859f,0.104198f},{0.281601f,-0.00849054f,0.104198f},{0.282124f,-0.0096143f,0.104198f}, -{0.279995f,-0.00250813f,0.104198f},{0.280177f,-0.00374334f,0.104198f},{0.28043f,-0.00496208f,0.104198f}, -{0.280752f,-0.00616144f,0.104198f},{0.279848f,-2.06038e-017f,0.104198f},{0.279885f,0.00125925f,0.104198f}, -{0.279885f,-0.00125938f,0.104198f},{0.280177f,0.00374312f,0.104198f},{0.279995f,0.00250793f,0.104198f}, -{0.281143f,0.0073385f,0.104198f},{0.280752f,0.00616138f,0.104198f},{0.28043f,0.00496191f,0.104198f}, -{0.282124f,0.00961408f,0.104198f},{0.281601f,0.00849036f,0.104198f},{0.284078f,0.0127873f,0.104198f}, -{0.283364f,0.0117655f,0.104198f},{0.282713f,0.0107068f,0.104198f},{0.285688f,0.0147082f,0.104198f}, -{0.284853f,0.0137691f,0.104198f},{0.28658f,0.0155998f,0.104198f},{0.287519f,0.0164352f,0.104198f}, -{0.288501f,0.0172102f,0.104198f},{0.289523f,0.0179242f,0.104198f},{0.290582f,0.018576f,0.104198f}, -{0.291674f,0.0191643f,0.104198f},{0.292798f,0.0196879f,0.104198f},{0.29395f,0.0201457f,0.104198f}, -{0.295127f,0.0205363f,0.104198f},{0.297545f,0.0211114f,0.104198f},{0.296326f,0.0208586f,0.104198f}, -{0.29878f,0.0212935f,0.104198f},{0.300029f,0.0214037f,0.104198f},{0.284853f,-0.0137693f,0.104198f}, -{0.28658f,-0.0156004f,0.104198f},{0.29395f,-0.0201457f,0.104198f},{0.300029f,-0.0214037f,0.104198f}, -{0.285399f,-0.0207081f,0.104198f},{0.275187f,2.47615e-017f,0.104198f},{0.275243f,-0.00170747f,0.104198f}, -{0.277174f,-0.0099892f,0.104198f},{0.275689f,-0.00509254f,0.104198f},{0.276076f,-0.00675606f,0.104198f}, -{0.277879f,-0.0115449f,0.104198f},{0.279586f,-0.0145019f,0.104198f},{0.280581f,-0.0158902f,0.104198f}, -{0.294533f,-0.0252123f,0.104198f},{0.296197f,-0.0256001f,0.104198f},{0.299582f,-0.0260375f,0.104198f}, -{0.288238f,-0.022605f,0.104198f},{0.289744f,-0.0234101f,0.104198f},{0.2913f,-0.0241149f,0.104198f}, -{0.292899f,-0.0247164f,0.104198f},{0.286788f,-0.0217031f,0.104198f},{0.282833f,-0.0184572f,0.104198f}, -{0.284079f,-0.0196247f,0.104198f},{0.297882f,-0.0258794f,0.104198f},{0.281665f,-0.0172106f,0.104198f}, -{0.278684f,-0.0130514f,0.104198f},{0.276572f,-0.00839068f,0.104198f},{0.27541f,-0.00340738f,0.104198f}, -{0.275243f,0.00170697f,0.104198f},{0.27541f,0.0034068f,0.104198f},{0.276572f,0.00839024f,0.104198f}, -{0.276076f,0.00675581f,0.104198f},{0.275688f,0.00509225f,0.104198f},{0.277174f,0.00998889f,0.104198f}, -{0.277879f,0.0115449f,0.104198f},{0.278684f,0.0130512f,0.104198f},{0.280581f,0.0158901f,0.104198f}, -{0.279586f,0.0145016f,0.104198f},{0.281664f,0.0172105f,0.104198f},{0.284079f,0.0196248f,0.104198f}, -{0.286787f,0.0217032f,0.104198f},{0.285399f,0.0207084f,0.104198f},{0.288238f,0.0226051f,0.104198f}, -{0.289744f,0.0234102f,0.104198f},{0.297881f,0.0258786f,0.104198f},{0.299581f,0.0260403f,0.104198f}, -{0.296196f,0.0256003f,0.104198f},{0.294533f,0.0252126f,0.104198f},{0.292898f,0.0247167f,0.104198f}, -{0.282832f,0.0184571f,0.104198f},{0.2913f,0.024115f,0.104198f},{0.289869f,0.0197792f,0.101587f}, -{0.288101f,0.0186469f,0.101587f},{0.288937f,0.0213938f,0.103079f},{0.28338f,0.0141739f,0.101587f}, -{0.284829f,0.0158335f,0.101587f},{0.286412f,0.0173289f,0.101587f},{0.278843f,0.00421973f,0.101587f}, -{0.279347f,0.00633871f,0.101587f},{0.280059f,0.00842303f,0.101587f},{0.27845f,6.45552e-018f,0.101587f}, -{0.278546f,0.00209801f,0.101587f},{0.288937f,-0.0213938f,0.103079f},{0.289869f,-0.0197792f,0.101587f}, -{0.291137f,-0.0204589f,0.101587f},{0.292465f,-0.0210659f,0.101587f},{0.293848f,-0.0215929f,0.101587f}, -{0.295277f,-0.0220336f,0.101587f},{0.296745f,-0.0223824f,0.101587f},{0.298242f,-0.022635f,0.101587f}, -{0.29976f,-0.0227878f,0.101587f},{0.294786f,-0.0238322f,0.103079f},{0.296374f,-0.0242096f,0.103079f}, -{0.290308f,-0.0221291f,0.103079f},{0.297994f,-0.0244827f,0.103079f},{0.299636f,-0.0246481f,0.103079f}, -{0.29324f,-0.0233556f,0.103079f},{0.291745f,-0.0227855f,0.103079f},{0.282089f,0.0123693f,0.101587f}, -{0.280977f,0.0104434f,0.101587f},{0.285197f,0.0187434f,0.103079f},{0.276585f,8.86415e-018f,0.103079f}, -{0.27669f,0.00226809f,0.103079f},{0.27701f,0.00456378f,0.103079f},{0.277555f,0.00685491f,0.103079f}, -{0.278326f,0.00910982f,0.103079f},{0.279319f,0.011295f,0.103079f},{0.280521f,0.0133782f,0.103079f}, -{0.281917f,0.0153304f,0.103079f},{0.283484f,0.0171254f,0.103079f},{0.287024f,0.0201689f,0.103079f}, -{0.326888f,-0.00136552f,0.120977f},{0.326779f,-0.00272732f,0.120977f},{0.315039f,-0.0216357f,0.120977f}, -{0.31683f,-0.0203873f,0.120977f},{0.31315f,-0.0227264f,0.120977f},{0.311173f,-0.0236533f,0.120977f}, -{0.291403f,-0.0236531f,0.120977f},{0.289427f,-0.0227263f,0.120977f},{0.285747f,-0.0203871f,0.120977f}, -{0.287538f,-0.0216356f,0.120977f},{0.27598f,-0.0040808f,0.120977f},{0.275798f,-0.00272711f,0.120977f}, -{0.275689f,-0.00136573f,0.120977f},{0.326597f,-0.00408095f,0.120977f},{0.289129f,0.000612842f,0.103265f}, -{0.288547f,0.00232777f,0.103265f},{0.288815f,0.00178369f,0.103265f},{0.28901f,0.00120978f,0.103265f}, -{0.287343f,0.00370055f,0.103265f},{0.288209f,0.0028342f,0.103265f},{0.287805f,0.00329584f,0.103265f}, -{0.285121f,0.00462066f,0.103265f},{0.285718f,0.00450141f,0.103265f},{0.286293f,0.00430621f,0.103265f}, -{0.283896f,0.00462052f,0.103265f},{0.283299f,0.00450127f,0.103265f},{0.284509f,0.00466102f,0.103265f}, -{0.282181f,0.00403818f,0.103265f},{0.282725f,0.00430621f,0.103265f},{0.281213f,0.00329584f,0.103265f}, -{0.281675f,0.00370041f,0.103265f},{0.280808f,0.00283386f,0.103265f},{0.280471f,0.00232743f,0.103265f}, -{0.280203f,0.00178369f,0.103265f},{0.280007f,0.00120944f,0.103265f},{0.279888f,0.000612502f,0.103265f}, -{0.286836f,0.00403832f,0.103265f},{0.291501f,-0.00884266f,0.109791f},{0.291838f,-0.00903773f,0.109791f}, -{0.29113f,-0.00872205f,0.109791f},{0.292128f,-0.00929879f,0.109791f},{0.292357f,-0.00961469f,0.109791f}, -{0.292515f,-0.00997137f,0.109791f},{0.292596f,-0.0103527f,0.109791f},{0.292596f,-0.0107427f,0.109791f}, -{0.292354f,-0.0114796f,0.109791f},{0.292514f,-0.011124f,0.109791f},{0.291836f,-0.0120547f,0.109791f}, -{0.292125f,-0.0117943f,0.109791f},{0.291129f,-0.0123696f,0.109791f},{0.291499f,-0.0122492f,0.109791f}, -{0.314571f,-0.0108202f,0.109791f},{0.314909f,-0.0110152f,0.109791f},{0.314201f,-0.0106996f,0.109791f}, -{0.315199f,-0.0112763f,0.109791f},{0.315428f,-0.0115922f,0.109791f},{0.315586f,-0.0119489f,0.109791f}, -{0.315667f,-0.0123302f,0.109791f},{0.315667f,-0.0127202f,0.109791f},{0.315425f,-0.0134571f,0.109791f}, -{0.315585f,-0.0131015f,0.109791f},{0.314907f,-0.0140322f,0.109791f},{0.315196f,-0.0137718f,0.109791f}, -{0.3142f,-0.0143471f,0.109791f},{0.31457f,-0.0142268f,0.109791f},{0.312594f,0.0122507f,0.109791f}, -{0.312932f,0.0120557f,0.109791f},{0.312223f,0.0123713f,0.109791f},{0.313222f,0.0117946f,0.109791f}, -{0.313451f,0.0114787f,0.109791f},{0.313609f,0.011122f,0.109791f},{0.313689f,0.0107407f,0.109791f}, -{0.313689f,0.0103507f,0.109791f},{0.313448f,0.00961383f,0.109791f},{0.313607f,0.00996936f,0.109791f}, -{0.312929f,0.00903866f,0.109791f},{0.313219f,0.00929907f,0.109791f},{0.312222f,0.00872375f,0.109791f}, -{0.312592f,0.00884413f,0.109791f},{0.289523f,0.0142282f,0.109791f},{0.289861f,0.0140332f,0.109791f}, -{0.289152f,0.0143488f,0.109791f},{0.290151f,0.0137721f,0.109791f},{0.29038f,0.0134562f,0.109791f}, -{0.290538f,0.0130995f,0.109791f},{0.290619f,0.0127182f,0.109791f},{0.290618f,0.0123282f,0.109791f}, -{0.290377f,0.0115913f,0.109791f},{0.290536f,0.0119469f,0.109791f},{0.289858f,0.0110162f,0.109791f}, -{0.290148f,0.0112766f,0.109791f},{0.289151f,0.0107013f,0.109791f},{0.289521f,0.0108216f,0.109791f}, -{0.300676f,-0.0121592f,0.103265f},{0.298961f,-0.0127415f,0.103265f},{0.300079f,-0.0122784f,0.103265f}, -{0.299505f,-0.0124735f,0.103265f},{0.297588f,-0.0139458f,0.103265f},{0.29725f,-0.0144523f,0.103265f}, -{0.297993f,-0.0134838f,0.103265f},{0.296668f,-0.0161672f,0.103265f},{0.296982f,-0.014996f,0.103265f}, -{0.296787f,-0.0155702f,0.103265f},{0.296787f,-0.0179895f,0.103265f},{0.296628f,-0.0167797f,0.103265f}, -{0.296668f,-0.0173925f,0.103265f},{0.29725f,-0.0191075f,0.103265f},{0.297588f,-0.0196139f,0.103265f}, -{0.296982f,-0.0185634f,0.103265f},{0.297993f,-0.0200755f,0.103265f},{0.298455f,-0.0204802f,0.103265f}, -{0.298961f,-0.020818f,0.103265f},{0.299505f,-0.0210859f,0.103265f},{0.300079f,-0.0212811f,0.103265f}, -{0.300676f,-0.0214003f,0.103265f},{0.298454f,-0.0130793f,0.103265f},{0.313448f,-0.000612842f,0.103265f}, -{0.31403f,-0.00232777f,0.103265f},{0.313762f,-0.00178369f,0.103265f},{0.313567f,-0.00120978f,0.103265f}, -{0.315234f,-0.00370055f,0.103265f},{0.314368f,-0.0028342f,0.103265f},{0.314772f,-0.00329584f,0.103265f}, -{0.317456f,-0.00462066f,0.103265f},{0.316859f,-0.00450141f,0.103265f},{0.316285f,-0.00430621f,0.103265f}, -{0.319278f,-0.00450127f,0.103265f},{0.318681f,-0.00462052f,0.103265f},{0.318068f,-0.00466102f,0.103265f}, -{0.320396f,-0.00403818f,0.103265f},{0.319852f,-0.00430621f,0.103265f},{0.321364f,-0.00329584f,0.103265f}, -{0.320902f,-0.00370041f,0.103265f},{0.321769f,-0.00283386f,0.103265f},{0.322107f,-0.00232743f,0.103265f}, -{0.322374f,-0.00178369f,0.103265f},{0.32257f,-0.00120944f,0.103265f},{0.322689f,-0.000612502f,0.103265f}, -{0.315741f,-0.00403832f,0.103265f},{0.301901f,0.0121592f,0.103265f},{0.303616f,0.0127415f,0.103265f}, -{0.303072f,0.0124735f,0.103265f},{0.302498f,0.0122784f,0.103265f},{0.304989f,0.0139458f,0.103265f}, -{0.304123f,0.0130793f,0.103265f},{0.304584f,0.0134838f,0.103265f},{0.305909f,0.0161672f,0.103265f}, -{0.30579f,0.0155702f,0.103265f},{0.305595f,0.014996f,0.103265f},{0.305909f,0.0173925f,0.103265f}, -{0.30579f,0.0179895f,0.103265f},{0.30595f,0.0167797f,0.103265f},{0.305327f,0.0191075f,0.103265f}, -{0.305595f,0.0185634f,0.103265f},{0.304584f,0.0200755f,0.103265f},{0.304989f,0.0196139f,0.103265f}, -{0.304122f,0.0204802f,0.103265f},{0.303616f,0.020818f,0.103265f},{0.303072f,0.0210859f,0.103265f}, -{0.302498f,0.0212811f,0.103265f},{0.301901f,0.0214003f,0.103265f},{0.305327f,0.0144523f,0.103265f}, -{0.312708f,-0.0197792f,0.103265f},{0.31077f,-0.0207778f,0.103265f},{0.304545f,-0.0226057f,0.103265f}, -{0.308754f,-0.0215843f,0.103265f},{0.298032f,-0.0226056f,0.103265f},{0.302379f,-0.022813f,0.103265f}, -{0.300197f,-0.0228129f,0.103265f},{0.293823f,-0.0215842f,0.103265f},{0.295902f,-0.0221948f,0.103265f}, -{0.291806f,-0.0207777f,0.103265f},{0.289869f,-0.0197792f,0.103265f},{0.306674f,-0.0221949f,0.103265f}, -{0.31364f,-0.0213938f,0.103265f},{0.288937f,-0.0213938f,0.103265f},{0.291033f,-0.022474f,0.103265f}, -{0.297767f,-0.0244511f,0.103265f},{0.293213f,-0.0233463f,0.103265f},{0.304811f,-0.024451f,0.103265f}, -{0.300109f,-0.0246752f,0.103265f},{0.302469f,-0.0246752f,0.103265f},{0.309364f,-0.0233462f,0.103265f}, -{0.311545f,-0.0224738f,0.103265f},{0.307114f,-0.0240066f,0.103265f},{0.295463f,-0.0240067f,0.103265f}, -{0.314542f,0.0186002f,0.103265f},{0.312708f,0.0197792f,0.103265f},{0.319238f,0.0141228f,0.103265f}, -{0.317817f,0.0157616f,0.103265f},{0.316248f,0.0172577f,0.103265f},{0.321591f,0.0104612f,0.103265f}, -{0.322494f,0.00848256f,0.103265f},{0.3205f,0.0123508f,0.103265f},{0.323714f,0.00432634f,0.103265f}, -{0.323203f,0.00643279f,0.103265f},{0.324024f,0.00217707f,0.103265f},{0.324128f,-1.5323e-017f,0.103265f}, -{0.31364f,0.0213938f,0.103265f},{0.325992f,-1.67506e-017f,0.103265f},{0.325879f,0.00235542f,0.103265f}, -{0.324225f,0.00917539f,0.103265f},{0.324992f,0.0069585f,0.103265f},{0.325545f,0.00467972f,0.103265f}, -{0.322068f,0.01336f,0.103265f},{0.320703f,0.015276f,0.103265f},{0.323248f,0.0113162f,0.103265f}, -{0.319166f,0.0170487f,0.103265f},{0.317469f,0.0186667f,0.103265f},{0.315623f,0.020119f,0.103265f}, -{0.278554f,0.00217765f,0.103265f},{0.27845f,2.16517e-018f,0.103265f},{0.280083f,0.00848291f,0.103265f}, -{0.279374f,0.00643333f,0.103265f},{0.278863f,0.00432654f,0.103265f},{0.282078f,0.0123517f,0.103265f}, -{0.28334f,0.0141231f,0.103265f},{0.280987f,0.0104622f,0.103265f},{0.286329f,0.0172579f,0.103265f}, -{0.28476f,0.015762f,0.103265f},{0.288036f,0.0186006f,0.103265f},{0.289869f,0.0197792f,0.103265f}, -{0.276585f,1.02508e-017f,0.103265f},{0.288937f,0.0213938f,0.103265f},{0.286953f,0.0201186f,0.103265f}, -{0.281874f,0.0152757f,0.103265f},{0.283411f,0.0170482f,0.103265f},{0.285108f,0.0186665f,0.103265f}, -{0.279329f,0.0113151f,0.103265f},{0.278352f,0.00917501f,0.103265f},{0.280509f,0.013359f,0.103265f}, -{0.277585f,0.00695792f,0.103265f},{0.277032f,0.00467951f,0.103265f},{0.276698f,0.00235479f,0.103265f}, -{0.298535f,-0.000488516f,0.0976722f},{0.299146f,-0.00179767f,0.0976722f},{0.298866f,-0.00139727f,0.0976722f}, -{0.298661f,-0.000957717f,0.0976722f},{0.300332f,-0.00262801f,0.0976722f},{0.300801f,-0.00275376f,0.0976722f}, -{0.299493f,-0.00214411f,0.0976722f},{0.299893f,-0.00242333f,0.0976722f},{0.302246f,-0.00262748f,0.0976722f}, -{0.301777f,-0.00275356f,0.0976722f},{0.301289f,-0.00279661f,0.0976722f},{0.303086f,-0.00214219f,0.0976722f}, -{0.302686f,-0.00242266f,0.0976722f},{0.303433f,-0.00179504f,0.0976722f},{0.303712f,-0.00139564f,0.0976722f}, -{0.303917f,-0.000956449f,0.0976722f},{0.304042f,-0.000488516f,0.0976722f},{0.318698f,-0.00122594f,0.120977f}, -{0.318576f,-0.00061944f,0.120977f},{0.318534f,2.3413e-019f,0.120977f},{0.318901f,-0.0018111f,0.120977f}, -{0.319529f,-0.00287862f,0.120977f},{0.31918f,-0.00236645f,0.120977f},{0.319943f,-0.00333866f,0.120977f}, -{0.320415f,-0.00374077f,0.120977f},{0.320937f,-0.00407752f,0.120977f},{0.321498f,-0.00434093f,0.120977f}, -{0.322088f,-0.00452747f,0.120977f},{0.322699f,-0.00463457f,0.120977f},{0.318576f,0.000619763f,0.120977f}, -{0.318698f,0.00122605f,0.120977f},{0.318901f,0.00181151f,0.120977f},{0.31918f,0.00236685f,0.120977f}, -{0.31953f,0.00287881f,0.120977f},{0.319943f,0.00333885f,0.120977f},{0.320415f,0.00374104f,0.120977f}, -{0.320938f,0.00407771f,0.120977f},{0.321498f,0.00434097f,0.120977f},{0.322088f,0.00452758f,0.120977f}, -{0.322699f,0.00463457f,0.120977f},{0.308905f,0.00708542f,0.120977f},{0.309508f,0.00862355f,0.120977f}, -{0.309231f,0.0081433f,0.120977f},{0.309029f,0.00762768f,0.120977f},{0.31073f,0.00975654f,0.120977f}, -{0.309858f,0.00906182f,0.120977f},{0.31027f,0.00944325f,0.120977f},{0.312873f,0.0102431f,0.120977f}, -{0.312313f,0.0102438f,0.120977f},{0.311758f,0.0101602f,0.120977f},{0.313954f,0.0099962f,0.120977f}, -{0.313425f,0.0101597f,0.120977f},{0.314916f,0.00944071f,0.120977f},{0.315326f,0.00905963f,0.120977f}, -{0.314454f,0.00975564f,0.120977f},{0.315674f,0.00862291f,0.120977f},{0.315951f,0.0081413f,0.120977f}, -{0.316154f,0.00762524f,0.120977f},{0.316277f,0.00708542f,0.120977f},{0.311229f,0.00999655f,0.120977f}, -{0.308787f,0.000388892f,0.120977f},{0.309364f,0.0013863f,0.120977f},{0.308908f,0.000758756f,0.120977f}, -{0.310416f,0.00185425f,0.120977f},{0.309679f,0.00161492f,0.120977f},{0.310035f,0.0017734f,0.120977f}, -{0.311188f,0.00177278f,0.120977f},{0.311543f,0.0016145f,0.120977f},{0.310806f,0.00185398f,0.120977f}, -{0.311859f,0.00138471f,0.120977f},{0.312119f,0.00109509f,0.120977f},{0.312314f,0.000757801f,0.120977f}, -{0.312434f,0.000387896f,0.120977f},{0.309103f,0.00109643f,0.120977f},{0.307612f,0.0184341f,0.120977f}, -{0.307586f,0.019053f,0.120977f},{0.307641f,0.0196708f,0.120977f},{0.307724f,0.0178247f,0.120977f}, -{0.307916f,0.0172353f,0.120977f},{0.308185f,0.0166765f,0.120977f},{0.308526f,0.0161585f,0.120977f}, -{0.309911f,0.0149353f,0.120977f},{0.310468f,0.0146616f,0.120977f},{0.308932f,0.0156903f,0.120977f}, -{0.309397f,0.0152802f,0.120977f},{0.311664f,0.0143468f,0.120977f},{0.312283f,0.0143112f,0.120977f}, -{0.31561f,0.0157495f,0.120977f},{0.315151f,0.015333f,0.120977f},{0.313508f,0.0144863f,0.120977f}, -{0.314092f,0.0146944f,0.120977f},{0.314643f,0.0149788f,0.120977f},{0.316008f,0.0162251f,0.120977f}, -{0.312901f,0.014358f,0.120977f},{0.311056f,0.0144643f,0.120977f},{0.307765f,0.0202771f,0.120977f}, -{0.30798f,0.0208597f,0.120977f},{0.29896f,0.0101384f,0.120977f},{0.29793f,0.0114304f,0.120977f}, -{0.298208f,0.0109503f,0.120977f},{0.298553f,0.0105172f,0.120977f},{0.29756f,0.0130549f,0.120977f}, -{0.297725f,0.011952f,0.120977f},{0.297601f,0.0124996f,0.120977f},{0.29821f,0.0151544f,0.120977f}, -{0.297929f,0.0146689f,0.120977f},{0.297725f,0.0141474f,0.120977f},{0.298964f,0.0159666f,0.120977f}, -{0.298558f,0.01559f,0.120977f},{0.299926f,0.0165217f,0.120977f},{0.300461f,0.0166864f,0.120977f}, -{0.299423f,0.0162794f,0.120977f},{0.301014f,0.0167695f,0.120977f},{0.301569f,0.016769f,0.120977f}, -{0.302118f,0.0166865f,0.120977f},{0.302647f,0.0165233f,0.120977f},{0.297601f,0.0136068f,0.120977f}, -{0.304701f,0.00668844f,0.120977f},{0.304126f,0.00768651f,0.120977f},{0.304441f,0.00697788f,0.120977f}, -{0.304247f,0.00883213f,0.120977f},{0.304085f,0.00807381f,0.120977f},{0.304126f,0.0084617f,0.120977f}, -{0.304703f,0.00945932f,0.120977f},{0.305018f,0.00968801f,0.120977f},{0.304442f,0.00916954f,0.120977f}, -{0.305374f,0.00984652f,0.120977f},{0.305755f,0.00992735f,0.120977f},{0.306145f,0.00992722f,0.120977f}, -{0.306526f,0.00984624f,0.120977f},{0.304246f,0.00731557f,0.120977f},{0.287937f,0.0149805f,0.120977f}, -{0.28743f,0.0153371f,0.120977f},{0.293646f,0.0156909f,0.120977f},{0.293181f,0.0152805f,0.120977f}, -{0.294052f,0.0161593f,0.120977f},{0.292666f,0.0149353f,0.120977f},{0.294392f,0.0166773f,0.120977f}, -{0.29466f,0.0172358f,0.120977f},{0.294853f,0.0178252f,0.120977f},{0.29211f,0.0146618f,0.120977f}, -{0.291522f,0.0144645f,0.120977f},{0.294964f,0.0184349f,0.120977f},{0.290913f,0.0143468f,0.120977f}, -{0.294994f,0.0190544f,0.120977f},{0.29481f,0.0202777f,0.120977f},{0.294941f,0.0196718f,0.120977f}, -{0.290295f,0.0143109f,0.120977f},{0.294597f,0.0208597f,0.120977f},{0.289676f,0.0143575f,0.120977f}, -{0.288486f,0.0146931f,0.120977f},{0.28907f,0.0144856f,0.120977f},{0.286966f,0.0157476f,0.120977f}, -{0.286569f,0.0162251f,0.120977f},{0.291344f,0.00305297f,0.120977f},{0.28971f,0.00280688f,0.120977f}, -{0.290265f,0.00280698f,0.120977f},{0.290813f,0.00288948f,0.120977f},{0.288118f,0.00329833f,0.120977f}, -{0.289156f,0.00289017f,0.120977f},{0.28862f,0.00305631f,0.120977f},{0.286625f,0.00491125f,0.120977f}, -{0.286905f,0.00442515f,0.120977f},{0.287255f,0.00398713f,0.120977f},{0.286299f,0.00597044f,0.120977f}, -{0.286422f,0.00543021f,0.120977f},{0.286299f,0.00708102f,0.120977f},{0.286424f,0.00762679f,0.120977f}, -{0.286257f,0.00652376f,0.120977f},{0.286628f,0.0081466f,0.120977f},{0.286907f,0.00862774f,0.120977f}, -{0.287252f,0.00906124f,0.120977f},{0.287658f,0.00943791f,0.120977f},{0.287661f,0.00361021f,0.120977f}, -{0.297203f,0.0062997f,0.120977f},{0.29605f,0.00630037f,0.120977f},{0.296822f,0.00621894f,0.120977f}, -{0.295119f,0.0069779f,0.120977f},{0.295695f,0.00645888f,0.120977f},{0.295379f,0.0066883f,0.120977f}, -{0.294804f,0.00768661f,0.120977f},{0.294763f,0.00807365f,0.120977f},{0.294924f,0.00731544f,0.120977f}, -{0.294804f,0.00846171f,0.120977f},{0.294925f,0.00883217f,0.120977f},{0.29512f,0.00916947f,0.120977f}, -{0.29538f,0.00945876f,0.120977f},{0.296432f,0.00621907f,0.120977f},{0.283398f,-0.0023656f,0.120977f}, -{0.283676f,-0.00181168f,0.120977f},{0.283048f,-0.00287783f,0.120977f},{0.282634f,-0.00333905f,0.120977f}, -{0.282163f,-0.00374099f,0.120977f},{0.283879f,-0.00122583f,0.120977f},{0.281639f,-0.00407246f,0.120977f}, -{0.284002f,-0.000618365f,0.120977f},{0.284043f,7.02945e-018f,0.120977f},{0.284001f,0.000618856f,0.120977f}, -{0.283878f,0.00122657f,0.120977f},{0.283676f,0.00181243f,0.120977f},{0.283397f,0.00236609f,0.120977f}, -{0.283048f,0.00287783f,0.120977f},{0.282634f,0.00333893f,0.120977f},{0.282161f,0.00374048f,0.120977f}, -{0.281639f,0.00407552f,0.120977f},{0.281079f,0.00433883f,0.120977f},{0.280488f,0.0045282f,0.120977f}, -{0.279878f,0.00463457f,0.120977f},{0.28049f,-0.00452954f,0.120977f},{0.281077f,-0.00433369f,0.120977f}, -{0.279878f,-0.00463457f,0.120977f},{0.293673f,-0.00708542f,0.120977f},{0.293069f,-0.00862355f,0.120977f}, -{0.293346f,-0.0081433f,0.120977f},{0.293548f,-0.00762768f,0.120977f},{0.291847f,-0.00975654f,0.120977f}, -{0.292719f,-0.00906182f,0.120977f},{0.292307f,-0.00944325f,0.120977f},{0.289704f,-0.0102431f,0.120977f}, -{0.290265f,-0.0102438f,0.120977f},{0.290819f,-0.0101602f,0.120977f},{0.288623f,-0.0099962f,0.120977f}, -{0.289153f,-0.0101597f,0.120977f},{0.287661f,-0.00944071f,0.120977f},{0.287251f,-0.00905963f,0.120977f}, -{0.288123f,-0.00975564f,0.120977f},{0.286903f,-0.00862291f,0.120977f},{0.286626f,-0.0081413f,0.120977f}, -{0.286423f,-0.00762524f,0.120977f},{0.2863f,-0.00708542f,0.120977f},{0.291348f,-0.00999655f,0.120977f}, -{0.29379f,-0.000388892f,0.120977f},{0.293213f,-0.0013863f,0.120977f},{0.29367f,-0.000758756f,0.120977f}, -{0.292161f,-0.00185425f,0.120977f},{0.292898f,-0.00161492f,0.120977f},{0.292542f,-0.0017734f,0.120977f}, -{0.291389f,-0.00177278f,0.120977f},{0.291034f,-0.0016145f,0.120977f},{0.291771f,-0.00185398f,0.120977f}, -{0.290718f,-0.00138471f,0.120977f},{0.290458f,-0.00109509f,0.120977f},{0.290263f,-0.000757801f,0.120977f}, -{0.290143f,-0.000387896f,0.120977f},{0.293474f,-0.00109643f,0.120977f},{0.294991f,-0.019053f,0.120977f}, -{0.294965f,-0.0184341f,0.120977f},{0.286569f,-0.0162251f,0.120977f},{0.294853f,-0.0178247f,0.120977f}, -{0.294936f,-0.0196708f,0.120977f},{0.294661f,-0.0172353f,0.120977f},{0.294392f,-0.0166765f,0.120977f}, -{0.293645f,-0.0156903f,0.120977f},{0.293181f,-0.0152802f,0.120977f},{0.294051f,-0.0161585f,0.120977f}, -{0.290913f,-0.0143468f,0.120977f},{0.290294f,-0.0143112f,0.120977f},{0.292666f,-0.0149353f,0.120977f}, -{0.292109f,-0.0146616f,0.120977f},{0.286967f,-0.0157495f,0.120977f},{0.287426f,-0.015333f,0.120977f}, -{0.289069f,-0.0144863f,0.120977f},{0.288486f,-0.0146944f,0.120977f},{0.287935f,-0.0149788f,0.120977f}, -{0.289676f,-0.014358f,0.120977f},{0.291521f,-0.0144643f,0.120977f},{0.294812f,-0.0202771f,0.120977f}, -{0.294597f,-0.0208597f,0.120977f},{0.303617f,-0.0101384f,0.120977f},{0.304647f,-0.0114304f,0.120977f}, -{0.304369f,-0.0109503f,0.120977f},{0.304024f,-0.0105172f,0.120977f},{0.305017f,-0.0130549f,0.120977f}, -{0.304852f,-0.011952f,0.120977f},{0.304976f,-0.0124996f,0.120977f},{0.304367f,-0.0151544f,0.120977f}, -{0.304648f,-0.0146689f,0.120977f},{0.304853f,-0.0141474f,0.120977f},{0.303613f,-0.0159666f,0.120977f}, -{0.304019f,-0.01559f,0.120977f},{0.302651f,-0.0165217f,0.120977f},{0.302116f,-0.0166864f,0.120977f}, -{0.303154f,-0.0162794f,0.120977f},{0.301564f,-0.0167695f,0.120977f},{0.301008f,-0.016769f,0.120977f}, -{0.300459f,-0.0166865f,0.120977f},{0.29993f,-0.0165233f,0.120977f},{0.304976f,-0.0136068f,0.120977f}, -{0.297876f,-0.00668858f,0.120977f},{0.298451f,-0.00768692f,0.120977f},{0.298136f,-0.00697763f,0.120977f}, -{0.29833f,-0.00883211f,0.120977f},{0.298492f,-0.00807384f,0.120977f},{0.298451f,-0.00846133f,0.120977f}, -{0.297874f,-0.00945929f,0.120977f},{0.297559f,-0.00968796f,0.120977f},{0.298135f,-0.00916975f,0.120977f}, -{0.297203f,-0.00984651f,0.120977f},{0.296822f,-0.00992734f,0.120977f},{0.296432f,-0.00992724f,0.120977f}, -{0.296052f,-0.00984636f,0.120977f},{0.298331f,-0.00731545f,0.120977f},{0.308931f,-0.0156909f,0.120977f}, -{0.308525f,-0.0161593f,0.120977f},{0.309396f,-0.0152805f,0.120977f},{0.309911f,-0.0149353f,0.120977f}, -{0.308185f,-0.0166773f,0.120977f},{0.307917f,-0.0172358f,0.120977f},{0.307724f,-0.0178252f,0.120977f}, -{0.310468f,-0.0146618f,0.120977f},{0.307613f,-0.0184349f,0.120977f},{0.307584f,-0.0190544f,0.120977f}, -{0.311055f,-0.0144645f,0.120977f},{0.307636f,-0.0196718f,0.120977f},{0.311664f,-0.0143468f,0.120977f}, -{0.312283f,-0.0143109f,0.120977f},{0.307767f,-0.0202777f,0.120977f},{0.30798f,-0.0208597f,0.120977f}, -{0.312901f,-0.0143575f,0.120977f},{0.314091f,-0.0146931f,0.120977f},{0.313507f,-0.0144856f,0.120977f}, -{0.31464f,-0.0149805f,0.120977f},{0.315148f,-0.0153371f,0.120977f},{0.315611f,-0.0157476f,0.120977f}, -{0.316008f,-0.0162251f,0.120977f},{0.311233f,-0.00305297f,0.120977f},{0.312867f,-0.00280688f,0.120977f}, -{0.312312f,-0.00280698f,0.120977f},{0.311764f,-0.00288948f,0.120977f},{0.314459f,-0.00329833f,0.120977f}, -{0.313421f,-0.00289017f,0.120977f},{0.313957f,-0.00305631f,0.120977f},{0.315952f,-0.00491125f,0.120977f}, -{0.315672f,-0.00442515f,0.120977f},{0.315323f,-0.00398713f,0.120977f},{0.316278f,-0.00597044f,0.120977f}, -{0.316155f,-0.00543021f,0.120977f},{0.316278f,-0.00708102f,0.120977f},{0.316153f,-0.00762679f,0.120977f}, -{0.31632f,-0.00652376f,0.120977f},{0.315949f,-0.0081466f,0.120977f},{0.315671f,-0.00862774f,0.120977f}, -{0.315325f,-0.00906124f,0.120977f},{0.314919f,-0.00943791f,0.120977f},{0.314916f,-0.00361021f,0.120977f}, -{0.305375f,-0.0062997f,0.120977f},{0.306527f,-0.00630037f,0.120977f},{0.305755f,-0.00621894f,0.120977f}, -{0.307458f,-0.0069779f,0.120977f},{0.306882f,-0.00645888f,0.120977f},{0.307198f,-0.0066883f,0.120977f}, -{0.307773f,-0.00768661f,0.120977f},{0.307814f,-0.00807365f,0.120977f},{0.307653f,-0.00731544f,0.120977f}, -{0.307773f,-0.00846171f,0.120977f},{0.307652f,-0.00883217f,0.120977f},{0.307458f,-0.00916947f,0.120977f}, -{0.307197f,-0.00945876f,0.120977f},{0.306145f,-0.00621907f,0.120977f},{0.305909f,-0.000612842f,0.126571f}, -{0.305327f,-0.00232777f,0.126571f},{0.30579f,-0.00120978f,0.126571f},{0.304122f,-0.00370055f,0.126571f}, -{0.303616f,-0.00403832f,0.126571f},{0.304584f,-0.00329584f,0.126571f},{0.301901f,-0.00462066f,0.126571f}, -{0.303072f,-0.00430621f,0.126571f},{0.302498f,-0.00450141f,0.126571f},{0.300079f,-0.00450127f,0.126571f}, -{0.301289f,-0.00466102f,0.126571f},{0.300676f,-0.00462052f,0.126571f},{0.298961f,-0.00403818f,0.126571f}, -{0.298454f,-0.00370041f,0.126571f},{0.299505f,-0.00430621f,0.126571f},{0.297993f,-0.00329584f,0.126571f}, -{0.297588f,-0.00283386f,0.126571f},{0.29725f,-0.00232743f,0.126571f},{0.296982f,-0.00178369f,0.126571f}, -{0.296787f,-0.00120944f,0.126571f},{0.296668f,-0.000612502f,0.126571f},{0.304989f,-0.0028342f,0.126571f}, -{0.305595f,-0.00178369f,0.126571f},{0.299891f,-0.00241971f,0.126571f},{0.298535f,-0.000484912f,0.126571f}, -{0.298867f,-0.00139723f,0.126571f},{0.299147f,-0.00179629f,0.126571f},{0.298661f,-0.000955369f,0.126571f}, -{0.299492f,-0.00214016f,0.126571f},{0.300332f,-0.00262702f,0.126571f},{0.300803f,-0.00275405f,0.126571f}, -{0.301289f,-0.00279661f,0.126571f},{0.302244f,-0.0026284f,0.126571f},{0.301774f,-0.00275426f,0.126571f}, -{0.302684f,-0.00241949f,0.126571f},{0.304044f,-0.000485989f,0.126571f},{0.303078f,-0.00213198f,0.126571f}, -{0.303917f,-0.000957231f,0.126571f},{0.303711f,-0.00139896f,0.126571f},{0.303432f,-0.0018009f,0.126571f}, -{0.298533f,-0.000485989f,0.134028f},{0.29866f,-0.000957231f,0.134028f},{0.298866f,-0.00139896f,0.134028f}, -{0.299145f,-0.0018009f,0.134028f},{0.299499f,-0.00213198f,0.134028f},{0.299894f,-0.00241949f,0.134028f}, -{0.300333f,-0.0026284f,0.134028f},{0.300803f,-0.00275426f,0.134028f},{0.301289f,-0.00279661f,0.134028f}, -{0.301774f,-0.00275405f,0.134028f},{0.303085f,-0.00214016f,0.134028f},{0.303916f,-0.000955369f,0.134028f}, -{0.302245f,-0.00262702f,0.134028f},{0.302686f,-0.00241971f,0.134028f},{0.30343f,-0.00179629f,0.134028f}, -{0.30371f,-0.00139723f,0.134028f},{0.304042f,-0.000484912f,0.134028f},{5.39634e-017f,-0.298492f,0.127503f}, -{5.05671e-017f,-0.298492f,0.13496f},{0.000488516f,-0.298535f,0.13496f},{0.000957717f,-0.298661f,0.13496f}, -{0.00048723f,-0.298535f,0.127503f},{0.000956449f,-0.298661f,0.127503f},{0.00139564f,-0.298865f,0.127503f}, -{0.00179504f,-0.299144f,0.127503f},{0.00139727f,-0.298866f,0.13496f},{0.00179767f,-0.299146f,0.13496f}, -{0.00214219f,-0.299491f,0.127503f},{0.00214411f,-0.299493f,0.13496f},{0.00242266f,-0.299891f,0.127503f}, -{0.00262748f,-0.300331f,0.127503f},{0.00242333f,-0.299893f,0.13496f},{0.00262801f,-0.300332f,0.13496f}, -{0.00275356f,-0.3008f,0.127503f},{0.00275356f,-0.3008f,0.13496f},{0.00279661f,-0.301289f,0.13496f}, -{0.00279661f,-0.301289f,0.127503f},{-0.000488516f,-0.298535f,0.127503f},{-0.000957717f,-0.298661f,0.127503f}, -{-0.00048723f,-0.298535f,0.13496f},{-0.00139564f,-0.298865f,0.13496f},{-0.000956449f,-0.298661f,0.13496f}, -{-0.00139727f,-0.298866f,0.127503f},{-0.00179504f,-0.299144f,0.13496f},{-0.00179767f,-0.299146f,0.127503f}, -{-0.00214219f,-0.299491f,0.13496f},{-0.00242266f,-0.299891f,0.13496f},{-0.00214411f,-0.299493f,0.127503f}, -{-0.00242333f,-0.299893f,0.127503f},{-0.00262748f,-0.300331f,0.13496f},{-0.00262801f,-0.300332f,0.127503f}, -{-0.00275356f,-0.3008f,0.13496f},{-0.00275356f,-0.3008f,0.127503f},{-0.00279661f,-0.301289f,0.127503f}, -{-0.00279661f,-0.301289f,0.13496f},{4.80219e-017f,-0.296628f,0.125638f},{5.09198e-017f,-0.296628f,0.127503f}, -{0.000612842f,-0.296668f,0.127503f},{0.00120978f,-0.296787f,0.127503f},{0.000612502f,-0.296668f,0.125638f}, -{0.00178369f,-0.296982f,0.127503f},{0.00120944f,-0.296787f,0.125638f},{0.00178369f,-0.296982f,0.125638f}, -{0.00232777f,-0.29725f,0.127503f},{0.0028342f,-0.297588f,0.127503f},{0.00232743f,-0.29725f,0.125638f}, -{0.00329584f,-0.297993f,0.127503f},{0.00283386f,-0.297588f,0.125638f},{0.00329584f,-0.297993f,0.125638f}, -{0.00370055f,-0.298455f,0.127503f},{0.00403832f,-0.298961f,0.127503f},{0.00370041f,-0.298454f,0.125638f}, -{0.00430621f,-0.299505f,0.127503f},{0.00403818f,-0.298961f,0.125638f},{0.00450127f,-0.300079f,0.125638f}, -{0.00430621f,-0.299505f,0.125638f},{0.00450141f,-0.300079f,0.127503f},{0.00462052f,-0.300676f,0.125638f}, -{0.00462066f,-0.300676f,0.127503f},{0.00466102f,-0.301289f,0.125638f},{0.00466102f,-0.301289f,0.127503f}, -{-0.000612842f,-0.296668f,0.125638f},{-0.00120978f,-0.296787f,0.125638f},{-0.000612502f,-0.296668f,0.127503f}, -{-0.00120944f,-0.296787f,0.127503f},{-0.00178369f,-0.296982f,0.125638f},{-0.00232777f,-0.29725f,0.125638f}, -{-0.00178369f,-0.296982f,0.127503f},{-0.0028342f,-0.297588f,0.125638f},{-0.00232743f,-0.29725f,0.127503f}, -{-0.00283386f,-0.297588f,0.127503f},{-0.00329584f,-0.297993f,0.125638f},{-0.00370055f,-0.298455f,0.125638f}, -{-0.00329584f,-0.297993f,0.127503f},{-0.00403832f,-0.298961f,0.125638f},{-0.00370041f,-0.298454f,0.127503f}, -{-0.00403818f,-0.298961f,0.127503f},{-0.00430621f,-0.299505f,0.125638f},{-0.00450127f,-0.300079f,0.127503f}, -{-0.00430621f,-0.299505f,0.127503f},{-0.00450141f,-0.300079f,0.125638f},{-0.00462052f,-0.300676f,0.127503f}, -{-0.00466102f,-0.301289f,0.127503f},{-0.00462066f,-0.300676f,0.125638f},{-0.00466102f,-0.301289f,0.125638f}, -{0.00295812f,-0.310121f,0.125638f},{0.00315337f,-0.310458f,0.125638f},{0.00315227f,-0.310457f,0.121909f}, -{0.00295749f,-0.310119f,0.121909f},{0.0028374f,-0.30975f,0.125638f},{0.00283721f,-0.309748f,0.121909f}, -{0.00279657f,-0.309361f,0.121909f},{0.00283728f,-0.308975f,0.125638f},{0.00279668f,-0.309362f,0.125638f}, -{0.0028377f,-0.308973f,0.121909f},{0.00295753f,-0.308604f,0.125638f},{0.00295825f,-0.308603f,0.121909f}, -{0.0031524f,-0.308266f,0.125638f},{0.00315303f,-0.308265f,0.121909f},{0.0034126f,-0.307977f,0.125638f}, -{0.0034133f,-0.307976f,0.121909f},{0.00372882f,-0.307747f,0.121909f},{0.00372882f,-0.307747f,0.125638f}, -{0.00341302f,-0.310747f,0.121909f},{0.00372824f,-0.310976f,0.121909f},{0.0034143f,-0.310748f,0.125638f}, -{0.00372908f,-0.310977f,0.125638f},{0.00408362f,-0.311134f,0.121909f},{0.00408596f,-0.311135f,0.125638f}, -{0.00446544f,-0.311216f,0.121909f},{0.00485544f,-0.311216f,0.121909f},{0.00446705f,-0.311216f,0.125638f}, -{0.00485646f,-0.311216f,0.125638f},{0.00523587f,-0.311135f,0.121909f},{0.00523689f,-0.311135f,0.125638f}, -{0.00559323f,-0.310976f,0.121909f},{0.00559323f,-0.310976f,0.125638f},{0.00794301f,-0.309432f,0.125638f}, -{0.00822403f,-0.309917f,0.125638f},{0.00822143f,-0.309914f,0.121909f},{0.00773834f,-0.30891f,0.125638f}, -{0.00794151f,-0.309428f,0.121909f},{0.00773817f,-0.308909f,0.121909f},{0.00761523f,-0.30837f,0.125638f}, -{0.00761511f,-0.308369f,0.121909f},{0.00757342f,-0.307816f,0.121909f},{0.00757373f,-0.307818f,0.125638f}, -{0.00761488f,-0.307263f,0.125638f},{0.00794445f,-0.306193f,0.121909f},{0.00822146f,-0.305713f,0.125638f}, -{0.00794412f,-0.306194f,0.125638f},{0.00761534f,-0.307258f,0.121909f},{0.00773918f,-0.306715f,0.125638f}, -{0.00774028f,-0.306713f,0.121909f},{0.00822277f,-0.305712f,0.121909f},{0.00856678f,-0.30528f,0.125638f}, -{0.00856839f,-0.305278f,0.121909f},{0.00897424f,-0.304902f,0.121909f},{0.00943797f,-0.304585f,0.125638f}, -{0.00897424f,-0.304902f,0.125638f},{0.00943797f,-0.304585f,0.121909f},{0.00857075f,-0.310352f,0.121909f}, -{0.00897738f,-0.310729f,0.121909f},{0.00857178f,-0.310353f,0.125638f},{0.00897811f,-0.31073f,0.125638f}, -{0.00943459f,-0.311041f,0.121909f},{0.00943645f,-0.311043f,0.125638f},{0.00993607f,-0.311283f,0.121909f}, -{0.0104724f,-0.311449f,0.121909f},{0.00994001f,-0.311285f,0.125638f},{0.0104751f,-0.31145f,0.125638f}, -{0.0110266f,-0.311533f,0.121909f},{0.0110274f,-0.311533f,0.125638f},{0.0115811f,-0.311532f,0.121909f}, -{0.0121288f,-0.31145f,0.121909f},{0.0115832f,-0.311532f,0.125638f},{0.0121315f,-0.31145f,0.125638f}, -{0.0126606f,-0.311286f,0.121909f},{0.0126606f,-0.311286f,0.125638f},{0.0131668f,-0.311043f,0.121909f}, -{0.0131668f,-0.311043f,0.125638f},{-0.00616977f,-0.308266f,0.125638f},{-0.00636455f,-0.308604f,0.125638f}, -{-0.00636392f,-0.308603f,0.121909f},{-0.00616867f,-0.308265f,0.121909f},{-0.00590902f,-0.307976f,0.125638f}, -{-0.00590775f,-0.307976f,0.121909f},{-0.00559297f,-0.307747f,0.121909f},{-0.00523843f,-0.307589f,0.125638f}, -{-0.00559381f,-0.307747f,0.125638f},{-0.00523609f,-0.307588f,0.121909f},{-0.00485661f,-0.307508f,0.125638f}, -{-0.00485499f,-0.307507f,0.121909f},{-0.0044666f,-0.307507f,0.125638f},{-0.00446558f,-0.307508f,0.121909f}, -{-0.00408618f,-0.307588f,0.125638f},{-0.00408515f,-0.307588f,0.121909f},{-0.00372882f,-0.307747f,0.121909f}, -{-0.00372882f,-0.307747f,0.125638f},{-0.00648464f,-0.308973f,0.121909f},{-0.00652537f,-0.309361f,0.121909f}, -{-0.00648484f,-0.308975f,0.125638f},{-0.00652548f,-0.309362f,0.125638f},{-0.00648477f,-0.309748f,0.121909f}, -{-0.00648435f,-0.30975f,0.125638f},{-0.00636452f,-0.310119f,0.121909f},{-0.00616965f,-0.310457f,0.121909f}, -{-0.0063638f,-0.310121f,0.125638f},{-0.00616901f,-0.310458f,0.125638f},{-0.00590945f,-0.310746f,0.121909f}, -{-0.00590875f,-0.310747f,0.125638f},{-0.00559323f,-0.310976f,0.121909f},{-0.00559323f,-0.310976f,0.125638f}, -{-0.00308095f,-0.312239f,0.125638f},{-0.00336087f,-0.312725f,0.125638f},{-0.00335937f,-0.312721f,0.121909f}, -{-0.00273163f,-0.311801f,0.125638f},{-0.00307835f,-0.312236f,0.121909f},{-0.0027306f,-0.3118f,0.121909f}, -{-0.002325f,-0.311424f,0.125638f},{-0.00232427f,-0.311424f,0.121909f},{-0.00186593f,-0.311111f,0.121909f}, -{-0.00186779f,-0.311112f,0.125638f},{-0.00136631f,-0.31087f,0.125638f},{-0.000274996f,-0.310621f,0.121909f}, -{0.0002787f,-0.310621f,0.125638f},{-0.000275788f,-0.310621f,0.125638f},{-0.00136237f,-0.310869f,0.121909f}, -{-0.000829945f,-0.310704f,0.125638f},{-0.000827251f,-0.310704f,0.121909f},{0.000280844f,-0.310621f,0.121909f}, -{0.000826454f,-0.310703f,0.125638f},{0.000829073f,-0.310704f,0.121909f},{0.00135821f,-0.310867f,0.121909f}, -{0.00186441f,-0.31111f,0.125638f},{0.00135821f,-0.310867f,0.125638f},{0.00186441f,-0.31111f,0.121909f}, -{-0.00356405f,-0.313243f,0.121909f},{-0.00368715f,-0.313783f,0.121909f},{-0.00356421f,-0.313244f,0.125638f}, -{-0.00368727f,-0.313784f,0.125638f},{-0.00372865f,-0.314335f,0.121909f},{-0.00372896f,-0.314338f,0.125638f}, -{-0.00368751f,-0.314891f,0.121909f},{-0.0035632f,-0.315438f,0.121909f},{-0.00368704f,-0.314895f,0.125638f}, -{-0.0035621f,-0.315441f,0.125638f},{-0.00335826f,-0.31596f,0.121909f},{-0.00335794f,-0.315961f,0.125638f}, -{-0.00308092f,-0.31644f,0.121909f},{-0.0027356f,-0.316873f,0.121909f},{-0.00307961f,-0.316442f,0.125638f}, -{-0.00273399f,-0.316875f,0.125638f},{-0.00232814f,-0.317252f,0.121909f},{-0.00232814f,-0.317252f,0.125638f}, -{-0.00186441f,-0.317569f,0.121909f},{-0.00186441f,-0.317569f,0.125638f},{-0.0091279f,-0.299434f,0.125638f}, -{-0.00951793f,-0.299435f,0.125638f},{-0.0095162f,-0.299434f,0.121909f},{-0.00912617f,-0.299435f,0.121909f}, -{-0.00874642f,-0.299515f,0.125638f},{-0.00874495f,-0.299516f,0.121909f},{-0.00838954f,-0.299674f,0.121909f}, -{-0.0080757f,-0.299902f,0.125638f},{-0.00839049f,-0.299674f,0.125638f},{-0.00807379f,-0.299904f,0.121909f}, -{-0.00781413f,-0.300192f,0.125638f},{-0.00781324f,-0.300193f,0.121909f},{-0.007619f,-0.30053f,0.125638f}, -{-0.00761862f,-0.300531f,0.121909f},{-0.00749878f,-0.3009f,0.125638f},{-0.00749845f,-0.300901f,0.121909f}, -{-0.00745764f,-0.301289f,0.121909f},{-0.00745764f,-0.301289f,0.125638f},{-0.00989767f,-0.299515f,0.121909f}, -{-0.0102536f,-0.299674f,0.121909f},{-0.00989914f,-0.299516f,0.125638f},{-0.0102546f,-0.299674f,0.125638f}, -{-0.0105684f,-0.299902f,0.121909f},{-0.0105703f,-0.299904f,0.125638f},{-0.01083f,-0.300192f,0.121909f}, -{-0.0110251f,-0.30053f,0.121909f},{-0.0108309f,-0.300193f,0.125638f},{-0.0110255f,-0.300531f,0.125638f}, -{-0.0111453f,-0.3009f,0.121909f},{-0.0111456f,-0.300901f,0.125638f},{-0.0111865f,-0.301289f,0.121909f}, -{-0.0111865f,-0.301289f,0.125638f},{-0.011024f,-0.304096f,0.125638f},{-0.0115849f,-0.304096f,0.125638f}, -{-0.0115808f,-0.304096f,0.121909f},{-0.01047f,-0.304179f,0.125638f},{-0.0110199f,-0.304096f,0.121909f}, -{-0.0104688f,-0.30418f,0.121909f},{-0.00994023f,-0.304343f,0.125638f},{-0.00993938f,-0.304343f,0.121909f}, -{-0.00943935f,-0.304584f,0.121909f},{-0.00944153f,-0.304583f,0.125638f},{-0.00898119f,-0.304896f,0.125638f}, -{-0.00821944f,-0.305716f,0.121909f},{-0.00794276f,-0.306196f,0.125638f},{-0.00821991f,-0.305716f,0.125638f}, -{-0.00897771f,-0.304899f,0.121909f},{-0.00856913f,-0.305278f,0.125638f},{-0.00856753f,-0.30528f,0.121909f}, -{-0.00794193f,-0.306198f,0.121909f},{-0.00774033f,-0.306712f,0.125638f},{-0.00773931f,-0.306714f,0.121909f}, -{-0.00761603f,-0.307254f,0.121909f},{-0.00757356f,-0.307814f,0.125638f},{-0.00761603f,-0.307254f,0.125638f}, -{-0.00757356f,-0.307814f,0.121909f},{-0.0121348f,-0.304179f,0.121909f},{-0.0126645f,-0.304343f,0.121909f}, -{-0.012136f,-0.30418f,0.125638f},{-0.0126654f,-0.304343f,0.125638f},{-0.0131632f,-0.304583f,0.121909f}, -{-0.0131654f,-0.304584f,0.125638f},{-0.0136236f,-0.304896f,0.121909f},{-0.0140356f,-0.305278f,0.121909f}, -{-0.0136271f,-0.304899f,0.125638f},{-0.0140372f,-0.30528f,0.125638f},{-0.0143849f,-0.305716f,0.121909f}, -{-0.0143853f,-0.305716f,0.125638f},{-0.014662f,-0.306196f,0.121909f},{-0.0148644f,-0.306712f,0.121909f}, -{-0.0146628f,-0.306198f,0.125638f},{-0.0148654f,-0.306714f,0.125638f},{-0.0149887f,-0.307254f,0.121909f}, -{-0.0149887f,-0.307254f,0.125638f},{-0.0150312f,-0.307814f,0.121909f},{-0.0150312f,-0.307814f,0.125638f}, -{-0.00295812f,-0.292456f,0.125638f},{-0.00315337f,-0.292119f,0.125638f},{-0.00315227f,-0.29212f,0.121909f}, -{-0.00295749f,-0.292458f,0.121909f},{-0.0028374f,-0.292827f,0.125638f},{-0.00283721f,-0.292829f,0.121909f}, -{-0.00279657f,-0.293216f,0.121909f},{-0.00283728f,-0.293602f,0.125638f},{-0.00279668f,-0.293215f,0.125638f}, -{-0.0028377f,-0.293604f,0.121909f},{-0.00295753f,-0.293973f,0.125638f},{-0.00295825f,-0.293975f,0.121909f}, -{-0.0031524f,-0.294311f,0.125638f},{-0.00315303f,-0.294312f,0.121909f},{-0.0034126f,-0.2946f,0.125638f}, -{-0.0034133f,-0.294601f,0.121909f},{-0.00372882f,-0.29483f,0.121909f},{-0.00372882f,-0.29483f,0.125638f}, -{-0.00341302f,-0.29183f,0.121909f},{-0.00372824f,-0.291601f,0.121909f},{-0.0034143f,-0.291829f,0.125638f}, -{-0.00372908f,-0.291601f,0.125638f},{-0.00408362f,-0.291443f,0.121909f},{-0.00408596f,-0.291442f,0.125638f}, -{-0.00446544f,-0.291361f,0.121909f},{-0.00485544f,-0.291361f,0.121909f},{-0.00446705f,-0.291361f,0.125638f}, -{-0.00485646f,-0.291361f,0.125638f},{-0.00523587f,-0.291442f,0.121909f},{-0.00523689f,-0.291442f,0.125638f}, -{-0.00559323f,-0.291601f,0.121909f},{-0.00559323f,-0.291601f,0.125638f},{-0.00794301f,-0.293145f,0.125638f}, -{-0.00822403f,-0.29266f,0.125638f},{-0.00822143f,-0.292663f,0.121909f},{-0.00773834f,-0.293667f,0.125638f}, -{-0.00794151f,-0.293149f,0.121909f},{-0.00773817f,-0.293668f,0.121909f},{-0.00761523f,-0.294207f,0.125638f}, -{-0.00761511f,-0.294208f,0.121909f},{-0.00757342f,-0.294761f,0.121909f},{-0.00757373f,-0.294759f,0.125638f}, -{-0.00761488f,-0.295314f,0.125638f},{-0.00794445f,-0.296384f,0.121909f},{-0.00822146f,-0.296864f,0.125638f}, -{-0.00794412f,-0.296384f,0.125638f},{-0.00761534f,-0.295319f,0.121909f},{-0.00773918f,-0.295862f,0.125638f}, -{-0.00774028f,-0.295864f,0.121909f},{-0.00822277f,-0.296865f,0.121909f},{-0.00856678f,-0.297297f,0.125638f}, -{-0.00856839f,-0.297299f,0.121909f},{-0.00897424f,-0.297676f,0.121909f},{-0.00943797f,-0.297992f,0.125638f}, -{-0.00897424f,-0.297676f,0.125638f},{-0.00943797f,-0.297992f,0.121909f},{-0.00857075f,-0.292225f,0.121909f}, -{-0.00897738f,-0.291848f,0.121909f},{-0.00857178f,-0.292224f,0.125638f},{-0.00897811f,-0.291847f,0.125638f}, -{-0.00943459f,-0.291536f,0.121909f},{-0.00943645f,-0.291535f,0.125638f},{-0.00993607f,-0.291294f,0.121909f}, -{-0.0104724f,-0.291128f,0.121909f},{-0.00994001f,-0.291292f,0.125638f},{-0.0104751f,-0.291128f,0.125638f}, -{-0.0110266f,-0.291045f,0.121909f},{-0.0110274f,-0.291044f,0.125638f},{-0.0115811f,-0.291045f,0.121909f}, -{-0.0121288f,-0.291127f,0.121909f},{-0.0115832f,-0.291045f,0.125638f},{-0.0121315f,-0.291128f,0.125638f}, -{-0.0126606f,-0.291291f,0.121909f},{-0.0126606f,-0.291291f,0.125638f},{-0.0131668f,-0.291534f,0.121909f}, -{-0.0131668f,-0.291534f,0.125638f},{0.00616977f,-0.294311f,0.125638f},{0.00636455f,-0.293973f,0.125638f}, -{0.00636392f,-0.293974f,0.121909f},{0.00616867f,-0.294312f,0.121909f},{0.00590902f,-0.294601f,0.125638f}, -{0.00590775f,-0.294602f,0.121909f},{0.00559297f,-0.29483f,0.121909f},{0.00523843f,-0.294988f,0.125638f}, -{0.00559381f,-0.29483f,0.125638f},{0.00523609f,-0.294989f,0.121909f},{0.00485661f,-0.29507f,0.125638f}, -{0.00485499f,-0.29507f,0.121909f},{0.0044666f,-0.29507f,0.125638f},{0.00446558f,-0.29507f,0.121909f}, -{0.00408618f,-0.294989f,0.125638f},{0.00408515f,-0.294989f,0.121909f},{0.00372882f,-0.29483f,0.121909f}, -{0.00372882f,-0.29483f,0.125638f},{0.00648464f,-0.293604f,0.121909f},{0.00652537f,-0.293216f,0.121909f}, -{0.00648484f,-0.293602f,0.125638f},{0.00652548f,-0.293215f,0.125638f},{0.00648477f,-0.292829f,0.121909f}, -{0.00648435f,-0.292827f,0.125638f},{0.00636452f,-0.292458f,0.121909f},{0.00616965f,-0.29212f,0.121909f}, -{0.0063638f,-0.292456f,0.125638f},{0.00616901f,-0.292119f,0.125638f},{0.00590945f,-0.291831f,0.121909f}, -{0.00590875f,-0.29183f,0.125638f},{0.00559323f,-0.291601f,0.121909f},{0.00559323f,-0.291601f,0.125638f}, -{0.00308095f,-0.290338f,0.125638f},{0.00336087f,-0.289852f,0.125638f},{0.00335937f,-0.289856f,0.121909f}, -{0.00273163f,-0.290776f,0.125638f},{0.00307835f,-0.290341f,0.121909f},{0.0027306f,-0.290777f,0.121909f}, -{0.002325f,-0.291153f,0.125638f},{0.00232427f,-0.291153f,0.121909f},{0.00186593f,-0.291466f,0.121909f}, -{0.00186779f,-0.291465f,0.125638f},{0.00136631f,-0.291707f,0.125638f},{0.000274996f,-0.291956f,0.121909f}, -{-0.0002787f,-0.291956f,0.125638f},{0.000275788f,-0.291956f,0.125638f},{0.00136237f,-0.291709f,0.121909f}, -{0.000829945f,-0.291873f,0.125638f},{0.000827251f,-0.291873f,0.121909f},{-0.000280844f,-0.291956f,0.121909f}, -{-0.000826454f,-0.291874f,0.125638f},{-0.000829073f,-0.291873f,0.121909f},{-0.00135821f,-0.29171f,0.121909f}, -{-0.00186441f,-0.291467f,0.125638f},{-0.00135821f,-0.29171f,0.125638f},{-0.00186441f,-0.291467f,0.121909f}, -{0.00356405f,-0.289334f,0.121909f},{0.00368715f,-0.288794f,0.121909f},{0.00356421f,-0.289333f,0.125638f}, -{0.00368727f,-0.288793f,0.125638f},{0.00372865f,-0.288242f,0.121909f},{0.00372896f,-0.288239f,0.125638f}, -{0.00368751f,-0.287686f,0.121909f},{0.0035632f,-0.287139f,0.121909f},{0.00368704f,-0.287682f,0.125638f}, -{0.0035621f,-0.287136f,0.125638f},{0.00335826f,-0.286617f,0.121909f},{0.00335794f,-0.286617f,0.125638f}, -{0.00308092f,-0.286137f,0.121909f},{0.0027356f,-0.285704f,0.121909f},{0.00307961f,-0.286135f,0.125638f}, -{0.00273399f,-0.285702f,0.125638f},{0.00232814f,-0.285325f,0.121909f},{0.00232814f,-0.285325f,0.125638f}, -{0.00186441f,-0.285008f,0.121909f},{0.00186441f,-0.285008f,0.125638f},{0.0091279f,-0.303143f,0.125638f}, -{0.00951793f,-0.303143f,0.125638f},{0.0095162f,-0.303143f,0.121909f},{0.00912617f,-0.303143f,0.121909f}, -{0.00874642f,-0.303062f,0.125638f},{0.00874495f,-0.303061f,0.121909f},{0.00838954f,-0.302903f,0.121909f}, -{0.0080757f,-0.302675f,0.125638f},{0.00839049f,-0.302903f,0.125638f},{0.00807379f,-0.302673f,0.121909f}, -{0.00781413f,-0.302385f,0.125638f},{0.00781324f,-0.302384f,0.121909f},{0.007619f,-0.302047f,0.125638f}, -{0.00761862f,-0.302046f,0.121909f},{0.00749878f,-0.301677f,0.125638f},{0.00749845f,-0.301676f,0.121909f}, -{0.00745764f,-0.301289f,0.121909f},{0.00745764f,-0.301289f,0.125638f},{0.00989767f,-0.303062f,0.121909f}, -{0.0102536f,-0.302903f,0.121909f},{0.00989914f,-0.303061f,0.125638f},{0.0102546f,-0.302903f,0.125638f}, -{0.0105684f,-0.302675f,0.121909f},{0.0105703f,-0.302673f,0.125638f},{0.01083f,-0.302385f,0.121909f}, -{0.0110251f,-0.302047f,0.121909f},{0.0108309f,-0.302384f,0.125638f},{0.0110255f,-0.302046f,0.125638f}, -{0.0111453f,-0.301677f,0.121909f},{0.0111456f,-0.301676f,0.125638f},{0.0111865f,-0.301289f,0.121909f}, -{0.0111865f,-0.301289f,0.125638f},{0.011024f,-0.298481f,0.125638f},{0.0115849f,-0.298481f,0.125638f}, -{0.0115808f,-0.298481f,0.121909f},{0.01047f,-0.298398f,0.125638f},{0.0110199f,-0.298481f,0.121909f}, -{0.0104688f,-0.298397f,0.121909f},{0.00994023f,-0.298234f,0.125638f},{0.00993938f,-0.298234f,0.121909f}, -{0.00943935f,-0.297993f,0.121909f},{0.00944153f,-0.297994f,0.125638f},{0.00898119f,-0.297681f,0.125638f}, -{0.00821944f,-0.296861f,0.121909f},{0.00794276f,-0.296381f,0.125638f},{0.00821991f,-0.296861f,0.125638f}, -{0.00897771f,-0.297678f,0.121909f},{0.00856913f,-0.297299f,0.125638f},{0.00856753f,-0.297297f,0.121909f}, -{0.00794193f,-0.296379f,0.121909f},{0.00774033f,-0.295865f,0.125638f},{0.00773931f,-0.295863f,0.121909f}, -{0.00761603f,-0.295323f,0.121909f},{0.00757356f,-0.294763f,0.125638f},{0.00761603f,-0.295323f,0.125638f}, -{0.00757356f,-0.294763f,0.121909f},{0.0121348f,-0.298398f,0.121909f},{0.0126645f,-0.298234f,0.121909f}, -{0.012136f,-0.298397f,0.125638f},{0.0126654f,-0.298234f,0.125638f},{0.0131632f,-0.297994f,0.121909f}, -{0.0131654f,-0.297993f,0.125638f},{0.0136236f,-0.297681f,0.121909f},{0.0140356f,-0.297299f,0.121909f}, -{0.0136271f,-0.297678f,0.125638f},{0.0140372f,-0.297297f,0.125638f},{0.0143849f,-0.296861f,0.121909f}, -{0.0143853f,-0.296861f,0.125638f},{0.014662f,-0.296381f,0.121909f},{0.0148644f,-0.295865f,0.121909f}, -{0.0146628f,-0.296379f,0.125638f},{0.0148654f,-0.295863f,0.125638f},{0.0149887f,-0.295323f,0.121909f}, -{0.0149887f,-0.295323f,0.125638f},{0.0150312f,-0.294763f,0.121909f},{0.0150312f,-0.294763f,0.125638f}, -{5.2016e-017f,-0.298492f,0.100469f},{5.25144e-017f,-0.298492f,0.0986044f},{-0.000488516f,-0.298535f,0.0986044f}, -{-0.000957717f,-0.298661f,0.0986044f},{-0.00048723f,-0.298535f,0.100469f},{-0.000956449f,-0.298661f,0.100469f}, -{-0.00139564f,-0.298865f,0.100469f},{-0.00179504f,-0.299144f,0.100469f},{-0.00139727f,-0.298866f,0.0986044f}, -{-0.00179767f,-0.299146f,0.0986044f},{-0.00214219f,-0.299491f,0.100469f},{-0.00214411f,-0.299493f,0.0986044f}, -{-0.00242266f,-0.299891f,0.100469f},{-0.00262748f,-0.300331f,0.100469f},{-0.00242333f,-0.299893f,0.0986044f}, -{-0.00262801f,-0.300332f,0.0986044f},{-0.00275356f,-0.3008f,0.100469f},{-0.00275356f,-0.3008f,0.0986044f}, -{-0.00279661f,-0.301289f,0.0986044f},{-0.00279661f,-0.301289f,0.100469f},{0.000488516f,-0.298535f,0.100469f}, -{0.000957717f,-0.298661f,0.100469f},{0.00048723f,-0.298535f,0.0986044f},{0.00139564f,-0.298865f,0.0986044f}, -{0.000956449f,-0.298661f,0.0986044f},{0.00139727f,-0.298866f,0.100469f},{0.00179504f,-0.299144f,0.0986044f}, -{0.00179767f,-0.299146f,0.100469f},{0.00214219f,-0.299491f,0.0986044f},{0.00242266f,-0.299891f,0.0986044f}, -{0.00214411f,-0.299493f,0.100469f},{0.00242333f,-0.299893f,0.100469f},{0.00262748f,-0.300331f,0.0986044f}, -{0.00262801f,-0.300332f,0.100469f},{0.00275356f,-0.3008f,0.0986044f},{0.00275356f,-0.3008f,0.100469f}, -{0.00279661f,-0.301289f,0.100469f},{0.00279661f,-0.301289f,0.0986044f},{4.88499e-017f,-0.293831f,0.100469f}, -{-0.000737081f,-0.293867f,0.100469f},{5.13338e-017f,-0.293831f,0.101401f},{-0.000737081f,-0.293867f,0.101401f}, -{-0.00146169f,-0.293976f,0.100469f},{-0.00216893f,-0.294153f,0.100469f},{-0.00146169f,-0.293976f,0.101401f}, -{-0.00285391f,-0.294399f,0.100469f},{-0.00216893f,-0.294153f,0.101401f},{-0.00285391f,-0.294399f,0.101401f}, -{-0.00351173f,-0.294709f,0.100469f},{-0.00413751f,-0.295084f,0.100469f},{-0.00351173f,-0.294709f,0.101401f}, -{-0.00472635f,-0.29552f,0.100469f},{-0.00413751f,-0.295084f,0.101401f},{-0.00472635f,-0.29552f,0.101401f}, -{-0.00527335f,-0.296015f,0.100469f},{-0.00576874f,-0.296562f,0.100469f},{-0.00527335f,-0.296015f,0.101401f}, -{-0.00620465f,-0.297151f,0.100469f},{-0.00576874f,-0.296562f,0.101401f},{-0.00620465f,-0.297151f,0.101401f}, -{-0.00657906f,-0.297777f,0.100469f},{-0.00688994f,-0.298435f,0.100469f},{-0.00657906f,-0.297777f,0.101401f}, -{-0.00713527f,-0.29912f,0.100469f},{-0.00688994f,-0.298435f,0.101401f},{-0.00713527f,-0.29912f,0.101401f}, -{-0.00731301f,-0.299827f,0.100469f},{-0.00742114f,-0.300551f,0.100469f},{-0.00731301f,-0.299827f,0.101401f}, -{-0.00745764f,-0.301289f,0.100469f},{-0.00742114f,-0.300551f,0.101401f},{-0.00745764f,-0.301289f,0.101401f}, -{0.000737081f,-0.293867f,0.101401f},{0.00146169f,-0.293976f,0.101401f},{0.000737081f,-0.293867f,0.100469f}, -{0.00216893f,-0.294153f,0.101401f},{0.00146169f,-0.293976f,0.100469f},{0.00216893f,-0.294153f,0.100469f}, -{0.00285391f,-0.294399f,0.101401f},{0.00351173f,-0.294709f,0.101401f},{0.00285391f,-0.294399f,0.100469f}, -{0.00413751f,-0.295084f,0.101401f},{0.00351173f,-0.294709f,0.100469f},{0.00413751f,-0.295084f,0.100469f}, -{0.00472635f,-0.29552f,0.101401f},{0.00527335f,-0.296015f,0.101401f},{0.00472635f,-0.29552f,0.100469f}, -{0.00576874f,-0.296562f,0.101401f},{0.00527335f,-0.296015f,0.100469f},{0.00576874f,-0.296562f,0.100469f}, -{0.00620465f,-0.297151f,0.101401f},{0.00657906f,-0.297777f,0.101401f},{0.00620465f,-0.297151f,0.100469f}, -{0.00688994f,-0.298435f,0.101401f},{0.00657906f,-0.297777f,0.100469f},{0.00688994f,-0.298435f,0.100469f}, -{0.00713527f,-0.29912f,0.101401f},{0.00731301f,-0.299827f,0.101401f},{0.00713527f,-0.29912f,0.100469f}, -{0.00742114f,-0.300551f,0.101401f},{0.00731301f,-0.299827f,0.100469f},{0.00742114f,-0.300551f,0.100469f}, -{0.00745764f,-0.301289f,0.101401f},{0.00745764f,-0.301289f,0.100469f},{-0.00462052f,-0.283896f,0.101401f}, -{-0.00462066f,-0.283896f,0.104198f},{-0.00466102f,-0.284509f,0.101401f},{-0.00462052f,-0.285122f,0.104198f}, -{-0.00462066f,-0.285121f,0.101401f},{-0.00466102f,-0.284509f,0.104198f},{-0.00430621f,-0.286293f,0.101401f}, -{-0.00430621f,-0.286293f,0.104198f},{-0.00403832f,-0.286836f,0.101401f},{-0.00450127f,-0.285719f,0.104198f}, -{-0.00450141f,-0.285718f,0.101401f},{-0.00403818f,-0.286837f,0.104198f},{-0.00370041f,-0.287343f,0.104198f}, -{-0.00370055f,-0.287343f,0.101401f},{-0.00329584f,-0.287805f,0.101401f},{-0.00329584f,-0.287805f,0.104198f}, -{-0.00283386f,-0.288209f,0.104198f},{-0.0028342f,-0.288209f,0.101401f},{-0.00232777f,-0.288547f,0.101401f}, -{-0.00232743f,-0.288547f,0.104198f},{-0.00178369f,-0.288815f,0.101401f},{-0.00178369f,-0.288815f,0.104198f}, -{-0.00120944f,-0.28901f,0.104198f},{-0.00120978f,-0.28901f,0.101401f},{5.69282e-017f,-0.28917f,0.101401f}, -{-0.000612842f,-0.289129f,0.101401f},{-0.000612502f,-0.28913f,0.104198f},{5.69282e-017f,-0.28917f,0.104198f}, -{-0.00450141f,-0.283299f,0.104198f},{-0.00450127f,-0.283299f,0.101401f},{-0.00430621f,-0.282725f,0.104198f}, -{-0.00403832f,-0.282181f,0.104198f},{-0.00430621f,-0.282725f,0.101401f},{-0.00403818f,-0.282181f,0.101401f}, -{-0.00370055f,-0.281675f,0.104198f},{-0.00370041f,-0.281675f,0.101401f},{-0.00329584f,-0.281213f,0.104198f}, -{-0.0028342f,-0.280808f,0.104198f},{-0.00329584f,-0.281213f,0.101401f},{-0.00283386f,-0.280808f,0.101401f}, -{-0.00232777f,-0.280471f,0.104198f},{-0.00232743f,-0.280471f,0.101401f},{-0.00178369f,-0.280203f,0.104198f}, -{-0.00120978f,-0.280008f,0.104198f},{-0.00178369f,-0.280203f,0.101401f},{-0.00120944f,-0.280007f,0.101401f}, -{-0.000612842f,-0.279888f,0.104198f},{-0.000612502f,-0.279888f,0.101401f},{5.57866e-017f,-0.279848f,0.104198f}, -{5.57866e-017f,-0.279848f,0.101401f},{0.0173922f,-0.296668f,0.101401f},{0.0167797f,-0.296628f,0.101401f}, -{0.0173922f,-0.296668f,0.104198f},{0.0161668f,-0.296668f,0.104198f},{0.0167797f,-0.296628f,0.104198f}, -{0.0161668f,-0.296668f,0.101401f},{0.014996f,-0.296982f,0.101401f},{0.0144519f,-0.29725f,0.101401f}, -{0.014996f,-0.296982f,0.104198f},{0.0155699f,-0.296787f,0.104198f},{0.0155699f,-0.296787f,0.101401f}, -{0.0144519f,-0.29725f,0.104198f},{0.0139455f,-0.297588f,0.101401f},{0.0139455f,-0.297588f,0.104198f}, -{0.0134838f,-0.297993f,0.101401f},{0.0134838f,-0.297993f,0.104198f},{0.0130791f,-0.298455f,0.101401f}, -{0.0130791f,-0.298455f,0.104198f},{0.0127414f,-0.298961f,0.101401f},{0.0124735f,-0.299505f,0.101401f}, -{0.0127414f,-0.298961f,0.104198f},{0.0124735f,-0.299505f,0.104198f},{0.0122783f,-0.300079f,0.101401f}, -{0.0122783f,-0.300079f,0.104198f},{0.0121187f,-0.301289f,0.101401f},{0.012159f,-0.300676f,0.104198f}, -{0.012159f,-0.300676f,0.101401f},{0.0121187f,-0.301289f,0.104198f},{0.0179891f,-0.296787f,0.104198f}, -{0.0185634f,-0.296982f,0.104198f},{0.0179891f,-0.296787f,0.101401f},{0.0191071f,-0.29725f,0.104198f}, -{0.0185634f,-0.296982f,0.101401f},{0.0191071f,-0.29725f,0.101401f},{0.0196135f,-0.297588f,0.104198f}, -{0.0200755f,-0.297993f,0.104198f},{0.0196135f,-0.297588f,0.101401f},{0.0204801f,-0.298454f,0.104198f}, -{0.0200755f,-0.297993f,0.101401f},{0.0204801f,-0.298454f,0.101401f},{0.0208179f,-0.298961f,0.104198f}, -{0.0210859f,-0.299505f,0.104198f},{0.0208179f,-0.298961f,0.101401f},{0.0212809f,-0.300079f,0.104198f}, -{0.0210859f,-0.299505f,0.101401f},{0.0212809f,-0.300079f,0.101401f},{0.0214002f,-0.300676f,0.104198f}, -{0.0214407f,-0.301289f,0.104198f},{0.0214002f,-0.300676f,0.101401f},{0.0214407f,-0.301289f,0.101401f}, -{0.00462066f,-0.318681f,0.104198f},{0.00466102f,-0.318068f,0.104198f},{0.00464709f,-0.318428f,0.101401f}, -{0.00458867f,-0.317251f,0.101401f},{0.00465528f,-0.317837f,0.101401f},{0.00462052f,-0.317455f,0.104198f}, -{0.00430621f,-0.316285f,0.104198f},{0.00403818f,-0.31574f,0.104198f},{0.00423671f,-0.316126f,0.101401f}, -{0.00444837f,-0.316677f,0.101401f},{0.00450127f,-0.316858f,0.104198f},{0.00370041f,-0.315234f,0.104198f}, -{0.00361392f,-0.315125f,0.101401f},{0.00395712f,-0.315606f,0.101401f},{0.00329584f,-0.314772f,0.104198f}, -{0.00283386f,-0.314368f,0.104198f},{0.00276013f,-0.314313f,0.101401f},{0.00321274f,-0.314692f,0.101401f}, -{0.00232743f,-0.31403f,0.104198f},{0.00178369f,-0.313762f,0.104198f},{0.00226347f,-0.313993f,0.101401f}, -{0.00120944f,-0.313567f,0.104198f},{0.00116855f,-0.313559f,0.101401f},{0.00172931f,-0.313743f,0.101401f}, -{0.000589403f,-0.313444f,0.101401f},{0.000612502f,-0.313448f,0.104198f},{5.16769e-017f,-0.313407f,0.104198f}, -{5.16769e-017f,-0.313407f,0.101401f},{0.00456433f,-0.319013f,0.101401f},{0.00440833f,-0.319582f,0.101401f}, -{0.00450141f,-0.319278f,0.104198f},{0.00430621f,-0.319852f,0.104198f},{0.00418158f,-0.320128f,0.101401f}, -{0.00388773f,-0.32064f,0.101401f},{0.00403832f,-0.320396f,0.104198f},{0.00353147f,-0.321111f,0.101401f}, -{0.00370055f,-0.320902f,0.104198f},{0.00329584f,-0.321364f,0.104198f},{0.0031185f,-0.321533f,0.101401f}, -{0.00265541f,-0.321899f,0.101401f},{0.0028342f,-0.321769f,0.104198f},{0.00214963f,-0.322204f,0.101401f}, -{0.00232777f,-0.322106f,0.104198f},{0.00178369f,-0.322374f,0.104198f},{0.00160952f,-0.322443f,0.101401f}, -{0.00104053f,-0.322599f,0.101401f},{0.00120978f,-0.322569f,0.104198f},{0.000461185f,-0.322725f,0.101401f}, -{0.000612842f,-0.322689f,0.104198f},{5.28185e-017f,-0.322729f,0.104198f},{5.28185e-017f,-0.322729f,0.101401f}, -{-0.0143886f,-0.288764f,0.110723f},{-0.0143784f,-0.288958f,0.101401f},{-0.0143782f,-0.288568f,0.101401f}, -{-0.014297f,-0.288187f,0.101401f},{-0.0143526f,-0.288401f,0.110723f},{-0.0142471f,-0.288051f,0.110723f}, -{-0.0139089f,-0.287516f,0.101401f},{-0.014075f,-0.287728f,0.110723f},{-0.0141387f,-0.287832f,0.101401f}, -{-0.0136193f,-0.287256f,0.101401f},{-0.0138429f,-0.287445f,0.110723f},{-0.0135601f,-0.287213f,0.110723f}, -{-0.013282f,-0.287061f,0.101401f},{-0.0129121f,-0.286941f,0.101401f},{-0.0132377f,-0.287041f,0.110723f}, -{-0.0125242f,-0.2869f,0.101401f},{-0.0125242f,-0.2869f,0.110723f},{-0.0128879f,-0.286935f,0.110723f}, -{-0.0143523f,-0.289129f,0.110723f},{-0.0142976f,-0.28934f,0.101401f},{-0.0142453f,-0.289478f,0.110723f}, -{-0.0140726f,-0.2898f,0.110723f},{-0.0141391f,-0.289696f,0.101401f},{-0.0138409f,-0.290082f,0.110723f}, -{-0.0139105f,-0.290011f,0.101401f},{-0.0136206f,-0.290272f,0.101401f},{-0.0135587f,-0.290314f,0.110723f}, -{-0.0132367f,-0.290486f,0.110723f},{-0.013283f,-0.290467f,0.101401f},{-0.0128873f,-0.290592f,0.110723f}, -{-0.0129131f,-0.290588f,0.101401f},{-0.0125242f,-0.290629f,0.101401f},{-0.0125242f,-0.290629f,0.110723f}, -{-0.0125242f,-0.288764f,0.111843f},{0.00868228f,-0.290742f,0.110723f},{0.00869244f,-0.290936f,0.101401f}, -{0.00869272f,-0.290546f,0.101401f},{0.00877392f,-0.290165f,0.101401f},{0.0087183f,-0.290378f,0.110723f}, -{0.00882381f,-0.290028f,0.110723f},{0.00916198f,-0.289494f,0.101401f},{0.00899591f,-0.289705f,0.110723f}, -{0.00893219f,-0.289809f,0.101401f},{0.0094516f,-0.289233f,0.101401f},{0.00922803f,-0.289422f,0.110723f}, -{0.00951082f,-0.289191f,0.110723f},{0.00978889f,-0.289038f,0.101401f},{0.0101588f,-0.288918f,0.101401f}, -{0.00983322f,-0.289018f,0.110723f},{0.0105467f,-0.288877f,0.101401f},{0.0105467f,-0.288877f,0.110723f}, -{0.010183f,-0.288912f,0.110723f},{0.00871859f,-0.291106f,0.110723f},{0.00877329f,-0.291317f,0.101401f}, -{0.00882557f,-0.291456f,0.110723f},{0.00899828f,-0.291778f,0.110723f},{0.00893177f,-0.291673f,0.101401f}, -{0.00922999f,-0.29206f,0.110723f},{0.00916039f,-0.291988f,0.101401f},{0.00945026f,-0.29225f,0.101401f}, -{0.00951221f,-0.292291f,0.110723f},{0.00983423f,-0.292464f,0.110723f},{0.00978794f,-0.292445f,0.101401f}, -{0.0101836f,-0.29257f,0.110723f},{0.0101578f,-0.292565f,0.101401f},{0.0105467f,-0.292606f,0.101401f}, -{0.0105467f,-0.292606f,0.110723f},{0.0105467f,-0.290742f,0.111843f},{0.0106598f,-0.313813f,0.110723f}, -{0.0106699f,-0.314007f,0.101401f},{0.0106702f,-0.313617f,0.101401f},{0.0107514f,-0.313236f,0.101401f}, -{0.0106958f,-0.313449f,0.110723f},{0.0108013f,-0.313099f,0.110723f},{0.0111395f,-0.312564f,0.101401f}, -{0.0109734f,-0.312776f,0.110723f},{0.0109097f,-0.31288f,0.101401f},{0.0114291f,-0.312304f,0.101401f}, -{0.0112055f,-0.312493f,0.110723f},{0.0114883f,-0.312261f,0.110723f},{0.0117664f,-0.312109f,0.101401f}, -{0.0121363f,-0.311989f,0.101401f},{0.0118107f,-0.312089f,0.110723f},{0.0125242f,-0.311948f,0.101401f}, -{0.0125242f,-0.311948f,0.110723f},{0.0121605f,-0.311983f,0.110723f},{0.0106961f,-0.314177f,0.110723f}, -{0.0107508f,-0.314388f,0.101401f},{0.0108031f,-0.314527f,0.110723f},{0.0109758f,-0.314848f,0.110723f}, -{0.0109093f,-0.314744f,0.101401f},{0.0112075f,-0.315131f,0.110723f},{0.0111379f,-0.315059f,0.101401f}, -{0.0114278f,-0.315321f,0.101401f},{0.0114897f,-0.315362f,0.110723f},{0.0118117f,-0.315534f,0.110723f}, -{0.0117654f,-0.315516f,0.101401f},{0.0121611f,-0.315641f,0.110723f},{0.0121353f,-0.315636f,0.101401f}, -{0.0125242f,-0.315677f,0.101401f},{0.0125242f,-0.315677f,0.110723f},{0.0125242f,-0.313813f,0.111843f}, -{-0.0124111f,-0.311835f,0.110723f},{-0.0124009f,-0.312029f,0.101401f},{-0.0124007f,-0.311639f,0.101401f}, -{-0.0123195f,-0.311258f,0.101401f},{-0.0123751f,-0.311472f,0.110723f},{-0.0122696f,-0.311121f,0.110723f}, -{-0.0119314f,-0.310587f,0.101401f},{-0.0120975f,-0.310799f,0.110723f},{-0.0121612f,-0.310903f,0.101401f}, -{-0.0116418f,-0.310326f,0.101401f},{-0.0118654f,-0.310516f,0.110723f},{-0.0115826f,-0.310284f,0.110723f}, -{-0.0113045f,-0.310132f,0.101401f},{-0.0109346f,-0.310012f,0.101401f},{-0.0112602f,-0.310112f,0.110723f}, -{-0.0105467f,-0.309971f,0.101401f},{-0.0105467f,-0.309971f,0.110723f},{-0.0109104f,-0.310006f,0.110723f}, -{-0.0123748f,-0.312199f,0.110723f},{-0.0123201f,-0.312411f,0.101401f},{-0.0122678f,-0.312549f,0.110723f}, -{-0.0120951f,-0.312871f,0.110723f},{-0.0121616f,-0.312767f,0.101401f},{-0.0118634f,-0.313153f,0.110723f}, -{-0.011933f,-0.313082f,0.101401f},{-0.0116431f,-0.313343f,0.101401f},{-0.0115812f,-0.313385f,0.110723f}, -{-0.0112592f,-0.313557f,0.110723f},{-0.0113054f,-0.313538f,0.101401f},{-0.0109098f,-0.313663f,0.110723f}, -{-0.0109356f,-0.313659f,0.101401f},{-0.0105467f,-0.3137f,0.101401f},{-0.0105467f,-0.3137f,0.110723f}, -{-0.0105467f,-0.311835f,0.111843f},{-0.0173925f,-0.305909f,0.101401f},{-0.0173922f,-0.305909f,0.104198f}, -{-0.0167797f,-0.30595f,0.101401f},{-0.0161668f,-0.305909f,0.104198f},{-0.0161672f,-0.305909f,0.101401f}, -{-0.0167797f,-0.30595f,0.104198f},{-0.014996f,-0.305595f,0.101401f},{-0.014996f,-0.305595f,0.104198f}, -{-0.0144523f,-0.305327f,0.101401f},{-0.0155699f,-0.30579f,0.104198f},{-0.0155702f,-0.30579f,0.101401f}, -{-0.0144519f,-0.305327f,0.104198f},{-0.0139455f,-0.304989f,0.104198f},{-0.0139458f,-0.304989f,0.101401f}, -{-0.0134838f,-0.304584f,0.101401f},{-0.0134838f,-0.304584f,0.104198f},{-0.0130791f,-0.304122f,0.104198f}, -{-0.0130793f,-0.304123f,0.101401f},{-0.0127415f,-0.303616f,0.101401f},{-0.0127414f,-0.303616f,0.104198f}, -{-0.0124735f,-0.303072f,0.101401f},{-0.0124735f,-0.303072f,0.104198f},{-0.0122783f,-0.302498f,0.104198f}, -{-0.0122784f,-0.302498f,0.101401f},{-0.0121187f,-0.301289f,0.101401f},{-0.0121592f,-0.301901f,0.101401f}, -{-0.012159f,-0.301901f,0.104198f},{-0.0121187f,-0.301289f,0.104198f},{-0.0179891f,-0.30579f,0.104198f}, -{-0.0179895f,-0.30579f,0.101401f},{-0.0185634f,-0.305595f,0.104198f},{-0.0191071f,-0.305327f,0.104198f}, -{-0.0185634f,-0.305595f,0.101401f},{-0.0191075f,-0.305327f,0.101401f},{-0.0196135f,-0.304989f,0.104198f}, -{-0.0196139f,-0.304989f,0.101401f},{-0.0200755f,-0.304584f,0.104198f},{-0.0204801f,-0.304123f,0.104198f}, -{-0.0200755f,-0.304584f,0.101401f},{-0.0204802f,-0.304122f,0.101401f},{-0.0208179f,-0.303616f,0.104198f}, -{-0.020818f,-0.303616f,0.101401f},{-0.0210859f,-0.303072f,0.104198f},{-0.0212809f,-0.302498f,0.104198f}, -{-0.0210859f,-0.303072f,0.101401f},{-0.0212811f,-0.302498f,0.101401f},{-0.0214002f,-0.301901f,0.104198f}, -{-0.0214003f,-0.301901f,0.101401f},{-0.0214407f,-0.301289f,0.104198f},{-0.0214407f,-0.301289f,0.101401f}, -{0.0254902f,-0.298561f,0.121909f},{0.0255985f,-0.29991f,0.120045f},{0.0254881f,-0.298542f,0.120045f}, -{0.0250554f,-0.295865f,0.121909f},{0.0250515f,-0.295847f,0.120045f},{0.0247276f,-0.294526f,0.120045f}, -{0.0255992f,-0.299923f,0.121909f},{0.0256356f,-0.301289f,0.120045f},{0.0256356f,-0.301289f,0.121909f}, -{0.0253087f,-0.297208f,0.121909f},{0.0253054f,-0.297187f,0.120045f},{0.0241907f,-0.292804f,0.121909f}, -{0.0246545f,-0.294325f,0.121909f},{0.0243348f,-0.293226f,0.120045f},{0.0222011f,-0.288471f,0.121909f}, -{0.0229537f,-0.289873f,0.121909f},{0.0227538f,-0.28948f,0.120045f},{0.0236177f,-0.291319f,0.121909f}, -{0.0238741f,-0.29195f,0.120045f},{0.0233468f,-0.2907f,0.120045f},{0.0205925f,-0.28602f,0.120045f}, -{0.0197483f,-0.284942f,0.120045f},{0.0204428f,-0.28582f,0.121909f},{0.0220964f,-0.288291f,0.120045f}, -{0.0213756f,-0.287137f,0.120045f},{0.0213632f,-0.287118f,0.121909f},{0.0178811f,-0.282919f,0.120045f}, -{0.0172245f,-0.282302f,0.121909f},{0.0183635f,-0.283414f,0.121909f},{0.0188436f,-0.283907f,0.120045f}, -{0.0194437f,-0.284581f,0.121909f},{0.0137508f,-0.279653f,0.121909f},{0.015542f,-0.280901f,0.121909f}, -{0.014715f,-0.280297f,0.120045f},{0.0168687f,-0.281985f,0.120045f},{0.0112022f,-0.27823f,0.120045f}, -{0.00996671f,-0.27767f,0.120045f},{0.00988506f,-0.277635f,0.121909f},{0.0124072f,-0.278855f,0.120045f}, -{0.0118618f,-0.278562f,0.121909f},{0.00610419f,-0.27639f,0.120045f},{0.00612578f,-0.276411f,0.121909f}, -{0.00741505f,-0.276749f,0.120045f},{0.00783085f,-0.276878f,0.121909f},{0.00870345f,-0.277176f,0.120045f}, -{0.00264799f,-0.27579f,0.121909f},{0.00342595f,-0.275883f,0.120045f},{0.00206394f,-0.275736f,0.120045f}, -{0.00477359f,-0.276101f,0.120045f},{0.00439916f,-0.276033f,0.121909f},{0.000884103f,-0.275668f,0.121909f}, -{-0.000690516f,-0.275662f,0.120045f},{-0.000883894f,-0.275668f,0.121909f},{0.000689447f,-0.275662f,0.120045f}, -{-0.00342617f,-0.275883f,0.120045f},{-0.00477376f,-0.276101f,0.120045f},{-0.00439897f,-0.276033f,0.121909f}, -{-0.00264771f,-0.27579f,0.121909f},{-0.00206419f,-0.275736f,0.120045f},{-0.0087035f,-0.277176f,0.120045f}, -{-0.00783085f,-0.276878f,0.121909f},{-0.00741509f,-0.276749f,0.120045f},{-0.00612769f,-0.276402f,0.121909f}, -{-0.0061043f,-0.27639f,0.120045f},{-0.0118616f,-0.278562f,0.121909f},{-0.00988475f,-0.277635f,0.121909f}, -{-0.0112024f,-0.27823f,0.120045f},{-0.00996683f,-0.27767f,0.120045f},{-0.0137506f,-0.279653f,0.121909f}, -{-0.0135792f,-0.279545f,0.120045f},{-0.0147152f,-0.280297f,0.120045f},{-0.0124074f,-0.278855f,0.120045f}, -{-0.016869f,-0.281985f,0.120045f},{-0.0178817f,-0.282919f,0.120045f},{-0.0172245f,-0.282302f,0.121909f}, -{-0.0155417f,-0.280901f,0.121909f},{-0.0158127f,-0.281111f,0.120045f},{-0.0188441f,-0.283908f,0.120045f}, -{-0.0197483f,-0.284943f,0.120045f},{-0.0194435f,-0.284581f,0.121909f},{-0.0183577f,-0.283419f,0.121909f}, -{-0.0204427f,-0.28582f,0.121909f},{-0.0205925f,-0.28602f,0.120045f},{-0.0213756f,-0.287137f,0.120045f}, -{-0.021363f,-0.287118f,0.121909f},{-0.0220965f,-0.288291f,0.120045f},{-0.0222011f,-0.288471f,0.121909f}, -{-0.0227539f,-0.28948f,0.120045f},{-0.0229535f,-0.289873f,0.121909f},{-0.0236176f,-0.291319f,0.121909f}, -{-0.0233469f,-0.290701f,0.120045f},{-0.0238742f,-0.29195f,0.120045f},{-0.0241907f,-0.292803f,0.121909f}, -{-0.0243349f,-0.293226f,0.120045f},{-0.0246619f,-0.294323f,0.121909f},{-0.0250554f,-0.295865f,0.121909f}, -{-0.0247277f,-0.294526f,0.120045f},{-0.0253055f,-0.297187f,0.120045f},{-0.0250516f,-0.295847f,0.120045f}, -{-0.0254882f,-0.298542f,0.120045f},{-0.0253087f,-0.297208f,0.121909f},{-0.0254901f,-0.298561f,0.121909f}, -{-0.0255986f,-0.29991f,0.120045f},{-0.0256356f,-0.301289f,0.120045f},{-0.0255992f,-0.299923f,0.121909f}, -{-0.0256356f,-0.301289f,0.121909f},{0.013579f,-0.279545f,0.120045f},{0.0158124f,-0.28111f,0.120045f}, -{0.0247034f,-0.301289f,0.104011f},{0.0261017f,-0.301289f,0.10513f},{0.0260447f,-0.303013f,0.10513f}, -{0.0148773f,-0.28396f,0.10252f},{0.0141264f,-0.285159f,0.101401f},{0.0130365f,-0.284266f,0.101401f}, -{0.0151609f,-0.286128f,0.101401f},{0.0131883f,-0.282642f,0.10252f},{0.0144813f,-0.279572f,0.10513f}, -{0.0123517f,-0.279895f,0.104011f},{0.0130346f,-0.278674f,0.10513f},{0.0118953f,-0.28345f,0.101401f}, -{0.0114195f,-0.281509f,0.10252f},{0.0115354f,-0.277874f,0.10513f},{0.00947527f,-0.282055f,0.101401f}, -{0.00998868f,-0.277174f,0.10513f},{0.00820499f,-0.28148f,0.101401f},{0.0084f,-0.276575f,0.10513f}, -{0.00689981f,-0.280988f,0.101401f},{0.00556423f,-0.280582f,0.101401f},{0.00677408f,-0.276081f,0.10513f}, -{0.00420236f,-0.280264f,0.101401f},{0.00511591f,-0.275693f,0.10513f},{0.00343096f,-0.275413f,0.10513f}, -{0.0028181f,-0.280034f,0.101401f},{0.00172399f,-0.275244f,0.10513f},{0.00141594f,-0.279895f,0.101401f}, -{5.61862e-017f,-0.275187f,0.10513f},{0.0164604f,-0.285456f,0.10252f},{0.016129f,-0.287162f,0.101401f}, -{0.0179091f,-0.287115f,0.10252f},{0.0170221f,-0.288252f,0.101401f},{0.0178384f,-0.289393f,0.101401f}, -{0.0192f,-0.28892f,0.10252f},{0.018576f,-0.290582f,0.101401f},{0.0203119f,-0.290846f,0.10252f}, -{0.0192333f,-0.291813f,0.101401f},{0.0212292f,-0.292866f,0.10252f},{0.0198086f,-0.293084f,0.101401f}, -{0.0252075f,-0.294515f,0.10513f},{0.0255955f,-0.296173f,0.10513f},{0.0242782f,-0.296724f,0.104011f}, -{0.021942f,-0.294951f,0.10252f},{0.0203001f,-0.294389f,0.101401f},{0.0224458f,-0.297069f,0.10252f}, -{0.0207061f,-0.295724f,0.101401f},{0.0210249f,-0.297086f,0.101401f},{0.0227423f,-0.299192f,0.10252f}, -{0.0212547f,-0.29847f,0.101401f},{0.0260448f,-0.299565f,0.10513f},{0.022839f,-0.301289f,0.10252f}, -{0.0213939f,-0.299872f,0.101401f},{0.0212463f,-0.304169f,0.101401f},{0.021392f,-0.302732f,0.101401f}, -{0.0258753f,-0.30472f,0.10513f},{0.0202358f,-0.308374f,0.101401f},{0.0206669f,-0.306996f,0.101401f}, -{0.0247131f,-0.309689f,0.10513f},{0.0210042f,-0.305592f,0.101401f},{0.0255955f,-0.306404f,0.10513f}, -{0.0252074f,-0.308063f,0.10513f},{0.0191008f,-0.311028f,0.101401f},{0.0226142f,-0.314323f,0.10513f}, -{0.0184019f,-0.312292f,0.101401f},{0.0241148f,-0.311277f,0.10513f},{0.0234144f,-0.312824f,0.10513f}, -{0.019713f,-0.309721f,0.101401f},{0.0207226f,-0.317159f,0.10513f},{0.0196354f,-0.318486f,0.10513f}, -{0.0167571f,-0.314664f,0.101401f},{0.0176194f,-0.313506f,0.101401f},{0.0217163f,-0.31577f,0.10513f}, -{0.0158706f,-0.322011f,0.10513f},{0.0137317f,-0.317755f,0.101401f},{0.0171974f,-0.320924f,0.10513f}, -{0.0148089f,-0.316793f,0.101401f},{0.0158188f,-0.315761f,0.101401f},{0.0184567f,-0.319745f,0.10513f}, -{0.0101475f,-0.320176f,0.101401f},{0.0113957f,-0.31945f,0.101401f},{0.0114195f,-0.321068f,0.10252f}, -{0.0125922f,-0.318642f,0.101401f},{0.0123517f,-0.322682f,0.104011f},{0.0130343f,-0.323903f,0.10513f}, -{0.0109801f,-0.323418f,0.104011f},{0.00954347f,-0.324074f,0.104011f},{0.00998868f,-0.325403f,0.10513f}, -{0.00804836f,-0.324644f,0.104011f},{0.0115351f,-0.324703f,0.10513f},{0.00650255f,-0.325121f,0.104011f}, -{0.00677384f,-0.326496f,0.10513f},{0.00491482f,-0.325498f,0.104011f},{0.00839976f,-0.326002f,0.10513f}, -{0.00329485f,-0.325771f,0.104011f},{0.00511591f,-0.326884f,0.10513f},{0.00343072f,-0.327164f,0.10513f}, -{0.00172376f,-0.327333f,0.10513f},{0.00165296f,-0.325937f,0.104011f},{5.29897e-017f,-0.32739f,0.10513f}, -{5.29897e-017f,-0.325992f,0.104011f},{0.0144813f,-0.323005f,0.10513f},{0.00454389f,-0.323671f,0.10252f}, -{0.00475341f,-0.322193f,0.101401f},{0.00601179f,-0.323322f,0.10252f},{0.00304618f,-0.323923f,0.10252f}, -{0.00333561f,-0.322467f,0.101401f},{0.00190254f,-0.322644f,0.101401f},{0.00152821f,-0.324076f,0.10252f}, -{5.29897e-017f,-0.324128f,0.10252f},{0.00615037f,-0.321828f,0.101401f},{0.00751875f,-0.321368f,0.101401f}, -{0.00882321f,-0.322354f,0.10252f},{0.00744093f,-0.322881f,0.10252f},{0.00885315f,-0.320816f,0.101401f}, -{0.0101514f,-0.321748f,0.10252f},{0.0142636f,-0.281119f,0.104011f},{0.0107068f,-0.282713f,0.101401f}, -{0.0160914f,-0.282545f,0.104011f},{0.0158708f,-0.280566f,0.10513f},{0.0184567f,-0.282832f,0.10513f}, -{0.0171976f,-0.281653f,0.10513f},{0.0178031f,-0.284163f,0.104011f},{0.0193705f,-0.285958f,0.104011f}, -{0.0196355f,-0.284091f,0.10513f},{0.0217163f,-0.286807f,0.10513f},{0.0207227f,-0.285418f,0.10513f}, -{0.0207667f,-0.287909f,0.104011f},{0.0219695f,-0.289993f,0.104011f},{0.0226143f,-0.288254f,0.10513f}, -{0.0234145f,-0.289753f,0.10513f},{0.0229621f,-0.292178f,0.104011f},{0.0241148f,-0.2913f,0.10513f}, -{0.0237331f,-0.294432f,0.104011f},{0.0247132f,-0.292889f,0.10513f},{0.0245992f,-0.299019f,0.104011f}, -{0.0258754f,-0.297858f,0.10513f},{0.0214407f,-0.301289f,0.10513f},{0.0214407f,-0.301289f,0.106062f}, -{0.0214037f,-0.302548f,0.106062f},{0.0212935f,-0.303797f,0.106062f},{0.0214037f,-0.302548f,0.10513f}, -{0.0211114f,-0.305032f,0.106062f},{0.0212936f,-0.303796f,0.10513f},{0.0211115f,-0.305032f,0.10513f}, -{0.0208586f,-0.306251f,0.106062f},{0.0205363f,-0.30745f,0.106062f},{0.0208587f,-0.30625f,0.10513f}, -{0.0201457f,-0.308627f,0.106062f},{0.0205363f,-0.30745f,0.10513f},{0.0201457f,-0.308627f,0.10513f}, -{0.0196879f,-0.309779f,0.106062f},{0.0191643f,-0.310903f,0.106062f},{0.019688f,-0.309779f,0.10513f}, -{0.018576f,-0.311996f,0.106062f},{0.0191643f,-0.310903f,0.10513f},{0.018576f,-0.311995f,0.10513f}, -{0.0179242f,-0.313054f,0.106062f},{0.0172102f,-0.314076f,0.106062f},{0.0179243f,-0.313054f,0.10513f}, -{0.0164352f,-0.315058f,0.106062f},{0.0172102f,-0.314076f,0.10513f},{0.0164352f,-0.315058f,0.10513f}, -{0.0155998f,-0.315997f,0.106062f},{0.0147082f,-0.316889f,0.106062f},{0.0156004f,-0.315997f,0.10513f}, -{0.0137691f,-0.317724f,0.106062f},{0.0147088f,-0.316888f,0.10513f},{0.0137693f,-0.317724f,0.10513f}, -{0.0127873f,-0.318499f,0.106062f},{0.0117655f,-0.319213f,0.106062f},{0.0127873f,-0.318499f,0.10513f}, -{0.0107068f,-0.319865f,0.106062f},{0.0117656f,-0.319213f,0.10513f},{0.010707f,-0.319865f,0.10513f}, -{0.00961408f,-0.320453f,0.106062f},{0.00849036f,-0.320976f,0.106062f},{0.0096143f,-0.320453f,0.10513f}, -{0.0073385f,-0.321434f,0.106062f},{0.00849054f,-0.320976f,0.10513f},{0.00733859f,-0.321434f,0.10513f}, -{0.00616138f,-0.321825f,0.106062f},{0.00496191f,-0.322147f,0.106062f},{0.00616144f,-0.321825f,0.10513f}, -{0.00496208f,-0.322147f,0.10513f},{0.00374334f,-0.3224f,0.10513f},{0.00250813f,-0.322582f,0.10513f}, -{0.00374312f,-0.3224f,0.106062f},{0.00125925f,-0.322692f,0.106062f},{0.00250793f,-0.322582f,0.106062f}, -{5.56154e-017f,-0.322729f,0.106062f},{0.00125938f,-0.322692f,0.10513f},{5.56154e-017f,-0.322729f,0.10513f}, -{0.0214037f,-0.300029f,0.10513f},{0.0212935f,-0.29878f,0.10513f},{0.0214037f,-0.300029f,0.106062f}, -{0.0212936f,-0.298781f,0.106062f},{0.0211114f,-0.297545f,0.10513f},{0.0208586f,-0.296326f,0.10513f}, -{0.0211115f,-0.297545f,0.106062f},{0.0205363f,-0.295127f,0.10513f},{0.0208587f,-0.296327f,0.106062f}, -{0.0205363f,-0.295127f,0.106062f},{0.0201457f,-0.29395f,0.10513f},{0.0196879f,-0.292798f,0.10513f}, -{0.0201457f,-0.29395f,0.106062f},{0.0191643f,-0.291674f,0.10513f},{0.019688f,-0.292798f,0.106062f}, -{0.0191643f,-0.291674f,0.106062f},{0.018576f,-0.290582f,0.10513f},{0.0179242f,-0.289523f,0.10513f}, -{0.018576f,-0.290582f,0.106062f},{0.0172102f,-0.288501f,0.10513f},{0.0179243f,-0.289523f,0.106062f}, -{0.0172102f,-0.288501f,0.106062f},{0.0164352f,-0.287519f,0.10513f},{0.0155998f,-0.28658f,0.10513f}, -{0.0164352f,-0.287519f,0.106062f},{0.0147082f,-0.285688f,0.10513f},{0.0156004f,-0.28658f,0.106062f}, -{0.0147088f,-0.285689f,0.106062f},{0.0137691f,-0.284853f,0.10513f},{0.0127873f,-0.284078f,0.10513f}, -{0.0137693f,-0.284853f,0.106062f},{0.0117655f,-0.283364f,0.10513f},{0.0127873f,-0.284078f,0.106062f}, -{0.0117656f,-0.283364f,0.106062f},{0.0107068f,-0.282713f,0.10513f},{0.00961408f,-0.282124f,0.10513f}, -{0.010707f,-0.282713f,0.106062f},{0.00849036f,-0.281601f,0.10513f},{0.0096143f,-0.282124f,0.106062f}, -{0.00849054f,-0.281601f,0.106062f},{0.0073385f,-0.281143f,0.10513f},{0.00616138f,-0.280752f,0.10513f}, -{0.00733859f,-0.281143f,0.106062f},{0.00496191f,-0.28043f,0.10513f},{0.00616144f,-0.280752f,0.106062f}, -{0.00374334f,-0.280177f,0.106062f},{0.00496208f,-0.28043f,0.106062f},{0.00374312f,-0.280177f,0.10513f}, -{0.00250813f,-0.279995f,0.106062f},{0.00250793f,-0.279995f,0.10513f},{0.00125925f,-0.279885f,0.10513f}, -{0.00125938f,-0.279885f,0.106062f},{5.29897e-017f,-0.279848f,0.10513f},{5.29897e-017f,-0.279848f,0.106062f}, -{0.0261017f,-0.301289f,0.106062f},{0.0261017f,-0.301289f,0.120045f},{0.0260652f,-0.302669f,0.120045f}, -{0.0259565f,-0.304039f,0.120045f},{0.0260653f,-0.302669f,0.106062f},{0.0257765f,-0.305396f,0.120045f}, -{0.0259565f,-0.304039f,0.106062f},{0.0257766f,-0.305396f,0.106062f},{0.0255265f,-0.306739f,0.120045f}, -{0.0252074f,-0.308063f,0.120045f},{0.0255265f,-0.306738f,0.106062f},{0.0248204f,-0.309366f,0.120045f}, -{0.0252075f,-0.308062f,0.106062f},{0.0248205f,-0.309366f,0.106062f},{0.0243664f,-0.310647f,0.120045f}, -{0.0238467f,-0.311901f,0.120045f},{0.0243666f,-0.310646f,0.106062f},{0.0232623f,-0.313128f,0.120045f}, -{0.0238468f,-0.311901f,0.106062f},{0.0232624f,-0.313127f,0.106062f},{0.0226142f,-0.314323f,0.120045f}, -{0.0219036f,-0.315485f,0.120045f},{0.0226143f,-0.314323f,0.106062f},{0.0211314f,-0.316611f,0.120045f}, -{0.0219036f,-0.315485f,0.106062f},{0.0211315f,-0.316611f,0.106062f},{0.0202988f,-0.317698f,0.120045f}, -{0.0194069f,-0.318743f,0.120045f},{0.0202989f,-0.317698f,0.106062f},{0.0184567f,-0.319745f,0.120045f}, -{0.0194069f,-0.318743f,0.106062f},{0.0184567f,-0.319745f,0.106062f},{0.0174549f,-0.320695f,0.120045f}, -{0.0164091f,-0.321587f,0.120045f},{0.0174549f,-0.320695f,0.106062f},{0.015322f,-0.32242f,0.120045f}, -{0.0164092f,-0.321587f,0.106062f},{0.0153222f,-0.32242f,0.106062f},{0.0141962f,-0.323192f,0.120045f}, -{0.0130343f,-0.323903f,0.120045f},{0.0141964f,-0.323192f,0.106062f},{0.0118389f,-0.324551f,0.120045f}, -{0.0130346f,-0.323903f,0.106062f},{0.0118391f,-0.324551f,0.106062f},{0.0106125f,-0.325135f,0.120045f}, -{0.00935782f,-0.325655f,0.120045f},{0.0106128f,-0.325135f,0.106062f},{0.0080774f,-0.326109f,0.120045f}, -{0.00935809f,-0.325655f,0.106062f},{0.00807765f,-0.326109f,0.106062f},{0.00677384f,-0.326496f,0.120045f}, -{0.00544975f,-0.326815f,0.120045f},{0.00677408f,-0.326496f,0.106062f},{0.00410773f,-0.327065f,0.120045f}, -{0.00544996f,-0.326815f,0.106062f},{0.0041079f,-0.327065f,0.106062f},{0.00275036f,-0.327245f,0.120045f}, -{0.00138025f,-0.327354f,0.120045f},{0.00275048f,-0.327245f,0.106062f},{5.61862e-017f,-0.32739f,0.120045f}, -{0.00138032f,-0.327354f,0.106062f},{5.61862e-017f,-0.32739f,0.106062f},{0.0260652f,-0.299908f,0.106062f}, -{0.0259565f,-0.298538f,0.106062f},{0.0260653f,-0.299908f,0.120045f},{0.0259565f,-0.298538f,0.120045f}, -{0.0257765f,-0.297181f,0.106062f},{0.0255265f,-0.295839f,0.106062f},{0.0257766f,-0.297181f,0.120045f}, -{0.0252074f,-0.294514f,0.106062f},{0.0255265f,-0.295839f,0.120045f},{0.0252075f,-0.294515f,0.120045f}, -{0.0248204f,-0.293211f,0.106062f},{0.0243664f,-0.29193f,0.106062f},{0.0248205f,-0.293211f,0.120045f}, -{0.0238467f,-0.290676f,0.106062f},{0.0243666f,-0.291931f,0.120045f},{0.0238468f,-0.290676f,0.120045f}, -{0.0232623f,-0.289449f,0.106062f},{0.0226142f,-0.288254f,0.106062f},{0.0232624f,-0.28945f,0.120045f}, -{0.0219036f,-0.287092f,0.106062f},{0.0226143f,-0.288254f,0.120045f},{0.0219036f,-0.287092f,0.120045f}, -{0.0211314f,-0.285966f,0.106062f},{0.0202988f,-0.284879f,0.106062f},{0.0211315f,-0.285967f,0.120045f}, -{0.0194069f,-0.283834f,0.106062f},{0.0202989f,-0.284879f,0.120045f},{0.0194069f,-0.283834f,0.120045f}, -{0.0184567f,-0.282832f,0.106062f},{0.0174549f,-0.281882f,0.106062f},{0.0184567f,-0.282832f,0.120045f}, -{0.0164091f,-0.28099f,0.106062f},{0.0174549f,-0.281882f,0.120045f},{0.0164092f,-0.28099f,0.120045f}, -{0.015322f,-0.280157f,0.106062f},{0.0141962f,-0.279385f,0.106062f},{0.0153222f,-0.280157f,0.120045f}, -{0.0130343f,-0.278674f,0.106062f},{0.0141964f,-0.279385f,0.120045f},{0.0130346f,-0.278674f,0.120045f}, -{0.0118389f,-0.278026f,0.106062f},{0.0106125f,-0.277442f,0.106062f},{0.0118391f,-0.278026f,0.120045f}, -{0.00935782f,-0.276922f,0.106062f},{0.0106128f,-0.277442f,0.120045f},{0.00935809f,-0.276922f,0.120045f}, -{0.0080774f,-0.276468f,0.106062f},{0.00677384f,-0.276081f,0.106062f},{0.00807765f,-0.276468f,0.120045f}, -{0.00544975f,-0.275762f,0.106062f},{0.00677408f,-0.276081f,0.120045f},{0.00544996f,-0.275762f,0.120045f}, -{0.00410773f,-0.275512f,0.106062f},{0.00275036f,-0.275332f,0.106062f},{0.0041079f,-0.275512f,0.120045f}, -{0.00138025f,-0.275223f,0.106062f},{0.00275048f,-0.275332f,0.120045f},{0.00138032f,-0.275223f,0.120045f}, -{5.29897e-017f,-0.275187f,0.106062f},{5.29897e-017f,-0.275187f,0.120045f},{0.0121333f,-0.304179f,0.125638f}, -{-0.0149893f,-0.295319f,0.125638f},{-0.0150309f,-0.294763f,0.125638f},{-0.019126f,-0.297548f,0.125638f}, -{-0.00810759f,-0.316569f,0.125638f},{-0.00862289f,-0.286353f,0.125638f},{-0.00372901f,-0.288237f,0.125638f}, -{-0.00810797f,-0.286008f,0.125638f},{-0.0122191f,-0.286802f,0.125638f},{-0.012803f,-0.286594f,0.125638f}, -{-0.0130106f,-0.290972f,0.125638f},{0.00523604f,-0.291442f,0.125638f},{0.00485519f,-0.291361f,0.125638f}, -{-0.0018645f,-0.285009f,0.125638f},{-0.00378085f,-0.279711f,0.125638f},{-0.00629776f,-0.282236f,0.125638f}, -{0.00943824f,-0.291533f,0.125638f},{0.00917901f,-0.286627f,0.125638f},{0.00862289f,-0.286353f,0.125638f}, -{0.00897792f,-0.291847f,0.125638f},{0.0172458f,-0.301289f,0.125638f},{0.0172871f,-0.30067f,0.125638f}, -{0.010994f,-0.286978f,0.125638f},{0.0110243f,-0.291045f,0.125638f},{0.0115815f,-0.291045f,0.125638f}, -{0.0207988f,-0.305818f,0.125638f},{0.0210452f,-0.307372f,0.125638f},{0.021411f,-0.305923f,0.125638f}, -{0.0174099f,-0.302514f,0.125638f},{0.017287f,-0.301907f,0.125638f},{0.0136278f,-0.304899f,0.125638f}, -{0.019126f,-0.30503f,0.125638f},{0.0149893f,-0.307258f,0.125638f},{0.0150309f,-0.307814f,0.125638f}, -{0.0202118f,-0.305622f,0.125638f},{0.0149893f,-0.30837f,0.125638f},{0.0148647f,-0.308913f,0.125638f}, -{0.0200086f,-0.310208f,0.125638f},{0.00994038f,-0.304343f,0.125638f},{0.0104733f,-0.304175f,0.125638f}, -{0.0143811f,-0.309913f,0.125638f},{0.0185801f,-0.312894f,0.125638f},{0.0193415f,-0.311575f,0.125638f}, -{0.0205774f,-0.308803f,0.125638f},{0.0196492f,-0.305361f,0.125638f},{0.0167976f,-0.315351f,0.125638f}, -{0.013354f,-0.316267f,0.125638f},{0.0157911f,-0.316472f,0.125638f},{0.0136271f,-0.310729f,0.125638f}, -{0.0138626f,-0.316622f,0.125638f},{0.0143217f,-0.317038f,0.125638f},{0.0147191f,-0.317514f,0.125638f}, -{0.0146599f,-0.309431f,0.125638f},{0.0149896f,-0.294208f,0.125638f},{0.0205772f,-0.293773f,0.125638f}, -{0.0148655f,-0.306715f,0.125638f},{0.0186543f,-0.304628f,0.125638f},{0.0182401f,-0.304166f,0.125638f}, -{0.0178906f,-0.303654f,0.125638f},{0.0143836f,-0.305714f,0.125638f},{0.0146621f,-0.306197f,0.125638f}, -{0.0105684f,-0.299902f,0.125638f},{0.01083f,-0.300192f,0.125638f},{0.0174101f,-0.300062f,0.125638f}, -{0.0102536f,-0.299674f,0.125638f},{0.00810759f,-0.286008f,0.125638f},{0.00764282f,-0.285598f,0.125638f}, -{0.0191272f,-0.297548f,0.125638f},{0.0133515f,-0.286308f,0.125638f},{0.0157911f,-0.286105f,0.125638f}, -{0.013859f,-0.285951f,0.125638f},{0.0143221f,-0.285541f,0.125638f},{0.0147191f,-0.285063f,0.125638f}, -{0.0126646f,-0.291292f,0.125638f},{0.0128028f,-0.286595f,0.125638f},{0.0122189f,-0.286803f,0.125638f}, -{0.0116123f,-0.286931f,0.125638f},{0.0121324f,-0.291128f,0.125638f},{0.014035f,-0.292227f,0.125638f}, -{0.0177287f,-0.28842f,0.125638f},{0.013627f,-0.291848f,0.125638f},{0.0131664f,-0.291534f,0.125638f}, -{0.0193407f,-0.291f,0.125638f},{0.018579f,-0.289681f,0.125638f},{0.0146599f,-0.293147f,0.125638f}, -{0.0167966f,-0.287225f,0.125638f},{0.0196491f,-0.297213f,0.125638f},{0.02021f,-0.29695f,0.125638f}, -{0.0210452f,-0.295205f,0.125638f},{0.0208003f,-0.29676f,0.125638f},{0.021411f,-0.296654f,0.125638f}, -{0.0143816f,-0.292664f,0.125638f},{0.0200082f,-0.292368f,0.125638f},{0.0148642f,-0.293665f,0.125638f}, -{-0.00635281f,-0.281618f,0.125638f},{-0.00525411f,-0.280021f,0.125638f},{-0.00647672f,-0.281011f,0.125638f}, -{0.00723674f,-0.285129f,0.125638f},{0.00689651f,-0.284611f,0.125638f},{0.018655f,-0.29795f,0.125638f}, -{0.00632427f,-0.282854f,0.125638f},{0.00643592f,-0.283463f,0.125638f},{0.0178912f,-0.298922f,0.125638f}, -{0.0182407f,-0.298411f,0.125638f},{-0.010376f,-0.286942f,0.125638f},{-0.0109947f,-0.286977f,0.125638f}, -{-0.00838954f,-0.302903f,0.125638f},{-0.00368715f,-0.287681f,0.125638f},{-0.00356297f,-0.287138f,0.125638f}, -{-0.00764334f,-0.285598f,0.125638f},{-0.00632322f,-0.282854f,0.125638f},{-0.00643547f,-0.283464f,0.125638f}, -{-0.00232474f,-0.285323f,0.125638f},{-0.000829763f,-0.284603f,0.125638f},{-0.00227994f,-0.279501f,0.125638f}, -{-0.00136226f,-0.284767f,0.125638f},{-0.00662778f,-0.284053f,0.125638f},{-0.00273315f,-0.285701f,0.125638f}, -{0.00377962f,-0.27971f,0.125638f},{0.00136248f,-0.284767f,0.125638f},{0.00027877f,-0.284522f,0.125638f}, -{0.000760576f,-0.279395f,0.125638f},{-0.000278327f,-0.284521f,0.125638f},{0.00629503f,-0.282234f,0.125638f}, -{0.00525411f,-0.280021f,0.125638f},{-0.00669182f,-0.280429f,0.125638f},{0.00634749f,-0.281617f,0.125638f}, -{0.0064786f,-0.281011f,0.125638f},{0.00669182f,-0.280429f,0.125638f},{-0.0030806f,-0.286137f,0.125638f}, -{-0.00689664f,-0.284612f,0.125638f},{-0.00335928f,-0.286619f,0.125638f},{0.00227826f,-0.2795f,0.125638f}, -{0.000829582f,-0.284604f,0.125638f},{-0.0146621f,-0.296381f,0.125638f},{-0.0178906f,-0.298923f,0.125638f}, -{-0.0143836f,-0.296863f,0.125638f},{0.00408395f,-0.291443f,0.125638f},{0.00446533f,-0.291361f,0.125638f}, -{-0.00917948f,-0.286627f,0.125638f},{-0.0130106f,-0.302446f,0.125638f},{-0.00632427f,-0.319723f,0.125638f}, -{-0.00643592f,-0.319114f,0.125638f},{-0.0097673f,-0.286824f,0.125638f},{-0.0205774f,-0.293774f,0.125638f}, -{-0.0210452f,-0.295205f,0.125638f},{-0.0196492f,-0.297216f,0.125638f},{-0.0136271f,-0.291848f,0.125638f}, -{-0.0177299f,-0.288421f,0.125638f},{-0.0140346f,-0.292228f,0.125638f},{-0.00590935f,-0.291831f,0.125638f}, -{-0.0207988f,-0.296759f,0.125638f},{-0.021411f,-0.296654f,0.125638f},{-0.0140362f,-0.297299f,0.125638f}, -{-0.0174099f,-0.300063f,0.125638f},{-0.0136278f,-0.297678f,0.125638f},{-0.0182401f,-0.298411f,0.125638f}, -{-0.0148655f,-0.295862f,0.125638f},{-0.0186543f,-0.297949f,0.125638f},{-0.0202118f,-0.296955f,0.125638f}, -{-0.0149893f,-0.294207f,0.125638f},{-0.0148647f,-0.293665f,0.125638f},{-0.0200086f,-0.292369f,0.125638f}, -{-0.0193415f,-0.291002f,0.125638f},{-0.0143811f,-0.292664f,0.125638f},{-0.0185801f,-0.289683f,0.125638f}, -{-0.0146599f,-0.293146f,0.125638f},{-0.013354f,-0.28631f,0.125638f},{-0.0157911f,-0.286105f,0.125638f}, -{-0.0167976f,-0.287226f,0.125638f},{-0.0138626f,-0.285956f,0.125638f},{-0.00976653f,-0.315753f,0.125638f}, -{-0.00917901f,-0.31595f,0.125638f},{-0.00994062f,-0.311285f,0.125638f},{-0.0143217f,-0.285539f,0.125638f}, -{-0.0147191f,-0.285063f,0.125638f},{-0.00636453f,-0.292458f,0.125638f},{-0.00648481f,-0.292829f,0.125638f}, -{-0.0176127f,-0.303101f,0.125638f},{-0.0178912f,-0.303655f,0.125638f},{-0.0116126f,-0.286931f,0.125638f}, -{-0.00862289f,-0.316224f,0.125638f},{-0.00943824f,-0.311044f,0.125638f},{-0.00315227f,-0.310457f,0.125638f}, -{-0.00295749f,-0.310119f,0.125638f},{-0.0104733f,-0.311449f,0.125638f},{-0.0196491f,-0.305364f,0.125638f}, -{-0.0205772f,-0.308804f,0.125638f},{-0.0167966f,-0.315352f,0.125638f},{-0.0157911f,-0.316472f,0.125638f}, -{-0.0130106f,-0.31392f,0.125638f},{-0.0122189f,-0.315774f,0.125638f},{-0.0116123f,-0.315646f,0.125638f}, -{-0.017287f,-0.30067f,0.125638f},{-0.0174101f,-0.302515f,0.125638f},{-0.0172458f,-0.301289f,0.125638f}, -{-0.00723674f,-0.317448f,0.125638f},{-0.00689651f,-0.317966f,0.125638f},{-0.013859f,-0.316626f,0.125638f}, -{-0.0133515f,-0.316269f,0.125638f},{-0.0115815f,-0.311532f,0.125638f},{-0.0121324f,-0.311449f,0.125638f}, -{-0.014035f,-0.31035f,0.125638f},{-0.0177287f,-0.314157f,0.125638f},{-0.013627f,-0.310729f,0.125638f}, -{-0.0143816f,-0.309913f,0.125638f},{-0.018579f,-0.312896f,0.125638f},{-0.0193407f,-0.311577f,0.125638f}, -{-0.0146599f,-0.309431f,0.125638f},{-0.0149896f,-0.308369f,0.125638f},{-0.0131664f,-0.311043f,0.125638f}, -{-0.0126646f,-0.311285f,0.125638f},{-0.0210452f,-0.307372f,0.125638f},{-0.0143221f,-0.317036f,0.125638f}, -{-0.02021f,-0.305627f,0.125638f},{-0.0208003f,-0.305817f,0.125638f},{-0.0147191f,-0.317514f,0.125638f}, -{-0.021411f,-0.305923f,0.125638f},{-0.0110243f,-0.311532f,0.125638f},{0.00874495f,-0.299516f,0.125638f}, -{0.00838954f,-0.299674f,0.125638f},{-0.00523587f,-0.311135f,0.125638f},{-0.00485544f,-0.311216f,0.125638f}, -{0.0063639f,-0.308603f,0.125638f},{0.00616894f,-0.308265f,0.125638f},{-0.00629503f,-0.320343f,0.125638f}, -{-0.00377962f,-0.322867f,0.125638f},{0.0099371f,-0.31392f,0.125638f},{0.0109947f,-0.3156f,0.125638f}, -{0.0116126f,-0.315647f,0.125638f},{0.00356297f,-0.315439f,0.125638f},{0.00764334f,-0.316979f,0.125638f}, -{0.00368715f,-0.314896f,0.125638f},{0.0097673f,-0.315753f,0.125638f},{0.00917948f,-0.31595f,0.125638f}, -{0.00643547f,-0.319113f,0.125638f},{0.00232474f,-0.317255f,0.125638f},{0.00632322f,-0.319723f,0.125638f}, -{0.00810797f,-0.316569f,0.125638f},{0.00862289f,-0.316224f,0.125638f},{0.00372901f,-0.31434f,0.125638f}, -{0.00378085f,-0.322866f,0.125638f},{0.00629776f,-0.320341f,0.125638f},{0.0018645f,-0.317568f,0.125638f}, -{0.0111453f,-0.3009f,0.125638f},{0.0110251f,-0.30053f,0.125638f},{-0.0200082f,-0.31021f,0.125638f}, -{-0.0148642f,-0.308912f,0.125638f},{-0.010994f,-0.3156f,0.125638f},{0.00773683f,-0.293662f,0.125638f}, -{-0.0110251f,-0.302047f,0.125638f},{-0.0111453f,-0.301677f,0.125638f},{-0.00764282f,-0.316979f,0.125638f}, -{-0.0105684f,-0.302675f,0.125638f},{0.00807379f,-0.299904f,0.125638f},{-0.000829582f,-0.317973f,0.125638f}, -{-0.00136248f,-0.31781f,0.125638f},{-0.00227826f,-0.323077f,0.125638f},{-0.00027877f,-0.318055f,0.125638f}, -{-0.000760576f,-0.323182f,0.125638f},{0.000278327f,-0.318056f,0.125638f},{0.000829763f,-0.317974f,0.125638f}, -{0.00227994f,-0.323076f,0.125638f},{0.00136226f,-0.31781f,0.125638f},{-0.00525411f,-0.322556f,0.125638f}, -{-0.00634749f,-0.32096f,0.125638f},{-0.0064786f,-0.321566f,0.125638f},{-0.00669182f,-0.322148f,0.125638f}, -{0.00335928f,-0.315958f,0.125638f},{0.0030806f,-0.31644f,0.125638f},{0.00689664f,-0.317965f,0.125638f}, -{0.00273315f,-0.316876f,0.125638f},{0.00662778f,-0.318524f,0.125638f},{0.00525411f,-0.322556f,0.125638f}, -{0.00635281f,-0.320959f,0.125638f},{0.00669182f,-0.322148f,0.125638f},{0.00647672f,-0.321566f,0.125638f}, -{0.0176127f,-0.299476f,0.125638f},{0.00994062f,-0.291292f,0.125638f},{0.0103751f,-0.286942f,0.125638f}, -{0.00976653f,-0.286824f,0.125638f},{0.0104733f,-0.291128f,0.125638f},{0.00912617f,-0.299435f,0.125638f}, -{0.0095162f,-0.299434f,0.125638f},{0.00989767f,-0.299515f,0.125638f},{0.0140362f,-0.305278f,0.125638f}, -{0.0110245f,-0.304105f,0.125638f},{0.0177299f,-0.314156f,0.125638f},{0.0140346f,-0.310349f,0.125638f}, -{0.00822623f,-0.292664f,0.125638f},{-0.00408474f,-0.294989f,0.125638f},{-0.00446554f,-0.29507f,0.125638f}, -{-0.018655f,-0.304627f,0.125638f},{-0.0191272f,-0.305029f,0.125638f},{0.00315227f,-0.29212f,0.125638f}, -{0.00295755f,-0.292458f,0.125638f},{0.00341361f,-0.294601f,0.125638f},{0.00749845f,-0.300901f,0.125638f}, -{0.00761862f,-0.300531f,0.125638f},{0.0126655f,-0.304343f,0.125638f},{0.0131672f,-0.304585f,0.125638f}, -{0.0115822f,-0.3041f,0.125638f},{0.0122191f,-0.315775f,0.125638f},{0.012803f,-0.315983f,0.125638f}, -{0.00590935f,-0.310746f,0.125638f},{0.00636453f,-0.310119f,0.125638f},{0.00648481f,-0.309748f,0.125638f}, -{-0.00408362f,-0.311134f,0.125638f},{-0.00446544f,-0.311216f,0.125638f},{-0.00807379f,-0.302673f,0.125638f}, -{-0.00430393f,-0.303071f,0.125638f},{0.00283746f,-0.304987f,0.125638f},{0.00408474f,-0.307589f,0.125638f}, -{0.00446554f,-0.307508f,0.125638f},{-0.00874495f,-0.303061f,0.125638f},{-0.0172871f,-0.301907f,0.125638f}, -{0.00761515f,-0.294207f,0.125638f},{0.0085695f,-0.292226f,0.125638f},{-0.00723717f,-0.28513f,0.125638f}, -{-0.000762504f,-0.279395f,0.125638f},{0.00662806f,-0.284053f,0.125638f},{0.00341281f,-0.291831f,0.125638f}, -{0.00372825f,-0.291601f,0.125638f},{0.00279662f,-0.293216f,0.125638f},{0.00283723f,-0.292829f,0.125638f}, -{0.00283764f,-0.293604f,0.125638f},{-0.00335595f,-0.289852f,0.125638f},{0.00795154f,-0.293149f,0.125638f}, -{-0.00369782f,-0.304126f,0.125638f},{0.00295819f,-0.293974f,0.125638f},{0.00315308f,-0.294312f,0.125638f}, -{-0.00523619f,-0.294989f,0.125638f},{-0.00616894f,-0.294312f,0.125638f},{-0.0063639f,-0.293974f,0.125638f}, -{-0.00273651f,-0.290775f,0.125638f},{-0.00232523f,-0.291153f,0.125638f},{-0.00356376f,-0.289336f,0.125638f}, -{-0.0131672f,-0.297992f,0.125638f},{-0.0176123f,-0.299477f,0.125638f},{-0.00616972f,-0.29212f,0.125638f}, -{-0.00648443f,-0.293604f,0.125638f},{-0.00652539f,-0.293216f,0.125638f},{-0.00559278f,-0.29483f,0.125638f}, -{-0.00590766f,-0.294602f,0.125638f},{-0.0048551f,-0.29507f,0.125638f},{-0.00307294f,-0.290333f,0.125638f}, -{-0.0110245f,-0.298472f,0.125638f},{-0.0095162f,-0.303143f,0.125638f},{-0.00368758f,-0.288793f,0.125638f}, -{-0.00897792f,-0.31073f,0.125638f},{-0.0103751f,-0.315635f,0.125638f},{-0.0128028f,-0.315982f,0.125638f}, -{-0.0182407f,-0.304166f,0.125638f},{-0.01083f,-0.302385f,0.125638f},{-0.0102536f,-0.302903f,0.125638f}, -{-0.00912617f,-0.303143f,0.125638f},{-0.00989767f,-0.303062f,0.125638f},{-0.0115822f,-0.298477f,0.125638f}, -{-0.0121333f,-0.298398f,0.125638f},{-0.0104733f,-0.298402f,0.125638f},{-0.00994038f,-0.298234f,0.125638f}, -{-0.00462174f,-0.301897f,0.125638f},{-0.00761862f,-0.302046f,0.125638f},{-0.00449935f,-0.302494f,0.125638f}, -{-0.00749845f,-0.301676f,0.125638f},{-0.00761515f,-0.30837f,0.125638f},{-0.0085695f,-0.310351f,0.125638f}, -{-0.00822623f,-0.309913f,0.125638f},{-0.00773683f,-0.308915f,0.125638f},{-0.00403697f,-0.303619f,0.125638f}, -{-0.0126655f,-0.298234f,0.125638f},{0.00559278f,-0.307747f,0.125638f},{0.00723717f,-0.317447f,0.125638f}, -{0.000762504f,-0.323182f,0.125638f},{-0.00662806f,-0.318524f,0.125638f},{-0.00341302f,-0.310747f,0.125638f}, -{-0.00372824f,-0.310976f,0.125638f},{-0.00279657f,-0.309361f,0.125638f},{-0.00283721f,-0.309748f,0.125638f}, -{-0.0028377f,-0.308973f,0.125638f},{0.00120604f,-0.305791f,0.125638f},{-0.00795154f,-0.309428f,0.125638f}, -{0.003698f,-0.304126f,0.125638f},{0.00329612f,-0.304585f,0.125638f},{0.0048551f,-0.307507f,0.125638f}, -{0.00523619f,-0.307588f,0.125638f},{0.00781324f,-0.300193f,0.125638f},{0.00430606f,-0.303073f,0.125638f}, -{0.00356376f,-0.313241f,0.125638f},{-0.00283752f,-0.304986f,0.125638f},{-0.00329569f,-0.304584f,0.125638f}, -{0.00178338f,-0.305595f,0.125638f},{0.000608186f,-0.30591f,0.125638f},{5.18512e-017f,-0.30595f,0.125638f}, -{-0.0034133f,-0.307976f,0.125638f},{-0.00233082f,-0.305324f,0.125638f},{-0.00295825f,-0.308603f,0.125638f}, -{-0.00120688f,-0.30579f,0.125638f},{-0.00315303f,-0.308265f,0.125638f},{0.0176123f,-0.3031f,0.125638f}, -{0.010376f,-0.315635f,0.125638f},{0.00616972f,-0.310457f,0.125638f},{0.00648443f,-0.308973f,0.125638f}, -{0.00652539f,-0.309361f,0.125638f},{0.00449528f,-0.302494f,0.125638f},{0.00590766f,-0.307976f,0.125638f}, -{0.00273651f,-0.311802f,0.125638f},{0.00335595f,-0.312725f,0.125638f},{0.00232523f,-0.311424f,0.125638f}, -{0.00307294f,-0.312244f,0.125638f},{0.00461789f,-0.301897f,0.125638f},{0.00403651f,-0.30362f,0.125638f}, -{0.00368758f,-0.313784f,0.125638f},{0.00233031f,-0.305326f,0.125638f},{-0.00060875f,-0.30591f,0.125638f}, -{-0.00178418f,-0.305594f,0.125638f},{-0.00781324f,-0.302384f,0.125638f},{0.0216239f,-0.307539f,0.12559f}, -{0.0211432f,-0.30901f,0.12559f},{0.0217239f,-0.309222f,0.125434f},{0.0192916f,-0.317439f,0.12373f}, -{0.0203623f,-0.316066f,0.12373f},{0.0200519f,-0.315841f,0.12429f},{0.0210134f,-0.314414f,0.12429f}, -{0.0213388f,-0.314617f,0.12373f},{0.0186268f,-0.316882f,0.124775f},{0.0181976f,-0.316523f,0.125161f}, -{0.0175107f,-0.318126f,0.124775f},{0.016671f,-0.317318f,0.125434f},{0.0158563f,-0.318767f,0.125232f}, -{0.0171072f,-0.317738f,0.125161f},{0.0151138f,-0.317949f,0.125592f},{0.0154952f,-0.318369f,0.125455f}, -{0.0162253f,-0.31689f,0.12559f},{0.0218746f,-0.312922f,0.12429f},{0.0222133f,-0.313102f,0.12373f}, -{0.0226291f,-0.311376f,0.12429f},{0.0215683f,-0.31476f,0.123126f},{0.0217015f,-0.314844f,0.122512f}, -{0.0224522f,-0.313229f,0.123126f},{0.021363f,-0.315459f,0.121909f},{0.0222009f,-0.314106f,0.121909f}, -{0.0207085f,-0.316317f,0.122512f},{0.0204426f,-0.316757f,0.121909f},{0.0196196f,-0.317713f,0.122512f}, -{0.0225908f,-0.313303f,0.122512f},{0.0229535f,-0.312704f,0.121909f},{0.0183695f,-0.31917f,0.121909f}, -{0.0194435f,-0.317996f,0.121909f},{0.018444f,-0.319023f,0.122512f},{0.0172245f,-0.320275f,0.121909f}, -{0.0171931f,-0.320241f,0.122497f},{0.02337f,-0.311706f,0.122512f},{0.0236175f,-0.311258f,0.121909f}, -{0.0240343f,-0.310066f,0.122512f},{0.0241903f,-0.309773f,0.121909f},{0.024671f,-0.308256f,0.121909f}, -{0.0245807f,-0.308394f,0.122512f},{0.0250097f,-0.306702f,0.122497f},{0.024876f,-0.306673f,0.123065f}, -{0.0229794f,-0.311532f,0.12373f},{0.0181357f,-0.318727f,0.12373f},{0.0189975f,-0.317193f,0.12429f}, -{0.0250554f,-0.306712f,0.121909f},{0.0232266f,-0.311642f,0.123126f},{0.0233369f,-0.308035f,0.124775f}, -{0.0235497f,-0.306386f,0.124929f},{0.0227992f,-0.307879f,0.125161f},{0.0239879f,-0.306481f,0.124546f}, -{0.0238014f,-0.308169f,0.12429f},{0.0209535f,-0.312432f,0.125161f},{0.0216762f,-0.310951f,0.125161f}, -{0.0211235f,-0.310705f,0.125434f},{0.0219851f,-0.306047f,0.125592f},{0.0244299f,-0.308351f,0.123126f}, -{0.0246584f,-0.306626f,0.123602f},{0.0241699f,-0.308275f,0.12373f},{0.0238868f,-0.310012f,0.123126f}, -{0.0205814f,-0.316225f,0.123126f},{0.0194991f,-0.317613f,0.123126f},{0.0183308f,-0.318914f,0.123126f}, -{0.0171019f,-0.32014f,0.123062f},{0.02436f,-0.306561f,0.1241f},{0.0236326f,-0.309919f,0.12373f}, -{0.0169523f,-0.319975f,0.1236f},{0.0222178f,-0.307711f,0.125434f},{0.0230629f,-0.306281f,0.125233f}, -{0.0232723f,-0.309787f,0.12429f},{0.0196606f,-0.315557f,0.124775f},{0.0178592f,-0.318461f,0.12429f}, -{0.0167476f,-0.31975f,0.124098f},{0.0221874f,-0.311179f,0.124775f},{0.0228181f,-0.309621f,0.124775f}, -{0.0214477f,-0.312695f,0.124775f},{0.0206034f,-0.314158f,0.124775f},{0.0164907f,-0.319467f,0.124546f}, -{0.0222924f,-0.309429f,0.125161f},{0.0201286f,-0.313861f,0.125161f},{0.0192076f,-0.315228f,0.125161f}, -{0.0161909f,-0.319136f,0.124927f},{0.0225375f,-0.306167f,0.125456f},{0.0204192f,-0.312148f,0.125434f}, -{0.0196153f,-0.313541f,0.125434f},{0.0187178f,-0.314873f,0.125434f},{0.0172595f,-0.315738f,0.12559f}, -{0.0177335f,-0.316134f,0.125434f},{0.0205588f,-0.310453f,0.12559f},{0.0198733f,-0.311858f,0.12559f}, -{0.019091f,-0.313213f,0.12559f},{0.0182174f,-0.314509f,0.12559f},{0.000885136f,-0.326703f,0.123126f}, -{0.00261846f,-0.326311f,0.12373f},{0.000875717f,-0.326433f,0.12373f},{0.00441602f,-0.326491f,0.122512f}, -{0.00266296f,-0.326736f,0.122512f},{0.00264799f,-0.326787f,0.121909f},{0.00257853f,-0.32593f,0.12429f}, -{0.000884103f,-0.326909f,0.121909f},{0.00609912f,-0.325976f,0.123126f},{0.00613678f,-0.326129f,0.122512f}, -{0.0077748f,-0.325524f,0.123065f},{0.00612578f,-0.326167f,0.121909f},{0.00781658f,-0.325654f,0.122497f}, -{0.00539858f,-0.323141f,0.12559f},{0.00388481f,-0.32346f,0.12559f},{0.00399151f,-0.324069f,0.125434f}, -{0.00783085f,-0.325699f,0.121909f},{0.00439916f,-0.326544f,0.121909f},{0.00749724f,-0.324659f,0.124546f}, -{0.00582624f,-0.324872f,0.124775f},{0.00594221f,-0.325341f,0.12429f},{0.00246996f,-0.324892f,0.125161f}, -{0.00240697f,-0.32429f,0.125434f},{0.000826054f,-0.325007f,0.125161f},{0.005692f,-0.324329f,0.125161f}, -{0.00736026f,-0.324232f,0.124929f},{0.000890602f,-0.32686f,0.122512f},{0.00264662f,-0.32658f,0.123126f}, -{-0.00427461f,-0.325693f,0.12429f},{-0.00603421f,-0.325714f,0.12373f},{-0.0043408f,-0.326071f,0.12373f}, -{0.00687127f,-0.322708f,0.125592f},{-0.000860185f,-0.326049f,0.12429f},{-0.00261652f,-0.326312f,0.12373f}, -{-0.000873503f,-0.326433f,0.12373f},{0.000862365f,-0.326049f,0.12429f},{-0.00582624f,-0.324872f,0.124775f}, -{-0.00419119f,-0.325217f,0.124775f},{-0.00409462f,-0.324665f,0.125161f},{-0.00554685f,-0.323741f,0.125434f}, -{-0.00720884f,-0.32376f,0.125232f},{-0.005692f,-0.324329f,0.125161f},{-0.00257663f,-0.32593f,0.12429f}, -{-0.00687127f,-0.322708f,0.125592f},{-0.00704464f,-0.323248f,0.125455f},{-0.00539858f,-0.323141f,0.12559f}, -{-0.00088835f,-0.32686f,0.122512f},{-0.000882898f,-0.326703f,0.123126f},{-0.000883894f,-0.326909f,0.121909f}, -{-0.002661f,-0.326737f,0.122512f},{-0.00264771f,-0.326787f,0.121909f},{-0.00441458f,-0.326492f,0.122512f}, -{-0.00439897f,-0.326544f,0.121909f},{-0.00612769f,-0.326175f,0.121909f},{-0.00613678f,-0.326129f,0.122512f}, -{-0.00783085f,-0.325699f,0.121909f},{0.00770679f,-0.325312f,0.123602f},{0.00603421f,-0.325714f,0.12373f}, -{0.00438891f,-0.326337f,0.123126f},{-0.00264467f,-0.326581f,0.123126f},{-0.00609912f,-0.325976f,0.123126f}, -{-0.00438748f,-0.326337f,0.123126f},{-0.00781658f,-0.325654f,0.122497f},{-0.0077751f,-0.325525f,0.123062f}, -{0.00761353f,-0.325021f,0.1241f},{0.00434221f,-0.32607f,0.12373f},{-0.00770709f,-0.325313f,0.1236f}, -{0.00554685f,-0.323741f,0.125434f},{0.00720812f,-0.323758f,0.125233f},{0.004276f,-0.325692f,0.12429f}, -{-0.00252634f,-0.325449f,0.124775f},{-0.00594221f,-0.325341f,0.12429f},{-0.00761404f,-0.325023f,0.124098f}, -{0.00252821f,-0.325449f,0.124775f},{0.00419255f,-0.325216f,0.124775f},{0.000845536f,-0.325566f,0.124775f}, -{-0.000843398f,-0.325566f,0.124775f},{-0.00749724f,-0.324659f,0.124546f},{0.00409595f,-0.324665f,0.125161f}, -{-0.000823965f,-0.325007f,0.125161f},{-0.00246814f,-0.324892f,0.125161f},{-0.00736095f,-0.324234f,0.124927f}, -{0.00704393f,-0.323246f,0.125456f},{0.000804989f,-0.324402f,0.125434f},{-0.000802953f,-0.324402f,0.125434f}, -{-0.0024052f,-0.324291f,0.125434f},{-0.00388354f,-0.32346f,0.12559f},{-0.00399021f,-0.324069f,0.125434f}, -{0.00234263f,-0.323675f,0.12559f},{0.00078347f,-0.323784f,0.12559f},{-0.000781489f,-0.323784f,0.12559f}, -{-0.0023409f,-0.323676f,0.12559f},{-0.0217002f,-0.314846f,0.122512f},{-0.02058f,-0.316226f,0.123126f}, -{-0.021567f,-0.314762f,0.123126f},{-0.0207071f,-0.316319f,0.122512f},{-0.0213629f,-0.315459f,0.121909f}, -{-0.0204426f,-0.316757f,0.121909f},{-0.020361f,-0.316067f,0.12373f},{-0.0213375f,-0.314619f,0.12373f}, -{-0.0200505f,-0.315842f,0.12429f},{-0.0183308f,-0.318914f,0.123126f},{-0.018444f,-0.319023f,0.122512f}, -{-0.0171015f,-0.32014f,0.123063f},{-0.0169508f,-0.319974f,0.123604f},{-0.0172584f,-0.315738f,0.12559f}, -{-0.0177324f,-0.316135f,0.125434f},{-0.0162253f,-0.31689f,0.12559f},{-0.0171936f,-0.320241f,0.122494f}, -{-0.0183693f,-0.31917f,0.121909f},{-0.0172245f,-0.320275f,0.121909f},{-0.0196183f,-0.317714f,0.122512f}, -{-0.0194434f,-0.317996f,0.121909f},{-0.0171072f,-0.317738f,0.125161f},{-0.0175107f,-0.318126f,0.124775f}, -{-0.0161913f,-0.319136f,0.124927f},{-0.0201275f,-0.313863f,0.125161f},{-0.0192063f,-0.315229f,0.125161f}, -{-0.0187165f,-0.314874f,0.125434f},{-0.0151117f,-0.317946f,0.125592f},{-0.0178592f,-0.318461f,0.12429f}, -{-0.0164907f,-0.319467f,0.124546f},{-0.0232721f,-0.309789f,0.12429f},{-0.0241699f,-0.308275f,0.12373f}, -{-0.0236324f,-0.30992f,0.12373f},{-0.0210122f,-0.314416f,0.12429f},{-0.0222178f,-0.307711f,0.125434f}, -{-0.0230652f,-0.306281f,0.125232f},{-0.0227992f,-0.307879f,0.125161f},{-0.0224512f,-0.313231f,0.123126f}, -{-0.0225899f,-0.313305f,0.122512f},{-0.0233369f,-0.308035f,0.124775f},{-0.0228179f,-0.309623f,0.124775f}, -{-0.0222922f,-0.309431f,0.125161f},{-0.0229789f,-0.311534f,0.12373f},{-0.0226285f,-0.311378f,0.12429f}, -{-0.0218736f,-0.312924f,0.12429f},{-0.0222123f,-0.313104f,0.12373f},{-0.0219851f,-0.306047f,0.125592f}, -{-0.0225398f,-0.306167f,0.125455f},{-0.0216239f,-0.307539f,0.12559f},{-0.0222011f,-0.314107f,0.121909f}, -{-0.0233694f,-0.311708f,0.122512f},{-0.0229536f,-0.312705f,0.121909f},{-0.0240341f,-0.310067f,0.122512f}, -{-0.0236177f,-0.311258f,0.121909f},{-0.0241882f,-0.309773f,0.121909f},{-0.0245807f,-0.308394f,0.122512f}, -{-0.0246627f,-0.308254f,0.121909f},{-0.0250554f,-0.306712f,0.121909f},{-0.0250097f,-0.306702f,0.122497f}, -{-0.0181357f,-0.318727f,0.12373f},{-0.0194979f,-0.317614f,0.123126f},{-0.023226f,-0.311644f,0.123126f}, -{-0.0238866f,-0.310013f,0.123126f},{-0.0244299f,-0.308351f,0.123126f},{-0.024877f,-0.306673f,0.123062f}, -{-0.0167454f,-0.319747f,0.124102f},{-0.0192904f,-0.31744f,0.12373f},{-0.0246594f,-0.306626f,0.1236f}, -{-0.016671f,-0.317318f,0.125434f},{-0.0158556f,-0.318766f,0.125233f},{-0.0189963f,-0.317194f,0.12429f}, -{-0.0221869f,-0.311181f,0.124775f},{-0.0238014f,-0.308169f,0.12429f},{-0.0243617f,-0.306562f,0.124098f}, -{-0.0196592f,-0.315558f,0.124775f},{-0.0186256f,-0.316883f,0.124775f},{-0.0206021f,-0.31416f,0.124775f}, -{-0.0214468f,-0.312697f,0.124775f},{-0.0239879f,-0.306481f,0.124546f},{-0.0181964f,-0.316524f,0.125161f}, -{-0.0209526f,-0.312434f,0.125161f},{-0.0216757f,-0.310953f,0.125161f},{-0.0235519f,-0.306387f,0.124927f}, -{-0.0154922f,-0.318366f,0.125456f},{-0.0196142f,-0.313542f,0.125434f},{-0.0204183f,-0.31215f,0.125434f}, -{-0.0211229f,-0.310707f,0.125434f},{-0.021143f,-0.309011f,0.12559f},{-0.0217237f,-0.309223f,0.125434f}, -{-0.0182162f,-0.314511f,0.12559f},{-0.0190899f,-0.313215f,0.12559f},{-0.0198725f,-0.31186f,0.12559f}, -{-0.0205583f,-0.310455f,0.12559f},{-0.0225908f,-0.289274f,0.122512f},{-0.0232266f,-0.290935f,0.123126f}, -{-0.0224522f,-0.289348f,0.123126f},{-0.02337f,-0.290871f,0.122512f},{-0.0229794f,-0.291045f,0.12373f}, -{-0.0222133f,-0.289475f,0.12373f},{-0.0226291f,-0.291201f,0.12429f},{-0.0244299f,-0.294227f,0.123126f}, -{-0.0245807f,-0.294183f,0.122512f},{-0.024876f,-0.295904f,0.123065f},{-0.0246584f,-0.295951f,0.123602f}, -{-0.0211432f,-0.293567f,0.12559f},{-0.0217239f,-0.293355f,0.125434f},{-0.0216239f,-0.295038f,0.12559f}, -{-0.0250097f,-0.295875f,0.122497f},{-0.0240343f,-0.292511f,0.122512f},{-0.0227992f,-0.294698f,0.125161f}, -{-0.0233369f,-0.294543f,0.124775f},{-0.0235497f,-0.296191f,0.124929f},{-0.0209535f,-0.290145f,0.125161f}, -{-0.0216762f,-0.291626f,0.125161f},{-0.0211235f,-0.291872f,0.125434f},{-0.0219851f,-0.29653f,0.125592f}, -{-0.0238014f,-0.294408f,0.12429f},{-0.0239879f,-0.296096f,0.124546f},{-0.0189975f,-0.285384f,0.12429f}, -{-0.0181357f,-0.28385f,0.12373f},{-0.0192916f,-0.285138f,0.12373f},{-0.0218746f,-0.289655f,0.12429f}, -{-0.016671f,-0.285259f,0.125434f},{-0.0158576f,-0.283808f,0.125231f},{-0.0171072f,-0.284839f,0.125161f}, -{-0.0215683f,-0.287817f,0.123126f},{-0.0217015f,-0.287733f,0.122512f},{-0.0175107f,-0.284451f,0.124775f}, -{-0.0186268f,-0.285695f,0.124775f},{-0.0181976f,-0.286054f,0.125161f},{-0.0203623f,-0.286511f,0.12373f}, -{-0.0200519f,-0.286736f,0.12429f},{-0.0210134f,-0.288163f,0.12429f},{-0.0213388f,-0.28796f,0.12373f}, -{-0.0151117f,-0.284631f,0.125592f},{-0.0154943f,-0.284209f,0.125455f},{-0.0162253f,-0.285687f,0.12559f}, -{-0.0207085f,-0.28626f,0.122512f},{-0.0196196f,-0.284864f,0.122512f},{-0.018444f,-0.283554f,0.122512f}, -{-0.0171936f,-0.282336f,0.122494f},{-0.0241699f,-0.294302f,0.12373f},{-0.0238868f,-0.292565f,0.123126f}, -{-0.0205814f,-0.286352f,0.123126f},{-0.0194991f,-0.284964f,0.123126f},{-0.0183308f,-0.283663f,0.123126f}, -{-0.0171022f,-0.282437f,0.12306f},{-0.02436f,-0.296016f,0.1241f},{-0.0236326f,-0.292658f,0.12373f}, -{-0.0169519f,-0.282602f,0.123601f},{-0.0222178f,-0.294866f,0.125434f},{-0.0230629f,-0.296296f,0.125233f}, -{-0.0232723f,-0.29279f,0.12429f},{-0.0196606f,-0.28702f,0.124775f},{-0.0178592f,-0.284116f,0.12429f}, -{-0.0167464f,-0.282829f,0.1241f},{-0.0221874f,-0.291398f,0.124775f},{-0.0228181f,-0.292956f,0.124775f}, -{-0.0214477f,-0.289882f,0.124775f},{-0.0206034f,-0.288419f,0.124775f},{-0.0164907f,-0.283111f,0.124546f}, -{-0.0222924f,-0.293148f,0.125161f},{-0.0201286f,-0.288716f,0.125161f},{-0.0192076f,-0.287349f,0.125161f}, -{-0.0161924f,-0.283439f,0.124925f},{-0.0225375f,-0.29641f,0.125456f},{-0.0204192f,-0.290429f,0.125434f}, -{-0.0196153f,-0.289036f,0.125434f},{-0.0187178f,-0.287705f,0.125434f},{-0.0172595f,-0.286839f,0.12559f}, -{-0.0177335f,-0.286443f,0.125434f},{-0.0205588f,-0.292124f,0.12559f},{-0.0198733f,-0.290719f,0.12559f}, -{-0.019091f,-0.289364f,0.12559f},{-0.0182174f,-0.288068f,0.12559f},{-0.000885136f,-0.275874f,0.123126f}, -{-0.00261846f,-0.276266f,0.12373f},{-0.000875717f,-0.276144f,0.12373f},{-0.00441602f,-0.276086f,0.122512f}, -{-0.00266296f,-0.275841f,0.122512f},{-0.00257853f,-0.276647f,0.12429f},{-0.00609912f,-0.276601f,0.123126f}, -{-0.00613678f,-0.276448f,0.122512f},{-0.0077748f,-0.277053f,0.123065f},{-0.00781658f,-0.276923f,0.122497f}, -{-0.00539858f,-0.279436f,0.12559f},{-0.00388481f,-0.279117f,0.12559f},{-0.00399151f,-0.278508f,0.125434f}, -{-0.00749724f,-0.277918f,0.124546f},{-0.00582624f,-0.277705f,0.124775f},{-0.00594221f,-0.277236f,0.12429f}, -{-0.00246996f,-0.277685f,0.125161f},{-0.00240697f,-0.278287f,0.125434f},{-0.000826054f,-0.27757f,0.125161f}, -{-0.005692f,-0.278249f,0.125161f},{-0.00736026f,-0.278345f,0.124929f},{-0.000890602f,-0.275717f,0.122512f}, -{-0.00264662f,-0.275997f,0.123126f},{0.00427461f,-0.276884f,0.12429f},{0.00603421f,-0.276863f,0.12373f}, -{0.0043408f,-0.276506f,0.12373f},{-0.00687127f,-0.279869f,0.125592f},{0.000860185f,-0.276528f,0.12429f}, -{0.00261652f,-0.276265f,0.12373f},{0.000873503f,-0.276144f,0.12373f},{-0.000862365f,-0.276528f,0.12429f}, -{0.00582624f,-0.277705f,0.124775f},{0.00419119f,-0.27736f,0.124775f},{0.00409462f,-0.277912f,0.125161f}, -{0.00554685f,-0.278836f,0.125434f},{0.00720884f,-0.278817f,0.125232f},{0.005692f,-0.278249f,0.125161f}, -{0.00257663f,-0.276647f,0.12429f},{0.00687127f,-0.279869f,0.125592f},{0.00704464f,-0.279329f,0.125455f}, -{0.00539858f,-0.279436f,0.12559f},{0.00088835f,-0.275717f,0.122512f},{0.000882898f,-0.275874f,0.123126f}, -{0.002661f,-0.27584f,0.122512f},{0.00441458f,-0.276085f,0.122512f},{0.00613678f,-0.276448f,0.122512f}, -{-0.00770679f,-0.277265f,0.123602f},{-0.00603421f,-0.276863f,0.12373f},{-0.00438891f,-0.27624f,0.123126f}, -{0.00264467f,-0.275996f,0.123126f},{0.00609912f,-0.276601f,0.123126f},{0.00438748f,-0.27624f,0.123126f}, -{0.00781658f,-0.276923f,0.122497f},{0.0077751f,-0.277052f,0.123062f},{-0.00761353f,-0.277556f,0.1241f}, -{-0.00434221f,-0.276507f,0.12373f},{0.00770709f,-0.277264f,0.1236f},{-0.00554685f,-0.278836f,0.125434f}, -{-0.00720812f,-0.278819f,0.125233f},{-0.004276f,-0.276885f,0.12429f},{0.00252634f,-0.277128f,0.124775f}, -{0.00594221f,-0.277236f,0.12429f},{0.00761404f,-0.277554f,0.124098f},{-0.00252821f,-0.277128f,0.124775f}, -{-0.00419255f,-0.277361f,0.124775f},{-0.000845536f,-0.277011f,0.124775f},{0.000843398f,-0.277011f,0.124775f}, -{0.00749724f,-0.277918f,0.124546f},{-0.00409595f,-0.277912f,0.125161f},{0.000823965f,-0.27757f,0.125161f}, -{0.00246814f,-0.277685f,0.125161f},{0.00736095f,-0.278343f,0.124927f},{-0.00704393f,-0.279331f,0.125456f}, -{-0.000804989f,-0.278175f,0.125434f},{0.000802953f,-0.278175f,0.125434f},{0.0024052f,-0.278286f,0.125434f}, -{0.00388354f,-0.279117f,0.12559f},{0.00399021f,-0.278508f,0.125434f},{-0.00234263f,-0.278902f,0.12559f}, -{-0.00078347f,-0.278793f,0.12559f},{0.000781489f,-0.278793f,0.12559f},{0.0023409f,-0.278901f,0.12559f}, -{0.0217002f,-0.287732f,0.122512f},{0.02058f,-0.286351f,0.123126f},{0.021567f,-0.287815f,0.123126f}, -{0.0207071f,-0.286258f,0.122512f},{0.020361f,-0.28651f,0.12373f},{0.0213375f,-0.287958f,0.12373f}, -{0.0200505f,-0.286735f,0.12429f},{0.0183308f,-0.283663f,0.123126f},{0.018444f,-0.283554f,0.122512f}, -{0.0171012f,-0.282438f,0.123065f},{0.0169516f,-0.282602f,0.123602f},{0.0172584f,-0.286839f,0.12559f}, -{0.0177324f,-0.286442f,0.125434f},{0.0162253f,-0.285687f,0.12559f},{0.0171931f,-0.282336f,0.122497f}, -{0.0196183f,-0.284863f,0.122512f},{0.0171072f,-0.284839f,0.125161f},{0.0175107f,-0.284451f,0.124775f}, -{0.0161894f,-0.283443f,0.124929f},{0.0201275f,-0.288714f,0.125161f},{0.0192063f,-0.287348f,0.125161f}, -{0.0187165f,-0.287703f,0.125434f},{0.0151138f,-0.284628f,0.125592f},{0.0178592f,-0.284116f,0.12429f}, -{0.0164907f,-0.283111f,0.124546f},{0.0232721f,-0.292788f,0.12429f},{0.0241699f,-0.294302f,0.12373f}, -{0.0236324f,-0.292657f,0.12373f},{0.0210122f,-0.288161f,0.12429f},{0.0222178f,-0.294866f,0.125434f}, -{0.0230652f,-0.296296f,0.125232f},{0.0227992f,-0.294698f,0.125161f},{0.0224512f,-0.289346f,0.123126f}, -{0.0225899f,-0.289272f,0.122512f},{0.0233369f,-0.294543f,0.124775f},{0.0228179f,-0.292954f,0.124775f}, -{0.0222922f,-0.293146f,0.125161f},{0.0229789f,-0.291043f,0.12373f},{0.0226285f,-0.291199f,0.12429f}, -{0.0218736f,-0.289653f,0.12429f},{0.0222123f,-0.289473f,0.12373f},{0.0219851f,-0.29653f,0.125592f}, -{0.0225398f,-0.29641f,0.125455f},{0.0216239f,-0.295038f,0.12559f},{0.0233694f,-0.290869f,0.122512f}, -{0.0240341f,-0.29251f,0.122512f},{0.0245807f,-0.294183f,0.122512f},{0.0250097f,-0.295875f,0.122497f}, -{0.0181357f,-0.28385f,0.12373f},{0.0194979f,-0.284964f,0.123126f},{0.023226f,-0.290933f,0.123126f}, -{0.0238866f,-0.292564f,0.123126f},{0.0244299f,-0.294227f,0.123126f},{0.024877f,-0.295904f,0.123062f}, -{0.0167465f,-0.282829f,0.1241f},{0.0192904f,-0.285137f,0.12373f},{0.0246594f,-0.295951f,0.1236f}, -{0.016671f,-0.285259f,0.125434f},{0.0158548f,-0.283812f,0.125233f},{0.0189963f,-0.285384f,0.12429f}, -{0.0221869f,-0.291396f,0.124775f},{0.0238014f,-0.294408f,0.12429f},{0.0243617f,-0.296015f,0.124098f}, -{0.0196592f,-0.287019f,0.124775f},{0.0186256f,-0.285694f,0.124775f},{0.0206021f,-0.288418f,0.124775f}, -{0.0214468f,-0.28988f,0.124775f},{0.0239879f,-0.296096f,0.124546f},{0.0181964f,-0.286053f,0.125161f}, -{0.0209526f,-0.290143f,0.125161f},{0.0216757f,-0.291624f,0.125161f},{0.0235519f,-0.296191f,0.124927f}, -{0.0154936f,-0.28421f,0.125456f},{0.0196142f,-0.289035f,0.125434f},{0.0204183f,-0.290427f,0.125434f}, -{0.0211229f,-0.291871f,0.125434f},{0.021143f,-0.293566f,0.12559f},{0.0217237f,-0.293354f,0.125434f}, -{0.0182162f,-0.288066f,0.12559f},{0.0190899f,-0.289362f,0.12559f},{0.0198725f,-0.290718f,0.12559f}, -{0.0205583f,-0.292122f,0.12559f},{0.00414391f,-0.307489f,0.100469f},{0.00139737f,-0.303708f,0.100469f}, -{0.00179665f,-0.303429f,0.100469f},{0.00285439f,-0.308179f,0.100469f},{0.00351607f,-0.307865f,0.100469f}, -{0.00216513f,-0.308425f,0.100469f},{0.000956049f,-0.303916f,0.100469f},{0.0047319f,-0.307053f,0.100469f}, -{0.00527427f,-0.306562f,0.100469f},{0.00145499f,-0.308603f,0.100469f},{0.000485772f,-0.304043f,0.100469f}, -{0.00214182f,-0.303085f,0.100469f},{0.00576579f,-0.30602f,0.100469f},{0.000730938f,-0.30871f,0.100469f}, -{5.39729e-017f,-0.304085f,0.100469f},{0.00620174f,-0.305432f,0.100469f},{0.00242194f,-0.302686f,0.100469f}, -{5.29897e-017f,-0.308746f,0.100469f},{-0.000731236f,-0.30871f,0.100469f},{-0.00145532f,-0.308602f,0.100469f}, -{-0.000485107f,-0.304043f,0.100469f},{-0.00216527f,-0.308424f,0.100469f},{-0.000955564f,-0.303917f,0.100469f}, -{0.00689072f,-0.304142f,0.100469f},{0.00657793f,-0.304804f,0.100469f},{-0.00351606f,-0.307865f,0.100469f}, -{-0.00285433f,-0.308178f,0.100469f},{0.00713697f,-0.303453f,0.100469f},{0.00262754f,-0.302244f,0.100469f}, -{0.00275363f,-0.301773f,0.100469f},{-0.00139499f,-0.303708f,0.100469f},{0.00742217f,-0.302019f,0.100469f}, -{0.00731456f,-0.302743f,0.100469f},{-0.00214373f,-0.303089f,0.100469f},{-0.00178917f,-0.303421f,0.100469f}, -{-0.00527358f,-0.306561f,0.100469f},{-0.00657692f,-0.304803f,0.100469f},{-0.00688983f,-0.304142f,0.100469f}, -{-0.00262887f,-0.302246f,0.100469f},{-0.00275512f,-0.301775f,0.100469f},{-0.00742136f,-0.302019f,0.100469f}, -{-0.0071365f,-0.303453f,0.100469f},{-0.00731416f,-0.302743f,0.100469f},{-0.00473148f,-0.307052f,0.100469f}, -{-0.00414378f,-0.307489f,0.100469f},{-0.00620074f,-0.305431f,0.100469f},{-0.00242212f,-0.302687f,0.100469f}, -{-0.0057649f,-0.306018f,0.100469f},{0.00060826f,-0.289127f,0.101401f},{0.00178435f,-0.288815f,0.101401f}, -{0.002331f,-0.288545f,0.101401f},{0.00216527f,-0.308424f,0.101401f},{0.00536018f,-0.312009f,0.101401f}, -{0.00742136f,-0.302019f,0.101401f},{0.0121618f,-0.301897f,0.101401f},{0.0071365f,-0.303453f,0.101401f}, -{0.0127432f,-0.30362f,0.101401f},{0.00688983f,-0.304142f,0.101401f},{0.00403701f,-0.286839f,0.101401f}, -{0.00430572f,-0.282725f,0.101401f},{0.014297f,-0.31439f,0.101401f},{-0.00279832f,-0.280033f,0.101401f}, -{0.0214014f,-0.301897f,0.101401f},{-0.00689197f,-0.280986f,0.101401f},{-0.00820481f,-0.28148f,0.101401f}, -{0.021279f,-0.302494f,0.101401f},{0.0210836f,-0.303071f,0.101401f},{0.0134836f,-0.304585f,0.101401f}, -{0.00657692f,-0.304803f,0.101401f},{0.0130817f,-0.304126f,0.101401f},{-0.00893219f,-0.312768f,0.101401f}, -{-0.00372602f,-0.315267f,0.101401f},{-0.00406291f,-0.315783f,0.101401f},{0.0208166f,-0.303619f,0.101401f}, -{0.0200754f,-0.304584f,0.101401f},{0.0204775f,-0.304126f,0.101401f},{0.0196172f,-0.304986f,0.101401f}, -{0.0139105f,-0.312566f,0.101401f},{0.0141391f,-0.312881f,0.101401f},{-0.00216513f,-0.308425f,0.101401f}, -{-0.00235358f,-0.314045f,0.101401f},{-0.00285439f,-0.308179f,0.101401f},{0.0191105f,-0.305324f,0.101401f}, -{0.0185639f,-0.305594f,0.101401f},{0.0167797f,-0.30595f,0.101401f},{0.0173884f,-0.30591f,0.101401f}, -{0.0179866f,-0.30579f,0.101401f},{-0.0141364f,-0.285168f,0.101401f},{-0.00948265f,-0.282059f,0.101401f}, -{-0.00121835f,-0.313576f,0.101401f},{-0.00145499f,-0.308603f,0.101401f},{-0.000730938f,-0.30871f,0.101401f}, -{0.0161715f,-0.30591f,0.101401f},{-0.00180244f,-0.31377f,0.101401f},{0.00620074f,-0.305431f,0.101401f}, -{-0.00286368f,-0.31439f,0.101401f},{0.0143784f,-0.313619f,0.101401f},{-0.0107514f,-0.289341f,0.101401f}, -{-0.0109097f,-0.289697f,0.101401f},{-0.00140229f,-0.279893f,0.101401f},{0.00329545f,-0.281213f,0.101401f}, -{0.00369728f,-0.281671f,0.101401f},{0.0057649f,-0.306018f,0.101401f},{0.00466102f,-0.284509f,0.101401f}, -{0.00462104f,-0.2839f,0.101401f},{0.00731416f,-0.302743f,0.101401f},{0.0124736f,-0.303073f,0.101401f}, -{0.0121612f,-0.291674f,0.101401f},{0.0109346f,-0.292565f,0.101401f},{0.0113045f,-0.292445f,0.101401f}, -{0.0123195f,-0.291319f,0.101401f},{0.0116418f,-0.292251f,0.101401f},{0.0119314f,-0.29199f,0.101401f}, -{0.0136206f,-0.312305f,0.101401f},{0.0136193f,-0.315322f,0.101401f},{0.013282f,-0.315516f,0.101401f}, -{0.013283f,-0.31211f,0.101401f},{0.0155736f,-0.305791f,0.101401f},{0.00473148f,-0.307052f,0.101401f}, -{0.00527358f,-0.306561f,0.101401f},{-0.0170097f,-0.288236f,0.101401f},{-0.00751912f,-0.321368f,0.101401f}, -{-0.00885348f,-0.320816f,0.101401f},{-0.00460913f,-0.318761f,0.101401f},{0.00285433f,-0.308178f,0.101401f}, -{0.00351606f,-0.307865f,0.101401f},{0.000731236f,-0.30871f,0.101401f},{0.00145532f,-0.308602f,0.101401f}, -{-0.0151604f,-0.286127f,0.101401f},{-0.0161195f,-0.287151f,0.101401f},{-0.0124736f,-0.299504f,0.101401f}, -{-0.0122844f,-0.300083f,0.101401f},{5.29897e-017f,-0.308746f,0.101401f},{-0.0043287f,-0.316339f,0.101401f}, -{-0.00916198f,-0.313083f,0.101401f},{-0.0107204f,-0.295928f,0.101401f},{-0.00869272f,-0.312031f,0.101401f}, -{-0.00332386f,-0.3148f,0.101401f},{-0.017827f,-0.289376f,0.101401f},{-0.00731456f,-0.302743f,0.101401f}, -{-0.00713697f,-0.303453f,0.101401f},{-0.00742217f,-0.302019f,0.101401f},{-0.0196172f,-0.297591f,0.101401f}, -{-0.0200754f,-0.297993f,0.101401f},{-0.0210285f,-0.297105f,0.101401f},{-0.0158194f,-0.315761f,0.101401f}, -{-0.0167576f,-0.314664f,0.101401f},{-0.0176198f,-0.313505f,0.101401f},{-0.00462997f,-0.317531f,0.101401f}, -{-0.0101477f,-0.320176f,0.101401f},{-0.0125926f,-0.318642f,0.101401f},{-0.013732f,-0.317755f,0.101401f}, -{-0.00466034f,-0.318147f,0.101401f},{-0.00426727f,-0.319943f,0.101401f},{-0.00615062f,-0.321828f,0.101401f}, -{-0.00447731f,-0.319363f,0.101401f},{-0.00165506f,-0.322422f,0.101401f},{-0.00190339f,-0.322647f,0.101401f}, -{-0.0022162f,-0.322169f,0.101401f},{-0.00362862f,-0.320993f,0.101401f},{-0.00475417f,-0.322196f,0.101401f}, -{-0.00398274f,-0.320489f,0.101401f},{-0.00321095f,-0.321446f,0.101401f},{-0.00273734f,-0.32184f,0.101401f}, -{-0.00333373f,-0.322455f,0.101401f},{-0.00106651f,-0.322603f,0.101401f},{-0.000459362f,-0.322708f,0.101401f}, -{-0.0101588f,-0.313659f,0.101401f},{-0.011396f,-0.31945f,0.101401f},{-0.0148092f,-0.316793f,0.101401f}, -{-0.0184021f,-0.312292f,0.101401f},{-0.0212465f,-0.304168f,0.101401f},{-0.0210045f,-0.305592f,0.101401f}, -{-0.0206672f,-0.306996f,0.101401f},{0.0122844f,-0.302494f,0.101401f},{-0.0047319f,-0.307053f,0.101401f}, -{-0.00893177f,-0.310904f,0.101401f},{-0.00916039f,-0.310589f,0.101401f},{-0.019101f,-0.311028f,0.101401f}, -{-0.00978889f,-0.313539f,0.101401f},{-0.0213921f,-0.302732f,0.101401f},{-0.0111395f,-0.290013f,0.101401f}, -{-0.0114291f,-0.290273f,0.101401f},{-0.00576579f,-0.30602f,0.101401f},{-0.00527427f,-0.306562f,0.101401f}, -{-0.00945026f,-0.310327f,0.101401f},{-0.00978794f,-0.310132f,0.101401f},{-0.0101578f,-0.310012f,0.101401f}, -{-0.00620174f,-0.305432f,0.101401f},{-0.00877329f,-0.31126f,0.101401f},{-0.00414391f,-0.307489f,0.101401f}, -{-0.00351607f,-0.307865f,0.101401f},{-0.0045188f,-0.316925f,0.101401f},{-0.0094516f,-0.313344f,0.101401f}, -{-0.000614697f,-0.313451f,0.101401f},{0.0139422f,-0.304987f,0.101401f},{0.00414378f,-0.307489f,0.101401f}, -{0.0144494f,-0.305326f,0.101401f},{0.0124009f,-0.290548f,0.101401f},{0.011933f,-0.289496f,0.101401f}, -{0.00430656f,-0.286292f,0.101401f},{0.00178272f,-0.280205f,0.101401f},{-0.00418236f,-0.280262f,0.101401f}, -{-0.0106702f,-0.28896f,0.101401f},{-0.00554911f,-0.280579f,0.101401f},{-0.0130817f,-0.298451f,0.101401f}, -{-0.0134836f,-0.297992f,0.101401f},{-0.013052f,-0.284278f,0.101401f},{-0.0185679f,-0.290568f,0.101401f}, -{-0.0203026f,-0.294396f,0.101401f},{-0.0185639f,-0.296983f,0.101401f},{-0.0207099f,-0.295739f,0.101401f}, -{-0.00689072f,-0.304142f,0.101401f},{-0.0119116f,-0.283461f,0.101401f},{-0.0117654f,-0.287061f,0.101401f}, -{-0.0121353f,-0.286941f,0.101401f},{-0.0192293f,-0.291805f,0.101401f},{-0.0149963f,-0.296982f,0.101401f}, -{-0.0121618f,-0.30068f,0.101401f},{-0.0109093f,-0.287833f,0.101401f},{-0.0111379f,-0.287518f,0.101401f}, -{-0.0106699f,-0.28857f,0.101401f},{-0.01072f,-0.28272f,0.101401f},{-0.0114278f,-0.287256f,0.101401f}, -{0.00120563f,-0.289004f,0.101401f},{0.0116431f,-0.289234f,0.101401f},{0.0113054f,-0.289039f,0.101401f}, -{0.0124007f,-0.290938f,0.101401f},{0.00462115f,-0.285117f,0.101401f},{0.00283787f,-0.288207f,0.101401f}, -{0.00329614f,-0.287805f,0.101401f},{0.00369829f,-0.287346f,0.101401f},{0.0123201f,-0.290166f,0.101401f}, -{0.0121616f,-0.28981f,0.101401f},{0.0109356f,-0.288919f,0.101401f},{0.0149963f,-0.305595f,0.101401f}, -{0.0129131f,-0.311989f,0.101401f},{0.0129121f,-0.315636f,0.101401f},{0.0139089f,-0.315061f,0.101401f}, -{0.0141387f,-0.314745f,0.101401f},{0.0143782f,-0.314009f,0.101401f},{0.0142976f,-0.313237f,0.101401f}, -{-0.0202361f,-0.308374f,0.101401f},{-0.0197133f,-0.30972f,0.101401f},{-0.00869244f,-0.311641f,0.101401f}, -{-0.00877392f,-0.312412f,0.101401f},{-0.00657793f,-0.304804f,0.101401f},{-0.0107508f,-0.288189f,0.101401f}, -{0.00450236f,-0.285715f,0.101401f},{0.00450189f,-0.283302f,0.101401f},{0.00403597f,-0.282178f,0.101401f}, -{0.00283697f,-0.280811f,0.101401f},{0.00233026f,-0.280472f,0.101401f},{0.0006084f,-0.279887f,0.101401f}, -{0.00120559f,-0.280009f,0.101401f},{-0.0210836f,-0.299506f,0.101401f},{-0.0213948f,-0.299886f,0.101401f}, -{-0.0212572f,-0.29849f,0.101401f},{-0.0198084f,-0.293083f,0.101401f},{-0.0167797f,-0.296628f,0.101401f}, -{-0.0173884f,-0.296667f,0.101401f},{-0.0161715f,-0.296667f,0.101401f},{-0.0127432f,-0.298958f,0.101401f}, -{-0.0155736f,-0.296786f,0.101401f},{-0.0139422f,-0.29759f,0.101401f},{-0.0144494f,-0.297252f,0.101401f}, -{-0.0121363f,-0.290588f,0.101401f},{-0.0117664f,-0.290468f,0.101401f},{-0.0179866f,-0.296787f,0.101401f}, -{-0.0191105f,-0.297253f,0.101401f},{-0.0204775f,-0.298452f,0.101401f},{-0.0208166f,-0.298958f,0.101401f}, -{-0.0214014f,-0.30068f,0.101401f},{-0.021279f,-0.300083f,0.101401f},{0.0220868f,-0.314303f,0.120045f}, -{0.0197356f,-0.31765f,0.120045f},{-0.0164263f,-0.281003f,0.120045f},{-0.0174654f,-0.281891f,0.120045f}, -{0.0227481f,-0.313109f,0.120045f},{-0.0130507f,-0.278683f,0.120045f},{-0.0142159f,-0.279397f,0.120045f}, -{0.0243386f,-0.30934f,0.120045f},{-0.00935393f,-0.27692f,0.120045f},{-0.0106164f,-0.277443f,0.120045f}, -{0.0253094f,-0.305366f,0.120045f},{-0.00542685f,-0.275757f,0.120045f},{-0.00408328f,-0.275508f,0.120045f}, -{-0.0067556f,-0.276076f,0.120045f},{-0.00806585f,-0.276464f,0.120045f},{-0.00136583f,-0.275231f,0.120045f}, -{-0.00272847f,-0.27533f,0.120045f},{0.025591f,-0.302653f,0.120045f},{0.0254905f,-0.304014f,0.120045f}, -{-0.0118498f,-0.278032f,0.120045f},{0.0247326f,-0.308033f,0.120045f},{0.0250564f,-0.306708f,0.120045f}, -{-0.0153421f,-0.280171f,0.120045f},{0.0233448f,-0.311881f,0.120045f},{0.0238755f,-0.310624f,0.120045f}, -{-0.0184567f,-0.282831f,0.120045f},{-0.0193973f,-0.283823f,0.120045f},{0.0213629f,-0.31546f,0.120045f}, -{-0.0202847f,-0.284862f,0.120045f},{-0.0211166f,-0.285946f,0.120045f},{-0.0218906f,-0.287072f,0.120045f}, -{0.0205784f,-0.316577f,0.120045f},{-0.0226048f,-0.288237f,0.120045f},{-0.0232569f,-0.289438f,0.120045f}, -{0.0188369f,-0.318677f,0.120045f},{-0.0238452f,-0.290672f,0.120045f},{0.0178847f,-0.319655f,0.120045f}, -{-0.0243681f,-0.291934f,0.120045f},{0.0168818f,-0.320581f,0.120045f},{-0.0248242f,-0.293222f,0.120045f}, -{0.0158311f,-0.321452f,0.120045f},{-0.0252123f,-0.294533f,0.120045f},{0.0147355f,-0.322266f,0.120045f}, -{-0.0255314f,-0.295862f,0.120045f},{0.0135981f,-0.323021f,0.120045f},{-0.0257804f,-0.297205f,0.120045f}, -{0.0124222f,-0.323714f,0.120045f},{-0.0259588f,-0.29856f,0.120045f},{0.011211f,-0.324343f,0.120045f}, -{-0.0260659f,-0.299922f,0.120045f},{0.00996802f,-0.324907f,0.120045f},{-0.0261017f,-0.301289f,0.120045f}, -{0.00869678f,-0.325404f,0.120045f},{-0.0255903f,-0.302653f,0.120045f},{-0.0260659f,-0.302655f,0.120045f}, -{0.00740092f,-0.325833f,0.120045f},{-0.0254908f,-0.304013f,0.120045f},{-0.0259586f,-0.304017f,0.120045f}, -{0.00608407f,-0.326192f,0.120045f},{-0.0253091f,-0.305366f,0.120045f},{-0.0257802f,-0.305372f,0.120045f}, -{0.00474994f,-0.32648f,0.120045f},{0.00340235f,-0.326697f,0.120045f},{0.000682229f,-0.326915f,0.120045f}, -{-0.0250563f,-0.306707f,0.120045f},{-0.0255311f,-0.306716f,0.120045f},{-0.00272834f,-0.327248f,0.120045f}, -{-0.00340291f,-0.326697f,0.120045f},{-0.00408304f,-0.327069f,0.120045f},{-0.0238754f,-0.310623f,0.120045f}, -{-0.0243383f,-0.30934f,0.120045f},{-0.0243677f,-0.310643f,0.120045f},{-0.00675524f,-0.326501f,0.120045f}, -{-0.00740123f,-0.325832f,0.120045f},{-0.00806539f,-0.326113f,0.120045f},{-0.0226042f,-0.31434f,0.120045f}, -{-0.0227481f,-0.313108f,0.120045f},{-0.0232562f,-0.313139f,0.120045f},{-0.0118493f,-0.324546f,0.120045f}, -{-0.010616f,-0.325134f,0.120045f},{-0.011211f,-0.324342f,0.120045f},{-0.0202843f,-0.317715f,0.120045f}, -{-0.0205783f,-0.316576f,0.120045f},{-0.0211162f,-0.316631f,0.120045f},{-0.0164256f,-0.321574f,0.120045f}, -{-0.0168818f,-0.320581f,0.120045f},{-0.0174647f,-0.320686f,0.120045f},{-0.0130502f,-0.323894f,0.120045f}, -{-0.0124221f,-0.323713f,0.120045f},{-0.0188368f,-0.318677f,0.120045f},{-0.0193967f,-0.318755f,0.120045f}, -{-0.018456f,-0.319746f,0.120045f},{-0.0178847f,-0.319655f,0.120045f},{-0.0153414f,-0.322406f,0.120045f}, -{-0.0142153f,-0.32318f,0.120045f},{-0.0147355f,-0.322266f,0.120045f},{-0.0135981f,-0.32302f,0.120045f}, -{-0.0197355f,-0.31765f,0.120045f},{-0.0158312f,-0.321452f,0.120045f},{-0.00869705f,-0.325404f,0.120045f}, -{-0.00935349f,-0.325657f,0.120045f},{-0.00996818f,-0.324907f,0.120045f},{-0.0220867f,-0.314302f,0.120045f}, -{-0.0218902f,-0.315505f,0.120045f},{-0.0213628f,-0.315459f,0.120045f},{-0.00475041f,-0.32648f,0.120045f}, -{-0.00542662f,-0.32682f,0.120045f},{-0.00608443f,-0.326192f,0.120045f},{-0.0233449f,-0.311881f,0.120045f}, -{-0.0238446f,-0.311906f,0.120045f},{-0.000682695f,-0.326915f,0.120045f},{-0.00136576f,-0.327345f,0.120045f}, -{-0.00204572f,-0.326842f,0.120045f},{-0.0252122f,-0.308045f,0.120045f},{-0.0247324f,-0.308033f,0.120045f}, -{-0.024824f,-0.309355f,0.120045f},{0.00204515f,-0.326842f,0.120045f},{-0.00544975f,-0.326815f,0.106062f}, -{-0.00410773f,-0.327065f,0.106062f},{-0.00275036f,-0.327245f,0.106062f},{-0.00935782f,-0.325655f,0.106062f}, -{-0.00677384f,-0.326496f,0.106062f},{-0.0141962f,-0.323192f,0.106062f},{-0.0130343f,-0.323903f,0.106062f}, -{-0.0118389f,-0.324551f,0.106062f},{-0.0106125f,-0.325135f,0.106062f},{-0.0174549f,-0.320695f,0.106062f}, -{-0.015322f,-0.32242f,0.106062f},{-0.0211314f,-0.316611f,0.106062f},{-0.0202988f,-0.317698f,0.106062f}, -{-0.0194069f,-0.318743f,0.106062f},{-0.0184567f,-0.319745f,0.106062f},{-0.0232623f,-0.313128f,0.106062f}, -{-0.0219036f,-0.315485f,0.106062f},{-0.0252074f,-0.308063f,0.106062f},{-0.0248204f,-0.309366f,0.106062f}, -{-0.0243664f,-0.310647f,0.106062f},{-0.0238467f,-0.311901f,0.106062f},{-0.0257765f,-0.305396f,0.106062f}, -{-0.0259565f,-0.304039f,0.106062f},{-0.0255265f,-0.306739f,0.106062f},{-0.0260653f,-0.299908f,0.106062f}, -{-0.0261017f,-0.301289f,0.106062f},{-0.0260652f,-0.302669f,0.106062f},{-0.0255265f,-0.295839f,0.106062f}, -{-0.0257766f,-0.297181f,0.106062f},{-0.0259565f,-0.298538f,0.106062f},{-0.0248205f,-0.293211f,0.106062f}, -{-0.0252075f,-0.294515f,0.106062f},{-0.0238468f,-0.290676f,0.106062f},{-0.0232624f,-0.28945f,0.106062f}, -{-0.0243666f,-0.291931f,0.106062f},{-0.0219036f,-0.287092f,0.106062f},{-0.0226143f,-0.288254f,0.106062f}, -{-0.0202989f,-0.284879f,0.106062f},{-0.0211315f,-0.285967f,0.106062f},{-0.0184567f,-0.282832f,0.106062f}, -{-0.0194069f,-0.283834f,0.106062f},{-0.0174549f,-0.281882f,0.106062f},{-0.0164092f,-0.28099f,0.106062f}, -{-0.0153222f,-0.280157f,0.106062f},{-0.0141964f,-0.279385f,0.106062f},{-0.0130346f,-0.278674f,0.106062f}, -{-0.0118391f,-0.278026f,0.106062f},{-0.0106128f,-0.277442f,0.106062f},{-0.00935809f,-0.276922f,0.106062f}, -{-0.00807765f,-0.276468f,0.106062f},{-0.00677408f,-0.276081f,0.106062f},{-0.00544996f,-0.275762f,0.106062f}, -{-0.0041079f,-0.275512f,0.106062f},{-0.00275048f,-0.275332f,0.106062f},{-0.00138032f,-0.275223f,0.106062f}, -{-0.0226142f,-0.314323f,0.106062f},{-0.0164091f,-0.321587f,0.106062f},{-0.0080774f,-0.326109f,0.106062f}, -{-0.00138025f,-0.327354f,0.106062f},{-0.0164242f,-0.315071f,0.106062f},{-0.0128032f,-0.318487f,0.106062f}, -{-0.00849194f,-0.320976f,0.106062f},{-0.00372282f,-0.322402f,0.106062f},{-0.00124674f,-0.322693f,0.106062f}, -{-0.00248901f,-0.322583f,0.106062f},{-0.00733302f,-0.321436f,0.106062f},{-0.00962222f,-0.320449f,0.106062f}, -{-0.01072f,-0.319857f,0.106062f},{-0.0117816f,-0.319202f,0.106062f},{-0.0155951f,-0.316002f,0.106062f}, -{-0.0147132f,-0.316884f,0.106062f},{-0.0137815f,-0.317713f,0.106062f},{-0.0185679f,-0.312009f,0.106062f}, -{-0.0179131f,-0.313071f,0.106062f},{-0.0171977f,-0.314092f,0.106062f},{-0.0191599f,-0.310912f,0.106062f}, -{-0.0196869f,-0.309781f,0.106062f},{-0.0201474f,-0.308622f,0.106062f},{-0.0205397f,-0.307438f,0.106062f}, -{-0.0208625f,-0.306233f,0.106062f},{-0.0211148f,-0.305012f,0.106062f},{-0.0212956f,-0.303778f,0.106062f}, -{-0.0214044f,-0.302535f,0.106062f},{-0.0214407f,-0.301289f,0.106062f},{-0.0214044f,-0.300042f,0.106062f}, -{-0.0212958f,-0.298799f,0.106062f},{-0.021115f,-0.297565f,0.106062f},{-0.0208629f,-0.296344f,0.106062f}, -{-0.0205401f,-0.295139f,0.106062f},{-0.0201478f,-0.293955f,0.106062f},{-0.0196872f,-0.292796f,0.106062f}, -{-0.0185682f,-0.290568f,0.106062f},{-0.00248899f,-0.279996f,0.106062f},{-0.00124708f,-0.279883f,0.106062f}, -{-0.0164246f,-0.287506f,0.106062f},{-0.00494506f,-0.280426f,0.106062f},{-0.00614966f,-0.280749f,0.106062f}, -{-0.0137818f,-0.284864f,0.106062f},{-0.0147135f,-0.285693f,0.106062f},{-0.0107205f,-0.28272f,0.106062f}, -{-0.0117819f,-0.283375f,0.106062f},{-0.0128035f,-0.28409f,0.106062f},{-0.00849255f,-0.281601f,0.106062f}, -{-0.00733349f,-0.281141f,0.106062f},{-0.00962282f,-0.282128f,0.106062f},{-0.00372197f,-0.280183f,0.106062f}, -{-0.0155954f,-0.286575f,0.106062f},{-0.0179135f,-0.289507f,0.106062f},{-0.0171982f,-0.288485f,0.106062f}, -{-0.0191601f,-0.291666f,0.106062f},{-0.00494408f,-0.322149f,0.106062f},{-0.00614928f,-0.321829f,0.106062f}, -{-0.00496191f,-0.322147f,0.10513f},{-0.00374312f,-0.3224f,0.10513f},{-0.00250793f,-0.322582f,0.10513f}, -{-0.00849036f,-0.320976f,0.10513f},{-0.00616138f,-0.321825f,0.10513f},{-0.0127873f,-0.318499f,0.10513f}, -{-0.0117655f,-0.319213f,0.10513f},{-0.0107068f,-0.319865f,0.10513f},{-0.00961408f,-0.320453f,0.10513f}, -{-0.0155998f,-0.315997f,0.10513f},{-0.0137691f,-0.317724f,0.10513f},{-0.018576f,-0.311996f,0.10513f}, -{-0.0179242f,-0.313054f,0.10513f},{-0.0172102f,-0.314076f,0.10513f},{-0.0201457f,-0.308627f,0.10513f}, -{-0.0196879f,-0.309779f,0.10513f},{-0.0191643f,-0.310903f,0.10513f},{-0.0212935f,-0.303797f,0.10513f}, -{-0.0211114f,-0.305032f,0.10513f},{-0.0208586f,-0.306251f,0.10513f},{-0.0205363f,-0.30745f,0.10513f}, -{-0.0214407f,-0.301289f,0.10513f},{-0.0214037f,-0.300029f,0.10513f},{-0.0214037f,-0.302548f,0.10513f}, -{-0.0211115f,-0.297545f,0.10513f},{-0.0212936f,-0.298781f,0.10513f},{-0.0201457f,-0.29395f,0.10513f}, -{-0.0205363f,-0.295127f,0.10513f},{-0.0208587f,-0.296327f,0.10513f},{-0.0191643f,-0.291674f,0.10513f}, -{-0.019688f,-0.292798f,0.10513f},{-0.0172102f,-0.288501f,0.10513f},{-0.0179243f,-0.289523f,0.10513f}, -{-0.018576f,-0.290582f,0.10513f},{-0.0156004f,-0.28658f,0.10513f},{-0.0164352f,-0.287519f,0.10513f}, -{-0.0147088f,-0.285689f,0.10513f},{-0.0137693f,-0.284853f,0.10513f},{-0.0127873f,-0.284078f,0.10513f}, -{-0.0117656f,-0.283364f,0.10513f},{-0.010707f,-0.282713f,0.10513f},{-0.0096143f,-0.282124f,0.10513f}, -{-0.00849054f,-0.281601f,0.10513f},{-0.00733859f,-0.281143f,0.10513f},{-0.00616144f,-0.280752f,0.10513f}, -{-0.00374334f,-0.280177f,0.10513f},{-0.00496208f,-0.28043f,0.10513f},{-0.00250813f,-0.279995f,0.10513f}, -{-0.00125938f,-0.279885f,0.10513f},{-0.0164352f,-0.315058f,0.10513f},{-0.0147082f,-0.316889f,0.10513f}, -{-0.0073385f,-0.321434f,0.10513f},{-0.00125925f,-0.322692f,0.10513f},{-0.015889f,-0.321997f,0.10513f}, -{-0.0261017f,-0.301289f,0.10513f},{-0.0260458f,-0.302996f,0.10513f},{-0.0241144f,-0.311278f,0.10513f}, -{-0.0256f,-0.306381f,0.10513f},{-0.0252122f,-0.308045f,0.10513f},{-0.0234094f,-0.312833f,0.10513f}, -{-0.0217023f,-0.31579f,0.10513f},{-0.0207075f,-0.317179f,0.10513f},{-0.00675524f,-0.326501f,0.10513f}, -{-0.00509193f,-0.326889f,0.10513f},{-0.00170673f,-0.327326f,0.10513f},{-0.0130502f,-0.323894f,0.10513f}, -{-0.011544f,-0.324699f,0.10513f},{-0.00998811f,-0.325403f,0.10513f},{-0.00838954f,-0.326005f,0.10513f}, -{-0.0145006f,-0.322992f,0.10513f},{-0.018456f,-0.319746f,0.10513f},{-0.0172093f,-0.320913f,0.10513f}, -{-0.00340673f,-0.327168f,0.10513f},{-0.0196237f,-0.318499f,0.10513f},{-0.0226042f,-0.31434f,0.10513f}, -{-0.0247162f,-0.309679f,0.10513f},{-0.0258783f,-0.304696f,0.10513f},{-0.0260458f,-0.299582f,0.10513f}, -{-0.0258785f,-0.297882f,0.10513f},{-0.0247166f,-0.292898f,0.10513f},{-0.0252123f,-0.294533f,0.10513f}, -{-0.0256002f,-0.296196f,0.10513f},{-0.024115f,-0.2913f,0.10513f},{-0.02341f,-0.289744f,0.10513f}, -{-0.0226048f,-0.288237f,0.10513f},{-0.0207077f,-0.285398f,0.10513f},{-0.0217027f,-0.286787f,0.10513f}, -{-0.0196242f,-0.284078f,0.10513f},{-0.01721f,-0.281664f,0.10513f},{-0.0145012f,-0.279585f,0.10513f}, -{-0.0158895f,-0.28058f,0.10513f},{-0.0130507f,-0.278683f,0.10513f},{-0.0115442f,-0.277878f,0.10513f}, -{-0.00340717f,-0.27541f,0.10513f},{-0.00170718f,-0.275248f,0.10513f},{-0.00509216f,-0.275688f,0.10513f}, -{-0.0067556f,-0.276076f,0.10513f},{-0.00839014f,-0.276572f,0.10513f},{-0.0184567f,-0.282831f,0.10513f}, -{-0.00998851f,-0.277174f,0.10513f},{-0.0114195f,-0.281509f,0.10252f},{-0.0131871f,-0.282642f,0.10252f}, -{-0.0123517f,-0.279895f,0.104011f},{-0.0179085f,-0.287115f,0.10252f},{-0.0164595f,-0.285455f,0.10252f}, -{-0.0148769f,-0.28396f,0.10252f},{-0.0224459f,-0.297069f,0.10252f},{-0.0219419f,-0.29495f,0.10252f}, -{-0.0212291f,-0.292866f,0.10252f},{-0.022839f,-0.301289f,0.10252f},{-0.0227427f,-0.299191f,0.10252f}, -{-0.0123517f,-0.322682f,0.104011f},{-0.0114195f,-0.321068f,0.10252f},{-0.0101514f,-0.321748f,0.10252f}, -{-0.00882321f,-0.322354f,0.10252f},{-0.00744093f,-0.322881f,0.10252f},{-0.00601179f,-0.323322f,0.10252f}, -{-0.00454389f,-0.323671f,0.10252f},{-0.00304618f,-0.323923f,0.10252f},{-0.00152821f,-0.324076f,0.10252f}, -{-0.00650255f,-0.325121f,0.104011f},{-0.00491482f,-0.325498f,0.104011f},{-0.0109801f,-0.323418f,0.104011f}, -{-0.00329485f,-0.325771f,0.104011f},{-0.00165296f,-0.325937f,0.104011f},{-0.00804836f,-0.324644f,0.104011f}, -{-0.00954347f,-0.324074f,0.104011f},{-0.0191994f,-0.288919f,0.10252f},{-0.0203114f,-0.290845f,0.10252f}, -{-0.0160918f,-0.282545f,0.104011f},{-0.0247034f,-0.301289f,0.104011f},{-0.0245988f,-0.29902f,0.104011f}, -{-0.0242781f,-0.296725f,0.104011f},{-0.0237331f,-0.294434f,0.104011f},{-0.0229622f,-0.292179f,0.104011f}, -{-0.02197f,-0.289994f,0.104011f},{-0.0207674f,-0.28791f,0.104011f},{-0.0193711f,-0.285958f,0.104011f}, -{-0.0178041f,-0.284163f,0.104011f},{-0.0142649f,-0.28112f,0.104011f},{0.0255992f,-0.302654f,0.121909f}, -{0.0254901f,-0.304016f,0.121909f},{0.0137506f,-0.322924f,0.121909f},{0.0155417f,-0.321676f,0.121909f}, -{0.0118616f,-0.324015f,0.121909f},{0.00988475f,-0.324942f,0.121909f},{-0.00988506f,-0.324942f,0.121909f}, -{-0.0118618f,-0.324015f,0.121909f},{-0.015542f,-0.321676f,0.121909f},{-0.0137508f,-0.322924f,0.121909f}, -{-0.0253087f,-0.305369f,0.121909f},{-0.0254902f,-0.304016f,0.121909f},{-0.0255992f,-0.302654f,0.121909f}, -{0.0253087f,-0.305369f,0.121909f},{-0.0121592f,-0.300676f,0.104198f},{-0.0127415f,-0.298961f,0.104198f}, -{-0.0124735f,-0.299505f,0.104198f},{-0.0122784f,-0.300079f,0.104198f},{-0.0139458f,-0.297588f,0.104198f}, -{-0.0130793f,-0.298454f,0.104198f},{-0.0134838f,-0.297993f,0.104198f},{-0.0161672f,-0.296668f,0.104198f}, -{-0.0155702f,-0.296787f,0.104198f},{-0.014996f,-0.296982f,0.104198f},{-0.0173925f,-0.296668f,0.104198f}, -{-0.0179895f,-0.296787f,0.104198f},{-0.0167797f,-0.296628f,0.104198f},{-0.0191075f,-0.29725f,0.104198f}, -{-0.0185634f,-0.296982f,0.104198f},{-0.0200755f,-0.297993f,0.104198f},{-0.0196139f,-0.297588f,0.104198f}, -{-0.0204802f,-0.298455f,0.104198f},{-0.020818f,-0.298961f,0.104198f},{-0.0210859f,-0.299505f,0.104198f}, -{-0.0212811f,-0.300079f,0.104198f},{-0.0214003f,-0.300676f,0.104198f},{-0.0144523f,-0.29725f,0.104198f}, -{-0.00978795f,-0.310131f,0.110723f},{-0.00945021f,-0.310326f,0.110723f},{-0.0101588f,-0.310011f,0.110723f}, -{-0.00916026f,-0.310587f,0.110723f},{-0.00893114f,-0.310903f,0.110723f},{-0.00877327f,-0.31126f,0.110723f}, -{-0.00869249f,-0.311641f,0.110723f},{-0.00869285f,-0.312031f,0.110723f},{-0.00893415f,-0.312768f,0.110723f}, -{-0.00877489f,-0.312413f,0.110723f},{-0.00945258f,-0.313343f,0.110723f},{-0.00916327f,-0.313083f,0.110723f}, -{-0.0101599f,-0.313658f,0.110723f},{-0.00978972f,-0.313538f,0.110723f},{0.0132829f,-0.312109f,0.110723f}, -{0.0136207f,-0.312304f,0.110723f},{0.0129121f,-0.311988f,0.110723f},{0.0139106f,-0.312565f,0.110723f}, -{0.0141397f,-0.312881f,0.110723f},{0.0142976f,-0.313237f,0.110723f},{0.0143784f,-0.313619f,0.110723f}, -{0.014378f,-0.314009f,0.110723f},{0.0141367f,-0.314746f,0.110723f},{0.014296f,-0.31439f,0.110723f}, -{0.0136183f,-0.315321f,0.110723f},{0.0139076f,-0.31506f,0.110723f},{0.012911f,-0.315636f,0.110723f}, -{0.0132812f,-0.315515f,0.110723f},{0.0113054f,-0.289038f,0.110723f},{0.0116432f,-0.289233f,0.110723f}, -{0.0109345f,-0.288917f,0.110723f},{0.0119331f,-0.289494f,0.110723f},{0.0121622f,-0.28981f,0.110723f}, -{0.0123201f,-0.290167f,0.110723f},{0.0124009f,-0.290548f,0.110723f},{0.0124005f,-0.290938f,0.110723f}, -{0.0121592f,-0.291675f,0.110723f},{0.0123185f,-0.291319f,0.110723f},{0.0116408f,-0.29225f,0.110723f}, -{0.0119301f,-0.291989f,0.110723f},{0.0109335f,-0.292565f,0.110723f},{0.0113037f,-0.292444f,0.110723f}, -{-0.0117655f,-0.28706f,0.110723f},{-0.0114277f,-0.287255f,0.110723f},{-0.0121363f,-0.28694f,0.110723f}, -{-0.0111378f,-0.287516f,0.110723f},{-0.0109086f,-0.287832f,0.110723f},{-0.0107508f,-0.288189f,0.110723f}, -{-0.01067f,-0.28857f,0.110723f},{-0.0106704f,-0.28896f,0.110723f},{-0.0109117f,-0.289697f,0.110723f}, -{-0.0107524f,-0.289342f,0.110723f},{-0.0114301f,-0.290272f,0.110723f},{-0.0111408f,-0.290012f,0.110723f}, -{-0.0121374f,-0.290587f,0.110723f},{-0.0117672f,-0.290467f,0.110723f},{-0.000612842f,-0.313448f,0.104198f}, -{-0.00232777f,-0.31403f,0.104198f},{-0.00120978f,-0.313567f,0.104198f},{-0.00178369f,-0.313762f,0.104198f}, -{-0.00370055f,-0.315234f,0.104198f},{-0.00403832f,-0.315741f,0.104198f},{-0.00329584f,-0.314772f,0.104198f}, -{-0.00462066f,-0.317456f,0.104198f},{-0.00430621f,-0.316285f,0.104198f},{-0.00450141f,-0.316859f,0.104198f}, -{-0.00450127f,-0.319278f,0.104198f},{-0.00466102f,-0.318068f,0.104198f},{-0.00462052f,-0.318681f,0.104198f}, -{-0.00403818f,-0.320396f,0.104198f},{-0.00370041f,-0.320902f,0.104198f},{-0.00430621f,-0.319852f,0.104198f}, -{-0.00329584f,-0.321364f,0.104198f},{-0.00283386f,-0.321769f,0.104198f},{-0.00232743f,-0.322107f,0.104198f}, -{-0.00178369f,-0.322374f,0.104198f},{-0.00120944f,-0.32257f,0.104198f},{-0.000612502f,-0.322689f,0.104198f}, -{-0.0028342f,-0.314368f,0.104198f},{0.0121592f,-0.301901f,0.104198f},{0.0127415f,-0.303616f,0.104198f}, -{0.0124735f,-0.303072f,0.104198f},{0.0122784f,-0.302498f,0.104198f},{0.0139458f,-0.304989f,0.104198f}, -{0.0130793f,-0.304123f,0.104198f},{0.0134838f,-0.304584f,0.104198f},{0.0161672f,-0.305909f,0.104198f}, -{0.0155702f,-0.30579f,0.104198f},{0.014996f,-0.305595f,0.104198f},{0.0179895f,-0.30579f,0.104198f}, -{0.0173925f,-0.305909f,0.104198f},{0.0167797f,-0.30595f,0.104198f},{0.0191075f,-0.305327f,0.104198f}, -{0.0185634f,-0.305595f,0.104198f},{0.0200755f,-0.304584f,0.104198f},{0.0196139f,-0.304989f,0.104198f}, -{0.0204802f,-0.304122f,0.104198f},{0.020818f,-0.303616f,0.104198f},{0.0210859f,-0.303072f,0.104198f}, -{0.0212811f,-0.302498f,0.104198f},{0.0214003f,-0.301901f,0.104198f},{0.0144523f,-0.305327f,0.104198f}, -{0.000612842f,-0.289129f,0.104198f},{0.00232777f,-0.288547f,0.104198f},{0.00178369f,-0.288815f,0.104198f}, -{0.00120978f,-0.28901f,0.104198f},{0.00370055f,-0.287343f,0.104198f},{0.0028342f,-0.288209f,0.104198f}, -{0.00329584f,-0.287805f,0.104198f},{0.00462066f,-0.285121f,0.104198f},{0.00450141f,-0.285718f,0.104198f}, -{0.00430621f,-0.286293f,0.104198f},{0.00462052f,-0.283896f,0.104198f},{0.00450127f,-0.283299f,0.104198f}, -{0.00466102f,-0.284509f,0.104198f},{0.00403818f,-0.282181f,0.104198f},{0.00430621f,-0.282725f,0.104198f}, -{0.00329584f,-0.281213f,0.104198f},{0.00370041f,-0.281675f,0.104198f},{0.00283386f,-0.280808f,0.104198f}, -{0.00232743f,-0.280471f,0.104198f},{0.00178369f,-0.280203f,0.104198f},{0.00120944f,-0.280007f,0.104198f}, -{0.000612502f,-0.279888f,0.104198f},{0.00403832f,-0.286836f,0.104198f},{0.0114195f,-0.321068f,0.104198f}, -{0.00948155f,-0.322066f,0.104198f},{0.0032562f,-0.323894f,0.104198f},{0.00746583f,-0.322873f,0.104198f}, -{-0.00325654f,-0.323894f,0.104198f},{0.00109039f,-0.324102f,0.104198f},{-0.00109151f,-0.324101f,0.104198f}, -{-0.00746603f,-0.322873f,0.104198f},{-0.00538621f,-0.323483f,0.104198f},{-0.00948213f,-0.322066f,0.104198f}, -{-0.0114195f,-0.321068f,0.104198f},{0.00538567f,-0.323483f,0.104198f},{0.0123517f,-0.322682f,0.104198f}, -{-0.0123517f,-0.322682f,0.104198f},{-0.0102556f,-0.323763f,0.104198f},{-0.00352201f,-0.32574f,0.104198f}, -{-0.00807529f,-0.324635f,0.104198f},{0.00352238f,-0.32574f,0.104198f},{-0.00117941f,-0.325964f,0.104198f}, -{0.00118061f,-0.325964f,0.104198f},{0.0080755f,-0.324635f,0.104198f},{0.0102562f,-0.323762f,0.104198f}, -{0.0058259f,-0.325295f,0.104198f},{-0.00582532f,-0.325295f,0.104198f},{0.0132534f,-0.282688f,0.104198f}, -{0.0114195f,-0.281509f,0.104198f},{0.017949f,-0.287166f,0.104198f},{0.0165285f,-0.285527f,0.104198f}, -{0.0149596f,-0.284031f,0.104198f},{0.0203023f,-0.290827f,0.104198f},{0.0212053f,-0.292806f,0.104198f}, -{0.0192114f,-0.288938f,0.104198f},{0.0224255f,-0.296962f,0.104198f},{0.0219143f,-0.294856f,0.104198f}, -{0.0227351f,-0.299111f,0.104198f},{0.022839f,-0.301289f,0.104198f},{0.0123517f,-0.279895f,0.104198f}, -{0.0247034f,-0.301289f,0.104198f},{0.0245908f,-0.298933f,0.104198f},{0.0229363f,-0.292113f,0.104198f}, -{0.0237031f,-0.29433f,0.104198f},{0.0242561f,-0.296609f,0.104198f},{0.020779f,-0.287929f,0.104198f}, -{0.019414f,-0.286013f,0.104198f},{0.0219591f,-0.289972f,0.104198f},{0.0178774f,-0.28424f,0.104198f}, -{0.0161807f,-0.282622f,0.104198f},{0.0143348f,-0.28117f,0.104198f},{-0.0227349f,-0.299111f,0.104198f}, -{-0.022839f,-0.301289f,0.104198f},{-0.0212052f,-0.292806f,0.104198f},{-0.0219142f,-0.294855f,0.104198f}, -{-0.0224254f,-0.296962f,0.104198f},{-0.0192108f,-0.288937f,0.104198f},{-0.0179488f,-0.287165f,0.104198f}, -{-0.0203018f,-0.290826f,0.104198f},{-0.0149595f,-0.284031f,0.104198f},{-0.0165281f,-0.285527f,0.104198f}, -{-0.0132529f,-0.282688f,0.104198f},{-0.0114195f,-0.281509f,0.104198f},{-0.0247034f,-0.301289f,0.104198f}, -{-0.0123517f,-0.279895f,0.104198f},{-0.0143353f,-0.28117f,0.104198f},{-0.0194142f,-0.286013f,0.104198f}, -{-0.0178778f,-0.28424f,0.104198f},{-0.0161808f,-0.282622f,0.104198f},{-0.0219596f,-0.289973f,0.104198f}, -{-0.0229364f,-0.292114f,0.104198f},{-0.0207797f,-0.28793f,0.104198f},{-0.0237033f,-0.294331f,0.104198f}, -{-0.0242561f,-0.296609f,0.104198f},{-0.024591f,-0.298934f,0.104198f},{-0.00275356f,-0.301777f,0.0986044f}, -{-0.00214219f,-0.303086f,0.0986044f},{-0.00242266f,-0.302686f,0.0986044f},{-0.00262748f,-0.302246f,0.0986044f}, -{-0.000956449f,-0.303917f,0.0986044f},{-0.00048723f,-0.304042f,0.0986044f},{-0.00179504f,-0.303433f,0.0986044f}, -{-0.00139564f,-0.303712f,0.0986044f},{0.000957717f,-0.303916f,0.0986044f},{0.000488516f,-0.304042f,0.0986044f}, -{5.2844e-017f,-0.304085f,0.0986044f},{0.00179767f,-0.303431f,0.0986044f},{0.00139727f,-0.303711f,0.0986044f}, -{0.00214411f,-0.303084f,0.0986044f},{0.00242333f,-0.302684f,0.0986044f},{0.00262801f,-0.302245f,0.0986044f}, -{0.00275356f,-0.301777f,0.0986044f},{0.0174099f,-0.302514f,0.121909f},{0.0172871f,-0.301908f,0.121909f}, -{0.0172458f,-0.301289f,0.121909f},{0.0176121f,-0.3031f,0.121909f},{0.0182409f,-0.304167f,0.121909f}, -{0.0178912f,-0.303655f,0.121909f},{0.0186544f,-0.304627f,0.121909f},{0.0191262f,-0.305029f,0.121909f}, -{0.0196487f,-0.305366f,0.121909f},{0.0202093f,-0.305629f,0.121909f},{0.0207991f,-0.305816f,0.121909f}, -{0.021411f,-0.305923f,0.121909f},{0.0172872f,-0.300669f,0.121909f},{0.0174099f,-0.300063f,0.121909f}, -{0.0176122f,-0.299477f,0.121909f},{0.0178915f,-0.298922f,0.121909f},{0.0182411f,-0.29841f,0.121909f}, -{0.0186545f,-0.29795f,0.121909f},{0.0191266f,-0.297547f,0.121909f},{0.0196491f,-0.297211f,0.121909f}, -{0.0202094f,-0.296948f,0.121909f},{0.0207994f,-0.296761f,0.121909f},{0.021411f,-0.296654f,0.121909f}, -{0.00761603f,-0.294203f,0.121909f},{0.00821991f,-0.292665f,0.121909f},{0.00794276f,-0.293145f,0.121909f}, -{0.00774033f,-0.293661f,0.121909f},{0.00944153f,-0.291532f,0.121909f},{0.00856913f,-0.292227f,0.121909f}, -{0.00898119f,-0.291845f,0.121909f},{0.0115849f,-0.291045f,0.121909f},{0.011024f,-0.291045f,0.121909f}, -{0.01047f,-0.291128f,0.121909f},{0.0126654f,-0.291292f,0.121909f},{0.012136f,-0.291129f,0.121909f}, -{0.0136271f,-0.291848f,0.121909f},{0.0140372f,-0.292229f,0.121909f},{0.0131654f,-0.291533f,0.121909f}, -{0.0143853f,-0.292666f,0.121909f},{0.0146628f,-0.293147f,0.121909f},{0.0148654f,-0.293663f,0.121909f}, -{0.0149887f,-0.294203f,0.121909f},{0.00994023f,-0.291292f,0.121909f},{0.00749878f,-0.3009f,0.121909f}, -{0.0080757f,-0.299902f,0.121909f},{0.007619f,-0.30053f,0.121909f},{0.0091279f,-0.299434f,0.121909f}, -{0.00839049f,-0.299674f,0.121909f},{0.00874642f,-0.299515f,0.121909f},{0.00989914f,-0.299516f,0.121909f}, -{0.0102546f,-0.299674f,0.121909f},{0.00951793f,-0.299435f,0.121909f},{0.0105703f,-0.299904f,0.121909f}, -{0.0108309f,-0.300193f,0.121909f},{0.0110255f,-0.300531f,0.121909f},{0.0111456f,-0.300901f,0.121909f}, -{0.00781413f,-0.300192f,0.121909f},{0.00632322f,-0.282854f,0.121909f},{0.00629776f,-0.282236f,0.121909f}, -{0.00635281f,-0.281618f,0.121909f},{0.00643547f,-0.283464f,0.121909f},{0.00662778f,-0.284053f,0.121909f}, -{0.00689664f,-0.284612f,0.121909f},{0.00723717f,-0.28513f,0.121909f},{0.00862289f,-0.286353f,0.121909f}, -{0.00917948f,-0.286627f,0.121909f},{0.00764334f,-0.285598f,0.121909f},{0.00810797f,-0.286008f,0.121909f}, -{0.010376f,-0.286942f,0.121909f},{0.0109947f,-0.286977f,0.121909f},{0.0143217f,-0.285539f,0.121909f}, -{0.0138626f,-0.285956f,0.121909f},{0.0122191f,-0.286802f,0.121909f},{0.012803f,-0.286594f,0.121909f}, -{0.013354f,-0.28631f,0.121909f},{0.0147191f,-0.285063f,0.121909f},{0.0116126f,-0.286931f,0.121909f}, -{0.0097673f,-0.286824f,0.121909f},{0.00647672f,-0.281011f,0.121909f},{0.00669182f,-0.280429f,0.121909f}, -{-0.00232814f,-0.29115f,0.121909f},{-0.00335826f,-0.289858f,0.121909f},{-0.00308092f,-0.290338f,0.121909f}, -{-0.0027356f,-0.290771f,0.121909f},{-0.00372865f,-0.288234f,0.121909f},{-0.0035632f,-0.289337f,0.121909f}, -{-0.00368751f,-0.288789f,0.121909f},{-0.00307835f,-0.286134f,0.121909f},{-0.00335937f,-0.28662f,0.121909f}, -{-0.00356405f,-0.287141f,0.121909f},{-0.00232427f,-0.285322f,0.121909f},{-0.0027306f,-0.285699f,0.121909f}, -{-0.00136237f,-0.284767f,0.121909f},{-0.000827251f,-0.284602f,0.121909f},{-0.00186593f,-0.285009f,0.121909f}, -{-0.000274996f,-0.284519f,0.121909f},{0.000280844f,-0.284519f,0.121909f},{0.000829073f,-0.284602f,0.121909f}, -{0.00135821f,-0.284765f,0.121909f},{-0.00368715f,-0.287682f,0.121909f},{0.0034127f,-0.2946f,0.121909f}, -{0.00283723f,-0.293602f,0.121909f},{0.00315233f,-0.294311f,0.121909f},{0.00295815f,-0.292456f,0.121909f}, -{0.00279666f,-0.293215f,0.121909f},{0.00283762f,-0.292827f,0.121909f},{0.00341439f,-0.291829f,0.121909f}, -{0.00372927f,-0.291601f,0.121909f},{0.00315311f,-0.292119f,0.121909f},{0.00408585f,-0.291442f,0.121909f}, -{0.00446695f,-0.291361f,0.121909f},{0.0048565f,-0.291361f,0.121909f},{0.00523731f,-0.291442f,0.121909f}, -{0.00295751f,-0.293973f,0.121909f},{-0.0133515f,-0.286308f,0.121909f},{-0.013859f,-0.285951f,0.121909f}, -{-0.00764282f,-0.285598f,0.121909f},{-0.00810759f,-0.286008f,0.121909f},{-0.00723674f,-0.285129f,0.121909f}, -{-0.00862289f,-0.286353f,0.121909f},{-0.00689651f,-0.284611f,0.121909f},{-0.00662806f,-0.284053f,0.121909f}, -{-0.00643592f,-0.283463f,0.121909f},{-0.00917901f,-0.286627f,0.121909f},{-0.00976653f,-0.286824f,0.121909f}, -{-0.00632427f,-0.282854f,0.121909f},{-0.0103751f,-0.286942f,0.121909f},{-0.00629503f,-0.282234f,0.121909f}, -{-0.0064786f,-0.281011f,0.121909f},{-0.00634749f,-0.281617f,0.121909f},{-0.010994f,-0.286978f,0.121909f}, -{-0.00669182f,-0.280429f,0.121909f},{-0.0116123f,-0.286931f,0.121909f},{-0.0128028f,-0.286595f,0.121909f}, -{-0.0122189f,-0.286803f,0.121909f},{-0.0143221f,-0.285541f,0.121909f},{-0.0147191f,-0.285063f,0.121909f}, -{-0.00994417f,-0.298236f,0.121909f},{-0.0115782f,-0.298482f,0.121909f},{-0.0110237f,-0.298482f,0.121909f}, -{-0.0104759f,-0.298399f,0.121909f},{-0.0131702f,-0.29799f,0.121909f},{-0.0121323f,-0.298398f,0.121909f}, -{-0.0126687f,-0.298232f,0.121909f},{-0.0146632f,-0.296377f,0.121909f},{-0.0143833f,-0.296863f,0.121909f}, -{-0.014034f,-0.297301f,0.121909f},{-0.0149897f,-0.295318f,0.121909f},{-0.0148666f,-0.295858f,0.121909f}, -{-0.0149894f,-0.294208f,0.121909f},{-0.0148645f,-0.293662f,0.121909f},{-0.0150313f,-0.294765f,0.121909f}, -{-0.0146603f,-0.293142f,0.121909f},{-0.014382f,-0.292661f,0.121909f},{-0.0140364f,-0.292227f,0.121909f}, -{-0.0136305f,-0.291851f,0.121909f},{-0.0136274f,-0.297678f,0.121909f},{-0.00408601f,-0.294989f,0.121909f}, -{-0.0052381f,-0.294988f,0.121909f},{-0.00446686f,-0.29507f,0.121909f},{-0.00616977f,-0.294311f,0.121909f}, -{-0.00559379f,-0.29483f,0.121909f},{-0.00590924f,-0.2946f,0.121909f},{-0.00648482f,-0.293602f,0.121909f}, -{-0.00652543f,-0.293215f,0.121909f},{-0.0063645f,-0.293973f,0.121909f},{-0.00648441f,-0.292827f,0.121909f}, -{-0.00636386f,-0.292456f,0.121909f},{-0.00616897f,-0.292119f,0.121909f},{-0.00590844f,-0.29183f,0.121909f}, -{-0.00485671f,-0.295069f,0.121909f},{-0.0178906f,-0.303654f,0.121909f},{-0.0176123f,-0.3031f,0.121909f}, -{-0.0182401f,-0.304166f,0.121909f},{-0.0186543f,-0.304628f,0.121909f},{-0.019126f,-0.30503f,0.121909f}, -{-0.0174099f,-0.302514f,0.121909f},{-0.0196492f,-0.305361f,0.121909f},{-0.017287f,-0.301907f,0.121909f}, -{-0.0172458f,-0.301289f,0.121909f},{-0.0172871f,-0.30067f,0.121909f},{-0.0174101f,-0.300062f,0.121909f}, -{-0.0176127f,-0.299476f,0.121909f},{-0.0178912f,-0.298922f,0.121909f},{-0.0182407f,-0.298411f,0.121909f}, -{-0.018655f,-0.29795f,0.121909f},{-0.0191272f,-0.297548f,0.121909f},{-0.0196491f,-0.297213f,0.121909f}, -{-0.02021f,-0.29695f,0.121909f},{-0.0208003f,-0.29676f,0.121909f},{-0.021411f,-0.296654f,0.121909f}, -{-0.0207988f,-0.305818f,0.121909f},{-0.0202118f,-0.305622f,0.121909f},{-0.021411f,-0.305923f,0.121909f}, -{-0.00761603f,-0.308374f,0.121909f},{-0.00821991f,-0.309912f,0.121909f},{-0.00794276f,-0.309432f,0.121909f}, -{-0.00774033f,-0.308916f,0.121909f},{-0.00944153f,-0.311045f,0.121909f},{-0.00856913f,-0.31035f,0.121909f}, -{-0.00898119f,-0.310732f,0.121909f},{-0.0115849f,-0.311532f,0.121909f},{-0.011024f,-0.311532f,0.121909f}, -{-0.01047f,-0.311449f,0.121909f},{-0.0126654f,-0.311285f,0.121909f},{-0.012136f,-0.311448f,0.121909f}, -{-0.0136271f,-0.310729f,0.121909f},{-0.0140372f,-0.310348f,0.121909f},{-0.0131654f,-0.311044f,0.121909f}, -{-0.0143853f,-0.309911f,0.121909f},{-0.0146628f,-0.30943f,0.121909f},{-0.0148654f,-0.308914f,0.121909f}, -{-0.0149887f,-0.308374f,0.121909f},{-0.00994023f,-0.311285f,0.121909f},{-0.00749878f,-0.301677f,0.121909f}, -{-0.0080757f,-0.302675f,0.121909f},{-0.007619f,-0.302047f,0.121909f},{-0.0091279f,-0.303143f,0.121909f}, -{-0.00839049f,-0.302903f,0.121909f},{-0.00874642f,-0.303062f,0.121909f},{-0.00989914f,-0.303061f,0.121909f}, -{-0.0102546f,-0.302903f,0.121909f},{-0.00951793f,-0.303143f,0.121909f},{-0.0105703f,-0.302673f,0.121909f}, -{-0.0108309f,-0.302384f,0.121909f},{-0.0110255f,-0.302046f,0.121909f},{-0.0111456f,-0.301676f,0.121909f}, -{-0.00781413f,-0.302385f,0.121909f},{-0.00629776f,-0.320341f,0.121909f},{-0.00632322f,-0.319723f,0.121909f}, -{-0.0147191f,-0.317514f,0.121909f},{-0.00643547f,-0.319113f,0.121909f},{-0.00635281f,-0.320959f,0.121909f}, -{-0.00662778f,-0.318524f,0.121909f},{-0.00689664f,-0.317965f,0.121909f},{-0.00764334f,-0.316979f,0.121909f}, -{-0.00810797f,-0.316569f,0.121909f},{-0.00723717f,-0.317447f,0.121909f},{-0.010376f,-0.315635f,0.121909f}, -{-0.0109947f,-0.3156f,0.121909f},{-0.00862289f,-0.316224f,0.121909f},{-0.00917948f,-0.31595f,0.121909f}, -{-0.0143217f,-0.317038f,0.121909f},{-0.0138626f,-0.316622f,0.121909f},{-0.0122191f,-0.315775f,0.121909f}, -{-0.012803f,-0.315983f,0.121909f},{-0.013354f,-0.316267f,0.121909f},{-0.0116126f,-0.315647f,0.121909f}, -{-0.0097673f,-0.315753f,0.121909f},{-0.00647672f,-0.321566f,0.121909f},{-0.00669182f,-0.322148f,0.121909f}, -{0.00232814f,-0.311427f,0.121909f},{0.00335826f,-0.312719f,0.121909f},{0.00308092f,-0.312239f,0.121909f}, -{0.0027356f,-0.311806f,0.121909f},{0.00372865f,-0.314343f,0.121909f},{0.0035632f,-0.313241f,0.121909f}, -{0.00368751f,-0.313788f,0.121909f},{0.00307835f,-0.316443f,0.121909f},{0.00335937f,-0.315957f,0.121909f}, -{0.00356405f,-0.315436f,0.121909f},{0.00232427f,-0.317255f,0.121909f},{0.0027306f,-0.316878f,0.121909f}, -{0.00136237f,-0.31781f,0.121909f},{0.000827251f,-0.317975f,0.121909f},{0.00186593f,-0.317568f,0.121909f}, -{0.000274996f,-0.318058f,0.121909f},{-0.000280844f,-0.318058f,0.121909f},{-0.000829073f,-0.317975f,0.121909f}, -{-0.00135821f,-0.317812f,0.121909f},{0.00368715f,-0.314895f,0.121909f},{-0.0034126f,-0.307977f,0.121909f}, -{-0.00283728f,-0.308975f,0.121909f},{-0.0031524f,-0.308266f,0.121909f},{-0.00295812f,-0.310121f,0.121909f}, -{-0.00279668f,-0.309362f,0.121909f},{-0.0028374f,-0.30975f,0.121909f},{-0.0034143f,-0.310748f,0.121909f}, -{-0.00372908f,-0.310977f,0.121909f},{-0.00315337f,-0.310458f,0.121909f},{-0.00408596f,-0.311135f,0.121909f}, -{-0.00446705f,-0.311216f,0.121909f},{-0.00485646f,-0.311216f,0.121909f},{-0.00523689f,-0.311135f,0.121909f}, -{-0.00295753f,-0.308604f,0.121909f},{0.00764282f,-0.316979f,0.121909f},{0.00723674f,-0.317448f,0.121909f}, -{0.00810759f,-0.316569f,0.121909f},{0.00862289f,-0.316224f,0.121909f},{0.00689651f,-0.317966f,0.121909f}, -{0.00662806f,-0.318524f,0.121909f},{0.00643592f,-0.319114f,0.121909f},{0.00917901f,-0.31595f,0.121909f}, -{0.00632427f,-0.319723f,0.121909f},{0.00629503f,-0.320343f,0.121909f},{0.00976653f,-0.315753f,0.121909f}, -{0.00634749f,-0.32096f,0.121909f},{0.0103751f,-0.315635f,0.121909f},{0.010994f,-0.3156f,0.121909f}, -{0.0064786f,-0.321566f,0.121909f},{0.00669182f,-0.322148f,0.121909f},{0.0116123f,-0.315646f,0.121909f}, -{0.0128028f,-0.315982f,0.121909f},{0.0122189f,-0.315774f,0.121909f},{0.0133515f,-0.316269f,0.121909f}, -{0.013859f,-0.316626f,0.121909f},{0.0143221f,-0.317036f,0.121909f},{0.0147191f,-0.317514f,0.121909f}, -{0.00994417f,-0.304342f,0.121909f},{0.0115782f,-0.304095f,0.121909f},{0.0110237f,-0.304096f,0.121909f}, -{0.0104759f,-0.304178f,0.121909f},{0.0131702f,-0.304587f,0.121909f},{0.0121323f,-0.304179f,0.121909f}, -{0.0126687f,-0.304345f,0.121909f},{0.0146632f,-0.3062f,0.121909f},{0.0143833f,-0.305714f,0.121909f}, -{0.014034f,-0.305276f,0.121909f},{0.0149897f,-0.307259f,0.121909f},{0.0148666f,-0.306719f,0.121909f}, -{0.0149894f,-0.30837f,0.121909f},{0.0148645f,-0.308915f,0.121909f},{0.0150313f,-0.307812f,0.121909f}, -{0.0146603f,-0.309435f,0.121909f},{0.014382f,-0.309916f,0.121909f},{0.0140364f,-0.31035f,0.121909f}, -{0.0136305f,-0.310726f,0.121909f},{0.0136274f,-0.304899f,0.121909f},{0.00408601f,-0.307588f,0.121909f}, -{0.0052381f,-0.307589f,0.121909f},{0.00446686f,-0.307507f,0.121909f},{0.00616977f,-0.308266f,0.121909f}, -{0.00559379f,-0.307747f,0.121909f},{0.00590924f,-0.307977f,0.121909f},{0.00648482f,-0.308975f,0.121909f}, -{0.00652543f,-0.309362f,0.121909f},{0.0063645f,-0.308604f,0.121909f},{0.00648441f,-0.30975f,0.121909f}, -{0.00636386f,-0.310121f,0.121909f},{0.00616897f,-0.310458f,0.121909f},{0.00590844f,-0.310747f,0.121909f}, -{0.00485671f,-0.307508f,0.121909f},{0.00462052f,-0.301901f,0.127503f},{0.00403818f,-0.303616f,0.127503f}, -{0.00450127f,-0.302498f,0.127503f},{0.00283386f,-0.304989f,0.127503f},{0.00232743f,-0.305327f,0.127503f}, -{0.00329584f,-0.304584f,0.127503f},{0.000612502f,-0.305909f,0.127503f},{0.00178369f,-0.305595f,0.127503f}, -{0.00120944f,-0.30579f,0.127503f},{-0.00120978f,-0.30579f,0.127503f},{5.46456e-017f,-0.30595f,0.127503f}, -{-0.000612842f,-0.305909f,0.127503f},{-0.00232777f,-0.305327f,0.127503f},{-0.0028342f,-0.304989f,0.127503f}, -{-0.00178369f,-0.305595f,0.127503f},{-0.00329584f,-0.304584f,0.127503f},{-0.00370055f,-0.304122f,0.127503f}, -{-0.00403832f,-0.303616f,0.127503f},{-0.00430621f,-0.303072f,0.127503f},{-0.00450141f,-0.302498f,0.127503f}, -{-0.00462066f,-0.301901f,0.127503f},{0.00370041f,-0.304123f,0.127503f},{0.00430621f,-0.303072f,0.127503f}, -{-0.00139737f,-0.303708f,0.127503f},{-0.00275363f,-0.301773f,0.127503f},{-0.00242194f,-0.302686f,0.127503f}, -{-0.00214182f,-0.303085f,0.127503f},{-0.00262754f,-0.302244f,0.127503f},{-0.00179665f,-0.303429f,0.127503f}, -{-0.000956049f,-0.303916f,0.127503f},{-0.000485772f,-0.304043f,0.127503f},{5.20065e-017f,-0.304085f,0.127503f}, -{0.000955564f,-0.303917f,0.127503f},{0.000485107f,-0.304043f,0.127503f},{0.00139499f,-0.303708f,0.127503f}, -{0.00275512f,-0.301775f,0.127503f},{0.00178917f,-0.303421f,0.127503f},{0.00262887f,-0.302246f,0.127503f}, -{0.00242212f,-0.302687f,0.127503f},{0.00214373f,-0.303089f,0.127503f},{-0.00275512f,-0.301775f,0.13496f}, -{-0.00262887f,-0.302246f,0.13496f},{-0.00242212f,-0.302687f,0.13496f},{-0.00214373f,-0.303089f,0.13496f}, -{-0.00178917f,-0.303421f,0.13496f},{-0.00139499f,-0.303708f,0.13496f},{-0.000955564f,-0.303917f,0.13496f}, -{-0.000485107f,-0.304043f,0.13496f},{5.2317e-017f,-0.304085f,0.13496f},{0.000485772f,-0.304043f,0.13496f}, -{0.00179665f,-0.303429f,0.13496f},{0.00262754f,-0.302244f,0.13496f},{0.000956049f,-0.303916f,0.13496f}, -{0.00139737f,-0.303708f,0.13496f},{0.00214182f,-0.303085f,0.13496f},{0.00242194f,-0.302686f,0.13496f}, -{0.00275363f,-0.301773f,0.13496f},{-0.278876f,0.0027207f,0.141016f},{-0.279289f,0.00279661f,0.127503f}, -{-0.279666f,0.00276223f,0.140921f},{-0.278101f,0.00254178f,0.141133f},{-0.278432f,0.00266037f,0.127503f}, -{-0.277654f,0.00226719f,0.127503f},{-0.277449f,0.00210085f,0.141283f},{-0.276631f,0.000869207f,0.127503f}, -{-0.277032f,0.00165072f,0.127503f},{-0.276921f,0.00149803f,0.141448f},{-0.276599f,0.000793813f,0.141604f}, -{-0.276492f,-8.9946e-019f,0.127503f},{-0.276492f,-2.12873e-008f,0.141748f},{-0.280158f,0.00265777f,0.127503f}, -{-0.280438f,0.00255964f,0.140869f},{-0.280939f,0.00225612f,0.127503f},{-0.281556f,0.00163414f,0.127503f}, -{-0.28111f,0.00212367f,0.140862f},{-0.281946f,0.000869207f,0.127503f},{-0.281644f,0.00151779f,0.140892f}, -{-0.281979f,0.000793595f,0.140955f},{-0.282085f,0.0f,0.127503f},{-0.282085f,0.0f,0.141048f}, -{-0.321654f,0.00226719f,0.127503f},{-0.32241f,0.00266113f,0.141631f},{-0.321628f,0.00225617f,0.141475f}, -{-0.322432f,0.00266037f,0.127503f},{-0.321032f,0.00165072f,0.127503f},{-0.321061f,0.00161123f,0.141322f}, -{-0.320631f,0.000869207f,0.127503f},{-0.320624f,0.000861428f,0.141174f},{-0.323269f,0.00279699f,0.141768f}, -{-0.320492f,2.26626e-008f,0.141048f},{-0.320492f,9.24713e-018f,0.127503f},{-0.323289f,0.00279661f,0.127503f}, -{-0.324142f,0.00267244f,0.141876f},{-0.324922f,0.00227523f,0.141932f},{-0.324158f,0.00265777f,0.127503f}, -{-0.324939f,0.00225612f,0.127503f},{-0.325551f,0.00164828f,0.14193f},{-0.325556f,0.00163414f,0.127503f}, -{-0.325946f,0.000869207f,0.127503f},{-0.325955f,0.000867575f,0.141868f},{-0.326085f,8.90465e-018f,0.127503f}, -{-0.326085f,8.90465e-018f,0.141748f},{-0.301289f,-0.00279661f,0.136825f},{-0.300432f,-0.00266037f,0.127503f}, -{-0.302923f,-0.00226719f,0.136825f},{-0.302158f,-0.00265777f,0.127503f},{-0.302939f,-0.00225612f,0.127503f}, -{-0.302145f,-0.00266037f,0.136825f},{-0.303545f,-0.00165072f,0.136825f},{-0.303946f,-0.000869207f,0.127503f}, -{-0.304085f,3.42486e-019f,0.136825f},{-0.303946f,-0.000869207f,0.136825f},{-0.303556f,-0.00163414f,0.127503f}, -{-0.304085f,3.42486e-019f,0.127503f},{-0.300419f,-0.00265777f,0.136825f},{-0.299654f,-0.00226719f,0.127503f}, -{-0.299638f,-0.00225612f,0.136825f},{-0.299021f,-0.00163414f,0.136825f},{-0.299032f,-0.00165072f,0.127503f}, -{-0.298631f,-0.000869207f,0.136825f},{-0.298631f,-0.000869207f,0.127503f},{-0.298492f,0.0f,0.127503f}, -{-0.298492f,0.0f,0.136825f},{-0.298637f,0.00383933f,0.140336f},{-0.299639f,0.00435933f,0.127503f}, -{-0.299629f,0.00437081f,0.140342f},{-0.30073f,0.00462728f,0.127503f},{-0.298643f,0.00383758f,0.127503f}, -{-0.30072f,0.00463064f,0.140371f},{-0.297804f,0.00309444f,0.127503f},{-0.297795f,0.00308762f,0.140354f}, -{-0.297163f,0.00216892f,0.127503f},{-0.30185f,0.00463006f,0.140416f},{-0.297147f,0.00216891f,0.14039f}, -{-0.296764f,0.00111911f,0.127503f},{-0.296628f,5.60046e-014f,0.140488f},{-0.296628f,3.35892e-010f,0.127503f}, -{-0.296754f,0.00112174f,0.140439f},{-0.301853f,0.00462657f,0.127503f},{-0.302944f,0.00435716f,0.127503f}, -{-0.302946f,0.00437228f,0.140465f},{-0.303934f,0.00384698f,0.140509f},{-0.303939f,0.0038338f,0.127503f}, -{-0.304779f,0.00308862f,0.127503f},{-0.304777f,0.00309221f,0.140537f},{-0.305417f,0.00216381f,0.127503f}, -{-0.305426f,0.00217168f,0.140543f},{-0.305823f,0.00112329f,0.140525f},{-0.305814f,0.00111503f,0.127503f}, -{-0.30595f,0.0f,0.140488f},{-0.268793f,0.0031834f,0.141919f},{-0.268706f,-0.0034311f,0.143258f}, -{-0.273216f,0.00348389f,0.141453f},{-0.280744f,-0.013311f,0.142108f},{-0.281094f,-0.00749864f,0.141891f}, -{-0.27672f,-0.01447f,0.142985f},{-0.26798f,-0.0237151f,0.145107f},{-0.268531f,-0.0168317f,0.144795f}, -{-0.264f,-0.0250351f,0.14612f},{-0.2978f,-0.00309212f,0.140537f},{-0.293788f,-0.00980991f,0.140443f}, -{-0.298643f,-0.00384705f,0.140509f},{-0.281979f,-0.000788852f,0.141161f},{-0.281606f,-0.00148198f,0.141294f}, -{-0.285735f,-0.00113058f,0.140739f},{-0.302948f,-0.00437081f,0.140342f},{-0.301857f,-0.00463066f,0.140371f}, -{-0.302709f,-0.00734722f,0.140099f},{-0.308774f,0.00981015f,0.140456f},{-0.30394f,-0.00383936f,0.140336f}, -{-0.304783f,-0.0030876f,0.140354f},{-0.307737f,-0.000835134f,0.140403f},{-0.312842f,0.00565577f,0.140706f}, -{-0.308256f,0.00448849f,0.140582f},{-0.320599f,-0.000794809f,0.140955f},{-0.316415f,-0.00431412f,0.139973f}, -{-0.320936f,-0.00152033f,0.140892f},{-0.334055f,0.0168309f,0.144796f},{-0.338577f,0.0250351f,0.14612f}, -{-0.334598f,0.0237151f,0.145107f},{-0.313348f,0.0110109f,0.140705f},{-0.329718f,0.00922726f,0.143432f}, -{-0.330654f,0.0222833f,0.144104f},{-0.329893f,0.0156491f,0.143876f},{-0.329371f,-0.00348559f,0.141452f}, -{-0.329543f,0.00283697f,0.142622f},{-0.325978f,-0.000793378f,0.141605f},{-0.333794f,-0.00318417f,0.141918f}, -{-0.33388f,0.00342276f,0.143256f},{-0.334267f,-0.00969325f,0.140239f},{-0.338577f,-0.00290707f,0.142335f}, -{-0.338577f,0.00398877f,0.143878f},{-0.338577f,-0.00968775f,0.140407f},{-0.325081f,-0.00378729f,0.140965f}, -{-0.325129f,-0.00209478f,0.141284f},{-0.324474f,-0.00253473f,0.141134f},{-0.333967f,0.010107f,0.144218f}, -{-0.323703f,-0.00272118f,0.141016f},{-0.321359f,-0.00973119f,0.139327f},{-0.320799f,-0.00404127f,0.140452f}, -{-0.298312f,-0.00858894f,0.140271f},{-0.290225f,-0.000322559f,0.140392f},{-0.29535f,0.00611166f,0.139905f}, -{-0.290725f,0.0049946f,0.139783f},{-0.299868f,0.00734676f,0.140099f},{-0.299631f,-0.0043723f,0.140465f}, -{-0.281789f,0.00405908f,0.140464f},{-0.286166f,0.00435339f,0.139998f},{-0.297151f,-0.00217165f,0.140543f}, -{-0.294309f,-0.00450063f,0.140568f},{-0.280465f,-0.00253786f,0.141575f},{-0.279704f,-0.00276739f,0.141709f}, -{-0.276982f,-0.00835592f,0.14266f},{-0.278136f,-0.00255847f,0.141903f},{-0.277464f,-0.00212169f,0.141937f}, -{-0.275858f,-0.0208182f,0.143118f},{-0.264f,-0.00398877f,0.143878f},{-0.272694f,-0.0156505f,0.143875f}, -{-0.264f,0.00968775f,0.140407f},{-0.264f,0.00290707f,0.142335f},{-0.268311f,0.00969325f,0.140239f}, -{-0.281218f,0.00973122f,0.139327f},{-0.276917f,0.00972934f,0.139659f},{-0.277503f,0.00378494f,0.140965f}, -{-0.284865f,-0.0121774f,0.141276f},{-0.2853f,-0.00665136f,0.141165f},{-0.294831f,0.000816648f,0.140389f}, -{-0.278905f,-0.0027728f,0.141822f},{-0.268619f,-0.0101155f,0.144218f},{-0.264f,-0.0179944f,0.145774f}, -{-0.271923f,-0.0222833f,0.144104f},{-0.264f,-0.0109671f,0.145026f},{-0.272615f,0.0097173f,0.139971f}, -{-0.285519f,0.0097497f,0.139013f},{-0.304264f,0.00858896f,0.140271f},{-0.307222f,-0.00613049f,0.139921f}, -{-0.316849f,0.00115281f,0.140712f},{-0.311834f,-0.00500873f,0.139791f},{-0.304385f,-0.0120097f,0.13929f}, -{-0.308539f,-0.0108714f,0.138995f},{-0.300727f,-0.00463004f,0.140416f},{-0.300237f,-0.0131607f,0.139564f}, -{-0.296096f,-0.0143354f,0.139836f},{-0.289722f,-0.00566917f,0.140697f},{-0.289219f,-0.0110148f,0.140695f}, -{-0.289811f,0.0100181f,0.138847f},{-0.294038f,0.0108714f,0.138995f},{-0.298192f,0.0120097f,0.13929f}, -{-0.30234f,0.0131607f,0.139564f},{-0.306481f,0.0143354f,0.139836f},{-0.317286f,0.00666271f,0.14114f}, -{-0.321494f,0.00749967f,0.141879f},{-0.322913f,-0.00277232f,0.14092f},{-0.32566f,-0.00972932f,0.139659f}, -{-0.325656f,-0.00149718f,0.141448f},{-0.317723f,0.0121843f,0.141251f},{-0.32214f,-0.00255887f,0.140869f}, -{-0.321467f,-0.00212359f,0.140862f},{-0.312336f,0.000305779f,0.140401f},{-0.305823f,-0.00112176f,0.140439f}, -{-0.30543f,-0.00216894f,0.14039f},{-0.321845f,0.0133136f,0.142096f},{-0.325602f,0.00834704f,0.14266f}, -{-0.325864f,0.0144683f,0.142986f},{-0.273043f,-0.0028458f,0.142624f},{-0.272869f,-0.0092361f,0.143432f}, -{-0.276934f,-0.00151619f,0.141923f},{-0.276599f,-0.00079021f,0.141859f},{-0.279796f,-0.019351f,0.142144f}, -{-0.28376f,-0.0179262f,0.14121f},{-0.287806f,-0.0166178f,0.140509f},{-0.281123f,-0.00210151f,0.141433f}, -{-0.296754f,-0.00112326f,0.140525f},{-0.291943f,-0.0154659f,0.14012f},{-0.312766f,-0.0100181f,0.138847f}, -{-0.310634f,0.0154659f,0.14012f},{-0.317058f,-0.00974966f,0.139013f},{-0.318817f,0.0179262f,0.14121f}, -{-0.314771f,0.0166178f,0.140509f},{-0.322781f,0.0193511f,0.142144f},{-0.326719f,0.0208182f,0.143118f}, -{-0.329962f,-0.00971729f,0.139971f},{-0.338577f,0.0179944f,0.145774f},{-0.338577f,0.0109671f,0.145026f}, -{-0.264f,-0.0262081f,0.148238f},{-0.267733f,-0.0248064f,0.147199f},{-0.267738f,-0.0250058f,0.146766f}, -{-0.271434f,-0.0233183f,0.146165f},{-0.271439f,-0.0235291f,0.145739f},{-0.282552f,-0.0188229f,0.143165f}, -{-0.282558f,-0.0190695f,0.142766f},{-0.278832f,-0.0203019f,0.144139f},{-0.278837f,-0.0205368f,0.143731f}, -{-0.275137f,-0.022035f,0.14473f},{-0.275132f,-0.0218112f,0.145147f},{-0.29417f,-0.015307f,0.141119f}, -{-0.294165f,-0.0150041f,0.141517f},{-0.298107f,-0.0141429f,0.140834f},{-0.286329f,-0.0174212f,0.1423f}, -{-0.290221f,-0.0161629f,0.141811f},{-0.290226f,-0.0164424f,0.141416f},{-0.305963f,-0.0114006f,0.14071f}, -{-0.309927f,-0.0106866f,0.140011f},{-0.30597f,-0.0117799f,0.140283f},{-0.302024f,-0.0125814f,0.14098f}, -{-0.302035f,-0.0129503f,0.14056f},{-0.298097f,-0.0138012f,0.141246f},{-0.322165f,-0.00963024f,0.140526f}, -{-0.318066f,-0.00968708f,0.140168f},{-0.318055f,-0.0091952f,0.140649f},{-0.313966f,-0.0099197f,0.139934f}, -{-0.309914f,-0.0102596f,0.140442f},{-0.313954f,-0.00946264f,0.140382f},{-0.322157f,-0.00907526f,0.141031f}, -{-0.326264f,-0.0095489f,0.140876f},{-0.326258f,-0.00894343f,0.141413f},{-0.330364f,-0.00945311f,0.141203f}, -{-0.334468f,-0.00933687f,0.14148f},{-0.33036f,-0.00879579f,0.141773f},{-0.334465f,-0.0086246f,0.142088f}, -{-0.338577f,-0.00922107f,0.141665f},{-0.338577f,-0.00845004f,0.142301f},{-0.286338f,-0.0176856f,0.141921f}, -{-0.264f,-0.0263793f,0.147802f},{-0.264f,-0.0259023f,0.148593f},{-0.267734f,-0.0244885f,0.147557f}, -{-0.271437f,-0.0229936f,0.146522f},{-0.282562f,-0.0184899f,0.143511f},{-0.275137f,-0.0214828f,0.145501f}, -{-0.294177f,-0.0146321f,0.14188f},{-0.286341f,-0.0170843f,0.142644f},{-0.290234f,-0.0158117f,0.142162f}, -{-0.305972f,-0.010968f,0.141112f},{-0.302034f,-0.0121699f,0.141368f},{-0.298108f,-0.0134094f,0.141622f}, -{-0.31806f,-0.0086637f,0.141107f},{-0.309921f,-0.00980481f,0.140857f},{-0.31396f,-0.00897481f,0.140813f}, -{-0.32216f,-0.00849863f,0.141523f},{-0.32626f,-0.00832061f,0.14194f},{-0.330362f,-0.00812583f,0.142335f}, -{-0.334466f,-0.00790535f,0.142688f},{-0.338577f,-0.00767878f,0.142938f},{-0.278839f,-0.0199715f,0.144489f}, -{-0.264f,-0.0254953f,0.148828f},{-0.267945f,-0.0239945f,0.147747f},{-0.271858f,-0.0224149f,0.146665f}, -{-0.283628f,-0.0176882f,0.143502f},{-0.275768f,-0.0208215f,0.145592f},{-0.279683f,-0.0192329f,0.144529f}, -{-0.295955f,-0.0136618f,0.142081f},{-0.287664f,-0.0162503f,0.14274f},{-0.2918f,-0.0149457f,0.142346f}, -{-0.31263f,-0.00869072f,0.141186f},{-0.308401f,-0.00973903f,0.141305f},{-0.304248f,-0.0110356f,0.141581f}, -{-0.321265f,-0.00795144f,0.141896f},{-0.316941f,-0.0081943f,0.14144f},{-0.325589f,-0.00772122f,0.142378f}, -{-0.329914f,-0.00747253f,0.142842f},{-0.334241f,-0.00719397f,0.143263f},{-0.338577f,-0.00690556f,0.143577f}, -{-0.300098f,-0.0123399f,0.141831f},{-0.264f,-0.0250324f,0.148916f},{-0.267971f,-0.0235306f,0.147857f}, -{-0.271889f,-0.0219498f,0.146794f},{-0.283688f,-0.0172517f,0.143711f},{-0.275809f,-0.0203651f,0.14574f}, -{-0.296012f,-0.0132021f,0.142332f},{-0.287719f,-0.0158114f,0.142927f},{-0.291851f,-0.0144807f,0.142544f}, -{-0.308457f,-0.0092687f,0.141666f},{-0.304299f,-0.0105497f,0.141886f},{-0.300157f,-0.0118813f,0.142106f}, -{-0.321297f,-0.0073368f,0.142324f},{-0.316973f,-0.00759572f,0.141811f},{-0.312673f,-0.00819435f,0.141567f}, -{-0.325613f,-0.00708183f,0.142866f},{-0.32993f,-0.00678804f,0.143377f},{-0.334249f,-0.00646507f,0.143843f}, -{-0.338577f,-0.00613003f,0.144218f},{-0.279733f,-0.0187868f,0.144697f},{-0.326294f,-0.00696068f,0.143005f}, -{-0.330384f,-0.00667554f,0.143491f},{-0.334476f,-0.00636198f,0.143939f},{-0.318115f,-0.00748015f,0.141999f}, -{-0.314024f,-0.00786981f,0.141631f},{-0.322205f,-0.00722771f,0.1425f},{-0.302112f,-0.0111819f,0.142035f}, -{-0.309993f,-0.00875236f,0.14162f},{-0.290321f,-0.014914f,0.142686f},{-0.298189f,-0.0124511f,0.142242f}, -{-0.294261f,-0.0137038f,0.142453f},{-0.282633f,-0.0175985f,0.143972f},{-0.278896f,-0.0190677f,0.144928f}, -{-0.286425f,-0.0162018f,0.143129f},{-0.275179f,-0.0205663f,0.145919f},{-0.271464f,-0.022067f,0.146916f}, -{-0.267747f,-0.0235578f,0.14792f},{-0.306047f,-0.00994863f,0.141826f},{-0.338577f,-0.00603944f,0.144293f}, -{-0.272455f,-0.00744254f,0.145994f},{-0.268304f,-0.015865f,0.147531f},{-0.268397f,-0.0083666f,0.146789f}, -{-0.272638f,-0.000311244f,0.144934f},{-0.268488f,-0.000930332f,0.145573f},{-0.272193f,0.00667554f,0.143491f}, -{-0.264f,-0.00158091f,0.146182f},{-0.268101f,0.0063617f,0.143935f},{-0.264f,-0.00932143f,0.147589f}, -{-0.264f,0.00603944f,0.144293f},{-0.276379f,-0.00654234f,0.145204f},{-0.28029f,-0.00567271f,0.144415f}, -{-0.276103f,-0.0134133f,0.14569f},{-0.287869f,-0.00989537f,0.143217f},{-0.283807f,-0.0110779f,0.143908f}, -{-0.28841f,-0.00388505f,0.143059f},{-0.279922f,-0.0122295f,0.144789f},{-0.296503f,-0.0072715f,0.142814f}, -{-0.301301f,-1.23849e-006f,0.142893f},{-0.300722f,-0.00593214f,0.142703f},{-0.292161f,-0.00860427f,0.142918f}, -{-0.30924f,-0.00327255f,0.142485f},{-0.31361f,-0.00211647f,0.14253f},{-0.305494f,0.00133631f,0.142894f}, -{-0.304916f,-0.00459153f,0.142593f},{-0.334185f,0.00836678f,0.146789f},{-0.334094f,0.00093054f,0.145573f}, -{-0.329944f,0.000310969f,0.144934f},{-0.317858f,-0.00135717f,0.142953f},{-0.318318f,0.00485039f,0.143617f}, -{-0.338577f,0.00158091f,0.146182f},{-0.325928f,-0.000284983f,0.144284f},{-0.330127f,0.00744232f,0.145994f}, -{-0.338577f,0.0171357f,0.148501f},{-0.334277f,0.0158652f,0.147532f},{-0.321928f,-0.000835711f,0.143615f}, -{-0.326203f,0.00654153f,0.145205f},{-0.322295f,0.00568021f,0.144405f},{-0.309815f,0.00265603f,0.142905f}, -{-0.314151f,0.00387587f,0.143071f},{-0.292745f,-0.00267273f,0.142876f},{-0.297082f,-0.00133739f,0.142892f}, -{-0.284266f,-0.00483092f,0.143642f},{-0.272271f,-0.0146267f,0.1466f},{-0.264f,-0.0171357f,0.148501f}, -{-0.276283f,0.0069607f,0.143005f},{-0.276654f,0.000284018f,0.144284f},{-0.280372f,0.00722775f,0.1425f}, -{-0.280656f,0.000847135f,0.143625f},{-0.284462f,0.00746803f,0.141989f},{-0.284723f,0.00138663f,0.142978f}, -{-0.288553f,0.00787057f,0.141632f},{-0.288949f,0.00210321f,0.142519f},{-0.292582f,0.00875939f,0.141625f}, -{-0.293326f,0.00324421f,0.142456f},{-0.296532f,0.00994211f,0.141827f},{-0.334828f,0.023562f,0.147921f}, -{-0.338577f,0.0249766f,0.148916f},{-0.29766f,0.00458966f,0.142591f},{-0.300462f,0.0111906f,0.142034f}, -{-0.304385f,0.0124586f,0.142239f},{-0.30188f,0.00592971f,0.142704f},{-0.308317f,0.0136985f,0.142455f}, -{-0.306073f,0.00727121f,0.142816f},{-0.312257f,0.0149126f,0.142682f},{-0.310392f,0.00859914f,0.142945f}, -{-0.316149f,0.0162055f,0.143141f},{-0.314695f,0.0098903f,0.143228f},{-0.319944f,0.0175985f,0.143972f}, -{-0.31878f,0.0110874f,0.143884f},{-0.323681f,0.0190677f,0.144928f},{-0.322664f,0.012233f,0.144779f}, -{-0.327398f,0.0205663f,0.145919f},{-0.326479f,0.0134127f,0.14569f},{-0.331113f,0.0220671f,0.146916f}, -{-0.330311f,0.0146265f,0.1466f},{-0.338577f,0.00932143f,0.147589f},{-0.264f,0.00690312f,0.143579f}, -{-0.268335f,0.00719191f,0.143259f},{-0.272663f,0.00746979f,0.142843f},{-0.285643f,0.00814762f,0.141414f}, -{-0.276988f,0.0077197f,0.142379f},{-0.281312f,0.00793083f,0.141883f},{-0.298329f,0.0110361f,0.141582f}, -{-0.302474f,0.0123542f,0.141829f},{-0.289949f,0.00871456f,0.141206f},{-0.294168f,0.00976951f,0.141335f}, -{-0.314917f,0.0162476f,0.14273f},{-0.310786f,0.0149252f,0.142321f},{-0.306622f,0.0136614f,0.142081f}, -{-0.322891f,0.0192347f,0.144536f},{-0.318943f,0.0176916f,0.143534f},{-0.326807f,0.0208212f,0.145595f}, -{-0.330719f,0.022413f,0.146665f},{-0.33463f,0.0239981f,0.147749f},{-0.338577f,0.0254927f,0.148829f}, -{-0.264f,0.00767576f,0.142941f},{-0.268111f,0.00790232f,0.142685f},{-0.272215f,0.00812312f,0.142338f}, -{-0.284517f,0.00864847f,0.1411f},{-0.276317f,0.00831807f,0.141942f},{-0.280417f,0.00849626f,0.141525f}, -{-0.296607f,0.0109591f,0.141114f},{-0.288618f,0.00897354f,0.140816f},{-0.292654f,0.00981108f,0.140864f}, -{-0.308402f,0.0146249f,0.141884f},{-0.304467f,0.0134151f,0.141621f},{-0.30054f,0.0121769f,0.141369f}, -{-0.320015f,0.0184881f,0.143513f},{-0.312344f,0.0158082f,0.142159f},{-0.316233f,0.0170869f,0.142657f}, -{-0.323738f,0.0199696f,0.144491f},{-0.32744f,0.0214809f,0.145503f},{-0.33114f,0.0229915f,0.146524f}, -{-0.334841f,0.0244911f,0.147559f},{-0.338577f,0.0259001f,0.148595f},{-0.264f,0.00844643f,0.142304f}, -{-0.268112f,0.0086212f,0.142086f},{-0.272217f,0.00879266f,0.141776f},{-0.284522f,0.00917932f,0.140643f}, -{-0.27632f,0.00894054f,0.141415f},{-0.296616f,0.0113914f,0.140713f},{-0.288623f,0.00946126f,0.140385f}, -{-0.292661f,0.0102671f,0.14045f},{-0.308414f,0.0149971f,0.141521f},{-0.304478f,0.0138071f,0.141245f}, -{-0.30055f,0.0125887f,0.140981f},{-0.320025f,0.0188214f,0.143167f},{-0.312357f,0.0161597f,0.14181f}, -{-0.316245f,0.0174245f,0.142314f},{-0.323745f,0.0203004f,0.144141f},{-0.327445f,0.0218097f,0.145149f}, -{-0.331143f,0.0233168f,0.146167f},{-0.334842f,0.0248099f,0.147201f},{-0.338577f,0.0262067f,0.148241f}, -{-0.280421f,0.0090726f,0.141033f},{-0.264f,0.00921688f,0.141668f},{-0.268109f,0.00933302f,0.141483f}, -{-0.272213f,0.00944958f,0.141206f},{-0.284511f,0.00968445f,0.140171f},{-0.276314f,0.00954568f,0.140879f}, -{-0.296607f,0.0117779f,0.140285f},{-0.288611f,0.00991732f,0.139936f},{-0.29265f,0.0106844f,0.140013f}, -{-0.308407f,0.0153055f,0.141121f},{-0.304471f,0.0141412f,0.140836f},{-0.300542f,0.0129485f,0.140562f}, -{-0.320019f,0.0190685f,0.142768f},{-0.316239f,0.0176844f,0.141924f},{-0.312351f,0.016441f,0.141419f}, -{-0.32374f,0.0205358f,0.143733f},{-0.32744f,0.0220341f,0.144732f},{-0.331138f,0.0235282f,0.145742f}, -{-0.334839f,0.0250051f,0.146769f},{-0.338577f,0.0263788f,0.147805f},{-0.280413f,0.00962732f,0.140529f}, -{-0.268106f,0.00976429f,0.141114f},{-0.264f,0.00968775f,0.141279f},{-0.280402f,0.00995451f,0.140217f}, -{-0.276306f,0.00990606f,0.140549f},{-0.272207f,0.00984421f,0.140856f},{-0.292635f,0.0109184f,0.13974f}, -{-0.284498f,0.00997907f,0.139878f},{-0.304457f,0.0143137f,0.140577f},{-0.300528f,0.01314f,0.140298f}, -{-0.296593f,0.0119892f,0.140016f},{-0.316228f,0.0178005f,0.141673f},{-0.312338f,0.0165744f,0.141169f}, -{-0.308394f,0.015459f,0.140867f},{-0.323731f,0.0206269f,0.143469f},{-0.320009f,0.0191718f,0.142511f}, -{-0.327432f,0.0221132f,0.144461f},{-0.331132f,0.0235942f,0.145464f},{-0.334836f,0.0250554f,0.146485f}, -{-0.338577f,0.0264087f,0.147518f},{-0.288596f,0.0101788f,0.139657f},{-0.302478f,0.0137161f,0.140288f}, -{-0.298329f,0.0124851f,0.140002f},{-0.294164f,0.0113146f,0.139715f},{-0.28994f,0.0103804f,0.139538f}, -{-0.285632f,0.00997452f,0.139665f},{-0.281304f,0.00994023f,0.140012f},{-0.276982f,0.00991203f,0.140375f}, -{-0.272659f,0.009849f,0.140706f},{-0.268332f,0.00976769f,0.140986f},{-0.264f,0.00968775f,0.141169f}, -{-0.306628f,0.014938f,0.140581f},{-0.310795f,0.0161103f,0.140863f},{-0.314927f,0.0173564f,0.141293f}, -{-0.318949f,0.0187613f,0.142077f},{-0.322893f,0.0202782f,0.143048f},{-0.326806f,0.021842f,0.144073f}, -{-0.330714f,0.0234057f,0.145113f},{-0.334625f,0.024951f,0.146173f},{-0.338577f,0.0263814f,0.147244f}, -{-0.268582f,0.00976336f,0.140775f},{-0.264f,0.00968775f,0.140979f},{-0.282301f,0.00990978f,0.139723f}, -{-0.27773f,0.00989796f,0.140113f},{-0.273158f,0.00983969f,0.140469f},{-0.291415f,0.0106101f,0.139359f}, -{-0.295853f,0.0117247f,0.139609f},{-0.286881f,0.00998742f,0.139387f},{-0.304641f,0.0142908f,0.140193f}, -{-0.309044f,0.0155467f,0.140484f},{-0.300252f,0.0129908f,0.139902f},{-0.321941f,0.0197978f,0.142487f}, -{-0.317743f,0.0182285f,0.141521f},{-0.313441f,0.0168071f,0.140836f},{-0.326094f,0.0214356f,0.143538f}, -{-0.330239f,0.0230806f,0.14461f},{-0.334386f,0.0247084f,0.145702f},{-0.338577f,0.0262125f,0.146805f}, -{-0.268576f,0.00974593f,0.140582f},{-0.264f,0.00968775f,0.140788f},{-0.282277f,0.00985594f,0.139537f}, -{-0.277712f,0.00985469f,0.139924f},{-0.273146f,0.00980831f,0.140278f},{-0.295818f,0.0116247f,0.13941f}, -{-0.28685f,0.00992109f,0.139202f},{-0.304602f,0.0141594f,0.139977f},{-0.309003f,0.0154002f,0.140259f}, -{-0.300215f,0.0128748f,0.139695f},{-0.321909f,0.0195912f,0.142214f},{-0.317704f,0.0180446f,0.141269f}, -{-0.3134f,0.0166436f,0.140601f},{-0.326069f,0.021206f,0.143245f},{-0.330222f,0.0228275f,0.144296f}, -{-0.334378f,0.0244304f,0.145365f},{-0.338577f,0.0259067f,0.146446f},{-0.291381f,0.0105278f,0.139169f}, -{-0.268569f,0.00972275f,0.140397f},{-0.264f,0.00968775f,0.140597f},{-0.282252f,0.00978412f,0.139372f}, -{-0.277693f,0.0097971f,0.139752f},{-0.273133f,0.00976655f,0.140099f},{-0.291345f,0.0104201f,0.139009f}, -{-0.295781f,0.0114944f,0.139248f},{-0.286819f,0.00983335f,0.139043f},{-0.304563f,0.013988f,0.139811f}, -{-0.308962f,0.0152086f,0.14009f},{-0.300177f,0.0127235f,0.13953f},{-0.321876f,0.01932f,0.142022f}, -{-0.317666f,0.017804f,0.141087f},{-0.313358f,0.0164298f,0.140429f},{-0.326044f,0.0209031f,0.143041f}, -{-0.330205f,0.0224922f,0.144081f},{-0.334369f,0.0240607f,0.145139f},{-0.338577f,0.0254987f,0.146209f}, -{-0.268205f,-0.0240512f,0.145139f},{-0.264f,-0.0254987f,0.146209f},{-0.276531f,-0.0208987f,0.143038f}, -{-0.272372f,-0.0224907f,0.144081f},{-0.289223f,-0.0164319f,0.14044f},{-0.29362f,-0.015224f,0.140101f}, -{-0.284903f,-0.0177924f,0.141053f},{-0.302398f,-0.0127141f,0.139531f},{-0.306793f,-0.0114783f,0.139232f}, -{-0.298012f,-0.0139803f,0.139813f},{-0.320325f,-0.00981234f,0.139389f},{-0.315765f,-0.00988648f,0.139069f}, -{-0.311233f,-0.0103884f,0.138993f},{-0.324884f,-0.00979575f,0.139753f},{-0.329444f,-0.00976673f,0.1401f}, -{-0.334007f,-0.00972076f,0.140404f},{-0.338577f,-0.00968775f,0.140597f},{-0.280697f,-0.0193145f,0.142013f}, -{-0.268196f,-0.0244211f,0.145365f},{-0.264f,-0.0259067f,0.146446f},{-0.280665f,-0.0195856f,0.142206f}, -{-0.276506f,-0.0212016f,0.143242f},{-0.272354f,-0.0228261f,0.144296f},{-0.289182f,-0.016646f,0.140613f}, -{-0.29358f,-0.0154158f,0.14027f},{-0.284865f,-0.0180326f,0.141234f},{-0.306756f,-0.0116084f,0.139394f}, -{-0.30236f,-0.0128655f,0.139695f},{-0.297973f,-0.0141518f,0.13998f},{-0.320299f,-0.0098846f,0.139554f}, -{-0.315733f,-0.0099743f,0.139229f},{-0.311197f,-0.0104962f,0.139152f},{-0.324865f,-0.00985341f,0.139926f}, -{-0.329431f,-0.00980859f,0.140279f},{-0.334001f,-0.0097442f,0.140589f},{-0.338577f,-0.00968775f,0.140788f}, -{-0.268187f,-0.0246992f,0.145701f},{-0.264f,-0.0262125f,0.146805f},{-0.280632f,-0.019792f,0.142478f}, -{-0.276481f,-0.0214312f,0.143536f},{-0.272337f,-0.0230793f,0.144611f},{-0.293539f,-0.0155626f,0.140495f}, -{-0.284826f,-0.0182163f,0.141486f},{-0.30672f,-0.0117083f,0.139593f},{-0.302322f,-0.0129816f,0.139903f}, -{-0.297934f,-0.0142832f,0.140196f},{-0.320275f,-0.00993888f,0.139741f},{-0.315703f,-0.0100406f,0.139415f}, -{-0.311163f,-0.0105787f,0.139342f},{-0.324847f,-0.00989672f,0.140115f},{-0.329419f,-0.00984006f,0.140471f}, -{-0.333995f,-0.00976183f,0.140782f},{-0.338577f,-0.00968775f,0.140979f},{-0.289141f,-0.0168098f,0.140849f}, -{-0.264f,-0.0264087f,0.147518f},{-0.275145f,-0.0221132f,0.144461f},{-0.271445f,-0.0235942f,0.145464f}, -{-0.267741f,-0.0250554f,0.146485f},{-0.28635f,-0.0178005f,0.141673f},{-0.290239f,-0.0165745f,0.141169f}, -{-0.278846f,-0.0206269f,0.143469f},{-0.282568f,-0.0191717f,0.142511f},{-0.302049f,-0.01314f,0.140298f}, -{-0.29812f,-0.0143137f,0.140577f},{-0.294183f,-0.015459f,0.140867f},{-0.313981f,-0.0101788f,0.139657f}, -{-0.309942f,-0.0109184f,0.13974f},{-0.305984f,-0.0119892f,0.140016f},{-0.322175f,-0.00995447f,0.140217f}, -{-0.318079f,-0.00997902f,0.139878f},{-0.326272f,-0.00990604f,0.140549f},{-0.33037f,-0.0098442f,0.140856f}, -{-0.334471f,-0.00976429f,0.141114f},{-0.338577f,-0.00968775f,0.141279f},{-0.267949f,-0.0249437f,0.146173f}, -{-0.264f,-0.0263814f,0.147244f},{-0.279681f,-0.0202741f,0.143041f},{-0.27577f,-0.0218394f,0.144071f}, -{-0.271862f,-0.023405f,0.145114f},{-0.287654f,-0.0173571f,0.141303f},{-0.291791f,-0.0161317f,0.140885f}, -{-0.283621f,-0.0187523f,0.14205f},{-0.300094f,-0.0136985f,0.140292f},{-0.304247f,-0.0124827f,0.140001f}, -{-0.295948f,-0.0149357f,0.140582f},{-0.31264f,-0.010352f,0.139523f},{-0.308404f,-0.0112762f,0.139687f}, -{-0.321273f,-0.00995919f,0.140024f},{-0.31695f,-0.010024f,0.139691f},{-0.325595f,-0.00991129f,0.140376f}, -{-0.329918f,-0.00984923f,0.140707f},{-0.338577f,-0.00968775f,0.141169f},{-0.334244f,-0.00976681f,0.140992f}, -{-0.113384f,0.00379135f,0.144903f},{-0.113745f,0.00496458f,0.14459f},{-0.113263f,-0.00742307f,0.147291f}, -{-0.113263f,0.00257039f,0.145216f},{-0.114327f,0.00603944f,0.144293f},{-0.113263f,-0.00240499f,0.146356f}, -{-0.215517f,-0.0211541f,0.148776f},{-0.167133f,-0.0173396f,0.148518f},{-0.118851f,-0.013533f,0.148143f}, -{-0.117569f,-0.0132893f,0.148115f},{-0.116377f,-0.0127783f,0.148054f},{-0.115321f,-0.0120253f,0.147961f}, -{-0.114448f,-0.0110634f,0.147836f},{-0.113799f,-0.00994277f,0.14768f},{-0.113398f,-0.00870927f,0.147496f}, -{-0.113525f,-0.0123416f,0.145204f},{-0.112615f,-0.0109102f,0.145018f},{-0.114734f,-0.0135295f,0.145346f}, -{-0.15205f,-0.0164058f,0.14564f},{-0.189366f,-0.0192822f,0.145867f},{-0.226683f,-0.0221586f,0.146027f}, -{-0.112054f,-0.00932212f,0.144792f},{-0.111865f,-0.00765064f,0.144531f},{-0.119322f,0.00968775f,0.140407f}, -{-0.117633f,0.00949318f,0.140468f},{-0.112587f,0.00543154f,0.141666f},{-0.112048f,0.00387196f,0.142086f}, -{-0.116038f,0.00892517f,0.140645f},{-0.114625f,0.0080214f,0.14092f},{-0.113456f,0.00683431f,0.141269f}, -{-0.111865f,0.00223012f,0.142505f},{-0.119322f,0.00968775f,0.141279f},{-0.111865f,-0.00268915f,0.144987f}, -{-0.111865f,0.00223012f,0.14386f},{-0.111865f,-0.00765064f,0.145911f},{-0.116009f,-0.0143331f,0.145639f}, -{-0.117166f,-0.0147899f,0.146726f},{-0.117347f,-0.0148426f,0.146158f},{-0.118743f,-0.0150857f,0.146754f}, -{-0.115703f,-0.014171f,0.146666f},{-0.1144f,-0.0132538f,0.146574f},{-0.113328f,-0.0120868f,0.14645f}, -{-0.112525f,-0.0107201f,0.146296f},{-0.112032f,-0.00921907f,0.146114f},{-0.114787f,0.00815064f,0.142549f}, -{-0.113553f,0.00695586f,0.14283f},{-0.112058f,0.00391721f,0.143508f},{-0.112631f,0.00552233f,0.143157f}, -{-0.116176f,0.0089918f,0.141854f},{-0.117706f,0.00951028f,0.141426f},{-0.113829f,0.00632699f,0.144055f}, -{-0.113789f,0.0068323f,0.143638f},{-0.114001f,0.00732043f,0.143234f},{-0.114347f,0.00776225f,0.14287f}, -{-0.227685f,-0.0235779f,0.147426f},{-0.216179f,-0.0219204f,0.148625f},{-0.216137f,-0.0224876f,0.148085f}, -{-0.155057f,-0.0179164f,0.147043f},{-0.118746f,-0.0149745f,0.1473f},{-0.167425f,-0.0186837f,0.147841f}, -{-0.118809f,-0.0140869f,0.148094f},{-0.167468f,-0.0180963f,0.148384f},{-0.11877f,-0.0146193f,0.147797f}, -{-0.191371f,-0.0207472f,0.147267f},{-0.112274f,-0.00748972f,0.146886f},{-0.112435f,-0.00897658f,0.147115f}, -{-0.112116f,-0.00911758f,0.146645f},{-0.112887f,-0.0103998f,0.147311f},{-0.113376f,-0.0119652f,0.146998f}, -{-0.112592f,-0.0106014f,0.146835f},{-0.114648f,-0.0128307f,0.147613f},{-0.11572f,-0.0140507f,0.147224f}, -{-0.114435f,-0.0131339f,0.147128f},{-0.117179f,-0.0146743f,0.147286f},{-0.114951f,-0.0124497f,0.147903f}, -{-0.114003f,-0.0113986f,0.14777f},{-0.117405f,-0.0138348f,0.148064f},{-0.117272f,-0.0143101f,0.147775f}, -{-0.116101f,-0.013274f,0.148f},{-0.112748f,-0.00743905f,0.147194f},{-0.112873f,-0.00883688f,0.14741f}, -{-0.111963f,-0.00756687f,0.146419f},{-0.1133f,-0.0101719f,0.147604f},{-0.115877f,-0.0137111f,0.147711f}, -{-0.113636f,-0.0117086f,0.147479f},{-0.112073f,-0.00254212f,0.145696f},{-0.112539f,-0.0024474f,0.146152f}, -{-0.112048f,0.00239822f,0.14453f},{-0.112586f,0.00252701f,0.145044f},{-0.11229f,0.00405957f,0.14418f}, -{-0.113281f,0.00550952f,0.144258f},{-0.112863f,0.00559184f,0.143809f},{-0.112743f,0.00407172f,0.14463f}, -{-0.227099f,-0.022887f,0.146255f},{-0.227063f,-0.0233314f,0.14672f},{-0.151481f,-0.0174497f,0.14634f}, -{-0.189252f,-0.0203893f,0.146565f},{-0.189288f,-0.0199559f,0.146102f},{-0.151517f,-0.0170273f,0.145879f}, -{-0.489052f,0.0123416f,0.145204f},{-0.489962f,0.0109102f,0.145018f},{-0.487844f,0.0135295f,0.145346f}, -{-0.450527f,0.0164058f,0.14564f},{-0.413211f,0.0192822f,0.145867f},{-0.375894f,0.0221586f,0.146027f}, -{-0.490523f,0.00932212f,0.144792f},{-0.490713f,0.00765064f,0.144531f},{-0.483255f,-0.00968775f,0.140407f}, -{-0.484944f,-0.00949318f,0.140468f},{-0.48999f,-0.00543154f,0.141666f},{-0.49053f,-0.00387196f,0.142086f}, -{-0.486539f,-0.00892517f,0.140645f},{-0.487952f,-0.0080214f,0.14092f},{-0.489121f,-0.00683431f,0.141269f}, -{-0.490713f,-0.00223012f,0.142505f},{-0.489193f,-0.00379135f,0.144903f},{-0.488833f,-0.00496458f,0.14459f}, -{-0.489314f,0.00742307f,0.147291f},{-0.489314f,-0.00257039f,0.145216f},{-0.48825f,-0.00603944f,0.144293f}, -{-0.489314f,0.00240499f,0.146356f},{-0.387061f,0.0211541f,0.148776f},{-0.435444f,0.0173396f,0.148518f}, -{-0.483726f,0.013533f,0.148143f},{-0.485001f,0.0132913f,0.148115f},{-0.486194f,0.0127821f,0.148055f}, -{-0.487252f,0.0120287f,0.147962f},{-0.488124f,0.0110706f,0.147837f},{-0.488776f,0.00994698f,0.14768f}, -{-0.489178f,0.00871793f,0.147497f},{-0.483255f,-0.00968775f,0.141279f},{-0.490713f,0.00268915f,0.144987f}, -{-0.490713f,0.00765064f,0.145911f},{-0.490713f,-0.00223012f,0.14386f},{-0.486568f,0.0143331f,0.145639f}, -{-0.4854f,0.014793f,0.146726f},{-0.48523f,0.0148426f,0.146158f},{-0.483834f,0.0150857f,0.146754f}, -{-0.486869f,0.014174f,0.146667f},{-0.488168f,0.0132606f,0.146575f},{-0.489246f,0.0120925f,0.146451f}, -{-0.490048f,0.0107278f,0.146297f},{-0.490544f,0.00922792f,0.146115f},{-0.48779f,-0.00815064f,0.142549f}, -{-0.489024f,-0.00695586f,0.14283f},{-0.489946f,-0.00552233f,0.143157f},{-0.490519f,-0.00391721f,0.143508f}, -{-0.486401f,-0.0089918f,0.141854f},{-0.484871f,-0.00951028f,0.141426f},{-0.488788f,-0.0068323f,0.143638f}, -{-0.488748f,-0.00632699f,0.144055f},{-0.488576f,-0.00732043f,0.143234f},{-0.48823f,-0.00776225f,0.14287f}, -{-0.374892f,0.0235779f,0.147426f},{-0.386398f,0.0219204f,0.148625f},{-0.38644f,0.0224876f,0.148085f}, -{-0.447521f,0.0179164f,0.147043f},{-0.483831f,0.0149745f,0.1473f},{-0.435152f,0.0186837f,0.147841f}, -{-0.483769f,0.0140869f,0.148094f},{-0.435109f,0.0180963f,0.148384f},{-0.483807f,0.0146193f,0.147797f}, -{-0.411206f,0.0207472f,0.147267f},{-0.486695f,0.0137517f,0.147682f},{-0.485162f,0.013838f,0.148064f}, -{-0.485304f,0.0143462f,0.147745f},{-0.488127f,0.0131473f,0.147128f},{-0.486836f,0.0140617f,0.147224f}, -{-0.485388f,0.0146779f,0.147286f},{-0.48927f,0.0101903f,0.147606f},{-0.488565f,0.0114133f,0.147771f}, -{-0.490167f,0.00899738f,0.147089f},{-0.490614f,0.00756687f,0.146419f},{-0.490303f,0.00748972f,0.146886f}, -{-0.489978f,0.0106218f,0.146837f},{-0.489191f,0.0119815f,0.146999f},{-0.490458f,0.00912889f,0.146646f}, -{-0.489708f,0.0104352f,0.147285f},{-0.489702f,0.00884706f,0.147411f},{-0.487935f,0.0128697f,0.147584f}, -{-0.486458f,0.0132839f,0.148001f},{-0.489829f,0.00743905f,0.147194f},{-0.487613f,0.0124617f,0.147903f}, -{-0.488955f,0.0117456f,0.147451f},{-0.490504f,0.00254212f,0.145696f},{-0.490038f,0.0024474f,0.146152f}, -{-0.490529f,-0.00239822f,0.14453f},{-0.489991f,-0.00252701f,0.145044f},{-0.490287f,-0.00405957f,0.14418f}, -{-0.489296f,-0.00550952f,0.144258f},{-0.489714f,-0.00559184f,0.143809f},{-0.489834f,-0.00407172f,0.14463f}, -{-0.375514f,0.0233314f,0.14672f},{-0.375478f,0.022887f,0.146255f},{-0.45106f,0.0170273f,0.145879f}, -{-0.451096f,0.0174497f,0.14634f},{-0.413325f,0.0203893f,0.146565f},{-0.413289f,0.0199559f,0.146102f}, -{-0.299632f,-0.0043568f,0.127503f},{-0.298639f,-0.00383438f,0.127503f},{-0.297796f,-0.00308638f,0.127503f}, -{-0.29716f,-0.00216232f,0.127503f},{-0.301848f,-0.00462734f,0.127503f},{-0.300722f,-0.00462608f,0.127503f}, -{-0.303933f,-0.00383806f,0.127503f},{-0.302939f,-0.00435903f,0.127503f},{-0.304776f,-0.00309213f,0.127503f}, -{-0.305415f,-0.00216808f,0.127503f},{-0.305813f,-0.00111857f,0.127503f},{-0.296762f,-0.0011128f,0.127503f}, -{-0.298964f,0.00150163f,0.127503f},{-0.29861f,0.000787374f,0.127503f},{-0.29946f,0.00211724f,0.127503f}, -{-0.30013f,0.00254559f,0.127503f},{-0.300894f,0.00276842f,0.127503f},{-0.301689f,0.00276723f,0.127503f}, -{-0.302452f,0.00254283f,0.127503f},{-0.303112f,0.00210508f,0.127503f},{-0.303628f,0.00150519f,0.127503f}, -{-0.303974f,0.00078745f,0.127503f},{-0.302447f,0.00254559f,0.136825f},{-0.301683f,0.00276842f,0.136825f}, -{-0.298949f,0.00150519f,0.136825f},{-0.300888f,0.00276723f,0.136825f},{-0.299465f,0.00210508f,0.136825f}, -{-0.298603f,0.00078745f,0.136825f},{-0.300125f,0.00254283f,0.136825f},{-0.303117f,0.00211724f,0.136825f}, -{-0.303613f,0.00150163f,0.136825f},{-0.303967f,0.000787374f,0.136825f},{-0.322419f,-0.00265777f,0.127503f}, -{-0.321638f,-0.00225612f,0.127503f},{-0.321021f,-0.00163414f,0.127503f},{-0.324145f,-0.00266037f,0.127503f}, -{-0.324923f,-0.00226719f,0.127503f},{-0.323289f,-0.00279661f,0.127503f},{-0.325545f,-0.00165072f,0.127503f}, -{-0.325946f,-0.000869207f,0.127503f},{-0.320631f,-0.000869207f,0.127503f},{-0.278419f,-0.00265777f,0.127503f}, -{-0.277638f,-0.00225612f,0.127503f},{-0.277021f,-0.00163414f,0.127503f},{-0.280145f,-0.00266037f,0.127503f}, -{-0.279289f,-0.00279661f,0.127503f},{-0.281545f,-0.00165072f,0.127503f},{-0.280923f,-0.00226719f,0.127503f}, -{-0.281946f,-0.000869207f,0.127503f},{-0.276631f,-0.000869207f,0.127503f},{-0.0027207f,0.323702f,0.141016f}, -{-0.00279661f,0.323289f,0.127503f},{-0.00276223f,0.322911f,0.140921f},{-0.00254178f,0.324476f,0.141133f}, -{-0.00266037f,0.324145f,0.127503f},{-0.00226719f,0.324923f,0.127503f},{-0.00210085f,0.325128f,0.141283f}, -{-0.000869207f,0.325946f,0.127503f},{-0.00165072f,0.325545f,0.127503f},{-0.00149803f,0.325656f,0.141448f}, -{-0.000793813f,0.325978f,0.141604f},{-2.68373e-017f,0.326085f,0.127503f},{2.12873e-008f,0.326085f,0.141748f}, -{-0.00265777f,0.322419f,0.127503f},{-0.00255964f,0.322139f,0.140869f},{-0.00225612f,0.321638f,0.127503f}, -{-0.00163414f,0.321021f,0.127503f},{-0.00212367f,0.321467f,0.140862f},{-0.000869207f,0.320631f,0.127503f}, -{-0.00151779f,0.320933f,0.140892f},{-0.000793595f,0.320598f,0.140955f},{-2.77368e-017f,0.320492f,0.127503f}, -{-2.77368e-017f,0.320492f,0.141048f},{-0.00226719f,0.280923f,0.127503f},{-0.00266113f,0.280167f,0.141631f}, -{-0.00225617f,0.280949f,0.141475f},{-0.00266037f,0.280145f,0.127503f},{-0.00165072f,0.281545f,0.127503f}, -{-0.00161123f,0.281516f,0.141322f},{-0.000869207f,0.281946f,0.127503f},{-0.000861428f,0.281954f,0.141174f}, -{-0.00279699f,0.279308f,0.141768f},{-2.26626e-008f,0.282085f,0.141048f},{-3.69839e-017f,0.282085f,0.127503f}, -{-0.00279661f,0.279289f,0.127503f},{-0.00267244f,0.278435f,0.141876f},{-0.00227523f,0.277655f,0.141932f}, -{-0.00265777f,0.278419f,0.127503f},{-0.00225612f,0.277638f,0.127503f},{-0.00164828f,0.277026f,0.14193f}, -{-0.00163414f,0.277021f,0.127503f},{-0.000869207f,0.276631f,0.127503f},{-0.000867575f,0.276622f,0.141868f}, -{-3.66414e-017f,0.276492f,0.127503f},{-3.66414e-017f,0.276492f,0.141748f},{0.00279661f,0.301289f,0.136825f}, -{0.00266037f,0.302145f,0.127503f},{0.00226719f,0.299654f,0.136825f},{0.00265777f,0.300419f,0.127503f}, -{0.00225612f,0.299638f,0.127503f},{0.00266037f,0.300432f,0.136825f},{0.00165072f,0.299032f,0.136825f}, -{0.000869207f,0.298631f,0.127503f},{-2.80793e-017f,0.298492f,0.136825f},{0.000869207f,0.298631f,0.136825f}, -{0.00163414f,0.299021f,0.127503f},{-2.80793e-017f,0.298492f,0.127503f},{0.00265777f,0.302158f,0.136825f}, -{0.00226719f,0.302923f,0.127503f},{0.00225612f,0.302939f,0.136825f},{0.00163414f,0.303556f,0.136825f}, -{0.00165072f,0.303545f,0.127503f},{0.000869207f,0.303946f,0.136825f},{0.000869207f,0.303946f,0.127503f}, -{-2.77368e-017f,0.304085f,0.127503f},{-2.77368e-017f,0.304085f,0.136825f},{-0.00383933f,0.303941f,0.140336f}, -{-0.00435933f,0.302938f,0.127503f},{-0.00437081f,0.302948f,0.140342f},{-0.00462728f,0.301847f,0.127503f}, -{-0.00383758f,0.303934f,0.127503f},{-0.00463064f,0.301857f,0.140371f},{-0.00309444f,0.304774f,0.127503f}, -{-0.00308762f,0.304783f,0.140354f},{-0.00216892f,0.305414f,0.127503f},{-0.00463006f,0.300727f,0.140416f}, -{-0.00216891f,0.30543f,0.14039f},{-0.00111911f,0.305813f,0.127503f},{-5.60324e-014f,0.30595f,0.140488f}, -{-3.35892e-010f,0.305949f,0.127503f},{-0.00112174f,0.305823f,0.140439f},{-0.00462657f,0.300724f,0.127503f}, -{-0.00435716f,0.299633f,0.127503f},{-0.00437228f,0.299631f,0.140465f},{-0.00384698f,0.298643f,0.140509f}, -{-0.0038338f,0.298638f,0.127503f},{-0.00308862f,0.297798f,0.127503f},{-0.00309221f,0.2978f,0.140537f}, -{-0.00216381f,0.29716f,0.127503f},{-0.00217168f,0.297151f,0.140543f},{-0.00112329f,0.296754f,0.140525f}, -{-0.00111503f,0.296763f,0.127503f},{-2.77368e-017f,0.296628f,0.140488f},{-2.77368e-017f,0.296628f,0.127503f}, -{-0.0031834f,0.333784f,0.141919f},{0.0034311f,0.333871f,0.143258f},{-0.00348389f,0.329361f,0.141453f}, -{0.013311f,0.321833f,0.142108f},{0.00749864f,0.321483f,0.141891f},{0.01447f,0.325857f,0.142985f}, -{0.0237151f,0.334598f,0.145107f},{0.0168317f,0.334046f,0.144795f},{0.0250351f,0.338577f,0.14612f}, -{0.00309212f,0.304777f,0.140537f},{0.00980991f,0.308789f,0.140443f},{0.00384705f,0.303935f,0.140509f}, -{0.000788852f,0.320598f,0.141161f},{0.00148198f,0.320971f,0.141294f},{0.00113058f,0.316843f,0.140739f}, -{0.00437081f,0.299629f,0.140342f},{0.00463066f,0.30072f,0.140371f},{0.00734722f,0.299868f,0.140099f}, -{-0.00981015f,0.293803f,0.140456f},{0.00383936f,0.298637f,0.140336f},{0.0030876f,0.297795f,0.140354f}, -{0.000835134f,0.29484f,0.140403f},{-0.00565577f,0.289735f,0.140706f},{-0.00448849f,0.294321f,0.140582f}, -{0.000794809f,0.281978f,0.140955f},{0.00431412f,0.286162f,0.139973f},{0.00152033f,0.281642f,0.140892f}, -{-0.0168309f,0.268522f,0.144796f},{-0.0250351f,0.264f,0.14612f},{-0.0237151f,0.26798f,0.145107f}, -{-0.0110109f,0.289229f,0.140705f},{-0.00922726f,0.272859f,0.143432f},{-0.0222833f,0.271923f,0.144104f}, -{-0.0156491f,0.272684f,0.143876f},{0.00348559f,0.273206f,0.141452f},{-0.00283697f,0.273034f,0.142622f}, -{0.000793378f,0.276599f,0.141605f},{0.00318417f,0.268783f,0.141918f},{-0.00342276f,0.268697f,0.143256f}, -{0.00969325f,0.268311f,0.140239f},{0.00290707f,0.264f,0.142335f},{-0.00398877f,0.264f,0.143878f}, -{0.00968775f,0.264f,0.140407f},{0.00378729f,0.277496f,0.140965f},{0.00209478f,0.277448f,0.141284f}, -{0.00253473f,0.278103f,0.141134f},{-0.010107f,0.26861f,0.144218f},{0.00272118f,0.278874f,0.141016f}, -{0.00973119f,0.281218f,0.139327f},{0.00404127f,0.281779f,0.140452f},{0.00858894f,0.304265f,0.140271f}, -{0.000322559f,0.312352f,0.140392f},{-0.00611166f,0.307227f,0.139905f},{-0.0049946f,0.311852f,0.139783f}, -{-0.00734676f,0.30271f,0.140099f},{0.0043723f,0.302947f,0.140465f},{-0.00405908f,0.320788f,0.140464f}, -{-0.00435339f,0.316411f,0.139998f},{0.00217165f,0.305426f,0.140543f},{0.00450063f,0.308268f,0.140568f}, -{0.00253786f,0.322112f,0.141575f},{0.00276739f,0.322873f,0.141709f},{0.00835592f,0.325595f,0.14266f}, -{0.00255847f,0.324441f,0.141903f},{0.00212169f,0.325113f,0.141937f},{0.0208182f,0.326719f,0.143118f}, -{0.00398877f,0.338577f,0.143878f},{0.0156505f,0.329883f,0.143875f},{-0.00968775f,0.338577f,0.140407f}, -{-0.00290707f,0.338577f,0.142335f},{-0.00969325f,0.334267f,0.140239f},{-0.00973122f,0.321359f,0.139327f}, -{-0.00972934f,0.32566f,0.139659f},{-0.00378494f,0.325074f,0.140965f},{0.0121774f,0.317712f,0.141276f}, -{0.00665136f,0.317277f,0.141165f},{-0.000816648f,0.307746f,0.140389f},{0.0027728f,0.323672f,0.141822f}, -{0.0101155f,0.333958f,0.144218f},{0.0179944f,0.338577f,0.145774f},{0.0222833f,0.330654f,0.144104f}, -{0.0109671f,0.338577f,0.145026f},{-0.0097173f,0.329962f,0.139971f},{-0.0097497f,0.317058f,0.139013f}, -{-0.00858896f,0.298313f,0.140271f},{0.00613049f,0.295355f,0.139921f},{-0.00115281f,0.285728f,0.140712f}, -{0.00500873f,0.290743f,0.139791f},{0.0120097f,0.298192f,0.13929f},{0.0108714f,0.294038f,0.138995f}, -{0.00463004f,0.30185f,0.140416f},{0.0131607f,0.30234f,0.139564f},{0.0143354f,0.306481f,0.139836f}, -{0.00566917f,0.312855f,0.140697f},{0.0110148f,0.313358f,0.140695f},{-0.0100181f,0.312766f,0.138847f}, -{-0.0108714f,0.308539f,0.138995f},{-0.0120097f,0.304385f,0.13929f},{-0.0131607f,0.300237f,0.139564f}, -{-0.0143354f,0.296096f,0.139836f},{-0.00666271f,0.285291f,0.14114f},{-0.00749967f,0.281083f,0.141879f}, -{0.00277232f,0.279664f,0.14092f},{0.00972932f,0.276917f,0.139659f},{0.00149718f,0.276921f,0.141448f}, -{-0.0121843f,0.284854f,0.141251f},{0.00255887f,0.280437f,0.140869f},{0.00212359f,0.28111f,0.140862f}, -{-0.000305779f,0.290241f,0.140401f},{0.00112176f,0.296754f,0.140439f},{0.00216894f,0.297147f,0.14039f}, -{-0.0133136f,0.280732f,0.142096f},{-0.00834704f,0.276975f,0.14266f},{-0.0144683f,0.276713f,0.142986f}, -{0.0028458f,0.329534f,0.142624f},{0.0092361f,0.329708f,0.143432f},{0.00151619f,0.325643f,0.141923f}, -{0.00079021f,0.325978f,0.141859f},{0.019351f,0.322781f,0.142144f},{0.0179262f,0.318817f,0.14121f}, -{0.0166178f,0.314771f,0.140509f},{0.00210151f,0.321454f,0.141433f},{0.00112326f,0.305823f,0.140525f}, -{0.0154659f,0.310634f,0.14012f},{0.0100181f,0.289811f,0.138847f},{-0.0154659f,0.291943f,0.14012f}, -{0.00974966f,0.285519f,0.139013f},{-0.0179262f,0.28376f,0.14121f},{-0.0166178f,0.287806f,0.140509f}, -{-0.0193511f,0.279796f,0.142144f},{-0.0208182f,0.275858f,0.143118f},{0.00971729f,0.272615f,0.139971f}, -{-0.0179944f,0.264f,0.145774f},{-0.0109671f,0.264f,0.145026f},{0.0262081f,0.338577f,0.148238f}, -{0.0248064f,0.334844f,0.147199f},{0.0250058f,0.334839f,0.146766f},{0.0233183f,0.331143f,0.146165f}, -{0.0235291f,0.331138f,0.145739f},{0.0188229f,0.320025f,0.143165f},{0.0190695f,0.320019f,0.142766f}, -{0.0203019f,0.323745f,0.144139f},{0.0205368f,0.32374f,0.143731f},{0.022035f,0.32744f,0.14473f}, -{0.0218112f,0.327445f,0.145147f},{0.015307f,0.308407f,0.141119f},{0.0150041f,0.308412f,0.141517f}, -{0.0141429f,0.304471f,0.140834f},{0.0174212f,0.316248f,0.1423f},{0.0161629f,0.312356f,0.141811f}, -{0.0164424f,0.312351f,0.141416f},{0.0114006f,0.296614f,0.14071f},{0.0106866f,0.29265f,0.140011f}, -{0.0117799f,0.296607f,0.140283f},{0.0125814f,0.300553f,0.14098f},{0.0129503f,0.300542f,0.14056f}, -{0.0138012f,0.30448f,0.141246f},{0.00963024f,0.280413f,0.140526f},{0.00968708f,0.284511f,0.140168f}, -{0.0091952f,0.284522f,0.140649f},{0.0099197f,0.288611f,0.139934f},{0.0102596f,0.292663f,0.140442f}, -{0.00946264f,0.288623f,0.140382f},{0.00907526f,0.280421f,0.141031f},{0.0095489f,0.276313f,0.140876f}, -{0.00894343f,0.27632f,0.141413f},{0.00945311f,0.272213f,0.141203f},{0.00933687f,0.268109f,0.14148f}, -{0.00879579f,0.272217f,0.141773f},{0.0086246f,0.268112f,0.142088f},{0.00922107f,0.264f,0.141665f}, -{0.00845004f,0.264f,0.142301f},{0.0176856f,0.316239f,0.141921f},{0.0263793f,0.338577f,0.147802f}, -{0.0259023f,0.338577f,0.148593f},{0.0244885f,0.334843f,0.147557f},{0.0229936f,0.33114f,0.146522f}, -{0.0184899f,0.320015f,0.143511f},{0.0214828f,0.32744f,0.145501f},{0.0146321f,0.3084f,0.14188f}, -{0.0170843f,0.316236f,0.142644f},{0.0158117f,0.312343f,0.142162f},{0.010968f,0.296605f,0.141112f}, -{0.0121699f,0.300543f,0.141368f},{0.0134094f,0.304469f,0.141622f},{0.0086637f,0.284517f,0.141107f}, -{0.00980481f,0.292656f,0.140857f},{0.00897481f,0.288617f,0.140813f},{0.00849863f,0.280417f,0.141523f}, -{0.00832061f,0.276317f,0.14194f},{0.00812583f,0.272215f,0.142335f},{0.00790535f,0.268111f,0.142688f}, -{0.00767878f,0.264f,0.142938f},{0.0199715f,0.323738f,0.144489f},{0.0254953f,0.338577f,0.148828f}, -{0.0239945f,0.334632f,0.147747f},{0.0224149f,0.330719f,0.146665f},{0.0176882f,0.318949f,0.143502f}, -{0.0208215f,0.326809f,0.145592f},{0.0192329f,0.322894f,0.144529f},{0.0136618f,0.306623f,0.142081f}, -{0.0162503f,0.314913f,0.14274f},{0.0149457f,0.310777f,0.142346f},{0.00869072f,0.289947f,0.141186f}, -{0.00973903f,0.294176f,0.141305f},{0.0110356f,0.29833f,0.141581f},{0.00795144f,0.281312f,0.141896f}, -{0.0081943f,0.285636f,0.14144f},{0.00772122f,0.276988f,0.142378f},{0.00747253f,0.272663f,0.142842f}, -{0.00719397f,0.268336f,0.143263f},{0.00690556f,0.264f,0.143577f},{0.0123399f,0.302479f,0.141831f}, -{0.0250324f,0.338577f,0.148916f},{0.0235306f,0.334606f,0.147857f},{0.0219498f,0.330688f,0.146794f}, -{0.0172517f,0.318889f,0.143711f},{0.0203651f,0.326769f,0.14574f},{0.0132021f,0.306566f,0.142332f}, -{0.0158114f,0.314858f,0.142927f},{0.0144807f,0.310726f,0.142544f},{0.0092687f,0.29412f,0.141666f}, -{0.0105497f,0.298278f,0.141886f},{0.0118813f,0.30242f,0.142106f},{0.0073368f,0.28128f,0.142324f}, -{0.00759572f,0.285604f,0.141811f},{0.00819435f,0.289904f,0.141567f},{0.00708183f,0.276964f,0.142866f}, -{0.00678804f,0.272648f,0.143377f},{0.00646507f,0.268328f,0.143843f},{0.00613003f,0.264f,0.144218f}, -{0.0187868f,0.322844f,0.144697f},{0.00696068f,0.276283f,0.143005f},{0.00667554f,0.272193f,0.143491f}, -{0.00636198f,0.268101f,0.143939f},{0.00748015f,0.284462f,0.141999f},{0.00786981f,0.288553f,0.141631f}, -{0.00722771f,0.280372f,0.1425f},{0.0111819f,0.300465f,0.142035f},{0.00875236f,0.292584f,0.14162f}, -{0.014914f,0.312256f,0.142686f},{0.0124511f,0.304388f,0.142242f},{0.0137038f,0.308316f,0.142453f}, -{0.0175985f,0.319944f,0.143972f},{0.0190677f,0.323681f,0.144928f},{0.0162018f,0.316153f,0.143129f}, -{0.0205663f,0.327398f,0.145919f},{0.022067f,0.331113f,0.146916f},{0.0235578f,0.33483f,0.14792f}, -{0.00994863f,0.29653f,0.141826f},{0.00603944f,0.264f,0.144293f},{0.00744254f,0.330122f,0.145994f}, -{0.015865f,0.334273f,0.147531f},{0.0083666f,0.334181f,0.146789f},{0.000311244f,0.329939f,0.144934f}, -{0.000930332f,0.334089f,0.145573f},{-0.00667554f,0.330384f,0.143491f},{0.00158091f,0.338577f,0.146182f}, -{-0.0063617f,0.334477f,0.143935f},{0.00932143f,0.338577f,0.147589f},{-0.00603944f,0.338577f,0.144293f}, -{0.00654234f,0.326198f,0.145204f},{0.00567271f,0.322287f,0.144415f},{0.0134133f,0.326474f,0.14569f}, -{0.00989537f,0.314708f,0.143217f},{0.0110779f,0.318771f,0.143908f},{0.00388505f,0.314167f,0.143059f}, -{0.0122295f,0.322655f,0.144789f},{0.0072715f,0.306074f,0.142814f},{1.23849e-006f,0.301276f,0.142893f}, -{0.00593214f,0.301855f,0.142703f},{0.00860427f,0.310416f,0.142918f},{0.00327255f,0.293337f,0.142485f}, -{0.00211647f,0.288967f,0.14253f},{-0.00133631f,0.297083f,0.142894f},{0.00459153f,0.297661f,0.142593f}, -{-0.00836678f,0.268392f,0.146789f},{-0.00093054f,0.268483f,0.145573f},{-0.000310969f,0.272633f,0.144934f}, -{0.00135717f,0.284719f,0.142953f},{-0.00485039f,0.284259f,0.143617f},{-0.00158091f,0.264f,0.146182f}, -{0.000284983f,0.276649f,0.144284f},{-0.00744232f,0.27245f,0.145994f},{-0.0171357f,0.264f,0.148501f}, -{-0.0158652f,0.2683f,0.147532f},{0.000835711f,0.280649f,0.143615f},{-0.00654153f,0.276375f,0.145205f}, -{-0.00568021f,0.280282f,0.144405f},{-0.00265603f,0.292762f,0.142905f},{-0.00387587f,0.288426f,0.143071f}, -{0.00267273f,0.309833f,0.142876f},{0.00133739f,0.305495f,0.142892f},{0.00483092f,0.318311f,0.143642f}, -{0.0146267f,0.330306f,0.1466f},{0.0171357f,0.338577f,0.148501f},{-0.0069607f,0.326294f,0.143005f}, -{-0.000284018f,0.325924f,0.144284f},{-0.00722775f,0.322205f,0.1425f},{-0.000847135f,0.321921f,0.143625f}, -{-0.00746803f,0.318116f,0.141989f},{-0.00138663f,0.317854f,0.142978f},{-0.00787057f,0.314024f,0.141632f}, -{-0.00210321f,0.313628f,0.142519f},{-0.00875939f,0.309995f,0.141625f},{-0.00324421f,0.309251f,0.142456f}, -{-0.00994211f,0.306045f,0.141827f},{-0.023562f,0.267749f,0.147921f},{-0.0249766f,0.264f,0.148916f}, -{-0.00458966f,0.304917f,0.142591f},{-0.0111906f,0.302115f,0.142034f},{-0.0124586f,0.298192f,0.142239f}, -{-0.00592971f,0.300697f,0.142704f},{-0.0136985f,0.29426f,0.142455f},{-0.00727121f,0.296504f,0.142816f}, -{-0.0149126f,0.29032f,0.142682f},{-0.00859914f,0.292185f,0.142945f},{-0.0162055f,0.286428f,0.143141f}, -{-0.0098903f,0.287882f,0.143228f},{-0.0175985f,0.282633f,0.143972f},{-0.0110874f,0.283798f,0.143884f}, -{-0.0190677f,0.278896f,0.144928f},{-0.012233f,0.279914f,0.144779f},{-0.0205663f,0.275179f,0.145919f}, -{-0.0134127f,0.276098f,0.14569f},{-0.0220671f,0.271464f,0.146916f},{-0.0146265f,0.272266f,0.1466f}, -{-0.00932143f,0.264f,0.147589f},{-0.00690312f,0.338577f,0.143579f},{-0.00719191f,0.334242f,0.143259f}, -{-0.00746979f,0.329914f,0.142843f},{-0.00814762f,0.316934f,0.141414f},{-0.0077197f,0.325589f,0.142379f}, -{-0.00793083f,0.321266f,0.141883f},{-0.0110361f,0.304248f,0.141582f},{-0.0123542f,0.300103f,0.141829f}, -{-0.00871456f,0.312628f,0.141206f},{-0.00976951f,0.308409f,0.141335f},{-0.0162476f,0.28766f,0.14273f}, -{-0.0149252f,0.291792f,0.142321f},{-0.0136614f,0.295955f,0.142081f},{-0.0192347f,0.279686f,0.144536f}, -{-0.0176916f,0.283634f,0.143534f},{-0.0208212f,0.27577f,0.145595f},{-0.022413f,0.271858f,0.146665f}, -{-0.0239981f,0.267947f,0.147749f},{-0.0254927f,0.264f,0.148829f},{-0.00767576f,0.338577f,0.142941f}, -{-0.00790232f,0.334466f,0.142685f},{-0.00812312f,0.330362f,0.142338f},{-0.00864847f,0.31806f,0.1411f}, -{-0.00831807f,0.32626f,0.141942f},{-0.00849626f,0.32216f,0.141525f},{-0.0109591f,0.30597f,0.141114f}, -{-0.00897354f,0.313959f,0.140816f},{-0.00981108f,0.309923f,0.140864f},{-0.0146249f,0.294175f,0.141884f}, -{-0.0134151f,0.29811f,0.141621f},{-0.0121769f,0.302037f,0.141369f},{-0.0184881f,0.282562f,0.143513f}, -{-0.0158082f,0.290233f,0.142159f},{-0.0170869f,0.286345f,0.142657f},{-0.0199696f,0.278839f,0.144491f}, -{-0.0214809f,0.275137f,0.145503f},{-0.0229915f,0.271437f,0.146524f},{-0.0244911f,0.267736f,0.147559f}, -{-0.0259001f,0.264f,0.148595f},{-0.00844643f,0.338577f,0.142304f},{-0.0086212f,0.334465f,0.142086f}, -{-0.00879266f,0.33036f,0.141776f},{-0.00917932f,0.318055f,0.140643f},{-0.00894054f,0.326258f,0.141415f}, -{-0.0113914f,0.305961f,0.140713f},{-0.00946126f,0.313954f,0.140385f},{-0.0102671f,0.309916f,0.14045f}, -{-0.0149971f,0.294163f,0.141521f},{-0.0138071f,0.298099f,0.141245f},{-0.0125887f,0.302027f,0.140981f}, -{-0.0188214f,0.282552f,0.143167f},{-0.0161597f,0.29022f,0.14181f},{-0.0174245f,0.286332f,0.142314f}, -{-0.0203004f,0.278832f,0.144141f},{-0.0218097f,0.275132f,0.145149f},{-0.0233168f,0.271434f,0.146167f}, -{-0.0248099f,0.267735f,0.147201f},{-0.0262067f,0.264f,0.148241f},{-0.0090726f,0.322157f,0.141033f}, -{-0.00921688f,0.338577f,0.141668f},{-0.00933302f,0.334468f,0.141483f},{-0.00944958f,0.330364f,0.141206f}, -{-0.00968445f,0.318066f,0.140171f},{-0.00954568f,0.326264f,0.140879f},{-0.0117779f,0.30597f,0.140285f}, -{-0.00991732f,0.313966f,0.139936f},{-0.0106844f,0.309927f,0.140013f},{-0.0153055f,0.29417f,0.141121f}, -{-0.0141412f,0.298106f,0.140836f},{-0.0129485f,0.302035f,0.140562f},{-0.0190685f,0.282558f,0.142768f}, -{-0.0176844f,0.286338f,0.141924f},{-0.016441f,0.290226f,0.141419f},{-0.0205358f,0.278837f,0.143733f}, -{-0.0220341f,0.275137f,0.144732f},{-0.0235282f,0.271439f,0.145742f},{-0.0250051f,0.267738f,0.146769f}, -{-0.0263788f,0.264f,0.147805f},{-0.00962732f,0.322165f,0.140529f},{-0.00976429f,0.334471f,0.141114f}, -{-0.00968775f,0.338577f,0.141279f},{-0.00995451f,0.322175f,0.140217f},{-0.00990606f,0.326272f,0.140549f}, -{-0.00984421f,0.33037f,0.140856f},{-0.0109184f,0.309942f,0.13974f},{-0.00997907f,0.318079f,0.139878f}, -{-0.0143137f,0.29812f,0.140577f},{-0.01314f,0.302049f,0.140298f},{-0.0119892f,0.305984f,0.140016f}, -{-0.0178005f,0.28635f,0.141673f},{-0.0165744f,0.290239f,0.141169f},{-0.015459f,0.294183f,0.140867f}, -{-0.0206269f,0.278846f,0.143469f},{-0.0191718f,0.282568f,0.142511f},{-0.0221132f,0.275145f,0.144461f}, -{-0.0235942f,0.271445f,0.145464f},{-0.0250554f,0.267741f,0.146485f},{-0.0264087f,0.264f,0.147518f}, -{-0.0101788f,0.313981f,0.139657f},{-0.0137161f,0.300099f,0.140288f},{-0.0124851f,0.304248f,0.140002f}, -{-0.0113146f,0.308413f,0.139715f},{-0.0103804f,0.312637f,0.139538f},{-0.00997452f,0.316945f,0.139665f}, -{-0.00994023f,0.321273f,0.140012f},{-0.00991203f,0.325595f,0.140375f},{-0.009849f,0.329918f,0.140706f}, -{-0.00976769f,0.334245f,0.140986f},{-0.00968775f,0.338577f,0.141169f},{-0.014938f,0.295949f,0.140581f}, -{-0.0161103f,0.291782f,0.140863f},{-0.0173564f,0.28765f,0.141293f},{-0.0187613f,0.283628f,0.142077f}, -{-0.0202782f,0.279684f,0.143048f},{-0.021842f,0.275771f,0.144073f},{-0.0234057f,0.271863f,0.145113f}, -{-0.024951f,0.267952f,0.146173f},{-0.0263814f,0.264f,0.147244f},{-0.00976336f,0.333995f,0.140775f}, -{-0.00968775f,0.338577f,0.140979f},{-0.00990978f,0.320276f,0.139723f},{-0.00989796f,0.324847f,0.140113f}, -{-0.00983969f,0.329419f,0.140469f},{-0.0106101f,0.311162f,0.139359f},{-0.0117247f,0.306724f,0.139609f}, -{-0.00998742f,0.315696f,0.139387f},{-0.0142908f,0.297936f,0.140193f},{-0.0155467f,0.293533f,0.140484f}, -{-0.0129908f,0.302325f,0.139902f},{-0.0197978f,0.280636f,0.142487f},{-0.0182285f,0.284834f,0.141521f}, -{-0.0168071f,0.289136f,0.140836f},{-0.0214356f,0.276483f,0.143538f},{-0.0230806f,0.272338f,0.14461f}, -{-0.0247084f,0.268191f,0.145702f},{-0.0262125f,0.264f,0.146805f},{-0.00974593f,0.334001f,0.140582f}, -{-0.00968775f,0.338577f,0.140788f},{-0.00985594f,0.3203f,0.139537f},{-0.00985469f,0.324865f,0.139924f}, -{-0.00980831f,0.329431f,0.140278f},{-0.0116247f,0.30676f,0.13941f},{-0.00992109f,0.315727f,0.139202f}, -{-0.0141594f,0.297975f,0.139977f},{-0.0154002f,0.293574f,0.140259f},{-0.0128748f,0.302362f,0.139695f}, -{-0.0195912f,0.280668f,0.142214f},{-0.0180446f,0.284873f,0.141269f},{-0.0166436f,0.289177f,0.140601f}, -{-0.021206f,0.276508f,0.143245f},{-0.0228275f,0.272355f,0.144296f},{-0.0244304f,0.268199f,0.145365f}, -{-0.0259067f,0.264f,0.146446f},{-0.0105278f,0.311196f,0.139169f},{-0.00972275f,0.334008f,0.140397f}, -{-0.00968775f,0.338577f,0.140597f},{-0.00978412f,0.320325f,0.139372f},{-0.0097971f,0.324884f,0.139752f}, -{-0.00976655f,0.329444f,0.140099f},{-0.0104201f,0.311232f,0.139009f},{-0.0114944f,0.306797f,0.139248f}, -{-0.00983335f,0.315758f,0.139043f},{-0.013988f,0.298014f,0.139811f},{-0.0152086f,0.293615f,0.14009f}, -{-0.0127235f,0.3024f,0.13953f},{-0.01932f,0.280701f,0.142022f},{-0.017804f,0.284911f,0.141087f}, -{-0.0164298f,0.289219f,0.140429f},{-0.0209031f,0.276533f,0.143041f},{-0.0224922f,0.272372f,0.144081f}, -{-0.0240607f,0.268208f,0.145139f},{-0.0254987f,0.264f,0.146209f},{0.0240512f,0.334373f,0.145139f}, -{0.0254987f,0.338577f,0.146209f},{0.0208987f,0.326047f,0.143038f},{0.0224907f,0.330206f,0.144081f}, -{0.0164319f,0.313354f,0.14044f},{0.015224f,0.308957f,0.140101f},{0.0177924f,0.317674f,0.141053f}, -{0.0127141f,0.300179f,0.139531f},{0.0114783f,0.295784f,0.139232f},{0.0139803f,0.304565f,0.139813f}, -{0.00981234f,0.282253f,0.139389f},{0.00988648f,0.286812f,0.139069f},{0.0103884f,0.291345f,0.138993f}, -{0.00979575f,0.277693f,0.139753f},{0.00976673f,0.273133f,0.1401f},{0.00972076f,0.26857f,0.140404f}, -{0.00968775f,0.264f,0.140597f},{0.0193145f,0.32188f,0.142013f},{0.0244211f,0.334381f,0.145365f}, -{0.0259067f,0.338577f,0.146446f},{0.0195856f,0.321913f,0.142206f},{0.0212016f,0.326071f,0.143242f}, -{0.0228261f,0.330223f,0.144296f},{0.016646f,0.313395f,0.140613f},{0.0154158f,0.308997f,0.14027f}, -{0.0180326f,0.317712f,0.141234f},{0.0116084f,0.295821f,0.139394f},{0.0128655f,0.300217f,0.139695f}, -{0.0141518f,0.304604f,0.13998f},{0.0098846f,0.282278f,0.139554f},{0.0099743f,0.286844f,0.139229f}, -{0.0104962f,0.29138f,0.139152f},{0.00985341f,0.277712f,0.139926f},{0.00980859f,0.273146f,0.140279f}, -{0.0097442f,0.268576f,0.140589f},{0.00968775f,0.264f,0.140788f},{0.0246992f,0.33439f,0.145701f}, -{0.0262125f,0.338577f,0.146805f},{0.019792f,0.321945f,0.142478f},{0.0214312f,0.326096f,0.143536f}, -{0.0230793f,0.33024f,0.144611f},{0.0155626f,0.309038f,0.140495f},{0.0182163f,0.317751f,0.141486f}, -{0.0117083f,0.295857f,0.139593f},{0.0129816f,0.300255f,0.139903f},{0.0142832f,0.304643f,0.140196f}, -{0.00993888f,0.282302f,0.139741f},{0.0100406f,0.286874f,0.139415f},{0.0105787f,0.291414f,0.139342f}, -{0.00989672f,0.27773f,0.140115f},{0.00984006f,0.273158f,0.140471f},{0.00976183f,0.268582f,0.140782f}, -{0.00968775f,0.264f,0.140979f},{0.0168098f,0.313436f,0.140849f},{0.0264087f,0.338577f,0.147518f}, -{0.0221132f,0.327432f,0.144461f},{0.0235942f,0.331132f,0.145464f},{0.0250554f,0.334836f,0.146485f}, -{0.0178005f,0.316228f,0.141673f},{0.0165745f,0.312338f,0.141169f},{0.0206269f,0.323731f,0.143469f}, -{0.0191717f,0.320009f,0.142511f},{0.01314f,0.300528f,0.140298f},{0.0143137f,0.304457f,0.140577f}, -{0.015459f,0.308394f,0.140867f},{0.0101788f,0.288596f,0.139657f},{0.0109184f,0.292635f,0.13974f}, -{0.0119892f,0.296593f,0.140016f},{0.00995447f,0.280402f,0.140217f},{0.00997902f,0.284498f,0.139878f}, -{0.00990604f,0.276306f,0.140549f},{0.0098442f,0.272207f,0.140856f},{0.00976429f,0.268106f,0.141114f}, -{0.00968775f,0.264f,0.141279f},{0.0249437f,0.334628f,0.146173f},{0.0263814f,0.338577f,0.147244f}, -{0.0202741f,0.322896f,0.143041f},{0.0218394f,0.326807f,0.144071f},{0.023405f,0.330715f,0.145114f}, -{0.0173571f,0.314923f,0.141303f},{0.0161317f,0.310786f,0.140885f},{0.0187523f,0.318956f,0.14205f}, -{0.0136985f,0.302483f,0.140292f},{0.0124827f,0.29833f,0.140001f},{0.0149357f,0.306629f,0.140582f}, -{0.010352f,0.289937f,0.139523f},{0.0112762f,0.294173f,0.139687f},{0.00995919f,0.281305f,0.140024f}, -{0.010024f,0.285627f,0.139691f},{0.00991129f,0.276982f,0.140376f},{0.00984923f,0.272659f,0.140707f}, -{0.00968775f,0.264f,0.141169f},{0.00976681f,0.268333f,0.140992f},{-0.00379135f,0.489193f,0.144903f}, -{-0.00496458f,0.488833f,0.14459f},{0.00742307f,0.489314f,0.147291f},{-0.00257039f,0.489314f,0.145216f}, -{-0.00603944f,0.48825f,0.144293f},{0.00240499f,0.489314f,0.146356f},{0.0211541f,0.387061f,0.148776f}, -{0.0173396f,0.435444f,0.148518f},{0.013533f,0.483726f,0.148143f},{0.0132893f,0.485008f,0.148115f}, -{0.0127783f,0.4862f,0.148054f},{0.0120253f,0.487256f,0.147961f},{0.0110634f,0.488129f,0.147836f}, -{0.00994277f,0.488778f,0.14768f},{0.00870927f,0.489179f,0.147496f},{0.0123416f,0.489052f,0.145204f}, -{0.0109102f,0.489962f,0.145018f},{0.0135295f,0.487844f,0.145346f},{0.0164058f,0.450527f,0.14564f}, -{0.0192822f,0.413211f,0.145867f},{0.0221586f,0.375894f,0.146027f},{0.00932212f,0.490523f,0.144792f}, -{0.00765064f,0.490713f,0.144531f},{-0.00968775f,0.483255f,0.140407f},{-0.00949318f,0.484944f,0.140468f}, -{-0.00543154f,0.48999f,0.141666f},{-0.00387196f,0.49053f,0.142086f},{-0.00892517f,0.486539f,0.140645f}, -{-0.0080214f,0.487952f,0.14092f},{-0.00683431f,0.489121f,0.141269f},{-0.00223012f,0.490713f,0.142505f}, -{-0.00968775f,0.483255f,0.141279f},{0.00268915f,0.490713f,0.144987f},{-0.00223012f,0.490713f,0.14386f}, -{0.00765064f,0.490713f,0.145911f},{0.0143331f,0.486568f,0.145639f},{0.0147899f,0.485411f,0.146726f}, -{0.0148426f,0.48523f,0.146158f},{0.0150857f,0.483834f,0.146754f},{0.014171f,0.486874f,0.146666f}, -{0.0132538f,0.488177f,0.146574f},{0.0120868f,0.489249f,0.14645f},{0.0107201f,0.490052f,0.146296f}, -{0.00921907f,0.490545f,0.146114f},{-0.00815064f,0.48779f,0.142549f},{-0.00695586f,0.489024f,0.14283f}, -{-0.00391721f,0.490519f,0.143508f},{-0.00552233f,0.489946f,0.143157f},{-0.0089918f,0.486401f,0.141854f}, -{-0.00951028f,0.484871f,0.141426f},{-0.00632699f,0.488748f,0.144055f},{-0.0068323f,0.488788f,0.143638f}, -{-0.00732043f,0.488576f,0.143234f},{-0.00776225f,0.48823f,0.14287f},{0.0235779f,0.374892f,0.147426f}, -{0.0219204f,0.386398f,0.148625f},{0.0224876f,0.38644f,0.148085f},{0.0179164f,0.44752f,0.147043f}, -{0.0149745f,0.483831f,0.1473f},{0.0186837f,0.435152f,0.147841f},{0.0140869f,0.483769f,0.148094f}, -{0.0180963f,0.435109f,0.148384f},{0.0146193f,0.483807f,0.147797f},{0.0207472f,0.411206f,0.147267f}, -{0.00748972f,0.490303f,0.146886f},{0.00897658f,0.490142f,0.147115f},{0.00911758f,0.490461f,0.146645f}, -{0.0103998f,0.48969f,0.147311f},{0.0119652f,0.489201f,0.146998f},{0.0106014f,0.489986f,0.146835f}, -{0.0128307f,0.48793f,0.147613f},{0.0140507f,0.486857f,0.147224f},{0.0131339f,0.488142f,0.147128f}, -{0.0146743f,0.485398f,0.147286f},{0.0124497f,0.487626f,0.147903f},{0.0113986f,0.488574f,0.14777f}, -{0.0138348f,0.485172f,0.148064f},{0.0143101f,0.485306f,0.147775f},{0.013274f,0.486476f,0.148f}, -{0.00743905f,0.489829f,0.147194f},{0.00883688f,0.489704f,0.14741f},{0.00756687f,0.490614f,0.146419f}, -{0.0101719f,0.489277f,0.147604f},{0.0137111f,0.486701f,0.147711f},{0.0117086f,0.488941f,0.147479f}, -{0.00254212f,0.490504f,0.145696f},{0.0024474f,0.490038f,0.146152f},{-0.00239822f,0.490529f,0.14453f}, -{-0.00252701f,0.489991f,0.145044f},{-0.00405957f,0.490287f,0.14418f},{-0.00550952f,0.489296f,0.144258f}, -{-0.00559184f,0.489714f,0.143809f},{-0.00407172f,0.489834f,0.14463f},{0.022887f,0.375478f,0.146255f}, -{0.0233314f,0.375514f,0.14672f},{0.0174497f,0.451096f,0.14634f},{0.0203893f,0.413325f,0.146565f}, -{0.0199559f,0.413289f,0.146102f},{0.0170273f,0.45106f,0.145879f},{-0.0123416f,0.113525f,0.145204f}, -{-0.0109102f,0.112615f,0.145018f},{-0.0135295f,0.114734f,0.145346f},{-0.0164058f,0.15205f,0.14564f}, -{-0.0192822f,0.189366f,0.145867f},{-0.0221586f,0.226683f,0.146027f},{-0.00932212f,0.112054f,0.144792f}, -{-0.00765064f,0.111865f,0.144531f},{0.00968775f,0.119322f,0.140407f},{0.00949318f,0.117633f,0.140468f}, -{0.00543154f,0.112587f,0.141666f},{0.00387196f,0.112048f,0.142086f},{0.00892517f,0.116038f,0.140645f}, -{0.0080214f,0.114625f,0.14092f},{0.00683431f,0.113456f,0.141269f},{0.00223012f,0.111865f,0.142505f}, -{0.00379135f,0.113384f,0.144903f},{0.00496458f,0.113745f,0.14459f},{-0.00742307f,0.113263f,0.147291f}, -{0.00257039f,0.113263f,0.145216f},{0.00603944f,0.114327f,0.144293f},{-0.00240499f,0.113263f,0.146356f}, -{-0.0211541f,0.215517f,0.148776f},{-0.0173396f,0.167133f,0.148518f},{-0.013533f,0.118851f,0.148143f}, -{-0.0132913f,0.117576f,0.148115f},{-0.0127821f,0.116383f,0.148055f},{-0.0120287f,0.115326f,0.147962f}, -{-0.0110706f,0.114453f,0.147837f},{-0.00994698f,0.113801f,0.14768f},{-0.00871793f,0.1134f,0.147497f}, -{0.00968775f,0.119322f,0.141279f},{-0.00268915f,0.111865f,0.144987f},{-0.00765064f,0.111865f,0.145911f}, -{0.00223012f,0.111865f,0.14386f},{-0.0143331f,0.116009f,0.145639f},{-0.014793f,0.117177f,0.146726f}, -{-0.0148426f,0.117347f,0.146158f},{-0.0150857f,0.118743f,0.146754f},{-0.014174f,0.115708f,0.146667f}, -{-0.0132606f,0.114409f,0.146575f},{-0.0120925f,0.113332f,0.146451f},{-0.0107278f,0.112529f,0.146297f}, -{-0.00922792f,0.112033f,0.146115f},{0.00815064f,0.114787f,0.142549f},{0.00695586f,0.113553f,0.14283f}, -{0.00552233f,0.112631f,0.143157f},{0.00391721f,0.112058f,0.143508f},{0.0089918f,0.116176f,0.141854f}, -{0.00951028f,0.117706f,0.141426f},{0.0068323f,0.113789f,0.143638f},{0.00632699f,0.113829f,0.144055f}, -{0.00732043f,0.114001f,0.143234f},{0.00776225f,0.114347f,0.14287f},{-0.0235779f,0.227685f,0.147426f}, -{-0.0219204f,0.216179f,0.148625f},{-0.0224876f,0.216137f,0.148085f},{-0.0179164f,0.155057f,0.147043f}, -{-0.0149745f,0.118746f,0.1473f},{-0.0186837f,0.167425f,0.147841f},{-0.0140869f,0.118809f,0.148094f}, -{-0.0180963f,0.167468f,0.148384f},{-0.0146193f,0.11877f,0.147797f},{-0.0207472f,0.191371f,0.147267f}, -{-0.0137517f,0.115882f,0.147682f},{-0.013838f,0.117415f,0.148064f},{-0.0143462f,0.117273f,0.147745f}, -{-0.0131473f,0.11445f,0.147128f},{-0.0140617f,0.115741f,0.147224f},{-0.0146779f,0.11719f,0.147286f}, -{-0.0101903f,0.113307f,0.147606f},{-0.0114133f,0.114012f,0.147771f},{-0.00899738f,0.11241f,0.147089f}, -{-0.00756687f,0.111963f,0.146419f},{-0.00748972f,0.112274f,0.146886f},{-0.0106218f,0.112599f,0.146837f}, -{-0.0119815f,0.113386f,0.146999f},{-0.00912889f,0.112119f,0.146646f},{-0.0104352f,0.112869f,0.147285f}, -{-0.00884706f,0.112875f,0.147411f},{-0.0128697f,0.114643f,0.147584f},{-0.0132839f,0.116119f,0.148001f}, -{-0.00743905f,0.112748f,0.147194f},{-0.0124617f,0.114964f,0.147903f},{-0.0117456f,0.113623f,0.147451f}, -{-0.00254212f,0.112073f,0.145696f},{-0.0024474f,0.112539f,0.146152f},{0.00239822f,0.112048f,0.14453f}, -{0.00252701f,0.112586f,0.145044f},{0.00405957f,0.11229f,0.14418f},{0.00550952f,0.113281f,0.144258f}, -{0.00559184f,0.112863f,0.143809f},{0.00407172f,0.112743f,0.14463f},{-0.0233314f,0.227063f,0.14672f}, -{-0.022887f,0.227099f,0.146255f},{-0.0170273f,0.151517f,0.145879f},{-0.0174497f,0.151481f,0.14634f}, -{-0.0203893f,0.189252f,0.146565f},{-0.0199559f,0.189288f,0.146102f},{0.0043568f,0.302945f,0.127503f}, -{0.00383438f,0.303939f,0.127503f},{0.00308638f,0.304781f,0.127503f},{0.00216232f,0.305417f,0.127503f}, -{0.00462734f,0.300729f,0.127503f},{0.00462608f,0.301855f,0.127503f},{0.00383806f,0.298645f,0.127503f}, -{0.00435903f,0.299638f,0.127503f},{0.00309213f,0.297801f,0.127503f},{0.00216808f,0.297163f,0.127503f}, -{0.00111857f,0.296764f,0.127503f},{0.0011128f,0.305815f,0.127503f},{-0.00150163f,0.303613f,0.127503f}, -{-0.000787374f,0.303967f,0.127503f},{-0.00211724f,0.303117f,0.127503f},{-0.00254559f,0.302447f,0.127503f}, -{-0.00276842f,0.301683f,0.127503f},{-0.00276723f,0.300888f,0.127503f},{-0.00254283f,0.300125f,0.127503f}, -{-0.00210508f,0.299465f,0.127503f},{-0.00150519f,0.298949f,0.127503f},{-0.00078745f,0.298603f,0.127503f}, -{-0.00254559f,0.30013f,0.136825f},{-0.00276842f,0.300894f,0.136825f},{-0.00150519f,0.303628f,0.136825f}, -{-0.00276723f,0.301689f,0.136825f},{-0.00210508f,0.303112f,0.136825f},{-0.00078745f,0.303974f,0.136825f}, -{-0.00254283f,0.302452f,0.136825f},{-0.00211724f,0.29946f,0.136825f},{-0.00150163f,0.298964f,0.136825f}, -{-0.000787374f,0.29861f,0.136825f},{0.00265777f,0.280158f,0.127503f},{0.00225612f,0.280939f,0.127503f}, -{0.00163414f,0.281556f,0.127503f},{0.00266037f,0.278432f,0.127503f},{0.00226719f,0.277654f,0.127503f}, -{0.00279661f,0.279289f,0.127503f},{0.00165072f,0.277032f,0.127503f},{0.000869207f,0.276631f,0.127503f}, -{0.000869207f,0.281946f,0.127503f},{0.00265777f,0.324158f,0.127503f},{0.00225612f,0.324939f,0.127503f}, -{0.00163414f,0.325556f,0.127503f},{0.00266037f,0.322432f,0.127503f},{0.00279661f,0.323289f,0.127503f}, -{0.00165072f,0.321032f,0.127503f},{0.00226719f,0.321654f,0.127503f},{0.000869207f,0.320631f,0.127503f}, -{0.000869207f,0.325946f,0.127503f},{0.323702f,0.0027207f,0.140084f},{0.323289f,0.00279661f,0.126571f}, -{0.322911f,0.00276223f,0.139989f},{0.324476f,0.00254178f,0.140201f},{0.324145f,0.00266037f,0.126571f}, -{0.324923f,0.00226719f,0.126571f},{0.325128f,0.00210085f,0.140351f},{0.325946f,0.000869207f,0.126571f}, -{0.325545f,0.00165072f,0.126571f},{0.325656f,0.00149803f,0.140516f},{0.325978f,0.000793813f,0.140672f}, -{0.326085f,1.80082e-018f,0.126571f},{0.326085f,-2.12873e-008f,0.140816f},{0.322419f,0.00265777f,0.126571f}, -{0.322139f,0.00255964f,0.139937f},{0.321638f,0.00225612f,0.126571f},{0.321021f,0.00163414f,0.126571f}, -{0.321467f,0.00212367f,0.13993f},{0.320631f,0.000869207f,0.126571f},{0.320933f,0.00151779f,0.13996f}, -{0.320598f,0.000793595f,0.140023f},{0.320492f,2.70028e-018f,0.126571f},{0.320492f,2.70028e-018f,0.140116f}, -{0.280923f,0.00226719f,0.126571f},{0.280167f,0.00266113f,0.140699f},{0.280949f,0.00225617f,0.140543f}, -{0.280145f,0.00266037f,0.126571f},{0.281545f,0.00165072f,0.126571f},{0.281516f,0.00161123f,0.140389f}, -{0.281946f,0.000869207f,0.126571f},{0.281954f,0.000861428f,0.140241f},{0.279308f,0.00279699f,0.140836f}, -{0.282085f,2.26626e-008f,0.140116f},{0.282085f,1.19474e-017f,0.126571f},{0.279289f,0.00279661f,0.126571f}, -{0.278435f,0.00267244f,0.140943f},{0.277655f,0.00227523f,0.141f},{0.278419f,0.00265777f,0.126571f}, -{0.277638f,0.00225612f,0.126571f},{0.277026f,0.00164828f,0.140998f},{0.277021f,0.00163414f,0.126571f}, -{0.276631f,0.000869207f,0.126571f},{0.276622f,0.000867575f,0.140935f},{0.276492f,1.16049e-017f,0.126571f}, -{0.276492f,1.16049e-017f,0.140816f},{0.301289f,-0.00279661f,0.135893f},{0.302145f,-0.00266037f,0.126571f}, -{0.299654f,-0.00226719f,0.135893f},{0.300419f,-0.00265777f,0.126571f},{0.299638f,-0.00225612f,0.126571f}, -{0.300432f,-0.00266037f,0.135893f},{0.299032f,-0.00165072f,0.135893f},{0.298631f,-0.000869207f,0.126571f}, -{0.298492f,3.04276e-018f,0.135893f},{0.298631f,-0.000869207f,0.135893f},{0.299021f,-0.00163414f,0.126571f}, -{0.298492f,3.04276e-018f,0.126571f},{0.302158f,-0.00265777f,0.135893f},{0.302923f,-0.00226719f,0.126571f}, -{0.302939f,-0.00225612f,0.135893f},{0.303556f,-0.00163414f,0.135893f},{0.303545f,-0.00165072f,0.126571f}, -{0.303946f,-0.000869207f,0.135893f},{0.303946f,-0.000869207f,0.126571f},{0.304085f,2.70028e-018f,0.126571f}, -{0.304085f,2.70028e-018f,0.135893f},{0.303941f,0.00383933f,0.139404f},{0.302938f,0.00435933f,0.126571f}, -{0.302948f,0.00437081f,0.13941f},{0.301847f,0.00462728f,0.126571f},{0.303934f,0.00383758f,0.126571f}, -{0.301857f,0.00463064f,0.139439f},{0.304774f,0.00309444f,0.126571f},{0.304783f,0.00308762f,0.139422f}, -{0.305414f,0.00216892f,0.126571f},{0.300727f,0.00463006f,0.139484f},{0.30543f,0.00216891f,0.139458f}, -{0.305813f,0.00111911f,0.126571f},{0.30595f,5.60073e-014f,0.139555f},{0.305949f,3.35892e-010f,0.126571f}, -{0.305823f,0.00112174f,0.139506f},{0.300724f,0.00462657f,0.126571f},{0.299633f,0.00435716f,0.126571f}, -{0.299631f,0.00437228f,0.139533f},{0.298643f,0.00384698f,0.139577f},{0.298638f,0.0038338f,0.126571f}, -{0.297798f,0.00308862f,0.126571f},{0.2978f,0.00309221f,0.139605f},{0.29716f,0.00216381f,0.126571f}, -{0.297151f,0.00217168f,0.139611f},{0.296754f,0.00112329f,0.139593f},{0.296763f,0.00111503f,0.126571f}, -{0.296628f,2.70028e-018f,0.139555f},{0.296628f,2.70028e-018f,0.126571f},{0.333784f,0.0031834f,0.140987f}, -{0.333871f,-0.0034311f,0.142326f},{0.329361f,0.00348389f,0.140521f},{0.321833f,-0.013311f,0.141175f}, -{0.321483f,-0.00749864f,0.140959f},{0.325857f,-0.01447f,0.142053f},{0.334598f,-0.0237151f,0.144174f}, -{0.334046f,-0.0168317f,0.143863f},{0.338577f,-0.0250351f,0.145188f},{0.304777f,-0.00309212f,0.139605f}, -{0.308789f,-0.00980991f,0.139511f},{0.303935f,-0.00384705f,0.139577f},{0.320598f,-0.000788852f,0.140229f}, -{0.320971f,-0.00148198f,0.140362f},{0.316843f,-0.00113058f,0.139807f},{0.299629f,-0.00437081f,0.13941f}, -{0.30072f,-0.00463066f,0.139439f},{0.299868f,-0.00734722f,0.139167f},{0.293803f,0.00981015f,0.139524f}, -{0.298637f,-0.00383936f,0.139404f},{0.297795f,-0.0030876f,0.139422f},{0.29484f,-0.000835134f,0.139471f}, -{0.289735f,0.00565577f,0.139774f},{0.294321f,0.00448849f,0.13965f},{0.281978f,-0.000794809f,0.140023f}, -{0.286162f,-0.00431412f,0.13904f},{0.281642f,-0.00152033f,0.13996f},{0.268522f,0.0168309f,0.143864f}, -{0.264f,0.0250351f,0.145188f},{0.26798f,0.0237151f,0.144174f},{0.289229f,0.0110109f,0.139773f}, -{0.272859f,0.00922726f,0.1425f},{0.271923f,0.0222833f,0.143172f},{0.272684f,0.0156491f,0.142944f}, -{0.273206f,-0.00348559f,0.14052f},{0.273034f,0.00283697f,0.14169f},{0.276599f,-0.000793378f,0.140672f}, -{0.268783f,-0.00318417f,0.140986f},{0.268697f,0.00342276f,0.142324f},{0.268311f,-0.00969325f,0.139307f}, -{0.264f,-0.00290707f,0.141403f},{0.264f,0.00398877f,0.142946f},{0.264f,-0.00968775f,0.139474f}, -{0.277496f,-0.00378729f,0.140033f},{0.277448f,-0.00209478f,0.140352f},{0.278103f,-0.00253473f,0.140202f}, -{0.26861f,0.010107f,0.143286f},{0.278874f,-0.00272118f,0.140084f},{0.281218f,-0.00973119f,0.138395f}, -{0.281779f,-0.00404127f,0.13952f},{0.304265f,-0.00858894f,0.139339f},{0.312352f,-0.000322559f,0.13946f}, -{0.307227f,0.00611166f,0.138973f},{0.311852f,0.0049946f,0.138851f},{0.30271f,0.00734676f,0.139167f}, -{0.302947f,-0.0043723f,0.139533f},{0.320788f,0.00405908f,0.139532f},{0.316411f,0.00435339f,0.139066f}, -{0.305426f,-0.00217165f,0.139611f},{0.308268f,-0.00450063f,0.139635f},{0.322112f,-0.00253786f,0.140643f}, -{0.322873f,-0.00276739f,0.140776f},{0.325595f,-0.00835592f,0.141728f},{0.324441f,-0.00255847f,0.140971f}, -{0.325113f,-0.00212169f,0.141005f},{0.326719f,-0.0208182f,0.142186f},{0.338577f,-0.00398877f,0.142946f}, -{0.329883f,-0.0156505f,0.142943f},{0.338577f,0.00968775f,0.139474f},{0.338577f,0.00290707f,0.141403f}, -{0.334267f,0.00969325f,0.139307f},{0.321359f,0.00973122f,0.138395f},{0.32566f,0.00972934f,0.138727f}, -{0.325074f,0.00378494f,0.140033f},{0.317712f,-0.0121774f,0.140344f},{0.317277f,-0.00665136f,0.140233f}, -{0.307746f,0.000816648f,0.139456f},{0.323672f,-0.0027728f,0.14089f},{0.333958f,-0.0101155f,0.143286f}, -{0.338577f,-0.0179944f,0.144842f},{0.330654f,-0.0222833f,0.143172f},{0.338577f,-0.0109671f,0.144094f}, -{0.329962f,0.0097173f,0.139038f},{0.317058f,0.0097497f,0.138081f},{0.298313f,0.00858896f,0.139339f}, -{0.295355f,-0.00613049f,0.138989f},{0.285728f,0.00115281f,0.13978f},{0.290743f,-0.00500873f,0.138859f}, -{0.298192f,-0.0120097f,0.138358f},{0.294038f,-0.0108714f,0.138063f},{0.30185f,-0.00463004f,0.139484f}, -{0.30234f,-0.0131607f,0.138632f},{0.306481f,-0.0143354f,0.138904f},{0.312855f,-0.00566917f,0.139765f}, -{0.313358f,-0.0110148f,0.139763f},{0.312766f,0.0100181f,0.137915f},{0.308539f,0.0108714f,0.138063f}, -{0.304385f,0.0120097f,0.138358f},{0.300237f,0.0131607f,0.138632f},{0.296096f,0.0143354f,0.138904f}, -{0.285291f,0.00666271f,0.140207f},{0.281083f,0.00749967f,0.140947f},{0.279664f,-0.00277232f,0.139987f}, -{0.276917f,-0.00972932f,0.138727f},{0.276921f,-0.00149718f,0.140516f},{0.284854f,0.0121843f,0.140319f}, -{0.280437f,-0.00255887f,0.139937f},{0.28111f,-0.00212359f,0.13993f},{0.290241f,0.000305779f,0.139469f}, -{0.296754f,-0.00112176f,0.139506f},{0.297147f,-0.00216894f,0.139458f},{0.280732f,0.0133136f,0.141164f}, -{0.276975f,0.00834704f,0.141728f},{0.276713f,0.0144683f,0.142054f},{0.329534f,-0.0028458f,0.141692f}, -{0.329708f,-0.0092361f,0.1425f},{0.325643f,-0.00151619f,0.140991f},{0.325978f,-0.00079021f,0.140927f}, -{0.322781f,-0.019351f,0.141212f},{0.318817f,-0.0179262f,0.140278f},{0.314771f,-0.0166178f,0.139577f}, -{0.321454f,-0.00210151f,0.140501f},{0.305823f,-0.00112326f,0.139593f},{0.310634f,-0.0154659f,0.139188f}, -{0.289811f,-0.0100181f,0.137915f},{0.291943f,0.0154659f,0.139188f},{0.285519f,-0.00974966f,0.138081f}, -{0.28376f,0.0179262f,0.140277f},{0.287806f,0.0166178f,0.139577f},{0.279796f,0.0193511f,0.141212f}, -{0.275858f,0.0208182f,0.142186f},{0.272615f,-0.00971729f,0.139038f},{0.264f,0.0179944f,0.144842f}, -{0.264f,0.0109671f,0.144094f},{0.338577f,-0.0262081f,0.147306f},{0.334844f,-0.0248064f,0.146267f}, -{0.334839f,-0.0250058f,0.145834f},{0.331143f,-0.0233183f,0.145233f},{0.331138f,-0.0235291f,0.144807f}, -{0.320025f,-0.0188229f,0.142233f},{0.320019f,-0.0190695f,0.141834f},{0.323745f,-0.0203019f,0.143206f}, -{0.32374f,-0.0205368f,0.142798f},{0.32744f,-0.022035f,0.143797f},{0.327445f,-0.0218112f,0.144215f}, -{0.308407f,-0.015307f,0.140187f},{0.308412f,-0.0150041f,0.140585f},{0.304471f,-0.0141429f,0.139901f}, -{0.316248f,-0.0174212f,0.141368f},{0.312356f,-0.0161629f,0.140879f},{0.312351f,-0.0164424f,0.140484f}, -{0.296614f,-0.0114006f,0.139778f},{0.29265f,-0.0106866f,0.139078f},{0.296607f,-0.0117799f,0.13935f}, -{0.300553f,-0.0125814f,0.140047f},{0.300542f,-0.0129503f,0.139627f},{0.30448f,-0.0138012f,0.140314f}, -{0.280413f,-0.00963024f,0.139594f},{0.284511f,-0.00968708f,0.139236f},{0.284522f,-0.0091952f,0.139717f}, -{0.288611f,-0.0099197f,0.139001f},{0.292663f,-0.0102596f,0.139509f},{0.288623f,-0.00946264f,0.13945f}, -{0.280421f,-0.00907526f,0.140098f},{0.276313f,-0.0095489f,0.139944f},{0.27632f,-0.00894343f,0.140481f}, -{0.272213f,-0.00945311f,0.140271f},{0.268109f,-0.00933687f,0.140548f},{0.272217f,-0.00879579f,0.140841f}, -{0.268112f,-0.0086246f,0.141156f},{0.264f,-0.00922107f,0.140732f},{0.264f,-0.00845004f,0.141369f}, -{0.316239f,-0.0176856f,0.140989f},{0.338577f,-0.0263793f,0.14687f},{0.338577f,-0.0259023f,0.147661f}, -{0.334843f,-0.0244885f,0.146625f},{0.33114f,-0.0229936f,0.14559f},{0.320015f,-0.0184899f,0.142579f}, -{0.32744f,-0.0214828f,0.144569f},{0.3084f,-0.0146321f,0.140948f},{0.316236f,-0.0170843f,0.141711f}, -{0.312343f,-0.0158117f,0.14123f},{0.296605f,-0.010968f,0.14018f},{0.300543f,-0.0121699f,0.140436f}, -{0.304469f,-0.0134094f,0.140689f},{0.284517f,-0.0086637f,0.140175f},{0.292656f,-0.00980481f,0.139924f}, -{0.288617f,-0.00897481f,0.139881f},{0.280417f,-0.00849863f,0.14059f},{0.276317f,-0.00832061f,0.141007f}, -{0.272215f,-0.00812583f,0.141403f},{0.268111f,-0.00790535f,0.141755f},{0.264f,-0.00767878f,0.142006f}, -{0.323738f,-0.0199715f,0.143557f},{0.338577f,-0.0254953f,0.147896f},{0.334632f,-0.0239945f,0.146815f}, -{0.330719f,-0.0224149f,0.145732f},{0.318949f,-0.0176882f,0.14257f},{0.326809f,-0.0208215f,0.14466f}, -{0.322894f,-0.0192329f,0.143596f},{0.306623f,-0.0136618f,0.141149f},{0.314913f,-0.0162503f,0.141808f}, -{0.310777f,-0.0149457f,0.141414f},{0.289947f,-0.00869072f,0.140254f},{0.294176f,-0.00973903f,0.140373f}, -{0.29833f,-0.0110356f,0.140649f},{0.281312f,-0.00795144f,0.140963f},{0.285636f,-0.0081943f,0.140508f}, -{0.276988f,-0.00772122f,0.141446f},{0.272663f,-0.00747253f,0.14191f},{0.268336f,-0.00719397f,0.142331f}, -{0.264f,-0.00690556f,0.142645f},{0.302479f,-0.0123399f,0.140899f},{0.338577f,-0.0250324f,0.147984f}, -{0.334606f,-0.0235306f,0.146925f},{0.330688f,-0.0219498f,0.145862f},{0.318889f,-0.0172517f,0.142779f}, -{0.326769f,-0.0203651f,0.144808f},{0.306566f,-0.0132021f,0.1414f},{0.314858f,-0.0158114f,0.141995f}, -{0.310726f,-0.0144807f,0.141612f},{0.29412f,-0.0092687f,0.140734f},{0.298278f,-0.0105497f,0.140954f}, -{0.30242f,-0.0118813f,0.141174f},{0.28128f,-0.0073368f,0.141392f},{0.285604f,-0.00759572f,0.140879f}, -{0.289904f,-0.00819435f,0.140634f},{0.276964f,-0.00708183f,0.141934f},{0.272648f,-0.00678804f,0.142445f}, -{0.268328f,-0.00646507f,0.142911f},{0.264f,-0.00613003f,0.143285f},{0.322844f,-0.0187868f,0.143765f}, -{0.276283f,-0.00696068f,0.142073f},{0.272193f,-0.00667554f,0.142559f},{0.268101f,-0.00636198f,0.143007f}, -{0.284462f,-0.00748015f,0.141066f},{0.288553f,-0.00786981f,0.140699f},{0.280372f,-0.00722771f,0.141568f}, -{0.300465f,-0.0111819f,0.141102f},{0.292584f,-0.00875236f,0.140687f},{0.312256f,-0.014914f,0.141754f}, -{0.304388f,-0.0124511f,0.141309f},{0.308316f,-0.0137038f,0.141521f},{0.319944f,-0.0175985f,0.14304f}, -{0.323681f,-0.0190677f,0.143996f},{0.316153f,-0.0162018f,0.142196f},{0.327398f,-0.0205663f,0.144987f}, -{0.331113f,-0.022067f,0.145984f},{0.33483f,-0.0235578f,0.146988f},{0.29653f,-0.00994863f,0.140894f}, -{0.264f,-0.00603944f,0.14336f},{0.330122f,-0.00744254f,0.145062f},{0.334273f,-0.015865f,0.146599f}, -{0.334181f,-0.0083666f,0.145857f},{0.329939f,-0.000311244f,0.144002f},{0.334089f,-0.000930332f,0.144641f}, -{0.330384f,0.00667554f,0.142559f},{0.338577f,-0.00158091f,0.14525f},{0.334477f,0.0063617f,0.143002f}, -{0.338577f,-0.00932143f,0.146656f},{0.338577f,0.00603944f,0.14336f},{0.326198f,-0.00654234f,0.144272f}, -{0.322287f,-0.00567271f,0.143483f},{0.326474f,-0.0134133f,0.144758f},{0.314708f,-0.00989537f,0.142284f}, -{0.318771f,-0.0110779f,0.142976f},{0.314167f,-0.00388505f,0.142127f},{0.322655f,-0.0122295f,0.143857f}, -{0.306074f,-0.0072715f,0.141882f},{0.301276f,-1.23849e-006f,0.14196f},{0.301855f,-0.00593214f,0.141771f}, -{0.310416f,-0.00860427f,0.141986f},{0.293337f,-0.00327255f,0.141553f},{0.288967f,-0.00211647f,0.141598f}, -{0.297083f,0.00133631f,0.141962f},{0.297661f,-0.00459153f,0.141661f},{0.268392f,0.00836678f,0.145857f}, -{0.268483f,0.00093054f,0.144641f},{0.272633f,0.000310969f,0.144002f},{0.284719f,-0.00135717f,0.142021f}, -{0.284259f,0.00485039f,0.142684f},{0.264f,0.00158091f,0.14525f},{0.276649f,-0.000284983f,0.143352f}, -{0.27245f,0.00744232f,0.145062f},{0.264f,0.0171357f,0.147569f},{0.2683f,0.0158652f,0.1466f}, -{0.280649f,-0.000835711f,0.142683f},{0.276375f,0.00654153f,0.144272f},{0.280282f,0.00568021f,0.143473f}, -{0.292762f,0.00265603f,0.141973f},{0.288426f,0.00387587f,0.142138f},{0.309833f,-0.00267273f,0.141944f}, -{0.305495f,-0.00133739f,0.14196f},{0.318311f,-0.00483092f,0.14271f},{0.330306f,-0.0146267f,0.145667f}, -{0.338577f,-0.0171357f,0.147569f},{0.326294f,0.0069607f,0.142073f},{0.325924f,0.000284018f,0.143351f}, -{0.322205f,0.00722775f,0.141568f},{0.321921f,0.000847135f,0.142693f},{0.318116f,0.00746803f,0.141057f}, -{0.317854f,0.00138663f,0.142046f},{0.314024f,0.00787057f,0.1407f},{0.313628f,0.00210321f,0.141587f}, -{0.309995f,0.00875939f,0.140692f},{0.309251f,0.00324421f,0.141524f},{0.306045f,0.00994211f,0.140894f}, -{0.267749f,0.023562f,0.146989f},{0.264f,0.0249766f,0.147983f},{0.304917f,0.00458966f,0.141659f}, -{0.302115f,0.0111906f,0.141102f},{0.298192f,0.0124586f,0.141307f},{0.300697f,0.00592971f,0.141772f}, -{0.29426f,0.0136985f,0.141523f},{0.296504f,0.00727121f,0.141884f},{0.29032f,0.0149126f,0.14175f}, -{0.292185f,0.00859914f,0.142013f},{0.286428f,0.0162055f,0.142209f},{0.287882f,0.0098903f,0.142296f}, -{0.282633f,0.0175985f,0.14304f},{0.283798f,0.0110874f,0.142952f},{0.278896f,0.0190677f,0.143996f}, -{0.279914f,0.012233f,0.143847f},{0.275179f,0.0205663f,0.144987f},{0.276098f,0.0134127f,0.144758f}, -{0.271464f,0.0220671f,0.145984f},{0.272266f,0.0146265f,0.145668f},{0.264f,0.00932143f,0.146656f}, -{0.338577f,0.00690312f,0.142647f},{0.334242f,0.00719191f,0.142327f},{0.329914f,0.00746979f,0.14191f}, -{0.316934f,0.00814762f,0.140482f},{0.325589f,0.0077197f,0.141447f},{0.321266f,0.00793083f,0.14095f}, -{0.304248f,0.0110361f,0.14065f},{0.300103f,0.0123542f,0.140896f},{0.312628f,0.00871456f,0.140273f}, -{0.308409f,0.00976951f,0.140403f},{0.28766f,0.0162476f,0.141798f},{0.291792f,0.0149252f,0.141389f}, -{0.295955f,0.0136614f,0.141149f},{0.279686f,0.0192347f,0.143604f},{0.283634f,0.0176916f,0.142602f}, -{0.27577f,0.0208212f,0.144662f},{0.271858f,0.022413f,0.145733f},{0.267947f,0.0239981f,0.146816f}, -{0.264f,0.0254927f,0.147897f},{0.338577f,0.00767576f,0.142009f},{0.334466f,0.00790232f,0.141753f}, -{0.330362f,0.00812312f,0.141405f},{0.31806f,0.00864847f,0.140168f},{0.32626f,0.00831807f,0.14101f}, -{0.32216f,0.00849626f,0.140592f},{0.30597f,0.0109591f,0.140182f},{0.313959f,0.00897354f,0.139884f}, -{0.309923f,0.00981108f,0.139931f},{0.294175f,0.0146249f,0.140952f},{0.29811f,0.0134151f,0.140688f}, -{0.302037f,0.0121769f,0.140437f},{0.282562f,0.0184881f,0.142581f},{0.290233f,0.0158082f,0.141227f}, -{0.286345f,0.0170869f,0.141725f},{0.278839f,0.0199696f,0.143558f},{0.275137f,0.0214809f,0.14457f}, -{0.271437f,0.0229915f,0.145592f},{0.267736f,0.0244911f,0.146626f},{0.264f,0.0259001f,0.147663f}, -{0.338577f,0.00844643f,0.141372f},{0.334465f,0.0086212f,0.141154f},{0.33036f,0.00879266f,0.140843f}, -{0.318055f,0.00917932f,0.139711f},{0.326258f,0.00894054f,0.140483f},{0.305961f,0.0113914f,0.139781f}, -{0.313954f,0.00946126f,0.139453f},{0.309916f,0.0102671f,0.139517f},{0.294163f,0.0149971f,0.140589f}, -{0.298099f,0.0138071f,0.140313f},{0.302027f,0.0125887f,0.140048f},{0.282552f,0.0188214f,0.142234f}, -{0.29022f,0.0161597f,0.140877f},{0.286332f,0.0174245f,0.141382f},{0.278832f,0.0203004f,0.143209f}, -{0.275132f,0.0218097f,0.144217f},{0.271434f,0.0233168f,0.145235f},{0.267735f,0.0248099f,0.146269f}, -{0.264f,0.0262067f,0.147309f},{0.322157f,0.0090726f,0.140101f},{0.338577f,0.00921688f,0.140736f}, -{0.334468f,0.00933302f,0.140551f},{0.330364f,0.00944958f,0.140274f},{0.318066f,0.00968445f,0.139239f}, -{0.326264f,0.00954568f,0.139947f},{0.30597f,0.0117779f,0.139353f},{0.313966f,0.00991732f,0.139004f}, -{0.309927f,0.0106844f,0.139081f},{0.29417f,0.0153055f,0.140189f},{0.298106f,0.0141412f,0.139904f}, -{0.302035f,0.0129485f,0.13963f},{0.282558f,0.0190685f,0.141836f},{0.286338f,0.0176844f,0.140992f}, -{0.290226f,0.016441f,0.140486f},{0.278837f,0.0205358f,0.142801f},{0.275137f,0.0220341f,0.1438f}, -{0.271439f,0.0235282f,0.14481f},{0.267738f,0.0250051f,0.145837f},{0.264f,0.0263788f,0.146873f}, -{0.322165f,0.00962732f,0.139597f},{0.334471f,0.00976429f,0.140182f},{0.338577f,0.00968775f,0.140347f}, -{0.322175f,0.00995451f,0.139285f},{0.326272f,0.00990606f,0.139616f},{0.33037f,0.00984421f,0.139924f}, -{0.309942f,0.0109184f,0.138808f},{0.318079f,0.00997907f,0.138946f},{0.29812f,0.0143137f,0.139645f}, -{0.302049f,0.01314f,0.139366f},{0.305984f,0.0119892f,0.139084f},{0.28635f,0.0178005f,0.140741f}, -{0.290239f,0.0165744f,0.140236f},{0.294183f,0.015459f,0.139935f},{0.278846f,0.0206269f,0.142536f}, -{0.282568f,0.0191718f,0.141579f},{0.275145f,0.0221132f,0.143529f},{0.271445f,0.0235942f,0.144532f}, -{0.267741f,0.0250554f,0.145553f},{0.264f,0.0264087f,0.146586f},{0.313981f,0.0101788f,0.138724f}, -{0.300099f,0.0137161f,0.139356f},{0.304248f,0.0124851f,0.13907f},{0.308413f,0.0113146f,0.138783f}, -{0.312637f,0.0103804f,0.138606f},{0.316945f,0.00997452f,0.138733f},{0.321273f,0.00994023f,0.13908f}, -{0.325595f,0.00991203f,0.139443f},{0.329918f,0.009849f,0.139773f},{0.334245f,0.00976769f,0.140054f}, -{0.338577f,0.00968775f,0.140237f},{0.295949f,0.014938f,0.139648f},{0.291782f,0.0161103f,0.139931f}, -{0.28765f,0.0173564f,0.140361f},{0.283628f,0.0187613f,0.141145f},{0.279684f,0.0202782f,0.142115f}, -{0.275771f,0.021842f,0.143141f},{0.271863f,0.0234057f,0.144181f},{0.267952f,0.024951f,0.14524f}, -{0.264f,0.0263814f,0.146312f},{0.333995f,0.00976336f,0.139842f},{0.338577f,0.00968775f,0.140047f}, -{0.320276f,0.00990978f,0.138791f},{0.324847f,0.00989796f,0.139181f},{0.329419f,0.00983969f,0.139537f}, -{0.311162f,0.0106101f,0.138427f},{0.306724f,0.0117247f,0.138676f},{0.315696f,0.00998742f,0.138455f}, -{0.297936f,0.0142908f,0.139261f},{0.293533f,0.0155467f,0.139552f},{0.302325f,0.0129908f,0.13897f}, -{0.280636f,0.0197978f,0.141555f},{0.284834f,0.0182285f,0.140588f},{0.289136f,0.0168071f,0.139904f}, -{0.276483f,0.0214356f,0.142606f},{0.272338f,0.0230806f,0.143678f},{0.268191f,0.0247084f,0.144769f}, -{0.264f,0.0262125f,0.145873f},{0.334001f,0.00974593f,0.13965f},{0.338577f,0.00968775f,0.139856f}, -{0.3203f,0.00985594f,0.138605f},{0.324865f,0.00985469f,0.138992f},{0.329431f,0.00980831f,0.139346f}, -{0.30676f,0.0116247f,0.138477f},{0.315727f,0.00992109f,0.13827f},{0.297975f,0.0141594f,0.139045f}, -{0.293574f,0.0154002f,0.139327f},{0.302362f,0.0128748f,0.138762f},{0.280668f,0.0195912f,0.141282f}, -{0.284873f,0.0180446f,0.140336f},{0.289177f,0.0166436f,0.139669f},{0.276508f,0.021206f,0.142313f}, -{0.272355f,0.0228275f,0.143363f},{0.268199f,0.0244304f,0.144433f},{0.264f,0.0259067f,0.145514f}, -{0.311196f,0.0105278f,0.138237f},{0.334008f,0.00972275f,0.139465f},{0.338577f,0.00968775f,0.139665f}, -{0.320325f,0.00978412f,0.13844f},{0.324884f,0.0097971f,0.13882f},{0.329444f,0.00976655f,0.139166f}, -{0.311232f,0.0104201f,0.138077f},{0.306797f,0.0114944f,0.138315f},{0.315758f,0.00983335f,0.13811f}, -{0.298014f,0.013988f,0.138879f},{0.293615f,0.0152086f,0.139158f},{0.3024f,0.0127235f,0.138598f}, -{0.280701f,0.01932f,0.14109f},{0.284911f,0.017804f,0.140155f},{0.289219f,0.0164298f,0.139496f}, -{0.276533f,0.0209031f,0.142109f},{0.272372f,0.0224922f,0.143148f},{0.268208f,0.0240607f,0.144207f}, -{0.264f,0.0254987f,0.145277f},{0.334373f,-0.0240512f,0.144207f},{0.338577f,-0.0254987f,0.145277f}, -{0.326047f,-0.0208987f,0.142106f},{0.330206f,-0.0224907f,0.143149f},{0.313354f,-0.0164319f,0.139508f}, -{0.308957f,-0.015224f,0.139169f},{0.317674f,-0.0177924f,0.140121f},{0.300179f,-0.0127141f,0.138599f}, -{0.295784f,-0.0114783f,0.1383f},{0.304565f,-0.0139803f,0.138881f},{0.282253f,-0.00981234f,0.138457f}, -{0.286812f,-0.00988648f,0.138137f},{0.291345f,-0.0103884f,0.138061f},{0.277693f,-0.00979575f,0.138821f}, -{0.273133f,-0.00976673f,0.139168f},{0.26857f,-0.00972076f,0.139471f},{0.264f,-0.00968775f,0.139665f}, -{0.32188f,-0.0193145f,0.141081f},{0.334381f,-0.0244211f,0.144433f},{0.338577f,-0.0259067f,0.145514f}, -{0.321913f,-0.0195856f,0.141274f},{0.326071f,-0.0212016f,0.14231f},{0.330223f,-0.0228261f,0.143364f}, -{0.313395f,-0.016646f,0.139681f},{0.308997f,-0.0154158f,0.139338f},{0.317712f,-0.0180326f,0.140302f}, -{0.295821f,-0.0116084f,0.138462f},{0.300217f,-0.0128655f,0.138763f},{0.304604f,-0.0141518f,0.139047f}, -{0.282278f,-0.0098846f,0.138622f},{0.286844f,-0.0099743f,0.138297f},{0.29138f,-0.0104962f,0.13822f}, -{0.277712f,-0.00985341f,0.138994f},{0.273146f,-0.00980859f,0.139347f},{0.268576f,-0.0097442f,0.139657f}, -{0.264f,-0.00968775f,0.139856f},{0.33439f,-0.0246992f,0.144769f},{0.338577f,-0.0262125f,0.145873f}, -{0.321945f,-0.019792f,0.141546f},{0.326096f,-0.0214312f,0.142603f},{0.33024f,-0.0230793f,0.143679f}, -{0.309038f,-0.0155626f,0.139563f},{0.317751f,-0.0182163f,0.140554f},{0.295857f,-0.0117083f,0.13866f}, -{0.300255f,-0.0129816f,0.138971f},{0.304643f,-0.0142832f,0.139263f},{0.282302f,-0.00993888f,0.138809f}, -{0.286874f,-0.0100406f,0.138482f},{0.291414f,-0.0105787f,0.13841f},{0.27773f,-0.00989672f,0.139183f}, -{0.273158f,-0.00984006f,0.139539f},{0.268582f,-0.00976183f,0.139849f},{0.264f,-0.00968775f,0.140047f}, -{0.313436f,-0.0168098f,0.139917f},{0.338577f,-0.0264087f,0.146586f},{0.327432f,-0.0221132f,0.143529f}, -{0.331132f,-0.0235942f,0.144532f},{0.334836f,-0.0250554f,0.145553f},{0.316228f,-0.0178005f,0.140741f}, -{0.312338f,-0.0165745f,0.140236f},{0.323731f,-0.0206269f,0.142536f},{0.320009f,-0.0191717f,0.141579f}, -{0.300528f,-0.01314f,0.139366f},{0.304457f,-0.0143137f,0.139645f},{0.308394f,-0.015459f,0.139935f}, -{0.288596f,-0.0101788f,0.138724f},{0.292635f,-0.0109184f,0.138808f},{0.296593f,-0.0119892f,0.139084f}, -{0.280402f,-0.00995447f,0.139285f},{0.284498f,-0.00997902f,0.138946f},{0.276306f,-0.00990604f,0.139616f}, -{0.272207f,-0.0098442f,0.139924f},{0.268106f,-0.00976429f,0.140182f},{0.264f,-0.00968775f,0.140347f}, -{0.334628f,-0.0249437f,0.145241f},{0.338577f,-0.0263814f,0.146312f},{0.322896f,-0.0202741f,0.142109f}, -{0.326807f,-0.0218394f,0.143139f},{0.330715f,-0.023405f,0.144181f},{0.314923f,-0.0173571f,0.14037f}, -{0.310786f,-0.0161317f,0.139953f},{0.318956f,-0.0187523f,0.141118f},{0.302483f,-0.0136985f,0.13936f}, -{0.29833f,-0.0124827f,0.139069f},{0.306629f,-0.0149357f,0.139649f},{0.289937f,-0.010352f,0.138591f}, -{0.294173f,-0.0112762f,0.138755f},{0.281305f,-0.00995919f,0.139092f},{0.285627f,-0.010024f,0.138759f}, -{0.276982f,-0.00991129f,0.139444f},{0.272659f,-0.00984923f,0.139775f},{0.264f,-0.00968775f,0.140237f}, -{0.268333f,-0.00976681f,0.14006f},{0.489193f,0.00379135f,0.143971f},{0.488833f,0.00496458f,0.143658f}, -{0.489314f,-0.00742307f,0.146358f},{0.489314f,0.00257039f,0.144284f},{0.48825f,0.00603944f,0.14336f}, -{0.489314f,-0.00240499f,0.145424f},{0.387061f,-0.0211541f,0.147844f},{0.435444f,-0.0173396f,0.147586f}, -{0.483726f,-0.013533f,0.147211f},{0.485008f,-0.0132893f,0.147183f},{0.4862f,-0.0127783f,0.147122f}, -{0.487256f,-0.0120253f,0.147029f},{0.488129f,-0.0110634f,0.146904f},{0.488778f,-0.00994277f,0.146747f}, -{0.489179f,-0.00870927f,0.146564f},{0.489052f,-0.0123416f,0.144272f},{0.489962f,-0.0109102f,0.144086f}, -{0.487844f,-0.0135295f,0.144414f},{0.450527f,-0.0164058f,0.144708f},{0.413211f,-0.0192822f,0.144935f}, -{0.375894f,-0.0221586f,0.145095f},{0.490523f,-0.00932212f,0.14386f},{0.490713f,-0.00765064f,0.143599f}, -{0.483255f,0.00968775f,0.139474f},{0.484944f,0.00949318f,0.139536f},{0.48999f,0.00543154f,0.140734f}, -{0.49053f,0.00387196f,0.141154f},{0.486539f,0.00892517f,0.139713f},{0.487952f,0.0080214f,0.139987f}, -{0.489121f,0.00683431f,0.140337f},{0.490713f,0.00223012f,0.141572f},{0.483255f,0.00968775f,0.140347f}, -{0.490713f,-0.00268915f,0.144055f},{0.490713f,0.00223012f,0.142928f},{0.490713f,-0.00765064f,0.144979f}, -{0.486568f,-0.0143331f,0.144707f},{0.485411f,-0.0147899f,0.145794f},{0.48523f,-0.0148426f,0.145225f}, -{0.483834f,-0.0150857f,0.145821f},{0.486874f,-0.014171f,0.145734f},{0.488177f,-0.0132538f,0.145642f}, -{0.489249f,-0.0120868f,0.145518f},{0.490052f,-0.0107201f,0.145364f},{0.490545f,-0.00921907f,0.145182f}, -{0.48779f,0.00815064f,0.141617f},{0.489024f,0.00695586f,0.141898f},{0.490519f,0.00391721f,0.142576f}, -{0.489946f,0.00552233f,0.142225f},{0.486401f,0.0089918f,0.140922f},{0.484871f,0.00951028f,0.140494f}, -{0.488748f,0.00632699f,0.143123f},{0.488788f,0.0068323f,0.142705f},{0.488576f,0.00732043f,0.142302f}, -{0.48823f,0.00776225f,0.141937f},{0.374892f,-0.0235779f,0.146493f},{0.386398f,-0.0219204f,0.147693f}, -{0.38644f,-0.0224876f,0.147153f},{0.44752f,-0.0179164f,0.146111f},{0.483831f,-0.0149745f,0.146368f}, -{0.435152f,-0.0186837f,0.146909f},{0.483769f,-0.0140869f,0.147162f},{0.435109f,-0.0180963f,0.147451f}, -{0.483807f,-0.0146193f,0.146864f},{0.411206f,-0.0207472f,0.146335f},{0.490303f,-0.00748972f,0.145954f}, -{0.490142f,-0.00897658f,0.146183f},{0.490461f,-0.00911758f,0.145712f},{0.48969f,-0.0103998f,0.146379f}, -{0.489201f,-0.0119652f,0.146066f},{0.489986f,-0.0106014f,0.145903f},{0.48793f,-0.0128307f,0.14668f}, -{0.486857f,-0.0140507f,0.146292f},{0.488142f,-0.0131339f,0.146196f},{0.485398f,-0.0146743f,0.146354f}, -{0.487626f,-0.0124497f,0.14697f},{0.488574f,-0.0113986f,0.146838f},{0.485172f,-0.0138348f,0.147131f}, -{0.485306f,-0.0143101f,0.146843f},{0.486476f,-0.013274f,0.147068f},{0.489829f,-0.00743905f,0.146261f}, -{0.489704f,-0.00883688f,0.146478f},{0.490614f,-0.00756687f,0.145487f},{0.489277f,-0.0101719f,0.146672f}, -{0.486701f,-0.0137111f,0.146779f},{0.488941f,-0.0117086f,0.146547f},{0.490504f,-0.00254212f,0.144763f}, -{0.490038f,-0.0024474f,0.14522f},{0.490529f,0.00239822f,0.143598f},{0.489991f,0.00252701f,0.144111f}, -{0.490287f,0.00405957f,0.143247f},{0.489296f,0.00550952f,0.143326f},{0.489714f,0.00559184f,0.142876f}, -{0.489834f,0.00407172f,0.143698f},{0.375478f,-0.022887f,0.145323f},{0.375514f,-0.0233314f,0.145788f}, -{0.451096f,-0.0174497f,0.145407f},{0.413325f,-0.0203893f,0.145633f},{0.413289f,-0.0199559f,0.14517f}, -{0.45106f,-0.0170273f,0.144947f},{0.113525f,0.0123416f,0.144272f},{0.112615f,0.0109102f,0.144086f}, -{0.114734f,0.0135295f,0.144414f},{0.15205f,0.0164058f,0.144708f},{0.189366f,0.0192822f,0.144935f}, -{0.226683f,0.0221586f,0.145095f},{0.112054f,0.00932212f,0.14386f},{0.111865f,0.00765064f,0.143599f}, -{0.119322f,-0.00968775f,0.139474f},{0.117633f,-0.00949318f,0.139536f},{0.112587f,-0.00543154f,0.140734f}, -{0.112048f,-0.00387196f,0.141154f},{0.116038f,-0.00892517f,0.139713f},{0.114625f,-0.0080214f,0.139987f}, -{0.113456f,-0.00683431f,0.140337f},{0.111865f,-0.00223012f,0.141572f},{0.113384f,-0.00379135f,0.143971f}, -{0.113745f,-0.00496458f,0.143658f},{0.113263f,0.00742307f,0.146358f},{0.113263f,-0.00257039f,0.144284f}, -{0.114327f,-0.00603944f,0.14336f},{0.113263f,0.00240499f,0.145424f},{0.215517f,0.0211541f,0.147844f}, -{0.167133f,0.0173396f,0.147586f},{0.118851f,0.013533f,0.147211f},{0.117576f,0.0132913f,0.147183f}, -{0.116383f,0.0127821f,0.147123f},{0.115326f,0.0120287f,0.14703f},{0.114453f,0.0110706f,0.146905f}, -{0.113801f,0.00994698f,0.146748f},{0.1134f,0.00871793f,0.146565f},{0.119322f,-0.00968775f,0.140347f}, -{0.111865f,0.00268915f,0.144055f},{0.111865f,0.00765064f,0.144979f},{0.111865f,-0.00223012f,0.142928f}, -{0.116009f,0.0143331f,0.144707f},{0.117177f,0.014793f,0.145794f},{0.117347f,0.0148426f,0.145225f}, -{0.118743f,0.0150857f,0.145821f},{0.115708f,0.014174f,0.145734f},{0.114409f,0.0132606f,0.145643f}, -{0.113332f,0.0120925f,0.145519f},{0.112529f,0.0107278f,0.145364f},{0.112033f,0.00922792f,0.145183f}, -{0.114787f,-0.00815064f,0.141617f},{0.113553f,-0.00695586f,0.141898f},{0.112631f,-0.00552233f,0.142225f}, -{0.112058f,-0.00391721f,0.142576f},{0.116176f,-0.0089918f,0.140922f},{0.117706f,-0.00951028f,0.140494f}, -{0.113789f,-0.0068323f,0.142705f},{0.113829f,-0.00632699f,0.143123f},{0.114001f,-0.00732043f,0.142302f}, -{0.114347f,-0.00776225f,0.141937f},{0.227685f,0.0235779f,0.146493f},{0.216179f,0.0219204f,0.147693f}, -{0.216137f,0.0224876f,0.147153f},{0.155057f,0.0179164f,0.146111f},{0.118746f,0.0149745f,0.146368f}, -{0.167425f,0.0186837f,0.146909f},{0.118809f,0.0140869f,0.147162f},{0.167468f,0.0180963f,0.147451f}, -{0.11877f,0.0146193f,0.146864f},{0.191371f,0.0207472f,0.146335f},{0.115882f,0.0137517f,0.146749f}, -{0.117415f,0.013838f,0.147132f},{0.117273f,0.0143462f,0.146813f},{0.11445f,0.0131473f,0.146196f}, -{0.115741f,0.0140617f,0.146292f},{0.11719f,0.0146779f,0.146354f},{0.113307f,0.0101903f,0.146674f}, -{0.114012f,0.0114133f,0.146839f},{0.11241f,0.00899738f,0.146157f},{0.111963f,0.00756687f,0.145487f}, -{0.112274f,0.00748972f,0.145954f},{0.112599f,0.0106218f,0.145905f},{0.113386f,0.0119815f,0.146067f}, -{0.112119f,0.00912889f,0.145714f},{0.112869f,0.0104352f,0.146353f},{0.112875f,0.00884706f,0.146479f}, -{0.114643f,0.0128697f,0.146651f},{0.116119f,0.0132839f,0.147069f},{0.112748f,0.00743905f,0.146261f}, -{0.114964f,0.0124617f,0.146971f},{0.113623f,0.0117456f,0.146519f},{0.112073f,0.00254212f,0.144763f}, -{0.112539f,0.0024474f,0.14522f},{0.112048f,-0.00239822f,0.143598f},{0.112586f,-0.00252701f,0.144111f}, -{0.11229f,-0.00405957f,0.143247f},{0.113281f,-0.00550952f,0.143326f},{0.112863f,-0.00559184f,0.142876f}, -{0.112743f,-0.00407172f,0.143698f},{0.227063f,0.0233314f,0.145788f},{0.227099f,0.022887f,0.145323f}, -{0.151517f,0.0170273f,0.144947f},{0.151481f,0.0174497f,0.145407f},{0.189252f,0.0203893f,0.145633f}, -{0.189288f,0.0199559f,0.14517f},{0.302945f,-0.0043568f,0.126571f},{0.303939f,-0.00383438f,0.126571f}, -{0.304781f,-0.00308638f,0.126571f},{0.305417f,-0.00216232f,0.126571f},{0.300729f,-0.00462734f,0.126571f}, -{0.301855f,-0.00462608f,0.126571f},{0.298645f,-0.00383806f,0.126571f},{0.299638f,-0.00435903f,0.126571f}, -{0.297801f,-0.00309213f,0.126571f},{0.297163f,-0.00216808f,0.126571f},{0.296764f,-0.00111857f,0.126571f}, -{0.305815f,-0.0011128f,0.126571f},{0.303613f,0.00150163f,0.126571f},{0.303967f,0.000787374f,0.126571f}, -{0.303117f,0.00211724f,0.126571f},{0.302447f,0.00254559f,0.126571f},{0.301683f,0.00276842f,0.126571f}, -{0.300888f,0.00276723f,0.126571f},{0.300125f,0.00254283f,0.126571f},{0.299465f,0.00210508f,0.126571f}, -{0.298949f,0.00150519f,0.126571f},{0.298603f,0.00078745f,0.126571f},{0.30013f,0.00254559f,0.135893f}, -{0.300894f,0.00276842f,0.135893f},{0.303628f,0.00150519f,0.135893f},{0.301689f,0.00276723f,0.135893f}, -{0.303112f,0.00210508f,0.135893f},{0.303974f,0.00078745f,0.135893f},{0.302452f,0.00254283f,0.135893f}, -{0.29946f,0.00211724f,0.135893f},{0.298964f,0.00150163f,0.135893f},{0.29861f,0.000787374f,0.135893f}, -{0.280158f,-0.00265777f,0.126571f},{0.280939f,-0.00225612f,0.126571f},{0.281556f,-0.00163414f,0.126571f}, -{0.278432f,-0.00266037f,0.126571f},{0.277654f,-0.00226719f,0.126571f},{0.279289f,-0.00279661f,0.126571f}, -{0.277032f,-0.00165072f,0.126571f},{0.276631f,-0.000869207f,0.126571f},{0.281946f,-0.000869207f,0.126571f}, -{0.324158f,-0.00265777f,0.126571f},{0.324939f,-0.00225612f,0.126571f},{0.325556f,-0.00163414f,0.126571f}, -{0.322432f,-0.00266037f,0.126571f},{0.323289f,-0.00279661f,0.126571f},{0.321032f,-0.00165072f,0.126571f}, -{0.321654f,-0.00226719f,0.126571f},{0.320631f,-0.000869207f,0.126571f},{0.325946f,-0.000869207f,0.126571f}, -{-0.0027207f,-0.278876f,0.141016f},{-0.00279661f,-0.279289f,0.127503f},{-0.00276223f,-0.279666f,0.140921f}, -{-0.00254178f,-0.278101f,0.141133f},{-0.00266037f,-0.278432f,0.127503f},{-0.00226719f,-0.277654f,0.127503f}, -{-0.00210085f,-0.277449f,0.141283f},{-0.000869207f,-0.276631f,0.127503f},{-0.00165072f,-0.277032f,0.127503f}, -{-0.00149803f,-0.276921f,0.141448f},{-0.000793813f,-0.276599f,0.141604f},{8.0384e-017f,-0.276492f,0.127503f}, -{2.12873e-008f,-0.276492f,0.141748f},{-0.00265777f,-0.280158f,0.127503f},{-0.00255964f,-0.280438f,0.140869f}, -{-0.00225612f,-0.280939f,0.127503f},{-0.00163414f,-0.281556f,0.127503f},{-0.00212367f,-0.28111f,0.140862f}, -{-0.000869207f,-0.281946f,0.127503f},{-0.00151779f,-0.281644f,0.140892f},{-0.000793595f,-0.281979f,0.140955f}, -{7.94845e-017f,-0.282085f,0.127503f},{7.94845e-017f,-0.282085f,0.141048f},{-0.00226719f,-0.321654f,0.127503f}, -{-0.00266113f,-0.32241f,0.141631f},{-0.00225617f,-0.321628f,0.141475f},{-0.00266037f,-0.322432f,0.127503f}, -{-0.00165072f,-0.321032f,0.127503f},{-0.00161123f,-0.321061f,0.141322f},{-0.000869207f,-0.320631f,0.127503f}, -{-0.000861428f,-0.320624f,0.141174f},{-0.00279699f,-0.323269f,0.141768f},{-2.26626e-008f,-0.320492f,0.141048f}, -{7.02374e-017f,-0.320492f,0.127503f},{-0.00279661f,-0.323289f,0.127503f},{-0.00267244f,-0.324142f,0.141876f}, -{-0.00227523f,-0.324922f,0.141932f},{-0.00265777f,-0.324158f,0.127503f},{-0.00225612f,-0.324939f,0.127503f}, -{-0.00164828f,-0.325551f,0.14193f},{-0.00163414f,-0.325556f,0.127503f},{-0.000869207f,-0.325946f,0.127503f}, -{-0.000867575f,-0.325955f,0.141868f},{7.05799e-017f,-0.326085f,0.127503f},{7.05799e-017f,-0.326085f,0.141748f}, -{0.00279661f,-0.301289f,0.136825f},{0.00266037f,-0.300432f,0.127503f},{0.00226719f,-0.302923f,0.136825f}, -{0.00265777f,-0.302158f,0.127503f},{0.00225612f,-0.302939f,0.127503f},{0.00266037f,-0.302145f,0.136825f}, -{0.00165072f,-0.303545f,0.136825f},{0.000869207f,-0.303946f,0.127503f},{7.91421e-017f,-0.304085f,0.136825f}, -{0.000869207f,-0.303946f,0.136825f},{0.00163414f,-0.303556f,0.127503f},{7.91421e-017f,-0.304085f,0.127503f}, -{0.00265777f,-0.300419f,0.136825f},{0.00226719f,-0.299654f,0.127503f},{0.00225612f,-0.299638f,0.136825f}, -{0.00163414f,-0.299021f,0.136825f},{0.00165072f,-0.299032f,0.127503f},{0.000869207f,-0.298631f,0.136825f}, -{0.000869207f,-0.298631f,0.127503f},{7.94845e-017f,-0.298492f,0.127503f},{7.94845e-017f,-0.298492f,0.136825f}, -{-0.00383933f,-0.298637f,0.140336f},{-0.00435933f,-0.299639f,0.127503f},{-0.00437081f,-0.299629f,0.140342f}, -{-0.00462728f,-0.30073f,0.127503f},{-0.00383758f,-0.298643f,0.127503f},{-0.00463064f,-0.30072f,0.140371f}, -{-0.00309444f,-0.297804f,0.127503f},{-0.00308762f,-0.297795f,0.140354f},{-0.00216892f,-0.297163f,0.127503f}, -{-0.00463006f,-0.30185f,0.140416f},{-0.00216891f,-0.297147f,0.14039f},{-0.00111911f,-0.296764f,0.127503f}, -{-5.59251e-014f,-0.296628f,0.140488f},{-3.35892e-010f,-0.296628f,0.127503f},{-0.00112174f,-0.296754f,0.140439f}, -{-0.00462657f,-0.301853f,0.127503f},{-0.00435716f,-0.302944f,0.127503f},{-0.00437228f,-0.302946f,0.140465f}, -{-0.00384698f,-0.303934f,0.140509f},{-0.0038338f,-0.303939f,0.127503f},{-0.00308862f,-0.304779f,0.127503f}, -{-0.00309221f,-0.304777f,0.140537f},{-0.00216381f,-0.305417f,0.127503f},{-0.00217168f,-0.305426f,0.140543f}, -{-0.00112329f,-0.305823f,0.140525f},{-0.00111503f,-0.305814f,0.127503f},{7.94845e-017f,-0.30595f,0.140488f}, -{7.94845e-017f,-0.30595f,0.127503f},{-0.0031834f,-0.268793f,0.141919f},{0.0034311f,-0.268706f,0.143258f}, -{-0.00348389f,-0.273216f,0.141453f},{0.013311f,-0.280744f,0.142108f},{0.00749864f,-0.281094f,0.141891f}, -{0.01447f,-0.27672f,0.142985f},{0.0237151f,-0.26798f,0.145107f},{0.0168317f,-0.268531f,0.144795f}, -{0.0250351f,-0.264f,0.14612f},{0.00309212f,-0.2978f,0.140537f},{0.00980991f,-0.293788f,0.140443f}, -{0.00384705f,-0.298643f,0.140509f},{0.000788852f,-0.281979f,0.141161f},{0.00148198f,-0.281606f,0.141294f}, -{0.00113058f,-0.285735f,0.140739f},{0.00437081f,-0.302948f,0.140342f},{0.00463066f,-0.301857f,0.140371f}, -{0.00734722f,-0.302709f,0.140099f},{-0.00981015f,-0.308774f,0.140456f},{0.00383936f,-0.30394f,0.140336f}, -{0.0030876f,-0.304783f,0.140354f},{0.000835134f,-0.307737f,0.140403f},{-0.00565577f,-0.312842f,0.140706f}, -{-0.00448849f,-0.308256f,0.140582f},{0.000794809f,-0.320599f,0.140955f},{0.00431412f,-0.316415f,0.139973f}, -{0.00152033f,-0.320936f,0.140892f},{-0.0168309f,-0.334055f,0.144796f},{-0.0250351f,-0.338577f,0.14612f}, -{-0.0237151f,-0.334598f,0.145107f},{-0.0110109f,-0.313348f,0.140705f},{-0.00922726f,-0.329718f,0.143432f}, -{-0.0222833f,-0.330654f,0.144104f},{-0.0156491f,-0.329893f,0.143876f},{0.00348559f,-0.329371f,0.141452f}, -{-0.00283697f,-0.329543f,0.142622f},{0.000793378f,-0.325978f,0.141605f},{0.00318417f,-0.333794f,0.141918f}, -{-0.00342276f,-0.33388f,0.143256f},{0.00969325f,-0.334267f,0.140239f},{0.00290707f,-0.338577f,0.142335f}, -{-0.00398877f,-0.338577f,0.143878f},{0.00968775f,-0.338577f,0.140407f},{0.00378729f,-0.325081f,0.140965f}, -{0.00209478f,-0.325129f,0.141284f},{0.00253473f,-0.324474f,0.141134f},{-0.010107f,-0.333967f,0.144218f}, -{0.00272118f,-0.323703f,0.141016f},{0.00973119f,-0.321359f,0.139327f},{0.00404127f,-0.320799f,0.140452f}, -{0.00858894f,-0.298312f,0.140271f},{0.000322559f,-0.290225f,0.140392f},{-0.00611166f,-0.29535f,0.139905f}, -{-0.0049946f,-0.290725f,0.139783f},{-0.00734676f,-0.299868f,0.140099f},{0.0043723f,-0.299631f,0.140465f}, -{-0.00405908f,-0.281789f,0.140464f},{-0.00435339f,-0.286166f,0.139998f},{0.00217165f,-0.297151f,0.140543f}, -{0.00450063f,-0.294309f,0.140568f},{0.00253786f,-0.280465f,0.141575f},{0.00276739f,-0.279704f,0.141709f}, -{0.00835592f,-0.276982f,0.14266f},{0.00255847f,-0.278136f,0.141903f},{0.00212169f,-0.277464f,0.141937f}, -{0.0208182f,-0.275858f,0.143118f},{0.00398877f,-0.264f,0.143878f},{0.0156505f,-0.272694f,0.143875f}, -{-0.00968775f,-0.264f,0.140407f},{-0.00290707f,-0.264f,0.142335f},{-0.00969325f,-0.268311f,0.140239f}, -{-0.00973122f,-0.281218f,0.139327f},{-0.00972934f,-0.276917f,0.139659f},{-0.00378494f,-0.277503f,0.140965f}, -{0.0121774f,-0.284865f,0.141276f},{0.00665136f,-0.2853f,0.141165f},{-0.000816648f,-0.294831f,0.140389f}, -{0.0027728f,-0.278905f,0.141822f},{0.0101155f,-0.268619f,0.144218f},{0.0179944f,-0.264f,0.145774f}, -{0.0222833f,-0.271923f,0.144104f},{0.0109671f,-0.264f,0.145026f},{-0.0097173f,-0.272615f,0.139971f}, -{-0.0097497f,-0.285519f,0.139013f},{-0.00858896f,-0.304264f,0.140271f},{0.00613049f,-0.307222f,0.139921f}, -{-0.00115281f,-0.316849f,0.140712f},{0.00500873f,-0.311834f,0.139791f},{0.0120097f,-0.304385f,0.13929f}, -{0.0108714f,-0.308539f,0.138995f},{0.00463004f,-0.300727f,0.140416f},{0.0131607f,-0.300237f,0.139564f}, -{0.0143354f,-0.296096f,0.139836f},{0.00566917f,-0.289722f,0.140697f},{0.0110148f,-0.289219f,0.140695f}, -{-0.0100181f,-0.289811f,0.138847f},{-0.0108714f,-0.294038f,0.138995f},{-0.0120097f,-0.298192f,0.13929f}, -{-0.0131607f,-0.30234f,0.139564f},{-0.0143354f,-0.306481f,0.139836f},{-0.00666271f,-0.317286f,0.14114f}, -{-0.00749967f,-0.321494f,0.141879f},{0.00277232f,-0.322913f,0.14092f},{0.00972932f,-0.32566f,0.139659f}, -{0.00149718f,-0.325656f,0.141448f},{-0.0121843f,-0.317723f,0.141251f},{0.00255887f,-0.32214f,0.140869f}, -{0.00212359f,-0.321467f,0.140862f},{-0.000305779f,-0.312336f,0.140401f},{0.00112176f,-0.305823f,0.140439f}, -{0.00216894f,-0.30543f,0.14039f},{-0.0133136f,-0.321845f,0.142096f},{-0.00834704f,-0.325602f,0.14266f}, -{-0.0144683f,-0.325864f,0.142986f},{0.0028458f,-0.273043f,0.142624f},{0.0092361f,-0.272869f,0.143432f}, -{0.00151619f,-0.276934f,0.141923f},{0.00079021f,-0.276599f,0.141859f},{0.019351f,-0.279796f,0.142144f}, -{0.0179262f,-0.28376f,0.14121f},{0.0166178f,-0.287806f,0.140509f},{0.00210151f,-0.281123f,0.141433f}, -{0.00112326f,-0.296754f,0.140525f},{0.0154659f,-0.291943f,0.14012f},{0.0100181f,-0.312766f,0.138847f}, -{-0.0154659f,-0.310634f,0.14012f},{0.00974966f,-0.317058f,0.139013f},{-0.0179262f,-0.318817f,0.14121f}, -{-0.0166178f,-0.314771f,0.140509f},{-0.0193511f,-0.322781f,0.142144f},{-0.0208182f,-0.326719f,0.143118f}, -{0.00971729f,-0.329962f,0.139971f},{-0.0179944f,-0.338577f,0.145774f},{-0.0109671f,-0.338577f,0.145026f}, -{0.0262081f,-0.264f,0.148238f},{0.0248064f,-0.267733f,0.147199f},{0.0250058f,-0.267738f,0.146766f}, -{0.0233183f,-0.271434f,0.146165f},{0.0235291f,-0.271439f,0.145739f},{0.0188229f,-0.282552f,0.143165f}, -{0.0190695f,-0.282558f,0.142766f},{0.0203019f,-0.278832f,0.144139f},{0.0205368f,-0.278837f,0.143731f}, -{0.022035f,-0.275137f,0.14473f},{0.0218112f,-0.275132f,0.145147f},{0.015307f,-0.29417f,0.141119f}, -{0.0150041f,-0.294165f,0.141517f},{0.0141429f,-0.298107f,0.140834f},{0.0174212f,-0.286329f,0.1423f}, -{0.0161629f,-0.290221f,0.141811f},{0.0164424f,-0.290226f,0.141416f},{0.0114006f,-0.305963f,0.14071f}, -{0.0106866f,-0.309927f,0.140011f},{0.0117799f,-0.30597f,0.140283f},{0.0125814f,-0.302024f,0.14098f}, -{0.0129503f,-0.302035f,0.14056f},{0.0138012f,-0.298097f,0.141246f},{0.00963024f,-0.322165f,0.140526f}, -{0.00968708f,-0.318066f,0.140168f},{0.0091952f,-0.318055f,0.140649f},{0.0099197f,-0.313966f,0.139934f}, -{0.0102596f,-0.309914f,0.140442f},{0.00946264f,-0.313954f,0.140382f},{0.00907526f,-0.322157f,0.141031f}, -{0.0095489f,-0.326264f,0.140876f},{0.00894343f,-0.326258f,0.141413f},{0.00945311f,-0.330364f,0.141203f}, -{0.00933687f,-0.334468f,0.14148f},{0.00879579f,-0.33036f,0.141773f},{0.0086246f,-0.334465f,0.142088f}, -{0.00922107f,-0.338577f,0.141665f},{0.00845004f,-0.338577f,0.142301f},{0.0176856f,-0.286338f,0.141921f}, -{0.0263793f,-0.264f,0.147802f},{0.0259023f,-0.264f,0.148593f},{0.0244885f,-0.267734f,0.147557f}, -{0.0229936f,-0.271437f,0.146522f},{0.0184899f,-0.282562f,0.143511f},{0.0214828f,-0.275137f,0.145501f}, -{0.0146321f,-0.294177f,0.14188f},{0.0170843f,-0.286341f,0.142644f},{0.0158117f,-0.290234f,0.142162f}, -{0.010968f,-0.305972f,0.141112f},{0.0121699f,-0.302034f,0.141368f},{0.0134094f,-0.298108f,0.141622f}, -{0.0086637f,-0.31806f,0.141107f},{0.00980481f,-0.309921f,0.140857f},{0.00897481f,-0.31396f,0.140813f}, -{0.00849863f,-0.32216f,0.141523f},{0.00832061f,-0.32626f,0.14194f},{0.00812583f,-0.330362f,0.142335f}, -{0.00790535f,-0.334466f,0.142688f},{0.00767878f,-0.338577f,0.142938f},{0.0199715f,-0.278839f,0.144489f}, -{0.0254953f,-0.264f,0.148828f},{0.0239945f,-0.267945f,0.147747f},{0.0224149f,-0.271858f,0.146665f}, -{0.0176882f,-0.283628f,0.143502f},{0.0208215f,-0.275768f,0.145592f},{0.0192329f,-0.279683f,0.144529f}, -{0.0136618f,-0.295955f,0.142081f},{0.0162503f,-0.287664f,0.14274f},{0.0149457f,-0.2918f,0.142346f}, -{0.00869072f,-0.31263f,0.141186f},{0.00973903f,-0.308401f,0.141305f},{0.0110356f,-0.304248f,0.141581f}, -{0.00795144f,-0.321265f,0.141896f},{0.0081943f,-0.316941f,0.14144f},{0.00772122f,-0.325589f,0.142378f}, -{0.00747253f,-0.329914f,0.142842f},{0.00719397f,-0.334241f,0.143263f},{0.00690556f,-0.338577f,0.143577f}, -{0.0123399f,-0.300098f,0.141831f},{0.0250324f,-0.264f,0.148916f},{0.0235306f,-0.267971f,0.147857f}, -{0.0219498f,-0.271889f,0.146794f},{0.0172517f,-0.283688f,0.143711f},{0.0203651f,-0.275809f,0.14574f}, -{0.0132021f,-0.296012f,0.142332f},{0.0158114f,-0.287719f,0.142927f},{0.0144807f,-0.291851f,0.142544f}, -{0.0092687f,-0.308457f,0.141666f},{0.0105497f,-0.304299f,0.141886f},{0.0118813f,-0.300157f,0.142106f}, -{0.0073368f,-0.321297f,0.142324f},{0.00759572f,-0.316973f,0.141811f},{0.00819435f,-0.312673f,0.141567f}, -{0.00708183f,-0.325613f,0.142866f},{0.00678804f,-0.32993f,0.143377f},{0.00646507f,-0.334249f,0.143843f}, -{0.00613003f,-0.338577f,0.144218f},{0.0187868f,-0.279733f,0.144697f},{0.00696068f,-0.326294f,0.143005f}, -{0.00667554f,-0.330384f,0.143491f},{0.00636198f,-0.334476f,0.143939f},{0.00748015f,-0.318115f,0.141999f}, -{0.00786981f,-0.314024f,0.141631f},{0.00722771f,-0.322205f,0.1425f},{0.0111819f,-0.302112f,0.142035f}, -{0.00875236f,-0.309993f,0.14162f},{0.014914f,-0.290321f,0.142686f},{0.0124511f,-0.298189f,0.142242f}, -{0.0137038f,-0.294261f,0.142453f},{0.0175985f,-0.282633f,0.143972f},{0.0190677f,-0.278896f,0.144928f}, -{0.0162018f,-0.286425f,0.143129f},{0.0205663f,-0.275179f,0.145919f},{0.022067f,-0.271464f,0.146916f}, -{0.0235578f,-0.267747f,0.14792f},{0.00994863f,-0.306047f,0.141826f},{0.00603944f,-0.338577f,0.144293f}, -{0.00744254f,-0.272455f,0.145994f},{0.015865f,-0.268304f,0.147531f},{0.0083666f,-0.268397f,0.146789f}, -{0.000311244f,-0.272638f,0.144934f},{0.000930332f,-0.268488f,0.145573f},{-0.00667554f,-0.272193f,0.143491f}, -{0.00158091f,-0.264f,0.146182f},{-0.0063617f,-0.268101f,0.143935f},{0.00932143f,-0.264f,0.147589f}, -{-0.00603944f,-0.264f,0.144293f},{0.00654234f,-0.276379f,0.145204f},{0.00567271f,-0.28029f,0.144415f}, -{0.0134133f,-0.276103f,0.14569f},{0.00989537f,-0.287869f,0.143217f},{0.0110779f,-0.283807f,0.143908f}, -{0.00388505f,-0.28841f,0.143059f},{0.0122295f,-0.279922f,0.144789f},{0.0072715f,-0.296503f,0.142814f}, -{1.23849e-006f,-0.301301f,0.142893f},{0.00593214f,-0.300722f,0.142703f},{0.00860427f,-0.292161f,0.142918f}, -{0.00327255f,-0.30924f,0.142485f},{0.00211647f,-0.31361f,0.14253f},{-0.00133631f,-0.305494f,0.142894f}, -{0.00459153f,-0.304916f,0.142593f},{-0.00836678f,-0.334185f,0.146789f},{-0.00093054f,-0.334094f,0.145573f}, -{-0.000310969f,-0.329944f,0.144934f},{0.00135717f,-0.317858f,0.142953f},{-0.00485039f,-0.318318f,0.143617f}, -{-0.00158091f,-0.338577f,0.146182f},{0.000284983f,-0.325928f,0.144284f},{-0.00744232f,-0.330127f,0.145994f}, -{-0.0171357f,-0.338577f,0.148501f},{-0.0158652f,-0.334277f,0.147532f},{0.000835711f,-0.321928f,0.143615f}, -{-0.00654153f,-0.326203f,0.145205f},{-0.00568021f,-0.322295f,0.144405f},{-0.00265603f,-0.309815f,0.142905f}, -{-0.00387587f,-0.314151f,0.143071f},{0.00267273f,-0.292745f,0.142876f},{0.00133739f,-0.297082f,0.142892f}, -{0.00483092f,-0.284266f,0.143642f},{0.0146267f,-0.272271f,0.1466f},{0.0171357f,-0.264f,0.148501f}, -{-0.0069607f,-0.276283f,0.143005f},{-0.000284018f,-0.276654f,0.144284f},{-0.00722775f,-0.280372f,0.1425f}, -{-0.000847135f,-0.280656f,0.143625f},{-0.00746803f,-0.284462f,0.141989f},{-0.00138663f,-0.284723f,0.142978f}, -{-0.00787057f,-0.288553f,0.141632f},{-0.00210321f,-0.288949f,0.142519f},{-0.00875939f,-0.292582f,0.141625f}, -{-0.00324421f,-0.293326f,0.142456f},{-0.00994211f,-0.296532f,0.141827f},{-0.023562f,-0.334828f,0.147921f}, -{-0.0249766f,-0.338577f,0.148916f},{-0.00458966f,-0.29766f,0.142591f},{-0.0111906f,-0.300462f,0.142034f}, -{-0.0124586f,-0.304385f,0.142239f},{-0.00592971f,-0.30188f,0.142704f},{-0.0136985f,-0.308317f,0.142455f}, -{-0.00727121f,-0.306073f,0.142816f},{-0.0149126f,-0.312257f,0.142682f},{-0.00859914f,-0.310392f,0.142945f}, -{-0.0162055f,-0.316149f,0.143141f},{-0.0098903f,-0.314695f,0.143228f},{-0.0175985f,-0.319944f,0.143972f}, -{-0.0110874f,-0.31878f,0.143884f},{-0.0190677f,-0.323681f,0.144928f},{-0.012233f,-0.322664f,0.144779f}, -{-0.0205663f,-0.327398f,0.145919f},{-0.0134127f,-0.326479f,0.14569f},{-0.0220671f,-0.331113f,0.146916f}, -{-0.0146265f,-0.330311f,0.1466f},{-0.00932143f,-0.338577f,0.147589f},{-0.00690312f,-0.264f,0.143579f}, -{-0.00719191f,-0.268335f,0.143259f},{-0.00746979f,-0.272663f,0.142843f},{-0.00814762f,-0.285643f,0.141414f}, -{-0.0077197f,-0.276988f,0.142379f},{-0.00793083f,-0.281312f,0.141883f},{-0.0110361f,-0.298329f,0.141582f}, -{-0.0123542f,-0.302474f,0.141829f},{-0.00871456f,-0.289949f,0.141206f},{-0.00976951f,-0.294168f,0.141335f}, -{-0.0162476f,-0.314917f,0.14273f},{-0.0149252f,-0.310786f,0.142321f},{-0.0136614f,-0.306622f,0.142081f}, -{-0.0192347f,-0.322891f,0.144536f},{-0.0176916f,-0.318943f,0.143534f},{-0.0208212f,-0.326807f,0.145595f}, -{-0.022413f,-0.330719f,0.146665f},{-0.0239981f,-0.33463f,0.147749f},{-0.0254927f,-0.338577f,0.148829f}, -{-0.00767576f,-0.264f,0.142941f},{-0.00790232f,-0.268111f,0.142685f},{-0.00812312f,-0.272215f,0.142338f}, -{-0.00864847f,-0.284517f,0.1411f},{-0.00831807f,-0.276317f,0.141942f},{-0.00849626f,-0.280417f,0.141525f}, -{-0.0109591f,-0.296607f,0.141114f},{-0.00897354f,-0.288618f,0.140816f},{-0.00981108f,-0.292654f,0.140864f}, -{-0.0146249f,-0.308402f,0.141884f},{-0.0134151f,-0.304467f,0.141621f},{-0.0121769f,-0.30054f,0.141369f}, -{-0.0184881f,-0.320015f,0.143513f},{-0.0158082f,-0.312344f,0.142159f},{-0.0170869f,-0.316233f,0.142657f}, -{-0.0199696f,-0.323738f,0.144491f},{-0.0214809f,-0.32744f,0.145503f},{-0.0229915f,-0.33114f,0.146524f}, -{-0.0244911f,-0.334841f,0.147559f},{-0.0259001f,-0.338577f,0.148595f},{-0.00844643f,-0.264f,0.142304f}, -{-0.0086212f,-0.268112f,0.142086f},{-0.00879266f,-0.272217f,0.141776f},{-0.00917932f,-0.284522f,0.140643f}, -{-0.00894054f,-0.27632f,0.141415f},{-0.0113914f,-0.296616f,0.140713f},{-0.00946126f,-0.288623f,0.140385f}, -{-0.0102671f,-0.292661f,0.14045f},{-0.0149971f,-0.308414f,0.141521f},{-0.0138071f,-0.304478f,0.141245f}, -{-0.0125887f,-0.30055f,0.140981f},{-0.0188214f,-0.320025f,0.143167f},{-0.0161597f,-0.312357f,0.14181f}, -{-0.0174245f,-0.316245f,0.142314f},{-0.0203004f,-0.323745f,0.144141f},{-0.0218097f,-0.327445f,0.145149f}, -{-0.0233168f,-0.331143f,0.146167f},{-0.0248099f,-0.334842f,0.147201f},{-0.0262067f,-0.338577f,0.148241f}, -{-0.0090726f,-0.280421f,0.141033f},{-0.00921688f,-0.264f,0.141668f},{-0.00933302f,-0.268109f,0.141483f}, -{-0.00944958f,-0.272213f,0.141206f},{-0.00968445f,-0.284511f,0.140171f},{-0.00954568f,-0.276314f,0.140879f}, -{-0.0117779f,-0.296607f,0.140285f},{-0.00991732f,-0.288611f,0.139936f},{-0.0106844f,-0.29265f,0.140013f}, -{-0.0153055f,-0.308407f,0.141121f},{-0.0141412f,-0.304471f,0.140836f},{-0.0129485f,-0.300542f,0.140562f}, -{-0.0190685f,-0.320019f,0.142768f},{-0.0176844f,-0.316239f,0.141924f},{-0.016441f,-0.312351f,0.141419f}, -{-0.0205358f,-0.32374f,0.143733f},{-0.0220341f,-0.32744f,0.144732f},{-0.0235282f,-0.331138f,0.145742f}, -{-0.0250051f,-0.334839f,0.146769f},{-0.0263788f,-0.338577f,0.147805f},{-0.00962732f,-0.280413f,0.140529f}, -{-0.00976429f,-0.268106f,0.141114f},{-0.00968775f,-0.264f,0.141279f},{-0.00995451f,-0.280402f,0.140217f}, -{-0.00990606f,-0.276306f,0.140549f},{-0.00984421f,-0.272207f,0.140856f},{-0.0109184f,-0.292635f,0.13974f}, -{-0.00997907f,-0.284498f,0.139878f},{-0.0143137f,-0.304457f,0.140577f},{-0.01314f,-0.300528f,0.140298f}, -{-0.0119892f,-0.296593f,0.140016f},{-0.0178005f,-0.316228f,0.141673f},{-0.0165744f,-0.312338f,0.141169f}, -{-0.015459f,-0.308394f,0.140867f},{-0.0206269f,-0.323731f,0.143469f},{-0.0191718f,-0.320009f,0.142511f}, -{-0.0221132f,-0.327432f,0.144461f},{-0.0235942f,-0.331132f,0.145464f},{-0.0250554f,-0.334836f,0.146485f}, -{-0.0264087f,-0.338577f,0.147518f},{-0.0101788f,-0.288596f,0.139657f},{-0.0137161f,-0.302478f,0.140288f}, -{-0.0124851f,-0.298329f,0.140002f},{-0.0113146f,-0.294164f,0.139715f},{-0.0103804f,-0.28994f,0.139538f}, -{-0.00997452f,-0.285632f,0.139665f},{-0.00994023f,-0.281304f,0.140012f},{-0.00991203f,-0.276982f,0.140375f}, -{-0.009849f,-0.272659f,0.140706f},{-0.00976769f,-0.268332f,0.140986f},{-0.00968775f,-0.264f,0.141169f}, -{-0.014938f,-0.306628f,0.140581f},{-0.0161103f,-0.310795f,0.140863f},{-0.0173564f,-0.314927f,0.141293f}, -{-0.0187613f,-0.318949f,0.142077f},{-0.0202782f,-0.322893f,0.143048f},{-0.021842f,-0.326806f,0.144073f}, -{-0.0234057f,-0.330714f,0.145113f},{-0.024951f,-0.334625f,0.146173f},{-0.0263814f,-0.338577f,0.147244f}, -{-0.00976336f,-0.268582f,0.140775f},{-0.00968775f,-0.264f,0.140979f},{-0.00990978f,-0.282301f,0.139723f}, -{-0.00989796f,-0.27773f,0.140113f},{-0.00983969f,-0.273158f,0.140469f},{-0.0106101f,-0.291415f,0.139359f}, -{-0.0117247f,-0.295853f,0.139609f},{-0.00998742f,-0.286881f,0.139387f},{-0.0142908f,-0.304641f,0.140193f}, -{-0.0155467f,-0.309044f,0.140484f},{-0.0129908f,-0.300252f,0.139902f},{-0.0197978f,-0.321941f,0.142487f}, -{-0.0182285f,-0.317743f,0.141521f},{-0.0168071f,-0.313441f,0.140836f},{-0.0214356f,-0.326094f,0.143538f}, -{-0.0230806f,-0.330239f,0.14461f},{-0.0247084f,-0.334386f,0.145702f},{-0.0262125f,-0.338577f,0.146805f}, -{-0.00974593f,-0.268576f,0.140582f},{-0.00968775f,-0.264f,0.140788f},{-0.00985594f,-0.282277f,0.139537f}, -{-0.00985469f,-0.277712f,0.139924f},{-0.00980831f,-0.273146f,0.140278f},{-0.0116247f,-0.295818f,0.13941f}, -{-0.00992109f,-0.28685f,0.139202f},{-0.0141594f,-0.304602f,0.139977f},{-0.0154002f,-0.309003f,0.140259f}, -{-0.0128748f,-0.300215f,0.139695f},{-0.0195912f,-0.321909f,0.142214f},{-0.0180446f,-0.317704f,0.141269f}, -{-0.0166436f,-0.3134f,0.140601f},{-0.021206f,-0.326069f,0.143245f},{-0.0228275f,-0.330222f,0.144296f}, -{-0.0244304f,-0.334378f,0.145365f},{-0.0259067f,-0.338577f,0.146446f},{-0.0105278f,-0.291381f,0.139169f}, -{-0.00972275f,-0.268569f,0.140397f},{-0.00968775f,-0.264f,0.140597f},{-0.00978412f,-0.282252f,0.139372f}, -{-0.0097971f,-0.277693f,0.139752f},{-0.00976655f,-0.273133f,0.140099f},{-0.0104201f,-0.291345f,0.139009f}, -{-0.0114944f,-0.295781f,0.139248f},{-0.00983335f,-0.286819f,0.139043f},{-0.013988f,-0.304563f,0.139811f}, -{-0.0152086f,-0.308962f,0.14009f},{-0.0127235f,-0.300177f,0.13953f},{-0.01932f,-0.321876f,0.142022f}, -{-0.017804f,-0.317666f,0.141087f},{-0.0164298f,-0.313358f,0.140429f},{-0.0209031f,-0.326044f,0.143041f}, -{-0.0224922f,-0.330205f,0.144081f},{-0.0240607f,-0.334369f,0.145139f},{-0.0254987f,-0.338577f,0.146209f}, -{0.0240512f,-0.268205f,0.145139f},{0.0254987f,-0.264f,0.146209f},{0.0208987f,-0.276531f,0.143038f}, -{0.0224907f,-0.272372f,0.144081f},{0.0164319f,-0.289223f,0.14044f},{0.015224f,-0.29362f,0.140101f}, -{0.0177924f,-0.284903f,0.141053f},{0.0127141f,-0.302398f,0.139531f},{0.0114783f,-0.306793f,0.139232f}, -{0.0139803f,-0.298012f,0.139813f},{0.00981234f,-0.320325f,0.139389f},{0.00988648f,-0.315765f,0.139069f}, -{0.0103884f,-0.311233f,0.138993f},{0.00979575f,-0.324884f,0.139753f},{0.00976673f,-0.329444f,0.1401f}, -{0.00972076f,-0.334007f,0.140404f},{0.00968775f,-0.338577f,0.140597f},{0.0193145f,-0.280697f,0.142013f}, -{0.0244211f,-0.268196f,0.145365f},{0.0259067f,-0.264f,0.146446f},{0.0195856f,-0.280665f,0.142206f}, -{0.0212016f,-0.276506f,0.143242f},{0.0228261f,-0.272354f,0.144296f},{0.016646f,-0.289182f,0.140613f}, -{0.0154158f,-0.29358f,0.14027f},{0.0180326f,-0.284865f,0.141234f},{0.0116084f,-0.306756f,0.139394f}, -{0.0128655f,-0.30236f,0.139695f},{0.0141518f,-0.297973f,0.13998f},{0.0098846f,-0.320299f,0.139554f}, -{0.0099743f,-0.315733f,0.139229f},{0.0104962f,-0.311197f,0.139152f},{0.00985341f,-0.324865f,0.139926f}, -{0.00980859f,-0.329431f,0.140279f},{0.0097442f,-0.334001f,0.140589f},{0.00968775f,-0.338577f,0.140788f}, -{0.0246992f,-0.268187f,0.145701f},{0.0262125f,-0.264f,0.146805f},{0.019792f,-0.280632f,0.142478f}, -{0.0214312f,-0.276481f,0.143536f},{0.0230793f,-0.272337f,0.144611f},{0.0155626f,-0.293539f,0.140495f}, -{0.0182163f,-0.284826f,0.141486f},{0.0117083f,-0.30672f,0.139593f},{0.0129816f,-0.302322f,0.139903f}, -{0.0142832f,-0.297934f,0.140196f},{0.00993888f,-0.320275f,0.139741f},{0.0100406f,-0.315703f,0.139415f}, -{0.0105787f,-0.311163f,0.139342f},{0.00989672f,-0.324847f,0.140115f},{0.00984006f,-0.329419f,0.140471f}, -{0.00976183f,-0.333995f,0.140782f},{0.00968775f,-0.338577f,0.140979f},{0.0168098f,-0.289141f,0.140849f}, -{0.0264087f,-0.264f,0.147518f},{0.0221132f,-0.275145f,0.144461f},{0.0235942f,-0.271445f,0.145464f}, -{0.0250554f,-0.267741f,0.146485f},{0.0178005f,-0.28635f,0.141673f},{0.0165745f,-0.290239f,0.141169f}, -{0.0206269f,-0.278846f,0.143469f},{0.0191717f,-0.282568f,0.142511f},{0.01314f,-0.302049f,0.140298f}, -{0.0143137f,-0.29812f,0.140577f},{0.015459f,-0.294183f,0.140867f},{0.0101788f,-0.313981f,0.139657f}, -{0.0109184f,-0.309942f,0.13974f},{0.0119892f,-0.305984f,0.140016f},{0.00995447f,-0.322175f,0.140217f}, -{0.00997902f,-0.318079f,0.139878f},{0.00990604f,-0.326272f,0.140549f},{0.0098442f,-0.33037f,0.140856f}, -{0.00976429f,-0.334471f,0.141114f},{0.00968775f,-0.338577f,0.141279f},{0.0249437f,-0.267949f,0.146173f}, -{0.0263814f,-0.264f,0.147244f},{0.0202741f,-0.279681f,0.143041f},{0.0218394f,-0.27577f,0.144071f}, -{0.023405f,-0.271862f,0.145114f},{0.0173571f,-0.287654f,0.141303f},{0.0161317f,-0.291791f,0.140885f}, -{0.0187523f,-0.283621f,0.14205f},{0.0136985f,-0.300094f,0.140292f},{0.0124827f,-0.304247f,0.140001f}, -{0.0149357f,-0.295948f,0.140582f},{0.010352f,-0.31264f,0.139523f},{0.0112762f,-0.308404f,0.139687f}, -{0.00995919f,-0.321273f,0.140024f},{0.010024f,-0.31695f,0.139691f},{0.00991129f,-0.325595f,0.140376f}, -{0.00984923f,-0.329918f,0.140707f},{0.00968775f,-0.338577f,0.141169f},{0.00976681f,-0.334244f,0.140992f}, -{-0.00379135f,-0.113384f,0.144903f},{-0.00496458f,-0.113745f,0.14459f},{0.00742307f,-0.113263f,0.147291f}, -{-0.00257039f,-0.113263f,0.145216f},{-0.00603944f,-0.114327f,0.144293f},{0.00240499f,-0.113263f,0.146356f}, -{0.0211541f,-0.215517f,0.148776f},{0.0173396f,-0.167133f,0.148518f},{0.013533f,-0.118851f,0.148143f}, -{0.0132893f,-0.117569f,0.148115f},{0.0127783f,-0.116377f,0.148054f},{0.0120253f,-0.115321f,0.147961f}, -{0.0110634f,-0.114448f,0.147836f},{0.00994277f,-0.113799f,0.14768f},{0.00870927f,-0.113398f,0.147496f}, -{0.0123416f,-0.113525f,0.145204f},{0.0109102f,-0.112615f,0.145018f},{0.0135295f,-0.114734f,0.145346f}, -{0.0164058f,-0.15205f,0.14564f},{0.0192822f,-0.189366f,0.145867f},{0.0221586f,-0.226683f,0.146027f}, -{0.00932212f,-0.112054f,0.144792f},{0.00765064f,-0.111865f,0.144531f},{-0.00968775f,-0.119322f,0.140407f}, -{-0.00949318f,-0.117633f,0.140468f},{-0.00543154f,-0.112587f,0.141666f},{-0.00387196f,-0.112048f,0.142086f}, -{-0.00892517f,-0.116038f,0.140645f},{-0.0080214f,-0.114625f,0.14092f},{-0.00683431f,-0.113456f,0.141269f}, -{-0.00223012f,-0.111865f,0.142505f},{-0.00968775f,-0.119322f,0.141279f},{0.00268915f,-0.111865f,0.144987f}, -{-0.00223012f,-0.111865f,0.14386f},{0.00765064f,-0.111865f,0.145911f},{0.0143331f,-0.116009f,0.145639f}, -{0.0147899f,-0.117166f,0.146726f},{0.0148426f,-0.117347f,0.146158f},{0.0150857f,-0.118743f,0.146754f}, -{0.014171f,-0.115703f,0.146666f},{0.0132538f,-0.1144f,0.146574f},{0.0120868f,-0.113328f,0.14645f}, -{0.0107201f,-0.112525f,0.146296f},{0.00921907f,-0.112032f,0.146114f},{-0.00815064f,-0.114787f,0.142549f}, -{-0.00695586f,-0.113553f,0.14283f},{-0.00391721f,-0.112058f,0.143508f},{-0.00552233f,-0.112631f,0.143157f}, -{-0.0089918f,-0.116176f,0.141854f},{-0.00951028f,-0.117706f,0.141426f},{-0.00632699f,-0.113829f,0.144055f}, -{-0.0068323f,-0.113789f,0.143638f},{-0.00732043f,-0.114001f,0.143234f},{-0.00776225f,-0.114347f,0.14287f}, -{0.0235779f,-0.227685f,0.147426f},{0.0219204f,-0.216179f,0.148625f},{0.0224876f,-0.216137f,0.148085f}, -{0.0179164f,-0.155057f,0.147043f},{0.0149745f,-0.118746f,0.1473f},{0.0186837f,-0.167425f,0.147841f}, -{0.0140869f,-0.118809f,0.148094f},{0.0180963f,-0.167468f,0.148384f},{0.0146193f,-0.11877f,0.147797f}, -{0.0207472f,-0.191371f,0.147267f},{0.00748972f,-0.112274f,0.146886f},{0.00897658f,-0.112435f,0.147115f}, -{0.00911758f,-0.112116f,0.146645f},{0.0103998f,-0.112887f,0.147311f},{0.0119652f,-0.113376f,0.146998f}, -{0.0106014f,-0.112592f,0.146835f},{0.0128307f,-0.114648f,0.147613f},{0.0140507f,-0.11572f,0.147224f}, -{0.0131339f,-0.114435f,0.147128f},{0.0146743f,-0.117179f,0.147286f},{0.0124497f,-0.114951f,0.147903f}, -{0.0113986f,-0.114003f,0.14777f},{0.0138348f,-0.117405f,0.148064f},{0.0143101f,-0.117272f,0.147775f}, -{0.013274f,-0.116101f,0.148f},{0.00743905f,-0.112748f,0.147194f},{0.00883688f,-0.112873f,0.14741f}, -{0.00756687f,-0.111963f,0.146419f},{0.0101719f,-0.1133f,0.147604f},{0.0137111f,-0.115877f,0.147711f}, -{0.0117086f,-0.113636f,0.147479f},{0.00254212f,-0.112073f,0.145696f},{0.0024474f,-0.112539f,0.146152f}, -{-0.00239822f,-0.112048f,0.14453f},{-0.00252701f,-0.112586f,0.145044f},{-0.00405957f,-0.11229f,0.14418f}, -{-0.00550952f,-0.113281f,0.144258f},{-0.00559184f,-0.112863f,0.143809f},{-0.00407172f,-0.112743f,0.14463f}, -{0.022887f,-0.227099f,0.146255f},{0.0233314f,-0.227063f,0.14672f},{0.0174497f,-0.151481f,0.14634f}, -{0.0203893f,-0.189252f,0.146565f},{0.0199559f,-0.189288f,0.146102f},{0.0170273f,-0.151517f,0.145879f}, -{-0.0123416f,-0.489052f,0.145204f},{-0.0109102f,-0.489962f,0.145018f},{-0.0135295f,-0.487844f,0.145346f}, -{-0.0164058f,-0.450527f,0.14564f},{-0.0192822f,-0.413211f,0.145867f},{-0.0221586f,-0.375894f,0.146027f}, -{-0.00932212f,-0.490523f,0.144792f},{-0.00765064f,-0.490713f,0.144531f},{0.00968775f,-0.483255f,0.140407f}, -{0.00949318f,-0.484944f,0.140468f},{0.00543154f,-0.48999f,0.141666f},{0.00387196f,-0.49053f,0.142086f}, -{0.00892517f,-0.486539f,0.140645f},{0.0080214f,-0.487952f,0.14092f},{0.00683431f,-0.489121f,0.141269f}, -{0.00223012f,-0.490713f,0.142505f},{0.00379135f,-0.489193f,0.144903f},{0.00496458f,-0.488833f,0.14459f}, -{-0.00742307f,-0.489314f,0.147291f},{0.00257039f,-0.489314f,0.145216f},{0.00603944f,-0.48825f,0.144293f}, -{-0.00240499f,-0.489314f,0.146356f},{-0.0211541f,-0.387061f,0.148776f},{-0.0173396f,-0.435444f,0.148518f}, -{-0.013533f,-0.483726f,0.148143f},{-0.0132913f,-0.485001f,0.148115f},{-0.0127821f,-0.486194f,0.148055f}, -{-0.0120287f,-0.487252f,0.147962f},{-0.0110706f,-0.488124f,0.147837f},{-0.00994698f,-0.488776f,0.14768f}, -{-0.00871793f,-0.489178f,0.147497f},{0.00968775f,-0.483255f,0.141279f},{-0.00268915f,-0.490713f,0.144987f}, -{-0.00765064f,-0.490713f,0.145911f},{0.00223012f,-0.490713f,0.14386f},{-0.0143331f,-0.486568f,0.145639f}, -{-0.014793f,-0.4854f,0.146726f},{-0.0148426f,-0.48523f,0.146158f},{-0.0150857f,-0.483834f,0.146754f}, -{-0.014174f,-0.486869f,0.146667f},{-0.0132606f,-0.488168f,0.146575f},{-0.0120925f,-0.489246f,0.146451f}, -{-0.0107278f,-0.490048f,0.146297f},{-0.00922792f,-0.490544f,0.146115f},{0.00815064f,-0.48779f,0.142549f}, -{0.00695586f,-0.489024f,0.14283f},{0.00552233f,-0.489946f,0.143157f},{0.00391721f,-0.490519f,0.143508f}, -{0.0089918f,-0.486401f,0.141854f},{0.00951028f,-0.484871f,0.141426f},{0.0068323f,-0.488788f,0.143638f}, -{0.00632699f,-0.488748f,0.144055f},{0.00732043f,-0.488576f,0.143234f},{0.00776225f,-0.48823f,0.14287f}, -{-0.0235779f,-0.374892f,0.147426f},{-0.0219204f,-0.386398f,0.148625f},{-0.0224876f,-0.38644f,0.148085f}, -{-0.0179164f,-0.447521f,0.147043f},{-0.0149745f,-0.483831f,0.1473f},{-0.0186837f,-0.435152f,0.147841f}, -{-0.0140869f,-0.483769f,0.148094f},{-0.0180963f,-0.435109f,0.148384f},{-0.0146193f,-0.483807f,0.147797f}, -{-0.0207472f,-0.411206f,0.147267f},{-0.0137517f,-0.486695f,0.147682f},{-0.013838f,-0.485162f,0.148064f}, -{-0.0143462f,-0.485304f,0.147745f},{-0.0131473f,-0.488127f,0.147128f},{-0.0140617f,-0.486836f,0.147224f}, -{-0.0146779f,-0.485388f,0.147286f},{-0.0101903f,-0.48927f,0.147606f},{-0.0114133f,-0.488565f,0.147771f}, -{-0.00899738f,-0.490167f,0.147089f},{-0.00756687f,-0.490614f,0.146419f},{-0.00748972f,-0.490303f,0.146886f}, -{-0.0106218f,-0.489978f,0.146837f},{-0.0119815f,-0.489191f,0.146999f},{-0.00912889f,-0.490458f,0.146646f}, -{-0.0104352f,-0.489708f,0.147285f},{-0.00884706f,-0.489702f,0.147411f},{-0.0128697f,-0.487935f,0.147584f}, -{-0.0132839f,-0.486458f,0.148001f},{-0.00743905f,-0.489829f,0.147194f},{-0.0124617f,-0.487613f,0.147903f}, -{-0.0117456f,-0.488955f,0.147451f},{-0.00254212f,-0.490504f,0.145696f},{-0.0024474f,-0.490038f,0.146152f}, -{0.00239822f,-0.490529f,0.14453f},{0.00252701f,-0.489991f,0.145044f},{0.00405957f,-0.490287f,0.14418f}, -{0.00550952f,-0.489296f,0.144258f},{0.00559184f,-0.489714f,0.143809f},{0.00407172f,-0.489834f,0.14463f}, -{-0.0233314f,-0.375514f,0.14672f},{-0.022887f,-0.375478f,0.146255f},{-0.0170273f,-0.45106f,0.145879f}, -{-0.0174497f,-0.451096f,0.14634f},{-0.0203893f,-0.413325f,0.146565f},{-0.0199559f,-0.413289f,0.146102f}, -{0.0043568f,-0.299632f,0.127503f},{0.00383438f,-0.298639f,0.127503f},{0.00308638f,-0.297796f,0.127503f}, -{0.00216232f,-0.29716f,0.127503f},{0.00462734f,-0.301848f,0.127503f},{0.00462608f,-0.300722f,0.127503f}, -{0.00383806f,-0.303933f,0.127503f},{0.00435903f,-0.302939f,0.127503f},{0.00309213f,-0.304776f,0.127503f}, -{0.00216808f,-0.305415f,0.127503f},{0.00111857f,-0.305813f,0.127503f},{0.0011128f,-0.296762f,0.127503f}, -{-0.00150163f,-0.298964f,0.127503f},{-0.000787374f,-0.29861f,0.127503f},{-0.00211724f,-0.29946f,0.127503f}, -{-0.00254559f,-0.30013f,0.127503f},{-0.00276842f,-0.300894f,0.127503f},{-0.00276723f,-0.301689f,0.127503f}, -{-0.00254283f,-0.302452f,0.127503f},{-0.00210508f,-0.303112f,0.127503f},{-0.00150519f,-0.303628f,0.127503f}, -{-0.00078745f,-0.303974f,0.127503f},{-0.00254559f,-0.302447f,0.136825f},{-0.00276842f,-0.301683f,0.136825f}, -{-0.00150519f,-0.298949f,0.136825f},{-0.00276723f,-0.300888f,0.136825f},{-0.00210508f,-0.299465f,0.136825f}, -{-0.00078745f,-0.298603f,0.136825f},{-0.00254283f,-0.300125f,0.136825f},{-0.00211724f,-0.303117f,0.136825f}, -{-0.00150163f,-0.303613f,0.136825f},{-0.000787374f,-0.303967f,0.136825f},{0.00265777f,-0.322419f,0.127503f}, -{0.00225612f,-0.321638f,0.127503f},{0.00163414f,-0.321021f,0.127503f},{0.00266037f,-0.324145f,0.127503f}, -{0.00226719f,-0.324923f,0.127503f},{0.00279661f,-0.323289f,0.127503f},{0.00165072f,-0.325545f,0.127503f}, -{0.000869207f,-0.325946f,0.127503f},{0.000869207f,-0.320631f,0.127503f},{0.00265777f,-0.278419f,0.127503f}, -{0.00225612f,-0.277638f,0.127503f},{0.00163414f,-0.277021f,0.127503f},{0.00266037f,-0.280145f,0.127503f}, -{0.00279661f,-0.279289f,0.127503f},{0.00165072f,-0.281545f,0.127503f},{0.00226719f,-0.280923f,0.127503f}, -{0.000869207f,-0.281946f,0.127503f},{0.000869207f,-0.276631f,0.127503f},{0.14024f,0.0905829f,-0.141015f}, -{0.136285f,0.0947137f,-0.142188f},{0.141059f,0.0890842f,-0.140701f},{0.164944f,0.0609206f,-0.129448f}, -{0.166387f,0.0597515f,-0.12867f},{0.162134f,0.0647663f,-0.131224f},{0.121812f,0.11117f,-0.145366f}, -{0.121542f,0.1109f,-0.145713f},{0.12625f,0.10535f,-0.144944f},{0.13153f,0.100321f,-0.143429f}, -{0.135762f,0.095863f,-0.142366f},{0.130854f,0.0995405f,-0.144466f},{0.126104f,0.105142f,-0.145472f}, -{0.122103f,0.111436f,-0.145199f},{0.126512f,0.105627f,-0.144598f},{0.1268f,0.105898f,-0.144431f}, -{0.112085f,0.121672f,-0.147719f},{0.112073f,0.121686f,-0.147105f},{0.107472f,0.127074f,-0.147351f}, -{0.121386f,0.110705f,-0.146243f},{0.107827f,0.127376f,-0.148558f},{0.112579f,0.122056f,-0.148599f}, -{0.112283f,0.121818f,-0.148251f},{0.107534f,0.127127f,-0.148015f},{0.117758f,0.117092f,-0.148493f}, -{0.117549f,0.116806f,-0.148445f},{0.112883f,0.122308f,-0.148767f},{0.113146f,0.12253f,-0.14881f}, -{0.108275f,0.127755f,-0.148876f},{0.10853f,0.127972f,-0.148916f},{0.149108f,0.0801256f,-0.137702f}, -{0.145845f,0.0834412f,-0.138964f},{0.150634f,0.0777938f,-0.136973f},{0.14469f,0.0853356f,-0.13946f}, -{0.15542f,0.0721513f,-0.134725f},{0.153491f,0.0749577f,-0.135742f},{0.159928f,0.0662252f,-0.132375f}, -{0.160192f,0.0665236f,-0.132217f},{0.157834f,0.0698365f,-0.133582f},{0.169666f,0.0553525f,-0.126416f}, -{0.170589f,0.0547966f,-0.125923f},{0.178987f,0.0443625f,-0.119568f},{0.183567f,0.0389616f,-0.115753f}, -{0.182854f,0.040335f,-0.116543f},{0.17435f,0.0498296f,-0.123123f},{0.194531f,0.0265656f,-0.105516f}, -{0.19071f,0.0310716f,-0.109369f},{0.192523f,0.028401f,-0.107358f},{0.186816f,0.0356628f,-0.113046f}, -{0.201944f,0.0178247f,-0.0972923f},{0.201149f,0.0182303f,-0.0979722f},{0.205317f,0.0133161f,-0.0929223f}, -{0.196882f,0.0232619f,-0.102786f},{0.212441f,0.00544782f,-0.0837205f},{0.213321f,0.00387764f,-0.0821464f}, -{0.215761f,0.00153276f,-0.0788827f},{0.209376f,0.00852884f,-0.0876442f},{0.225146f,-0.009533f,-0.0634868f}, -{0.222116f,-0.00596092f,-0.0687614f},{0.224391f,-0.00917553f,-0.0644306f},{0.218987f,-0.00227125f,-0.0738949f}, -{0.220835f,-0.00498246f,-0.0705292f},{0.233609f,-0.0195123f,-0.0468636f},{0.231071f,-0.0170525f,-0.0517099f}, -{0.234185f,-0.0207242f,-0.0451124f},{0.227805f,-0.013201f,-0.0581535f},{0.239939f,-0.0275089f,-0.0315071f}, -{0.241084f,-0.0283265f,-0.0291439f},{0.238706f,-0.0255224f,-0.0351637f},{0.236213f,-0.0225835f,-0.041072f}, -{0.247512f,-0.0359059f,-0.010468f},{0.245489f,-0.0335205f,-0.0167907f},{0.247339f,-0.0362343f,-0.0102766f}, -{0.242572f,-0.0306138f,-0.0245261f},{0.249469f,-0.0387463f,-0.0030353f},{0.25119f,-0.0402428f,0.00244111f}, -{0.249413f,-0.0381473f,-0.00405553f},{0.254843f,-0.0450829f,0.0189909f},{0.254367f,-0.0439888f,0.0156645f}, -{0.253221f,-0.0431703f,0.0116119f},{0.252842f,-0.0421905f,0.00901635f},{0.25143f,-0.0410583f,0.00426541f}, -{0.257032f,-0.0471308f,0.0291557f},{0.257585f,-0.0483159f,0.0337941f},{0.258169f,-0.0484718f,0.0359868f}, -{0.256297f,-0.0467975f,0.0263892f},{0.255764f,-0.0456361f,0.0223796f},{0.259175f,-0.0496578f,0.0428671f}, -{0.259671f,-0.0507748f,0.0485748f},{0.260048f,-0.0506878f,0.0497904f},{0.258709f,-0.0496406f,0.0411933f}, -{0.262173f,-0.0537259f,0.0848371f},{0.262476f,-0.0535502f,0.0918925f},{0.262408f,-0.0534705f,0.0848393f}, -{0.260789f,-0.0515609f,0.0567509f},{0.260474f,-0.0517219f,0.0559272f},{0.261618f,-0.0530714f,0.0705019f}, -{0.261426f,-0.0534542f,0.0704868f},{0.261775f,-0.0538661f,0.077694f},{0.262205f,-0.0532315f,0.0777923f}, -{0.261395f,-0.0522762f,0.0637421f},{0.261868f,-0.0528332f,0.0707579f},{0.261967f,-0.053483f,0.0777041f}, -{0.261122f,-0.0524859f,0.0632397f},{0.26171f,-0.054377f,0.0776733f},{0.262073f,-0.0551849f,0.084806f}, -{0.261917f,-0.0546204f,0.0848218f},{0.259477f,-0.051156f,0.0485442f},{0.258514f,-0.050021f,0.0411575f}, -{0.26136f,-0.0539645f,0.0704555f},{0.260929f,-0.0528684f,0.0632194f},{0.260863f,-0.0533778f,0.0631775f}, -{0.259408f,-0.0516629f,0.0484808f},{0.261911f,-0.0549937f,0.0703525f},{0.261411f,-0.0544042f,0.0630396f}, -{0.262441f,-0.055239f,0.0703047f},{0.261017f,-0.0539394f,0.0631135f},{0.261516f,-0.0545274f,0.0704077f}, -{0.262955f,-0.0552578f,0.0702734f},{0.263308f,-0.0556738f,0.0775525f},{0.263265f,-0.0560102f,0.0918925f}, -{0.263001f,-0.0558996f,0.0847721f},{0.263516f,-0.0559194f,0.0847617f},{0.263926f,-0.0557923f,0.0847568f}, -{0.263974f,-0.0558822f,0.0918925f},{0.263625f,-0.0559923f,0.0918925f},{0.264284f,-0.055683f,0.0918925f}, -{0.256101f,-0.0471759f,0.026343f},{0.237143f,-0.0242111f,-0.0383737f},{0.243346f,-0.0309933f,-0.0230178f}, -{0.24504f,-0.033523f,-0.0174448f},{0.239731f,-0.0278737f,-0.0315942f},{0.230894f,-0.0163116f,-0.0525331f}, -{0.228073f,-0.0129842f,-0.0580758f},{0.217143f,-0.000628865f,-0.0764381f},{0.209029f,0.00947049f,-0.088404f}, -{0.220614f,-0.00533134f,-0.0706439f},{0.220489f,-0.00577124f,-0.0708815f},{0.224052f,-0.0099734f,-0.0647696f}, -{0.205529f,0.0135974f,-0.0929293f},{0.198277f,0.0221487f,-0.101489f},{0.178826f,0.0450842f,-0.119856f}, -{0.174737f,0.0499061f,-0.122984f},{0.188082f,0.0336377f,-0.111682f},{0.20076f,0.0174918f,-0.098384f}, -{0.196643f,0.0229329f,-0.102924f},{0.196483f,0.0225343f,-0.103209f},{0.13126f,0.101171f,-0.14351f}, -{0.126738f,0.106503f,-0.144448f},{0.1222f,0.111854f,-0.145179f},{0.11225f,0.121856f,-0.146574f}, -{0.107533f,0.127126f,-0.147023f},{0.117445f,0.116929f,-0.145739f},{0.11765f,0.117219f,-0.145701f}, -{0.112831f,0.122369f,-0.146057f},{0.113092f,0.122593f,-0.146014f},{0.107472f,0.127075f,-0.147687f}, -{0.108274f,0.127755f,-0.146158f},{0.10853f,0.127972f,-0.146119f},{0.108041f,0.127557f,-0.146297f}, -{0.107823f,0.127372f,-0.146474f},{0.112534f,0.12211f,-0.146225f},{0.107652f,0.127227f,-0.146724f}, -{0.11715f,0.116666f,-0.145907f},{0.131245f,0.100046f,-0.143596f},{0.136004f,0.0944352f,-0.142353f}, -{0.140782f,0.0888017f,-0.140865f},{0.145571f,0.0831547f,-0.139127f},{0.150363f,0.0775033f,-0.137134f}, -{0.155152f,0.0718569f,-0.134885f},{0.164476f,0.0602748f,-0.129928f},{0.169209f,0.0546946f,-0.12689f}, -{0.164683f,0.0606183f,-0.129604f},{0.169409f,0.0550462f,-0.126571f},{0.174096f,0.0495195f,-0.123274f}, -{0.178736f,0.0440485f,-0.119717f},{0.183319f,0.0386437f,-0.1159f},{0.187838f,0.0333161f,-0.111826f}, -{0.192282f,0.0280757f,-0.107499f},{0.200914f,0.0178978f,-0.0981062f},{0.205084f,0.0129801f,-0.0930527f}, -{0.209147f,0.00818951f,-0.087771f},{0.213094f,0.00353502f,-0.0822693f},{0.216919f,-0.000974661f,-0.0765569f}, -{0.224172f,-0.00952736f,-0.0645409f},{0.227589f,-0.0135557f,-0.0582594f},{0.230857f,-0.0174099f,-0.0518113f}, -{0.233973f,-0.0210842f,-0.0452091f},{0.236933f,-0.0245736f,-0.0384656f},{0.247174f,-0.0376161f,-0.0107265f}, -{0.244746f,-0.0343736f,-0.017682f},{0.244864f,-0.0348929f,-0.0179263f},{0.242366f,-0.0309808f,-0.0246083f}, -{0.244835f,-0.033892f,-0.017522f},{0.247136f,-0.0366052f,-0.0103487f},{0.249268f,-0.039119f,-0.0031023f}, -{0.25123f,-0.0414326f,0.00420356f},{0.253023f,-0.0435461f,0.0115553f},{0.254646f,-0.0454601f,0.0189394f}, -{0.25739f,-0.0486953f,0.0337531f},{0.258444f,-0.0505263f,0.0410833f},{0.26028f,-0.0521038f,0.0559018f}, -{0.261981f,-0.0541092f,0.0848321f},{0.262065f,-0.0541415f,0.0918925f},{0.262228f,-0.0538242f,0.0918925f}, -{0.107655f,0.12723f,-0.14831f},{0.116874f,0.116405f,-0.146254f},{0.130989f,0.0997606f,-0.14394f}, -{0.135755f,0.0941412f,-0.142695f},{0.14054f,0.0884994f,-0.141205f},{0.145336f,0.0828442f,-0.139464f}, -{0.150136f,0.0771845f,-0.137469f},{0.154931f,0.0715299f,-0.135216f},{0.159714f,0.0658899f,-0.132703f}, -{0.173903f,0.0491597f,-0.123589f},{0.173863f,0.0488268f,-0.12407f},{0.17852f,0.0433355f,-0.120499f}, -{0.17855f,0.0436807f,-0.120026f},{0.18314f,0.0382681f,-0.116203f},{0.187665f,0.0329327f,-0.112124f}, -{0.192115f,0.0276847f,-0.10779f},{0.209044f,0.00734409f,-0.0884349f},{0.209305f,0.00703665f,-0.0888979f}, -{0.213277f,0.00235295f,-0.0833616f},{0.204936f,0.012567f,-0.0933231f},{0.209005f,0.00776938f,-0.0880336f}, -{0.212958f,0.00310807f,-0.0825239f},{0.216788f,-0.00140821f,-0.0768032f},{0.230834f,-0.0183499f,-0.0523423f}, -{0.231151f,-0.0187233f,-0.0527127f},{0.234287f,-0.0224207f,-0.046069f},{0.227474f,-0.0140076f,-0.0584789f}, -{0.230747f,-0.0178675f,-0.0520214f},{0.233868f,-0.0215472f,-0.0454095f},{0.236831f,-0.0250416f,-0.0386562f}, -{0.239634f,-0.0283465f,-0.0317747f},{0.242273f,-0.0314582f,-0.0247786f},{0.24705f,-0.0370908f,-0.0104982f}, -{0.249185f,-0.0396083f,-0.00324118f},{0.25115f,-0.0419253f,0.00407537f},{0.252945f,-0.0440419f,0.0114378f}, -{0.254571f,-0.0459587f,0.0188328f},{0.256028f,-0.0476769f,0.0262471f},{0.257318f,-0.0491986f,0.0336681f}, -{0.260213f,-0.052612f,0.0558492f},{0.262263f,-0.0554082f,0.077605f},{0.261986f,-0.054502f,0.0918925f}, -{0.117242f,0.116558f,-0.148277f},{0.116707f,0.116222f,-0.146785f},{0.135631f,0.0939085f,-0.143218f}, -{0.135703f,0.0938233f,-0.143822f},{0.14051f,0.0881545f,-0.142325f},{0.140426f,0.0882542f,-0.141725f}, -{0.145233f,0.0825863f,-0.13998f},{0.150043f,0.076914f,-0.137981f},{0.154849f,0.0712468f,-0.135723f}, -{0.159643f,0.0655943f,-0.133204f},{0.164416f,0.0599666f,-0.130423f},{0.169159f,0.0543739f,-0.127378f}, -{0.183121f,0.0379109f,-0.116668f},{0.183315f,0.0376819f,-0.117203f},{0.187862f,0.0323208f,-0.113104f}, -{0.187656f,0.0325635f,-0.112579f},{0.192116f,0.0273038f,-0.108236f},{0.196494f,0.022142f,-0.103644f}, -{0.20078f,0.0170882f,-0.0988083f},{0.204966f,0.0121524f,-0.0937362f},{0.213006f,0.00267239f,-0.0829128f}, -{0.216844f,-0.00185395f,-0.0771794f},{0.220553f,-0.00622672f,-0.0712445f},{0.224125f,-0.0104382f,-0.065119f}, -{0.227554f,-0.0144815f,-0.0588143f},{0.233962f,-0.0220378f,-0.0457157f},{0.236932f,-0.0255401f,-0.0389474f}, -{0.239741f,-0.0288523f,-0.0320505f},{0.242386f,-0.0319709f,-0.0250388f},{0.249313f,-0.0401392f,-0.00345334f}, -{0.249678f,-0.0405686f,-0.00369814f},{0.251652f,-0.0428967f,0.00365355f},{0.251283f,-0.0424614f,0.00387953f}, -{0.253082f,-0.0445827f,0.0112584f},{0.254711f,-0.0465038f,0.0186698f},{0.256171f,-0.0482259f,0.0261007f}, -{0.257465f,-0.049751f,0.0335382f},{0.258593f,-0.0510816f,0.04097f},{0.259559f,-0.0522207f,0.048384f}, -{0.260366f,-0.053172f,0.0557688f},{0.261866f,-0.0549408f,0.0776416f},{0.262004f,-0.0548614f,0.0918925f}, -{0.121422f,0.110663f,-0.146855f},{0.126152f,0.105086f,-0.146081f},{0.116731f,0.116194f,-0.147398f}, -{0.130914f,0.0994698f,-0.145073f},{0.145329f,0.0824721f,-0.140576f},{0.150152f,0.0767852f,-0.138571f}, -{0.154971f,0.0711034f,-0.136307f},{0.155264f,0.071138f,-0.136814f},{0.16008f,0.0654584f,-0.134283f}, -{0.159777f,0.0654364f,-0.133782f},{0.164562f,0.0597942f,-0.130993f},{0.169317f,0.0541872f,-0.127941f}, -{0.174034f,0.0486258f,-0.124624f},{0.178703f,0.0431205f,-0.121044f},{0.192334f,0.0270476f,-0.10875f}, -{0.192709f,0.0269844f,-0.109195f},{0.197108f,0.0217978f,-0.104581f},{0.196723f,0.0218725f,-0.104146f}, -{0.20102f,0.0168058f,-0.0992979f},{0.205216f,0.0118573f,-0.0942128f},{0.217125f,-0.00218501f,-0.0776135f}, -{0.217556f,-0.0023131f,-0.0779897f},{0.221282f,-0.00670683f,-0.0720263f},{0.220843f,-0.00656901f,-0.0716633f}, -{0.224424f,-0.0107914f,-0.0655221f},{0.227862f,-0.0148449f,-0.0592012f},{0.237264f,-0.025932f,-0.0392833f}, -{0.23774f,-0.0261128f,-0.0395744f},{0.240562f,-0.0294409f,-0.0326445f},{0.240081f,-0.0292527f,-0.0323688f}, -{0.242732f,-0.0323793f,-0.025339f},{0.245217f,-0.0353088f,-0.0182083f},{0.247532f,-0.038039f,-0.01099f}, -{0.253456f,-0.0450235f,0.0110514f},{0.255089f,-0.0469495f,0.0184819f},{0.255604f,-0.0471769f,0.0183189f}, -{0.257071f,-0.0489073f,0.0257854f},{0.256553f,-0.048676f,0.0259318f},{0.25785f,-0.050205f,0.0333884f}, -{0.258981f,-0.051539f,0.0408392f},{0.25995f,-0.0526811f,0.0482723f},{0.260759f,-0.0536348f,0.0556761f}, -{0.26247f,-0.0556528f,0.0847878f},{0.262314f,-0.055521f,0.0918925f},{0.262114f,-0.0552103f,0.0918925f}, -{0.12164f,0.110785f,-0.147384f},{0.12638f,0.105196f,-0.14661f},{0.116939f,0.116328f,-0.147929f}, -{0.131153f,0.0995673f,-0.145599f},{0.135953f,0.0939083f,-0.144345f},{0.140771f,0.0882269f,-0.142845f}, -{0.145601f,0.0825319f,-0.141092f},{0.150434f,0.0768324f,-0.139082f},{0.164876f,0.0598037f,-0.131488f}, -{0.170021f,0.0543241f,-0.128748f},{0.169642f,0.0541843f,-0.128429f},{0.174369f,0.0486105f,-0.125105f}, -{0.179048f,0.043093f,-0.121517f},{0.183671f,0.0376423f,-0.117667f},{0.188227f,0.0322693f,-0.113559f}, -{0.20184f,0.0168054f,-0.1f},{0.201414f,0.0167199f,-0.0997223f},{0.20562f,0.0117604f,-0.0946258f}, -{0.209718f,0.00692902f,-0.0892991f},{0.213699f,0.00223494f,-0.0837506f},{0.225331f,-0.0108931f,-0.0661002f}, -{0.224871f,-0.0109385f,-0.0658715f},{0.228316f,-0.0150011f,-0.0595366f},{0.231613f,-0.0188881f,-0.0530336f}, -{0.234755f,-0.0225937f,-0.0463752f},{0.243706f,-0.0325604f,-0.0257695f},{0.24322f,-0.0325744f,-0.0255992f}, -{0.24571f,-0.0355104f,-0.0184526f},{0.24803f,-0.0382467f,-0.0112184f},{0.25018f,-0.0407819f,-0.00391029f}, -{0.252159f,-0.0431152f,0.00345771f},{0.253967f,-0.0452467f,0.0108719f},{0.258371f,-0.0504397f,0.0332586f}, -{0.260015f,-0.0517904f,0.0406518f},{0.259505f,-0.0517766f,0.0407259f},{0.260475f,-0.0529213f,0.0481755f}, -{0.261286f,-0.0538771f,0.0555957f},{0.26194f,-0.0546482f,0.0629755f},{0.262793f,-0.0556544f,0.0775733f}, -{0.262905f,-0.0559313f,0.0918925f},{0.26258f,-0.0557625f,0.0918925f},{0.108037f,0.127554f,-0.148751f}, -{0.12195f,0.111007f,-0.147731f},{0.126697f,0.105409f,-0.146955f},{0.131477f,0.0997729f,-0.145943f}, -{0.136283f,0.0941057f,-0.144688f},{0.141109f,0.0884161f,-0.143185f},{0.145945f,0.0827128f,-0.141429f}, -{0.150786f,0.077005f,-0.139417f},{0.155622f,0.0713023f,-0.137145f},{0.160446f,0.0656145f,-0.134611f}, -{0.165249f,0.0599517f,-0.131812f},{0.175103f,0.0489424f,-0.125571f},{0.179652f,0.0441098f,-0.122344f}, -{0.179792f,0.043413f,-0.121975f},{0.174755f,0.0487422f,-0.125419f},{0.179441f,0.0432167f,-0.121826f}, -{0.18407f,0.0377581f,-0.117971f},{0.188634f,0.0323774f,-0.113856f},{0.193122f,0.0270848f,-0.109486f}, -{0.197527f,0.0218907f,-0.104866f},{0.206052f,0.0118387f,-0.0948962f},{0.206422f,0.0120131f,-0.0950266f}, -{0.210155f,0.00700034f,-0.0895618f},{0.214142f,0.00229945f,-0.0840052f},{0.218005f,-0.00225518f,-0.0782359f}, -{0.221737f,-0.00665528f,-0.072264f},{0.229166f,-0.0148059f,-0.059862f},{0.232332f,-0.0180071f,-0.0542297f}, -{0.23247f,-0.0187013f,-0.053345f},{0.228781f,-0.0149616f,-0.059756f},{0.232082f,-0.0188542f,-0.0532437f}, -{0.235229f,-0.0225652f,-0.0465757f},{0.238218f,-0.0260893f,-0.039765f},{0.241045f,-0.0294223f,-0.0328251f}, -{0.2462f,-0.0355006f,-0.0186126f},{0.248923f,-0.0381014f,-0.0114399f},{0.248524f,-0.0382409f,-0.0113678f}, -{0.250677f,-0.0407797f,-0.00404916f},{0.252658f,-0.0431164f,0.00332952f},{0.254469f,-0.045251f,0.0107545f}, -{0.256108f,-0.047184f,0.0182123f},{0.257578f,-0.0489169f,0.0256896f},{0.258879f,-0.0504515f,0.0331736f}, -{0.260987f,-0.0529367f,0.0481121f},{0.261799f,-0.0538939f,0.0555431f},{0.262453f,-0.0546661f,0.0629336f}, -{0.12226f,0.111251f,-0.147899f},{0.127011f,0.105649f,-0.147122f},{0.131794f,0.100009f,-0.146109f}, -{0.136604f,0.0943376f,-0.144853f},{0.141433f,0.0886439f,-0.143349f},{0.146273f,0.0829367f,-0.141592f}, -{0.151117f,0.077225f,-0.139579f},{0.155957f,0.0715183f,-0.137305f},{0.160784f,0.0658265f,-0.134769f}, -{0.16559f,0.0601597f,-0.131968f},{0.170366f,0.0545282f,-0.128902f},{0.184425f,0.0379506f,-0.118117f}, -{0.188991f,0.0325661f,-0.114f},{0.193483f,0.0272698f,-0.109627f},{0.197891f,0.0220721f,-0.105003f}, -{0.202207f,0.0169833f,-0.100134f},{0.203042f,0.0165301f,-0.0995149f},{0.210528f,0.00717136f,-0.0896885f}, -{0.214517f,0.00246719f,-0.0841281f},{0.218383f,-0.00209063f,-0.0783547f},{0.222117f,-0.0064938f,-0.0723786f}, -{0.225713f,-0.0107346f,-0.0662105f},{0.235619f,-0.0224148f,-0.0466724f},{0.23861f,-0.0259414f,-0.039857f}, -{0.241439f,-0.0292767f,-0.0329122f},{0.244102f,-0.032417f,-0.0258517f},{0.246597f,-0.0353593f,-0.0186898f}, -{0.247098f,-0.035418f,-0.0180672f},{0.251077f,-0.0406421f,-0.00411618f},{0.25306f,-0.0429804f,0.00326766f}, -{0.254872f,-0.0451164f,0.0106978f},{0.256512f,-0.0470508f,0.0181608f},{0.257983f,-0.0487849f,0.0256434f}, -{0.259285f,-0.0503206f,0.0331326f},{0.260422f,-0.0516605f,0.040616f},{0.261395f,-0.0528075f,0.0480815f}, -{0.262207f,-0.0537654f,0.0555177f},{0.262862f,-0.0545382f,0.0629134f},{0.263364f,-0.0551303f,0.0702583f}, -{0.263717f,-0.0555466f,0.0775425f},{0.122361f,0.111664f,-0.147965f},{0.126952f,0.106251f,-0.147226f}, -{0.131527f,0.100856f,-0.146277f},{0.136082f,0.0954854f,-0.145118f},{0.140613f,0.0901431f,-0.143752f}, -{0.145115f,0.0848342f,-0.142179f},{0.149585f,0.0795631f,-0.1404f},{0.154019f,0.0743346f,-0.138417f}, -{0.158414f,0.069153f,-0.136232f},{0.162764f,0.0640231f,-0.133846f},{0.167067f,0.0589495f,-0.131262f}, -{0.171319f,0.0539366f,-0.128482f},{0.175515f,0.0489885f,-0.125509f},{0.183727f,0.0393048f,-0.118992f}, -{0.187736f,0.0345778f,-0.115454f},{0.191676f,0.0299328f,-0.111734f},{0.195542f,0.0253738f,-0.107835f}, -{0.199332f,0.0209049f,-0.103761f},{0.206669f,0.0122532f,-0.0951008f},{0.21021f,0.00807804f,-0.0905224f}, -{0.213662f,0.00400799f,-0.0857837f},{0.217021f,4.68757e-005f,-0.080889f},{0.220285f,-0.00380184f,-0.0758426f}, -{0.223451f,-0.00753479f,-0.0706488f},{0.226516f,-0.0111487f,-0.0653124f},{0.229477f,-0.0146406f,-0.0598376f}, -{0.235079f,-0.0212454f,-0.0484934f},{0.237714f,-0.0243525f,-0.042634f},{0.240235f,-0.027326f,-0.0366563f}, -{0.242642f,-0.030163f,-0.0305656f},{0.24493f,-0.0328612f,-0.0243674f},{0.249145f,-0.0378313f,-0.0116704f}, -{0.251068f,-0.0400991f,-0.00518257f},{0.252866f,-0.0422192f,0.00139061f},{0.254537f,-0.0441898f,0.00804317f}, -{0.25608f,-0.0460092f,0.0147693f},{0.257494f,-0.0476758f,0.0215631f},{0.258776f,-0.0491881f,0.0284189f}, -{0.259927f,-0.0505448f,0.0353305f},{0.260944f,-0.0517447f,0.0422916f},{0.261828f,-0.0527868f,0.0492962f}, -{0.262577f,-0.0536701f,0.0563382f},{0.263191f,-0.0543939f,0.0634117f},{0.263669f,-0.0549575f,0.0705101f}, -{0.264011f,-0.0553604f,0.0776272f},{0.264216f,-0.0556023f,0.0847567f},{-0.0421135f,0.305602f,0.0428677f}, -{-0.0431344f,0.306274f,0.0485758f},{-0.0421725f,0.30514f,0.0411945f},{-0.0348943f,0.296558f,0.00426646f}, -{-0.0341289f,0.296187f,0.00244165f},{-0.0357808f,0.298135f,0.00901696f},{-0.0445856f,0.307985f,0.0632405f}, -{-0.0450821f,0.30857f,0.0705025f},{-0.0449943f,0.307857f,0.0632202f},{-0.0437274f,0.307505f,0.0567511f}, -{-0.0443341f,0.308221f,0.0637424f},{-0.0465618f,0.309118f,0.084822f},{-0.0467942f,0.309247f,0.0918925f}, -{-0.047093f,0.309365f,0.0848062f},{-0.0460053f,0.308462f,0.0704561f},{-0.0455077f,0.307875f,0.0631783f}, -{-0.0454912f,0.308443f,0.0704874f},{-0.0474899f,0.309833f,0.084788f},{-0.0476948f,0.310316f,0.0918925f}, -{-0.0476466f,0.310397f,0.0847723f},{-0.0465353f,0.308707f,0.0704083f},{-0.0460366f,0.308119f,0.0631143f}, -{-0.0473898f,0.311292f,0.084757f},{-0.0471813f,0.311046f,0.0775429f},{-0.047582f,0.310908f,0.084762f}, -{-0.0477127f,0.310676f,0.0918925f},{-0.0472235f,0.311628f,0.0918925f},{-0.0474707f,0.311354f,0.0918925f}, -{-0.0469501f,0.311305f,0.0776267f},{-0.0439376f,0.307221f,0.0559281f},{-0.042987f,0.306632f,0.0497909f}, -{-0.0471552f,0.311547f,0.0847564f},{-0.0399705f,0.303075f,0.0291561f},{-0.0410491f,0.303815f,0.0337954f}, -{-0.0397614f,0.302297f,0.0263905f},{-0.0411077f,0.304416f,0.0359874f},{-0.0383074f,0.300582f,0.0189921f}, -{-0.0387028f,0.301581f,0.0223799f},{-0.0366854f,0.29867f,0.0116131f},{-0.0373058f,0.299933f,0.015665f}, -{-0.0329336f,0.294246f,-0.00303443f},{-0.0323518f,0.294092f,-0.0040552f},{-0.0285038f,0.289022f,-0.0174445f}, -{-0.0260366f,0.286113f,-0.0245261f},{-0.0262848f,0.286938f,-0.0230172f},{-0.0308032f,0.291734f,-0.010276f}, -{-0.0191526f,0.278528f,-0.0410717f},{-0.021645f,0.281467f,-0.0351634f},{-0.0206068f,0.279711f,-0.0383731f}, -{-0.0240231f,0.284271f,-0.0291434f},{-0.0138336f,0.272256f,-0.0525327f},{-0.0145359f,0.272552f,-0.051709f}, -{-0.0112697f,0.268701f,-0.0581524f},{-0.0176497f,0.276224f,-0.0451116f},{-0.00505546f,0.261906f,-0.0687612f}, -{-0.00429986f,0.260483f,-0.0705281f},{-0.0019264f,0.258216f,-0.0738946f},{-0.00785583f,0.264676f,-0.0644294f}, -{0.00803165f,0.246474f,-0.088404f},{0.00462002f,0.250497f,-0.0837203f},{0.00715869f,0.246971f,-0.0876434f}, -{0.0012997f,0.254412f,-0.0788824f},{0.0032141f,0.251623f,-0.0821454f},{0.0187835f,0.233796f,-0.101489f}, -{0.0153863f,0.23727f,-0.0979716f},{0.0196536f,0.232238f,-0.102786f},{0.0112187f,0.242184f,-0.0929216f}, -{0.0284535f,0.221862f,-0.111682f},{0.0302445f,0.220282f,-0.113046f},{0.0263509f,0.224873f,-0.109369f}, -{0.0225294f,0.229379f,-0.105516f},{0.042324f,0.206039f,-0.122984f},{0.0382345f,0.210861f,-0.119856f}, -{0.0421853f,0.20567f,-0.123123f},{0.0329688f,0.216538f,-0.115753f},{0.046869f,0.200148f,-0.126416f}, -{0.0506736f,0.196194f,-0.12867f},{0.0464716f,0.201148f,-0.125923f},{0.0611154f,0.183349f,-0.134725f}, -{0.0592264f,0.186109f,-0.133582f},{0.0563427f,0.188977f,-0.132217f},{0.0549264f,0.191179f,-0.131224f}, -{0.051591f,0.19458f,-0.129448f},{0.0679525f,0.175819f,-0.137702f},{0.0659006f,0.177707f,-0.136973f}, -{0.0706901f,0.172059f,-0.138964f},{0.0635697f,0.180987f,-0.135742f},{0.076821f,0.165362f,-0.141015f}, -{0.0754758f,0.166416f,-0.140701f},{0.0802502f,0.160787f,-0.142188f},{0.0723708f,0.170609f,-0.13946f}, -{0.085801f,0.154773f,-0.143511f},{0.081299f,0.160082f,-0.142366f},{0.0850057f,0.155179f,-0.14343f}, -{0.0935937f,0.143476f,-0.146244f},{0.0938119f,0.143598f,-0.145714f},{0.0891046f,0.149149f,-0.144944f}, -{0.103705f,0.133131f,-0.146058f},{0.0994105f,0.138726f,-0.145701f},{0.0990909f,0.138571f,-0.145739f}, -{0.103968f,0.133352f,-0.146015f},{0.0944326f,0.144064f,-0.145199f},{0.0897354f,0.149602f,-0.144432f}, -{0.0941219f,0.14382f,-0.145367f},{0.0948607f,0.144091f,-0.145179f},{0.0903229f,0.149442f,-0.144449f}, -{0.0751518f,0.166188f,-0.140865f},{0.0795988f,0.160357f,-0.142696f},{0.0799295f,0.160555f,-0.142353f}, -{0.0888759f,0.149039f,-0.145472f},{0.0894214f,0.149362f,-0.144599f},{0.093558f,0.143518f,-0.146855f}, -{0.0982489f,0.137987f,-0.147398f},{0.0982726f,0.137959f,-0.146786f},{0.0939839f,0.143983f,-0.147732f}, -{0.098692f,0.138431f,-0.148277f},{0.0937144f,0.143713f,-0.147385f},{0.103072f,0.132679f,-0.148251f}, -{0.103355f,0.132933f,-0.148599f},{0.103653f,0.133192f,-0.148767f},{0.103915f,0.133415f,-0.14881f}, -{0.0655698f,0.177487f,-0.137135f},{0.0240122f,0.227099f,-0.107358f},{0.0342068f,0.21561f,-0.116543f}, -{0.0375489f,0.211137f,-0.119568f},{0.0280962f,0.221673f,-0.111826f},{0.0151164f,0.23812f,-0.097292f}, -{0.0115314f,0.242348f,-0.0929291f},{-0.000607728f,0.256129f,-0.076437f},{-0.00808476f,0.265478f,-0.0634867f}, -{0.00283905f,0.251455f,-0.0822683f},{0.00239561f,0.25139f,-0.0825229f},{0.00634876f,0.246729f,-0.0880327f}, -{-0.0110117f,0.268929f,-0.0580755f},{-0.0165481f,0.275457f,-0.0468631f},{-0.028428f,0.289465f,-0.0167902f}, -{-0.0304509f,0.29185f,-0.0104677f},{-0.0234034f,0.283008f,-0.0315068f},{-0.0153929f,0.272365f,-0.0520204f}, -{-0.0180395f,0.276074f,-0.0452083f},{-0.0185135f,0.276045f,-0.0454087f},{-0.0370886f,0.298535f,0.0115564f}, -{-0.0448065f,0.308778f,0.0707584f},{-0.0473856f,0.309657f,0.0918925f},{-0.0451443f,0.309176f,0.0777929f}, -{-0.0454312f,0.308982f,0.0777045f},{-0.0460469f,0.309098f,0.0848323f},{-0.0464337f,0.309168f,0.0918925f}, -{-0.045347f,0.309415f,0.0848396f},{-0.0456374f,0.309225f,0.0848373f},{-0.0457254f,0.309296f,0.0918925f}, -{-0.0460743f,0.309186f,0.0918925f},{-0.0454147f,0.309495f,0.0918925f},{-0.0471187f,0.309415f,0.0918925f}, -{-0.0475847f,0.309968f,0.0918925f},{-0.0458406f,0.308855f,0.0776945f},{-0.0443459f,0.307092f,0.0559028f}, -{-0.0435421f,0.306145f,0.0485453f},{-0.0425796f,0.30501f,0.0411587f},{-0.0414554f,0.303684f,0.0337544f}, -{-0.0401668f,0.302165f,0.0263442f},{-0.0387117f,0.300449f,0.0189407f},{-0.0357954f,0.296423f,0.00407642f}, -{-0.0338304f,0.294106f,-0.00324031f},{-0.0352962f,0.296422f,0.00420461f},{-0.0333341f,0.294108f,-0.00310144f}, -{-0.0312023f,0.291594f,-0.0103481f},{-0.0289012f,0.288881f,-0.0175217f},{-0.0264323f,0.28597f,-0.0246083f}, -{-0.0237973f,0.282863f,-0.0315939f},{-0.0209987f,0.279563f,-0.038465f},{-0.0149235f,0.272399f,-0.0518103f}, -{-0.0116549f,0.268545f,-0.0582583f},{-0.00823869f,0.264517f,-0.0645398f},{-0.00468021f,0.260321f,-0.0706427f}, -{-0.00098547f,0.255965f,-0.0765558f},{0.00678642f,0.2468f,-0.0877701f},{0.0108493f,0.24201f,-0.093052f}, -{0.0150199f,0.237092f,-0.0981056f},{0.0192902f,0.232057f,-0.102923f},{0.0236518f,0.226914f,-0.107499f}, -{0.0411164f,0.205354f,-0.12407f},{0.0368049f,0.210817f,-0.120026f},{0.0364596f,0.210845f,-0.120499f}, -{0.0326147f,0.216345f,-0.1159f},{0.0371981f,0.210941f,-0.119717f},{0.0418378f,0.20547f,-0.123274f}, -{0.0465247f,0.199943f,-0.126571f},{0.0512501f,0.194372f,-0.129604f},{0.0560052f,0.188765f,-0.132375f}, -{0.0607812f,0.183133f,-0.134885f},{0.0703627f,0.171835f,-0.139127f},{0.0748141f,0.165999f,-0.141206f}, -{0.0846884f,0.154943f,-0.143596f},{0.0987835f,0.138323f,-0.145907f},{0.1034f,0.132879f,-0.146226f}, -{-0.0473737f,0.310663f,0.0775529f},{-0.0463552f,0.308874f,0.0776737f},{-0.0448583f,0.307109f,0.0558501f}, -{-0.0440534f,0.30616f,0.0484819f},{-0.0430895f,0.305024f,0.0410845f},{-0.0419636f,0.303696f,0.0336694f}, -{-0.0406731f,0.302174f,0.0262484f},{-0.0392159f,0.300456f,0.018834f},{-0.0375904f,0.298539f,0.011439f}, -{-0.0316955f,0.291588f,-0.0104976f},{-0.0321936f,0.291796f,-0.0107259f},{-0.029884f,0.289073f,-0.017926f}, -{-0.0293911f,0.288871f,-0.0176816f},{-0.0269185f,0.285956f,-0.0247786f},{-0.0242797f,0.282844f,-0.0317744f}, -{-0.0214769f,0.279539f,-0.0386556f},{-0.00914513f,0.264619f,-0.0651178f},{-0.00944459f,0.264972f,-0.065521f}, -{-0.00586379f,0.26075f,-0.0716622f},{-0.0121196f,0.268506f,-0.0584778f},{-0.00869832f,0.264472f,-0.0647685f}, -{-0.00513464f,0.26027f,-0.0708804f},{-0.0014345f,0.255907f,-0.0768021f},{0.0141994f,0.237092f,-0.0988077f}, -{0.0139599f,0.237375f,-0.0992973f},{0.018257f,0.232308f,-0.104145f},{0.0104176f,0.241931f,-0.0933224f}, -{0.0145943f,0.237006f,-0.0983834f},{0.0188708f,0.231964f,-0.103208f},{0.0232388f,0.226813f,-0.10779f}, -{0.0276897f,0.221565f,-0.112123f},{0.0322148f,0.216229f,-0.116203f},{0.0414513f,0.205338f,-0.123589f}, -{0.0461451f,0.199804f,-0.12689f},{0.0508775f,0.194224f,-0.129928f},{0.0556395f,0.188609f,-0.132703f}, -{0.0604225f,0.182969f,-0.135216f},{0.0652181f,0.177314f,-0.137469f},{0.0700179f,0.171654f,-0.139465f}, -{0.0843646f,0.154738f,-0.14394f},{0.102895f,0.132508f,-0.147719f},{0.0984804f,0.138093f,-0.146255f}, -{0.103104f,0.132641f,-0.146574f},{-0.0453858f,0.307352f,0.0557698f},{-0.046886f,0.309121f,0.077642f}, -{-0.044579f,0.3064f,0.0483851f},{-0.0449695f,0.306861f,0.0482734f},{-0.0440009f,0.305719f,0.0408405f}, -{-0.043613f,0.305261f,0.0409712f},{-0.0424846f,0.303931f,0.0335395f},{-0.0411912f,0.302406f,0.026102f}, -{-0.0397308f,0.300684f,0.0186711f},{-0.0381016f,0.298763f,0.0112596f},{-0.0363027f,0.296641f,0.00388058f}, -{-0.0343333f,0.294319f,-0.00345247f},{-0.0274059f,0.286151f,-0.0250388f},{-0.0277523f,0.286559f,-0.025339f}, -{-0.0251008f,0.283433f,-0.0323684f},{-0.0247612f,0.283032f,-0.0320502f},{-0.0219523f,0.27972f,-0.0389468f}, -{-0.0189822f,0.276218f,-0.0457149f},{-0.0158546f,0.27253f,-0.0523413f},{-0.012574f,0.268662f,-0.0588132f}, -{-0.0055735f,0.260407f,-0.0712434f},{-0.00186511f,0.256035f,-0.0771783f},{0.00197355f,0.251508f,-0.0829118f}, -{0.00593551f,0.246837f,-0.088434f},{0.0100134f,0.242028f,-0.0937354f},{0.0184855f,0.232039f,-0.103643f}, -{0.0228632f,0.226877f,-0.108235f},{0.0273241f,0.221617f,-0.112578f},{0.0318592f,0.216269f,-0.116668f}, -{0.0458206f,0.199807f,-0.127378f},{0.0456623f,0.199993f,-0.127941f},{0.0504174f,0.194386f,-0.130993f}, -{0.0505635f,0.194214f,-0.130423f},{0.0553362f,0.188587f,-0.133204f},{0.0601299f,0.182934f,-0.135723f}, -{0.0649361f,0.177267f,-0.137981f},{0.0697467f,0.171595f,-0.139981f},{0.0745535f,0.165927f,-0.141725f}, -{0.0793489f,0.160272f,-0.143219f},{0.0841253f,0.15464f,-0.144466f},{0.102907f,0.132495f,-0.147106f}, -{-0.0469308f,0.309173f,0.0703531f},{-0.0464308f,0.308584f,0.0630404f},{-0.0472824f,0.309588f,0.0776054f}, -{-0.0457783f,0.307814f,0.055677f},{-0.0428696f,0.304385f,0.0333897f},{-0.0415729f,0.302856f,0.0259331f}, -{-0.0401088f,0.301129f,0.0184831f},{-0.0402491f,0.301674f,0.0183202f},{-0.0386121f,0.299744f,0.0108731f}, -{-0.0384754f,0.299203f,0.0110526f},{-0.0366719f,0.297077f,0.00365461f},{-0.0346974f,0.294749f,-0.00369726f}, -{-0.0325522f,0.292219f,-0.0109894f},{-0.0302367f,0.289489f,-0.0182079f},{-0.0222846f,0.280112f,-0.0392827f}, -{-0.0223853f,0.280611f,-0.0395738f},{-0.019401f,0.277092f,-0.0463744f},{-0.0193069f,0.276601f,-0.0460682f}, -{-0.0161713f,0.272904f,-0.0527117f},{-0.0128823f,0.269025f,-0.0592001f},{-0.00214587f,0.256366f,-0.0776124f}, -{-0.00220193f,0.256811f,-0.0779886f},{0.00165512f,0.252264f,-0.0837496f},{0.00170264f,0.251828f,-0.0833607f}, -{0.00567477f,0.247144f,-0.088897f},{0.00976312f,0.242323f,-0.094212f},{0.022646f,0.227133f,-0.108749f}, -{0.0226449f,0.227514f,-0.109195f},{0.0271272f,0.222229f,-0.113558f},{0.0271182f,0.221859f,-0.113103f}, -{0.031665f,0.216498f,-0.117203f},{0.0362772f,0.21106f,-0.121044f},{0.0409459f,0.205555f,-0.124624f}, -{0.0552022f,0.188744f,-0.133782f},{0.0600083f,0.183077f,-0.136307f},{0.0600902f,0.183361f,-0.136814f}, -{0.0649195f,0.177666f,-0.139083f},{0.0648269f,0.177396f,-0.138571f},{0.0696498f,0.171709f,-0.140576f}, -{0.0744689f,0.166026f,-0.142325f},{0.0792766f,0.160357f,-0.143823f},{0.0840654f,0.154711f,-0.145073f}, -{0.0888281f,0.149095f,-0.146082f},{-0.0470862f,0.309736f,0.0703053f},{-0.0465851f,0.309145f,0.0629764f}, -{-0.0474386f,0.310152f,0.0775737f},{-0.0459312f,0.308374f,0.0555966f},{-0.0451206f,0.307418f,0.0481766f}, -{-0.0441499f,0.306274f,0.0407271f},{-0.043016f,0.304937f,0.0332599f},{-0.0417165f,0.303405f,0.0257867f}, -{-0.0368045f,0.297613f,0.00345877f},{-0.0347426f,0.295769f,-0.00404829f},{-0.0348257f,0.295279f,-0.00390942f}, -{-0.0326757f,0.292744f,-0.0112177f},{-0.0303551f,0.290008f,-0.0184523f},{-0.0278652f,0.287072f,-0.0255992f}, -{-0.0252078f,0.283939f,-0.0326442f},{-0.0161484f,0.273844f,-0.0532427f},{-0.0162585f,0.273386f,-0.0530326f}, -{-0.0129621f,0.269499f,-0.0595354f},{-0.00951684f,0.265437f,-0.0658703f},{-0.00592809f,0.261205f,-0.0720252f}, -{0.0057779f,0.24799f,-0.0895609f},{0.00563608f,0.247569f,-0.0892982f},{0.00973349f,0.242738f,-0.0946251f}, -{0.0139396f,0.237778f,-0.0997217f},{0.0182462f,0.2327f,-0.10458f},{0.0318636f,0.217231f,-0.117971f}, -{0.031684f,0.216855f,-0.117667f},{0.0363064f,0.211405f,-0.121517f},{0.0409855f,0.205888f,-0.125105f}, -{0.0457124f,0.200314f,-0.128429f},{0.050478f,0.194695f,-0.131488f},{0.0552735f,0.18904f,-0.134283f}, -{0.0697531f,0.171967f,-0.141092f},{0.0748247f,0.166574f,-0.143185f},{0.0745829f,0.166272f,-0.142845f}, -{0.0794013f,0.16059f,-0.144346f},{0.0842006f,0.154931f,-0.145599f},{0.0889739f,0.149303f,-0.14661f}, -{0.0984157f,0.13817f,-0.147929f},{-0.0476338f,0.311036f,0.0918925f},{-0.0470208f,0.310247f,0.070274f}, -{-0.046519f,0.309655f,0.0629344f},{-0.0458641f,0.308883f,0.055544f},{-0.0450523f,0.307925f,0.0481132f}, -{-0.0440802f,0.306779f,0.040653f},{-0.0429447f,0.30544f,0.0331749f},{-0.0416433f,0.303906f,0.0256909f}, -{-0.0401738f,0.302173f,0.0182135f},{-0.0385344f,0.30024f,0.0107557f},{-0.0367242f,0.298105f,0.00333058f}, -{-0.0323867f,0.293601f,-0.0114393f},{-0.0300372f,0.291363f,-0.0180677f},{-0.0300611f,0.290859f,-0.0186894f}, -{-0.0325894f,0.29323f,-0.0113672f},{-0.0302655f,0.29049f,-0.0186123f},{-0.0277719f,0.287549f,-0.0257695f}, -{-0.0251106f,0.284411f,-0.0328247f},{-0.0222841f,0.281079f,-0.0397644f},{-0.0192955f,0.277555f,-0.0465748f}, -{-0.0128473f,0.269951f,-0.0597549f},{-0.0126308f,0.270306f,-0.0598609f},{-0.00939697f,0.265883f,-0.066099f}, -{-0.00580302f,0.261645f,-0.0722628f},{-0.00207146f,0.257245f,-0.0782348f},{0.00179119f,0.25269f,-0.0840042f}, -{0.0101136f,0.243487f,-0.0950259f},{0.0140191f,0.239414f,-0.0995152f},{0.0143288f,0.238517f,-0.100133f}, -{0.00988127f,0.243151f,-0.0948954f},{0.0140934f,0.238184f,-0.0999994f},{0.0184063f,0.233099f,-0.104865f}, -{0.0228114f,0.227905f,-0.109486f},{0.0273001f,0.222612f,-0.113856f},{0.0364927f,0.211773f,-0.121826f}, -{0.0414329f,0.206557f,-0.125571f},{0.0411786f,0.206247f,-0.125419f},{0.0459123f,0.200666f,-0.128748f}, -{0.0506848f,0.195038f,-0.131812f},{0.0554873f,0.189375f,-0.134611f},{0.0603109f,0.183688f,-0.137145f}, -{0.0651472f,0.177985f,-0.139417f},{0.0699878f,0.172277f,-0.14143f},{0.07965f,0.160884f,-0.144688f}, -{0.0844564f,0.155217f,-0.145943f},{0.0892366f,0.14958f,-0.146956f},{-0.0468282f,0.310629f,0.0702589f}, -{-0.046326f,0.310037f,0.0629142f},{-0.0456706f,0.309264f,0.0555186f},{-0.0448583f,0.308307f,0.0480826f}, -{-0.0438855f,0.30716f,0.0406172f},{-0.0427492f,0.30582f,0.0331338f},{-0.0414469f,0.304284f,0.0256447f}, -{-0.0399763f,0.30255f,0.0181621f},{-0.0383359f,0.300616f,0.010699f},{-0.0365244f,0.29848f,0.00326873f}, -{-0.0345413f,0.296141f,-0.0041153f},{-0.0275658f,0.287916f,-0.0258517f},{-0.0249027f,0.284776f,-0.0329118f}, -{-0.0220742f,0.281441f,-0.0398563f},{-0.0190835f,0.277915f,-0.0466715f},{-0.0159342f,0.274201f,-0.0533441f}, -{-0.0152712f,0.273952f,-0.0542301f},{-0.00917805f,0.266235f,-0.0662094f},{-0.00558159f,0.261994f,-0.0723775f}, -{-0.00184742f,0.257591f,-0.0783537f},{0.00201793f,0.253033f,-0.0841271f},{0.00600743f,0.248329f,-0.0896876f}, -{0.0186446f,0.233428f,-0.105003f},{0.0230528f,0.22823f,-0.109627f},{0.0275447f,0.222934f,-0.114f}, -{0.0321114f,0.217549f,-0.118117f},{0.0367437f,0.212087f,-0.121975f},{0.0374089f,0.211834f,-0.122344f}, -{0.0461698f,0.200972f,-0.128902f},{0.0509457f,0.195341f,-0.131968f},{0.0557515f,0.189674f,-0.134769f}, -{0.0605785f,0.183982f,-0.137305f},{0.0654182f,0.178275f,-0.139579f},{0.0702622f,0.172564f,-0.141593f}, -{0.0751025f,0.166856f,-0.143349f},{0.0799311f,0.161163f,-0.144853f},{0.0847408f,0.155491f,-0.146109f}, -{0.0895244f,0.149851f,-0.147123f},{0.094275f,0.144249f,-0.147899f},{0.0989864f,0.138694f,-0.148445f}, -{-0.0466084f,0.310902f,0.0705096f},{-0.0461304f,0.310339f,0.0634113f},{-0.0455166f,0.309615f,0.056338f}, -{-0.0447675f,0.308732f,0.0492957f},{-0.0438837f,0.30769f,0.042291f},{-0.0428661f,0.30649f,0.0353299f}, -{-0.0417155f,0.305133f,0.0284186f},{-0.0404329f,0.303621f,0.0215629f},{-0.0390195f,0.301954f,0.0147688f}, -{-0.0374764f,0.300135f,0.00804257f},{-0.0358052f,0.298164f,0.00139006f},{-0.0340072f,0.296044f,-0.00518291f}, -{-0.032084f,0.293776f,-0.0116708f},{-0.0278688f,0.288806f,-0.024368f},{-0.0255805f,0.286108f,-0.0305661f}, -{-0.0231746f,0.283271f,-0.0366566f},{-0.0206528f,0.280297f,-0.0426344f},{-0.0180176f,0.27719f,-0.0484939f}, -{-0.0124162f,0.270585f,-0.0598379f},{-0.00945494f,0.267093f,-0.0653124f},{-0.00638994f,0.263479f,-0.0706491f}, -{-0.00322406f,0.259746f,-0.0758429f},{3.99566e-005f,0.255898f,-0.0808893f},{0.00339924f,0.251936f,-0.0857839f}, -{0.00685086f,0.247867f,-0.0905225f},{0.0103919f,0.243691f,-0.095101f},{0.0177293f,0.235039f,-0.103761f}, -{0.0215192f,0.230571f,-0.107835f},{0.0253855f,0.226012f,-0.111734f},{0.029325f,0.221366f,-0.115454f}, -{0.0333339f,0.216639f,-0.118992f},{0.0415463f,0.206956f,-0.125509f},{0.0457426f,0.202008f,-0.128482f}, -{0.0499941f,0.196995f,-0.131262f},{0.054297f,0.191921f,-0.133846f},{0.0586474f,0.186791f,-0.136231f}, -{0.0630417f,0.18161f,-0.138417f},{0.067476f,0.176381f,-0.1404f},{0.0719463f,0.17111f,-0.142179f}, -{0.0764488f,0.165801f,-0.143752f},{0.0809793f,0.160459f,-0.145118f},{0.0855341f,0.155088f,-0.146276f}, -{0.0901092f,0.149694f,-0.147225f},{0.0947004f,0.14428f,-0.147964f},{0.0993037f,0.138852f,-0.148493f}, -{-0.0215492f,0.281886f,-0.0398563f},{-0.0185585f,0.27836f,-0.0466715f},{-0.0108014f,0.27079f,-0.0592001f}, -{-0.00781054f,0.266884f,-0.0658703f},{-0.0112558f,0.270946f,-0.0595354f},{-0.0270408f,0.288362f,-0.0258517f}, -{-0.0243777f,0.285221f,-0.0329118f},{-0.0318617f,0.294046f,-0.0114393f},{-0.0295361f,0.291304f,-0.0186894f}, -{-0.0340163f,0.296587f,-0.0041153f},{-0.0359994f,0.298925f,0.00326873f},{-0.0378109f,0.301061f,0.010699f}, -{-0.0309694f,0.294191f,-0.0112177f},{-0.0314626f,0.294186f,-0.0113672f},{-0.0331194f,0.296727f,-0.00390942f}, -{-0.0394513f,0.302995f,0.0181621f},{-0.0409219f,0.304729f,0.0256447f},{-0.0422242f,0.306265f,0.0331338f}, -{-0.0433605f,0.307605f,0.0406172f},{-0.0443333f,0.308752f,0.0480826f},{-0.0451456f,0.30971f,0.0555186f}, -{-0.045801f,0.310482f,0.0629142f},{-0.0463032f,0.311075f,0.0702589f},{-0.045894f,0.311202f,0.070274f}, -{-0.0453922f,0.31061f,0.0629344f},{-0.0451123f,0.30967f,0.0848373f},{-0.0449201f,0.310054f,0.0848323f}, -{-0.0448555f,0.310565f,0.084822f},{-0.0449255f,0.310447f,0.0918925f},{-0.0451675f,0.309769f,0.0918925f}, -{-0.0449062f,0.309427f,0.0777045f},{-0.0445571f,0.309016f,0.0705025f},{-0.0443644f,0.309399f,0.0704874f}, -{-0.0453799f,0.311183f,0.0703053f},{-0.0448788f,0.310592f,0.0629764f},{-0.0443499f,0.310348f,0.0630404f}, -{-0.0442249f,0.309821f,0.0555966f},{-0.0448499f,0.310938f,0.0703531f},{-0.0466563f,0.311491f,0.0775429f}, -{-0.0462046f,0.311955f,0.0918925f},{-0.0459403f,0.311844f,0.0847723f},{-0.0464552f,0.311864f,0.084762f}, -{-0.045844f,0.311876f,0.0918925f},{-0.0454091f,0.311597f,0.084788f},{-0.0455195f,0.311707f,0.0918925f}, -{-0.046564f,0.311937f,0.0918925f},{-0.0468648f,0.311737f,0.084757f},{-0.0469128f,0.311827f,0.0918925f}, -{-0.0450122f,0.311129f,0.0848062f},{-0.0449434f,0.310806f,0.0918925f},{-0.0154092f,0.274646f,-0.0533441f}, -{-0.0121057f,0.270751f,-0.0598609f},{-0.00865303f,0.26668f,-0.0662094f},{-0.00505658f,0.262439f,-0.0723775f}, -{-0.00132241f,0.258036f,-0.0783537f},{0.00254294f,0.253478f,-0.0841271f},{0.0110081f,0.244107f,-0.0948954f}, -{0.00734237f,0.249017f,-0.0892982f},{0.0114398f,0.244185f,-0.0946251f},{0.00653244f,0.248774f,-0.0896876f}, -{0.0106387f,0.243932f,-0.0950259f},{0.0148538f,0.238962f,-0.100133f},{0.0191697f,0.233873f,-0.105003f}, -{0.0235778f,0.228675f,-0.109627f},{0.0280697f,0.223379f,-0.114f},{0.0326364f,0.217994f,-0.118117f}, -{0.0426918f,0.207335f,-0.125105f},{0.0430268f,0.207319f,-0.124624f},{0.0474187f,0.201761f,-0.128429f}, -{0.0372687f,0.212532f,-0.121975f},{0.0419579f,0.207003f,-0.125571f},{0.0466949f,0.201417f,-0.128902f}, -{0.0514707f,0.195786f,-0.131968f},{0.0562765f,0.190119f,-0.134769f},{0.0611035f,0.184427f,-0.137305f}, -{0.0659432f,0.178721f,-0.139579f},{0.0707872f,0.173009f,-0.141593f},{0.0759515f,0.16753f,-0.143185f}, -{0.0756275f,0.167302f,-0.143349f},{0.0711147f,0.173233f,-0.14143f},{0.0804562f,0.161608f,-0.144853f}, -{0.0900494f,0.150296f,-0.147123f},{0.0855832f,0.156172f,-0.145943f},{0.0903634f,0.150536f,-0.146956f}, -{0.0956389f,0.145282f,-0.146855f},{0.0956746f,0.14524f,-0.146244f},{0.10033f,0.139751f,-0.147398f}, -{0.0813575f,0.162122f,-0.143823f},{0.0861462f,0.156476f,-0.145073f},{0.0859069f,0.156378f,-0.145599f}, -{0.0952487f,0.144775f,-0.145367f},{0.0955182f,0.145045f,-0.145714f},{0.0905482f,0.150318f,-0.144599f}, -{0.104527f,0.133835f,-0.146226f},{0.109238f,0.128572f,-0.146474f},{0.10481f,0.134088f,-0.146574f}, -{0.100122f,0.139617f,-0.147929f},{0.0954207f,0.14516f,-0.147385f},{0.10902f,0.128388f,-0.146297f}, -{0.10423f,0.133576f,-0.146058f},{0.108787f,0.12819f,-0.146158f},{0.0906802f,0.15075f,-0.14661f}, -{0.0909089f,0.15086f,-0.146082f},{0.0998188f,0.139387f,-0.148277f},{0.0951107f,0.144938f,-0.147732f}, -{0.0852658f,0.155937f,-0.146109f},{0.0948f,0.144695f,-0.147899f},{0.0995114f,0.139139f,-0.148445f}, -{0.104178f,0.133637f,-0.148767f},{0.108786f,0.128189f,-0.148876f},{-0.0450535f,0.311155f,0.0918925f}, -{-0.0462469f,0.311618f,0.0775529f},{-0.0447373f,0.309838f,0.055544f},{-0.0439255f,0.308881f,0.0481132f}, -{-0.0429534f,0.307735f,0.040653f},{-0.0418179f,0.306396f,0.0331749f},{-0.0405165f,0.304861f,0.0256909f}, -{-0.039047f,0.303129f,0.0182135f},{-0.0374076f,0.301196f,0.0107557f},{-0.0355974f,0.299061f,0.00333058f}, -{-0.0336158f,0.296724f,-0.00404829f},{-0.0291387f,0.291445f,-0.0186123f},{-0.0266451f,0.288505f,-0.0257695f}, -{-0.0239838f,0.285367f,-0.0328247f},{-0.0211573f,0.282034f,-0.0397644f},{-0.0181687f,0.27851f,-0.0465748f}, -{-0.0150216f,0.274799f,-0.0532427f},{-0.0117205f,0.270907f,-0.0597549f},{-0.00827017f,0.266838f,-0.066099f}, -{-0.00467622f,0.262601f,-0.0722628f},{-0.000944657f,0.258201f,-0.0782348f},{0.00291799f,0.253646f,-0.0840042f}, -{0.0069047f,0.248945f,-0.0895609f},{0.0152202f,0.23914f,-0.0999994f},{0.0195331f,0.234055f,-0.104865f}, -{0.0239382f,0.22886f,-0.109486f},{0.0284269f,0.223568f,-0.113856f},{0.0329904f,0.218187f,-0.117971f}, -{0.0376195f,0.212728f,-0.121826f},{0.0423054f,0.207203f,-0.125419f},{0.0470391f,0.201621f,-0.128748f}, -{0.0518116f,0.195994f,-0.131812f},{0.0566141f,0.190331f,-0.134611f},{0.0614377f,0.184643f,-0.137145f}, -{0.066274f,0.178941f,-0.139417f},{0.0807768f,0.16184f,-0.144688f},{0.0811076f,0.162037f,-0.144346f}, -{0.104482f,0.133888f,-0.148599f},{0.109024f,0.128391f,-0.148751f},{-0.0457323f,0.311599f,0.0775737f}, -{-0.0434143f,0.308866f,0.0481766f},{-0.0424436f,0.307721f,0.0407271f},{-0.0413097f,0.306384f,0.0332599f}, -{-0.0400102f,0.304852f,0.0257867f},{-0.0385428f,0.303121f,0.0183202f},{-0.0369058f,0.301191f,0.0108731f}, -{-0.0350982f,0.29906f,0.00345877f},{-0.0261589f,0.288519f,-0.0255992f},{-0.0286488f,0.291455f,-0.0184523f}, -{-0.0281559f,0.291253f,-0.0182079f},{-0.0235015f,0.285386f,-0.0326442f},{-0.020679f,0.282058f,-0.0395738f}, -{-0.0176947f,0.278539f,-0.0463744f},{-0.0145522f,0.274833f,-0.0530326f},{-0.0042218f,0.262652f,-0.0720252f}, -{-0.000495634f,0.258259f,-0.0779886f},{0.00336142f,0.253711f,-0.0837496f},{0.0203378f,0.234073f,-0.104145f}, -{0.0205663f,0.233803f,-0.103643f},{0.0247268f,0.228898f,-0.108749f},{0.0156459f,0.239226f,-0.0997217f}, -{0.0199525f,0.234147f,-0.10458f},{0.0243512f,0.228961f,-0.109195f},{0.0288334f,0.223676f,-0.113558f}, -{0.0333903f,0.218302f,-0.117667f},{0.0380127f,0.212852f,-0.121517f},{0.0521843f,0.196142f,-0.131488f}, -{0.0569798f,0.190487f,-0.134283f},{0.0617965f,0.184808f,-0.136814f},{0.0666258f,0.179113f,-0.139083f}, -{0.0714594f,0.173414f,-0.141092f},{0.0762892f,0.167719f,-0.142845f},{0.109589f,0.12887f,-0.147687f}, -{0.104976f,0.134273f,-0.147719f},{0.104987f,0.134259f,-0.147106f},{0.104778f,0.134126f,-0.148251f}, -{0.109234f,0.128569f,-0.148558f},{-0.0452527f,0.311466f,0.0918925f},{-0.0452015f,0.311353f,0.0776054f}, -{-0.0436974f,0.309579f,0.055677f},{-0.0428886f,0.308625f,0.0482734f},{-0.0404037f,0.305695f,0.0335395f}, -{-0.0394921f,0.30462f,0.0259331f},{-0.0407888f,0.306149f,0.0333897f},{-0.0419201f,0.307483f,0.0408405f}, -{-0.0380279f,0.302894f,0.0184831f},{-0.0363946f,0.300968f,0.0110526f},{-0.034591f,0.298841f,0.00365461f}, -{-0.0326166f,0.296513f,-0.00369726f},{-0.0304713f,0.293984f,-0.0109894f},{-0.0226804f,0.284797f,-0.0320502f}, -{-0.0202037f,0.281877f,-0.0392827f},{-0.0230199f,0.285197f,-0.0323684f},{-0.0256714f,0.288324f,-0.025339f}, -{-0.017226f,0.278366f,-0.0460682f},{-0.0140905f,0.274668f,-0.0527117f},{-0.00349265f,0.262172f,-0.0712434f}, -{-6.50204e-005f,0.25813f,-0.0776124f},{-0.00378294f,0.262514f,-0.0716622f},{-0.00736374f,0.266737f,-0.065521f}, -{0.00378349f,0.253593f,-0.0833607f},{0.00775562f,0.248909f,-0.088897f},{0.011844f,0.244088f,-0.094212f}, -{0.0160407f,0.23914f,-0.0992973f},{0.0291991f,0.223624f,-0.113103f},{0.0337459f,0.218263f,-0.117203f}, -{0.0383581f,0.212824f,-0.121044f},{0.0526444f,0.195979f,-0.130423f},{0.0572831f,0.190509f,-0.133782f}, -{0.0524982f,0.196151f,-0.130993f},{0.0477432f,0.201758f,-0.127941f},{0.0620891f,0.184842f,-0.136307f}, -{0.0669077f,0.17916f,-0.138571f},{0.0717306f,0.173474f,-0.140576f},{0.0765498f,0.167791f,-0.142325f}, -{0.100187f,0.13954f,-0.146255f},{0.0909567f,0.150803f,-0.145472f},{0.109527f,0.128818f,-0.148015f}, -{0.109406f,0.128715f,-0.14831f},{-0.0444545f,0.310472f,0.0704083f},{-0.0448052f,0.310885f,0.077642f}, -{-0.0439558f,0.309884f,0.0631143f},{-0.0433049f,0.309116f,0.0557698f},{-0.0424982f,0.308165f,0.0483851f}, -{-0.0415321f,0.307026f,0.0409712f},{-0.0391104f,0.30417f,0.026102f},{-0.0342218f,0.298406f,0.00388058f}, -{-0.0360208f,0.300527f,0.0112596f},{-0.0358841f,0.299986f,0.011439f},{-0.0376499f,0.302448f,0.0186711f}, -{-0.0322525f,0.296084f,-0.00345247f},{-0.0301127f,0.293561f,-0.0107259f},{-0.0278032f,0.290838f,-0.017926f}, -{-0.0253251f,0.287916f,-0.0250388f},{-0.0137967f,0.273355f,-0.0518103f},{-0.0136866f,0.273813f,-0.0520204f}, -{-0.0169127f,0.277029f,-0.0452083f},{-0.0198714f,0.281485f,-0.0389468f},{-0.0169013f,0.277983f,-0.0457149f}, -{-0.0137738f,0.274295f,-0.0523413f},{-0.0104931f,0.270427f,-0.0588132f},{-0.00706428f,0.266384f,-0.0651178f}, -{0.00791323f,0.247756f,-0.0877701f},{0.00805506f,0.248176f,-0.0880327f},{0.00396585f,0.252411f,-0.0822683f}, -{0.000215743f,0.257799f,-0.0771783f},{0.0040544f,0.253273f,-0.0829118f},{0.00801636f,0.248601f,-0.088434f}, -{0.0120942f,0.243793f,-0.0937354f},{0.0162803f,0.238857f,-0.0988077f},{0.0339401f,0.218034f,-0.116668f}, -{0.0294049f,0.223381f,-0.112578f},{0.029396f,0.223012f,-0.112123f},{0.0249441f,0.228641f,-0.108235f}, -{0.0385404f,0.212609f,-0.120499f},{0.0431972f,0.207118f,-0.12407f},{0.0479015f,0.201571f,-0.127378f}, -{0.057417f,0.190351f,-0.133204f},{0.0718275f,0.173359f,-0.139981f},{0.067017f,0.179032f,-0.137981f}, -{0.0669244f,0.178761f,-0.137469f},{0.0622107f,0.184699f,-0.135723f},{0.0766344f,0.167691f,-0.141725f}, -{0.0814297f,0.162037f,-0.143219f},{0.0862062f,0.156405f,-0.144466f},{0.0908109f,0.150596f,-0.144944f}, -{0.100353f,0.139723f,-0.146786f},{-0.044299f,0.309909f,0.0704561f},{-0.0446489f,0.310321f,0.0776737f}, -{-0.0438014f,0.309322f,0.0631783f},{-0.043152f,0.308556f,0.0558501f},{-0.0423471f,0.307607f,0.0484819f}, -{-0.0413832f,0.306471f,0.0410845f},{-0.0402573f,0.305143f,0.0336694f},{-0.0389668f,0.303621f,0.0262484f}, -{-0.0375096f,0.301903f,0.018834f},{-0.0341694f,0.297377f,0.00420461f},{-0.0322073f,0.295064f,-0.00310144f}, -{-0.0321242f,0.295553f,-0.00324031f},{-0.0340891f,0.29787f,0.00407642f},{-0.0299892f,0.293036f,-0.0104976f}, -{-0.0276848f,0.290318f,-0.0176816f},{-0.0252122f,0.287403f,-0.0247786f},{-0.0225734f,0.284291f,-0.0317744f}, -{-0.0197706f,0.280986f,-0.0386556f},{-0.0168072f,0.277492f,-0.0454087f},{-0.0104133f,0.269953f,-0.0584778f}, -{-0.00699203f,0.265919f,-0.0647685f},{-0.00342834f,0.261717f,-0.0708804f},{0.000271795f,0.257354f,-0.0768021f}, -{0.00410191f,0.252837f,-0.0825229f},{0.0121239f,0.243378f,-0.0933224f},{0.0163006f,0.238454f,-0.0983834f}, -{0.0205771f,0.233411f,-0.103208f},{0.0249451f,0.22826f,-0.10779f},{0.0337415f,0.217301f,-0.1159f}, -{0.0383249f,0.211896f,-0.119717f},{0.0385112f,0.212264f,-0.120026f},{0.0339211f,0.217677f,-0.116203f}, -{0.0431576f,0.206785f,-0.123589f},{0.0478514f,0.201251f,-0.12689f},{0.0525838f,0.195671f,-0.129928f}, -{0.0573458f,0.190056f,-0.132703f},{0.0621288f,0.184416f,-0.135216f},{0.0717242f,0.173101f,-0.139465f}, -{0.0762786f,0.167144f,-0.140865f},{0.0810563f,0.16151f,-0.142353f},{0.0813051f,0.161804f,-0.142696f}, -{0.0765204f,0.167446f,-0.141206f},{0.0860709f,0.156185f,-0.14394f},{0.109528f,0.128818f,-0.147023f}, -{0.109589f,0.12887f,-0.147351f},{-0.0450044f,0.310086f,0.0918925f},{-0.0447138f,0.309811f,0.0776945f}, -{-0.0438675f,0.308813f,0.0632202f},{-0.0432191f,0.308048f,0.0559028f},{-0.0440605f,0.30843f,0.0632405f}, -{-0.0424153f,0.3071f,0.0485453f},{-0.0414528f,0.305965f,0.0411587f},{-0.0403286f,0.30464f,0.0337544f}, -{-0.03904f,0.30312f,0.0263442f},{-0.0375849f,0.301405f,0.0189407f},{-0.0359618f,0.299491f,0.0115564f}, -{-0.0279788f,0.289468f,-0.0174445f},{-0.0302782f,0.292179f,-0.010276f},{-0.0300755f,0.29255f,-0.0103481f}, -{-0.0277744f,0.289837f,-0.0175217f},{-0.0253055f,0.286925f,-0.0246083f},{-0.0226705f,0.283818f,-0.0315939f}, -{-0.0198719f,0.280518f,-0.038465f},{-0.0107446f,0.269146f,-0.0581524f},{-0.0105281f,0.269501f,-0.0582583f}, -{-0.0140109f,0.272998f,-0.051709f},{-0.00711189f,0.265473f,-0.0645398f},{-0.00355341f,0.261277f,-0.0706427f}, -{0.00014133f,0.25692f,-0.0765558f},{0.0117437f,0.242629f,-0.0929216f},{0.0159114f,0.237715f,-0.0979716f}, -{0.0119761f,0.242965f,-0.093052f},{0.0161467f,0.238048f,-0.0981056f},{0.020417f,0.233012f,-0.102923f}, -{0.0247786f,0.227869f,-0.107499f},{0.029223f,0.222629f,-0.111826f},{0.0427103f,0.206115f,-0.123123f}, -{0.0429646f,0.206426f,-0.123274f},{0.0380739f,0.211582f,-0.119568f},{0.0476515f,0.200899f,-0.126571f}, -{0.0523769f,0.195327f,-0.129604f},{0.057132f,0.18972f,-0.132375f},{0.061908f,0.184089f,-0.134885f}, -{0.0666966f,0.178442f,-0.137135f},{0.0714895f,0.172791f,-0.139127f},{0.0858152f,0.155899f,-0.143596f}, -{0.0996159f,0.139016f,-0.145739f},{0.0949576f,0.144509f,-0.145199f},{0.0999103f,0.139279f,-0.145907f}, -{0.109409f,0.128718f,-0.146724f},{-0.0434125f,0.307666f,0.0559281f},{-0.0426093f,0.306719f,0.0485758f}, -{-0.0416475f,0.305585f,0.0411945f},{-0.0405241f,0.30426f,0.0337954f},{-0.0392364f,0.302742f,0.0263905f}, -{-0.0377824f,0.301027f,0.0189921f},{-0.0361604f,0.299115f,0.0116131f},{-0.0343693f,0.297003f,0.00426646f}, -{-0.0324086f,0.294691f,-0.00303443f},{-0.0255116f,0.286558f,-0.0245261f},{-0.0228784f,0.283454f,-0.0315068f}, -{-0.0200818f,0.280156f,-0.0383731f},{-0.0171247f,0.276669f,-0.0451116f},{-0.00733081f,0.265121f,-0.0644294f}, -{-0.00377484f,0.260928f,-0.0705281f},{-8.27133e-005f,0.256574f,-0.076437f},{0.00373911f,0.252068f,-0.0821454f}, -{0.00768371f,0.247417f,-0.0876434f},{0.0201786f,0.232683f,-0.102786f},{0.0245372f,0.227544f,-0.107358f}, -{0.0289785f,0.222307f,-0.111682f},{0.0334938f,0.216983f,-0.115753f},{0.047394f,0.200593f,-0.126416f}, -{0.052116f,0.195025f,-0.129448f},{0.0568677f,0.189422f,-0.132217f},{0.0616404f,0.183794f,-0.134725f}, -{0.0664256f,0.178152f,-0.136973f},{0.0712151f,0.172504f,-0.138964f},{0.0760009f,0.166861f,-0.140701f}, -{0.0807752f,0.161232f,-0.142188f},{0.0855307f,0.155624f,-0.14343f},{0.0902604f,0.150047f,-0.144432f}, -{0.211424f,0.00837609f,-0.0892991f},{0.207327f,0.0132075f,-0.0946258f},{0.207297f,0.0136221f,-0.0942128f}, -{0.189516f,0.0330114f,-0.114f},{0.194008f,0.0277151f,-0.109627f},{0.18495f,0.0383959f,-0.118117f}, -{0.180317f,0.0438583f,-0.121975f},{0.175628f,0.0493877f,-0.125571f},{0.170891f,0.0549734f,-0.128902f}, -{0.166115f,0.0606049f,-0.131968f},{0.161309f,0.0662717f,-0.134769f},{0.175882f,0.0496979f,-0.125419f}, -{0.171348f,0.0556313f,-0.128429f},{0.176075f,0.0500576f,-0.125105f},{0.156482f,0.0719635f,-0.137305f}, -{0.151642f,0.0776702f,-0.139579f},{0.146798f,0.0833819f,-0.141592f},{0.137129f,0.0947828f,-0.144853f}, -{0.141958f,0.0890892f,-0.143349f},{0.132319f,0.100454f,-0.146109f},{0.127536f,0.106094f,-0.147122f}, -{0.122786f,0.111696f,-0.147899f},{0.113356f,0.122814f,-0.146057f},{0.123077f,0.111963f,-0.147731f}, -{0.127824f,0.106365f,-0.146955f},{0.122628f,0.111882f,-0.145199f},{0.122939f,0.112125f,-0.145366f}, -{0.11797f,0.117374f,-0.145739f},{0.128232f,0.10685f,-0.146081f},{0.13286f,0.101014f,-0.145599f}, -{0.128086f,0.106643f,-0.14661f},{0.113957f,0.123303f,-0.146574f},{0.114154f,0.12345f,-0.147105f}, -{0.11366f,0.123066f,-0.146225f},{0.123346f,0.112232f,-0.147384f},{0.114166f,0.123436f,-0.147719f}, -{0.113408f,0.122753f,-0.148767f},{0.113706f,0.123012f,-0.148599f},{0.118074f,0.117251f,-0.148445f}, -{0.113989f,0.123266f,-0.148251f},{0.123502f,0.112427f,-0.146855f},{0.198416f,0.0225174f,-0.105003f}, -{0.202732f,0.0174285f,-0.100134f},{0.206947f,0.0124584f,-0.0950266f},{0.211053f,0.00761661f,-0.0896885f}, -{0.215042f,0.00291244f,-0.0841281f},{0.218908f,-0.00164537f,-0.0783547f},{0.222642f,-0.00604854f,-0.0723786f}, -{0.229908f,-0.014006f,-0.059756f},{0.226577f,-0.00949148f,-0.0658715f},{0.230023f,-0.0135541f,-0.0595366f}, -{0.226238f,-0.0102893f,-0.0662105f},{0.229691f,-0.0143607f,-0.059862f},{0.232995f,-0.018256f,-0.053345f}, -{0.236144f,-0.0219695f,-0.0466724f},{0.239135f,-0.0254962f,-0.039857f},{0.241964f,-0.0288315f,-0.0329122f}, -{0.244627f,-0.0319717f,-0.0258517f},{0.249737f,-0.0367996f,-0.0112184f},{0.249613f,-0.0362743f,-0.01099f}, -{0.251887f,-0.0393348f,-0.00391029f},{0.247122f,-0.034914f,-0.0186898f},{0.249448f,-0.0376562f,-0.0114399f}, -{0.251602f,-0.0401968f,-0.00411618f},{0.253585f,-0.0425352f,0.00326766f},{0.255397f,-0.0446712f,0.0106978f}, -{0.257037f,-0.0466056f,0.0181608f},{0.258508f,-0.0483397f,0.0256434f},{0.25981f,-0.0498754f,0.0331326f}, -{0.261141f,-0.0508348f,0.0406518f},{0.260947f,-0.0512152f,0.040616f},{0.260006f,-0.0494959f,0.0331736f}, -{0.26192f,-0.0523623f,0.0480815f},{0.264708f,-0.0544525f,0.0847721f},{0.264344f,-0.0536435f,0.077605f}, -{0.264551f,-0.0538881f,0.0847878f},{0.263067f,-0.0525174f,0.0704555f},{0.263597f,-0.0527627f,0.0704077f}, -{0.262569f,-0.0519307f,0.0631775f},{0.262925f,-0.0529383f,0.0555431f},{0.26358f,-0.0537105f,0.0629336f}, -{0.263387f,-0.0540929f,0.0629134f},{0.262552f,-0.0524986f,0.0704868f},{0.262056f,-0.0519127f,0.0632194f}, -{0.263108f,-0.0531536f,0.0848321f},{0.263495f,-0.053223f,0.0918925f},{0.263623f,-0.0531734f,0.0848218f}, -{0.263492f,-0.0526395f,0.0630396f},{0.264147f,-0.0537919f,0.0703047f},{0.263646f,-0.0532011f,0.0629755f}, -{0.262698f,-0.0532807f,0.0848371f},{0.263135f,-0.0532409f,0.0918925f},{0.262839f,-0.0518701f,0.0556761f}, -{0.262992f,-0.05243f,0.0555957f},{0.262031f,-0.0509164f,0.0482723f},{0.262786f,-0.053351f,0.0918925f}, -{0.262732f,-0.0533202f,0.0555177f},{0.264242f,-0.0551013f,0.0775425f},{0.263889f,-0.054685f,0.0702583f}, -{0.264082f,-0.0543022f,0.0702734f},{0.264451f,-0.055347f,0.0847568f},{0.118369f,0.117514f,-0.148277f}, -{0.132604f,0.100729f,-0.145943f},{0.13741f,0.0950613f,-0.144688f},{0.142235f,0.0893717f,-0.143185f}, -{0.147072f,0.0836684f,-0.141429f},{0.151913f,0.0779607f,-0.139417f},{0.156749f,0.072258f,-0.137145f}, -{0.161573f,0.0665701f,-0.134611f},{0.166375f,0.0609073f,-0.131812f},{0.171148f,0.0552797f,-0.128748f}, -{0.180568f,0.0441723f,-0.121826f},{0.185197f,0.0387137f,-0.117971f},{0.189761f,0.033333f,-0.113856f}, -{0.194249f,0.0280404f,-0.109486f},{0.198654f,0.0228463f,-0.104866f},{0.202967f,0.017761f,-0.1f}, -{0.207179f,0.0127943f,-0.0948962f},{0.211282f,0.00795595f,-0.0895618f},{0.215269f,0.00325506f,-0.0840052f}, -{0.219132f,-0.00129956f,-0.0782359f},{0.222863f,-0.00569967f,-0.072264f},{0.226457f,-0.00993752f,-0.0661002f}, -{0.233209f,-0.0178986f,-0.0532437f},{0.236356f,-0.0216096f,-0.0465757f},{0.239345f,-0.0251337f,-0.039765f}, -{0.242172f,-0.0284667f,-0.0328251f},{0.244833f,-0.0316048f,-0.0257695f},{0.247326f,-0.034545f,-0.0186126f}, -{0.24965f,-0.0372852f,-0.0113678f},{0.251803f,-0.0398241f,-0.00404916f},{0.253785f,-0.0421608f,0.00332952f}, -{0.255595f,-0.0442954f,0.0107545f},{0.257235f,-0.0462284f,0.0182123f},{0.258704f,-0.0479613f,0.0256896f}, -{0.262114f,-0.0519811f,0.0481121f},{0.262182f,-0.0514742f,0.0481755f},{0.264643f,-0.0549637f,0.0847617f}, -{0.264435f,-0.0547182f,0.0775525f},{0.264695f,-0.0550917f,0.0918925f},{0.264532f,-0.055409f,0.0918925f}, -{0.118645f,0.117775f,-0.147929f},{0.137659f,0.0953554f,-0.144345f},{0.142477f,0.089674f,-0.142845f}, -{0.147307f,0.083979f,-0.141092f},{0.152141f,0.0782795f,-0.139082f},{0.15697f,0.072585f,-0.136814f}, -{0.161787f,0.0669054f,-0.134283f},{0.166582f,0.0612508f,-0.131488f},{0.185377f,0.0390894f,-0.117667f}, -{0.180754f,0.04454f,-0.121517f},{0.180784f,0.0448852f,-0.121044f},{0.189934f,0.0337164f,-0.113559f}, -{0.194416f,0.0284315f,-0.109195f},{0.198814f,0.0232449f,-0.104581f},{0.203121f,0.0181669f,-0.0997223f}, -{0.215405f,0.00368201f,-0.0837506f},{0.219262f,-0.000866029f,-0.0779897f},{0.222988f,-0.00525976f,-0.0720263f}, -{0.236368f,-0.020656f,-0.046069f},{0.236043f,-0.0202731f,-0.0457157f},{0.239345f,-0.0241672f,-0.0392833f}, -{0.233319f,-0.017441f,-0.0530336f},{0.236462f,-0.0211466f,-0.0463752f},{0.239446f,-0.0246657f,-0.0395744f}, -{0.242269f,-0.0279938f,-0.0326445f},{0.244926f,-0.0311274f,-0.0255992f},{0.247416f,-0.0340633f,-0.0184526f}, -{0.253865f,-0.0416681f,0.00345771f},{0.255673f,-0.0437996f,0.0108719f},{0.25731f,-0.0457298f,0.0183189f}, -{0.258778f,-0.0474602f,0.0257854f},{0.260077f,-0.0489926f,0.0332586f},{0.261211f,-0.0503296f,0.0407259f}, -{0.2645f,-0.0542073f,0.0775733f},{0.263992f,-0.053229f,0.0703525f},{0.264774f,-0.0547312f,0.0918925f}, -{0.118812f,0.117958f,-0.147398f},{0.132995f,0.101235f,-0.145073f},{0.137784f,0.095588f,-0.143822f}, -{0.147313f,0.0843511f,-0.13998f},{0.152233f,0.0785499f,-0.138571f},{0.14741f,0.0842368f,-0.140576f}, -{0.142591f,0.0899192f,-0.142325f},{0.157052f,0.0728681f,-0.136307f},{0.161858f,0.0672011f,-0.133782f}, -{0.166643f,0.061559f,-0.130993f},{0.171398f,0.055952f,-0.127941f},{0.176115f,0.0503905f,-0.124624f}, -{0.189737f,0.0343283f,-0.112579f},{0.194415f,0.0288123f,-0.10875f},{0.189942f,0.0340856f,-0.113104f}, -{0.185396f,0.0394466f,-0.117203f},{0.198803f,0.0236373f,-0.104146f},{0.2031f,0.0185705f,-0.0992979f}, -{0.215087f,0.00443712f,-0.0829128f},{0.219206f,-0.000420286f,-0.0776135f},{0.215358f,0.00411768f,-0.0833616f}, -{0.211385f,0.00880137f,-0.0888979f},{0.222924f,-0.00480429f,-0.0716633f},{0.226505f,-0.00902663f,-0.0655221f}, -{0.229943f,-0.0130802f,-0.0592012f},{0.233232f,-0.0169586f,-0.0527127f},{0.242162f,-0.027488f,-0.0323688f}, -{0.244813f,-0.0306146f,-0.025339f},{0.247298f,-0.0335441f,-0.0182083f},{0.253364f,-0.0406967f,0.00387953f}, -{0.255536f,-0.0432588f,0.0110514f},{0.253733f,-0.041132f,0.00365355f},{0.251758f,-0.0388039f,-0.00369814f}, -{0.25717f,-0.0451848f,0.0184819f},{0.258634f,-0.0469113f,0.0259318f},{0.259931f,-0.0484403f,0.0333884f}, -{0.261062f,-0.0497743f,0.0408392f},{0.263098f,-0.0521747f,0.0631135f},{0.264756f,-0.0543717f,0.0918925f}, -{0.123467f,0.112469f,-0.146243f},{0.118788f,0.117986f,-0.146785f},{0.128185f,0.106907f,-0.145472f}, -{0.132935f,0.101305f,-0.144466f},{0.137711f,0.0956732f,-0.143218f},{0.142507f,0.0900189f,-0.141725f}, -{0.152124f,0.0786788f,-0.137981f},{0.166497f,0.0617313f,-0.130423f},{0.161724f,0.067359f,-0.133204f}, -{0.161421f,0.067337f,-0.132703f},{0.15693f,0.0730115f,-0.135723f},{0.17124f,0.0561387f,-0.127378f}, -{0.175944f,0.0505915f,-0.12407f},{0.180601f,0.0451003f,-0.120499f},{0.185202f,0.0396756f,-0.116668f}, -{0.20204f,0.0188534f,-0.0981062f},{0.202466f,0.0189389f,-0.098384f},{0.19777f,0.0238885f,-0.102924f}, -{0.194197f,0.0290685f,-0.108236f},{0.198575f,0.0239067f,-0.103644f},{0.202861f,0.018853f,-0.0988083f}, -{0.207047f,0.0139172f,-0.0937362f},{0.211125f,0.00910882f,-0.0884349f},{0.225299f,-0.00857174f,-0.0645409f}, -{0.225759f,-0.00852633f,-0.0647696f},{0.22174f,-0.00437572f,-0.0706439f},{0.218925f,-8.92274e-005f,-0.0771794f}, -{0.222634f,-0.004462f,-0.0712445f},{0.226205f,-0.00867353f,-0.065119f},{0.229634f,-0.0127167f,-0.0588143f}, -{0.232915f,-0.0165852f,-0.0523423f},{0.244467f,-0.0302062f,-0.0250388f},{0.241822f,-0.0270876f,-0.0320505f}, -{0.241341f,-0.0268995f,-0.0317747f},{0.239013f,-0.0237754f,-0.0389474f},{0.246945f,-0.0331282f,-0.0179263f}, -{0.249254f,-0.0358514f,-0.0107265f},{0.251394f,-0.0383745f,-0.00345334f},{0.255163f,-0.042818f,0.0112584f}, -{0.259546f,-0.0479863f,0.0335382f},{0.258252f,-0.0464612f,0.0261007f},{0.257734f,-0.0462299f,0.0262471f}, -{0.256792f,-0.044739f,0.0186698f},{0.260674f,-0.0493168f,0.04097f},{0.26164f,-0.050456f,0.048384f}, -{0.262447f,-0.0514073f,0.0557688f},{0.263947f,-0.0531761f,0.0776416f},{0.264154f,-0.0534201f,0.084806f}, -{0.264446f,-0.0537122f,0.0918925f},{0.264646f,-0.0540229f,0.0918925f},{0.123249f,0.112347f,-0.145713f}, -{0.11858f,0.117852f,-0.146254f},{0.127956f,0.106797f,-0.144944f},{0.132696f,0.101208f,-0.14394f}, -{0.137461f,0.0955882f,-0.142695f},{0.142246f,0.0899465f,-0.141205f},{0.147042f,0.0842913f,-0.139464f}, -{0.151842f,0.0786316f,-0.137469f},{0.156638f,0.0729769f,-0.135216f},{0.16581f,0.0615739f,-0.129604f}, -{0.170536f,0.0560018f,-0.126571f},{0.170915f,0.0561416f,-0.12689f},{0.166183f,0.0617218f,-0.129928f}, -{0.175609f,0.0506068f,-0.123589f},{0.180256f,0.0451278f,-0.120026f},{0.184846f,0.0397152f,-0.116203f}, -{0.189371f,0.0343798f,-0.112124f},{0.193822f,0.0291317f,-0.10779f},{0.19819f,0.0239814f,-0.103209f}, -{0.206643f,0.0140141f,-0.0933231f},{0.210711f,0.00921645f,-0.0880336f},{0.214665f,0.00455514f,-0.0825239f}, -{0.218495f,3.88646e-005f,-0.0768032f},{0.222195f,-0.00432417f,-0.0708815f},{0.22918f,-0.0125605f,-0.0584789f}, -{0.232453f,-0.0164204f,-0.0520214f},{0.235574f,-0.0201001f,-0.0454095f},{0.238538f,-0.0235946f,-0.0386562f}, -{0.243493f,-0.0300252f,-0.0246083f},{0.245962f,-0.0329364f,-0.017522f},{0.246452f,-0.0329266f,-0.017682f}, -{0.243979f,-0.0300111f,-0.0247786f},{0.248756f,-0.0356438f,-0.0104982f},{0.250891f,-0.0381612f,-0.00324118f}, -{0.252856f,-0.0404783f,0.00407537f},{0.254651f,-0.0425948f,0.0114378f},{0.256277f,-0.0445116f,0.0188328f}, -{0.259025f,-0.0477516f,0.0336681f},{0.259641f,-0.0490654f,0.0411575f},{0.260603f,-0.0502004f,0.0485442f}, -{0.261115f,-0.0502158f,0.0484808f},{0.260151f,-0.0490792f,0.0410833f},{0.26192f,-0.051165f,0.0558492f}, -{0.263416f,-0.0529299f,0.0776733f},{0.263855f,-0.0533019f,0.0918925f},{0.26418f,-0.0534707f,0.0918925f}, -{0.118277f,0.117622f,-0.145907f},{0.127639f,0.106583f,-0.144598f},{0.132372f,0.101002f,-0.143596f}, -{0.127325f,0.106343f,-0.144431f},{0.137131f,0.0953908f,-0.142353f},{0.141908f,0.0897573f,-0.140865f}, -{0.146697f,0.0841104f,-0.139127f},{0.15149f,0.0784589f,-0.137134f},{0.156279f,0.0728125f,-0.134885f}, -{0.161055f,0.0671808f,-0.132375f},{0.179512f,0.0448077f,-0.119568f},{0.174875f,0.0502749f,-0.123123f}, -{0.175223f,0.0504751f,-0.123274f},{0.179863f,0.0450041f,-0.119717f},{0.184446f,0.0395993f,-0.1159f}, -{0.188964f,0.0342717f,-0.111826f},{0.193409f,0.0290313f,-0.107499f},{0.205842f,0.0137614f,-0.0929223f}, -{0.206211f,0.0139358f,-0.0930527f},{0.201674f,0.0186755f,-0.0979722f},{0.210274f,0.00914513f,-0.087771f}, -{0.214221f,0.00449063f,-0.0822693f},{0.218046f,-1.90473e-005f,-0.0765569f},{0.22833f,-0.0127558f,-0.0581535f}, -{0.231596f,-0.0166073f,-0.0517099f},{0.228715f,-0.0126001f,-0.0582594f},{0.231984f,-0.0164543f,-0.0518113f}, -{0.2351f,-0.0201286f,-0.0452091f},{0.238059f,-0.023618f,-0.0384656f},{0.240858f,-0.026918f,-0.0315942f}, -{0.247864f,-0.035789f,-0.0102766f},{0.248263f,-0.0356496f,-0.0103487f},{0.245565f,-0.0330777f,-0.0174448f}, -{0.250395f,-0.0381634f,-0.0031023f},{0.252357f,-0.040477f,0.00420356f},{0.25415f,-0.0425905f,0.0115553f}, -{0.255773f,-0.0445045f,0.0189394f},{0.257228f,-0.0462203f,0.026343f},{0.258517f,-0.0477397f,0.0337531f}, -{0.261407f,-0.0511481f,0.0559018f},{0.262492f,-0.0530377f,0.0777041f},{0.262143f,-0.0526261f,0.0705019f}, -{0.262902f,-0.0529105f,0.077694f},{0.132055f,0.100766f,-0.143429f},{0.13681f,0.095159f,-0.142188f}, -{0.141584f,0.0895295f,-0.140701f},{0.14637f,0.0838865f,-0.138964f},{0.151159f,0.078239f,-0.136973f}, -{0.155945f,0.0725966f,-0.134725f},{0.160717f,0.0669689f,-0.132217f},{0.165469f,0.0613659f,-0.129448f}, -{0.170191f,0.0557978f,-0.126416f},{0.184092f,0.0394068f,-0.115753f},{0.188607f,0.034083f,-0.111682f}, -{0.193048f,0.0288463f,-0.107358f},{0.197407f,0.0237071f,-0.102786f},{0.209901f,0.0089741f,-0.0876442f}, -{0.213846f,0.00432289f,-0.0821464f},{0.217668f,-0.000183612f,-0.0764381f},{0.22136f,-0.00453721f,-0.0705292f}, -{0.224916f,-0.00873028f,-0.0644306f},{0.23471f,-0.020279f,-0.0451124f},{0.237668f,-0.0237659f,-0.0383737f}, -{0.240464f,-0.0270636f,-0.0315071f},{0.243098f,-0.0301686f,-0.0245261f},{0.249994f,-0.038301f,-0.0030353f}, -{0.251955f,-0.0406131f,0.00426541f},{0.253746f,-0.042725f,0.0116119f},{0.255368f,-0.0446377f,0.0189909f}, -{0.256823f,-0.0463522f,0.0263892f},{0.25811f,-0.0478706f,0.0337941f},{0.259234f,-0.0491954f,0.0411933f}, -{0.260196f,-0.0503295f,0.0485748f},{0.260999f,-0.0512766f,0.0559272f},{0.261647f,-0.0520407f,0.0632397f}, -{-0.164482f,0.077386f,-0.141015f},{-0.160376f,0.0813663f,-0.142188f},{-0.165975f,0.076557f,-0.140701f}, -{-0.193989f,0.0524965f,-0.129448f},{-0.195149f,0.0510464f,-0.12867f},{-0.190161f,0.0553306f,-0.131224f}, -{-0.144011f,0.0959421f,-0.145366f},{-0.144282f,0.0962099f,-0.145713f},{-0.149803f,0.0914681f,-0.144944f}, -{-0.154798f,0.0861567f,-0.143429f},{-0.15923f,0.0818969f,-0.142366f},{-0.155583f,0.0868273f,-0.144466f}, -{-0.150012f,0.0916126f,-0.145472f},{-0.143742f,0.0956526f,-0.145199f},{-0.149524f,0.0912072f,-0.144598f}, -{-0.149251f,0.0909211f,-0.144431f},{-0.13357f,0.105734f,-0.147719f},{-0.133556f,0.105746f,-0.147105f}, -{-0.128196f,0.110381f,-0.147351f},{-0.144478f,0.096365f,-0.146243f},{-0.127892f,0.110028f,-0.148558f}, -{-0.133182f,0.105243f,-0.148599f},{-0.133422f,0.105538f,-0.148251f},{-0.128143f,0.11032f,-0.148015f}, -{-0.138114f,0.100033f,-0.148493f},{-0.138401f,0.10024f,-0.148445f},{-0.132929f,0.10494f,-0.148767f}, -{-0.132705f,0.104679f,-0.14881f},{-0.12751f,0.109583f,-0.148876f},{-0.127291f,0.109328f,-0.148916f}, -{-0.174884f,0.0684522f,-0.137702f},{-0.171588f,0.0717361f,-0.138964f},{-0.177206f,0.0669114f,-0.136973f}, -{-0.169701f,0.0729032f,-0.13946f},{-0.182818f,0.062091f,-0.134725f},{-0.180024f,0.0640372f,-0.135742f}, -{-0.188716f,0.0575456f,-0.132375f},{-0.188416f,0.0572832f,-0.132217f},{-0.185118f,0.0596621f,-0.133582f}, -{-0.199528f,0.0477396f,-0.126416f},{-0.200078f,0.0468134f,-0.125923f},{-0.210459f,0.0383507f,-0.119568f}, -{-0.215831f,0.0337366f,-0.115753f},{-0.214463f,0.0344587f,-0.116543f},{-0.205021f,0.0430213f,-0.123123f}, -{-0.228159f,0.0226953f,-0.105516f},{-0.223677f,0.0265448f,-0.109369f},{-0.226336f,0.0247146f,-0.107358f}, -{-0.21911f,0.0304671f,-0.113046f},{-0.236853f,0.0152278f,-0.0972923f},{-0.236452f,0.0160256f,-0.0979722f}, -{-0.24134f,0.0118274f,-0.0929223f},{-0.231448f,0.0203242f,-0.102786f},{-0.249164f,0.00465414f,-0.0837205f}, -{-0.250729f,0.00376401f,-0.0821464f},{-0.253058f,0.00130946f,-0.0788827f},{-0.246102f,0.00773759f,-0.0876442f}, -{-0.264065f,-0.00814415f,-0.0634868f},{-0.260512f,-0.00509248f,-0.0687614f},{-0.263712f,-0.00738746f,-0.0644306f}, -{-0.256842f,-0.00194036f,-0.0738949f},{-0.259542f,-0.00380527f,-0.0705292f},{-0.273991f,-0.0166696f,-0.0468636f}, -{-0.271547f,-0.0141168f,-0.0517099f},{-0.2752f,-0.0172537f,-0.0451124f},{-0.267717f,-0.0108265f,-0.0581535f}, -{-0.281948f,-0.0230499f,-0.0315071f},{-0.282759f,-0.0241996f,-0.0291439f},{-0.27997f,-0.0218041f,-0.0351637f}, -{-0.277046f,-0.0192933f,-0.041072f},{-0.290298f,-0.0306748f,-0.010468f},{-0.287925f,-0.0286369f,-0.0167907f}, -{-0.290627f,-0.030504f,-0.0102766f},{-0.285037f,-0.0257024f,-0.0245261f},{-0.293126f,-0.0326501f,-0.0030353f}, -{-0.294612f,-0.0343798f,0.00244111f},{-0.292527f,-0.0325897f,-0.00405553f},{-0.299429f,-0.0380636f,0.0189909f}, -{-0.298338f,-0.0375801f,0.0156645f},{-0.297526f,-0.0364296f,0.0116119f},{-0.296549f,-0.0360438f,0.00901635f}, -{-0.295426f,-0.0346253f,0.00426541f},{-0.301463f,-0.0402644f,0.0291557f},{-0.302645f,-0.0408255f,0.0337941f}, -{-0.302797f,-0.04141f,0.0359868f},{-0.301134f,-0.0395283f,0.0263892f},{-0.299976f,-0.0389874f,0.0223796f}, -{-0.303977f,-0.0424232f,0.0428671f},{-0.30509f,-0.0429262f,0.0485748f},{-0.305001f,-0.0433031f,0.0497904f}, -{-0.303962f,-0.0419573f,0.0411933f},{-0.308026f,-0.0454474f,0.0848371f},{-0.307848f,-0.0457485f,0.0918925f}, -{-0.307769f,-0.0456805f,0.0848393f},{-0.305869f,-0.044049f,0.0567509f},{-0.306032f,-0.0437353f,0.0559272f}, -{-0.307375f,-0.0448882f,0.0705019f},{-0.307759f,-0.0446979f,0.0704868f},{-0.308168f,-0.0450498f,0.077694f}, -{-0.307531f,-0.0454763f,0.0777923f},{-0.306581f,-0.0446602f,0.0637421f},{-0.307135f,-0.0451361f,0.0707579f}, -{-0.307784f,-0.0452398f,0.0777041f},{-0.306792f,-0.044388f,0.0632397f},{-0.30868f,-0.0449881f,0.0776733f}, -{-0.309485f,-0.0453564f,0.084806f},{-0.308922f,-0.0451961f,0.0848218f},{-0.305473f,-0.0427346f,0.0485442f}, -{-0.304344f,-0.041765f,0.0411575f},{-0.308269f,-0.0446357f,0.0704555f},{-0.307176f,-0.0441974f,0.0632194f}, -{-0.307686f,-0.0441345f,0.0631775f},{-0.30598f,-0.0426695f,0.0484808f},{-0.309295f,-0.0451931f,0.0703525f}, -{-0.308709f,-0.0446894f,0.0630396f},{-0.309537f,-0.0457246f,0.0703047f},{-0.308247f,-0.0442923f,0.0631135f}, -{-0.308831f,-0.0447947f,0.0704077f},{-0.309553f,-0.0462388f,0.0702734f},{-0.309967f,-0.0465942f,0.0775525f}, -{-0.310303f,-0.0465537f,0.0918925f},{-0.310194f,-0.0462889f,0.0847721f},{-0.310211f,-0.046804f,0.0847617f}, -{-0.310081f,-0.0472127f,0.0847568f},{-0.310171f,-0.0472612f,0.0918925f},{-0.310283f,-0.046913f,0.0918925f}, -{-0.30997f,-0.0475707f,0.0918925f},{-0.301514f,-0.0393343f,0.026343f},{-0.278668f,-0.0202326f,-0.0383737f}, -{-0.285411f,-0.0264779f,-0.0230178f},{-0.28793f,-0.0281877f,-0.0174448f},{-0.282314f,-0.0228442f,-0.0315942f}, -{-0.270808f,-0.0139352f,-0.0525331f},{-0.267498f,-0.0110925f,-0.0580758f},{-0.255211f,-8.59432e-005f,-0.0764381f}, -{-0.245163f,0.00809075f,-0.088404f},{-0.259892f,-0.00358602f,-0.0706439f},{-0.260333f,-0.0034637f,-0.0708815f}, -{-0.264512f,-0.00705366f,-0.0647696f},{-0.241058f,0.0116164f,-0.0929293f},{-0.232552f,0.0189219f,-0.101489f}, -{-0.209739f,0.0385159f,-0.119856f},{-0.204942f,0.0426353f,-0.122984f},{-0.221127f,0.0291884f,-0.111682f}, -{-0.237193f,0.0164102f,-0.098384f},{-0.231778f,0.0205605f,-0.102924f},{-0.232178f,0.0207181f,-0.103209f}, -{-0.15395f,0.0864318f,-0.14351f},{-0.148646f,0.090987f,-0.144448f},{-0.143324f,0.0955583f,-0.145179f}, -{-0.133384f,0.10557f,-0.146574f},{-0.128144f,0.110321f,-0.147023f},{-0.138279f,0.100345f,-0.145739f}, -{-0.137988f,0.100142f,-0.145701f},{-0.132868f,0.104993f,-0.146057f},{-0.132642f,0.104733f,-0.146014f}, -{-0.128196f,0.110381f,-0.147687f},{-0.12751f,0.109583f,-0.146158f},{-0.127291f,0.109328f,-0.146119f}, -{-0.12771f,0.109815f,-0.146297f},{-0.127896f,0.110032f,-0.146474f},{-0.133129f,0.105289f,-0.146225f}, -{-0.128042f,0.110202f,-0.146724f},{-0.138543f,0.100638f,-0.145907f},{-0.155075f,0.0864395f,-0.143596f}, -{-0.160656f,0.0816457f,-0.142353f},{-0.16626f,0.0768329f,-0.140865f},{-0.171877f,0.0720087f,-0.139127f}, -{-0.177498f,0.0671806f,-0.137134f},{-0.183114f,0.0623568f,-0.134885f},{-0.194638f,0.0529602f,-0.129928f}, -{-0.200189f,0.0481929f,-0.12689f},{-0.194293f,0.0527555f,-0.129604f},{-0.199836f,0.0479952f,-0.126571f}, -{-0.205333f,0.0432736f,-0.123274f},{-0.210775f,0.0385997f,-0.119717f},{-0.216151f,0.0339824f,-0.1159f}, -{-0.22145f,0.0294309f,-0.111826f},{-0.226663f,0.024954f,-0.107499f},{-0.236786f,0.0162589f,-0.0981062f}, -{-0.241678f,0.0120577f,-0.0930527f},{-0.246443f,0.00796499f,-0.087771f},{-0.251073f,0.00398861f,-0.0822693f}, -{-0.255558f,0.000135934f,-0.0765569f},{-0.264066f,-0.00717073f,-0.0645409f},{-0.268073f,-0.0106122f,-0.0582594f}, -{-0.271906f,-0.0139049f,-0.0518113f},{-0.275561f,-0.0170439f,-0.0452091f},{-0.279032f,-0.0200249f,-0.0384656f}, -{-0.29201f,-0.0303472f,-0.0107265f},{-0.288783f,-0.0278991f,-0.017682f},{-0.289301f,-0.0280207f,-0.0179263f}, -{-0.285405f,-0.0254986f,-0.0246083f},{-0.288301f,-0.0279857f,-0.017522f},{-0.290999f,-0.0303036f,-0.0103487f}, -{-0.2935f,-0.0324512f,-0.0031023f},{-0.295801f,-0.0344278f,0.00420356f},{-0.297903f,-0.0362334f,0.0115553f}, -{-0.299807f,-0.0378685f,0.0189394f},{-0.303025f,-0.0406324f,0.0337531f},{-0.30485f,-0.0416984f,0.0410833f}, -{-0.306415f,-0.0435442f,0.0559018f},{-0.30841f,-0.0452575f,0.0848321f},{-0.308442f,-0.0453419f,0.0918925f}, -{-0.308124f,-0.045503f,0.0918925f},{-0.128039f,0.110199f,-0.14831f},{-0.138807f,0.100913f,-0.146254f}, -{-0.155362f,0.0866934f,-0.14394f},{-0.160952f,0.0818926f,-0.142695f},{-0.166563f,0.0770728f,-0.141205f}, -{-0.172189f,0.0722415f,-0.139464f},{-0.177818f,0.0674064f,-0.137469f},{-0.183443f,0.0625755f,-0.135216f}, -{-0.189053f,0.0577573f,-0.132703f},{-0.205694f,0.0434645f,-0.123589f},{-0.206027f,0.043502f,-0.12407f}, -{-0.211489f,0.0388108f,-0.120499f},{-0.211144f,0.0387837f,-0.120026f},{-0.216528f,0.0341596f,-0.116203f}, -{-0.221835f,0.0296015f,-0.112124f},{-0.227055f,0.0251181f,-0.10779f},{-0.247289f,0.00806285f,-0.0884349f}, -{-0.247595f,0.00780019f,-0.0888979f},{-0.252254f,0.00379886f,-0.0833616f},{-0.242092f,0.0122029f,-0.0933231f}, -{-0.246864f,0.0081042f,-0.0880336f},{-0.251501f,0.00412199f,-0.0825239f},{-0.255993f,0.000263687f,-0.0768032f}, -{-0.272846f,-0.0138878f,-0.0523423f},{-0.273218f,-0.0142069f,-0.0527127f},{-0.276895f,-0.0173656f,-0.046069f}, -{-0.268525f,-0.0105001f,-0.0584789f},{-0.272364f,-0.0137976f,-0.0520214f},{-0.276025f,-0.0169413f,-0.0454095f}, -{-0.2795f,-0.0199266f,-0.0386562f},{-0.282788f,-0.02275f,-0.0317747f},{-0.285883f,-0.0254083f,-0.0247786f}, -{-0.291486f,-0.0302204f,-0.0104982f},{-0.29399f,-0.0323711f,-0.00324118f},{-0.296294f,-0.0343506f,0.00407537f}, -{-0.2984f,-0.0361588f,0.0114378f},{-0.300306f,-0.0377963f,0.0188328f},{-0.302015f,-0.0392642f,0.0262471f}, -{-0.303529f,-0.0405642f,0.0336681f},{-0.306924f,-0.0434803f,0.0558492f},{-0.309707f,-0.0455472f,0.077605f}, -{-0.308803f,-0.0452653f,0.0918925f},{-0.138651f,0.100546f,-0.148277f},{-0.138991f,0.101078f,-0.146785f}, -{-0.161185f,0.0820158f,-0.143218f},{-0.16127f,0.081943f,-0.143822f},{-0.166909f,0.0771001f,-0.142325f}, -{-0.166809f,0.0771853f,-0.141725f},{-0.172447f,0.0723432f,-0.13998f},{-0.178089f,0.0674973f,-0.137981f}, -{-0.183726f,0.0626556f,-0.135723f},{-0.189349f,0.0578266f,-0.133204f},{-0.194947f,0.0530188f,-0.130423f}, -{-0.200509f,0.048241f,-0.127378f},{-0.216885f,0.0341764f,-0.116668f},{-0.217113f,0.0339808f,-0.117203f}, -{-0.222445f,0.0294008f,-0.113104f},{-0.222204f,0.0296081f,-0.112579f},{-0.227436f,0.0251146f,-0.108236f}, -{-0.23257f,0.0207049f,-0.103644f},{-0.237597f,0.0163874f,-0.0988083f},{-0.242506f,0.0121707f,-0.0937362f}, -{-0.251936f,0.00407176f,-0.0829128f},{-0.256438f,0.00020485f,-0.0771794f},{-0.260788f,-0.00353086f,-0.0712445f}, -{-0.264977f,-0.00712881f,-0.065119f},{-0.268999f,-0.010583f,-0.0588143f},{-0.276515f,-0.0170385f,-0.0457157f}, -{-0.279998f,-0.0200305f,-0.0389474f},{-0.283293f,-0.0228602f,-0.0320505f},{-0.286395f,-0.0255244f,-0.0250388f}, -{-0.29452f,-0.0325027f,-0.00345334f},{-0.294947f,-0.0328695f,-0.00369814f},{-0.297263f,-0.0348585f,0.00365355f}, -{-0.29683f,-0.0344866f,0.00387953f},{-0.29894f,-0.0362988f,0.0112584f},{-0.30085f,-0.03794f,0.0186698f}, -{-0.302563f,-0.0394112f,0.0261007f},{-0.30408f,-0.0407141f,0.0335382f},{-0.305404f,-0.0418509f,0.04097f}, -{-0.306537f,-0.0428241f,0.048384f},{-0.307483f,-0.0436367f,0.0557688f},{-0.309243f,-0.0451479f,0.0776416f}, -{-0.309162f,-0.0452855f,0.0918925f},{-0.14452f,0.0963291f,-0.146855f},{-0.150068f,0.0915645f,-0.146081f}, -{-0.139019f,0.101054f,-0.147398f},{-0.155654f,0.0867669f,-0.145073f},{-0.172561f,0.0722455f,-0.140576f}, -{-0.178217f,0.0673872f,-0.138571f},{-0.183869f,0.0625331f,-0.136307f},{-0.183833f,0.0622407f,-0.136814f}, -{-0.189482f,0.0573886f,-0.134283f},{-0.189506f,0.0576918f,-0.133782f},{-0.195118f,0.0528716f,-0.130993f}, -{-0.200695f,0.0480815f,-0.127941f},{-0.206227f,0.0433303f,-0.124624f},{-0.211703f,0.0386271f,-0.121044f}, -{-0.22769f,0.0248958f,-0.10875f},{-0.227751f,0.0245198f,-0.109195f},{-0.23291f,0.0200889f,-0.104581f}, -{-0.232838f,0.0204747f,-0.104146f},{-0.237878f,0.0161461f,-0.0992979f},{-0.2428f,0.0119186f,-0.0942128f}, -{-0.256767f,-7.79773e-005f,-0.0776135f},{-0.256893f,-0.000509374f,-0.0779897f},{-0.261263f,-0.00426299f,-0.0720263f}, -{-0.261128f,-0.00382328f,-0.0716633f},{-0.265328f,-0.00743047f,-0.0655221f},{-0.26936f,-0.0108935f,-0.0592012f}, -{-0.280388f,-0.0203653f,-0.0392833f},{-0.280566f,-0.0208417f,-0.0395744f},{-0.283876f,-0.023685f,-0.0326445f}, -{-0.283691f,-0.0232022f,-0.0323688f},{-0.286801f,-0.0258733f,-0.025339f},{-0.289715f,-0.028376f,-0.0182083f}, -{-0.292431f,-0.0307085f,-0.01099f},{-0.299378f,-0.0366754f,0.0110514f},{-0.301294f,-0.0383208f,0.0184819f}, -{-0.301518f,-0.038837f,0.0183189f},{-0.303239f,-0.0403153f,0.0257854f},{-0.303011f,-0.0397958f,0.0259318f}, -{-0.304532f,-0.041102f,0.0333884f},{-0.305859f,-0.0422417f,0.0408392f},{-0.306995f,-0.0432174f,0.0482723f}, -{-0.307944f,-0.0440321f,0.0556761f},{-0.309951f,-0.0457562f,0.0847878f},{-0.30982f,-0.0455988f,0.0918925f}, -{-0.309511f,-0.0453977f,0.0918925f},{-0.144396f,0.0961117f,-0.147384f},{-0.149956f,0.0913365f,-0.14661f}, -{-0.138883f,0.100847f,-0.147929f},{-0.155555f,0.0865282f,-0.145599f},{-0.161183f,0.0816937f,-0.144345f}, -{-0.166835f,0.07684f,-0.142845f},{-0.172499f,0.0719747f,-0.141092f},{-0.178168f,0.0671055f,-0.139082f}, -{-0.195107f,0.0525577f,-0.131488f},{-0.200554f,0.0473783f,-0.128748f},{-0.200696f,0.047757f,-0.128429f}, -{-0.20624f,0.0429952f,-0.125105f},{-0.211728f,0.0382816f,-0.121517f},{-0.21715f,0.033625f,-0.117667f}, -{-0.222494f,0.0290348f,-0.113559f},{-0.237873f,0.0153256f,-0.1f},{-0.237961f,0.0157507f,-0.0997223f}, -{-0.242894f,0.0115138f,-0.0946258f},{-0.2477f,0.00738628f,-0.0892991f},{-0.252369f,0.00337607f,-0.0837506f}, -{-0.265424f,-0.00833753f,-0.0661002f},{-0.265472f,-0.00787819f,-0.0658715f},{-0.269513f,-0.0113489f,-0.0595366f}, -{-0.27338f,-0.0146696f,-0.0530336f},{-0.277066f,-0.0178353f,-0.0463752f},{-0.286976f,-0.0268481f,-0.0257695f}, -{-0.286993f,-0.026362f,-0.0255992f},{-0.289914f,-0.0288702f,-0.0184526f},{-0.292635f,-0.0312079f,-0.0112184f}, -{-0.295157f,-0.0333737f,-0.00391029f},{-0.297478f,-0.0353671f,0.00345771f},{-0.299598f,-0.037188f,0.0108719f}, -{-0.304763f,-0.0416245f,0.0332586f},{-0.306104f,-0.0432766f,0.0406518f},{-0.306093f,-0.0427667f,0.0407259f}, -{-0.307232f,-0.0437445f,0.0481755f},{-0.308183f,-0.0445611f,0.0555957f},{-0.30895f,-0.0452198f,0.0629755f}, -{-0.30995f,-0.0460795f,0.0775733f},{-0.310227f,-0.0461927f,0.0918925f},{-0.31006f,-0.0458671f,0.0918925f}, -{-0.127713f,0.109819f,-0.148751f},{-0.144173f,0.0958031f,-0.147731f},{-0.149741f,0.091021f,-0.146955f}, -{-0.155347f,0.0862057f,-0.145943f},{-0.160984f,0.0813642f,-0.144688f},{-0.166643f,0.0765035f,-0.143185f}, -{-0.172316f,0.0716311f,-0.141429f},{-0.177994f,0.0667549f,-0.139417f},{-0.183666f,0.061883f,-0.137145f}, -{-0.189324f,0.0570238f,-0.134611f},{-0.194956f,0.052186f,-0.131812f},{-0.205904f,0.0422634f,-0.125571f}, -{-0.210708f,0.0376835f,-0.122344f},{-0.211404f,0.0375395f,-0.121975f},{-0.206106f,0.0426097f,-0.125419f}, -{-0.211602f,0.0378891f,-0.121826f},{-0.217032f,0.0332258f,-0.117971f},{-0.222384f,0.028629f,-0.113856f}, -{-0.227648f,0.0241074f,-0.109486f},{-0.232815f,0.0196701f,-0.104866f},{-0.242813f,0.0110826f,-0.0948962f}, -{-0.242637f,0.0107143f,-0.0950266f},{-0.247626f,0.00694907f,-0.0895618f},{-0.252302f,0.00293304f,-0.0840052f}, -{-0.256832f,-0.000958027f,-0.0782359f},{-0.261209f,-0.00471708f,-0.072264f},{-0.269313f,-0.0121976f,-0.059862f}, -{-0.272494f,-0.0153837f,-0.0542297f},{-0.273188f,-0.0155254f,-0.053345f},{-0.269471f,-0.0118133f,-0.059756f}, -{-0.273343f,-0.0151388f,-0.0532437f},{-0.277034f,-0.0183091f,-0.0465757f},{-0.280539f,-0.0213198f,-0.039765f}, -{-0.283855f,-0.0241672f,-0.0328251f},{-0.289901f,-0.02936f,-0.0186126f},{-0.292484f,-0.0320992f,-0.0114399f}, -{-0.292626f,-0.031701f,-0.0113678f},{-0.295152f,-0.03387f,-0.00404916f},{-0.297476f,-0.0358663f,0.00332952f}, -{-0.299599f,-0.0376898f,0.0107545f},{-0.301522f,-0.0393413f,0.0182123f},{-0.303246f,-0.0408217f,0.0256896f}, -{-0.304772f,-0.0421327f,0.0331736f},{-0.307244f,-0.0442558f,0.0481121f},{-0.308196f,-0.0450736f,0.0555431f}, -{-0.308964f,-0.0457333f,0.0629336f},{-0.143927f,0.095494f,-0.147899f},{-0.149499f,0.0907085f,-0.147122f}, -{-0.155109f,0.0858899f,-0.146109f},{-0.16075f,0.081045f,-0.144853f},{-0.166413f,0.0761809f,-0.143349f}, -{-0.17209f,0.0713051f,-0.141592f},{-0.177772f,0.0664255f,-0.139579f},{-0.183448f,0.0615502f,-0.137305f}, -{-0.189109f,0.0566876f,-0.134769f},{-0.194746f,0.0518464f,-0.131968f},{-0.200348f,0.0470353f,-0.128902f}, -{-0.216837f,0.032873f,-0.118117f},{-0.222193f,0.0282729f,-0.114f},{-0.227461f,0.0237482f,-0.109627f}, -{-0.232631f,0.0193078f,-0.105003f},{-0.237693f,0.0149603f,-0.100134f},{-0.238141f,0.0141219f,-0.0995149f}, -{-0.247453f,0.00657788f,-0.0896885f},{-0.252132f,0.00255905f,-0.0841281f},{-0.256665f,-0.00133474f,-0.0783547f}, -{-0.261045f,-0.00509642f,-0.0723786f},{-0.265263f,-0.00871939f,-0.0662105f},{-0.276881f,-0.0186979f,-0.0466724f}, -{-0.280389f,-0.0217108f,-0.039857f},{-0.283707f,-0.0245601f,-0.0329122f},{-0.28683f,-0.0272429f,-0.0258517f}, -{-0.289757f,-0.0297565f,-0.0186898f},{-0.289812f,-0.030258f,-0.0180672f},{-0.295012f,-0.0342697f,-0.00411618f}, -{-0.297337f,-0.0362674f,0.00326766f},{-0.299462f,-0.0380922f,0.0106978f},{-0.301386f,-0.0397448f,0.0181608f}, -{-0.303111f,-0.0412262f,0.0256434f},{-0.304639f,-0.0425382f,0.0331326f},{-0.305971f,-0.0436828f,0.040616f}, -{-0.307112f,-0.0446628f,0.0480815f},{-0.308065f,-0.0454811f,0.0555177f},{-0.308834f,-0.0461413f,0.0629134f}, -{-0.309423f,-0.0466471f,0.0702583f},{-0.309837f,-0.0470028f,0.0775425f},{-0.143513f,0.0953962f,-0.147965f}, -{-0.148897f,0.0907713f,-0.147226f},{-0.154263f,0.0861627f,-0.146277f},{-0.159606f,0.0815743f,-0.145118f}, -{-0.164919f,0.0770103f,-0.143752f},{-0.1702f,0.0724748f,-0.142179f},{-0.175443f,0.0679717f,-0.1404f}, -{-0.180644f,0.0635049f,-0.138417f},{-0.185798f,0.0590782f,-0.136232f},{-0.1909f,0.0546957f,-0.133846f}, -{-0.195947f,0.0503613f,-0.131262f},{-0.200933f,0.0460786f,-0.128482f},{-0.205855f,0.0418515f,-0.125509f}, -{-0.215487f,0.0335786f,-0.118992f},{-0.220189f,0.0295402f,-0.115454f},{-0.224809f,0.0255719f,-0.111734f}, -{-0.229344f,0.0216771f,-0.107835f},{-0.233789f,0.0178593f,-0.103761f},{-0.242395f,0.0104681f,-0.0951008f}, -{-0.246548f,0.00690116f,-0.0905224f},{-0.250596f,0.00342407f,-0.0857837f},{-0.254536f,4.00465e-005f,-0.080889f}, -{-0.258365f,-0.00324795f,-0.0758426f},{-0.262078f,-0.00643705f,-0.0706488f},{-0.265672f,-0.00952448f,-0.0653124f}, -{-0.269146f,-0.0125076f,-0.0598376f},{-0.275715f,-0.0181502f,-0.0484934f},{-0.278806f,-0.0208047f,-0.042634f}, -{-0.281763f,-0.0233449f,-0.0366563f},{-0.284585f,-0.0257686f,-0.0305656f},{-0.287269f,-0.0280737f,-0.0243674f}, -{-0.292213f,-0.0323197f,-0.0116704f},{-0.294469f,-0.0342571f,-0.00518257f},{-0.296578f,-0.0360684f,0.00139061f}, -{-0.298538f,-0.0377519f,0.00804317f},{-0.300347f,-0.0393062f,0.0147693f},{-0.302005f,-0.04073f,0.0215631f}, -{-0.303509f,-0.042022f,0.0284189f},{-0.304859f,-0.043181f,0.0353305f},{-0.306052f,-0.0442061f,0.0422916f}, -{-0.307089f,-0.0450964f,0.0492962f},{-0.307967f,-0.045851f,0.0563382f},{-0.308687f,-0.0464693f,0.0634117f}, -{-0.309248f,-0.0469508f,0.0705101f},{-0.309649f,-0.047295f,0.0776272f},{-0.309889f,-0.0475017f,0.0847567f}, -{0.0493934f,0.26108f,0.0428677f},{0.0500586f,0.262105f,0.0485758f},{0.0489305f,0.261136f,0.0411945f}, -{0.0403941f,0.253804f,0.00426646f},{0.0400286f,0.253036f,0.00244165f},{0.041966f,0.2547f,0.00901696f}, -{0.0517606f,0.263566f,0.0632405f},{0.052343f,0.264067f,0.0705025f},{0.0516301f,0.263974f,0.0632202f}, -{0.0512863f,0.262705f,0.0567511f},{0.0519978f,0.263316f,0.0637424f},{0.0528812f,0.26555f,0.084822f}, -{0.0530084f,0.265783f,0.0918925f},{0.0531246f,0.266082f,0.0848062f},{0.0522285f,0.264989f,0.0704561f}, -{0.0516449f,0.264488f,0.0631783f},{0.0522129f,0.264475f,0.0704874f},{0.0535901f,0.266482f,0.084788f}, -{0.0540726f,0.26669f,0.0918925f},{0.0541535f,0.266643f,0.0847723f},{0.0524705f,0.265521f,0.0704083f}, -{0.0518855f,0.265018f,0.0631143f},{0.0550496f,0.266391f,0.084757f},{0.0548051f,0.266181f,0.0775429f}, -{0.0546651f,0.266581f,0.084762f},{0.0544319f,0.26671f,0.0918925f},{0.0553868f,0.266227f,0.0918925f}, -{0.0551112f,0.266473f,0.0918925f},{0.0550661f,0.265952f,0.0776267f},{0.0510006f,0.262914f,0.0559281f}, -{0.0504179f,0.261959f,0.0497909f},{0.0553066f,0.266158f,0.0847564f},{0.0468799f,0.258921f,0.0291561f}, -{0.0476128f,0.260004f,0.0337954f},{0.0461026f,0.258707f,0.0263905f},{0.0482137f,0.260066f,0.0359874f}, -{0.0443972f,0.257242f,0.0189921f},{0.0453931f,0.257644f,0.0223799f},{0.0424948f,0.255608f,0.0116131f}, -{0.0437546f,0.256236f,0.015665f},{0.0380944f,0.251829f,-0.00303443f},{0.0379442f,0.251246f,-0.0040552f}, -{0.0328989f,0.247366f,-0.0174445f},{0.0300052f,0.244881f,-0.0245261f},{0.0308284f,0.245134f,-0.0230172f}, -{0.0355958f,0.249683f,-0.010276f},{0.0224634f,0.23795f,-0.0410717f},{0.0253866f,0.240461f,-0.0351634f}, -{0.0236368f,0.239411f,-0.0383731f},{0.0281758f,0.242856f,-0.0291434f},{0.016225f,0.232592f,-0.0525327f}, -{0.0165165f,0.233296f,-0.051709f},{0.0126856f,0.230006f,-0.0581524f},{0.0201686f,0.236433f,-0.0451116f}, -{0.00592937f,0.223749f,-0.0687612f},{0.004511f,0.222985f,-0.0705281f},{0.00225941f,0.220597f,-0.0738946f}, -{0.00868167f,0.226567f,-0.0644294f},{-0.00942004f,0.210566f,-0.088404f},{-0.00541866f,0.214002f,-0.0837203f}, -{-0.00892832f,0.211442f,-0.0876434f},{-0.00152437f,0.217347f,-0.0788824f},{-0.00430185f,0.215415f,-0.0821454f}, -{-0.0220305f,0.199735f,-0.101489f},{-0.0185782f,0.203154f,-0.0979716f},{-0.0235832f,0.198855f,-0.102786f}, -{-0.0136901f,0.207352f,-0.0929216f},{-0.0339042f,0.189991f,-0.111682f},{-0.0354727f,0.18819f,-0.113046f}, -{-0.030906f,0.192112f,-0.109369f},{-0.026424f,0.195961f,-0.105516f},{-0.0496403f,0.176021f,-0.122984f}, -{-0.0448439f,0.180141f,-0.119856f},{-0.0500098f,0.176158f,-0.123123f},{-0.0392f,0.185442f,-0.115753f}, -{-0.055503f,0.17144f,-0.126416f},{-0.0594332f,0.16761f,-0.12867f},{-0.0545048f,0.171843f,-0.125923f}, -{-0.0722122f,0.157088f,-0.134725f},{-0.0694645f,0.158995f,-0.133582f},{-0.0666145f,0.161896f,-0.132217f}, -{-0.0644212f,0.163326f,-0.131224f},{-0.0610414f,0.166683f,-0.129448f},{-0.079699f,0.150204f,-0.137702f}, -{-0.0778246f,0.152268f,-0.136973f},{-0.083442f,0.147443f,-0.138964f},{-0.0745587f,0.154619f,-0.135742f}, -{-0.0901005f,0.141271f,-0.141015f},{-0.089055f,0.142623f,-0.140701f},{-0.0946547f,0.137813f,-0.142188f}, -{-0.0848811f,0.145754f,-0.13946f},{-0.100633f,0.132225f,-0.143511f},{-0.0953526f,0.13676f,-0.142366f}, -{-0.100232f,0.133023f,-0.14343f},{-0.111882f,0.124362f,-0.146244f},{-0.111758f,0.124144f,-0.145714f}, -{-0.106237f,0.128886f,-0.144944f},{-0.122163f,0.114186f,-0.146058f},{-0.116595f,0.118515f,-0.145701f}, -{-0.116752f,0.118834f,-0.145739f},{-0.121941f,0.113924f,-0.146015f},{-0.111289f,0.123526f,-0.145199f}, -{-0.10578f,0.128258f,-0.144432f},{-0.111534f,0.123836f,-0.145367f},{-0.111259f,0.123099f,-0.145179f}, -{-0.105936f,0.12767f,-0.144449f},{-0.0892849f,0.142945f,-0.140865f},{-0.095088f,0.138462f,-0.142696f}, -{-0.0948885f,0.138132f,-0.142353f},{-0.106348f,0.129114f,-0.145472f},{-0.106021f,0.128571f,-0.144599f}, -{-0.11184f,0.124398f,-0.146855f},{-0.117342f,0.119672f,-0.147398f},{-0.117369f,0.119648f,-0.146786f}, -{-0.111372f,0.123975f,-0.147732f},{-0.116894f,0.119232f,-0.148277f},{-0.111644f,0.124242f,-0.147385f}, -{-0.122619f,0.114816f,-0.148251f},{-0.122363f,0.114535f,-0.148599f},{-0.122103f,0.114239f,-0.148767f}, -{-0.121878f,0.113978f,-0.14881f},{-0.0780466f,0.152598f,-0.137135f},{-0.0286952f,0.194464f,-0.107358f}, -{-0.04012f,0.184198f,-0.116543f},{-0.0445719f,0.180828f,-0.119568f},{-0.0340952f,0.190347f,-0.111826f}, -{-0.0177295f,0.203429f,-0.097292f},{-0.0135248f,0.20704f,-0.0929291f},{0.000180634f,0.219265f,-0.076437f}, -{0.00948232f,0.226801f,-0.0634867f},{-0.00447193f,0.215789f,-0.0822683f},{-0.00453921f,0.216232f,-0.0825229f}, -{-0.00917572f,0.21225f,-0.0880327f},{0.0129153f,0.229749f,-0.0580755f},{0.0194086f,0.235326f,-0.0468631f}, -{0.0333422f,0.247293f,-0.0167902f},{0.0357148f,0.249331f,-0.0104677f},{0.0269169f,0.242229f,-0.0315068f}, -{0.0163243f,0.234152f,-0.0520204f},{0.0200158f,0.236821f,-0.0452083f},{0.0199843f,0.237295f,-0.0454087f}, -{0.0423578f,0.256011f,0.0115564f},{0.0525519f,0.263792f,0.0707584f},{0.0534149f,0.266377f,0.0918925f}, -{0.0529481f,0.264133f,0.0777929f},{0.0527525f,0.264418f,0.0777045f},{0.0528646f,0.265035f,0.0848323f}, -{0.0529317f,0.265422f,0.0918925f},{0.0531859f,0.264337f,0.0848396f},{0.0529943f,0.264626f,0.0848373f}, -{0.0530642f,0.264714f,0.0918925f},{0.0529519f,0.265063f,0.0918925f},{0.0532653f,0.264405f,0.0918925f}, -{0.0531751f,0.266108f,0.0918925f},{0.0537244f,0.266578f,0.0918925f},{0.0526227f,0.264827f,0.0776945f}, -{0.0508696f,0.263321f,0.0559028f},{0.0499269f,0.262512f,0.0485453f},{0.048798f,0.261542f,0.0411587f}, -{0.0474794f,0.260409f,0.0337544f},{0.0459681f,0.259111f,0.0263442f},{0.0442615f,0.257646f,0.0189407f}, -{0.0402537f,0.254704f,0.00407642f},{0.037949f,0.252725f,-0.00324031f},{0.0402556f,0.254205f,0.00420461f}, -{0.0379543f,0.252228f,-0.00310144f},{0.0354539f,0.250081f,-0.0103481f},{0.0327551f,0.247763f,-0.0175217f}, -{0.0298594f,0.245276f,-0.0246083f},{0.0267689f,0.242622f,-0.0315939f},{0.0234865f,0.239802f,-0.038465f}, -{0.0163611f,0.233683f,-0.0518103f},{0.0125275f,0.23039f,-0.0582583f},{0.00852075f,0.226949f,-0.0645398f}, -{0.00434714f,0.223364f,-0.0706427f},{1.37117e-005f,0.219642f,-0.0765558f},{-0.00910166f,0.211813f,-0.0877701f}, -{-0.0138668f,0.20772f,-0.093052f},{-0.0187584f,0.203519f,-0.0981056f},{-0.0237669f,0.199217f,-0.102923f}, -{-0.0288825f,0.194824f,-0.107499f},{-0.050333f,0.177225f,-0.12407f},{-0.0448966f,0.18157f,-0.120026f}, -{-0.0448712f,0.181916f,-0.120499f},{-0.0393947f,0.185795f,-0.1159f},{-0.0447704f,0.181178f,-0.119717f}, -{-0.0502121f,0.176504f,-0.123274f},{-0.0557093f,0.171783f,-0.126571f},{-0.0612515f,0.167022f,-0.129604f}, -{-0.0668286f,0.162232f,-0.132375f},{-0.0724302f,0.157421f,-0.134885f},{-0.0836679f,0.147769f,-0.139127f}, -{-0.0894762f,0.143282f,-0.141206f},{-0.10047f,0.133338f,-0.143596f},{-0.117002f,0.11914f,-0.145907f}, -{-0.122417f,0.114489f,-0.146226f},{0.0544208f,0.266371f,0.0775529f},{0.0526389f,0.265342f,0.0776737f}, -{0.0508832f,0.263834f,0.0558501f},{0.0499391f,0.263023f,0.0484819f},{0.0488086f,0.262052f,0.0410845f}, -{0.0474881f,0.260918f,0.0336694f},{0.0459745f,0.259618f,0.0262484f},{0.0442655f,0.25815f,0.018834f}, -{0.0423589f,0.256512f,0.011439f},{0.035445f,0.250574f,-0.0104976f},{0.0356495f,0.251073f,-0.0107259f}, -{0.0329408f,0.248747f,-0.017926f},{0.0327422f,0.248253f,-0.0176816f},{0.0298423f,0.245762f,-0.0247786f}, -{0.0267473f,0.243104f,-0.0317744f},{0.02346f,0.24028f,-0.0386556f},{0.00861687f,0.227856f,-0.0651178f}, -{0.00896809f,0.228157f,-0.065521f},{0.0047683f,0.22455f,-0.0716622f},{0.0124851f,0.230854f,-0.0584778f}, -{0.00847247f,0.227408f,-0.0647685f},{0.00429275f,0.223818f,-0.0708804f},{-4.70058e-005f,0.220091f,-0.0768021f}, -{-0.0187631f,0.20434f,-0.0988077f},{-0.0184822f,0.204581f,-0.0992973f},{-0.0235221f,0.200252f,-0.104145f}, -{-0.0139479f,0.208152f,-0.0933224f},{-0.0188466f,0.203944f,-0.0983834f},{-0.0238624f,0.199636f,-0.103208f}, -{-0.0289854f,0.195236f,-0.10779f},{-0.0342058f,0.190752f,-0.112123f},{-0.0395131f,0.186194f,-0.116203f}, -{-0.0503463f,0.17689f,-0.123589f},{-0.0558515f,0.172161f,-0.12689f},{-0.0614018f,0.167394f,-0.129928f}, -{-0.066987f,0.162597f,-0.132703f},{-0.0725969f,0.157779f,-0.135216f},{-0.0782214f,0.152948f,-0.137469f}, -{-0.083851f,0.148113f,-0.139465f},{-0.100678f,0.133661f,-0.14394f},{-0.122791f,0.114992f,-0.147719f}, -{-0.117234f,0.119441f,-0.146255f},{-0.122656f,0.114784f,-0.146574f},{0.0511222f,0.264363f,0.0557698f}, -{0.0528818f,0.265874f,0.077642f},{0.050176f,0.26355f,0.0483851f},{0.0506339f,0.263943f,0.0482734f}, -{0.049498f,0.262968f,0.0408405f},{0.0490429f,0.262577f,0.0409712f},{0.0477195f,0.26144f,0.0335395f}, -{0.0462026f,0.260137f,0.026102f},{0.0444897f,0.258666f,0.0186711f},{0.0425789f,0.257025f,0.0112596f}, -{0.040469f,0.255213f,0.00388058f},{0.0381592f,0.253229f,-0.00345247f},{0.0300343f,0.246251f,-0.0250388f}, -{0.0304405f,0.2466f,-0.025339f},{0.0273306f,0.243929f,-0.0323684f},{0.0269324f,0.243587f,-0.0320502f}, -{0.0236379f,0.240757f,-0.0389468f},{0.0201544f,0.237765f,-0.0457149f},{0.0164862f,0.234614f,-0.0523413f}, -{0.0126385f,0.23131f,-0.0588132f},{0.00442784f,0.224258f,-0.0712434f},{7.83923e-005f,0.220522f,-0.0771783f}, -{-0.00442383f,0.216655f,-0.0829118f},{-0.00907067f,0.212664f,-0.088434f},{-0.0138535f,0.208556f,-0.0937354f}, -{-0.0237901f,0.200022f,-0.103643f},{-0.0289246f,0.195612f,-0.108235f},{-0.0341565f,0.191118f,-0.112578f}, -{-0.0394757f,0.18655f,-0.116668f},{-0.0558505f,0.172486f,-0.127378f},{-0.0556648f,0.172645f,-0.127941f}, -{-0.0612418f,0.167855f,-0.130993f},{-0.0614133f,0.167708f,-0.130423f},{-0.0670109f,0.1629f,-0.133204f}, -{-0.0726333f,0.158071f,-0.135723f},{-0.0782704f,0.15323f,-0.137981f},{-0.0839125f,0.148384f,-0.139981f}, -{-0.0895502f,0.143542f,-0.141725f},{-0.0951746f,0.138711f,-0.143219f},{-0.100777f,0.1339f,-0.144466f}, -{-0.122804f,0.11498f,-0.147106f},{0.0529343f,0.265919f,0.0703531f},{0.0523479f,0.265415f,0.0630404f}, -{0.0533467f,0.266273f,0.0776054f},{0.0515825f,0.264758f,0.055677f},{0.0481711f,0.261828f,0.0333897f}, -{0.0466503f,0.260522f,0.0259331f},{0.044933f,0.259047f,0.0184831f},{0.0454772f,0.259191f,0.0183202f}, -{0.0435573f,0.257542f,0.0108731f},{0.0430173f,0.257402f,0.0110526f},{0.040902f,0.255585f,0.00365461f}, -{0.0385862f,0.253596f,-0.00369726f},{0.0360702f,0.251435f,-0.0109894f},{0.0333545f,0.249102f,-0.0182079f}, -{0.0240277f,0.241092f,-0.0392827f},{0.0245255f,0.241196f,-0.0395738f},{0.0210253f,0.238189f,-0.0463744f}, -{0.0205352f,0.238092f,-0.0460682f},{0.0168576f,0.234933f,-0.0527117f},{0.013f,0.23162f,-0.0592001f}, -{0.00040769f,0.220805f,-0.0776124f},{0.000853084f,0.220864f,-0.0779886f},{-0.00367072f,0.216978f,-0.0837496f}, -{-0.00410608f,0.216928f,-0.0833607f},{-0.00876485f,0.212927f,-0.088897f},{-0.0135599f,0.208808f,-0.094212f}, -{-0.0286697f,0.195831f,-0.108749f},{-0.0282889f,0.195834f,-0.109195f},{-0.0335459f,0.191319f,-0.113558f}, -{-0.0339151f,0.191326f,-0.113103f},{-0.0392479f,0.186745f,-0.117203f},{-0.0446573f,0.182099f,-0.121044f}, -{-0.0501331f,0.177396f,-0.124624f},{-0.0668538f,0.163035f,-0.133782f},{-0.0724906f,0.158194f,-0.136307f}, -{-0.072207f,0.158114f,-0.136814f},{-0.0778712f,0.153249f,-0.139083f},{-0.0781422f,0.15334f,-0.138571f}, -{-0.0837988f,0.148482f,-0.140576f},{-0.0894511f,0.143627f,-0.142325f},{-0.0950898f,0.138784f,-0.143823f}, -{-0.100706f,0.13396f,-0.145073f},{-0.106292f,0.129162f,-0.146082f},{0.0534963f,0.266078f,0.0703053f}, -{0.0529085f,0.265573f,0.0629764f},{0.0539095f,0.266433f,0.0775737f},{0.0521415f,0.264914f,0.0555966f}, -{0.0511908f,0.264098f,0.0481766f},{0.0500523f,0.26312f,0.0407271f},{0.0487225f,0.261978f,0.0332599f}, -{0.0471983f,0.260669f,0.0257867f},{0.0414372f,0.255721f,0.00345877f},{0.0396062f,0.253647f,-0.00404829f}, -{0.0391164f,0.253727f,-0.00390942f},{0.0365947f,0.251562f,-0.0112177f},{0.033873f,0.249224f,-0.0184523f}, -{0.0309526f,0.246716f,-0.0255992f},{0.0278358f,0.244039f,-0.0326442f},{0.0177978f,0.234916f,-0.0532427f}, -{0.0173395f,0.235024f,-0.0530326f},{0.0134733f,0.231703f,-0.0595354f},{0.00943248f,0.228232f,-0.0658703f}, -{0.00522337f,0.224617f,-0.0720252f},{-0.0079188f,0.212829f,-0.0895609f},{-0.00833983f,0.212968f,-0.0892982f}, -{-0.0131455f,0.208841f,-0.0946251f},{-0.0180787f,0.204604f,-0.0997217f},{-0.0231298f,0.200265f,-0.10458f}, -{-0.0385138f,0.186551f,-0.117971f},{-0.0388905f,0.186729f,-0.117667f},{-0.044312f,0.182072f,-0.121517f}, -{-0.0497999f,0.177359f,-0.125105f},{-0.0553439f,0.172597f,-0.128429f},{-0.0609333f,0.167797f,-0.131488f}, -{-0.0665577f,0.162966f,-0.134283f},{-0.0835403f,0.14838f,-0.141092f},{-0.0889013f,0.143275f,-0.143185f}, -{-0.0892051f,0.143514f,-0.142845f},{-0.0948564f,0.138661f,-0.144346f},{-0.100485f,0.133826f,-0.145599f}, -{-0.106084f,0.129018f,-0.14661f},{-0.117158f,0.119507f,-0.147929f},{0.0547929f,0.266634f,0.0918925f}, -{0.0540069f,0.266016f,0.070274f},{0.0534183f,0.26551f,0.0629344f},{0.0526502f,0.264851f,0.055544f}, -{0.0516981f,0.264033f,0.0481132f},{0.050558f,0.263054f,0.040653f},{0.0492262f,0.26191f,0.0331749f}, -{0.0476998f,0.260599f,0.0256909f},{0.0459762f,0.259118f,0.0182135f},{0.0440535f,0.257467f,0.0107557f}, -{0.0419304f,0.255643f,0.00333058f},{0.037453f,0.251278f,-0.0114393f},{0.0352296f,0.248914f,-0.0180677f}, -{0.0347255f,0.248935f,-0.0186894f},{0.0370809f,0.251478f,-0.0113672f},{0.0343552f,0.249137f,-0.0186123f}, -{0.0314306f,0.246625f,-0.0257695f},{0.0283092f,0.243945f,-0.0328247f},{0.0249941f,0.241097f,-0.0397644f}, -{0.0214889f,0.238087f,-0.0465748f},{0.013926f,0.231591f,-0.0597549f},{0.014282f,0.231377f,-0.0598609f}, -{0.00987926f,0.228115f,-0.066099f},{0.00566404f,0.224495f,-0.0722628f},{0.00128743f,0.220736f,-0.0782348f}, -{-0.00324293f,0.216845f,-0.0840042f},{-0.0123941f,0.208465f,-0.0950259f},{-0.0164425f,0.204534f,-0.0995152f}, -{-0.0173378f,0.204219f,-0.100133f},{-0.0127315f,0.208695f,-0.0948954f},{-0.0176718f,0.204452f,-0.0999994f}, -{-0.0227302f,0.200108f,-0.104865f},{-0.0278968f,0.19567f,-0.109486f},{-0.0331614f,0.191149f,-0.113856f}, -{-0.0439431f,0.181888f,-0.121826f},{-0.0491273f,0.176916f,-0.125571f},{-0.049439f,0.177168f,-0.125419f}, -{-0.054991f,0.1724f,-0.128748f},{-0.0605885f,0.167592f,-0.131812f},{-0.0662211f,0.162754f,-0.134611f}, -{-0.0718786f,0.157895f,-0.137145f},{-0.0775509f,0.153023f,-0.139417f},{-0.0832283f,0.148147f,-0.14143f}, -{-0.0945608f,0.138414f,-0.144688f},{-0.100198f,0.133572f,-0.145943f},{-0.105804f,0.128757f,-0.146956f}, -{0.0543909f,0.265826f,0.0702589f},{0.0538019f,0.26532f,0.0629142f},{0.0530333f,0.264659f,0.0555186f}, -{0.0520805f,0.263841f,0.0480826f},{0.0509396f,0.262861f,0.0406172f},{0.0496069f,0.261717f,0.0331338f}, -{0.0480794f,0.260405f,0.0256447f},{0.0463547f,0.258923f,0.0181621f},{0.0444306f,0.257271f,0.010699f}, -{0.042306f,0.255446f,0.00326873f},{0.0399801f,0.253448f,-0.0041153f},{0.0317988f,0.246422f,-0.0258517f}, -{0.0286753f,0.243739f,-0.0329118f},{0.0253579f,0.24089f,-0.0398563f},{0.0218502f,0.237877f,-0.0466715f}, -{0.0181565f,0.234704f,-0.0533441f},{0.0179111f,0.23404f,-0.0542301f},{0.0102325f,0.227899f,-0.0662094f}, -{0.0060143f,0.224276f,-0.0723775f},{0.00163463f,0.220514f,-0.0783537f},{-0.0028989f,0.21662f,-0.0841271f}, -{-0.00757805f,0.212602f,-0.0896876f},{-0.0223998f,0.199871f,-0.105003f},{-0.02757f,0.195431f,-0.109627f}, -{-0.0328383f,0.190906f,-0.114f},{-0.0381944f,0.186306f,-0.118117f},{-0.0436275f,0.181639f,-0.121975f}, -{-0.0438755f,0.180973f,-0.122344f},{-0.0546831f,0.172144f,-0.128902f},{-0.0602845f,0.167333f,-0.131968f}, -{-0.0659211f,0.162492f,-0.134769f},{-0.0715825f,0.157629f,-0.137305f},{-0.0772588f,0.152754f,-0.139579f}, -{-0.0829402f,0.147874f,-0.141593f},{-0.0886171f,0.142999f,-0.143349f},{-0.0942805f,0.138134f,-0.144853f}, -{-0.0999216f,0.133289f,-0.146109f},{-0.105532f,0.128471f,-0.147123f},{-0.111104f,0.123685f,-0.147899f}, -{-0.11663f,0.118939f,-0.148445f},{0.0546653f,0.265607f,0.0705096f},{0.0541047f,0.265126f,0.0634113f}, -{0.0533848f,0.264508f,0.056338f},{0.0525062f,0.263753f,0.0492957f},{0.0514696f,0.262863f,0.042291f}, -{0.0502761f,0.261838f,0.0353299f},{0.0489266f,0.260679f,0.0284186f},{0.0474223f,0.259387f,0.0215629f}, -{0.0457645f,0.257963f,0.0147688f},{0.0439548f,0.256408f,0.00804257f},{0.0419946f,0.254725f,0.00139006f}, -{0.0398858f,0.252914f,-0.00518291f},{0.0376301f,0.250976f,-0.0116708f},{0.0326863f,0.24673f,-0.024368f}, -{0.0300025f,0.244425f,-0.0305661f},{0.0271806f,0.242001f,-0.0366566f},{0.0242229f,0.239461f,-0.0426344f}, -{0.0211322f,0.236806f,-0.0484939f},{0.0145625f,0.231164f,-0.0598379f},{0.0110894f,0.228181f,-0.0653124f}, -{0.00749453f,0.225093f,-0.0706491f},{0.00378138f,0.221904f,-0.0758429f},{-4.68637e-005f,0.218616f,-0.0808893f}, -{-0.00398685f,0.215232f,-0.0857839f},{-0.00803512f,0.211755f,-0.0905225f},{-0.0121883f,0.208188f,-0.095101f}, -{-0.020794f,0.200797f,-0.103761f},{-0.025239f,0.196979f,-0.107835f},{-0.0297737f,0.193084f,-0.111734f}, -{-0.0343942f,0.189116f,-0.115454f},{-0.0390962f,0.185078f,-0.118992f},{-0.0487282f,0.176805f,-0.125509f}, -{-0.0536499f,0.172578f,-0.128482f},{-0.0586363f,0.168295f,-0.131262f},{-0.063683f,0.16396f,-0.133846f}, -{-0.0687854f,0.159578f,-0.136231f},{-0.0739393f,0.155151f,-0.138417f},{-0.0791401f,0.150685f,-0.1404f}, -{-0.0843832f,0.146181f,-0.142179f},{-0.089664f,0.141646f,-0.143752f},{-0.0949777f,0.137082f,-0.145118f}, -{-0.10032f,0.132494f,-0.146276f},{-0.105686f,0.127885f,-0.147225f},{-0.111071f,0.12326f,-0.147964f}, -{-0.11647f,0.118623f,-0.148493f},{0.0258064f,0.240367f,-0.0398563f},{0.0222987f,0.237355f,-0.0466715f}, -{0.0147777f,0.22955f,-0.0592001f},{0.0108902f,0.226535f,-0.0658703f},{0.0149311f,0.230006f,-0.0595354f}, -{0.0322473f,0.245899f,-0.0258517f},{0.0291238f,0.243217f,-0.0329118f},{0.0379016f,0.250756f,-0.0114393f}, -{0.035174f,0.248413f,-0.0186894f},{0.0404286f,0.252926f,-0.0041153f},{0.0427545f,0.254924f,0.00326873f}, -{0.0448791f,0.256749f,0.010699f},{0.0380524f,0.249864f,-0.0112177f},{0.0380435f,0.250358f,-0.0113672f}, -{0.0405741f,0.25203f,-0.00390942f},{0.0468032f,0.258401f,0.0181621f},{0.048528f,0.259882f,0.0256447f}, -{0.0500554f,0.261194f,0.0331338f},{0.0513881f,0.262339f,0.0406172f},{0.052529f,0.263319f,0.0480826f}, -{0.0534818f,0.264137f,0.0555186f},{0.0542505f,0.264797f,0.0629142f},{0.0548395f,0.265303f,0.0702589f}, -{0.0549696f,0.264895f,0.070274f},{0.054381f,0.264389f,0.0629344f},{0.0534428f,0.264104f,0.0848373f}, -{0.0538273f,0.263914f,0.0848323f},{0.0543389f,0.263852f,0.084822f},{0.0542202f,0.263922f,0.0918925f}, -{0.0535408f,0.26416f,0.0918925f},{0.053201f,0.263896f,0.0777045f},{0.0527915f,0.263544f,0.0705025f}, -{0.0531755f,0.263354f,0.0704874f},{0.054954f,0.264381f,0.0703053f},{0.0543662f,0.263876f,0.0629764f}, -{0.0541256f,0.263346f,0.0630404f},{0.0535992f,0.263217f,0.0555966f},{0.054712f,0.263849f,0.0703531f}, -{0.0552536f,0.265659f,0.0775429f},{0.0557203f,0.26521f,0.0918925f},{0.0556112f,0.264945f,0.0847723f}, -{0.0556278f,0.26546f,0.084762f},{0.0556436f,0.264849f,0.0918925f},{0.0553678f,0.264412f,0.084788f}, -{0.0554769f,0.264524f,0.0918925f},{0.0557001f,0.26557f,0.0918925f},{0.0554981f,0.265869f,0.084757f}, -{0.0555879f,0.265918f,0.0918925f},{0.0549023f,0.264013f,0.0848062f},{0.0545795f,0.263942f,0.0918925f}, -{0.018605f,0.234182f,-0.0533441f},{0.0147305f,0.230855f,-0.0598609f},{0.010681f,0.227376f,-0.0662094f}, -{0.00646282f,0.223754f,-0.0723775f},{0.00208315f,0.219992f,-0.0783537f},{-0.00245038f,0.216098f,-0.0841271f}, -{-0.0117689f,0.207575f,-0.0948954f},{-0.00688212f,0.211271f,-0.0892982f},{-0.0116878f,0.207143f,-0.0946251f}, -{-0.00712952f,0.212079f,-0.0896876f},{-0.0119456f,0.207943f,-0.0950259f},{-0.0168893f,0.203697f,-0.100133f}, -{-0.0219512f,0.199349f,-0.105003f},{-0.0271214f,0.194909f,-0.109627f},{-0.0323898f,0.190384f,-0.114f}, -{-0.0377459f,0.185784f,-0.118117f},{-0.0483422f,0.175662f,-0.125105f},{-0.0483555f,0.175327f,-0.124624f}, -{-0.0538862f,0.1709f,-0.128429f},{-0.043179f,0.181117f,-0.121975f},{-0.0486787f,0.176393f,-0.125571f}, -{-0.0542346f,0.171622f,-0.128902f},{-0.059836f,0.166811f,-0.131968f},{-0.0654725f,0.16197f,-0.134769f}, -{-0.071134f,0.157107f,-0.137305f},{-0.0768103f,0.152232f,-0.139579f},{-0.0824916f,0.147352f,-0.141593f}, -{-0.0879387f,0.142154f,-0.143185f},{-0.0881686f,0.142476f,-0.143349f},{-0.0822657f,0.147026f,-0.14143f}, -{-0.093832f,0.137612f,-0.144853f},{-0.105084f,0.127948f,-0.147123f},{-0.0992353f,0.132451f,-0.145943f}, -{-0.104842f,0.127636f,-0.146956f},{-0.110062f,0.122328f,-0.146855f},{-0.110104f,0.122292f,-0.146244f}, -{-0.115564f,0.117602f,-0.147398f},{-0.0933121f,0.136714f,-0.143823f},{-0.0989286f,0.13189f,-0.145073f}, -{-0.0990277f,0.132129f,-0.145599f},{-0.110572f,0.122715f,-0.145367f},{-0.1103f,0.122447f,-0.145714f}, -{-0.105059f,0.12745f,-0.144599f},{-0.121454f,0.113368f,-0.146226f},{-0.126687f,0.108624f,-0.146474f}, -{-0.121199f,0.113087f,-0.146574f},{-0.1157f,0.117809f,-0.147929f},{-0.110186f,0.122545f,-0.147385f}, -{-0.126873f,0.108841f,-0.146297f},{-0.121715f,0.113664f,-0.146058f},{-0.127073f,0.109073f,-0.146158f}, -{-0.104626f,0.12732f,-0.14661f},{-0.104515f,0.127092f,-0.146082f},{-0.115932f,0.118111f,-0.148277f}, -{-0.11041f,0.122854f,-0.147732f},{-0.0994731f,0.132767f,-0.146109f},{-0.110655f,0.123163f,-0.147899f}, -{-0.116181f,0.118417f,-0.148445f},{-0.121654f,0.113716f,-0.148767f},{-0.127073f,0.109074f,-0.148876f}, -{0.0549276f,0.264054f,0.0918925f},{0.0553834f,0.26525f,0.0775529f},{0.0536128f,0.26373f,0.055544f}, -{0.0526607f,0.262912f,0.0481132f},{0.0515206f,0.261933f,0.040653f},{0.0501889f,0.260789f,0.0331749f}, -{0.0486625f,0.259478f,0.0256909f},{0.0469389f,0.257998f,0.0182135f},{0.0450162f,0.256346f,0.0107557f}, -{0.042893f,0.254523f,0.00333058f},{0.0405688f,0.252526f,-0.00404829f},{0.0353178f,0.248016f,-0.0186123f}, -{0.0323932f,0.245505f,-0.0257695f},{0.0292719f,0.242824f,-0.0328247f},{0.0259568f,0.239976f,-0.0397644f}, -{0.0224515f,0.236966f,-0.0465748f},{0.0187604f,0.233796f,-0.0532427f},{0.0148886f,0.23047f,-0.0597549f}, -{0.0108419f,0.226995f,-0.066099f},{0.00662668f,0.223374f,-0.0722628f},{0.00225007f,0.219615f,-0.0782348f}, -{-0.00228029f,0.215724f,-0.0840042f},{-0.00695617f,0.211708f,-0.0895609f},{-0.0167092f,0.203331f,-0.0999994f}, -{-0.0217676f,0.198987f,-0.104865f},{-0.0269342f,0.194549f,-0.109486f},{-0.0321988f,0.190028f,-0.113856f}, -{-0.0375512f,0.185431f,-0.117971f},{-0.0429805f,0.180768f,-0.121826f},{-0.0484764f,0.176047f,-0.125419f}, -{-0.0540283f,0.171279f,-0.128748f},{-0.0596258f,0.166471f,-0.131812f},{-0.0652585f,0.161633f,-0.134611f}, -{-0.070916f,0.156774f,-0.137145f},{-0.0765883f,0.151902f,-0.139417f},{-0.0935981f,0.137293f,-0.144688f}, -{-0.0933987f,0.136964f,-0.144346f},{-0.121401f,0.113414f,-0.148599f},{-0.12687f,0.108837f,-0.148751f}, -{0.0553672f,0.264736f,0.0775737f},{0.0526485f,0.262401f,0.0481766f},{0.05151f,0.261423f,0.0407271f}, -{0.0501802f,0.260281f,0.0332599f},{0.048656f,0.258972f,0.0257867f},{0.0469349f,0.257493f,0.0183202f}, -{0.045015f,0.255844f,0.0108731f},{0.0428949f,0.254024f,0.00345877f},{0.0324103f,0.245018f,-0.0255992f}, -{0.0353307f,0.247527f,-0.0184523f},{0.0351321f,0.247032f,-0.0182079f},{0.0292935f,0.242341f,-0.0326442f}, -{0.0259832f,0.239498f,-0.0395738f},{0.022483f,0.236492f,-0.0463744f},{0.0187972f,0.233326f,-0.0530326f}, -{0.00668107f,0.22292f,-0.0720252f},{0.00231079f,0.219167f,-0.0779886f},{-0.00221301f,0.215281f,-0.0837496f}, -{-0.0217444f,0.198182f,-0.104145f},{-0.0220124f,0.197952f,-0.103643f},{-0.0268921f,0.193761f,-0.108749f}, -{-0.016621f,0.202906f,-0.0997217f},{-0.0216721f,0.198568f,-0.10458f},{-0.0268312f,0.194137f,-0.109195f}, -{-0.0320882f,0.189622f,-0.113558f},{-0.0374328f,0.185032f,-0.117667f},{-0.0428543f,0.180375f,-0.121517f}, -{-0.0594756f,0.166099f,-0.131488f},{-0.0651f,0.161269f,-0.134283f},{-0.0707493f,0.156417f,-0.136814f}, -{-0.0764135f,0.151552f,-0.139083f},{-0.0820826f,0.146683f,-0.141092f},{-0.0877474f,0.141817f,-0.142845f}, -{-0.126387f,0.108276f,-0.147687f},{-0.121013f,0.112922f,-0.147719f},{-0.121027f,0.112911f,-0.147106f}, -{-0.121161f,0.113119f,-0.148251f},{-0.12669f,0.108628f,-0.148558f},{0.0552371f,0.264255f,0.0918925f}, -{0.0551243f,0.264203f,0.0776054f},{0.0533602f,0.262688f,0.055677f},{0.0524116f,0.261874f,0.0482734f}, -{0.0494972f,0.25937f,0.0335395f},{0.048428f,0.258452f,0.0259331f},{0.0499488f,0.259758f,0.0333897f}, -{0.0512756f,0.260898f,0.0408405f},{0.0467107f,0.256977f,0.0184831f},{0.044795f,0.255332f,0.0110526f}, -{0.0426797f,0.253515f,0.00365461f},{0.0403639f,0.251526f,-0.00369726f},{0.0378479f,0.249365f,-0.0109894f}, -{0.0287101f,0.241517f,-0.0320502f},{0.0258054f,0.239022f,-0.0392827f},{0.0291083f,0.241859f,-0.0323684f}, -{0.0322182f,0.24453f,-0.025339f},{0.0223129f,0.236022f,-0.0460682f},{0.0186353f,0.232864f,-0.0527117f}, -{0.00620553f,0.222188f,-0.0712434f},{0.00218538f,0.218735f,-0.0776124f},{0.006546f,0.22248f,-0.0716622f}, -{0.0107458f,0.226088f,-0.065521f},{-0.00232839f,0.214858f,-0.0833607f},{-0.00698716f,0.210857f,-0.088897f}, -{-0.0117822f,0.206739f,-0.094212f},{-0.0167045f,0.202511f,-0.0992973f},{-0.0321374f,0.189256f,-0.113103f}, -{-0.0374702f,0.184676f,-0.117203f},{-0.0428796f,0.18003f,-0.121044f},{-0.0596356f,0.165638f,-0.130423f}, -{-0.0650762f,0.160965f,-0.133782f},{-0.0594641f,0.165786f,-0.130993f},{-0.0538871f,0.170576f,-0.127941f}, -{-0.0707129f,0.156124f,-0.136307f},{-0.0763645f,0.15127f,-0.138571f},{-0.0820211f,0.146412f,-0.140576f}, -{-0.0876734f,0.141557f,-0.142325f},{-0.115776f,0.117744f,-0.146255f},{-0.104571f,0.127044f,-0.145472f}, -{-0.12644f,0.108337f,-0.148015f},{-0.126544f,0.108458f,-0.14831f},{0.0542482f,0.263451f,0.0704083f}, -{0.0546595f,0.263804f,0.077642f},{0.0536632f,0.262949f,0.0631143f},{0.0528999f,0.262293f,0.0557698f}, -{0.0519537f,0.26148f,0.0483851f},{0.0508206f,0.260507f,0.0409712f},{0.0479802f,0.258067f,0.026102f}, -{0.0422467f,0.253143f,0.00388058f},{0.0443566f,0.254955f,0.0112596f},{0.0438167f,0.254815f,0.011439f}, -{0.0462674f,0.256596f,0.0186711f},{0.0399369f,0.251159f,-0.00345247f},{0.0374272f,0.249004f,-0.0107259f}, -{0.0347185f,0.246677f,-0.017926f},{0.031812f,0.244181f,-0.0250388f},{0.0173238f,0.232562f,-0.0518103f}, -{0.017782f,0.232454f,-0.0520204f},{0.0209784f,0.235701f,-0.0452083f},{0.0254156f,0.238687f,-0.0389468f}, -{0.0219321f,0.235695f,-0.0457149f},{0.0182639f,0.232545f,-0.0523413f},{0.0144162f,0.22924f,-0.0588132f}, -{0.0103946f,0.225786f,-0.0651178f},{-0.00813902f,0.210692f,-0.0877701f},{-0.00771801f,0.210553f,-0.0880327f}, -{-0.00350929f,0.214669f,-0.0822683f},{0.00185609f,0.218452f,-0.0771783f},{-0.00264613f,0.214585f,-0.0829118f}, -{-0.00729298f,0.210594f,-0.088434f},{-0.0120758f,0.206487f,-0.0937354f},{-0.0169854f,0.20227f,-0.0988077f}, -{-0.037698f,0.18448f,-0.116668f},{-0.0323788f,0.189049f,-0.112578f},{-0.0327481f,0.189055f,-0.112123f}, -{-0.0271469f,0.193542f,-0.108235f},{-0.0430935f,0.179846f,-0.120499f},{-0.0485553f,0.175155f,-0.12407f}, -{-0.0540728f,0.170416f,-0.127378f},{-0.0652332f,0.160831f,-0.133204f},{-0.0821348f,0.146314f,-0.139981f}, -{-0.0764927f,0.15116f,-0.137981f},{-0.0767637f,0.151251f,-0.137469f},{-0.0708556f,0.156002f,-0.135723f}, -{-0.0877726f,0.141472f,-0.141725f},{-0.0933968f,0.136641f,-0.143219f},{-0.098999f,0.13183f,-0.144466f}, -{-0.104779f,0.127189f,-0.144944f},{-0.115592f,0.117579f,-0.146786f},{0.0536862f,0.263292f,0.0704561f}, -{0.0540966f,0.263644f,0.0776737f},{0.0531026f,0.262791f,0.0631783f},{0.0523409f,0.262136f,0.0558501f}, -{0.0513968f,0.261326f,0.0484819f},{0.0502663f,0.260355f,0.0410845f},{0.0489458f,0.25922f,0.0336694f}, -{0.0474322f,0.257921f,0.0262484f},{0.0457232f,0.256453f,0.018834f},{0.0412182f,0.253084f,0.00420461f}, -{0.0389169f,0.251108f,-0.00310144f},{0.0394067f,0.251028f,-0.00324031f},{0.0417114f,0.253007f,0.00407642f}, -{0.0369027f,0.248877f,-0.0104976f},{0.0342f,0.246556f,-0.0176816f},{0.0313f,0.244065f,-0.0247786f}, -{0.028205f,0.241407f,-0.0317744f},{0.0249178f,0.238583f,-0.0386556f},{0.021442f,0.235598f,-0.0454087f}, -{0.0139428f,0.229157f,-0.0584778f},{0.00993018f,0.225711f,-0.0647685f},{0.00575046f,0.222121f,-0.0708804f}, -{0.0014107f,0.218393f,-0.0768021f},{-0.0030815f,0.214535f,-0.0825229f},{-0.0124902f,0.206454f,-0.0933224f}, -{-0.0173889f,0.202247f,-0.0983834f},{-0.0224047f,0.197939f,-0.103208f},{-0.0275277f,0.193539f,-0.10779f}, -{-0.0384321f,0.184674f,-0.1159f},{-0.0438078f,0.180057f,-0.119717f},{-0.0434389f,0.179873f,-0.120026f}, -{-0.0380553f,0.184497f,-0.116203f},{-0.0488885f,0.175192f,-0.123589f},{-0.0543937f,0.170464f,-0.12689f}, -{-0.0599441f,0.165697f,-0.129928f},{-0.0655293f,0.1609f,-0.132703f},{-0.0711392f,0.156082f,-0.135216f}, -{-0.0823933f,0.146416f,-0.139465f},{-0.0883223f,0.141824f,-0.140865f},{-0.0939259f,0.137011f,-0.142353f}, -{-0.0936303f,0.136765f,-0.142696f},{-0.0880185f,0.141584f,-0.141206f},{-0.09922f,0.131964f,-0.14394f}, -{-0.126439f,0.108336f,-0.147023f},{-0.126387f,0.108275f,-0.147351f},{0.0538591f,0.263998f,0.0918925f}, -{0.0535853f,0.263706f,0.0776945f},{0.0525928f,0.262854f,0.0632202f},{0.0518322f,0.2622f,0.0559028f}, -{0.0522092f,0.263044f,0.0632405f},{0.0508895f,0.261391f,0.0485453f},{0.0497606f,0.260421f,0.0411587f}, -{0.048442f,0.259289f,0.0337544f},{0.0469307f,0.257991f,0.0263442f},{0.0452241f,0.256525f,0.0189407f}, -{0.0433204f,0.25489f,0.0115564f},{0.0333475f,0.246844f,-0.0174445f},{0.0360443f,0.249161f,-0.010276f}, -{0.0364165f,0.24896f,-0.0103481f},{0.0337177f,0.246642f,-0.0175217f},{0.030822f,0.244155f,-0.0246083f}, -{0.0277315f,0.241501f,-0.0315939f},{0.0244491f,0.238682f,-0.038465f},{0.0131342f,0.229483f,-0.0581524f}, -{0.0134902f,0.229269f,-0.0582583f},{0.016965f,0.232774f,-0.051709f},{0.00948339f,0.225828f,-0.0645398f}, -{0.00530978f,0.222243f,-0.0706427f},{0.00097635f,0.218521f,-0.0765558f},{-0.0132416f,0.20683f,-0.0929216f}, -{-0.0181297f,0.202631f,-0.0979716f},{-0.0129042f,0.206599f,-0.093052f},{-0.0177958f,0.202398f,-0.0981056f}, -{-0.0228042f,0.198097f,-0.102923f},{-0.0279198f,0.193703f,-0.107499f},{-0.0331325f,0.189226f,-0.111826f}, -{-0.0495612f,0.175636f,-0.123123f},{-0.0492495f,0.175383f,-0.123274f},{-0.0441234f,0.180306f,-0.119568f}, -{-0.0547466f,0.170662f,-0.126571f},{-0.0602889f,0.165902f,-0.129604f},{-0.0658659f,0.161112f,-0.132375f}, -{-0.0714676f,0.156301f,-0.134885f},{-0.0770839f,0.151477f,-0.137135f},{-0.0827053f,0.146649f,-0.139127f}, -{-0.0995074f,0.132218f,-0.143596f},{-0.116304f,0.118312f,-0.145739f},{-0.11084f,0.123004f,-0.145199f}, -{-0.116039f,0.118019f,-0.145907f},{-0.126541f,0.108454f,-0.146724f},{0.0514492f,0.262391f,0.0559281f}, -{0.0505071f,0.261582f,0.0485758f},{0.049379f,0.260613f,0.0411945f},{0.0480614f,0.259482f,0.0337954f}, -{0.0465511f,0.258185f,0.0263905f},{0.0448457f,0.25672f,0.0189921f},{0.0429433f,0.255086f,0.0116131f}, -{0.0408426f,0.253282f,0.00426646f},{0.038543f,0.251307f,-0.00303443f},{0.0304538f,0.244359f,-0.0245261f}, -{0.0273654f,0.241706f,-0.0315068f},{0.0240853f,0.238889f,-0.0383731f},{0.0206171f,0.23591f,-0.0451116f}, -{0.00913019f,0.226044f,-0.0644294f},{0.00495953f,0.222462f,-0.0705281f},{0.00062916f,0.218743f,-0.076437f}, -{-0.00385332f,0.214893f,-0.0821454f},{-0.00847979f,0.21092f,-0.0876434f},{-0.0231347f,0.198333f,-0.102786f}, -{-0.0282467f,0.193942f,-0.107358f},{-0.0334557f,0.189468f,-0.111682f},{-0.0387515f,0.18492f,-0.115753f}, -{-0.0550545f,0.170917f,-0.126416f},{-0.0605929f,0.166161f,-0.129448f},{-0.066166f,0.161374f,-0.132217f}, -{-0.0717637f,0.156566f,-0.134725f},{-0.0773761f,0.151746f,-0.136973f},{-0.0829935f,0.146921f,-0.138964f}, -{-0.0886065f,0.1421f,-0.140701f},{-0.0942061f,0.137291f,-0.142188f},{-0.0997837f,0.1325f,-0.14343f}, -{-0.105331f,0.127736f,-0.144432f},{-0.246242f,0.00568906f,-0.0892991f},{-0.241437f,0.00981657f,-0.0946258f}, -{-0.241022f,0.00984878f,-0.0942128f},{-0.221744f,0.0277507f,-0.114f},{-0.227012f,0.023226f,-0.109627f}, -{-0.216388f,0.0323507f,-0.118117f},{-0.210955f,0.0370173f,-0.121975f},{-0.205455f,0.0417412f,-0.125571f}, -{-0.199899f,0.0465131f,-0.128902f},{-0.194298f,0.0513242f,-0.131968f},{-0.188661f,0.0561654f,-0.134769f}, -{-0.205143f,0.0414889f,-0.125419f},{-0.199238f,0.0460598f,-0.128429f},{-0.204783f,0.041298f,-0.125105f}, -{-0.182999f,0.061028f,-0.137305f},{-0.177323f,0.0659033f,-0.139579f},{-0.171642f,0.0707829f,-0.141592f}, -{-0.160302f,0.0805227f,-0.144853f},{-0.165965f,0.0756586f,-0.143349f},{-0.154661f,0.0853677f,-0.146109f}, -{-0.14905f,0.0901863f,-0.147122f},{-0.143479f,0.0949717f,-0.147899f},{-0.132419f,0.10447f,-0.146057f}, -{-0.14321f,0.0946823f,-0.147731f},{-0.148778f,0.0899002f,-0.146955f},{-0.143294f,0.0951304f,-0.145199f}, -{-0.143048f,0.0948213f,-0.145366f},{-0.13783f,0.0998229f,-0.145739f},{-0.14829f,0.0894947f,-0.146081f}, -{-0.154097f,0.084831f,-0.145599f},{-0.148499f,0.0896393f,-0.14661f},{-0.131926f,0.103873f,-0.146574f}, -{-0.131778f,0.103676f,-0.147105f},{-0.132166f,0.104168f,-0.146225f},{-0.142939f,0.0944145f,-0.147384f}, -{-0.131792f,0.103664f,-0.147719f},{-0.13248f,0.104418f,-0.148767f},{-0.132219f,0.104122f,-0.148599f}, -{-0.137953f,0.0997176f,-0.148445f},{-0.131964f,0.10384f,-0.148251f},{-0.142742f,0.0942593f,-0.146855f}, -{-0.232183f,0.0187856f,-0.105003f},{-0.237244f,0.0144381f,-0.100134f},{-0.242188f,0.010192f,-0.0950266f}, -{-0.247004f,0.00605566f,-0.0896885f},{-0.251683f,0.00203683f,-0.0841281f},{-0.256217f,-0.00185696f,-0.0783547f}, -{-0.260596f,-0.00561864f,-0.0723786f},{-0.268508f,-0.0129341f,-0.059756f},{-0.264015f,-0.00957541f,-0.0658715f}, -{-0.268056f,-0.0130461f,-0.0595366f},{-0.264815f,-0.00924161f,-0.0662105f},{-0.268864f,-0.0127198f,-0.059862f}, -{-0.272739f,-0.0160476f,-0.053345f},{-0.276433f,-0.0192201f,-0.0466724f},{-0.279941f,-0.022233f,-0.039857f}, -{-0.283258f,-0.0250823f,-0.0329122f},{-0.286382f,-0.0277651f,-0.0258517f},{-0.291178f,-0.0329051f,-0.0112184f}, -{-0.290653f,-0.0327782f,-0.01099f},{-0.293699f,-0.0350709f,-0.00391029f},{-0.289308f,-0.0302787f,-0.0186898f}, -{-0.292036f,-0.0326214f,-0.0114399f},{-0.294563f,-0.0347919f,-0.00411618f},{-0.296889f,-0.0367896f,0.00326766f}, -{-0.299014f,-0.0386144f,0.0106978f},{-0.300938f,-0.040267f,0.0181608f},{-0.302663f,-0.0417484f,0.0256434f}, -{-0.30419f,-0.0430604f,0.0331326f},{-0.305141f,-0.0443974f,0.0406518f},{-0.305523f,-0.044205f,0.040616f}, -{-0.303809f,-0.0432535f,0.0331736f},{-0.306664f,-0.045185f,0.0480815f},{-0.308737f,-0.0479862f,0.0847721f}, -{-0.30793f,-0.0476169f,0.077605f},{-0.308173f,-0.0478259f,0.0847878f},{-0.306812f,-0.0463329f,0.0704555f}, -{-0.307054f,-0.0468645f,0.0704077f},{-0.306228f,-0.0458317f,0.0631775f},{-0.307233f,-0.0461944f,0.0555431f}, -{-0.308002f,-0.0468541f,0.0629336f},{-0.308385f,-0.0466635f,0.0629134f},{-0.306796f,-0.0458187f,0.0704868f}, -{-0.306213f,-0.0453183f,0.0632194f},{-0.307448f,-0.0463783f,0.0848321f},{-0.307515f,-0.0467654f,0.0918925f}, -{-0.307464f,-0.0468934f,0.0848218f},{-0.306931f,-0.0467592f,0.0630396f},{-0.308079f,-0.0474218f,0.0703047f}, -{-0.307492f,-0.046917f,0.0629755f},{-0.307577f,-0.0459696f,0.0848371f},{-0.307535f,-0.0464061f,0.0918925f}, -{-0.306166f,-0.0461019f,0.0556761f},{-0.306725f,-0.0462583f,0.0555957f},{-0.305217f,-0.0452871f,0.0482723f}, -{-0.307647f,-0.046058f,0.0918925f},{-0.307617f,-0.0460033f,0.0555177f},{-0.309388f,-0.047525f,0.0775425f}, -{-0.308974f,-0.0471693f,0.0702583f},{-0.30859f,-0.0473596f,0.0702734f},{-0.309633f,-0.0477349f,0.0847568f}, -{-0.137688f,0.0994249f,-0.148277f},{-0.154384f,0.0850849f,-0.145943f},{-0.160021f,0.0802434f,-0.144688f}, -{-0.165681f,0.0753827f,-0.143185f},{-0.171354f,0.0705103f,-0.141429f},{-0.177031f,0.0656341f,-0.139417f}, -{-0.182703f,0.0607622f,-0.137145f},{-0.188361f,0.055903f,-0.134611f},{-0.193994f,0.0510652f,-0.131812f}, -{-0.199591f,0.0462575f,-0.128748f},{-0.21064f,0.0367683f,-0.121826f},{-0.216069f,0.032105f,-0.117971f}, -{-0.221421f,0.0275082f,-0.113856f},{-0.226686f,0.0229866f,-0.109486f},{-0.231852f,0.0185493f,-0.104866f}, -{-0.23691f,0.0142048f,-0.1f},{-0.241851f,0.00996175f,-0.0948962f},{-0.246663f,0.00582826f,-0.0895618f}, -{-0.251339f,0.00181224f,-0.0840052f},{-0.25587f,-0.00207883f,-0.0782359f},{-0.260246f,-0.00583789f,-0.072264f}, -{-0.264462f,-0.00945834f,-0.0661002f},{-0.27238f,-0.0162596f,-0.0532437f},{-0.276071f,-0.0194299f,-0.0465757f}, -{-0.279577f,-0.0224406f,-0.039765f},{-0.282892f,-0.025288f,-0.0328251f},{-0.286013f,-0.0279689f,-0.0257695f}, -{-0.288938f,-0.0304808f,-0.0186126f},{-0.291664f,-0.0328218f,-0.0113678f},{-0.294189f,-0.0349908f,-0.00404916f}, -{-0.296513f,-0.0369871f,0.00332952f},{-0.298637f,-0.0388106f,0.0107545f},{-0.300559f,-0.0404621f,0.0182123f}, -{-0.302283f,-0.0419425f,0.0256896f},{-0.306281f,-0.0453766f,0.0481121f},{-0.305774f,-0.0454417f,0.0481755f}, -{-0.309248f,-0.0479248f,0.0847617f},{-0.309004f,-0.047715f,0.0775525f},{-0.309376f,-0.0479772f,0.0918925f}, -{-0.309694f,-0.0478162f,0.0918925f},{-0.137425f,0.0991502f,-0.147929f},{-0.159726f,0.0799965f,-0.144345f}, -{-0.165377f,0.0751428f,-0.142845f},{-0.171042f,0.0702775f,-0.141092f},{-0.176711f,0.0654083f,-0.139082f}, -{-0.182375f,0.0605435f,-0.136814f},{-0.188024f,0.0556914f,-0.134283f},{-0.193649f,0.0508605f,-0.131488f}, -{-0.215692f,0.0319277f,-0.117667f},{-0.210271f,0.0365843f,-0.121517f},{-0.209925f,0.0365573f,-0.121044f}, -{-0.221037f,0.0273376f,-0.113559f},{-0.226294f,0.0228226f,-0.109195f},{-0.231453f,0.0183917f,-0.104581f}, -{-0.236503f,0.0140535f,-0.0997223f},{-0.250911f,0.00167885f,-0.0837506f},{-0.255435f,-0.00220659f,-0.0779897f}, -{-0.259806f,-0.00596021f,-0.0720263f},{-0.275118f,-0.0194353f,-0.046069f},{-0.274737f,-0.0191082f,-0.0457157f}, -{-0.27861f,-0.022435f,-0.0392833f},{-0.271922f,-0.0163668f,-0.0530336f},{-0.275608f,-0.0195325f,-0.0463752f}, -{-0.279108f,-0.0225389f,-0.0395744f},{-0.282419f,-0.0253822f,-0.0326445f},{-0.285535f,-0.0280592f,-0.0255992f}, -{-0.288456f,-0.0305674f,-0.0184526f},{-0.29602f,-0.0370643f,0.00345771f},{-0.29814f,-0.0388852f,0.0108719f}, -{-0.30006f,-0.0405343f,0.0183189f},{-0.301781f,-0.0420125f,0.0257854f},{-0.303306f,-0.0433217f,0.0332586f}, -{-0.304636f,-0.0444639f,0.0407259f},{-0.308493f,-0.0477767f,0.0775733f},{-0.307518f,-0.0472628f,0.0703525f}, -{-0.309015f,-0.0480539f,0.0918925f},{-0.137241f,0.0989846f,-0.147398f},{-0.153876f,0.0846971f,-0.145073f}, -{-0.159492f,0.0798733f,-0.143822f},{-0.170669f,0.0702734f,-0.13998f},{-0.17644f,0.0653174f,-0.138571f}, -{-0.170783f,0.0701758f,-0.140576f},{-0.165131f,0.0750303f,-0.142325f},{-0.182091f,0.0604634f,-0.136307f}, -{-0.187728f,0.055622f,-0.133782f},{-0.19334f,0.0508018f,-0.130993f},{-0.198917f,0.0460117f,-0.127941f}, -{-0.204449f,0.0412605f,-0.124624f},{-0.220426f,0.0275383f,-0.112579f},{-0.225913f,0.022826f,-0.10875f}, -{-0.220668f,0.027331f,-0.113104f},{-0.215335f,0.031911f,-0.117203f},{-0.23106f,0.0184049f,-0.104146f}, -{-0.2361f,0.0140763f,-0.0992979f},{-0.250158f,0.00200198f,-0.0829128f},{-0.25499f,-0.00214776f,-0.0776135f}, -{-0.250476f,0.00172908f,-0.0833616f},{-0.245817f,0.00573041f,-0.0888979f},{-0.25935f,-0.00589306f,-0.0716633f}, -{-0.26355f,-0.00950025f,-0.0655221f},{-0.267582f,-0.0129633f,-0.0592012f},{-0.27144f,-0.0162766f,-0.0527127f}, -{-0.281913f,-0.025272f,-0.0323688f},{-0.285023f,-0.0279431f,-0.025339f},{-0.287937f,-0.0304458f,-0.0182083f}, -{-0.295052f,-0.0365564f,0.00387953f},{-0.2976f,-0.0387452f,0.0110514f},{-0.295485f,-0.0369283f,0.00365355f}, -{-0.293169f,-0.0349393f,-0.00369814f},{-0.299516f,-0.0403906f,0.0184819f},{-0.301233f,-0.0418655f,0.0259318f}, -{-0.302754f,-0.0431718f,0.0333884f},{-0.304081f,-0.0443114f,0.0408392f},{-0.306469f,-0.0463621f,0.0631135f}, -{-0.308656f,-0.0480337f,0.0918925f},{-0.142701f,0.0942953f,-0.146243f},{-0.137213f,0.0990084f,-0.146785f}, -{-0.148234f,0.0895429f,-0.145472f},{-0.153805f,0.0847575f,-0.144466f},{-0.159408f,0.079946f,-0.143218f}, -{-0.165032f,0.0751155f,-0.141725f},{-0.176312f,0.0654275f,-0.137981f},{-0.193169f,0.0509491f,-0.130423f}, -{-0.187571f,0.0557569f,-0.133204f},{-0.187595f,0.05606f,-0.132703f},{-0.181949f,0.0605859f,-0.135723f}, -{-0.198732f,0.0461712f,-0.127378f},{-0.204249f,0.0414322f,-0.12407f},{-0.209711f,0.036741f,-0.120499f}, -{-0.215107f,0.0321066f,-0.116668f},{-0.235824f,0.0151381f,-0.0981062f},{-0.235736f,0.014713f,-0.098384f}, -{-0.230815f,0.0194397f,-0.102924f},{-0.225658f,0.0230449f,-0.108236f},{-0.230792f,0.0186351f,-0.103644f}, -{-0.235819f,0.0143176f,-0.0988083f},{-0.240729f,0.0101009f,-0.0937362f},{-0.245511f,0.00599306f,-0.0884349f}, -{-0.263103f,-0.00829154f,-0.0645409f},{-0.263055f,-0.00875088f,-0.0647696f},{-0.258929f,-0.00470683f,-0.0706439f}, -{-0.25466f,-0.00186493f,-0.0771794f},{-0.25901f,-0.00560064f,-0.0712445f},{-0.263199f,-0.00919859f,-0.065119f}, -{-0.267221f,-0.0126528f,-0.0588143f},{-0.271069f,-0.0159576f,-0.0523423f},{-0.284617f,-0.0275942f,-0.0250388f}, -{-0.281515f,-0.02493f,-0.0320505f},{-0.28133f,-0.0244472f,-0.0317747f},{-0.278221f,-0.0221003f,-0.0389474f}, -{-0.287524f,-0.0300905f,-0.0179263f},{-0.290232f,-0.032417f,-0.0107265f},{-0.292742f,-0.0345725f,-0.00345334f}, -{-0.297162f,-0.0383686f,0.0112584f},{-0.302303f,-0.0427839f,0.0335382f},{-0.300786f,-0.041481f,0.0261007f}, -{-0.300558f,-0.0409614f,0.0262471f},{-0.299073f,-0.0400098f,0.0186698f},{-0.303626f,-0.0439206f,0.04097f}, -{-0.304759f,-0.0448938f,0.048384f},{-0.305705f,-0.0457065f,0.0557688f},{-0.307465f,-0.0472177f,0.0776416f}, -{-0.307708f,-0.0474261f,0.084806f},{-0.307998f,-0.0477204f,0.0918925f},{-0.308307f,-0.0479214f,0.0918925f}, -{-0.142824f,0.0945127f,-0.145713f},{-0.137349f,0.0992153f,-0.146254f},{-0.148345f,0.0897709f,-0.144944f}, -{-0.153904f,0.0849962f,-0.14394f},{-0.159494f,0.0801954f,-0.142695f},{-0.165106f,0.0753756f,-0.141205f}, -{-0.170731f,0.0705443f,-0.139464f},{-0.176361f,0.0657091f,-0.137469f},{-0.181985f,0.0608783f,-0.135216f}, -{-0.193331f,0.0516347f,-0.129604f},{-0.198873f,0.0468744f,-0.126571f},{-0.198731f,0.0464957f,-0.12689f}, -{-0.19318f,0.0512629f,-0.129928f},{-0.204236f,0.0417672f,-0.123589f},{-0.209686f,0.0370865f,-0.120026f}, -{-0.21507f,0.0324624f,-0.116203f},{-0.220377f,0.0279043f,-0.112124f},{-0.225597f,0.0234208f,-0.10779f}, -{-0.23072f,0.0190209f,-0.103209f},{-0.240634f,0.0105057f,-0.0933231f},{-0.245406f,0.00640698f,-0.0880336f}, -{-0.250043f,0.00242477f,-0.0825239f},{-0.254535f,-0.00143353f,-0.0768032f},{-0.258875f,-0.00516092f,-0.0708815f}, -{-0.267067f,-0.0121974f,-0.0584789f},{-0.270907f,-0.0154949f,-0.0520214f},{-0.274567f,-0.0186385f,-0.0454095f}, -{-0.278043f,-0.0216238f,-0.0386562f},{-0.284442f,-0.0266194f,-0.0246083f},{-0.287338f,-0.0291065f,-0.017522f}, -{-0.287325f,-0.0295963f,-0.017682f},{-0.284425f,-0.0271056f,-0.0247786f},{-0.290028f,-0.0319176f,-0.0104982f}, -{-0.292532f,-0.0340683f,-0.00324118f},{-0.294837f,-0.0360478f,0.00407537f},{-0.296942f,-0.037856f,0.0114378f}, -{-0.298849f,-0.0394935f,0.0188328f},{-0.302071f,-0.0422615f,0.0336681f},{-0.303381f,-0.0428858f,0.0411575f}, -{-0.30451f,-0.0438554f,0.0485442f},{-0.304522f,-0.0443667f,0.0484808f},{-0.303392f,-0.0433957f,0.0410833f}, -{-0.305467f,-0.0451776f,0.0558492f},{-0.307222f,-0.0466854f,0.0776733f},{-0.307591f,-0.0471265f,0.0918925f}, -{-0.307758f,-0.047452f,0.0918925f},{-0.137581f,0.0995171f,-0.145907f},{-0.148561f,0.0900864f,-0.144598f}, -{-0.154112f,0.0853187f,-0.143596f},{-0.148803f,0.0903988f,-0.144431f},{-0.159694f,0.0805249f,-0.142353f}, -{-0.165297f,0.0757121f,-0.140865f},{-0.170914f,0.0708878f,-0.139127f},{-0.176535f,0.0660598f,-0.137134f}, -{-0.182152f,0.061236f,-0.134885f},{-0.187753f,0.0564248f,-0.132375f},{-0.210011f,0.0378285f,-0.119568f}, -{-0.204573f,0.0424991f,-0.123123f},{-0.20437f,0.0421528f,-0.123274f},{-0.209812f,0.0374789f,-0.119717f}, -{-0.215188f,0.0328616f,-0.1159f},{-0.220487f,0.0283101f,-0.111826f},{-0.2257f,0.0238332f,-0.107499f}, -{-0.240892f,0.0113052f,-0.0929223f},{-0.240715f,0.0109369f,-0.0930527f},{-0.236004f,0.0155034f,-0.0979722f}, -{-0.24548f,0.00684419f,-0.087771f},{-0.25011f,0.0028678f,-0.0822693f},{-0.254596f,-0.000984871f,-0.0765569f}, -{-0.267268f,-0.0113487f,-0.0581535f},{-0.271099f,-0.0146391f,-0.0517099f},{-0.26711f,-0.011733f,-0.0582594f}, -{-0.270944f,-0.0150257f,-0.0518113f},{-0.274598f,-0.0181647f,-0.0452091f},{-0.278069f,-0.0211457f,-0.0384656f}, -{-0.281352f,-0.023965f,-0.0315942f},{-0.290179f,-0.0310263f,-0.0102766f},{-0.290037f,-0.0314244f,-0.0103487f}, -{-0.287482f,-0.02871f,-0.0174448f},{-0.292537f,-0.033572f,-0.0031023f},{-0.294839f,-0.0355486f,0.00420356f}, -{-0.296941f,-0.0373542f,0.0115553f},{-0.298845f,-0.0389893f,0.0189394f},{-0.300551f,-0.0404551f,0.026343f}, -{-0.302063f,-0.0417532f,0.0337531f},{-0.305453f,-0.044665f,0.0559018f},{-0.307336f,-0.0457621f,0.0777041f}, -{-0.306926f,-0.0454104f,0.0705019f},{-0.307206f,-0.0461706f,0.077694f},{-0.15435f,0.0856345f,-0.143429f}, -{-0.159927f,0.0808441f,-0.142188f},{-0.165527f,0.0760347f,-0.140701f},{-0.17114f,0.0712139f,-0.138964f}, -{-0.176757f,0.0663892f,-0.136973f},{-0.18237f,0.0615688f,-0.134725f},{-0.187968f,0.056761f,-0.132217f}, -{-0.193541f,0.0519743f,-0.129448f},{-0.199079f,0.0472174f,-0.126416f},{-0.215383f,0.0332144f,-0.115753f}, -{-0.220678f,0.0286662f,-0.111682f},{-0.225887f,0.0241924f,-0.107358f},{-0.230999f,0.019802f,-0.102786f}, -{-0.245654f,0.00721537f,-0.0876442f},{-0.25028f,0.00324179f,-0.0821464f},{-0.254763f,-0.000608165f,-0.0764381f}, -{-0.259093f,-0.00432749f,-0.0705292f},{-0.263264f,-0.00790968f,-0.0644306f},{-0.274751f,-0.0177759f,-0.0451124f}, -{-0.27822f,-0.0207548f,-0.0383737f},{-0.2815f,-0.0235721f,-0.0315071f},{-0.284588f,-0.0262246f,-0.0245261f}, -{-0.292677f,-0.0331723f,-0.0030353f},{-0.294977f,-0.0351475f,0.00426541f},{-0.297078f,-0.0369518f,0.0116119f}, -{-0.29898f,-0.0385858f,0.0189909f},{-0.300686f,-0.0400505f,0.0263892f},{-0.302196f,-0.0413477f,0.0337941f}, -{-0.303514f,-0.0424795f,0.0411933f},{-0.304642f,-0.0434484f,0.0485748f},{-0.305584f,-0.0442575f,0.0559272f}, -{-0.306344f,-0.0449103f,0.0632397f},{0.164482f,-0.077386f,-0.141015f},{0.160376f,-0.0813663f,-0.142188f}, -{0.165975f,-0.076557f,-0.140701f},{0.193989f,-0.0524965f,-0.129448f},{0.195149f,-0.0510464f,-0.12867f}, -{0.190161f,-0.0553306f,-0.131224f},{0.144011f,-0.0959421f,-0.145366f},{0.144282f,-0.0962099f,-0.145713f}, -{0.149803f,-0.0914681f,-0.144944f},{0.154798f,-0.0861567f,-0.143429f},{0.15923f,-0.0818969f,-0.142366f}, -{0.155583f,-0.0868273f,-0.144466f},{0.150012f,-0.0916126f,-0.145472f},{0.143742f,-0.0956526f,-0.145199f}, -{0.149524f,-0.0912072f,-0.144598f},{0.149251f,-0.0909211f,-0.144431f},{0.13357f,-0.105734f,-0.147719f}, -{0.133556f,-0.105746f,-0.147105f},{0.128196f,-0.110381f,-0.147351f},{0.144478f,-0.096365f,-0.146243f}, -{0.127892f,-0.110028f,-0.148558f},{0.133182f,-0.105243f,-0.148599f},{0.133422f,-0.105538f,-0.148251f}, -{0.128143f,-0.11032f,-0.148015f},{0.138114f,-0.100033f,-0.148493f},{0.138401f,-0.10024f,-0.148445f}, -{0.132929f,-0.10494f,-0.148767f},{0.132705f,-0.104679f,-0.14881f},{0.12751f,-0.109583f,-0.148876f}, -{0.127291f,-0.109328f,-0.148916f},{0.174884f,-0.0684522f,-0.137702f},{0.171588f,-0.0717361f,-0.138964f}, -{0.177206f,-0.0669114f,-0.136973f},{0.169701f,-0.0729032f,-0.13946f},{0.182818f,-0.062091f,-0.134725f}, -{0.180024f,-0.0640372f,-0.135742f},{0.188716f,-0.0575456f,-0.132375f},{0.188416f,-0.0572832f,-0.132217f}, -{0.185118f,-0.0596621f,-0.133582f},{0.199528f,-0.0477396f,-0.126416f},{0.200078f,-0.0468134f,-0.125923f}, -{0.210459f,-0.0383507f,-0.119568f},{0.215831f,-0.0337366f,-0.115753f},{0.214463f,-0.0344587f,-0.116543f}, -{0.205021f,-0.0430213f,-0.123123f},{0.228159f,-0.0226953f,-0.105516f},{0.223677f,-0.0265448f,-0.109369f}, -{0.226336f,-0.0247146f,-0.107358f},{0.21911f,-0.0304671f,-0.113046f},{0.236853f,-0.0152278f,-0.0972923f}, -{0.236452f,-0.0160256f,-0.0979722f},{0.24134f,-0.0118274f,-0.0929223f},{0.231448f,-0.0203242f,-0.102786f}, -{0.249164f,-0.00465414f,-0.0837205f},{0.250729f,-0.00376401f,-0.0821464f},{0.253058f,-0.00130946f,-0.0788827f}, -{0.246102f,-0.00773759f,-0.0876442f},{0.264065f,0.00814415f,-0.0634868f},{0.260512f,0.00509248f,-0.0687614f}, -{0.263712f,0.00738746f,-0.0644306f},{0.256842f,0.00194036f,-0.0738949f},{0.259542f,0.00380527f,-0.0705292f}, -{0.273991f,0.0166696f,-0.0468636f},{0.271547f,0.0141168f,-0.0517099f},{0.2752f,0.0172537f,-0.0451124f}, -{0.267717f,0.0108265f,-0.0581535f},{0.281948f,0.0230499f,-0.0315071f},{0.282759f,0.0241996f,-0.0291439f}, -{0.27997f,0.0218041f,-0.0351637f},{0.277046f,0.0192933f,-0.041072f},{0.290298f,0.0306748f,-0.010468f}, -{0.287925f,0.0286369f,-0.0167907f},{0.290627f,0.030504f,-0.0102766f},{0.285037f,0.0257024f,-0.0245261f}, -{0.293126f,0.0326501f,-0.0030353f},{0.294612f,0.0343798f,0.00244111f},{0.292527f,0.0325897f,-0.00405553f}, -{0.299429f,0.0380636f,0.0189909f},{0.298338f,0.0375801f,0.0156645f},{0.297526f,0.0364296f,0.0116119f}, -{0.296549f,0.0360438f,0.00901635f},{0.295426f,0.0346253f,0.00426541f},{0.301463f,0.0402644f,0.0291557f}, -{0.302645f,0.0408255f,0.0337941f},{0.302797f,0.04141f,0.0359868f},{0.301134f,0.0395283f,0.0263892f}, -{0.299976f,0.0389874f,0.0223796f},{0.303977f,0.0424232f,0.0428671f},{0.30509f,0.0429262f,0.0485748f}, -{0.305001f,0.0433031f,0.0497904f},{0.303962f,0.0419573f,0.0411933f},{0.308026f,0.0454474f,0.0848371f}, -{0.307848f,0.0457485f,0.0918925f},{0.307769f,0.0456805f,0.0848393f},{0.305869f,0.044049f,0.0567509f}, -{0.306032f,0.0437353f,0.0559272f},{0.307375f,0.0448882f,0.0705019f},{0.307759f,0.0446979f,0.0704868f}, -{0.308168f,0.0450498f,0.077694f},{0.307531f,0.0454763f,0.0777923f},{0.306581f,0.0446602f,0.0637421f}, -{0.307135f,0.0451361f,0.0707579f},{0.307784f,0.0452398f,0.0777041f},{0.306792f,0.044388f,0.0632397f}, -{0.30868f,0.0449881f,0.0776733f},{0.309485f,0.0453564f,0.084806f},{0.308922f,0.0451961f,0.0848218f}, -{0.305473f,0.0427346f,0.0485442f},{0.304344f,0.041765f,0.0411575f},{0.308269f,0.0446357f,0.0704555f}, -{0.307176f,0.0441974f,0.0632194f},{0.307686f,0.0441345f,0.0631775f},{0.30598f,0.0426695f,0.0484808f}, -{0.309295f,0.0451931f,0.0703525f},{0.308709f,0.0446894f,0.0630396f},{0.309537f,0.0457246f,0.0703047f}, -{0.308247f,0.0442923f,0.0631135f},{0.308831f,0.0447947f,0.0704077f},{0.309553f,0.0462388f,0.0702734f}, -{0.309967f,0.0465942f,0.0775525f},{0.310303f,0.0465537f,0.0918925f},{0.310194f,0.0462889f,0.0847721f}, -{0.310211f,0.046804f,0.0847617f},{0.310081f,0.0472127f,0.0847568f},{0.310171f,0.0472612f,0.0918925f}, -{0.310283f,0.046913f,0.0918925f},{0.30997f,0.0475707f,0.0918925f},{0.301514f,0.0393343f,0.026343f}, -{0.278668f,0.0202326f,-0.0383737f},{0.285411f,0.0264779f,-0.0230178f},{0.28793f,0.0281877f,-0.0174448f}, -{0.282314f,0.0228442f,-0.0315942f},{0.270808f,0.0139352f,-0.0525331f},{0.267498f,0.0110925f,-0.0580758f}, -{0.255211f,8.59432e-005f,-0.0764381f},{0.245163f,-0.00809075f,-0.088404f},{0.259892f,0.00358602f,-0.0706439f}, -{0.260333f,0.0034637f,-0.0708815f},{0.264512f,0.00705366f,-0.0647696f},{0.241058f,-0.0116164f,-0.0929293f}, -{0.232552f,-0.0189219f,-0.101489f},{0.209739f,-0.0385159f,-0.119856f},{0.204942f,-0.0426353f,-0.122984f}, -{0.221127f,-0.0291884f,-0.111682f},{0.237193f,-0.0164102f,-0.098384f},{0.231778f,-0.0205605f,-0.102924f}, -{0.232178f,-0.0207181f,-0.103209f},{0.15395f,-0.0864318f,-0.14351f},{0.148646f,-0.090987f,-0.144448f}, -{0.143324f,-0.0955583f,-0.145179f},{0.133384f,-0.10557f,-0.146574f},{0.128144f,-0.110321f,-0.147023f}, -{0.138279f,-0.100345f,-0.145739f},{0.137988f,-0.100142f,-0.145701f},{0.132868f,-0.104993f,-0.146057f}, -{0.132642f,-0.104733f,-0.146014f},{0.128196f,-0.110381f,-0.147687f},{0.12751f,-0.109583f,-0.146158f}, -{0.127291f,-0.109328f,-0.146119f},{0.12771f,-0.109815f,-0.146297f},{0.127896f,-0.110032f,-0.146474f}, -{0.133129f,-0.105289f,-0.146225f},{0.128042f,-0.110202f,-0.146724f},{0.138543f,-0.100638f,-0.145907f}, -{0.155075f,-0.0864395f,-0.143596f},{0.160656f,-0.0816457f,-0.142353f},{0.16626f,-0.0768329f,-0.140865f}, -{0.171877f,-0.0720087f,-0.139127f},{0.177498f,-0.0671806f,-0.137134f},{0.183114f,-0.0623568f,-0.134885f}, -{0.194638f,-0.0529602f,-0.129928f},{0.200189f,-0.0481929f,-0.12689f},{0.194293f,-0.0527555f,-0.129604f}, -{0.199836f,-0.0479952f,-0.126571f},{0.205333f,-0.0432736f,-0.123274f},{0.210775f,-0.0385997f,-0.119717f}, -{0.216151f,-0.0339824f,-0.1159f},{0.22145f,-0.0294309f,-0.111826f},{0.226663f,-0.024954f,-0.107499f}, -{0.236786f,-0.0162589f,-0.0981062f},{0.241678f,-0.0120577f,-0.0930527f},{0.246443f,-0.00796499f,-0.087771f}, -{0.251073f,-0.00398861f,-0.0822693f},{0.255558f,-0.000135934f,-0.0765569f},{0.264066f,0.00717073f,-0.0645409f}, -{0.268073f,0.0106122f,-0.0582594f},{0.271906f,0.0139049f,-0.0518113f},{0.275561f,0.0170439f,-0.0452091f}, -{0.279032f,0.0200249f,-0.0384656f},{0.29201f,0.0303472f,-0.0107265f},{0.288783f,0.0278991f,-0.017682f}, -{0.289301f,0.0280207f,-0.0179263f},{0.285405f,0.0254986f,-0.0246083f},{0.288301f,0.0279857f,-0.017522f}, -{0.290999f,0.0303036f,-0.0103487f},{0.2935f,0.0324512f,-0.0031023f},{0.295801f,0.0344278f,0.00420356f}, -{0.297903f,0.0362334f,0.0115553f},{0.299807f,0.0378685f,0.0189394f},{0.303025f,0.0406324f,0.0337531f}, -{0.30485f,0.0416984f,0.0410833f},{0.306415f,0.0435442f,0.0559018f},{0.30841f,0.0452575f,0.0848321f}, -{0.308442f,0.0453419f,0.0918925f},{0.308124f,0.045503f,0.0918925f},{0.128039f,-0.110199f,-0.14831f}, -{0.138807f,-0.100913f,-0.146254f},{0.155362f,-0.0866934f,-0.14394f},{0.160952f,-0.0818926f,-0.142695f}, -{0.166563f,-0.0770728f,-0.141205f},{0.172189f,-0.0722415f,-0.139464f},{0.177818f,-0.0674064f,-0.137469f}, -{0.183443f,-0.0625755f,-0.135216f},{0.189053f,-0.0577573f,-0.132703f},{0.205694f,-0.0434645f,-0.123589f}, -{0.206027f,-0.043502f,-0.12407f},{0.211489f,-0.0388108f,-0.120499f},{0.211144f,-0.0387837f,-0.120026f}, -{0.216528f,-0.0341596f,-0.116203f},{0.221835f,-0.0296015f,-0.112124f},{0.227055f,-0.0251181f,-0.10779f}, -{0.247289f,-0.00806285f,-0.0884349f},{0.247595f,-0.00780019f,-0.0888979f},{0.252254f,-0.00379886f,-0.0833616f}, -{0.242092f,-0.0122029f,-0.0933231f},{0.246864f,-0.0081042f,-0.0880336f},{0.251501f,-0.00412199f,-0.0825239f}, -{0.255993f,-0.000263687f,-0.0768032f},{0.272846f,0.0138878f,-0.0523423f},{0.273218f,0.0142069f,-0.0527127f}, -{0.276895f,0.0173656f,-0.046069f},{0.268525f,0.0105001f,-0.0584789f},{0.272364f,0.0137976f,-0.0520214f}, -{0.276025f,0.0169413f,-0.0454095f},{0.2795f,0.0199266f,-0.0386562f},{0.282788f,0.02275f,-0.0317747f}, -{0.285883f,0.0254083f,-0.0247786f},{0.291486f,0.0302204f,-0.0104982f},{0.29399f,0.0323711f,-0.00324118f}, -{0.296294f,0.0343506f,0.00407537f},{0.2984f,0.0361588f,0.0114378f},{0.300306f,0.0377963f,0.0188328f}, -{0.302015f,0.0392642f,0.0262471f},{0.303529f,0.0405642f,0.0336681f},{0.306924f,0.0434803f,0.0558492f}, -{0.309707f,0.0455472f,0.077605f},{0.308803f,0.0452653f,0.0918925f},{0.138651f,-0.100546f,-0.148277f}, -{0.138991f,-0.101078f,-0.146785f},{0.161185f,-0.0820158f,-0.143218f},{0.16127f,-0.081943f,-0.143822f}, -{0.166909f,-0.0771001f,-0.142325f},{0.166809f,-0.0771853f,-0.141725f},{0.172447f,-0.0723432f,-0.13998f}, -{0.178089f,-0.0674973f,-0.137981f},{0.183726f,-0.0626556f,-0.135723f},{0.189349f,-0.0578266f,-0.133204f}, -{0.194947f,-0.0530188f,-0.130423f},{0.200509f,-0.048241f,-0.127378f},{0.216885f,-0.0341764f,-0.116668f}, -{0.217113f,-0.0339808f,-0.117203f},{0.222445f,-0.0294008f,-0.113104f},{0.222204f,-0.0296081f,-0.112579f}, -{0.227436f,-0.0251146f,-0.108236f},{0.23257f,-0.0207049f,-0.103644f},{0.237597f,-0.0163874f,-0.0988083f}, -{0.242506f,-0.0121707f,-0.0937362f},{0.251936f,-0.00407176f,-0.0829128f},{0.256438f,-0.00020485f,-0.0771794f}, -{0.260788f,0.00353086f,-0.0712445f},{0.264977f,0.00712881f,-0.065119f},{0.268999f,0.010583f,-0.0588143f}, -{0.276515f,0.0170385f,-0.0457157f},{0.279998f,0.0200305f,-0.0389474f},{0.283293f,0.0228602f,-0.0320505f}, -{0.286395f,0.0255244f,-0.0250388f},{0.29452f,0.0325027f,-0.00345334f},{0.294947f,0.0328695f,-0.00369814f}, -{0.297263f,0.0348585f,0.00365355f},{0.29683f,0.0344866f,0.00387953f},{0.29894f,0.0362988f,0.0112584f}, -{0.30085f,0.03794f,0.0186698f},{0.302563f,0.0394112f,0.0261007f},{0.30408f,0.0407141f,0.0335382f}, -{0.305404f,0.0418509f,0.04097f},{0.306537f,0.0428241f,0.048384f},{0.307483f,0.0436367f,0.0557688f}, -{0.309243f,0.0451479f,0.0776416f},{0.309162f,0.0452855f,0.0918925f},{0.14452f,-0.0963291f,-0.146855f}, -{0.150068f,-0.0915645f,-0.146081f},{0.139019f,-0.101054f,-0.147398f},{0.155654f,-0.0867669f,-0.145073f}, -{0.172561f,-0.0722455f,-0.140576f},{0.178217f,-0.0673872f,-0.138571f},{0.183869f,-0.0625331f,-0.136307f}, -{0.183833f,-0.0622407f,-0.136814f},{0.189482f,-0.0573886f,-0.134283f},{0.189506f,-0.0576918f,-0.133782f}, -{0.195118f,-0.0528716f,-0.130993f},{0.200695f,-0.0480815f,-0.127941f},{0.206227f,-0.0433303f,-0.124624f}, -{0.211703f,-0.0386271f,-0.121044f},{0.22769f,-0.0248958f,-0.10875f},{0.227751f,-0.0245198f,-0.109195f}, -{0.23291f,-0.0200889f,-0.104581f},{0.232838f,-0.0204747f,-0.104146f},{0.237878f,-0.0161461f,-0.0992979f}, -{0.2428f,-0.0119186f,-0.0942128f},{0.256767f,7.79773e-005f,-0.0776135f},{0.256893f,0.000509374f,-0.0779897f}, -{0.261263f,0.00426299f,-0.0720263f},{0.261128f,0.00382328f,-0.0716633f},{0.265328f,0.00743047f,-0.0655221f}, -{0.26936f,0.0108935f,-0.0592012f},{0.280388f,0.0203653f,-0.0392833f},{0.280566f,0.0208417f,-0.0395744f}, -{0.283876f,0.023685f,-0.0326445f},{0.283691f,0.0232022f,-0.0323688f},{0.286801f,0.0258733f,-0.025339f}, -{0.289715f,0.028376f,-0.0182083f},{0.292431f,0.0307085f,-0.01099f},{0.299378f,0.0366754f,0.0110514f}, -{0.301294f,0.0383208f,0.0184819f},{0.301518f,0.038837f,0.0183189f},{0.303239f,0.0403153f,0.0257854f}, -{0.303011f,0.0397958f,0.0259318f},{0.304532f,0.041102f,0.0333884f},{0.305859f,0.0422417f,0.0408392f}, -{0.306995f,0.0432174f,0.0482723f},{0.307944f,0.0440321f,0.0556761f},{0.309951f,0.0457562f,0.0847878f}, -{0.30982f,0.0455988f,0.0918925f},{0.309511f,0.0453977f,0.0918925f},{0.144396f,-0.0961117f,-0.147384f}, -{0.149956f,-0.0913365f,-0.14661f},{0.138883f,-0.100847f,-0.147929f},{0.155555f,-0.0865282f,-0.145599f}, -{0.161183f,-0.0816937f,-0.144345f},{0.166835f,-0.07684f,-0.142845f},{0.172499f,-0.0719747f,-0.141092f}, -{0.178168f,-0.0671055f,-0.139082f},{0.195107f,-0.0525577f,-0.131488f},{0.200554f,-0.0473783f,-0.128748f}, -{0.200696f,-0.047757f,-0.128429f},{0.20624f,-0.0429952f,-0.125105f},{0.211728f,-0.0382816f,-0.121517f}, -{0.21715f,-0.033625f,-0.117667f},{0.222494f,-0.0290348f,-0.113559f},{0.237873f,-0.0153256f,-0.1f}, -{0.237961f,-0.0157507f,-0.0997223f},{0.242894f,-0.0115138f,-0.0946258f},{0.2477f,-0.00738628f,-0.0892991f}, -{0.252369f,-0.00337607f,-0.0837506f},{0.265424f,0.00833753f,-0.0661002f},{0.265472f,0.00787819f,-0.0658715f}, -{0.269513f,0.0113489f,-0.0595366f},{0.27338f,0.0146696f,-0.0530336f},{0.277066f,0.0178353f,-0.0463752f}, -{0.286976f,0.0268481f,-0.0257695f},{0.286993f,0.026362f,-0.0255992f},{0.289914f,0.0288702f,-0.0184526f}, -{0.292635f,0.0312079f,-0.0112184f},{0.295157f,0.0333737f,-0.00391029f},{0.297478f,0.0353671f,0.00345771f}, -{0.299598f,0.037188f,0.0108719f},{0.304763f,0.0416245f,0.0332586f},{0.306104f,0.0432766f,0.0406518f}, -{0.306093f,0.0427667f,0.0407259f},{0.307232f,0.0437445f,0.0481755f},{0.308183f,0.0445611f,0.0555957f}, -{0.30895f,0.0452198f,0.0629755f},{0.30995f,0.0460795f,0.0775733f},{0.310227f,0.0461927f,0.0918925f}, -{0.31006f,0.0458671f,0.0918925f},{0.127713f,-0.109819f,-0.148751f},{0.144173f,-0.0958031f,-0.147731f}, -{0.149741f,-0.091021f,-0.146955f},{0.155347f,-0.0862057f,-0.145943f},{0.160984f,-0.0813642f,-0.144688f}, -{0.166643f,-0.0765035f,-0.143185f},{0.172316f,-0.0716311f,-0.141429f},{0.177994f,-0.0667549f,-0.139417f}, -{0.183666f,-0.061883f,-0.137145f},{0.189324f,-0.0570238f,-0.134611f},{0.194956f,-0.052186f,-0.131812f}, -{0.205904f,-0.0422634f,-0.125571f},{0.210708f,-0.0376835f,-0.122344f},{0.211404f,-0.0375395f,-0.121975f}, -{0.206106f,-0.0426097f,-0.125419f},{0.211602f,-0.0378891f,-0.121826f},{0.217032f,-0.0332258f,-0.117971f}, -{0.222384f,-0.028629f,-0.113856f},{0.227648f,-0.0241074f,-0.109486f},{0.232815f,-0.0196701f,-0.104866f}, -{0.242813f,-0.0110826f,-0.0948962f},{0.242637f,-0.0107143f,-0.0950266f},{0.247626f,-0.00694907f,-0.0895618f}, -{0.252302f,-0.00293304f,-0.0840052f},{0.256832f,0.000958027f,-0.0782359f},{0.261209f,0.00471708f,-0.072264f}, -{0.269313f,0.0121976f,-0.059862f},{0.272494f,0.0153837f,-0.0542297f},{0.273188f,0.0155254f,-0.053345f}, -{0.269471f,0.0118133f,-0.059756f},{0.273343f,0.0151388f,-0.0532437f},{0.277034f,0.0183091f,-0.0465757f}, -{0.280539f,0.0213198f,-0.039765f},{0.283855f,0.0241672f,-0.0328251f},{0.289901f,0.02936f,-0.0186126f}, -{0.292484f,0.0320992f,-0.0114399f},{0.292626f,0.031701f,-0.0113678f},{0.295152f,0.03387f,-0.00404916f}, -{0.297476f,0.0358663f,0.00332952f},{0.299599f,0.0376898f,0.0107545f},{0.301522f,0.0393413f,0.0182123f}, -{0.303246f,0.0408217f,0.0256896f},{0.304772f,0.0421327f,0.0331736f},{0.307244f,0.0442558f,0.0481121f}, -{0.308196f,0.0450736f,0.0555431f},{0.308964f,0.0457333f,0.0629336f},{0.143927f,-0.095494f,-0.147899f}, -{0.149499f,-0.0907085f,-0.147122f},{0.155109f,-0.0858899f,-0.146109f},{0.16075f,-0.081045f,-0.144853f}, -{0.166413f,-0.0761809f,-0.143349f},{0.17209f,-0.0713051f,-0.141592f},{0.177772f,-0.0664255f,-0.139579f}, -{0.183448f,-0.0615502f,-0.137305f},{0.189109f,-0.0566876f,-0.134769f},{0.194746f,-0.0518464f,-0.131968f}, -{0.200348f,-0.0470353f,-0.128902f},{0.216837f,-0.032873f,-0.118117f},{0.222193f,-0.0282729f,-0.114f}, -{0.227461f,-0.0237482f,-0.109627f},{0.232631f,-0.0193078f,-0.105003f},{0.237693f,-0.0149603f,-0.100134f}, -{0.238141f,-0.0141219f,-0.0995149f},{0.247453f,-0.00657788f,-0.0896885f},{0.252132f,-0.00255905f,-0.0841281f}, -{0.256665f,0.00133474f,-0.0783547f},{0.261045f,0.00509642f,-0.0723786f},{0.265263f,0.00871939f,-0.0662105f}, -{0.276881f,0.0186979f,-0.0466724f},{0.280389f,0.0217108f,-0.039857f},{0.283707f,0.0245601f,-0.0329122f}, -{0.28683f,0.0272429f,-0.0258517f},{0.289757f,0.0297565f,-0.0186898f},{0.289812f,0.030258f,-0.0180672f}, -{0.295012f,0.0342697f,-0.00411618f},{0.297337f,0.0362674f,0.00326766f},{0.299462f,0.0380922f,0.0106978f}, -{0.301386f,0.0397448f,0.0181608f},{0.303111f,0.0412262f,0.0256434f},{0.304639f,0.0425382f,0.0331326f}, -{0.305971f,0.0436828f,0.040616f},{0.307112f,0.0446628f,0.0480815f},{0.308065f,0.0454811f,0.0555177f}, -{0.308834f,0.0461413f,0.0629134f},{0.309423f,0.0466471f,0.0702583f},{0.309837f,0.0470028f,0.0775425f}, -{0.143513f,-0.0953962f,-0.147965f},{0.148897f,-0.0907713f,-0.147226f},{0.154263f,-0.0861627f,-0.146277f}, -{0.159606f,-0.0815743f,-0.145118f},{0.164919f,-0.0770103f,-0.143752f},{0.1702f,-0.0724748f,-0.142179f}, -{0.175443f,-0.0679717f,-0.1404f},{0.180644f,-0.0635049f,-0.138417f},{0.185798f,-0.0590782f,-0.136232f}, -{0.1909f,-0.0546957f,-0.133846f},{0.195947f,-0.0503613f,-0.131262f},{0.200933f,-0.0460786f,-0.128482f}, -{0.205855f,-0.0418515f,-0.125509f},{0.215487f,-0.0335786f,-0.118992f},{0.220189f,-0.0295402f,-0.115454f}, -{0.224809f,-0.0255719f,-0.111734f},{0.229344f,-0.0216771f,-0.107835f},{0.233789f,-0.0178593f,-0.103761f}, -{0.242395f,-0.0104681f,-0.0951008f},{0.246548f,-0.00690116f,-0.0905224f},{0.250596f,-0.00342407f,-0.0857837f}, -{0.254536f,-4.00465e-005f,-0.080889f},{0.258365f,0.00324795f,-0.0758426f},{0.262078f,0.00643705f,-0.0706488f}, -{0.265672f,0.00952448f,-0.0653124f},{0.269146f,0.0125076f,-0.0598376f},{0.275715f,0.0181502f,-0.0484934f}, -{0.278806f,0.0208047f,-0.042634f},{0.281763f,0.0233449f,-0.0366563f},{0.284585f,0.0257686f,-0.0305656f}, -{0.287269f,0.0280737f,-0.0243674f},{0.292213f,0.0323197f,-0.0116704f},{0.294469f,0.0342571f,-0.00518257f}, -{0.296578f,0.0360684f,0.00139061f},{0.298538f,0.0377519f,0.00804317f},{0.300347f,0.0393062f,0.0147693f}, -{0.302005f,0.04073f,0.0215631f},{0.303509f,0.042022f,0.0284189f},{0.304859f,0.043181f,0.0353305f}, -{0.306052f,0.0442061f,0.0422916f},{0.307089f,0.0450964f,0.0492962f},{0.307967f,0.045851f,0.0563382f}, -{0.308687f,0.0464693f,0.0634117f},{0.309248f,0.0469508f,0.0705101f},{0.309649f,0.047295f,0.0776272f}, -{0.309889f,0.0475017f,0.0847567f},{-0.0493934f,-0.26108f,0.0428677f},{-0.0500586f,-0.262105f,0.0485758f}, -{-0.0489305f,-0.261136f,0.0411945f},{-0.0403941f,-0.253804f,0.00426646f},{-0.0400286f,-0.253036f,0.00244165f}, -{-0.041966f,-0.2547f,0.00901696f},{-0.0517606f,-0.263566f,0.0632405f},{-0.052343f,-0.264067f,0.0705025f}, -{-0.0516301f,-0.263974f,0.0632202f},{-0.0512863f,-0.262705f,0.0567511f},{-0.0519978f,-0.263316f,0.0637424f}, -{-0.0528812f,-0.26555f,0.084822f},{-0.0530084f,-0.265783f,0.0918925f},{-0.0531246f,-0.266082f,0.0848062f}, -{-0.0522285f,-0.264989f,0.0704561f},{-0.0516449f,-0.264488f,0.0631783f},{-0.0522129f,-0.264475f,0.0704874f}, -{-0.0535901f,-0.266482f,0.084788f},{-0.0540726f,-0.26669f,0.0918925f},{-0.0541535f,-0.266643f,0.0847723f}, -{-0.0524705f,-0.265521f,0.0704083f},{-0.0518855f,-0.265018f,0.0631143f},{-0.0550496f,-0.266391f,0.084757f}, -{-0.0548051f,-0.266181f,0.0775429f},{-0.0546651f,-0.266581f,0.084762f},{-0.0544319f,-0.26671f,0.0918925f}, -{-0.0553868f,-0.266227f,0.0918925f},{-0.0551112f,-0.266473f,0.0918925f},{-0.0550661f,-0.265952f,0.0776267f}, -{-0.0510006f,-0.262914f,0.0559281f},{-0.0504179f,-0.261959f,0.0497909f},{-0.0553066f,-0.266158f,0.0847564f}, -{-0.0468799f,-0.258921f,0.0291561f},{-0.0476128f,-0.260004f,0.0337954f},{-0.0461026f,-0.258707f,0.0263905f}, -{-0.0482137f,-0.260066f,0.0359874f},{-0.0443972f,-0.257242f,0.0189921f},{-0.0453931f,-0.257644f,0.0223799f}, -{-0.0424948f,-0.255608f,0.0116131f},{-0.0437546f,-0.256236f,0.015665f},{-0.0380944f,-0.251829f,-0.00303443f}, -{-0.0379442f,-0.251246f,-0.0040552f},{-0.0328989f,-0.247366f,-0.0174445f},{-0.0300052f,-0.244881f,-0.0245261f}, -{-0.0308284f,-0.245134f,-0.0230172f},{-0.0355958f,-0.249683f,-0.010276f},{-0.0224634f,-0.23795f,-0.0410717f}, -{-0.0253866f,-0.240461f,-0.0351634f},{-0.0236368f,-0.239411f,-0.0383731f},{-0.0281758f,-0.242856f,-0.0291434f}, -{-0.016225f,-0.232592f,-0.0525327f},{-0.0165165f,-0.233296f,-0.051709f},{-0.0126856f,-0.230006f,-0.0581524f}, -{-0.0201686f,-0.236433f,-0.0451116f},{-0.00592937f,-0.223749f,-0.0687612f},{-0.004511f,-0.222985f,-0.0705281f}, -{-0.00225941f,-0.220597f,-0.0738946f},{-0.00868167f,-0.226567f,-0.0644294f},{0.00942004f,-0.210566f,-0.088404f}, -{0.00541866f,-0.214002f,-0.0837203f},{0.00892832f,-0.211442f,-0.0876434f},{0.00152437f,-0.217347f,-0.0788824f}, -{0.00430185f,-0.215415f,-0.0821454f},{0.0220305f,-0.199735f,-0.101489f},{0.0185782f,-0.203154f,-0.0979716f}, -{0.0235832f,-0.198855f,-0.102786f},{0.0136901f,-0.207352f,-0.0929216f},{0.0339042f,-0.189991f,-0.111682f}, -{0.0354727f,-0.18819f,-0.113046f},{0.030906f,-0.192112f,-0.109369f},{0.026424f,-0.195961f,-0.105516f}, -{0.0496403f,-0.176021f,-0.122984f},{0.0448439f,-0.180141f,-0.119856f},{0.0500098f,-0.176158f,-0.123123f}, -{0.0392f,-0.185442f,-0.115753f},{0.055503f,-0.17144f,-0.126416f},{0.0594332f,-0.16761f,-0.12867f}, -{0.0545048f,-0.171843f,-0.125923f},{0.0722122f,-0.157088f,-0.134725f},{0.0694645f,-0.158995f,-0.133582f}, -{0.0666145f,-0.161896f,-0.132217f},{0.0644212f,-0.163326f,-0.131224f},{0.0610414f,-0.166683f,-0.129448f}, -{0.079699f,-0.150204f,-0.137702f},{0.0778246f,-0.152268f,-0.136973f},{0.083442f,-0.147443f,-0.138964f}, -{0.0745587f,-0.154619f,-0.135742f},{0.0901005f,-0.141271f,-0.141015f},{0.089055f,-0.142623f,-0.140701f}, -{0.0946547f,-0.137813f,-0.142188f},{0.0848811f,-0.145754f,-0.13946f},{0.100633f,-0.132225f,-0.143511f}, -{0.0953526f,-0.13676f,-0.142366f},{0.100232f,-0.133023f,-0.14343f},{0.111882f,-0.124362f,-0.146244f}, -{0.111758f,-0.124144f,-0.145714f},{0.106237f,-0.128886f,-0.144944f},{0.122163f,-0.114186f,-0.146058f}, -{0.116595f,-0.118515f,-0.145701f},{0.116752f,-0.118834f,-0.145739f},{0.121941f,-0.113924f,-0.146015f}, -{0.111289f,-0.123526f,-0.145199f},{0.10578f,-0.128258f,-0.144432f},{0.111534f,-0.123836f,-0.145367f}, -{0.111259f,-0.123099f,-0.145179f},{0.105936f,-0.12767f,-0.144449f},{0.0892849f,-0.142945f,-0.140865f}, -{0.095088f,-0.138462f,-0.142696f},{0.0948885f,-0.138132f,-0.142353f},{0.106348f,-0.129114f,-0.145472f}, -{0.106021f,-0.128571f,-0.144599f},{0.11184f,-0.124398f,-0.146855f},{0.117342f,-0.119672f,-0.147398f}, -{0.117369f,-0.119648f,-0.146786f},{0.111372f,-0.123975f,-0.147732f},{0.116894f,-0.119232f,-0.148277f}, -{0.111644f,-0.124242f,-0.147385f},{0.122619f,-0.114816f,-0.148251f},{0.122363f,-0.114535f,-0.148599f}, -{0.122103f,-0.114239f,-0.148767f},{0.121878f,-0.113978f,-0.14881f},{0.0780466f,-0.152598f,-0.137135f}, -{0.0286952f,-0.194464f,-0.107358f},{0.04012f,-0.184198f,-0.116543f},{0.0445719f,-0.180828f,-0.119568f}, -{0.0340952f,-0.190347f,-0.111826f},{0.0177295f,-0.203429f,-0.097292f},{0.0135248f,-0.20704f,-0.0929291f}, -{-0.000180634f,-0.219265f,-0.076437f},{-0.00948232f,-0.226801f,-0.0634867f},{0.00447193f,-0.215789f,-0.0822683f}, -{0.00453921f,-0.216232f,-0.0825229f},{0.00917572f,-0.21225f,-0.0880327f},{-0.0129153f,-0.229749f,-0.0580755f}, -{-0.0194086f,-0.235326f,-0.0468631f},{-0.0333422f,-0.247293f,-0.0167902f},{-0.0357148f,-0.249331f,-0.0104677f}, -{-0.0269169f,-0.242229f,-0.0315068f},{-0.0163243f,-0.234152f,-0.0520204f},{-0.0200158f,-0.236821f,-0.0452083f}, -{-0.0199843f,-0.237295f,-0.0454087f},{-0.0423578f,-0.256011f,0.0115564f},{-0.0525519f,-0.263792f,0.0707584f}, -{-0.0534149f,-0.266377f,0.0918925f},{-0.0529481f,-0.264133f,0.0777929f},{-0.0527525f,-0.264418f,0.0777045f}, -{-0.0528646f,-0.265035f,0.0848323f},{-0.0529317f,-0.265422f,0.0918925f},{-0.0531859f,-0.264337f,0.0848396f}, -{-0.0529943f,-0.264626f,0.0848373f},{-0.0530642f,-0.264714f,0.0918925f},{-0.0529519f,-0.265063f,0.0918925f}, -{-0.0532653f,-0.264405f,0.0918925f},{-0.0531751f,-0.266108f,0.0918925f},{-0.0537244f,-0.266578f,0.0918925f}, -{-0.0526227f,-0.264827f,0.0776945f},{-0.0508696f,-0.263321f,0.0559028f},{-0.0499269f,-0.262512f,0.0485453f}, -{-0.048798f,-0.261542f,0.0411587f},{-0.0474794f,-0.260409f,0.0337544f},{-0.0459681f,-0.259111f,0.0263442f}, -{-0.0442615f,-0.257646f,0.0189407f},{-0.0402537f,-0.254704f,0.00407642f},{-0.037949f,-0.252725f,-0.00324031f}, -{-0.0402556f,-0.254205f,0.00420461f},{-0.0379543f,-0.252228f,-0.00310144f},{-0.0354539f,-0.250081f,-0.0103481f}, -{-0.0327551f,-0.247763f,-0.0175217f},{-0.0298594f,-0.245276f,-0.0246083f},{-0.0267689f,-0.242622f,-0.0315939f}, -{-0.0234865f,-0.239802f,-0.038465f},{-0.0163611f,-0.233683f,-0.0518103f},{-0.0125275f,-0.23039f,-0.0582583f}, -{-0.00852075f,-0.226949f,-0.0645398f},{-0.00434714f,-0.223364f,-0.0706427f},{-1.37117e-005f,-0.219642f,-0.0765558f}, -{0.00910166f,-0.211813f,-0.0877701f},{0.0138668f,-0.20772f,-0.093052f},{0.0187584f,-0.203519f,-0.0981056f}, -{0.0237669f,-0.199217f,-0.102923f},{0.0288825f,-0.194824f,-0.107499f},{0.050333f,-0.177225f,-0.12407f}, -{0.0448966f,-0.18157f,-0.120026f},{0.0448712f,-0.181916f,-0.120499f},{0.0393947f,-0.185795f,-0.1159f}, -{0.0447704f,-0.181178f,-0.119717f},{0.0502121f,-0.176504f,-0.123274f},{0.0557093f,-0.171783f,-0.126571f}, -{0.0612515f,-0.167022f,-0.129604f},{0.0668286f,-0.162232f,-0.132375f},{0.0724302f,-0.157421f,-0.134885f}, -{0.0836679f,-0.147769f,-0.139127f},{0.0894762f,-0.143282f,-0.141206f},{0.10047f,-0.133338f,-0.143596f}, -{0.117002f,-0.11914f,-0.145907f},{0.122417f,-0.114489f,-0.146226f},{-0.0544208f,-0.266371f,0.0775529f}, -{-0.0526389f,-0.265342f,0.0776737f},{-0.0508832f,-0.263834f,0.0558501f},{-0.0499391f,-0.263023f,0.0484819f}, -{-0.0488086f,-0.262052f,0.0410845f},{-0.0474881f,-0.260918f,0.0336694f},{-0.0459745f,-0.259618f,0.0262484f}, -{-0.0442655f,-0.25815f,0.018834f},{-0.0423589f,-0.256512f,0.011439f},{-0.035445f,-0.250574f,-0.0104976f}, -{-0.0356495f,-0.251073f,-0.0107259f},{-0.0329408f,-0.248747f,-0.017926f},{-0.0327422f,-0.248253f,-0.0176816f}, -{-0.0298423f,-0.245762f,-0.0247786f},{-0.0267473f,-0.243104f,-0.0317744f},{-0.02346f,-0.24028f,-0.0386556f}, -{-0.00861687f,-0.227856f,-0.0651178f},{-0.00896809f,-0.228157f,-0.065521f},{-0.0047683f,-0.22455f,-0.0716622f}, -{-0.0124851f,-0.230854f,-0.0584778f},{-0.00847247f,-0.227408f,-0.0647685f},{-0.00429275f,-0.223818f,-0.0708804f}, -{4.70058e-005f,-0.220091f,-0.0768021f},{0.0187631f,-0.20434f,-0.0988077f},{0.0184822f,-0.204581f,-0.0992973f}, -{0.0235221f,-0.200252f,-0.104145f},{0.0139479f,-0.208152f,-0.0933224f},{0.0188466f,-0.203944f,-0.0983834f}, -{0.0238624f,-0.199636f,-0.103208f},{0.0289854f,-0.195236f,-0.10779f},{0.0342058f,-0.190752f,-0.112123f}, -{0.0395131f,-0.186194f,-0.116203f},{0.0503463f,-0.17689f,-0.123589f},{0.0558515f,-0.172161f,-0.12689f}, -{0.0614018f,-0.167394f,-0.129928f},{0.066987f,-0.162597f,-0.132703f},{0.0725969f,-0.157779f,-0.135216f}, -{0.0782214f,-0.152948f,-0.137469f},{0.083851f,-0.148113f,-0.139465f},{0.100678f,-0.133661f,-0.14394f}, -{0.122791f,-0.114992f,-0.147719f},{0.117234f,-0.119441f,-0.146255f},{0.122656f,-0.114784f,-0.146574f}, -{-0.0511222f,-0.264363f,0.0557698f},{-0.0528818f,-0.265874f,0.077642f},{-0.050176f,-0.26355f,0.0483851f}, -{-0.0506339f,-0.263943f,0.0482734f},{-0.049498f,-0.262968f,0.0408405f},{-0.0490429f,-0.262577f,0.0409712f}, -{-0.0477195f,-0.26144f,0.0335395f},{-0.0462026f,-0.260137f,0.026102f},{-0.0444897f,-0.258666f,0.0186711f}, -{-0.0425789f,-0.257025f,0.0112596f},{-0.040469f,-0.255213f,0.00388058f},{-0.0381592f,-0.253229f,-0.00345247f}, -{-0.0300343f,-0.246251f,-0.0250388f},{-0.0304405f,-0.2466f,-0.025339f},{-0.0273306f,-0.243929f,-0.0323684f}, -{-0.0269324f,-0.243587f,-0.0320502f},{-0.0236379f,-0.240757f,-0.0389468f},{-0.0201544f,-0.237765f,-0.0457149f}, -{-0.0164862f,-0.234614f,-0.0523413f},{-0.0126385f,-0.23131f,-0.0588132f},{-0.00442784f,-0.224258f,-0.0712434f}, -{-7.83923e-005f,-0.220522f,-0.0771783f},{0.00442383f,-0.216655f,-0.0829118f},{0.00907067f,-0.212664f,-0.088434f}, -{0.0138535f,-0.208556f,-0.0937354f},{0.0237901f,-0.200022f,-0.103643f},{0.0289246f,-0.195612f,-0.108235f}, -{0.0341565f,-0.191118f,-0.112578f},{0.0394757f,-0.18655f,-0.116668f},{0.0558505f,-0.172486f,-0.127378f}, -{0.0556648f,-0.172645f,-0.127941f},{0.0612418f,-0.167855f,-0.130993f},{0.0614133f,-0.167708f,-0.130423f}, -{0.0670109f,-0.1629f,-0.133204f},{0.0726333f,-0.158071f,-0.135723f},{0.0782704f,-0.15323f,-0.137981f}, -{0.0839125f,-0.148384f,-0.139981f},{0.0895502f,-0.143542f,-0.141725f},{0.0951746f,-0.138711f,-0.143219f}, -{0.100777f,-0.1339f,-0.144466f},{0.122804f,-0.11498f,-0.147106f},{-0.0529343f,-0.265919f,0.0703531f}, -{-0.0523479f,-0.265415f,0.0630404f},{-0.0533467f,-0.266273f,0.0776054f},{-0.0515825f,-0.264758f,0.055677f}, -{-0.0481711f,-0.261828f,0.0333897f},{-0.0466503f,-0.260522f,0.0259331f},{-0.044933f,-0.259047f,0.0184831f}, -{-0.0454772f,-0.259191f,0.0183202f},{-0.0435573f,-0.257542f,0.0108731f},{-0.0430173f,-0.257402f,0.0110526f}, -{-0.040902f,-0.255585f,0.00365461f},{-0.0385862f,-0.253596f,-0.00369726f},{-0.0360702f,-0.251435f,-0.0109894f}, -{-0.0333545f,-0.249102f,-0.0182079f},{-0.0240277f,-0.241092f,-0.0392827f},{-0.0245255f,-0.241196f,-0.0395738f}, -{-0.0210253f,-0.238189f,-0.0463744f},{-0.0205352f,-0.238092f,-0.0460682f},{-0.0168576f,-0.234933f,-0.0527117f}, -{-0.013f,-0.23162f,-0.0592001f},{-0.00040769f,-0.220805f,-0.0776124f},{-0.000853084f,-0.220864f,-0.0779886f}, -{0.00367072f,-0.216978f,-0.0837496f},{0.00410608f,-0.216928f,-0.0833607f},{0.00876485f,-0.212927f,-0.088897f}, -{0.0135599f,-0.208808f,-0.094212f},{0.0286697f,-0.195831f,-0.108749f},{0.0282889f,-0.195834f,-0.109195f}, -{0.0335459f,-0.191319f,-0.113558f},{0.0339151f,-0.191326f,-0.113103f},{0.0392479f,-0.186745f,-0.117203f}, -{0.0446573f,-0.182099f,-0.121044f},{0.0501331f,-0.177396f,-0.124624f},{0.0668538f,-0.163035f,-0.133782f}, -{0.0724906f,-0.158194f,-0.136307f},{0.072207f,-0.158114f,-0.136814f},{0.0778712f,-0.153249f,-0.139083f}, -{0.0781422f,-0.15334f,-0.138571f},{0.0837988f,-0.148482f,-0.140576f},{0.0894511f,-0.143627f,-0.142325f}, -{0.0950898f,-0.138784f,-0.143823f},{0.100706f,-0.13396f,-0.145073f},{0.106292f,-0.129162f,-0.146082f}, -{-0.0534963f,-0.266078f,0.0703053f},{-0.0529085f,-0.265573f,0.0629764f},{-0.0539095f,-0.266433f,0.0775737f}, -{-0.0521415f,-0.264914f,0.0555966f},{-0.0511908f,-0.264098f,0.0481766f},{-0.0500523f,-0.26312f,0.0407271f}, -{-0.0487225f,-0.261978f,0.0332599f},{-0.0471983f,-0.260669f,0.0257867f},{-0.0414372f,-0.255721f,0.00345877f}, -{-0.0396062f,-0.253647f,-0.00404829f},{-0.0391164f,-0.253727f,-0.00390942f},{-0.0365947f,-0.251562f,-0.0112177f}, -{-0.033873f,-0.249224f,-0.0184523f},{-0.0309526f,-0.246716f,-0.0255992f},{-0.0278358f,-0.244039f,-0.0326442f}, -{-0.0177978f,-0.234916f,-0.0532427f},{-0.0173395f,-0.235024f,-0.0530326f},{-0.0134733f,-0.231703f,-0.0595354f}, -{-0.00943248f,-0.228232f,-0.0658703f},{-0.00522337f,-0.224617f,-0.0720252f},{0.0079188f,-0.212829f,-0.0895609f}, -{0.00833983f,-0.212968f,-0.0892982f},{0.0131455f,-0.208841f,-0.0946251f},{0.0180787f,-0.204604f,-0.0997217f}, -{0.0231298f,-0.200265f,-0.10458f},{0.0385138f,-0.186551f,-0.117971f},{0.0388905f,-0.186729f,-0.117667f}, -{0.044312f,-0.182072f,-0.121517f},{0.0497999f,-0.177359f,-0.125105f},{0.0553439f,-0.172597f,-0.128429f}, -{0.0609333f,-0.167797f,-0.131488f},{0.0665577f,-0.162966f,-0.134283f},{0.0835403f,-0.14838f,-0.141092f}, -{0.0889013f,-0.143275f,-0.143185f},{0.0892051f,-0.143514f,-0.142845f},{0.0948564f,-0.138661f,-0.144346f}, -{0.100485f,-0.133826f,-0.145599f},{0.106084f,-0.129018f,-0.14661f},{0.117158f,-0.119507f,-0.147929f}, -{-0.0547929f,-0.266634f,0.0918925f},{-0.0540069f,-0.266016f,0.070274f},{-0.0534183f,-0.26551f,0.0629344f}, -{-0.0526502f,-0.264851f,0.055544f},{-0.0516981f,-0.264033f,0.0481132f},{-0.050558f,-0.263054f,0.040653f}, -{-0.0492262f,-0.26191f,0.0331749f},{-0.0476998f,-0.260599f,0.0256909f},{-0.0459762f,-0.259118f,0.0182135f}, -{-0.0440535f,-0.257467f,0.0107557f},{-0.0419304f,-0.255643f,0.00333058f},{-0.037453f,-0.251278f,-0.0114393f}, -{-0.0352296f,-0.248914f,-0.0180677f},{-0.0347255f,-0.248935f,-0.0186894f},{-0.0370809f,-0.251478f,-0.0113672f}, -{-0.0343552f,-0.249137f,-0.0186123f},{-0.0314306f,-0.246625f,-0.0257695f},{-0.0283092f,-0.243945f,-0.0328247f}, -{-0.0249941f,-0.241097f,-0.0397644f},{-0.0214889f,-0.238087f,-0.0465748f},{-0.013926f,-0.231591f,-0.0597549f}, -{-0.014282f,-0.231377f,-0.0598609f},{-0.00987926f,-0.228115f,-0.066099f},{-0.00566404f,-0.224495f,-0.0722628f}, -{-0.00128743f,-0.220736f,-0.0782348f},{0.00324293f,-0.216845f,-0.0840042f},{0.0123941f,-0.208465f,-0.0950259f}, -{0.0164425f,-0.204534f,-0.0995152f},{0.0173378f,-0.204219f,-0.100133f},{0.0127315f,-0.208695f,-0.0948954f}, -{0.0176718f,-0.204452f,-0.0999994f},{0.0227302f,-0.200108f,-0.104865f},{0.0278968f,-0.19567f,-0.109486f}, -{0.0331614f,-0.191149f,-0.113856f},{0.0439431f,-0.181888f,-0.121826f},{0.0491273f,-0.176916f,-0.125571f}, -{0.049439f,-0.177168f,-0.125419f},{0.054991f,-0.1724f,-0.128748f},{0.0605885f,-0.167592f,-0.131812f}, -{0.0662211f,-0.162754f,-0.134611f},{0.0718786f,-0.157895f,-0.137145f},{0.0775509f,-0.153023f,-0.139417f}, -{0.0832283f,-0.148147f,-0.14143f},{0.0945608f,-0.138414f,-0.144688f},{0.100198f,-0.133572f,-0.145943f}, -{0.105804f,-0.128757f,-0.146956f},{-0.0543909f,-0.265826f,0.0702589f},{-0.0538019f,-0.26532f,0.0629142f}, -{-0.0530333f,-0.264659f,0.0555186f},{-0.0520805f,-0.263841f,0.0480826f},{-0.0509396f,-0.262861f,0.0406172f}, -{-0.0496069f,-0.261717f,0.0331338f},{-0.0480794f,-0.260405f,0.0256447f},{-0.0463547f,-0.258923f,0.0181621f}, -{-0.0444306f,-0.257271f,0.010699f},{-0.042306f,-0.255446f,0.00326873f},{-0.0399801f,-0.253448f,-0.0041153f}, -{-0.0317988f,-0.246422f,-0.0258517f},{-0.0286753f,-0.243739f,-0.0329118f},{-0.0253579f,-0.24089f,-0.0398563f}, -{-0.0218502f,-0.237877f,-0.0466715f},{-0.0181565f,-0.234704f,-0.0533441f},{-0.0179111f,-0.23404f,-0.0542301f}, -{-0.0102325f,-0.227899f,-0.0662094f},{-0.0060143f,-0.224276f,-0.0723775f},{-0.00163463f,-0.220514f,-0.0783537f}, -{0.0028989f,-0.21662f,-0.0841271f},{0.00757805f,-0.212602f,-0.0896876f},{0.0223998f,-0.199871f,-0.105003f}, -{0.02757f,-0.195431f,-0.109627f},{0.0328383f,-0.190906f,-0.114f},{0.0381944f,-0.186306f,-0.118117f}, -{0.0436275f,-0.181639f,-0.121975f},{0.0438755f,-0.180973f,-0.122344f},{0.0546831f,-0.172144f,-0.128902f}, -{0.0602845f,-0.167333f,-0.131968f},{0.0659211f,-0.162492f,-0.134769f},{0.0715825f,-0.157629f,-0.137305f}, -{0.0772588f,-0.152754f,-0.139579f},{0.0829402f,-0.147874f,-0.141593f},{0.0886171f,-0.142999f,-0.143349f}, -{0.0942805f,-0.138134f,-0.144853f},{0.0999216f,-0.133289f,-0.146109f},{0.105532f,-0.128471f,-0.147123f}, -{0.111104f,-0.123685f,-0.147899f},{0.11663f,-0.118939f,-0.148445f},{-0.0546653f,-0.265607f,0.0705096f}, -{-0.0541047f,-0.265126f,0.0634113f},{-0.0533848f,-0.264508f,0.056338f},{-0.0525062f,-0.263753f,0.0492957f}, -{-0.0514696f,-0.262863f,0.042291f},{-0.0502761f,-0.261838f,0.0353299f},{-0.0489266f,-0.260679f,0.0284186f}, -{-0.0474223f,-0.259387f,0.0215629f},{-0.0457645f,-0.257963f,0.0147688f},{-0.0439548f,-0.256408f,0.00804257f}, -{-0.0419946f,-0.254725f,0.00139006f},{-0.0398858f,-0.252914f,-0.00518291f},{-0.0376301f,-0.250976f,-0.0116708f}, -{-0.0326863f,-0.24673f,-0.024368f},{-0.0300025f,-0.244425f,-0.0305661f},{-0.0271806f,-0.242001f,-0.0366566f}, -{-0.0242229f,-0.239461f,-0.0426344f},{-0.0211322f,-0.236806f,-0.0484939f},{-0.0145625f,-0.231164f,-0.0598379f}, -{-0.0110894f,-0.228181f,-0.0653124f},{-0.00749453f,-0.225093f,-0.0706491f},{-0.00378138f,-0.221904f,-0.0758429f}, -{4.68637e-005f,-0.218616f,-0.0808893f},{0.00398685f,-0.215232f,-0.0857839f},{0.00803512f,-0.211755f,-0.0905225f}, -{0.0121883f,-0.208188f,-0.095101f},{0.020794f,-0.200797f,-0.103761f},{0.025239f,-0.196979f,-0.107835f}, -{0.0297737f,-0.193084f,-0.111734f},{0.0343942f,-0.189116f,-0.115454f},{0.0390962f,-0.185078f,-0.118992f}, -{0.0487282f,-0.176805f,-0.125509f},{0.0536499f,-0.172578f,-0.128482f},{0.0586363f,-0.168295f,-0.131262f}, -{0.063683f,-0.16396f,-0.133846f},{0.0687854f,-0.159578f,-0.136231f},{0.0739393f,-0.155151f,-0.138417f}, -{0.0791401f,-0.150685f,-0.1404f},{0.0843832f,-0.146181f,-0.142179f},{0.089664f,-0.141646f,-0.143752f}, -{0.0949777f,-0.137082f,-0.145118f},{0.10032f,-0.132494f,-0.146276f},{0.105686f,-0.127885f,-0.147225f}, -{0.111071f,-0.12326f,-0.147964f},{0.11647f,-0.118623f,-0.148493f},{-0.0258064f,-0.240367f,-0.0398563f}, -{-0.0222987f,-0.237355f,-0.0466715f},{-0.0147777f,-0.22955f,-0.0592001f},{-0.0108902f,-0.226535f,-0.0658703f}, -{-0.0149311f,-0.230006f,-0.0595354f},{-0.0322473f,-0.245899f,-0.0258517f},{-0.0291238f,-0.243217f,-0.0329118f}, -{-0.0379016f,-0.250756f,-0.0114393f},{-0.035174f,-0.248413f,-0.0186894f},{-0.0404286f,-0.252926f,-0.0041153f}, -{-0.0427545f,-0.254924f,0.00326873f},{-0.0448791f,-0.256749f,0.010699f},{-0.0380524f,-0.249864f,-0.0112177f}, -{-0.0380435f,-0.250358f,-0.0113672f},{-0.0405741f,-0.25203f,-0.00390942f},{-0.0468032f,-0.258401f,0.0181621f}, -{-0.048528f,-0.259882f,0.0256447f},{-0.0500554f,-0.261194f,0.0331338f},{-0.0513881f,-0.262339f,0.0406172f}, -{-0.052529f,-0.263319f,0.0480826f},{-0.0534818f,-0.264137f,0.0555186f},{-0.0542505f,-0.264797f,0.0629142f}, -{-0.0548395f,-0.265303f,0.0702589f},{-0.0549696f,-0.264895f,0.070274f},{-0.054381f,-0.264389f,0.0629344f}, -{-0.0534428f,-0.264104f,0.0848373f},{-0.0538273f,-0.263914f,0.0848323f},{-0.0543389f,-0.263852f,0.084822f}, -{-0.0542202f,-0.263922f,0.0918925f},{-0.0535408f,-0.26416f,0.0918925f},{-0.053201f,-0.263896f,0.0777045f}, -{-0.0527915f,-0.263544f,0.0705025f},{-0.0531755f,-0.263354f,0.0704874f},{-0.054954f,-0.264381f,0.0703053f}, -{-0.0543662f,-0.263876f,0.0629764f},{-0.0541256f,-0.263346f,0.0630404f},{-0.0535992f,-0.263217f,0.0555966f}, -{-0.054712f,-0.263849f,0.0703531f},{-0.0552536f,-0.265659f,0.0775429f},{-0.0557203f,-0.26521f,0.0918925f}, -{-0.0556112f,-0.264945f,0.0847723f},{-0.0556278f,-0.26546f,0.084762f},{-0.0556436f,-0.264849f,0.0918925f}, -{-0.0553678f,-0.264412f,0.084788f},{-0.0554769f,-0.264524f,0.0918925f},{-0.0557001f,-0.26557f,0.0918925f}, -{-0.0554981f,-0.265869f,0.084757f},{-0.0555879f,-0.265918f,0.0918925f},{-0.0549023f,-0.264013f,0.0848062f}, -{-0.0545795f,-0.263942f,0.0918925f},{-0.018605f,-0.234182f,-0.0533441f},{-0.0147305f,-0.230855f,-0.0598609f}, -{-0.010681f,-0.227376f,-0.0662094f},{-0.00646282f,-0.223754f,-0.0723775f},{-0.00208315f,-0.219992f,-0.0783537f}, -{0.00245038f,-0.216098f,-0.0841271f},{0.0117689f,-0.207575f,-0.0948954f},{0.00688212f,-0.211271f,-0.0892982f}, -{0.0116878f,-0.207143f,-0.0946251f},{0.00712952f,-0.212079f,-0.0896876f},{0.0119456f,-0.207943f,-0.0950259f}, -{0.0168893f,-0.203697f,-0.100133f},{0.0219512f,-0.199349f,-0.105003f},{0.0271214f,-0.194909f,-0.109627f}, -{0.0323898f,-0.190384f,-0.114f},{0.0377459f,-0.185784f,-0.118117f},{0.0483422f,-0.175662f,-0.125105f}, -{0.0483555f,-0.175327f,-0.124624f},{0.0538862f,-0.1709f,-0.128429f},{0.043179f,-0.181117f,-0.121975f}, -{0.0486787f,-0.176393f,-0.125571f},{0.0542346f,-0.171622f,-0.128902f},{0.059836f,-0.166811f,-0.131968f}, -{0.0654725f,-0.16197f,-0.134769f},{0.071134f,-0.157107f,-0.137305f},{0.0768103f,-0.152232f,-0.139579f}, -{0.0824916f,-0.147352f,-0.141593f},{0.0879387f,-0.142154f,-0.143185f},{0.0881686f,-0.142476f,-0.143349f}, -{0.0822657f,-0.147026f,-0.14143f},{0.093832f,-0.137612f,-0.144853f},{0.105084f,-0.127948f,-0.147123f}, -{0.0992353f,-0.132451f,-0.145943f},{0.104842f,-0.127636f,-0.146956f},{0.110062f,-0.122328f,-0.146855f}, -{0.110104f,-0.122292f,-0.146244f},{0.115564f,-0.117602f,-0.147398f},{0.0933121f,-0.136714f,-0.143823f}, -{0.0989286f,-0.13189f,-0.145073f},{0.0990277f,-0.132129f,-0.145599f},{0.110572f,-0.122715f,-0.145367f}, -{0.1103f,-0.122447f,-0.145714f},{0.105059f,-0.12745f,-0.144599f},{0.121454f,-0.113368f,-0.146226f}, -{0.126687f,-0.108624f,-0.146474f},{0.121199f,-0.113087f,-0.146574f},{0.1157f,-0.117809f,-0.147929f}, -{0.110186f,-0.122545f,-0.147385f},{0.126873f,-0.108841f,-0.146297f},{0.121715f,-0.113664f,-0.146058f}, -{0.127073f,-0.109073f,-0.146158f},{0.104626f,-0.12732f,-0.14661f},{0.104515f,-0.127092f,-0.146082f}, -{0.115932f,-0.118111f,-0.148277f},{0.11041f,-0.122854f,-0.147732f},{0.0994731f,-0.132767f,-0.146109f}, -{0.110655f,-0.123163f,-0.147899f},{0.116181f,-0.118417f,-0.148445f},{0.121654f,-0.113716f,-0.148767f}, -{0.127073f,-0.109074f,-0.148876f},{-0.0549276f,-0.264054f,0.0918925f},{-0.0553834f,-0.26525f,0.0775529f}, -{-0.0536128f,-0.26373f,0.055544f},{-0.0526607f,-0.262912f,0.0481132f},{-0.0515206f,-0.261933f,0.040653f}, -{-0.0501889f,-0.260789f,0.0331749f},{-0.0486625f,-0.259478f,0.0256909f},{-0.0469389f,-0.257998f,0.0182135f}, -{-0.0450162f,-0.256346f,0.0107557f},{-0.042893f,-0.254523f,0.00333058f},{-0.0405688f,-0.252526f,-0.00404829f}, -{-0.0353178f,-0.248016f,-0.0186123f},{-0.0323932f,-0.245505f,-0.0257695f},{-0.0292719f,-0.242824f,-0.0328247f}, -{-0.0259568f,-0.239976f,-0.0397644f},{-0.0224515f,-0.236966f,-0.0465748f},{-0.0187604f,-0.233796f,-0.0532427f}, -{-0.0148886f,-0.23047f,-0.0597549f},{-0.0108419f,-0.226995f,-0.066099f},{-0.00662668f,-0.223374f,-0.0722628f}, -{-0.00225007f,-0.219615f,-0.0782348f},{0.00228029f,-0.215724f,-0.0840042f},{0.00695617f,-0.211708f,-0.0895609f}, -{0.0167092f,-0.203331f,-0.0999994f},{0.0217676f,-0.198987f,-0.104865f},{0.0269342f,-0.194549f,-0.109486f}, -{0.0321988f,-0.190028f,-0.113856f},{0.0375512f,-0.185431f,-0.117971f},{0.0429805f,-0.180768f,-0.121826f}, -{0.0484764f,-0.176047f,-0.125419f},{0.0540283f,-0.171279f,-0.128748f},{0.0596258f,-0.166471f,-0.131812f}, -{0.0652585f,-0.161633f,-0.134611f},{0.070916f,-0.156774f,-0.137145f},{0.0765883f,-0.151902f,-0.139417f}, -{0.0935981f,-0.137293f,-0.144688f},{0.0933987f,-0.136964f,-0.144346f},{0.121401f,-0.113414f,-0.148599f}, -{0.12687f,-0.108837f,-0.148751f},{-0.0553672f,-0.264736f,0.0775737f},{-0.0526485f,-0.262401f,0.0481766f}, -{-0.05151f,-0.261423f,0.0407271f},{-0.0501802f,-0.260281f,0.0332599f},{-0.048656f,-0.258972f,0.0257867f}, -{-0.0469349f,-0.257493f,0.0183202f},{-0.045015f,-0.255844f,0.0108731f},{-0.0428949f,-0.254024f,0.00345877f}, -{-0.0324103f,-0.245018f,-0.0255992f},{-0.0353307f,-0.247527f,-0.0184523f},{-0.0351321f,-0.247032f,-0.0182079f}, -{-0.0292935f,-0.242341f,-0.0326442f},{-0.0259832f,-0.239498f,-0.0395738f},{-0.022483f,-0.236492f,-0.0463744f}, -{-0.0187972f,-0.233326f,-0.0530326f},{-0.00668107f,-0.22292f,-0.0720252f},{-0.00231079f,-0.219167f,-0.0779886f}, -{0.00221301f,-0.215281f,-0.0837496f},{0.0217444f,-0.198182f,-0.104145f},{0.0220124f,-0.197952f,-0.103643f}, -{0.0268921f,-0.193761f,-0.108749f},{0.016621f,-0.202906f,-0.0997217f},{0.0216721f,-0.198568f,-0.10458f}, -{0.0268312f,-0.194137f,-0.109195f},{0.0320882f,-0.189622f,-0.113558f},{0.0374328f,-0.185032f,-0.117667f}, -{0.0428543f,-0.180375f,-0.121517f},{0.0594756f,-0.166099f,-0.131488f},{0.0651f,-0.161269f,-0.134283f}, -{0.0707493f,-0.156417f,-0.136814f},{0.0764135f,-0.151552f,-0.139083f},{0.0820826f,-0.146683f,-0.141092f}, -{0.0877474f,-0.141817f,-0.142845f},{0.126387f,-0.108276f,-0.147687f},{0.121013f,-0.112922f,-0.147719f}, -{0.121027f,-0.112911f,-0.147106f},{0.121161f,-0.113119f,-0.148251f},{0.12669f,-0.108628f,-0.148558f}, -{-0.0552371f,-0.264255f,0.0918925f},{-0.0551243f,-0.264203f,0.0776054f},{-0.0533602f,-0.262688f,0.055677f}, -{-0.0524116f,-0.261874f,0.0482734f},{-0.0494972f,-0.25937f,0.0335395f},{-0.048428f,-0.258452f,0.0259331f}, -{-0.0499488f,-0.259758f,0.0333897f},{-0.0512756f,-0.260898f,0.0408405f},{-0.0467107f,-0.256977f,0.0184831f}, -{-0.044795f,-0.255332f,0.0110526f},{-0.0426797f,-0.253515f,0.00365461f},{-0.0403639f,-0.251526f,-0.00369726f}, -{-0.0378479f,-0.249365f,-0.0109894f},{-0.0287101f,-0.241517f,-0.0320502f},{-0.0258054f,-0.239022f,-0.0392827f}, -{-0.0291083f,-0.241859f,-0.0323684f},{-0.0322182f,-0.24453f,-0.025339f},{-0.0223129f,-0.236022f,-0.0460682f}, -{-0.0186353f,-0.232864f,-0.0527117f},{-0.00620553f,-0.222188f,-0.0712434f},{-0.00218538f,-0.218735f,-0.0776124f}, -{-0.006546f,-0.22248f,-0.0716622f},{-0.0107458f,-0.226088f,-0.065521f},{0.00232839f,-0.214858f,-0.0833607f}, -{0.00698716f,-0.210857f,-0.088897f},{0.0117822f,-0.206739f,-0.094212f},{0.0167045f,-0.202511f,-0.0992973f}, -{0.0321374f,-0.189256f,-0.113103f},{0.0374702f,-0.184676f,-0.117203f},{0.0428796f,-0.18003f,-0.121044f}, -{0.0596356f,-0.165638f,-0.130423f},{0.0650762f,-0.160965f,-0.133782f},{0.0594641f,-0.165786f,-0.130993f}, -{0.0538871f,-0.170576f,-0.127941f},{0.0707129f,-0.156124f,-0.136307f},{0.0763645f,-0.15127f,-0.138571f}, -{0.0820211f,-0.146412f,-0.140576f},{0.0876734f,-0.141557f,-0.142325f},{0.115776f,-0.117744f,-0.146255f}, -{0.104571f,-0.127044f,-0.145472f},{0.12644f,-0.108337f,-0.148015f},{0.126544f,-0.108458f,-0.14831f}, -{-0.0542482f,-0.263451f,0.0704083f},{-0.0546595f,-0.263804f,0.077642f},{-0.0536632f,-0.262949f,0.0631143f}, -{-0.0528999f,-0.262293f,0.0557698f},{-0.0519537f,-0.26148f,0.0483851f},{-0.0508206f,-0.260507f,0.0409712f}, -{-0.0479802f,-0.258067f,0.026102f},{-0.0422467f,-0.253143f,0.00388058f},{-0.0443566f,-0.254955f,0.0112596f}, -{-0.0438167f,-0.254815f,0.011439f},{-0.0462674f,-0.256596f,0.0186711f},{-0.0399369f,-0.251159f,-0.00345247f}, -{-0.0374272f,-0.249004f,-0.0107259f},{-0.0347185f,-0.246677f,-0.017926f},{-0.031812f,-0.244181f,-0.0250388f}, -{-0.0173238f,-0.232562f,-0.0518103f},{-0.017782f,-0.232454f,-0.0520204f},{-0.0209784f,-0.235701f,-0.0452083f}, -{-0.0254156f,-0.238687f,-0.0389468f},{-0.0219321f,-0.235695f,-0.0457149f},{-0.0182639f,-0.232545f,-0.0523413f}, -{-0.0144162f,-0.22924f,-0.0588132f},{-0.0103946f,-0.225786f,-0.0651178f},{0.00813902f,-0.210692f,-0.0877701f}, -{0.00771801f,-0.210553f,-0.0880327f},{0.00350929f,-0.214669f,-0.0822683f},{-0.00185609f,-0.218452f,-0.0771783f}, -{0.00264613f,-0.214585f,-0.0829118f},{0.00729298f,-0.210594f,-0.088434f},{0.0120758f,-0.206487f,-0.0937354f}, -{0.0169854f,-0.20227f,-0.0988077f},{0.037698f,-0.18448f,-0.116668f},{0.0323788f,-0.189049f,-0.112578f}, -{0.0327481f,-0.189055f,-0.112123f},{0.0271469f,-0.193542f,-0.108235f},{0.0430935f,-0.179846f,-0.120499f}, -{0.0485553f,-0.175155f,-0.12407f},{0.0540728f,-0.170416f,-0.127378f},{0.0652332f,-0.160831f,-0.133204f}, -{0.0821348f,-0.146314f,-0.139981f},{0.0764927f,-0.15116f,-0.137981f},{0.0767637f,-0.151251f,-0.137469f}, -{0.0708556f,-0.156002f,-0.135723f},{0.0877726f,-0.141472f,-0.141725f},{0.0933968f,-0.136641f,-0.143219f}, -{0.098999f,-0.13183f,-0.144466f},{0.104779f,-0.127189f,-0.144944f},{0.115592f,-0.117579f,-0.146786f}, -{-0.0536862f,-0.263292f,0.0704561f},{-0.0540966f,-0.263644f,0.0776737f},{-0.0531026f,-0.262791f,0.0631783f}, -{-0.0523409f,-0.262136f,0.0558501f},{-0.0513968f,-0.261326f,0.0484819f},{-0.0502663f,-0.260355f,0.0410845f}, -{-0.0489458f,-0.25922f,0.0336694f},{-0.0474322f,-0.257921f,0.0262484f},{-0.0457232f,-0.256453f,0.018834f}, -{-0.0412182f,-0.253084f,0.00420461f},{-0.0389169f,-0.251108f,-0.00310144f},{-0.0394067f,-0.251028f,-0.00324031f}, -{-0.0417114f,-0.253007f,0.00407642f},{-0.0369027f,-0.248877f,-0.0104976f},{-0.0342f,-0.246556f,-0.0176816f}, -{-0.0313f,-0.244065f,-0.0247786f},{-0.028205f,-0.241407f,-0.0317744f},{-0.0249178f,-0.238583f,-0.0386556f}, -{-0.021442f,-0.235598f,-0.0454087f},{-0.0139428f,-0.229157f,-0.0584778f},{-0.00993018f,-0.225711f,-0.0647685f}, -{-0.00575046f,-0.222121f,-0.0708804f},{-0.0014107f,-0.218393f,-0.0768021f},{0.0030815f,-0.214535f,-0.0825229f}, -{0.0124902f,-0.206454f,-0.0933224f},{0.0173889f,-0.202247f,-0.0983834f},{0.0224047f,-0.197939f,-0.103208f}, -{0.0275277f,-0.193539f,-0.10779f},{0.0384321f,-0.184674f,-0.1159f},{0.0438078f,-0.180057f,-0.119717f}, -{0.0434389f,-0.179873f,-0.120026f},{0.0380553f,-0.184497f,-0.116203f},{0.0488885f,-0.175192f,-0.123589f}, -{0.0543937f,-0.170464f,-0.12689f},{0.0599441f,-0.165697f,-0.129928f},{0.0655293f,-0.1609f,-0.132703f}, -{0.0711392f,-0.156082f,-0.135216f},{0.0823933f,-0.146416f,-0.139465f},{0.0883223f,-0.141824f,-0.140865f}, -{0.0939259f,-0.137011f,-0.142353f},{0.0936303f,-0.136765f,-0.142696f},{0.0880185f,-0.141584f,-0.141206f}, -{0.09922f,-0.131964f,-0.14394f},{0.126439f,-0.108336f,-0.147023f},{0.126387f,-0.108275f,-0.147351f}, -{-0.0538591f,-0.263998f,0.0918925f},{-0.0535853f,-0.263706f,0.0776945f},{-0.0525928f,-0.262854f,0.0632202f}, -{-0.0518322f,-0.2622f,0.0559028f},{-0.0522092f,-0.263044f,0.0632405f},{-0.0508895f,-0.261391f,0.0485453f}, -{-0.0497606f,-0.260421f,0.0411587f},{-0.048442f,-0.259289f,0.0337544f},{-0.0469307f,-0.257991f,0.0263442f}, -{-0.0452241f,-0.256525f,0.0189407f},{-0.0433204f,-0.25489f,0.0115564f},{-0.0333475f,-0.246844f,-0.0174445f}, -{-0.0360443f,-0.249161f,-0.010276f},{-0.0364165f,-0.24896f,-0.0103481f},{-0.0337177f,-0.246642f,-0.0175217f}, -{-0.030822f,-0.244155f,-0.0246083f},{-0.0277315f,-0.241501f,-0.0315939f},{-0.0244491f,-0.238682f,-0.038465f}, -{-0.0131342f,-0.229483f,-0.0581524f},{-0.0134902f,-0.229269f,-0.0582583f},{-0.016965f,-0.232774f,-0.051709f}, -{-0.00948339f,-0.225828f,-0.0645398f},{-0.00530978f,-0.222243f,-0.0706427f},{-0.00097635f,-0.218521f,-0.0765558f}, -{0.0132416f,-0.20683f,-0.0929216f},{0.0181297f,-0.202631f,-0.0979716f},{0.0129042f,-0.206599f,-0.093052f}, -{0.0177958f,-0.202398f,-0.0981056f},{0.0228042f,-0.198097f,-0.102923f},{0.0279198f,-0.193703f,-0.107499f}, -{0.0331325f,-0.189226f,-0.111826f},{0.0495612f,-0.175636f,-0.123123f},{0.0492495f,-0.175383f,-0.123274f}, -{0.0441234f,-0.180306f,-0.119568f},{0.0547466f,-0.170662f,-0.126571f},{0.0602889f,-0.165902f,-0.129604f}, -{0.0658659f,-0.161112f,-0.132375f},{0.0714676f,-0.156301f,-0.134885f},{0.0770839f,-0.151477f,-0.137135f}, -{0.0827053f,-0.146649f,-0.139127f},{0.0995074f,-0.132218f,-0.143596f},{0.116304f,-0.118312f,-0.145739f}, -{0.11084f,-0.123004f,-0.145199f},{0.116039f,-0.118019f,-0.145907f},{0.126541f,-0.108454f,-0.146724f}, -{-0.0514492f,-0.262391f,0.0559281f},{-0.0505071f,-0.261582f,0.0485758f},{-0.049379f,-0.260613f,0.0411945f}, -{-0.0480614f,-0.259482f,0.0337954f},{-0.0465511f,-0.258185f,0.0263905f},{-0.0448457f,-0.25672f,0.0189921f}, -{-0.0429433f,-0.255086f,0.0116131f},{-0.0408426f,-0.253282f,0.00426646f},{-0.038543f,-0.251307f,-0.00303443f}, -{-0.0304538f,-0.244359f,-0.0245261f},{-0.0273654f,-0.241706f,-0.0315068f},{-0.0240853f,-0.238889f,-0.0383731f}, -{-0.0206171f,-0.23591f,-0.0451116f},{-0.00913019f,-0.226044f,-0.0644294f},{-0.00495953f,-0.222462f,-0.0705281f}, -{-0.00062916f,-0.218743f,-0.076437f},{0.00385332f,-0.214893f,-0.0821454f},{0.00847979f,-0.21092f,-0.0876434f}, -{0.0231347f,-0.198333f,-0.102786f},{0.0282467f,-0.193942f,-0.107358f},{0.0334557f,-0.189468f,-0.111682f}, -{0.0387515f,-0.18492f,-0.115753f},{0.0550545f,-0.170917f,-0.126416f},{0.0605929f,-0.166161f,-0.129448f}, -{0.066166f,-0.161374f,-0.132217f},{0.0717637f,-0.156566f,-0.134725f},{0.0773761f,-0.151746f,-0.136973f}, -{0.0829935f,-0.146921f,-0.138964f},{0.0886065f,-0.1421f,-0.140701f},{0.0942061f,-0.137291f,-0.142188f}, -{0.0997837f,-0.1325f,-0.14343f},{0.105331f,-0.127736f,-0.144432f},{0.246242f,-0.00568906f,-0.0892991f}, -{0.241437f,-0.00981657f,-0.0946258f},{0.241022f,-0.00984878f,-0.0942128f},{0.221744f,-0.0277507f,-0.114f}, -{0.227012f,-0.023226f,-0.109627f},{0.216388f,-0.0323507f,-0.118117f},{0.210955f,-0.0370173f,-0.121975f}, -{0.205455f,-0.0417412f,-0.125571f},{0.199899f,-0.0465131f,-0.128902f},{0.194298f,-0.0513242f,-0.131968f}, -{0.188661f,-0.0561654f,-0.134769f},{0.205143f,-0.0414889f,-0.125419f},{0.199238f,-0.0460598f,-0.128429f}, -{0.204783f,-0.041298f,-0.125105f},{0.182999f,-0.061028f,-0.137305f},{0.177323f,-0.0659033f,-0.139579f}, -{0.171642f,-0.0707829f,-0.141592f},{0.160302f,-0.0805227f,-0.144853f},{0.165965f,-0.0756586f,-0.143349f}, -{0.154661f,-0.0853677f,-0.146109f},{0.14905f,-0.0901863f,-0.147122f},{0.143479f,-0.0949717f,-0.147899f}, -{0.132419f,-0.10447f,-0.146057f},{0.14321f,-0.0946823f,-0.147731f},{0.148778f,-0.0899002f,-0.146955f}, -{0.143294f,-0.0951304f,-0.145199f},{0.143048f,-0.0948213f,-0.145366f},{0.13783f,-0.0998229f,-0.145739f}, -{0.14829f,-0.0894947f,-0.146081f},{0.154097f,-0.084831f,-0.145599f},{0.148499f,-0.0896393f,-0.14661f}, -{0.131926f,-0.103873f,-0.146574f},{0.131778f,-0.103676f,-0.147105f},{0.132166f,-0.104168f,-0.146225f}, -{0.142939f,-0.0944145f,-0.147384f},{0.131792f,-0.103664f,-0.147719f},{0.13248f,-0.104418f,-0.148767f}, -{0.132219f,-0.104122f,-0.148599f},{0.137953f,-0.0997176f,-0.148445f},{0.131964f,-0.10384f,-0.148251f}, -{0.142742f,-0.0942593f,-0.146855f},{0.232183f,-0.0187856f,-0.105003f},{0.237244f,-0.0144381f,-0.100134f}, -{0.242188f,-0.010192f,-0.0950266f},{0.247004f,-0.00605566f,-0.0896885f},{0.251683f,-0.00203683f,-0.0841281f}, -{0.256217f,0.00185696f,-0.0783547f},{0.260596f,0.00561864f,-0.0723786f},{0.268508f,0.0129341f,-0.059756f}, -{0.264015f,0.00957541f,-0.0658715f},{0.268056f,0.0130461f,-0.0595366f},{0.264815f,0.00924161f,-0.0662105f}, -{0.268864f,0.0127198f,-0.059862f},{0.272739f,0.0160476f,-0.053345f},{0.276433f,0.0192201f,-0.0466724f}, -{0.279941f,0.022233f,-0.039857f},{0.283258f,0.0250823f,-0.0329122f},{0.286382f,0.0277651f,-0.0258517f}, -{0.291178f,0.0329051f,-0.0112184f},{0.290653f,0.0327782f,-0.01099f},{0.293699f,0.0350709f,-0.00391029f}, -{0.289308f,0.0302787f,-0.0186898f},{0.292036f,0.0326214f,-0.0114399f},{0.294563f,0.0347919f,-0.00411618f}, -{0.296889f,0.0367896f,0.00326766f},{0.299014f,0.0386144f,0.0106978f},{0.300938f,0.040267f,0.0181608f}, -{0.302663f,0.0417484f,0.0256434f},{0.30419f,0.0430604f,0.0331326f},{0.305141f,0.0443974f,0.0406518f}, -{0.305523f,0.044205f,0.040616f},{0.303809f,0.0432535f,0.0331736f},{0.306664f,0.045185f,0.0480815f}, -{0.308737f,0.0479862f,0.0847721f},{0.30793f,0.0476169f,0.077605f},{0.308173f,0.0478259f,0.0847878f}, -{0.306812f,0.0463329f,0.0704555f},{0.307054f,0.0468645f,0.0704077f},{0.306228f,0.0458317f,0.0631775f}, -{0.307233f,0.0461944f,0.0555431f},{0.308002f,0.0468541f,0.0629336f},{0.308385f,0.0466635f,0.0629134f}, -{0.306796f,0.0458187f,0.0704868f},{0.306213f,0.0453183f,0.0632194f},{0.307448f,0.0463783f,0.0848321f}, -{0.307515f,0.0467654f,0.0918925f},{0.307464f,0.0468934f,0.0848218f},{0.306931f,0.0467592f,0.0630396f}, -{0.308079f,0.0474218f,0.0703047f},{0.307492f,0.046917f,0.0629755f},{0.307577f,0.0459696f,0.0848371f}, -{0.307535f,0.0464061f,0.0918925f},{0.306166f,0.0461019f,0.0556761f},{0.306725f,0.0462583f,0.0555957f}, -{0.305217f,0.0452871f,0.0482723f},{0.307647f,0.046058f,0.0918925f},{0.307617f,0.0460033f,0.0555177f}, -{0.309388f,0.047525f,0.0775425f},{0.308974f,0.0471693f,0.0702583f},{0.30859f,0.0473596f,0.0702734f}, -{0.309633f,0.0477349f,0.0847568f},{0.137688f,-0.0994249f,-0.148277f},{0.154384f,-0.0850849f,-0.145943f}, -{0.160021f,-0.0802434f,-0.144688f},{0.165681f,-0.0753827f,-0.143185f},{0.171354f,-0.0705103f,-0.141429f}, -{0.177031f,-0.0656341f,-0.139417f},{0.182703f,-0.0607622f,-0.137145f},{0.188361f,-0.055903f,-0.134611f}, -{0.193994f,-0.0510652f,-0.131812f},{0.199591f,-0.0462575f,-0.128748f},{0.21064f,-0.0367683f,-0.121826f}, -{0.216069f,-0.032105f,-0.117971f},{0.221421f,-0.0275082f,-0.113856f},{0.226686f,-0.0229866f,-0.109486f}, -{0.231852f,-0.0185493f,-0.104866f},{0.23691f,-0.0142048f,-0.1f},{0.241851f,-0.00996175f,-0.0948962f}, -{0.246663f,-0.00582826f,-0.0895618f},{0.251339f,-0.00181224f,-0.0840052f},{0.25587f,0.00207883f,-0.0782359f}, -{0.260246f,0.00583789f,-0.072264f},{0.264462f,0.00945834f,-0.0661002f},{0.27238f,0.0162596f,-0.0532437f}, -{0.276071f,0.0194299f,-0.0465757f},{0.279577f,0.0224406f,-0.039765f},{0.282892f,0.025288f,-0.0328251f}, -{0.286013f,0.0279689f,-0.0257695f},{0.288938f,0.0304808f,-0.0186126f},{0.291664f,0.0328218f,-0.0113678f}, -{0.294189f,0.0349908f,-0.00404916f},{0.296513f,0.0369871f,0.00332952f},{0.298637f,0.0388106f,0.0107545f}, -{0.300559f,0.0404621f,0.0182123f},{0.302283f,0.0419425f,0.0256896f},{0.306281f,0.0453766f,0.0481121f}, -{0.305774f,0.0454417f,0.0481755f},{0.309248f,0.0479248f,0.0847617f},{0.309004f,0.047715f,0.0775525f}, -{0.309376f,0.0479772f,0.0918925f},{0.309694f,0.0478162f,0.0918925f},{0.137425f,-0.0991502f,-0.147929f}, -{0.159726f,-0.0799965f,-0.144345f},{0.165377f,-0.0751428f,-0.142845f},{0.171042f,-0.0702775f,-0.141092f}, -{0.176711f,-0.0654083f,-0.139082f},{0.182375f,-0.0605435f,-0.136814f},{0.188024f,-0.0556914f,-0.134283f}, -{0.193649f,-0.0508605f,-0.131488f},{0.215692f,-0.0319277f,-0.117667f},{0.210271f,-0.0365843f,-0.121517f}, -{0.209925f,-0.0365573f,-0.121044f},{0.221037f,-0.0273376f,-0.113559f},{0.226294f,-0.0228226f,-0.109195f}, -{0.231453f,-0.0183917f,-0.104581f},{0.236503f,-0.0140535f,-0.0997223f},{0.250911f,-0.00167885f,-0.0837506f}, -{0.255435f,0.00220659f,-0.0779897f},{0.259806f,0.00596021f,-0.0720263f},{0.275118f,0.0194353f,-0.046069f}, -{0.274737f,0.0191082f,-0.0457157f},{0.27861f,0.022435f,-0.0392833f},{0.271922f,0.0163668f,-0.0530336f}, -{0.275608f,0.0195325f,-0.0463752f},{0.279108f,0.0225389f,-0.0395744f},{0.282419f,0.0253822f,-0.0326445f}, -{0.285535f,0.0280592f,-0.0255992f},{0.288456f,0.0305674f,-0.0184526f},{0.29602f,0.0370643f,0.00345771f}, -{0.29814f,0.0388852f,0.0108719f},{0.30006f,0.0405343f,0.0183189f},{0.301781f,0.0420125f,0.0257854f}, -{0.303306f,0.0433217f,0.0332586f},{0.304636f,0.0444639f,0.0407259f},{0.308493f,0.0477767f,0.0775733f}, -{0.307518f,0.0472628f,0.0703525f},{0.309015f,0.0480539f,0.0918925f},{0.137241f,-0.0989846f,-0.147398f}, -{0.153876f,-0.0846971f,-0.145073f},{0.159492f,-0.0798733f,-0.143822f},{0.170669f,-0.0702734f,-0.13998f}, -{0.17644f,-0.0653174f,-0.138571f},{0.170783f,-0.0701758f,-0.140576f},{0.165131f,-0.0750303f,-0.142325f}, -{0.182091f,-0.0604634f,-0.136307f},{0.187728f,-0.055622f,-0.133782f},{0.19334f,-0.0508018f,-0.130993f}, -{0.198917f,-0.0460117f,-0.127941f},{0.204449f,-0.0412605f,-0.124624f},{0.220426f,-0.0275383f,-0.112579f}, -{0.225913f,-0.022826f,-0.10875f},{0.220668f,-0.027331f,-0.113104f},{0.215335f,-0.031911f,-0.117203f}, -{0.23106f,-0.0184049f,-0.104146f},{0.2361f,-0.0140763f,-0.0992979f},{0.250158f,-0.00200198f,-0.0829128f}, -{0.25499f,0.00214776f,-0.0776135f},{0.250476f,-0.00172908f,-0.0833616f},{0.245817f,-0.00573041f,-0.0888979f}, -{0.25935f,0.00589306f,-0.0716633f},{0.26355f,0.00950025f,-0.0655221f},{0.267582f,0.0129633f,-0.0592012f}, -{0.27144f,0.0162766f,-0.0527127f},{0.281913f,0.025272f,-0.0323688f},{0.285023f,0.0279431f,-0.025339f}, -{0.287937f,0.0304458f,-0.0182083f},{0.295052f,0.0365564f,0.00387953f},{0.2976f,0.0387452f,0.0110514f}, -{0.295485f,0.0369283f,0.00365355f},{0.293169f,0.0349393f,-0.00369814f},{0.299516f,0.0403906f,0.0184819f}, -{0.301233f,0.0418655f,0.0259318f},{0.302754f,0.0431718f,0.0333884f},{0.304081f,0.0443114f,0.0408392f}, -{0.306469f,0.0463621f,0.0631135f},{0.308656f,0.0480337f,0.0918925f},{0.142701f,-0.0942953f,-0.146243f}, -{0.137213f,-0.0990084f,-0.146785f},{0.148234f,-0.0895429f,-0.145472f},{0.153805f,-0.0847575f,-0.144466f}, -{0.159408f,-0.079946f,-0.143218f},{0.165032f,-0.0751155f,-0.141725f},{0.176312f,-0.0654275f,-0.137981f}, -{0.193169f,-0.0509491f,-0.130423f},{0.187571f,-0.0557569f,-0.133204f},{0.187595f,-0.05606f,-0.132703f}, -{0.181949f,-0.0605859f,-0.135723f},{0.198732f,-0.0461712f,-0.127378f},{0.204249f,-0.0414322f,-0.12407f}, -{0.209711f,-0.036741f,-0.120499f},{0.215107f,-0.0321066f,-0.116668f},{0.235824f,-0.0151381f,-0.0981062f}, -{0.235736f,-0.014713f,-0.098384f},{0.230815f,-0.0194397f,-0.102924f},{0.225658f,-0.0230449f,-0.108236f}, -{0.230792f,-0.0186351f,-0.103644f},{0.235819f,-0.0143176f,-0.0988083f},{0.240729f,-0.0101009f,-0.0937362f}, -{0.245511f,-0.00599306f,-0.0884349f},{0.263103f,0.00829154f,-0.0645409f},{0.263055f,0.00875088f,-0.0647696f}, -{0.258929f,0.00470683f,-0.0706439f},{0.25466f,0.00186493f,-0.0771794f},{0.25901f,0.00560064f,-0.0712445f}, -{0.263199f,0.00919859f,-0.065119f},{0.267221f,0.0126528f,-0.0588143f},{0.271069f,0.0159576f,-0.0523423f}, -{0.284617f,0.0275942f,-0.0250388f},{0.281515f,0.02493f,-0.0320505f},{0.28133f,0.0244472f,-0.0317747f}, -{0.278221f,0.0221003f,-0.0389474f},{0.287524f,0.0300905f,-0.0179263f},{0.290232f,0.032417f,-0.0107265f}, -{0.292742f,0.0345725f,-0.00345334f},{0.297162f,0.0383686f,0.0112584f},{0.302303f,0.0427839f,0.0335382f}, -{0.300786f,0.041481f,0.0261007f},{0.300558f,0.0409614f,0.0262471f},{0.299073f,0.0400098f,0.0186698f}, -{0.303626f,0.0439206f,0.04097f},{0.304759f,0.0448938f,0.048384f},{0.305705f,0.0457065f,0.0557688f}, -{0.307465f,0.0472177f,0.0776416f},{0.307708f,0.0474261f,0.084806f},{0.307998f,0.0477204f,0.0918925f}, -{0.308307f,0.0479214f,0.0918925f},{0.142824f,-0.0945127f,-0.145713f},{0.137349f,-0.0992153f,-0.146254f}, -{0.148345f,-0.0897709f,-0.144944f},{0.153904f,-0.0849962f,-0.14394f},{0.159494f,-0.0801954f,-0.142695f}, -{0.165106f,-0.0753756f,-0.141205f},{0.170731f,-0.0705443f,-0.139464f},{0.176361f,-0.0657091f,-0.137469f}, -{0.181985f,-0.0608783f,-0.135216f},{0.193331f,-0.0516347f,-0.129604f},{0.198873f,-0.0468744f,-0.126571f}, -{0.198731f,-0.0464957f,-0.12689f},{0.19318f,-0.0512629f,-0.129928f},{0.204236f,-0.0417672f,-0.123589f}, -{0.209686f,-0.0370865f,-0.120026f},{0.21507f,-0.0324624f,-0.116203f},{0.220377f,-0.0279043f,-0.112124f}, -{0.225597f,-0.0234208f,-0.10779f},{0.23072f,-0.0190209f,-0.103209f},{0.240634f,-0.0105057f,-0.0933231f}, -{0.245406f,-0.00640698f,-0.0880336f},{0.250043f,-0.00242477f,-0.0825239f},{0.254535f,0.00143353f,-0.0768032f}, -{0.258875f,0.00516092f,-0.0708815f},{0.267067f,0.0121974f,-0.0584789f},{0.270907f,0.0154949f,-0.0520214f}, -{0.274567f,0.0186385f,-0.0454095f},{0.278043f,0.0216238f,-0.0386562f},{0.284442f,0.0266194f,-0.0246083f}, -{0.287338f,0.0291065f,-0.017522f},{0.287325f,0.0295963f,-0.017682f},{0.284425f,0.0271056f,-0.0247786f}, -{0.290028f,0.0319176f,-0.0104982f},{0.292532f,0.0340683f,-0.00324118f},{0.294837f,0.0360478f,0.00407537f}, -{0.296942f,0.037856f,0.0114378f},{0.298849f,0.0394935f,0.0188328f},{0.302071f,0.0422615f,0.0336681f}, -{0.303381f,0.0428858f,0.0411575f},{0.30451f,0.0438554f,0.0485442f},{0.304522f,0.0443667f,0.0484808f}, -{0.303392f,0.0433957f,0.0410833f},{0.305467f,0.0451776f,0.0558492f},{0.307222f,0.0466854f,0.0776733f}, -{0.307591f,0.0471265f,0.0918925f},{0.307758f,0.047452f,0.0918925f},{0.137581f,-0.0995171f,-0.145907f}, -{0.148561f,-0.0900864f,-0.144598f},{0.154112f,-0.0853187f,-0.143596f},{0.148803f,-0.0903988f,-0.144431f}, -{0.159694f,-0.0805249f,-0.142353f},{0.165297f,-0.0757121f,-0.140865f},{0.170914f,-0.0708878f,-0.139127f}, -{0.176535f,-0.0660598f,-0.137134f},{0.182152f,-0.061236f,-0.134885f},{0.187753f,-0.0564248f,-0.132375f}, -{0.210011f,-0.0378285f,-0.119568f},{0.204573f,-0.0424991f,-0.123123f},{0.20437f,-0.0421528f,-0.123274f}, -{0.209812f,-0.0374789f,-0.119717f},{0.215188f,-0.0328616f,-0.1159f},{0.220487f,-0.0283101f,-0.111826f}, -{0.2257f,-0.0238332f,-0.107499f},{0.240892f,-0.0113052f,-0.0929223f},{0.240715f,-0.0109369f,-0.0930527f}, -{0.236004f,-0.0155034f,-0.0979722f},{0.24548f,-0.00684419f,-0.087771f},{0.25011f,-0.0028678f,-0.0822693f}, -{0.254596f,0.000984871f,-0.0765569f},{0.267268f,0.0113487f,-0.0581535f},{0.271099f,0.0146391f,-0.0517099f}, -{0.26711f,0.011733f,-0.0582594f},{0.270944f,0.0150257f,-0.0518113f},{0.274598f,0.0181647f,-0.0452091f}, -{0.278069f,0.0211457f,-0.0384656f},{0.281352f,0.023965f,-0.0315942f},{0.290179f,0.0310263f,-0.0102766f}, -{0.290037f,0.0314244f,-0.0103487f},{0.287482f,0.02871f,-0.0174448f},{0.292537f,0.033572f,-0.0031023f}, -{0.294839f,0.0355486f,0.00420356f},{0.296941f,0.0373542f,0.0115553f},{0.298845f,0.0389893f,0.0189394f}, -{0.300551f,0.0404551f,0.026343f},{0.302063f,0.0417532f,0.0337531f},{0.305453f,0.044665f,0.0559018f}, -{0.307336f,0.0457621f,0.0777041f},{0.306926f,0.0454104f,0.0705019f},{0.307206f,0.0461706f,0.077694f}, -{0.15435f,-0.0856345f,-0.143429f},{0.159927f,-0.0808441f,-0.142188f},{0.165527f,-0.0760347f,-0.140701f}, -{0.17114f,-0.0712139f,-0.138964f},{0.176757f,-0.0663892f,-0.136973f},{0.18237f,-0.0615688f,-0.134725f}, -{0.187968f,-0.056761f,-0.132217f},{0.193541f,-0.0519743f,-0.129448f},{0.199079f,-0.0472174f,-0.126416f}, -{0.215383f,-0.0332144f,-0.115753f},{0.220678f,-0.0286662f,-0.111682f},{0.225887f,-0.0241924f,-0.107358f}, -{0.230999f,-0.019802f,-0.102786f},{0.245654f,-0.00721537f,-0.0876442f},{0.25028f,-0.00324179f,-0.0821464f}, -{0.254763f,0.000608165f,-0.0764381f},{0.259093f,0.00432749f,-0.0705292f},{0.263264f,0.00790968f,-0.0644306f}, -{0.274751f,0.0177759f,-0.0451124f},{0.27822f,0.0207548f,-0.0383737f},{0.2815f,0.0235721f,-0.0315071f}, -{0.284588f,0.0262246f,-0.0245261f},{0.292677f,0.0331723f,-0.0030353f},{0.294977f,0.0351475f,0.00426541f}, -{0.297078f,0.0369518f,0.0116119f},{0.29898f,0.0385858f,0.0189909f},{0.300686f,0.0400505f,0.0263892f}, -{0.302196f,0.0413477f,0.0337941f},{0.303514f,0.0424795f,0.0411933f},{0.304642f,0.0434484f,0.0485748f}, -{0.305584f,0.0442575f,0.0559272f},{0.306344f,0.0449103f,0.0632397f},{-0.0768213f,-0.165362f,-0.141015f}, -{-0.0807759f,-0.161231f,-0.142188f},{-0.0760016f,-0.16686f,-0.140701f},{-0.0521167f,-0.195024f,-0.129448f}, -{-0.0506739f,-0.196193f,-0.12867f},{-0.0549268f,-0.191178f,-0.131224f},{-0.0952491f,-0.144775f,-0.145366f}, -{-0.0955186f,-0.145045f,-0.145713f},{-0.0908114f,-0.150595f,-0.144944f},{-0.0855313f,-0.155624f,-0.143429f}, -{-0.0812993f,-0.160082f,-0.142366f},{-0.0862068f,-0.156404f,-0.144466f},{-0.0909572f,-0.150803f,-0.145472f}, -{-0.094958f,-0.144508f,-0.145199f},{-0.0905487f,-0.150317f,-0.144598f},{-0.0902609f,-0.150047f,-0.144431f}, -{-0.104976f,-0.134273f,-0.147719f},{-0.104988f,-0.134259f,-0.147105f},{-0.109589f,-0.12887f,-0.147351f}, -{-0.095675f,-0.14524f,-0.146243f},{-0.109234f,-0.128569f,-0.148558f},{-0.104482f,-0.133888f,-0.148599f}, -{-0.104778f,-0.134126f,-0.148251f},{-0.109527f,-0.128818f,-0.148015f},{-0.0993034f,-0.138852f,-0.148493f}, -{-0.0995117f,-0.139139f,-0.148445f},{-0.104178f,-0.133637f,-0.148767f},{-0.103915f,-0.133415f,-0.14881f}, -{-0.108786f,-0.128189f,-0.148876f},{-0.10853f,-0.127972f,-0.148916f},{-0.0679527f,-0.175819f,-0.137702f}, -{-0.0712159f,-0.172503f,-0.138964f},{-0.0664265f,-0.178151f,-0.136973f},{-0.0723712f,-0.170609f,-0.13946f}, -{-0.0616412f,-0.183793f,-0.134725f},{-0.0635699f,-0.180987f,-0.135742f},{-0.0571328f,-0.189719f,-0.132375f}, -{-0.0568685f,-0.189421f,-0.132217f},{-0.0592267f,-0.186108f,-0.133582f},{-0.0473945f,-0.200592f,-0.126416f}, -{-0.0464718f,-0.201148f,-0.125923f},{-0.0380742f,-0.211582f,-0.119568f},{-0.0334938f,-0.216983f,-0.115753f}, -{-0.0342072f,-0.21561f,-0.116543f},{-0.0427107f,-0.206115f,-0.123123f},{-0.0225297f,-0.229379f,-0.105516f}, -{-0.0263511f,-0.224873f,-0.109369f},{-0.0245376f,-0.227544f,-0.107358f},{-0.0302448f,-0.220282f,-0.113046f}, -{-0.0151167f,-0.23812f,-0.0972923f},{-0.015912f,-0.237714f,-0.0979722f},{-0.0117444f,-0.242629f,-0.0929223f}, -{-0.0201792f,-0.232683f,-0.102786f},{-0.00462018f,-0.250497f,-0.0837205f},{-0.00373985f,-0.252067f,-0.0821464f}, -{-0.0012999f,-0.254412f,-0.0788827f},{-0.00768443f,-0.247416f,-0.0876442f},{0.00808472f,-0.265478f,-0.0634868f}, -{0.00505532f,-0.261906f,-0.0687614f},{0.00733025f,-0.26512f,-0.0644306f},{0.0019262f,-0.258216f,-0.0738949f}, -{0.0037742f,-0.260927f,-0.0705292f},{0.0165479f,-0.275457f,-0.0468636f},{0.0140105f,-0.272997f,-0.0517099f}, -{0.0171244f,-0.276669f,-0.0451124f},{0.0107442f,-0.269146f,-0.0581535f},{0.0228784f,-0.283454f,-0.0315071f}, -{0.0240231f,-0.284271f,-0.0291439f},{0.021645f,-0.281467f,-0.0351637f},{0.0191525f,-0.278528f,-0.041072f}, -{0.0304509f,-0.291851f,-0.010468f},{0.028428f,-0.289465f,-0.0167907f},{0.0302782f,-0.292179f,-0.0102766f}, -{0.0255116f,-0.286558f,-0.0245261f},{0.0324085f,-0.294691f,-0.0030353f},{0.034129f,-0.296187f,0.00244111f}, -{0.0323519f,-0.294092f,-0.00405553f},{0.0377825f,-0.301028f,0.0189909f},{0.0373059f,-0.299933f,0.0156645f}, -{0.0361604f,-0.299115f,0.0116119f},{0.0357808f,-0.298135f,0.00901635f},{0.0343693f,-0.297003f,0.00426541f}, -{0.0399706f,-0.303075f,0.0291557f},{0.0405243f,-0.304261f,0.0337941f},{0.0411078f,-0.304416f,0.0359868f}, -{0.0392366f,-0.302742f,0.0263892f},{0.0387029f,-0.301581f,0.0223796f},{0.0421137f,-0.305602f,0.0428671f}, -{0.0426097f,-0.306719f,0.0485748f},{0.0429872f,-0.306632f,0.0497904f},{0.0416478f,-0.305585f,0.0411933f}, -{0.0451124f,-0.309671f,0.0848371f},{0.0454147f,-0.309495f,0.0918925f},{0.0453472f,-0.309415f,0.0848393f}, -{0.0437276f,-0.307506f,0.0567509f},{0.0434129f,-0.307667f,0.0559272f},{0.0445573f,-0.309016f,0.0705019f}, -{0.0443647f,-0.309399f,0.0704868f},{0.044714f,-0.309811f,0.077694f},{0.0451444f,-0.309176f,0.0777923f}, -{0.0443343f,-0.308221f,0.0637421f},{0.0448067f,-0.308778f,0.0707579f},{0.0449064f,-0.309428f,0.0777041f}, -{0.0440608f,-0.308431f,0.0632397f},{0.0446491f,-0.310322f,0.0776733f},{0.0450123f,-0.31113f,0.084806f}, -{0.0448556f,-0.310565f,0.0848218f},{0.0424156f,-0.307101f,0.0485442f},{0.0414531f,-0.305966f,0.0411575f}, -{0.0442993f,-0.309909f,0.0704555f},{0.0438679f,-0.308813f,0.0632194f},{0.0438017f,-0.309322f,0.0631775f}, -{0.0423474f,-0.307608f,0.0484808f},{0.0448502f,-0.310938f,0.0703525f},{0.0443502f,-0.310349f,0.0630396f}, -{0.0453802f,-0.311184f,0.0703047f},{0.043956f,-0.309884f,0.0631135f},{0.0444547f,-0.310472f,0.0704077f}, -{0.0458943f,-0.311202f,0.0702734f},{0.0462471f,-0.311618f,0.0775525f},{0.0462046f,-0.311955f,0.0918925f}, -{0.0459404f,-0.311844f,0.0847721f},{0.0464553f,-0.311864f,0.0847617f},{0.0468649f,-0.311737f,0.0847568f}, -{0.0469128f,-0.311827f,0.0918925f},{0.046564f,-0.311937f,0.0918925f},{0.0472235f,-0.311628f,0.0918925f}, -{0.0390402f,-0.303121f,0.026343f},{0.0200816f,-0.280156f,-0.0383737f},{0.0262847f,-0.286938f,-0.0230178f}, -{0.0279788f,-0.289468f,-0.0174448f},{0.0226704f,-0.283818f,-0.0315942f},{0.0138335f,-0.272256f,-0.0525331f}, -{0.0110116f,-0.268929f,-0.0580758f},{8.20141e-005f,-0.256573f,-0.0764381f},{-0.00803171f,-0.246474f,-0.088404f}, -{0.00355277f,-0.261276f,-0.0706439f},{0.0034277f,-0.261716f,-0.0708815f},{0.00699146f,-0.265918f,-0.0647696f}, -{-0.0115316f,-0.242347f,-0.0929293f},{-0.0187838f,-0.233796f,-0.101489f},{-0.0382349f,-0.21086f,-0.119856f}, -{-0.0423242f,-0.206039f,-0.122984f},{-0.0289787f,-0.222307f,-0.111682f},{-0.0163012f,-0.238453f,-0.098384f}, -{-0.0204175f,-0.233012f,-0.102924f},{-0.0205776f,-0.23341f,-0.103209f},{-0.0858011f,-0.154773f,-0.14351f}, -{-0.0903231f,-0.149441f,-0.144448f},{-0.094861f,-0.14409f,-0.145179f},{-0.10481f,-0.134088f,-0.146574f}, -{-0.109528f,-0.128818f,-0.147023f},{-0.0996162f,-0.139016f,-0.145739f},{-0.0994109f,-0.138726f,-0.145701f}, -{-0.10423f,-0.133576f,-0.146057f},{-0.103969f,-0.133351f,-0.146014f},{-0.109589f,-0.12887f,-0.147687f}, -{-0.108787f,-0.12819f,-0.146158f},{-0.10853f,-0.127972f,-0.146119f},{-0.10902f,-0.128388f,-0.146297f}, -{-0.109238f,-0.128572f,-0.146474f},{-0.104527f,-0.133835f,-0.146225f},{-0.109409f,-0.128718f,-0.146724f}, -{-0.0999106f,-0.139278f,-0.145907f},{-0.0858158f,-0.155898f,-0.143596f},{-0.081057f,-0.161509f,-0.142353f}, -{-0.0762794f,-0.167143f,-0.140865f},{-0.0714903f,-0.17279f,-0.139127f},{-0.0666975f,-0.178441f,-0.137134f}, -{-0.0619089f,-0.184088f,-0.134885f},{-0.0525844f,-0.19567f,-0.129928f},{-0.047852f,-0.20125f,-0.12689f}, -{-0.0523776f,-0.195326f,-0.129604f},{-0.0476521f,-0.200898f,-0.126571f},{-0.042965f,-0.206425f,-0.123274f}, -{-0.0383251f,-0.211896f,-0.119717f},{-0.0337415f,-0.217301f,-0.1159f},{-0.0292233f,-0.222629f,-0.111826f}, -{-0.024779f,-0.227869f,-0.107499f},{-0.0161473f,-0.238047f,-0.0981062f},{-0.0119768f,-0.242965f,-0.0930527f}, -{-0.00791396f,-0.247755f,-0.087771f},{-0.00396659f,-0.25241f,-0.0822693f},{-0.000142029f,-0.256919f,-0.0765569f}, -{0.00711132f,-0.265472f,-0.0645409f},{0.0105277f,-0.2695f,-0.0582594f},{0.0137963f,-0.273355f,-0.0518113f}, -{0.0169124f,-0.277029f,-0.0452091f},{0.0198717f,-0.280518f,-0.0384656f},{0.0301127f,-0.293561f,-0.0107265f}, -{0.0276847f,-0.290318f,-0.017682f},{0.0278031f,-0.290838f,-0.0179263f},{0.0253055f,-0.286925f,-0.0246083f}, -{0.0277744f,-0.289837f,-0.017522f},{0.0300754f,-0.29255f,-0.0103487f},{0.0322073f,-0.295064f,-0.0031023f}, -{0.0341695f,-0.297377f,0.00420356f},{0.0359619f,-0.299491f,0.0115553f},{0.0375851f,-0.301405f,0.0189394f}, -{0.0403288f,-0.30464f,0.0337531f},{0.0413834f,-0.306471f,0.0410833f},{0.0432194f,-0.308048f,0.0559018f}, -{0.0449202f,-0.310054f,0.0848321f},{0.0450044f,-0.310086f,0.0918925f},{0.0451675f,-0.309769f,0.0918925f}, -{-0.109406f,-0.128715f,-0.14831f},{-0.100187f,-0.13954f,-0.146254f},{-0.0860715f,-0.156184f,-0.14394f}, -{-0.0813058f,-0.161803f,-0.142695f},{-0.0765212f,-0.167445f,-0.141205f},{-0.0717251f,-0.1731f,-0.139464f}, -{-0.0669252f,-0.17876f,-0.137469f},{-0.0621296f,-0.184415f,-0.135216f},{-0.0573465f,-0.190055f,-0.132703f}, -{-0.043158f,-0.206785f,-0.123589f},{-0.0431976f,-0.207118f,-0.12407f},{-0.0385406f,-0.212609f,-0.120499f}, -{-0.0385114f,-0.212264f,-0.120026f},{-0.0339211f,-0.217677f,-0.116203f},{-0.0293962f,-0.223012f,-0.112124f}, -{-0.0249455f,-0.22826f,-0.10779f},{-0.0080171f,-0.248601f,-0.0884349f},{-0.00775636f,-0.248908f,-0.0888979f}, -{-0.00378422f,-0.253592f,-0.0833616f},{-0.0121246f,-0.243378f,-0.0933231f},{-0.0080558f,-0.248175f,-0.0880336f}, -{-0.00410265f,-0.252837f,-0.0825239f},{-0.000272494f,-0.257353f,-0.0768032f},{0.0137734f,-0.274295f,-0.0523423f}, -{0.0140901f,-0.274668f,-0.0527127f},{0.0172258f,-0.278365f,-0.046069f},{0.0104128f,-0.269952f,-0.0584789f}, -{0.0136862f,-0.273812f,-0.0520214f},{0.0168069f,-0.277492f,-0.0454095f},{0.0197705f,-0.280986f,-0.0386562f}, -{0.0225733f,-0.284291f,-0.0317747f},{0.0252122f,-0.287403f,-0.0247786f},{0.0299891f,-0.293035f,-0.0104982f}, -{0.0321241f,-0.295553f,-0.00324118f},{0.0340892f,-0.29787f,0.00407537f},{0.0358842f,-0.299987f,0.0114378f}, -{0.0375098f,-0.301903f,0.0188328f},{0.038967f,-0.303622f,0.0262471f},{0.0402575f,-0.305143f,0.0336681f}, -{0.0431523f,-0.308557f,0.0558492f},{0.0452017f,-0.311353f,0.077605f},{0.0449255f,-0.310447f,0.0918925f}, -{-0.0998191f,-0.139386f,-0.148277f},{-0.100354f,-0.139723f,-0.146785f},{-0.0814304f,-0.162036f,-0.143218f}, -{-0.0813582f,-0.162121f,-0.143822f},{-0.0765506f,-0.16779f,-0.142325f},{-0.0766352f,-0.16769f,-0.141725f}, -{-0.0718284f,-0.173358f,-0.13998f},{-0.0670178f,-0.179031f,-0.137981f},{-0.0622115f,-0.184698f,-0.135723f}, -{-0.0574178f,-0.19035f,-0.133204f},{-0.0526451f,-0.195978f,-0.130423f},{-0.0479021f,-0.201571f,-0.127378f}, -{-0.0339401f,-0.218034f,-0.116668f},{-0.0337459f,-0.218263f,-0.117203f},{-0.0291993f,-0.223624f,-0.113104f}, -{-0.0294051f,-0.223381f,-0.112579f},{-0.0249445f,-0.228641f,-0.108236f},{-0.0205669f,-0.233803f,-0.103644f}, -{-0.0162809f,-0.238856f,-0.0988083f},{-0.0120949f,-0.243792f,-0.0937362f},{-0.00405513f,-0.253272f,-0.0829128f}, -{-0.000216443f,-0.257799f,-0.0771794f},{0.00349201f,-0.262171f,-0.0712445f},{0.00706371f,-0.266383f,-0.065119f}, -{0.0104927f,-0.270426f,-0.0588143f},{0.016901f,-0.277982f,-0.0457157f},{0.0198712f,-0.281485f,-0.0389474f}, -{0.0226803f,-0.284797f,-0.0320505f},{0.0253251f,-0.287916f,-0.0250388f},{0.0322524f,-0.296084f,-0.00345334f}, -{0.0326166f,-0.296513f,-0.00369814f},{0.034591f,-0.298841f,0.00365355f},{0.0342218f,-0.298406f,0.00387953f}, -{0.0360209f,-0.300527f,0.0112584f},{0.0376501f,-0.302448f,0.0186698f},{0.0391106f,-0.304171f,0.0261007f}, -{0.0404039f,-0.305696f,0.0335382f},{0.0415324f,-0.307026f,0.04097f},{0.0424985f,-0.308165f,0.048384f}, -{0.0433052f,-0.309117f,0.0557688f},{0.0448054f,-0.310885f,0.0776416f},{0.0449434f,-0.310806f,0.0918925f}, -{-0.0956393f,-0.145282f,-0.146855f},{-0.0909094f,-0.150859f,-0.146081f},{-0.10033f,-0.139751f,-0.147398f}, -{-0.0861468f,-0.156475f,-0.145073f},{-0.0717315f,-0.173473f,-0.140576f},{-0.0669086f,-0.179159f,-0.138571f}, -{-0.0620899f,-0.184841f,-0.136307f},{-0.0617973f,-0.184807f,-0.136814f},{-0.0569805f,-0.190486f,-0.134283f}, -{-0.0572839f,-0.190508f,-0.133782f},{-0.0524989f,-0.19615f,-0.130993f},{-0.0477437f,-0.201757f,-0.127941f}, -{-0.0430272f,-0.207319f,-0.124624f},{-0.0383583f,-0.212824f,-0.121044f},{-0.0247272f,-0.228897f,-0.10875f}, -{-0.0243516f,-0.22896f,-0.109195f},{-0.019953f,-0.234147f,-0.104581f},{-0.0203383f,-0.234072f,-0.104146f}, -{-0.0160414f,-0.239139f,-0.0992979f},{-0.0118447f,-0.244087f,-0.0942128f},{6.43211e-005f,-0.25813f,-0.0776135f}, -{0.000494926f,-0.258258f,-0.0779897f},{0.00422115f,-0.262651f,-0.0720263f},{0.0037823f,-0.262514f,-0.0716633f}, -{0.00736317f,-0.266736f,-0.0655221f},{0.0108009f,-0.27079f,-0.0592012f},{0.0202036f,-0.281877f,-0.0392833f}, -{0.0206789f,-0.282057f,-0.0395744f},{0.0235014f,-0.285386f,-0.0326445f},{0.0230198f,-0.285197f,-0.0323688f}, -{0.0256714f,-0.288324f,-0.025339f},{0.0281559f,-0.291253f,-0.0182083f},{0.0304713f,-0.293984f,-0.01099f}, -{0.0363947f,-0.300968f,0.0110514f},{0.0380281f,-0.302894f,0.0184819f},{0.0385429f,-0.303122f,0.0183189f}, -{0.0400104f,-0.304852f,0.0257854f},{0.0394923f,-0.304621f,0.0259318f},{0.040789f,-0.30615f,0.0333884f}, -{0.0419203f,-0.307484f,0.0408392f},{0.0428889f,-0.308626f,0.0482723f},{0.0436977f,-0.309579f,0.0556761f}, -{0.0454092f,-0.311597f,0.0847878f},{0.0452527f,-0.311466f,0.0918925f},{0.0450535f,-0.311155f,0.0918925f}, -{-0.0954211f,-0.14516f,-0.147384f},{-0.0906807f,-0.150749f,-0.14661f},{-0.100122f,-0.139616f,-0.147929f}, -{-0.0859076f,-0.156377f,-0.145599f},{-0.0811083f,-0.162036f,-0.144345f},{-0.07629f,-0.167718f,-0.142845f}, -{-0.0714602f,-0.173413f,-0.141092f},{-0.0666266f,-0.179112f,-0.139082f},{-0.052185f,-0.196141f,-0.131488f}, -{-0.0470397f,-0.201621f,-0.128748f},{-0.0474192f,-0.20176f,-0.128429f},{-0.0426922f,-0.207334f,-0.125105f}, -{-0.0380129f,-0.212852f,-0.121517f},{-0.0333903f,-0.218302f,-0.117667f},{-0.0288337f,-0.223675f,-0.113559f}, -{-0.0152209f,-0.239139f,-0.1f},{-0.0156465f,-0.239225f,-0.0997223f},{-0.0114405f,-0.244184f,-0.0946258f}, -{-0.00734311f,-0.249016f,-0.0892991f},{-0.00336217f,-0.25371f,-0.0837506f},{0.0082696f,-0.266838f,-0.0661002f}, -{0.00780997f,-0.266883f,-0.0658715f},{0.0112554f,-0.270946f,-0.0595366f},{0.0145518f,-0.274833f,-0.0530336f}, -{0.0176944f,-0.278538f,-0.0463752f},{0.0266451f,-0.288505f,-0.0257695f},{0.0261589f,-0.288519f,-0.0255992f}, -{0.0286488f,-0.291455f,-0.0184526f},{0.0309694f,-0.294191f,-0.0112184f},{0.0331194f,-0.296727f,-0.00391029f}, -{0.0350983f,-0.29906f,0.00345771f},{0.0369059f,-0.301191f,0.0108719f},{0.04131f,-0.306384f,0.0332586f}, -{0.0429537f,-0.307735f,0.0406518f},{0.0424438f,-0.307721f,0.0407259f},{0.0434146f,-0.308866f,0.0481755f}, -{0.0442252f,-0.309822f,0.0555957f},{0.0448791f,-0.310593f,0.0629755f},{0.0457325f,-0.311599f,0.0775733f}, -{0.045844f,-0.311876f,0.0918925f},{0.0455195f,-0.311707f,0.0918925f},{-0.109024f,-0.128391f,-0.148751f}, -{-0.0951111f,-0.144938f,-0.147731f},{-0.0903639f,-0.150535f,-0.146955f},{-0.0855838f,-0.156172f,-0.145943f}, -{-0.0807776f,-0.161839f,-0.144688f},{-0.0759523f,-0.167529f,-0.143185f},{-0.0711155f,-0.173232f,-0.141429f}, -{-0.0662749f,-0.17894f,-0.139417f},{-0.0614385f,-0.184642f,-0.137145f},{-0.0566148f,-0.19033f,-0.134611f}, -{-0.0518123f,-0.195993f,-0.131812f},{-0.0419583f,-0.207002f,-0.125571f},{-0.0374085f,-0.211835f,-0.122344f}, -{-0.0372689f,-0.212532f,-0.121975f},{-0.0423058f,-0.207202f,-0.125419f},{-0.0376197f,-0.212728f,-0.121826f}, -{-0.0329904f,-0.218187f,-0.117971f},{-0.0284272f,-0.223567f,-0.113856f},{-0.0239386f,-0.22886f,-0.109486f}, -{-0.0195336f,-0.234054f,-0.104866f},{-0.0110088f,-0.244106f,-0.0948962f},{-0.0106394f,-0.243932f,-0.0950266f}, -{-0.00690545f,-0.248944f,-0.0895618f},{-0.00291873f,-0.253645f,-0.0840052f},{0.000943949f,-0.2582f,-0.0782359f}, -{0.00467558f,-0.2626f,-0.072264f},{0.0121053f,-0.270751f,-0.059862f},{0.0152714f,-0.273952f,-0.0542297f}, -{0.0154088f,-0.274646f,-0.053345f},{0.01172f,-0.270906f,-0.059756f},{0.0150212f,-0.274799f,-0.0532437f}, -{0.0181684f,-0.27851f,-0.0465757f},{0.0211572f,-0.282034f,-0.039765f},{0.0239838f,-0.285367f,-0.0328251f}, -{0.0291386f,-0.291445f,-0.0186126f},{0.0318617f,-0.294046f,-0.0114399f},{0.0314626f,-0.294185f,-0.0113678f}, -{0.0336157f,-0.296724f,-0.00404916f},{0.0355975f,-0.299061f,0.00332952f},{0.0374077f,-0.301196f,0.0107545f}, -{0.0390471f,-0.303129f,0.0182123f},{0.0405167f,-0.304862f,0.0256896f},{0.0418182f,-0.306396f,0.0331736f}, -{0.0439258f,-0.308881f,0.0481121f},{0.0447376f,-0.309839f,0.0555431f},{0.0453925f,-0.310611f,0.0629336f}, -{-0.0948004f,-0.144694f,-0.147899f},{-0.0900499f,-0.150296f,-0.147122f},{-0.0852665f,-0.155936f,-0.146109f}, -{-0.0804569f,-0.161607f,-0.144853f},{-0.0756283f,-0.167301f,-0.143349f},{-0.0707881f,-0.173008f,-0.141592f}, -{-0.0659441f,-0.17872f,-0.139579f},{-0.0611044f,-0.184426f,-0.137305f},{-0.0562773f,-0.190118f,-0.134769f}, -{-0.0514714f,-0.195785f,-0.131968f},{-0.0466954f,-0.201416f,-0.128902f},{-0.0326364f,-0.217994f,-0.118117f}, -{-0.0280699f,-0.223379f,-0.114f},{-0.0235782f,-0.228675f,-0.109627f},{-0.0191702f,-0.233873f,-0.105003f}, -{-0.0148544f,-0.238961f,-0.100134f},{-0.0140188f,-0.239415f,-0.0995149f},{-0.00653318f,-0.248773f,-0.0896885f}, -{-0.00254368f,-0.253477f,-0.0841281f},{0.0013217f,-0.258035f,-0.0783547f},{0.00505593f,-0.262438f,-0.0723786f}, -{0.00865246f,-0.266679f,-0.0662105f},{0.0185582f,-0.278359f,-0.0466724f},{0.021549f,-0.281886f,-0.039857f}, -{0.0243776f,-0.285221f,-0.0329122f},{0.0270408f,-0.288362f,-0.0258517f},{0.0295361f,-0.291304f,-0.0186898f}, -{0.0300372f,-0.291363f,-0.0180672f},{0.0340163f,-0.296587f,-0.00411618f},{0.0359994f,-0.298925f,0.00326766f}, -{0.0378109f,-0.301061f,0.0106978f},{0.0394515f,-0.302996f,0.0181608f},{0.0409221f,-0.30473f,0.0256434f}, -{0.0422245f,-0.306265f,0.0331326f},{0.0433608f,-0.307605f,0.040616f},{0.0443336f,-0.308752f,0.0480815f}, -{0.0451459f,-0.30971f,0.0555177f},{0.0458013f,-0.310483f,0.0629134f},{0.0463034f,-0.311075f,0.0702583f}, -{0.0466565f,-0.311491f,0.0775425f},{-0.0947f,-0.14428f,-0.147965f},{-0.0901089f,-0.149694f,-0.147226f}, -{-0.0855339f,-0.155088f,-0.146277f},{-0.080979f,-0.160459f,-0.145118f},{-0.0764484f,-0.165802f,-0.143752f}, -{-0.071946f,-0.17111f,-0.142179f},{-0.0674757f,-0.176382f,-0.1404f},{-0.0630415f,-0.18161f,-0.138417f}, -{-0.0586471f,-0.186792f,-0.136232f},{-0.0542966f,-0.191922f,-0.133846f},{-0.0499938f,-0.196995f,-0.131262f}, -{-0.0457424f,-0.202008f,-0.128482f},{-0.0415461f,-0.206956f,-0.125509f},{-0.0333335f,-0.21664f,-0.118992f}, -{-0.0293246f,-0.221367f,-0.115454f},{-0.0253853f,-0.226012f,-0.111734f},{-0.0215189f,-0.230571f,-0.107835f}, -{-0.017729f,-0.23504f,-0.103761f},{-0.0103917f,-0.243691f,-0.0951008f},{-0.0068508f,-0.247867f,-0.0905224f}, -{-0.00339908f,-0.251937f,-0.0857837f},{-3.97542e-005f,-0.255898f,-0.080889f},{0.00322425f,-0.259746f,-0.0758426f}, -{0.00639008f,-0.263479f,-0.0706488f},{0.00945498f,-0.267093f,-0.0653124f},{0.0124163f,-0.270585f,-0.0598376f}, -{0.0180177f,-0.27719f,-0.0484934f},{0.0206528f,-0.280297f,-0.042634f},{0.0231745f,-0.283271f,-0.0366563f}, -{0.0255806f,-0.286108f,-0.0305656f},{0.0278688f,-0.288806f,-0.0243674f},{0.0320839f,-0.293776f,-0.0116704f}, -{0.0340071f,-0.296044f,-0.00518257f},{0.0358052f,-0.298164f,0.00139061f},{0.0374764f,-0.300134f,0.00804317f}, -{0.0390194f,-0.301954f,0.0147693f},{0.0404328f,-0.30362f,0.0215631f},{0.0417153f,-0.305133f,0.0284189f}, -{0.0428659f,-0.306489f,0.0353305f},{0.0438836f,-0.307689f,0.0422916f},{0.0447673f,-0.308731f,0.0492962f}, -{0.0455164f,-0.309615f,0.0563382f},{0.0461302f,-0.310339f,0.0634117f},{0.0466082f,-0.310902f,0.0705101f}, -{0.0469499f,-0.311305f,0.0776272f},{0.0471551f,-0.311547f,0.0847567f},{-0.259174f,0.0496576f,0.0428677f}, -{-0.260195f,0.0503292f,0.0485758f},{-0.259233f,0.0491951f,0.0411945f},{-0.251955f,0.040613f,0.00426646f}, -{-0.25119f,0.0402427f,0.00244165f},{-0.252842f,0.0421904f,0.00901696f},{-0.261646f,0.0520403f,0.0632405f}, -{-0.262143f,0.0526258f,0.0705025f},{-0.262055f,0.0519124f,0.0632202f},{-0.260788f,0.0515606f,0.0567511f}, -{-0.261395f,0.052276f,0.0637424f},{-0.263623f,0.0531732f,0.084822f},{-0.263855f,0.0533019f,0.0918925f}, -{-0.264154f,0.05342f,0.0848062f},{-0.263066f,0.0525171f,0.0704561f},{-0.262569f,0.0519303f,0.0631783f}, -{-0.262552f,0.0524983f,0.0704874f},{-0.264551f,0.053888f,0.084788f},{-0.264756f,0.0543717f,0.0918925f}, -{-0.264708f,0.0544524f,0.0847723f},{-0.263596f,0.0527624f,0.0704083f},{-0.263098f,0.0521743f,0.0631143f}, -{-0.264451f,0.0553469f,0.084757f},{-0.264242f,0.0551011f,0.0775429f},{-0.264643f,0.0549636f,0.084762f}, -{-0.264774f,0.0547312f,0.0918925f},{-0.264284f,0.055683f,0.0918925f},{-0.264532f,0.055409f,0.0918925f}, -{-0.264011f,0.0553606f,0.0776267f},{-0.260998f,0.0512763f,0.0559281f},{-0.260048f,0.0506876f,0.0497909f}, -{-0.264216f,0.0556025f,0.0847564f},{-0.257031f,0.0471307f,0.0291561f},{-0.25811f,0.0478703f,0.0337954f}, -{-0.256822f,0.046352f,0.0263905f},{-0.258169f,0.0484716f,0.0359874f},{-0.255368f,0.0446375f,0.0189921f}, -{-0.255764f,0.0456359f,0.0223799f},{-0.253746f,0.0427249f,0.0116131f},{-0.254367f,0.0439887f,0.015665f}, -{-0.249995f,0.038301f,-0.00303443f},{-0.249413f,0.0381472f,-0.0040552f},{-0.245565f,0.0330777f,-0.0174445f}, -{-0.243098f,0.0301686f,-0.0245261f},{-0.243346f,0.0309933f,-0.0230172f},{-0.247864f,0.035789f,-0.010276f}, -{-0.236214f,0.0225835f,-0.0410717f},{-0.238706f,0.0255224f,-0.0351634f},{-0.237668f,0.0237661f,-0.0383731f}, -{-0.241084f,0.0283265f,-0.0291434f},{-0.230895f,0.0163118f,-0.0525327f},{-0.231597f,0.0166077f,-0.051709f}, -{-0.228331f,0.0127563f,-0.0581524f},{-0.234711f,0.0202793f,-0.0451116f},{-0.222116f,0.00596108f,-0.0687612f}, -{-0.221361f,0.00453797f,-0.0705281f},{-0.218987f,0.00227149f,-0.0738946f},{-0.224917f,0.00873094f,-0.0644294f}, -{-0.209029f,-0.00947042f,-0.088404f},{-0.212441f,-0.00544764f,-0.0837203f},{-0.209902f,-0.00897324f,-0.0876434f}, -{-0.215761f,-0.00153252f,-0.0788824f},{-0.213847f,-0.00432202f,-0.0821454f},{-0.198277f,-0.0221483f,-0.101489f}, -{-0.201675f,-0.0186748f,-0.0979716f},{-0.197407f,-0.0237065f,-0.102786f},{-0.205842f,-0.0137605f,-0.0929216f}, -{-0.188607f,-0.0340827f,-0.111682f},{-0.186816f,-0.0356624f,-0.113046f},{-0.19071f,-0.0310714f,-0.109369f}, -{-0.194531f,-0.0265653f,-0.105516f},{-0.174737f,-0.0499058f,-0.122984f},{-0.178826f,-0.0450837f,-0.119856f}, -{-0.174876f,-0.0502744f,-0.123123f},{-0.184092f,-0.0394068f,-0.115753f},{-0.170192f,-0.0557971f,-0.126416f}, -{-0.166387f,-0.0597511f,-0.12867f},{-0.170589f,-0.0547964f,-0.125923f},{-0.155946f,-0.0725956f,-0.134725f}, -{-0.157835f,-0.0698361f,-0.133582f},{-0.160718f,-0.066968f,-0.132217f},{-0.162134f,-0.0647658f,-0.131224f}, -{-0.16547f,-0.0613651f,-0.129448f},{-0.149108f,-0.0801253f,-0.137702f},{-0.15116f,-0.078238f,-0.136973f}, -{-0.146371f,-0.0838855f,-0.138964f},{-0.153491f,-0.0749575f,-0.135742f},{-0.14024f,-0.0905825f,-0.141015f}, -{-0.141585f,-0.0895285f,-0.140701f},{-0.136811f,-0.0951581f,-0.142188f},{-0.14469f,-0.0853352f,-0.13946f}, -{-0.13126f,-0.101171f,-0.143511f},{-0.135762f,-0.0958627f,-0.142366f},{-0.132055f,-0.100766f,-0.14343f}, -{-0.123467f,-0.112469f,-0.146244f},{-0.123249f,-0.112347f,-0.145714f},{-0.127956f,-0.106796f,-0.144944f}, -{-0.113356f,-0.122814f,-0.146058f},{-0.11765f,-0.117219f,-0.145701f},{-0.11797f,-0.117374f,-0.145739f}, -{-0.113092f,-0.122593f,-0.146015f},{-0.122628f,-0.111881f,-0.145199f},{-0.127326f,-0.106343f,-0.144432f}, -{-0.122939f,-0.112125f,-0.145367f},{-0.1222f,-0.111854f,-0.145179f},{-0.126738f,-0.106503f,-0.144449f}, -{-0.141909f,-0.0897564f,-0.140865f},{-0.137462f,-0.0955874f,-0.142696f},{-0.137131f,-0.09539f,-0.142353f}, -{-0.128185f,-0.106906f,-0.145472f},{-0.12764f,-0.106582f,-0.144599f},{-0.123503f,-0.112427f,-0.146855f}, -{-0.118812f,-0.117958f,-0.147398f},{-0.118788f,-0.117986f,-0.146786f},{-0.123077f,-0.111962f,-0.147732f}, -{-0.118369f,-0.117514f,-0.148277f},{-0.123347f,-0.112232f,-0.147385f},{-0.113989f,-0.123265f,-0.148251f}, -{-0.113706f,-0.123012f,-0.148599f},{-0.113408f,-0.122753f,-0.148767f},{-0.113146f,-0.12253f,-0.14881f}, -{-0.151491f,-0.078458f,-0.137135f},{-0.193049f,-0.0288458f,-0.107358f},{-0.182854f,-0.0403346f,-0.116543f}, -{-0.179512f,-0.0448075f,-0.119568f},{-0.188965f,-0.0342715f,-0.111826f},{-0.201945f,-0.0178243f,-0.097292f}, -{-0.205529f,-0.0135971f,-0.0929291f},{-0.217669f,0.000184436f,-0.076437f},{-0.225146f,0.00953304f,-0.0634867f}, -{-0.214222f,-0.00448977f,-0.0822683f},{-0.214665f,-0.00455427f,-0.0825229f},{-0.210712f,-0.00921558f,-0.0880327f}, -{-0.228073f,0.0129843f,-0.0580755f},{-0.233609f,0.0195124f,-0.0468631f},{-0.245489f,0.0335205f,-0.0167902f}, -{-0.247512f,0.0359058f,-0.0104677f},{-0.240464f,0.0270637f,-0.0315068f},{-0.232454f,0.0164208f,-0.0520204f}, -{-0.2351f,0.0201289f,-0.0452083f},{-0.235574f,0.0201004f,-0.0454087f},{-0.25415f,0.0425904f,0.0115564f}, -{-0.261867f,0.052833f,0.0707584f},{-0.264446f,0.0537122f,0.0918925f},{-0.262205f,0.0532313f,0.0777929f}, -{-0.262492f,0.0530375f,0.0777045f},{-0.263108f,0.0531535f,0.0848323f},{-0.263495f,0.053223f,0.0918925f}, -{-0.262408f,0.0534704f,0.0848396f},{-0.262698f,0.0532806f,0.0848373f},{-0.262786f,0.053351f,0.0918925f}, -{-0.263135f,0.0532409f,0.0918925f},{-0.262476f,0.0535502f,0.0918925f},{-0.26418f,0.0534707f,0.0918925f}, -{-0.264646f,0.0540229f,0.0918925f},{-0.262902f,0.0529103f,0.0776945f},{-0.261407f,0.0511478f,0.0559028f}, -{-0.260603f,0.0502f,0.0485453f},{-0.259641f,0.0490651f,0.0411587f},{-0.258516f,0.0477394f,0.0337544f}, -{-0.257228f,0.04622f,0.0263442f},{-0.255773f,0.0445043f,0.0189407f},{-0.252856f,0.0404782f,0.00407642f}, -{-0.250891f,0.0381612f,-0.00324031f},{-0.252357f,0.040477f,0.00420461f},{-0.250395f,0.0381634f,-0.00310144f}, -{-0.248263f,0.0356496f,-0.0103481f},{-0.245962f,0.0329364f,-0.0175217f},{-0.243493f,0.0300252f,-0.0246083f}, -{-0.240858f,0.0269181f,-0.0315939f},{-0.23806f,0.0236182f,-0.038465f},{-0.231984f,0.0164547f,-0.0518103f}, -{-0.228716f,0.0126006f,-0.0582583f},{-0.2253f,0.00857242f,-0.0645398f},{-0.221741f,0.00437648f,-0.0706427f}, -{-0.218046f,1.98718e-005f,-0.0765558f},{-0.210275f,-0.00914426f,-0.0877701f},{-0.206212f,-0.0139349f,-0.093052f}, -{-0.202041f,-0.0188527f,-0.0981056f},{-0.197771f,-0.0238879f,-0.102923f},{-0.193409f,-0.0290309f,-0.107499f}, -{-0.175945f,-0.050591f,-0.12407f},{-0.180256f,-0.0451276f,-0.120026f},{-0.180601f,-0.0451f,-0.120499f}, -{-0.184446f,-0.0395993f,-0.1159f},{-0.179863f,-0.0450038f,-0.119717f},{-0.175223f,-0.0504746f,-0.123274f}, -{-0.170536f,-0.0560012f,-0.126571f},{-0.165811f,-0.0615731f,-0.129604f},{-0.161056f,-0.0671799f,-0.132375f}, -{-0.15628f,-0.0728116f,-0.134885f},{-0.146698f,-0.0841094f,-0.139127f},{-0.142247f,-0.0899456f,-0.141206f}, -{-0.132373f,-0.101001f,-0.143596f},{-0.118277f,-0.117621f,-0.145907f},{-0.11366f,-0.123065f,-0.146226f}, -{-0.264435f,0.054718f,0.0775529f},{-0.263416f,0.0529297f,0.0776737f},{-0.261919f,0.0511646f,0.0558501f}, -{-0.261114f,0.0502154f,0.0484819f},{-0.26015f,0.0490789f,0.0410845f},{-0.259025f,0.0477513f,0.0336694f}, -{-0.257734f,0.0462296f,0.0262484f},{-0.256277f,0.0445114f,0.018834f},{-0.254651f,0.0425947f,0.011439f}, -{-0.248756f,0.0356438f,-0.0104976f},{-0.249254f,0.0358515f,-0.0107259f},{-0.246945f,0.0331282f,-0.017926f}, -{-0.246452f,0.0329266f,-0.0176816f},{-0.243979f,0.0300111f,-0.0247786f},{-0.241341f,0.0268995f,-0.0317744f}, -{-0.238538f,0.0235948f,-0.0386556f},{-0.226206f,0.0086742f,-0.0651178f},{-0.226506f,0.0090273f,-0.065521f}, -{-0.222925f,0.00480505f,-0.0716622f},{-0.22918f,0.0125611f,-0.0584778f},{-0.225759f,0.008527f,-0.0647685f}, -{-0.222196f,0.00432493f,-0.0708804f},{-0.218495f,-3.80402e-005f,-0.0768021f},{-0.202862f,-0.0188522f,-0.0988077f}, -{-0.203101f,-0.0185698f,-0.0992973f},{-0.198804f,-0.0236366f,-0.104145f},{-0.206643f,-0.0140133f,-0.0933224f}, -{-0.202467f,-0.0189382f,-0.0983834f},{-0.19819f,-0.0239808f,-0.103208f},{-0.193822f,-0.0291313f,-0.10779f}, -{-0.189371f,-0.0343795f,-0.112123f},{-0.184846f,-0.0397152f,-0.116203f},{-0.17561f,-0.0506063f,-0.123589f}, -{-0.170916f,-0.056141f,-0.12689f},{-0.166183f,-0.061721f,-0.129928f},{-0.161421f,-0.0673361f,-0.132703f}, -{-0.156638f,-0.072976f,-0.135216f},{-0.151843f,-0.0786306f,-0.137469f},{-0.147043f,-0.0842903f,-0.139465f}, -{-0.132696f,-0.101207f,-0.14394f},{-0.114166f,-0.123436f,-0.147719f},{-0.118581f,-0.117851f,-0.146255f}, -{-0.113957f,-0.123303f,-0.146574f},{-0.262447f,0.0514069f,0.0557698f},{-0.263947f,0.0531759f,0.077642f}, -{-0.26164f,0.0504556f,0.0483851f},{-0.26203f,0.050916f,0.0482734f},{-0.261062f,0.0497739f,0.0408405f}, -{-0.260674f,0.0493165f,0.0409712f},{-0.259545f,0.047986f,0.0335395f},{-0.258252f,0.0464609f,0.026102f}, -{-0.256792f,0.0447389f,0.0186711f},{-0.255163f,0.0428179f,0.0112596f},{-0.253364f,0.0406967f,0.00388058f}, -{-0.251394f,0.0383745f,-0.00345247f},{-0.244467f,0.0302062f,-0.0250388f},{-0.244813f,0.0306146f,-0.025339f}, -{-0.242162f,0.0274881f,-0.0323684f},{-0.241822f,0.0270877f,-0.0320502f},{-0.239013f,0.0237756f,-0.0389468f}, -{-0.236043f,0.0202734f,-0.0457149f},{-0.232916f,0.0165856f,-0.0523413f},{-0.229635f,0.0127173f,-0.0588132f}, -{-0.222634f,0.00446276f,-0.0712434f},{-0.218926f,9.00519e-005f,-0.0771783f},{-0.215087f,-0.00443625f,-0.0829118f}, -{-0.211125f,-0.00910795f,-0.088434f},{-0.207048f,-0.0139163f,-0.0937354f},{-0.198575f,-0.0239061f,-0.103643f}, -{-0.194198f,-0.0290681f,-0.108235f},{-0.189737f,-0.034328f,-0.112578f},{-0.185202f,-0.0396756f,-0.116668f}, -{-0.17124f,-0.056138f,-0.127378f},{-0.171399f,-0.0559513f,-0.127941f},{-0.166644f,-0.0615582f,-0.130993f}, -{-0.166497f,-0.0617305f,-0.130423f},{-0.161725f,-0.0673581f,-0.133204f},{-0.156931f,-0.0730105f,-0.135723f}, -{-0.152125f,-0.0786778f,-0.137981f},{-0.147314f,-0.0843501f,-0.139981f},{-0.142507f,-0.090018f,-0.141725f}, -{-0.137712f,-0.0956724f,-0.143219f},{-0.132936f,-0.101305f,-0.144466f},{-0.114154f,-0.12345f,-0.147106f}, -{-0.263992f,0.0532287f,0.0703531f},{-0.263492f,0.0526391f,0.0630404f},{-0.264343f,0.0536432f,0.0776054f}, -{-0.262839f,0.0518697f,0.055677f},{-0.259931f,0.04844f,0.0333897f},{-0.258634f,0.046911f,0.0259331f}, -{-0.25717f,0.0451846f,0.0184831f},{-0.25731f,0.0457297f,0.0183202f},{-0.255673f,0.0437995f,0.0108731f}, -{-0.255536f,0.0432587f,0.0110526f},{-0.253733f,0.041132f,0.00365461f},{-0.251758f,0.0388039f,-0.00369726f}, -{-0.249613f,0.0362743f,-0.0109894f},{-0.247298f,0.0335441f,-0.0182079f},{-0.239346f,0.0241674f,-0.0392827f}, -{-0.239446f,0.0246659f,-0.0395738f},{-0.236462f,0.0211469f,-0.0463744f},{-0.236368f,0.0206563f,-0.0460682f}, -{-0.233232f,0.016959f,-0.0527117f},{-0.229943f,0.0130808f,-0.0592001f},{-0.219207f,0.000421111f,-0.0776124f}, -{-0.219263f,0.000866864f,-0.0779886f},{-0.215406f,-0.00368113f,-0.0837496f},{-0.215358f,-0.00411681f,-0.0833607f}, -{-0.211386f,-0.0088005f,-0.088897f},{-0.207298f,-0.0136212f,-0.094212f},{-0.194415f,-0.0288119f,-0.108749f}, -{-0.194416f,-0.028431f,-0.109195f},{-0.189934f,-0.0337161f,-0.113558f},{-0.189943f,-0.0340853f,-0.113103f}, -{-0.185396f,-0.0394466f,-0.117203f},{-0.180784f,-0.044885f,-0.121044f},{-0.176115f,-0.0503901f,-0.124624f}, -{-0.161859f,-0.0672002f,-0.133782f},{-0.157053f,-0.0728671f,-0.136307f},{-0.156971f,-0.0725841f,-0.136814f}, -{-0.152141f,-0.0782785f,-0.139083f},{-0.152234f,-0.078549f,-0.138571f},{-0.147411f,-0.0842358f,-0.140576f}, -{-0.142592f,-0.0899183f,-0.142325f},{-0.137784f,-0.0955872f,-0.143823f},{-0.132996f,-0.101234f,-0.145073f}, -{-0.128233f,-0.10685f,-0.146082f},{-0.264147f,0.0537916f,0.0703053f},{-0.263646f,0.0532007f,0.0629764f}, -{-0.2645f,0.0542071f,0.0775737f},{-0.262992f,0.0524296f,0.0555966f},{-0.262181f,0.0514738f,0.0481766f}, -{-0.261211f,0.0503292f,0.0407271f},{-0.260077f,0.0489923f,0.0332599f},{-0.258777f,0.04746f,0.0257867f}, -{-0.253865f,0.0416681f,0.00345877f},{-0.251803f,0.0398241f,-0.00404829f},{-0.251887f,0.0393348f,-0.00390942f}, -{-0.249737f,0.0367997f,-0.0112177f},{-0.247416f,0.0340634f,-0.0184523f},{-0.244926f,0.0311274f,-0.0255992f}, -{-0.242269f,0.0279939f,-0.0326442f},{-0.233209f,0.0178991f,-0.0532427f},{-0.233319f,0.0174415f,-0.0530326f}, -{-0.230023f,0.0135546f,-0.0595354f},{-0.226578f,0.00949215f,-0.0658703f},{-0.222989f,0.00526052f,-0.0720252f}, -{-0.211283f,-0.00795507f,-0.0895609f},{-0.211425f,-0.00837522f,-0.0892982f},{-0.207327f,-0.0132066f,-0.0946251f}, -{-0.203121f,-0.0181662f,-0.0997217f},{-0.198815f,-0.0232443f,-0.10458f},{-0.185197f,-0.0387137f,-0.117971f}, -{-0.185377f,-0.0390894f,-0.117667f},{-0.180754f,-0.0445398f,-0.121517f},{-0.176075f,-0.0500571f,-0.125105f}, -{-0.171349f,-0.0556307f,-0.128429f},{-0.166583f,-0.06125f,-0.131488f},{-0.161787f,-0.0669045f,-0.134283f}, -{-0.147308f,-0.083978f,-0.141092f},{-0.142236f,-0.0893707f,-0.143185f},{-0.142478f,-0.089673f,-0.142845f}, -{-0.13766f,-0.0953545f,-0.144346f},{-0.13286f,-0.101014f,-0.145599f},{-0.128087f,-0.106642f,-0.14661f}, -{-0.118645f,-0.117775f,-0.147929f},{-0.264695f,0.0550917f,0.0918925f},{-0.264082f,0.0543019f,0.070274f}, -{-0.26358f,0.0537101f,0.0629344f},{-0.262925f,0.0529379f,0.055544f},{-0.262113f,0.0519807f,0.0481132f}, -{-0.261141f,0.0508345f,0.040653f},{-0.260006f,0.0494956f,0.0331749f},{-0.258704f,0.047961f,0.0256909f}, -{-0.257235f,0.0462282f,0.0182135f},{-0.255595f,0.0442953f,0.0107557f},{-0.253785f,0.0421608f,0.00333058f}, -{-0.249448f,0.0376562f,-0.0114393f},{-0.247098f,0.035418f,-0.0180677f},{-0.247122f,0.034914f,-0.0186894f}, -{-0.24965f,0.0372853f,-0.0113672f},{-0.247326f,0.034545f,-0.0186123f},{-0.244833f,0.0316048f,-0.0257695f}, -{-0.242172f,0.0284668f,-0.0328247f},{-0.239345f,0.0251339f,-0.0397644f},{-0.236356f,0.0216099f,-0.0465748f}, -{-0.229908f,0.0140066f,-0.0597549f},{-0.229692f,0.0143612f,-0.0598609f},{-0.226458f,0.00993819f,-0.066099f}, -{-0.222864f,0.00570042f,-0.0722628f},{-0.219132f,0.0013004f,-0.0782348f},{-0.21527f,-0.00325419f,-0.0840042f}, -{-0.206947f,-0.0124575f,-0.0950259f},{-0.203042f,-0.0165305f,-0.0995152f},{-0.202732f,-0.0174277f,-0.100133f}, -{-0.20718f,-0.0127935f,-0.0948954f},{-0.202967f,-0.0177602f,-0.0999994f},{-0.198655f,-0.0228457f,-0.104865f}, -{-0.19425f,-0.0280399f,-0.109486f},{-0.189761f,-0.0333327f,-0.113856f},{-0.180568f,-0.0441721f,-0.121826f}, -{-0.175628f,-0.0493872f,-0.125571f},{-0.175882f,-0.0496974f,-0.125419f},{-0.171149f,-0.055279f,-0.128748f}, -{-0.166376f,-0.0609065f,-0.131812f},{-0.161574f,-0.0665692f,-0.134611f},{-0.15675f,-0.072257f,-0.137145f}, -{-0.151914f,-0.0779597f,-0.139417f},{-0.147073f,-0.0836674f,-0.14143f},{-0.137411f,-0.0950605f,-0.144688f}, -{-0.132605f,-0.100728f,-0.145943f},{-0.127824f,-0.106364f,-0.146956f},{-0.263889f,0.0546847f,0.0702589f}, -{-0.263387f,0.0540926f,0.0629142f},{-0.262732f,0.0533198f,0.0555186f},{-0.261919f,0.0523619f,0.0480826f}, -{-0.260946f,0.0512149f,0.0406172f},{-0.25981f,0.0498751f,0.0331338f},{-0.258508f,0.0483394f,0.0256447f}, -{-0.257037f,0.0466054f,0.0181621f},{-0.255397f,0.0446711f,0.010699f},{-0.253585f,0.0425351f,0.00326873f}, -{-0.251602f,0.0401968f,-0.0041153f},{-0.244627f,0.0319717f,-0.0258517f},{-0.241964f,0.0288315f,-0.0329118f}, -{-0.239135f,0.0254964f,-0.0398563f},{-0.236144f,0.0219699f,-0.0466715f},{-0.232995f,0.0182565f,-0.0533441f}, -{-0.232332f,0.0180069f,-0.0542301f},{-0.226239f,0.01029f,-0.0662094f},{-0.222643f,0.0060493f,-0.0723775f}, -{-0.218908f,0.00164621f,-0.0783537f},{-0.215043f,-0.00291157f,-0.0841271f},{-0.211054f,-0.00761574f,-0.0896876f}, -{-0.198416f,-0.0225168f,-0.105003f},{-0.194008f,-0.0277146f,-0.109627f},{-0.189516f,-0.0330111f,-0.114f}, -{-0.18495f,-0.0383959f,-0.118117f},{-0.180317f,-0.043858f,-0.121975f},{-0.179652f,-0.0441102f,-0.122344f}, -{-0.170891f,-0.0549727f,-0.128902f},{-0.166115f,-0.0606041f,-0.131968f},{-0.161309f,-0.0662708f,-0.134769f}, -{-0.156482f,-0.0719626f,-0.137305f},{-0.151643f,-0.0776692f,-0.139579f},{-0.146799f,-0.083381f,-0.141593f}, -{-0.141958f,-0.0890883f,-0.143349f},{-0.13713f,-0.094782f,-0.144853f},{-0.13232f,-0.100453f,-0.146109f}, -{-0.127537f,-0.106094f,-0.147123f},{-0.122786f,-0.111695f,-0.147899f},{-0.118075f,-0.117251f,-0.148445f}, -{-0.263669f,0.0549577f,0.0705096f},{-0.263191f,0.0543941f,0.0634113f},{-0.262578f,0.0536704f,0.056338f}, -{-0.261828f,0.052787f,0.0492957f},{-0.260945f,0.0517449f,0.042291f},{-0.259927f,0.050545f,0.0353299f}, -{-0.258776f,0.0491883f,0.0284186f},{-0.257494f,0.047676f,0.0215629f},{-0.25608f,0.0460093f,0.0147688f}, -{-0.254537f,0.0441899f,0.00804257f},{-0.252866f,0.0422193f,0.00139006f},{-0.251068f,0.0400992f,-0.00518291f}, -{-0.249145f,0.0378314f,-0.0116708f},{-0.24493f,0.0328611f,-0.024368f},{-0.242641f,0.030163f,-0.0305661f}, -{-0.240235f,0.027326f,-0.0366566f},{-0.237714f,0.0243525f,-0.0426344f},{-0.235078f,0.0212452f,-0.0484939f}, -{-0.229477f,0.0146404f,-0.0598379f},{-0.226516f,0.0111487f,-0.0653124f},{-0.223451f,0.00753462f,-0.0706491f}, -{-0.220285f,0.00380161f,-0.0758429f},{-0.217021f,-4.71144e-005f,-0.0808893f},{-0.213662f,-0.00400817f,-0.0857839f}, -{-0.21021f,-0.0080781f,-0.0905225f},{-0.206669f,-0.0122535f,-0.095101f},{-0.199332f,-0.0209053f,-0.103761f}, -{-0.195542f,-0.025374f,-0.107835f},{-0.191675f,-0.029933f,-0.111734f},{-0.187736f,-0.0345782f,-0.115454f}, -{-0.183727f,-0.0393053f,-0.118992f},{-0.175515f,-0.0489888f,-0.125509f},{-0.171318f,-0.0539368f,-0.128482f}, -{-0.167067f,-0.0589499f,-0.131262f},{-0.162764f,-0.0640236f,-0.133846f},{-0.158413f,-0.0691534f,-0.136231f}, -{-0.154019f,-0.0743348f,-0.138417f},{-0.149585f,-0.0795634f,-0.1404f},{-0.145115f,-0.0848346f,-0.142179f}, -{-0.140612f,-0.0901436f,-0.143752f},{-0.136082f,-0.0954858f,-0.145118f},{-0.131527f,-0.100856f,-0.146276f}, -{-0.126952f,-0.106251f,-0.147225f},{-0.122361f,-0.111665f,-0.147964f},{-0.117757f,-0.117093f,-0.148493f}, -{-0.23861f,0.0259416f,-0.0398563f},{-0.235619f,0.0224151f,-0.0466715f},{-0.227862f,0.0148455f,-0.0592001f}, -{-0.224871f,0.0109392f,-0.0658703f},{-0.228317f,0.0150017f,-0.0595354f},{-0.244102f,0.032417f,-0.0258517f}, -{-0.241439f,0.0292768f,-0.0329118f},{-0.248923f,0.0381015f,-0.0114393f},{-0.246597f,0.0353593f,-0.0186894f}, -{-0.251077f,0.0406421f,-0.0041153f},{-0.25306f,0.0429804f,0.00326873f},{-0.254872f,0.0451164f,0.010699f}, -{-0.24803f,0.0382467f,-0.0112177f},{-0.248524f,0.0382409f,-0.0113672f},{-0.25018f,0.0407819f,-0.00390942f}, -{-0.256512f,0.0470507f,0.0181621f},{-0.257983f,0.0487847f,0.0256447f},{-0.259285f,0.0503203f,0.0331338f}, -{-0.260421f,0.0516601f,0.0406172f},{-0.261394f,0.0528072f,0.0480826f},{-0.262207f,0.053765f,0.0555186f}, -{-0.262862f,0.0545378f,0.0629142f},{-0.263364f,0.05513f,0.0702589f},{-0.262955f,0.0552575f,0.070274f}, -{-0.262453f,0.0546658f,0.0629344f},{-0.262173f,0.0537258f,0.0848373f},{-0.261981f,0.0541091f,0.0848323f}, -{-0.261916f,0.0546203f,0.084822f},{-0.261986f,0.054502f,0.0918925f},{-0.262228f,0.0538242f,0.0918925f}, -{-0.261967f,0.0534828f,0.0777045f},{-0.261618f,0.0530711f,0.0705025f},{-0.261425f,0.0534539f,0.0704874f}, -{-0.262441f,0.0552387f,0.0703053f},{-0.26194f,0.0546478f,0.0629764f},{-0.261411f,0.0544038f,0.0630404f}, -{-0.261286f,0.0538767f,0.0555966f},{-0.261911f,0.0549934f,0.0703531f},{-0.263717f,0.0555463f,0.0775429f}, -{-0.263265f,0.0560102f,0.0918925f},{-0.263001f,0.0558995f,0.0847723f},{-0.263516f,0.0559192f,0.084762f}, -{-0.262905f,0.0559313f,0.0918925f},{-0.26247f,0.0556527f,0.084788f},{-0.26258f,0.0557625f,0.0918925f}, -{-0.263625f,0.0559923f,0.0918925f},{-0.263926f,0.0557921f,0.084757f},{-0.263974f,0.0558822f,0.0918925f}, -{-0.262073f,0.0551847f,0.0848062f},{-0.262004f,0.0548614f,0.0918925f},{-0.23247f,0.0187017f,-0.0533441f}, -{-0.229167f,0.0148065f,-0.0598609f},{-0.225714f,0.0107353f,-0.0662094f},{-0.222117f,0.00649456f,-0.0723775f}, -{-0.218383f,0.00209146f,-0.0783537f},{-0.214518f,-0.00246632f,-0.0841271f},{-0.206053f,-0.0118379f,-0.0948954f}, -{-0.209719f,-0.00692815f,-0.0892982f},{-0.205621f,-0.0117596f,-0.0946251f},{-0.210528f,-0.00717049f,-0.0896876f}, -{-0.206422f,-0.0120123f,-0.0950259f},{-0.202207f,-0.0169825f,-0.100133f},{-0.197891f,-0.0220715f,-0.105003f}, -{-0.193483f,-0.0272694f,-0.109627f},{-0.188991f,-0.0325659f,-0.114f},{-0.184425f,-0.0379506f,-0.118117f}, -{-0.174369f,-0.04861f,-0.125105f},{-0.174034f,-0.0486253f,-0.124624f},{-0.169642f,-0.0541836f,-0.128429f}, -{-0.179792f,-0.0434128f,-0.121975f},{-0.175103f,-0.0489419f,-0.125571f},{-0.170366f,-0.0545275f,-0.128902f}, -{-0.16559f,-0.0601589f,-0.131968f},{-0.160784f,-0.0658256f,-0.134769f},{-0.155957f,-0.0715173f,-0.137305f}, -{-0.151118f,-0.077224f,-0.139579f},{-0.146274f,-0.0829357f,-0.141593f},{-0.141109f,-0.0884151f,-0.143185f}, -{-0.141433f,-0.088643f,-0.143349f},{-0.145946f,-0.0827118f,-0.14143f},{-0.136605f,-0.0943367f,-0.144853f}, -{-0.127012f,-0.105648f,-0.147123f},{-0.131478f,-0.0997722f,-0.145943f},{-0.126698f,-0.105409f,-0.146956f}, -{-0.121422f,-0.110662f,-0.146855f},{-0.121386f,-0.110704f,-0.146244f},{-0.116731f,-0.116193f,-0.147398f}, -{-0.135703f,-0.0938225f,-0.143823f},{-0.130915f,-0.099469f,-0.145073f},{-0.131154f,-0.0995666f,-0.145599f}, -{-0.121812f,-0.111169f,-0.145367f},{-0.121543f,-0.1109f,-0.145714f},{-0.126513f,-0.105627f,-0.144599f}, -{-0.112534f,-0.12211f,-0.146226f},{-0.107823f,-0.127372f,-0.146474f},{-0.112251f,-0.121856f,-0.146574f}, -{-0.116939f,-0.116328f,-0.147929f},{-0.12164f,-0.110785f,-0.147385f},{-0.108041f,-0.127557f,-0.146297f}, -{-0.112831f,-0.122369f,-0.146058f},{-0.108274f,-0.127755f,-0.146158f},{-0.126381f,-0.105195f,-0.14661f}, -{-0.126152f,-0.105085f,-0.146082f},{-0.117242f,-0.116558f,-0.148277f},{-0.12195f,-0.111006f,-0.147732f}, -{-0.131795f,-0.100008f,-0.146109f},{-0.122261f,-0.11125f,-0.147899f},{-0.117549f,-0.116805f,-0.148445f}, -{-0.112883f,-0.122308f,-0.148767f},{-0.108275f,-0.127755f,-0.148876f},{-0.262114f,0.0552103f,0.0918925f}, -{-0.263308f,0.0556736f,0.0775529f},{-0.261798f,0.0538935f,0.055544f},{-0.260986f,0.0529363f,0.0481132f}, -{-0.260014f,0.0517901f,0.040653f},{-0.258879f,0.0504512f,0.0331749f},{-0.257577f,0.0489167f,0.0256909f}, -{-0.256108f,0.0471839f,0.0182135f},{-0.254469f,0.0452509f,0.0107557f},{-0.252658f,0.0431164f,0.00333058f}, -{-0.250677f,0.0407797f,-0.00404829f},{-0.2462f,0.0355006f,-0.0186123f},{-0.243706f,0.0325604f,-0.0257695f}, -{-0.241045f,0.0294224f,-0.0328247f},{-0.238218f,0.0260895f,-0.0397644f},{-0.23523f,0.0225655f,-0.0465748f}, -{-0.232083f,0.0188547f,-0.0532427f},{-0.228781f,0.0149622f,-0.0597549f},{-0.225331f,0.0108938f,-0.066099f}, -{-0.221737f,0.00665604f,-0.0722628f},{-0.218006f,0.00225601f,-0.0782348f},{-0.214143f,-0.00229858f,-0.0840042f}, -{-0.210156f,-0.00699946f,-0.0895609f},{-0.201841f,-0.0168046f,-0.0999994f},{-0.197528f,-0.0218901f,-0.104865f}, -{-0.193123f,-0.0270843f,-0.109486f},{-0.188634f,-0.0323771f,-0.113856f},{-0.18407f,-0.0377581f,-0.117971f}, -{-0.179441f,-0.0432164f,-0.121826f},{-0.174756f,-0.0487418f,-0.125419f},{-0.170022f,-0.0543234f,-0.128748f}, -{-0.165249f,-0.0599509f,-0.131812f},{-0.160447f,-0.0656136f,-0.134611f},{-0.155623f,-0.0713014f,-0.137145f}, -{-0.150787f,-0.0770041f,-0.139417f},{-0.136284f,-0.0941049f,-0.144688f},{-0.135953f,-0.0939075f,-0.144346f}, -{-0.112579f,-0.122056f,-0.148599f},{-0.108037f,-0.127554f,-0.148751f},{-0.262793f,0.0556542f,0.0775737f}, -{-0.260475f,0.0529209f,0.0481766f},{-0.259504f,0.0517763f,0.0407271f},{-0.258371f,0.0504394f,0.0332599f}, -{-0.257071f,0.048907f,0.0257867f},{-0.255604f,0.0471768f,0.0183202f},{-0.253967f,0.0452466f,0.0108731f}, -{-0.252159f,0.0431152f,0.00345877f},{-0.24322f,0.0325744f,-0.0255992f},{-0.24571f,0.0355104f,-0.0184523f}, -{-0.245217f,0.0353088f,-0.0182079f},{-0.240562f,0.029441f,-0.0326442f},{-0.23774f,0.0261129f,-0.0395738f}, -{-0.234756f,0.022594f,-0.0463744f},{-0.231613f,0.0188886f,-0.0530326f},{-0.221283f,0.00670759f,-0.0720252f}, -{-0.217557f,0.00231394f,-0.0779886f},{-0.2137f,-0.00223406f,-0.0837496f},{-0.196723f,-0.0218719f,-0.104145f}, -{-0.196495f,-0.0221414f,-0.103643f},{-0.192334f,-0.0270471f,-0.108749f},{-0.201415f,-0.0167191f,-0.0997217f}, -{-0.197108f,-0.0217972f,-0.10458f},{-0.19271f,-0.0269839f,-0.109195f},{-0.188227f,-0.0322691f,-0.113558f}, -{-0.183671f,-0.0376423f,-0.117667f},{-0.179048f,-0.0430927f,-0.121517f},{-0.164877f,-0.0598029f,-0.131488f}, -{-0.160081f,-0.0654575f,-0.134283f},{-0.155264f,-0.071137f,-0.136814f},{-0.150435f,-0.0768314f,-0.139083f}, -{-0.145602f,-0.0825309f,-0.141092f},{-0.140772f,-0.088226f,-0.142845f},{-0.107472f,-0.127075f,-0.147687f}, -{-0.112085f,-0.121672f,-0.147719f},{-0.112074f,-0.121685f,-0.147106f},{-0.112283f,-0.121818f,-0.148251f}, -{-0.107827f,-0.127376f,-0.148558f},{-0.262314f,0.055521f,0.0918925f},{-0.262262f,0.055408f,0.0776054f}, -{-0.260758f,0.0536344f,0.055677f},{-0.25995f,0.0526807f,0.0482734f},{-0.257465f,0.0497507f,0.0335395f}, -{-0.256553f,0.0486758f,0.0259331f},{-0.25785f,0.0502047f,0.0333897f},{-0.258981f,0.0515387f,0.0408405f}, -{-0.255089f,0.0469493f,0.0184831f},{-0.253456f,0.0450234f,0.0110526f},{-0.251652f,0.0428967f,0.00365461f}, -{-0.249678f,0.0405686f,-0.00369726f},{-0.247532f,0.0380391f,-0.0109894f},{-0.239741f,0.0288524f,-0.0320502f}, -{-0.237265f,0.0259322f,-0.0392827f},{-0.240081f,0.0292528f,-0.0323684f},{-0.242732f,0.0323793f,-0.025339f}, -{-0.234287f,0.022421f,-0.0460682f},{-0.231151f,0.0187238f,-0.0527117f},{-0.220554f,0.00622748f,-0.0712434f}, -{-0.217126f,0.00218583f,-0.0776124f},{-0.220844f,0.00656977f,-0.0716622f},{-0.224425f,0.010792f,-0.065521f}, -{-0.213277f,-0.00235208f,-0.0833607f},{-0.209305f,-0.00703577f,-0.088897f},{-0.205217f,-0.0118565f,-0.094212f}, -{-0.20102f,-0.0168051f,-0.0992973f},{-0.187862f,-0.0323206f,-0.113103f},{-0.183315f,-0.0376819f,-0.117203f}, -{-0.178703f,-0.0431203f,-0.121044f},{-0.164417f,-0.0599658f,-0.130423f},{-0.159778f,-0.0654355f,-0.133782f}, -{-0.164563f,-0.0597934f,-0.130993f},{-0.169318f,-0.0541866f,-0.127941f},{-0.154972f,-0.0711024f,-0.136307f}, -{-0.150153f,-0.0767842f,-0.138571f},{-0.14533f,-0.0824711f,-0.140576f},{-0.140511f,-0.0881536f,-0.142325f}, -{-0.116874f,-0.116404f,-0.146255f},{-0.126104f,-0.105141f,-0.145472f},{-0.107534f,-0.127127f,-0.148015f}, -{-0.107655f,-0.12723f,-0.14831f},{-0.261515f,0.0545271f,0.0704083f},{-0.261866f,0.0549406f,0.077642f}, -{-0.261017f,0.053939f,0.0631143f},{-0.260366f,0.0531716f,0.0557698f},{-0.259559f,0.0522203f,0.0483851f}, -{-0.258593f,0.0510812f,0.0409712f},{-0.256171f,0.0482257f,0.026102f},{-0.251283f,0.0424614f,0.00388058f}, -{-0.253082f,0.0445826f,0.0112596f},{-0.252945f,0.0440418f,0.011439f},{-0.254711f,0.0465036f,0.0186711f}, -{-0.249313f,0.0401392f,-0.00345247f},{-0.247174f,0.0376162f,-0.0107259f},{-0.244864f,0.0348929f,-0.017926f}, -{-0.242386f,0.0319709f,-0.0250388f},{-0.230858f,0.0174103f,-0.0518103f},{-0.230748f,0.0178679f,-0.0520204f}, -{-0.233974f,0.0210845f,-0.0452083f},{-0.236932f,0.0255403f,-0.0389468f},{-0.233962f,0.0220381f,-0.0457149f}, -{-0.230835f,0.0183503f,-0.0523413f},{-0.227554f,0.014482f,-0.0588132f},{-0.224125f,0.0104389f,-0.0651178f}, -{-0.209148f,-0.00818865f,-0.0877701f},{-0.209006f,-0.00776851f,-0.0880327f},{-0.213095f,-0.00353415f,-0.0822683f}, -{-0.216845f,0.00185478f,-0.0771783f},{-0.213007f,-0.00267152f,-0.0829118f},{-0.209045f,-0.00734323f,-0.088434f}, -{-0.204967f,-0.0121516f,-0.0937354f},{-0.200781f,-0.0170875f,-0.0988077f},{-0.183121f,-0.0379109f,-0.116668f}, -{-0.187656f,-0.0325633f,-0.112578f},{-0.187665f,-0.0329324f,-0.112123f},{-0.192117f,-0.0273033f,-0.108235f}, -{-0.178521f,-0.0433353f,-0.120499f},{-0.173864f,-0.0488263f,-0.12407f},{-0.169159f,-0.0543733f,-0.127378f}, -{-0.159644f,-0.0655934f,-0.133204f},{-0.145233f,-0.0825854f,-0.139981f},{-0.150044f,-0.0769131f,-0.137981f}, -{-0.150137f,-0.0771835f,-0.137469f},{-0.15485f,-0.0712458f,-0.135723f},{-0.140427f,-0.0882533f,-0.141725f}, -{-0.135631f,-0.0939077f,-0.143219f},{-0.130855f,-0.0995398f,-0.144466f},{-0.12625f,-0.105349f,-0.144944f}, -{-0.116707f,-0.116221f,-0.146786f},{-0.26136f,0.0539641f,0.0704561f},{-0.26171f,0.0543767f,0.0776737f}, -{-0.260862f,0.0533774f,0.0631783f},{-0.260213f,0.0526117f,0.0558501f},{-0.259408f,0.0516625f,0.0484819f}, -{-0.258444f,0.0505259f,0.0410845f},{-0.257318f,0.0491984f,0.0336694f},{-0.256028f,0.0476767f,0.0262484f}, -{-0.254571f,0.0459585f,0.018834f},{-0.25123f,0.0414326f,0.00420461f},{-0.249268f,0.039119f,-0.00310144f}, -{-0.249185f,0.0396083f,-0.00324031f},{-0.25115f,0.0419253f,0.00407642f},{-0.24705f,0.0370909f,-0.0104976f}, -{-0.244746f,0.0343737f,-0.0176816f},{-0.242273f,0.0314582f,-0.0247786f},{-0.239634f,0.0283466f,-0.0317744f}, -{-0.236832f,0.0250418f,-0.0386556f},{-0.233868f,0.0215475f,-0.0454087f},{-0.227474f,0.0140082f,-0.0584778f}, -{-0.224053f,0.00997407f,-0.0647685f},{-0.220489f,0.005772f,-0.0708804f},{-0.216789f,0.00140903f,-0.0768021f}, -{-0.212959f,-0.0031072f,-0.0825229f},{-0.204937f,-0.0125662f,-0.0933224f},{-0.20076f,-0.0174911f,-0.0983834f}, -{-0.196484f,-0.0225337f,-0.103208f},{-0.192116f,-0.0276842f,-0.10779f},{-0.183319f,-0.0386437f,-0.1159f}, -{-0.178736f,-0.0440482f,-0.119717f},{-0.17855f,-0.0436805f,-0.120026f},{-0.18314f,-0.0382681f,-0.116203f}, -{-0.173903f,-0.0491593f,-0.123589f},{-0.169209f,-0.0546939f,-0.12689f},{-0.164477f,-0.060274f,-0.129928f}, -{-0.159715f,-0.065889f,-0.132703f},{-0.154932f,-0.0715289f,-0.135216f},{-0.145337f,-0.0828432f,-0.139465f}, -{-0.140782f,-0.0888008f,-0.140865f},{-0.136005f,-0.0944344f,-0.142353f},{-0.135756f,-0.0941403f,-0.142696f}, -{-0.140541f,-0.0884985f,-0.141206f},{-0.13099f,-0.0997599f,-0.14394f},{-0.107533f,-0.127126f,-0.147023f}, -{-0.107472f,-0.127074f,-0.147351f},{-0.262065f,0.0541415f,0.0918925f},{-0.261775f,0.0538659f,0.0776945f}, -{-0.260928f,0.052868f,0.0632202f},{-0.26028f,0.0521034f,0.0559028f},{-0.261121f,0.0524856f,0.0632405f}, -{-0.259476f,0.0511556f,0.0485453f},{-0.258514f,0.0500207f,0.0411587f},{-0.25739f,0.0486951f,0.0337544f}, -{-0.256101f,0.0471756f,0.0263442f},{-0.254646f,0.0454599f,0.0189407f},{-0.253023f,0.043546f,0.0115564f}, -{-0.24504f,0.033523f,-0.0174445f},{-0.247339f,0.0362343f,-0.010276f},{-0.247136f,0.0366052f,-0.0103481f}, -{-0.244835f,0.033892f,-0.0175217f},{-0.242366f,0.0309808f,-0.0246083f},{-0.239731f,0.0278737f,-0.0315939f}, -{-0.236933f,0.0245738f,-0.038465f},{-0.227806f,0.0132016f,-0.0581524f},{-0.227589f,0.0135563f,-0.0582583f}, -{-0.231072f,0.0170529f,-0.051709f},{-0.224173f,0.00952803f,-0.0645398f},{-0.220614f,0.0053321f,-0.0706427f}, -{-0.21692f,0.000975486f,-0.0765558f},{-0.205317f,-0.0133153f,-0.0929216f},{-0.20115f,-0.0182295f,-0.0979716f}, -{-0.205085f,-0.0129793f,-0.093052f},{-0.200914f,-0.017897f,-0.0981056f},{-0.196644f,-0.0229323f,-0.102923f}, -{-0.192282f,-0.0280753f,-0.107499f},{-0.187838f,-0.0333159f,-0.111826f},{-0.174351f,-0.0498292f,-0.123123f}, -{-0.174096f,-0.049519f,-0.123274f},{-0.178987f,-0.0443622f,-0.119568f},{-0.169409f,-0.0550456f,-0.126571f}, -{-0.164684f,-0.0606175f,-0.129604f},{-0.159929f,-0.0662243f,-0.132375f},{-0.155153f,-0.071856f,-0.134885f}, -{-0.150364f,-0.0775023f,-0.137135f},{-0.145571f,-0.0831538f,-0.139127f},{-0.131246f,-0.100046f,-0.143596f}, -{-0.117445f,-0.116929f,-0.145739f},{-0.122103f,-0.111436f,-0.145199f},{-0.117151f,-0.116666f,-0.145907f}, -{-0.107652f,-0.127227f,-0.146724f},{-0.260473f,0.0517215f,0.0559281f},{-0.25967f,0.0507744f,0.0485758f}, -{-0.258708f,0.0496403f,0.0411945f},{-0.257585f,0.0483156f,0.0337954f},{-0.256297f,0.0467972f,0.0263905f}, -{-0.254843f,0.0450828f,0.0189921f},{-0.253221f,0.0431702f,0.0116131f},{-0.25143f,0.0410583f,0.00426646f}, -{-0.249469f,0.0387463f,-0.00303443f},{-0.242572f,0.0306138f,-0.0245261f},{-0.239939f,0.027509f,-0.0315068f}, -{-0.237143f,0.0242113f,-0.0383731f},{-0.234186f,0.0207246f,-0.0451116f},{-0.224392f,0.00917619f,-0.0644294f}, -{-0.220836f,0.00498322f,-0.0705281f},{-0.217144f,0.000629689f,-0.076437f},{-0.213322f,-0.00387677f,-0.0821454f}, -{-0.209377f,-0.00852799f,-0.0876434f},{-0.196882f,-0.0232612f,-0.102786f},{-0.192524f,-0.0284006f,-0.107358f}, -{-0.188082f,-0.0336375f,-0.111682f},{-0.183567f,-0.0389616f,-0.115753f},{-0.169667f,-0.0553518f,-0.126416f}, -{-0.164945f,-0.0609198f,-0.129448f},{-0.160193f,-0.0665227f,-0.132217f},{-0.15542f,-0.0721504f,-0.134725f}, -{-0.150635f,-0.0777928f,-0.136973f},{-0.145846f,-0.0834402f,-0.138964f},{-0.14106f,-0.0890833f,-0.140701f}, -{-0.136286f,-0.0947129f,-0.142188f},{-0.13153f,-0.10032f,-0.14343f},{-0.126801f,-0.105897f,-0.144432f}, -{-0.00563681f,-0.247569f,-0.0892991f},{-0.0097342f,-0.242737f,-0.0946258f},{-0.00976382f,-0.242323f,-0.0942128f}, -{-0.0275449f,-0.222933f,-0.114f},{-0.0230532f,-0.22823f,-0.109627f},{-0.0321114f,-0.217549f,-0.118117f}, -{-0.0367439f,-0.212086f,-0.121975f},{-0.0414333f,-0.206557f,-0.125571f},{-0.0461704f,-0.200971f,-0.128902f}, -{-0.0509464f,-0.19534f,-0.131968f},{-0.0557523f,-0.189673f,-0.134769f},{-0.041179f,-0.206247f,-0.125419f}, -{-0.0457129f,-0.200313f,-0.128429f},{-0.0409859f,-0.205887f,-0.125105f},{-0.0605794f,-0.183981f,-0.137305f}, -{-0.0654191f,-0.178274f,-0.139579f},{-0.0702631f,-0.172563f,-0.141592f},{-0.0799319f,-0.161162f,-0.144853f}, -{-0.0751032f,-0.166855f,-0.143349f},{-0.0847415f,-0.155491f,-0.146109f},{-0.0895249f,-0.14985f,-0.147122f}, -{-0.0942754f,-0.144249f,-0.147899f},{-0.103705f,-0.13313f,-0.146057f},{-0.0939843f,-0.143982f,-0.147731f}, -{-0.0892371f,-0.14958f,-0.146955f},{-0.094433f,-0.144063f,-0.145199f},{-0.0941223f,-0.143819f,-0.145366f}, -{-0.0990912f,-0.13857f,-0.145739f},{-0.0888286f,-0.149094f,-0.146081f},{-0.0842013f,-0.15493f,-0.145599f}, -{-0.0889744f,-0.149302f,-0.14661f},{-0.103104f,-0.132641f,-0.146574f},{-0.102907f,-0.132494f,-0.147105f}, -{-0.103401f,-0.132879f,-0.146225f},{-0.0937148f,-0.143713f,-0.147384f},{-0.102895f,-0.132508f,-0.147719f}, -{-0.103653f,-0.133192f,-0.148767f},{-0.103355f,-0.132933f,-0.148599f},{-0.0989867f,-0.138694f,-0.148445f}, -{-0.103072f,-0.132679f,-0.148251f},{-0.0935584f,-0.143517f,-0.146855f},{-0.0186452f,-0.233427f,-0.105003f}, -{-0.0143294f,-0.238516f,-0.100134f},{-0.0101144f,-0.243486f,-0.0950266f},{-0.00600817f,-0.248328f,-0.0896885f}, -{-0.00201866f,-0.253032f,-0.0841281f},{0.00184672f,-0.25759f,-0.0783547f},{0.00558095f,-0.261993f,-0.0723786f}, -{0.0128468f,-0.269951f,-0.059756f},{0.00951627f,-0.265436f,-0.0658715f},{0.0129617f,-0.269499f,-0.0595366f}, -{0.00917748f,-0.266234f,-0.0662105f},{0.0126303f,-0.270305f,-0.059862f},{0.0159338f,-0.274201f,-0.053345f}, -{0.0190832f,-0.277914f,-0.0466724f},{0.022074f,-0.281441f,-0.039857f},{0.0249026f,-0.284776f,-0.0329122f}, -{0.0275658f,-0.287916f,-0.0258517f},{0.0326757f,-0.292744f,-0.0112184f},{0.0325522f,-0.292219f,-0.01099f}, -{0.0348257f,-0.295279f,-0.00391029f},{0.0300611f,-0.290859f,-0.0186898f},{0.0323867f,-0.293601f,-0.0114399f}, -{0.0345413f,-0.296141f,-0.00411618f},{0.0365244f,-0.29848f,0.00326766f},{0.0383359f,-0.300616f,0.0106978f}, -{0.0399765f,-0.30255f,0.0181608f},{0.0414471f,-0.304284f,0.0256434f},{0.0427495f,-0.30582f,0.0331326f}, -{0.0440805f,-0.306779f,0.0406518f},{0.0438858f,-0.30716f,0.040616f},{0.042945f,-0.305441f,0.0331736f}, -{0.0448586f,-0.308307f,0.0480815f},{0.0476467f,-0.310397f,0.0847721f},{0.0472826f,-0.309588f,0.077605f}, -{0.04749f,-0.309833f,0.0847878f},{0.0460056f,-0.308462f,0.0704555f},{0.0465356f,-0.308707f,0.0704077f}, -{0.045508f,-0.307875f,0.0631775f},{0.0458644f,-0.308883f,0.0555431f},{0.0465193f,-0.309655f,0.0629336f}, -{0.0463263f,-0.310038f,0.0629134f},{0.0454915f,-0.308443f,0.0704868f},{0.0449947f,-0.307857f,0.0632194f}, -{0.046047f,-0.309098f,0.0848321f},{0.0464337f,-0.309168f,0.0918925f},{0.0465619f,-0.309118f,0.0848218f}, -{0.0464311f,-0.308584f,0.0630396f},{0.0470865f,-0.309737f,0.0703047f},{0.0465854f,-0.309146f,0.0629755f}, -{0.0456375f,-0.309225f,0.0848371f},{0.0460743f,-0.309186f,0.0918925f},{0.0457786f,-0.307815f,0.0556761f}, -{0.0459315f,-0.308375f,0.0555957f},{0.0449698f,-0.306861f,0.0482723f},{0.0457254f,-0.309296f,0.0918925f}, -{0.0456709f,-0.309265f,0.0555177f},{0.0471815f,-0.311046f,0.0775425f},{0.0468284f,-0.31063f,0.0702583f}, -{0.0470211f,-0.310247f,0.0702734f},{0.0473899f,-0.311292f,0.0847568f},{-0.0986923f,-0.138431f,-0.148277f}, -{-0.084457f,-0.155216f,-0.145943f},{-0.0796508f,-0.160883f,-0.144688f},{-0.0748255f,-0.166573f,-0.143185f}, -{-0.0699887f,-0.172276f,-0.141429f},{-0.0651481f,-0.177984f,-0.139417f},{-0.0603117f,-0.183687f,-0.137145f}, -{-0.055488f,-0.189375f,-0.134611f},{-0.0506855f,-0.195037f,-0.131812f},{-0.0459129f,-0.200665f,-0.128748f}, -{-0.0364929f,-0.211772f,-0.121826f},{-0.0318636f,-0.217231f,-0.117971f},{-0.0273004f,-0.222612f,-0.113856f}, -{-0.0228118f,-0.227904f,-0.109486f},{-0.0184068f,-0.233098f,-0.104866f},{-0.0140941f,-0.238184f,-0.1f}, -{-0.00988197f,-0.24315f,-0.0948962f},{-0.00577865f,-0.247989f,-0.0895618f},{-0.00179193f,-0.25269f,-0.0840052f}, -{0.00207075f,-0.257244f,-0.0782359f},{0.00580238f,-0.261644f,-0.072264f},{0.0093964f,-0.265882f,-0.0661002f}, -{0.016148f,-0.273843f,-0.0532437f},{0.0192952f,-0.277554f,-0.0465757f},{0.022284f,-0.281078f,-0.039765f}, -{0.0251106f,-0.284411f,-0.0328251f},{0.0277719f,-0.287549f,-0.0257695f},{0.0302654f,-0.29049f,-0.0186126f}, -{0.0325894f,-0.29323f,-0.0113678f},{0.0347425f,-0.295769f,-0.00404916f},{0.0367243f,-0.298105f,0.00332952f}, -{0.0385345f,-0.30024f,0.0107545f},{0.0401739f,-0.302173f,0.0182123f},{0.0416435f,-0.303906f,0.0256896f}, -{0.0450526f,-0.307926f,0.0481121f},{0.0451209f,-0.307419f,0.0481755f},{0.0475821f,-0.310908f,0.0847617f}, -{0.0473739f,-0.310663f,0.0775525f},{0.0476338f,-0.311036f,0.0918925f},{0.0474707f,-0.311354f,0.0918925f}, -{-0.0984159f,-0.138169f,-0.147929f},{-0.079402f,-0.160589f,-0.144345f},{-0.0745837f,-0.166271f,-0.142845f}, -{-0.0697539f,-0.171966f,-0.141092f},{-0.0649203f,-0.177665f,-0.139082f},{-0.060091f,-0.18336f,-0.136814f}, -{-0.0552742f,-0.189039f,-0.134283f},{-0.0504787f,-0.194694f,-0.131488f},{-0.031684f,-0.216855f,-0.117667f}, -{-0.0363066f,-0.211405f,-0.121517f},{-0.0362774f,-0.211059f,-0.121044f},{-0.0271274f,-0.222228f,-0.113559f}, -{-0.0226453f,-0.227513f,-0.109195f},{-0.0182467f,-0.2327f,-0.104581f},{-0.0139402f,-0.237778f,-0.0997223f}, -{-0.00165587f,-0.252263f,-0.0837506f},{0.00220122f,-0.256811f,-0.0779897f},{0.00592745f,-0.261204f,-0.0720263f}, -{0.0193066f,-0.276601f,-0.046069f},{0.0189819f,-0.276218f,-0.0457157f},{0.0222844f,-0.280112f,-0.0392833f}, -{0.0162581f,-0.273386f,-0.0530336f},{0.0194007f,-0.277091f,-0.0463752f},{0.0223852f,-0.28061f,-0.0395744f}, -{0.0252077f,-0.283938f,-0.0326445f},{0.0278652f,-0.287072f,-0.0255992f},{0.0303551f,-0.290008f,-0.0184526f}, -{0.0368046f,-0.297613f,0.00345771f},{0.0386122f,-0.299744f,0.0108719f},{0.0402492f,-0.301674f,0.0183189f}, -{0.0417167f,-0.303405f,0.0257854f},{0.0430163f,-0.304937f,0.0332586f},{0.0441501f,-0.306274f,0.0407259f}, -{0.0474388f,-0.310152f,0.0775733f},{0.046931f,-0.309174f,0.0703525f},{0.0477127f,-0.310676f,0.0918925f}, -{-0.0982492f,-0.137986f,-0.147398f},{-0.084066f,-0.15471f,-0.145073f},{-0.0792773f,-0.160357f,-0.143822f}, -{-0.0697475f,-0.171594f,-0.13998f},{-0.0648277f,-0.177395f,-0.138571f},{-0.0696506f,-0.171708f,-0.140576f}, -{-0.0744697f,-0.166025f,-0.142325f},{-0.0600091f,-0.183077f,-0.136307f},{-0.055203f,-0.188744f,-0.133782f}, -{-0.050418f,-0.194386f,-0.130993f},{-0.0456629f,-0.199993f,-0.127941f},{-0.0409464f,-0.205554f,-0.124624f}, -{-0.0273243f,-0.221616f,-0.112579f},{-0.0226464f,-0.227132f,-0.10875f},{-0.0271185f,-0.221859f,-0.113104f}, -{-0.031665f,-0.216498f,-0.117203f},{-0.0182575f,-0.232307f,-0.104146f},{-0.0139605f,-0.237374f,-0.0992979f}, -{-0.00197428f,-0.251508f,-0.0829128f},{0.00214517f,-0.256365f,-0.0776135f},{-0.00170337f,-0.251827f,-0.0833616f}, -{-0.00567551f,-0.247143f,-0.0888979f},{0.00586315f,-0.260749f,-0.0716633f},{0.00944402f,-0.264971f,-0.0655221f}, -{0.0128818f,-0.269025f,-0.0592012f},{0.0161709f,-0.272903f,-0.0527127f},{0.0251007f,-0.283433f,-0.0323688f}, -{0.0277523f,-0.286559f,-0.025339f},{0.0302367f,-0.289489f,-0.0182083f},{0.0363027f,-0.296641f,0.00387953f}, -{0.0384755f,-0.299203f,0.0110514f},{0.0366719f,-0.297077f,0.00365355f},{0.0346974f,-0.294749f,-0.00369814f}, -{0.0401089f,-0.301129f,0.0184819f},{0.0415731f,-0.302856f,0.0259318f},{0.0428699f,-0.304385f,0.0333884f}, -{0.0440012f,-0.305719f,0.0408392f},{0.0460369f,-0.308119f,0.0631135f},{0.0476948f,-0.310316f,0.0918925f}, -{-0.0935941f,-0.143475f,-0.146243f},{-0.0982728f,-0.137958f,-0.146785f},{-0.0888764f,-0.149038f,-0.145472f}, -{-0.084126f,-0.154639f,-0.144466f},{-0.0793496f,-0.160271f,-0.143218f},{-0.0745543f,-0.165926f,-0.141725f}, -{-0.064937f,-0.177266f,-0.137981f},{-0.0505642f,-0.194213f,-0.130423f},{-0.0553369f,-0.188586f,-0.133204f}, -{-0.0556402f,-0.188608f,-0.132703f},{-0.0601307f,-0.182933f,-0.135723f},{-0.0458212f,-0.199806f,-0.127378f}, -{-0.0411168f,-0.205353f,-0.12407f},{-0.0364598f,-0.210844f,-0.120499f},{-0.0318592f,-0.216269f,-0.116668f}, -{-0.0150205f,-0.237091f,-0.0981062f},{-0.0145949f,-0.237006f,-0.098384f},{-0.0192907f,-0.232056f,-0.102924f}, -{-0.0228636f,-0.226876f,-0.108236f},{-0.018486f,-0.232038f,-0.103644f},{-0.0142f,-0.237092f,-0.0988083f}, -{-0.0100141f,-0.242028f,-0.0937362f},{-0.00593625f,-0.246836f,-0.0884349f},{0.00823812f,-0.264516f,-0.0645409f}, -{0.00869775f,-0.264471f,-0.0647696f},{0.00467957f,-0.26032f,-0.0706439f},{0.00186441f,-0.256034f,-0.0771794f}, -{0.00557286f,-0.260407f,-0.0712445f},{0.00914456f,-0.264618f,-0.065119f},{0.0125735f,-0.268661f,-0.0588143f}, -{0.0158543f,-0.27253f,-0.0523423f},{0.0274059f,-0.286151f,-0.0250388f},{0.0247611f,-0.283032f,-0.0320505f}, -{0.0242796f,-0.282844f,-0.0317747f},{0.0219521f,-0.27972f,-0.0389474f},{0.029884f,-0.289073f,-0.0179263f}, -{0.0321935f,-0.291796f,-0.0107265f},{0.0343333f,-0.294319f,-0.00345334f},{0.0381017f,-0.298763f,0.0112584f}, -{0.0424848f,-0.303931f,0.0335382f},{0.0411914f,-0.302406f,0.0261007f},{0.0406733f,-0.302175f,0.0262471f}, -{0.0397309f,-0.300684f,0.0186698f},{0.0436132f,-0.305261f,0.04097f},{0.0445793f,-0.306401f,0.048384f}, -{0.0453861f,-0.307352f,0.0557688f},{0.0468862f,-0.309121f,0.0776416f},{0.0470932f,-0.309365f,0.084806f}, -{0.0473856f,-0.309657f,0.0918925f},{0.0475847f,-0.309968f,0.0918925f},{-0.0938123f,-0.143598f,-0.145713f}, -{-0.0984806f,-0.138093f,-0.146254f},{-0.0891051f,-0.149148f,-0.144944f},{-0.0843652f,-0.154737f,-0.14394f}, -{-0.0795995f,-0.160356f,-0.142695f},{-0.0748149f,-0.165998f,-0.141205f},{-0.0700188f,-0.171653f,-0.139464f}, -{-0.0652189f,-0.177313f,-0.137469f},{-0.0604233f,-0.182968f,-0.135216f},{-0.0512508f,-0.194371f,-0.129604f}, -{-0.0465253f,-0.199943f,-0.126571f},{-0.0461457f,-0.199803f,-0.12689f},{-0.0508781f,-0.194223f,-0.129928f}, -{-0.0414517f,-0.205338f,-0.123589f},{-0.0368051f,-0.210817f,-0.120026f},{-0.0322148f,-0.216229f,-0.116203f}, -{-0.0276899f,-0.221565f,-0.112124f},{-0.0232392f,-0.226813f,-0.10779f},{-0.0188713f,-0.231963f,-0.103209f}, -{-0.0104183f,-0.241931f,-0.0933231f},{-0.0063495f,-0.246728f,-0.0880336f},{-0.00239635f,-0.25139f,-0.0825239f}, -{0.0014338f,-0.255906f,-0.0768032f},{0.00513399f,-0.260269f,-0.0708815f},{0.0121191f,-0.268505f,-0.0584789f}, -{0.0153925f,-0.272365f,-0.0520214f},{0.0185132f,-0.276045f,-0.0454095f},{0.0214768f,-0.279539f,-0.0386562f}, -{0.0264323f,-0.28597f,-0.0246083f},{0.0289012f,-0.288881f,-0.017522f},{0.029391f,-0.288871f,-0.017682f}, -{0.0269185f,-0.285956f,-0.0247786f},{0.0316954f,-0.291588f,-0.0104982f},{0.0338304f,-0.294106f,-0.00324118f}, -{0.0357955f,-0.296423f,0.00407537f},{0.0375905f,-0.298539f,0.0114378f},{0.0392161f,-0.300456f,0.0188328f}, -{0.0419638f,-0.303696f,0.0336681f},{0.0425799f,-0.30501f,0.0411575f},{0.0435424f,-0.306145f,0.0485442f}, -{0.0440537f,-0.30616f,0.0484808f},{0.0430897f,-0.305024f,0.0410833f},{0.0448586f,-0.30711f,0.0558492f}, -{0.0463554f,-0.308875f,0.0776733f},{0.0467942f,-0.309247f,0.0918925f},{0.0471187f,-0.309415f,0.0918925f}, -{-0.0987838f,-0.138323f,-0.145907f},{-0.0894219f,-0.149362f,-0.144598f},{-0.084689f,-0.154943f,-0.143596f}, -{-0.0897359f,-0.149602f,-0.144431f},{-0.0799302f,-0.160554f,-0.142353f},{-0.0751526f,-0.166187f,-0.140865f}, -{-0.0703635f,-0.171834f,-0.139127f},{-0.0655707f,-0.177486f,-0.137134f},{-0.0607821f,-0.183132f,-0.134885f}, -{-0.056006f,-0.188764f,-0.132375f},{-0.0375491f,-0.211137f,-0.119568f},{-0.0421857f,-0.20567f,-0.123123f}, -{-0.0418382f,-0.20547f,-0.123274f},{-0.0371983f,-0.210941f,-0.119717f},{-0.0326147f,-0.216345f,-0.1159f}, -{-0.0280965f,-0.221673f,-0.111826f},{-0.0236522f,-0.226913f,-0.107499f},{-0.0112194f,-0.242183f,-0.0929223f}, -{-0.01085f,-0.242009f,-0.0930527f},{-0.015387f,-0.237269f,-0.0979722f},{-0.00678716f,-0.2468f,-0.087771f}, -{-0.00283979f,-0.251454f,-0.0822693f},{0.000984771f,-0.255964f,-0.0765569f},{0.0112692f,-0.2687f,-0.0581535f}, -{0.0145356f,-0.272552f,-0.0517099f},{0.0116545f,-0.268545f,-0.0582594f},{0.0149231f,-0.272399f,-0.0518113f}, -{0.0180392f,-0.276073f,-0.0452091f},{0.0209985f,-0.279563f,-0.0384656f},{0.0237972f,-0.282863f,-0.0315942f}, -{0.0308032f,-0.291734f,-0.0102766f},{0.0312022f,-0.291594f,-0.0103487f},{0.0285038f,-0.289022f,-0.0174448f}, -{0.0333341f,-0.294108f,-0.0031023f},{0.0352963f,-0.296422f,0.00420356f},{0.0370887f,-0.298535f,0.0115553f}, -{0.0387119f,-0.300449f,0.0189394f},{0.040167f,-0.302165f,0.026343f},{0.0414556f,-0.303684f,0.0337531f}, -{0.0443462f,-0.307093f,0.0559018f},{0.0454314f,-0.308982f,0.0777041f},{0.0450823f,-0.308571f,0.0705019f}, -{0.0458408f,-0.308855f,0.077694f},{-0.0850063f,-0.155178f,-0.143429f},{-0.0802509f,-0.160786f,-0.142188f}, -{-0.0754766f,-0.166415f,-0.140701f},{-0.0706909f,-0.172058f,-0.138964f},{-0.0659015f,-0.177706f,-0.136973f}, -{-0.0611162f,-0.183348f,-0.134725f},{-0.0563435f,-0.188976f,-0.132217f},{-0.0515917f,-0.194579f,-0.129448f}, -{-0.0468695f,-0.200147f,-0.126416f},{-0.0329688f,-0.216538f,-0.115753f},{-0.0284537f,-0.221862f,-0.111682f}, -{-0.0240126f,-0.227098f,-0.107358f},{-0.0196542f,-0.232238f,-0.102786f},{-0.00715942f,-0.246971f,-0.0876442f}, -{-0.00321483f,-0.251622f,-0.0821464f},{0.000607029f,-0.256128f,-0.0764381f},{0.00429921f,-0.260482f,-0.0705292f}, -{0.00785526f,-0.264675f,-0.0644306f},{0.0176495f,-0.276224f,-0.0451124f},{0.0206066f,-0.279711f,-0.0383737f}, -{0.0234034f,-0.283008f,-0.0315071f},{0.0260366f,-0.286113f,-0.0245261f},{0.0329336f,-0.294246f,-0.0030353f}, -{0.0348943f,-0.296558f,0.00426541f},{0.0366855f,-0.29867f,0.0116119f},{0.0383075f,-0.300582f,0.0189909f}, -{0.0397616f,-0.302297f,0.0263892f},{0.0410493f,-0.303815f,0.0337941f},{0.0421728f,-0.30514f,0.0411933f}, -{0.0431347f,-0.306274f,0.0485748f},{0.0439379f,-0.307221f,0.0559272f},{0.0445859f,-0.307985f,0.0632397f}, -{-0.0391526f,0.0783052f,0.0434179f},{-0.0388614f,0.0783204f,0.0340958f},{-0.0394464f,0.0783208f,0.0340958f}, -{-0.0400182f,0.0784426f,0.0340958f},{-0.0396981f,0.0783592f,0.0434179f},{-0.0402232f,0.0785175f,0.0434179f}, -{-0.041025f,0.0790247f,0.0340958f},{-0.0407075f,0.0787756f,0.0434179f},{-0.0405514f,0.0786801f,0.0340958f}, -{-0.0414158f,0.0794592f,0.0340958f},{-0.0411317f,0.0791238f,0.0434179f},{-0.0414795f,0.079548f,0.0434179f}, -{-0.0417077f,0.0799651f,0.0340958f},{-0.041888f,0.08052f,0.0340958f},{-0.0417379f,0.0800316f,0.0434179f}, -{-0.0419492f,0.0811018f,0.0434179f},{-0.0418971f,0.0805563f,0.0434179f},{-0.0386063f,0.0783596f,0.0434179f}, -{-0.0382892f,0.0784417f,0.0340958f},{-0.0380818f,0.0785201f,0.0434179f},{-0.037599f,0.0787792f,0.0434179f}, -{-0.0377553f,0.0786794f,0.0340958f},{-0.0371757f,0.0791268f,0.0434179f},{-0.0372831f,0.0790223f,0.0340958f}, -{-0.0368907f,0.0794572f,0.0340958f},{-0.0368282f,0.0795501f,0.0434179f},{-0.0365701f,0.0800331f,0.0434179f}, -{-0.036598f,0.0799637f,0.0340958f},{-0.0364108f,0.0805572f,0.0434179f},{-0.0364177f,0.0805185f,0.0340958f}, -{-0.036356f,0.0811018f,0.0434179f},{-0.0391526f,0.0811018f,0.0450982f},{-0.035689f,0.0842218f,0.0359602f}, -{-0.035116f,0.0834323f,0.0359602f},{-0.0353809f,0.08384f,0.0340958f},{-0.0391526f,0.0857628f,0.0359602f}, -{-0.0391526f,0.0857628f,0.0340958f},{-0.0398869f,0.0857044f,0.0340958f},{-0.0349993f,0.0832175f,0.0340958f}, -{-0.0347708f,0.0826925f,0.0359602f},{-0.0347209f,0.0825456f,0.0340958f},{-0.0345623f,0.0819115f,0.0359602f}, -{-0.03455f,0.0818361f,0.0340958f},{-0.0344918f,0.0811018f,0.0359602f},{-0.0344916f,0.0811018f,0.0340958f}, -{-0.0358568f,0.0843977f,0.0340958f},{-0.0364173f,0.0848756f,0.0340958f},{-0.0364146f,0.084874f,0.0359602f}, -{-0.0370399f,0.0852564f,0.0340958f},{-0.0372574f,0.0853604f,0.0359602f},{-0.0377117f,0.0855347f,0.0340958f}, -{-0.0381842f,0.0856612f,0.0359602f},{-0.0384218f,0.085705f,0.0340958f},{-0.0410494f,0.0853588f,0.0359602f}, -{-0.0401233f,0.0856603f,0.0359602f},{-0.0405964f,0.0855335f,0.0340958f},{-0.0424484f,0.0843977f,0.0340958f}, -{-0.0418918f,0.0848727f,0.0359602f},{-0.0418907f,0.0848735f,0.0340958f},{-0.0412683f,0.0852551f,0.0340958f}, -{-0.0435327f,0.0826912f,0.0359602f},{-0.0431892f,0.0834324f,0.0359602f},{-0.0433072f,0.0832145f,0.0340958f}, -{-0.0426166f,0.0842194f,0.0359602f},{-0.0429264f,0.0838371f,0.0340958f},{-0.0437552f,0.0818361f,0.0340958f}, -{-0.0437427f,0.0819107f,0.0359602f},{-0.0435855f,0.0825427f,0.0340958f},{-0.0438136f,0.0811018f,0.0340958f}, -{-0.0438134f,0.0811018f,0.0359602f},{-0.0391526f,0.0838984f,0.062062f},{-0.0388614f,0.0838832f,0.071384f}, -{-0.0394464f,0.0838828f,0.071384f},{-0.0400182f,0.083761f,0.071384f},{-0.0396981f,0.0838444f,0.062062f}, -{-0.0402232f,0.0836861f,0.062062f},{-0.041025f,0.0831789f,0.071384f},{-0.0407075f,0.083428f,0.062062f}, -{-0.0405514f,0.0835236f,0.071384f},{-0.0414158f,0.0827444f,0.071384f},{-0.0411317f,0.0830798f,0.062062f}, -{-0.0414795f,0.0826556f,0.062062f},{-0.0417077f,0.0822385f,0.071384f},{-0.041888f,0.0816837f,0.071384f}, -{-0.0417379f,0.082172f,0.062062f},{-0.0419492f,0.0811018f,0.071384f},{-0.0419492f,0.0811018f,0.062062f}, -{-0.0418971f,0.0816473f,0.062062f},{-0.0386063f,0.083844f,0.062062f},{-0.0382892f,0.0837619f,0.071384f}, -{-0.0380818f,0.0836835f,0.062062f},{-0.037599f,0.0834244f,0.062062f},{-0.0377553f,0.0835242f,0.071384f}, -{-0.0371757f,0.0830768f,0.062062f},{-0.0372831f,0.0831813f,0.071384f},{-0.0368907f,0.0827465f,0.071384f}, -{-0.0368282f,0.0826535f,0.062062f},{-0.0365701f,0.0821705f,0.062062f},{-0.036598f,0.0822399f,0.071384f}, -{-0.0364108f,0.0816464f,0.062062f},{-0.0364177f,0.0816851f,0.071384f},{-0.036356f,0.0811018f,0.071384f}, -{-0.036356f,0.0811018f,0.062062f},{-0.0391526f,0.0811018f,0.0603816f},{-0.035689f,0.0779818f,0.0695196f}, -{-0.035116f,0.0787713f,0.0695196f},{-0.0353809f,0.0783636f,0.071384f},{-0.0391526f,0.0764408f,0.0695196f}, -{-0.0391526f,0.0764408f,0.071384f},{-0.0398869f,0.0764992f,0.071384f},{-0.0349993f,0.0789861f,0.071384f}, -{-0.0347708f,0.0795111f,0.0695196f},{-0.0347209f,0.079658f,0.071384f},{-0.0345623f,0.0802921f,0.0695196f}, -{-0.03455f,0.0803675f,0.071384f},{-0.0344918f,0.0811018f,0.0695196f},{-0.0344916f,0.0811018f,0.071384f}, -{-0.0358568f,0.077806f,0.071384f},{-0.0364173f,0.077328f,0.071384f},{-0.0364146f,0.0773296f,0.0695196f}, -{-0.0370399f,0.0769472f,0.071384f},{-0.0372574f,0.0768432f,0.0695196f},{-0.0377117f,0.0766689f,0.071384f}, -{-0.0381842f,0.0765424f,0.0695196f},{-0.0384218f,0.0764986f,0.071384f},{-0.0410494f,0.0768448f,0.0695196f}, -{-0.0401233f,0.0765433f,0.0695196f},{-0.0405964f,0.0766702f,0.071384f},{-0.0424484f,0.077806f,0.071384f}, -{-0.0418918f,0.0773309f,0.0695196f},{-0.0418907f,0.0773301f,0.071384f},{-0.0412683f,0.0769485f,0.071384f}, -{-0.0435327f,0.0795124f,0.0695196f},{-0.0431892f,0.0787712f,0.0695196f},{-0.0433072f,0.0789891f,0.071384f}, -{-0.0426166f,0.0779842f,0.0695196f},{-0.0429264f,0.0783665f,0.071384f},{-0.0437552f,0.0803675f,0.071384f}, -{-0.0437427f,0.0802929f,0.0695196f},{-0.0435855f,0.079661f,0.071384f},{-0.0438136f,0.0811018f,0.071384f}, -{-0.0438134f,0.0811018f,0.0695196f},{-0.0337705f,0.0811018f,0.0359602f},{-0.0351159f,0.0834324f,0.0695196f}, -{-0.0364616f,0.0857628f,0.0359602f},{-0.0364616f,0.0857628f,0.0695196f},{-0.0337705f,0.0811018f,0.0695196f}, -{-0.0388588f,0.0838828f,0.0340958f},{-0.0394438f,0.0838832f,0.0340958f},{-0.0405499f,0.0835242f,0.0340958f}, -{-0.040016f,0.0837619f,0.0340958f},{-0.0345484f,0.0803724f,0.0340958f},{-0.0347196f,0.0796609f,0.0340958f}, -{-0.0365975f,0.0822385f,0.0340958f},{-0.0364172f,0.0816837f,0.0340958f},{-0.0368894f,0.0827444f,0.0340958f}, -{-0.0372802f,0.0831789f,0.0340958f},{-0.0377538f,0.0835236f,0.0340958f},{-0.038287f,0.083761f,0.0340958f}, -{-0.0358645f,0.0778104f,0.0340958f},{-0.0364144f,0.0773296f,0.0340958f},{-0.0377132f,0.0766684f,0.0340958f}, -{-0.0370378f,0.0769479f,0.0340958f},{-0.038424f,0.076498f,0.0340958f},{-0.0410221f,0.0831813f,0.0340958f}, -{-0.0414831f,0.0834323f,0.0340958f},{-0.0398819f,0.0764984f,0.0340958f},{-0.0391526f,0.0764408f,0.0340958f}, -{-0.0412686f,0.0769492f,0.0340958f},{-0.0418918f,0.0773311f,0.0340958f},{-0.0405931f,0.0766694f,0.0340958f}, -{-0.0417072f,0.0822399f,0.0340958f},{-0.0414145f,0.0827465f,0.0340958f},{-0.0424471f,0.0778077f,0.0340958f}, -{-0.0433038f,0.0789871f,0.0340958f},{-0.0435854f,0.0796621f,0.0340958f},{-0.0437559f,0.0803733f,0.0340958f}, -{-0.0418875f,0.0816851f,0.0340958f},{-0.042921f,0.0783646f,0.0340958f},{-0.0349967f,0.0789819f,0.0340958f}, -{-0.0353925f,0.07837f,0.0340958f},{-0.0445347f,0.0811018f,0.0359602f},{-0.0431893f,0.0787712f,0.0359602f}, -{-0.0418436f,0.0764408f,0.0359602f},{-0.0418436f,0.0764408f,0.0695196f},{-0.0445347f,0.0811018f,0.0695196f}, -{-0.0364616f,0.0764408f,0.0359602f},{-0.0351159f,0.0787712f,0.0359602f},{-0.0364616f,0.0764408f,0.0695196f}, -{-0.0391526f,0.0764412f,0.0359602f},{-0.0391526f,0.0857625f,0.0695196f},{-0.0418436f,0.0857628f,0.0359602f}, -{-0.0418436f,0.0857628f,0.0695196f},{-0.0364144f,0.084874f,0.071384f},{-0.0358645f,0.0843932f,0.071384f}, -{-0.0437559f,0.0818303f,0.071384f},{-0.0435854f,0.0825415f,0.071384f},{-0.0370378f,0.0852557f,0.071384f}, -{-0.0377132f,0.0855352f,0.071384f},{-0.038424f,0.0857056f,0.071384f},{-0.0391526f,0.0857628f,0.071384f}, -{-0.0405931f,0.0855343f,0.071384f},{-0.0412686f,0.0852544f,0.071384f},{-0.0398819f,0.0857052f,0.071384f}, -{-0.0418918f,0.0848725f,0.071384f},{-0.0353925f,0.0838337f,0.071384f},{-0.0345484f,0.0818312f,0.071384f}, -{-0.0424471f,0.0843959f,0.071384f},{-0.0364172f,0.08052f,0.071384f},{-0.0368221f,0.0787713f,0.071384f}, -{-0.0368894f,0.0794592f,0.071384f},{-0.040016f,0.0784417f,0.071384f},{-0.0394438f,0.0783204f,0.071384f}, -{-0.038287f,0.0784426f,0.071384f},{-0.0410221f,0.0790223f,0.071384f},{-0.0405499f,0.0786794f,0.071384f}, -{-0.0417072f,0.0799637f,0.071384f},{-0.0414145f,0.0794572f,0.071384f},{-0.0388588f,0.0783208f,0.071384f}, -{-0.0418875f,0.0805185f,0.071384f},{-0.0365975f,0.0799651f,0.071384f},{-0.0377538f,0.0786801f,0.071384f}, -{-0.0433038f,0.0832165f,0.071384f},{-0.0347196f,0.0825428f,0.071384f},{-0.0349967f,0.0832217f,0.071384f}, -{-0.042921f,0.083839f,0.071384f},{-0.0372802f,0.0790247f,0.071384f},{-0.0431893f,0.0834324f,0.0695196f}, -{-0.0345623f,0.081909f,0.0695196f},{-0.0356893f,0.0842209f,0.0695196f},{-0.0347719f,0.0826889f,0.0695196f}, -{-0.0381833f,0.0856608f,0.0695196f},{-0.0364121f,0.0848714f,0.0695196f},{-0.0372548f,0.0853584f,0.0695196f}, -{-0.041893f,0.0848726f,0.0695196f},{-0.041049f,0.08536f,0.0695196f},{-0.0401215f,0.0856611f,0.0695196f}, -{-0.0426157f,0.0842217f,0.0695196f},{-0.0435351f,0.0826902f,0.0695196f},{-0.0437434f,0.0819096f,0.0695196f}, -{-0.0417086f,0.0799637f,0.062062f},{-0.041416f,0.0794571f,0.062062f},{-0.0418896f,0.08052f,0.062062f}, -{-0.0410244f,0.0790222f,0.062062f},{-0.0405506f,0.0786785f,0.062062f},{-0.0400156f,0.0784417f,0.062062f}, -{-0.0394436f,0.0783205f,0.062062f},{-0.0388585f,0.078321f,0.062062f},{-0.0377533f,0.078683f,0.062062f}, -{-0.0382866f,0.0784441f,0.062062f},{-0.0368906f,0.0794606f,0.062062f},{-0.0372812f,0.0790267f,0.062062f}, -{-0.0364182f,0.0805216f,0.062062f},{-0.0365988f,0.0799663f,0.062062f},{-0.0345623f,0.0802946f,0.0359602f}, -{-0.035689f,0.077983f,0.0359602f},{-0.0347719f,0.0795147f,0.0359602f},{-0.0381819f,0.0765431f,0.0359602f}, -{-0.0364115f,0.0773327f,0.0359602f},{-0.0372538f,0.0768457f,0.0359602f},{-0.0418924f,0.0773306f,0.0359602f}, -{-0.041048f,0.0768432f,0.0359602f},{-0.0401201f,0.0765423f,0.0359602f},{-0.0426154f,0.0779817f,0.0359602f}, -{-0.0435351f,0.0795134f,0.0359602f},{-0.0437434f,0.080294f,0.0359602f},{-0.0417086f,0.0822399f,0.0434179f}, -{-0.041416f,0.0827465f,0.0434179f},{-0.0418896f,0.0816836f,0.0434179f},{-0.0410244f,0.0831814f,0.0434179f}, -{-0.0405506f,0.0835251f,0.0434179f},{-0.0400156f,0.0837619f,0.0434179f},{-0.0394436f,0.0838831f,0.0434179f}, -{-0.0388585f,0.0838826f,0.0434179f},{-0.0377533f,0.0835206f,0.0434179f},{-0.0382866f,0.0837595f,0.0434179f}, -{-0.0368906f,0.082743f,0.0434179f},{-0.0372812f,0.0831769f,0.0434179f},{-0.0364182f,0.081682f,0.0434179f}, -{-0.0365988f,0.0822373f,0.0434179f},{0.0389901f,-0.0783099f,0.0434179f},{0.0387003f,-0.0783421f,0.0340958f}, -{0.0392843f,-0.0783085f,0.0340958f},{0.0398623f,-0.0783968f,0.0340958f},{0.0395378f,-0.0783322f,0.0434179f}, -{0.0400712f,-0.0784597f,0.0434179f},{0.0409011f,-0.0789195f,0.0340958f},{0.0405697f,-0.0786892f,0.0434179f}, -{0.0404083f,-0.0786029f,0.0340958f},{0.0413165f,-0.0793305f,0.0340958f},{0.0410134f,-0.0790122f,0.0434179f}, -{0.0413853f,-0.0794154f,0.0434179f},{0.0416374f,-0.0798186f,0.0340958f},{0.0418496f,-0.080362f,0.0340958f}, -{0.0416714f,-0.0798832f,0.0434179f},{0.0419445f,-0.0809393f,0.0340958f},{0.0419445f,-0.0809393f,0.0434179f}, -{0.0418608f,-0.0803977f,0.0434179f},{0.0384479f,-0.078396f,0.0434179f},{0.0381361f,-0.0784964f,0.0340958f}, -{0.0379336f,-0.0785867f,0.0434179f},{0.0374667f,-0.0788734f,0.0434179f},{0.0376169f,-0.0787647f,0.0340958f}, -{0.0370643f,-0.0792449f,0.0434179f},{0.0371654f,-0.0791345f,0.0340958f},{0.036799f,-0.0795913f,0.0340958f}, -{0.036742f,-0.0796878f,0.0434179f},{0.0365123f,-0.080185f,0.0434179f},{0.0365362f,-0.080114f,0.0340958f}, -{0.0363838f,-0.0807174f,0.0434179f},{0.0363884f,-0.0806783f,0.0340958f},{0.0363607f,-0.0812643f,0.0340958f}, -{0.0363607f,-0.0812643f,0.0434179f},{0.0391526f,-0.0811018f,0.0450982f},{0.0358762f,-0.0844178f,0.0359602f}, -{0.0352583f,-0.0836629f,0.0359602f},{0.0355463f,-0.0840545f,0.0340958f},{0.0394234f,-0.085755f,0.0359602f}, -{0.0394234f,-0.085755f,0.0340958f},{0.0401531f,-0.085654f,0.0340958f},{0.0351292f,-0.0834552f,0.0340958f}, -{0.0348706f,-0.0829444f,0.0359602f},{0.0348123f,-0.0828006f,0.0340958f},{0.0346171f,-0.0821768f,0.0359602f}, -{0.0346004f,-0.0821023f,0.0340958f},{0.0344997f,-0.0813726f,0.0359602f},{0.0344994f,-0.0813726f,0.0340958f}, -{0.0360538f,-0.0845836f,0.0340958f},{0.0366412f,-0.0850281f,0.0340958f},{0.0366384f,-0.0850267f,0.0359602f}, -{0.0372848f,-0.0853721f,0.0340958f},{0.037508f,-0.0854633f,0.0359602f},{0.0379717f,-0.0856109f,0.0340958f}, -{0.0384507f,-0.0857098f,0.0359602f},{0.0386904f,-0.0857397f,0.0340958f},{0.0412936f,-0.0852414f,0.0359602f}, -{0.0403865f,-0.0855962f,0.0359602f},{0.0408514f,-0.0854421f,0.0340958f},{0.0426344f,-0.0842006f,0.0340958f}, -{0.0421063f,-0.0847072f,0.0359602f},{0.0421053f,-0.0847081f,0.0340958f},{0.041506f,-0.0851252f,0.0340958f}, -{0.0436176f,-0.082434f,0.0359602f},{0.0433178f,-0.0831939f,0.0359602f},{0.0434229f,-0.0829696f,0.0340958f}, -{0.0427919f,-0.0840129f,0.0359602f},{0.0430789f,-0.0836132f,0.0340958f},{0.0437901f,-0.0815675f,0.0340958f}, -{0.0437819f,-0.0816426f,0.0359602f},{0.0436617f,-0.0822827f,0.0340958f},{0.0438057f,-0.080831f,0.0340958f}, -{0.0438055f,-0.080831f,0.0359602f},{0.0393151f,-0.0838937f,0.062062f},{0.0390235f,-0.0838954f,0.071384f}, -{0.0396075f,-0.083861f,0.071384f},{0.0401713f,-0.0837062f,0.071384f},{0.0398565f,-0.0838081f,0.062062f}, -{0.0403715f,-0.0836196f,0.062062f},{0.0411425f,-0.0830666f,0.071384f},{0.04084f,-0.0833337f,0.062062f}, -{0.0406897f,-0.0834382f,0.071384f},{0.0415074f,-0.0826102f,0.071384f},{0.0412433f,-0.0829615f,0.062062f}, -{0.0415658f,-0.0825178f,0.062062f},{0.0417695f,-0.0820881f,0.071384f},{0.0419172f,-0.0815237f,0.071384f}, -{0.0417958f,-0.08202f,0.062062f},{0.0419445f,-0.0809393f,0.071384f},{0.0419445f,-0.0809393f,0.062062f}, -{0.0419241f,-0.081487f,0.062062f},{0.0387666f,-0.0838711f,0.062062f},{0.0384452f,-0.0838076f,0.071384f}, -{0.0382336f,-0.0837413f,0.062062f},{0.0377365f,-0.0835108f,0.062062f},{0.0378984f,-0.0836013f,0.071384f}, -{0.0372938f,-0.0831884f,0.062062f},{0.0374071f,-0.0832864f,0.071384f},{0.0369901f,-0.0828751f,0.071384f}, -{0.0369223f,-0.0827859f,0.062062f},{0.0366365f,-0.0823187f,0.062062f},{0.0366685f,-0.0823864f,0.071384f}, -{0.0364471f,-0.0818048f,0.062062f},{0.0364562f,-0.0818431f,0.071384f},{0.0363607f,-0.0812643f,0.071384f}, -{0.0363607f,-0.0812643f,0.062062f},{0.0391526f,-0.0811018f,0.0603816f},{0.0355136f,-0.0781883f,0.0695196f}, -{0.0349875f,-0.0790097f,0.0695196f},{0.0352282f,-0.0785874f,0.071384f},{0.0388818f,-0.0764487f,0.0695196f}, -{0.0388818f,-0.0764487f,0.071384f},{0.0396183f,-0.0764643f,0.071384f},{0.0348834f,-0.079231f,0.071384f}, -{0.0346858f,-0.0797684f,0.0695196f},{0.0346446f,-0.0799179f,0.071384f},{0.034523f,-0.0805601f,0.0695196f}, -{0.0345151f,-0.0806361f,0.071384f},{0.0344996f,-0.0813726f,0.0695196f},{0.0344994f,-0.0813726f,0.071384f}, -{0.0356708f,-0.078003f,0.071384f},{0.0362027f,-0.0774933f,0.071384f},{0.0362001f,-0.0774951f,0.0695196f}, -{0.0368021f,-0.077077f,0.071384f},{0.0370131f,-0.0769605f,0.0695196f},{0.0374566f,-0.0767601f,0.071384f}, -{0.0379209f,-0.0766064f,0.0695196f},{0.0381555f,-0.0765489f,0.071384f},{0.0407989f,-0.0767418f,0.0695196f}, -{0.0398569f,-0.0764946f,0.0695196f},{0.0403365f,-0.0765938f,0.071384f},{0.0422514f,-0.07762f,0.071384f}, -{0.0416681f,-0.0771781f,0.0695196f},{0.041667f,-0.0771774f,0.071384f},{0.0410234f,-0.0768326f,0.071384f}, -{0.0434329f,-0.0792607f,0.0695196f},{0.043047f,-0.0785407f,0.0695196f},{0.0431774f,-0.0787513f,0.071384f}, -{0.0424296f,-0.0777882f,0.0695196f},{0.0427611f,-0.0781519f,0.071384f},{0.0437048f,-0.0801013f,0.071384f}, -{0.0436879f,-0.0800276f,0.0695196f},{0.0434943f,-0.0794058f,0.071384f},{0.0438057f,-0.080831f,0.071384f}, -{0.0438056f,-0.080831f,0.0695196f},{0.0337796f,-0.0814145f,0.0359602f},{0.0352581f,-0.083663f,0.0695196f}, -{0.0367369f,-0.0859113f,0.0359602f},{0.0367369f,-0.0859113f,0.0695196f},{0.0337796f,-0.0814145f,0.0695196f}, -{0.0390208f,-0.0838951f,0.0340958f},{0.0396049f,-0.0838616f,0.0340958f},{0.0406883f,-0.0834389f,0.0340958f}, -{0.0401691f,-0.0837073f,0.0340958f},{0.0345138f,-0.0806411f,0.0340958f},{0.0346434f,-0.0799208f,0.0340958f}, -{0.0366678f,-0.082385f,0.0340958f},{0.0364556f,-0.0818416f,0.0340958f},{0.0369886f,-0.0828732f,0.0340958f}, -{0.037404f,-0.0832841f,0.0340958f},{0.0378969f,-0.0836007f,0.0340958f},{0.0384429f,-0.0838068f,0.0340958f}, -{0.0356789f,-0.078007f,0.0340958f},{0.0361998f,-0.0774951f,0.0340958f},{0.0374581f,-0.0767596f,0.0340958f}, -{0.0368f,-0.0770778f,0.0340958f},{0.0381577f,-0.0765482f,0.0340958f},{0.0411398f,-0.0830691f,0.0340958f}, -{0.0416146f,-0.083293f,0.0340958f},{0.0396132f,-0.0764638f,0.0340958f},{0.0388818f,-0.0764487f,0.0340958f}, -{0.0410238f,-0.0768332f,0.0340958f},{0.0416681f,-0.0771784f,0.0340958f},{0.0403331f,-0.0765932f,0.0340958f}, -{0.041769f,-0.0820896f,0.0340958f},{0.0415062f,-0.0826123f,0.0340958f},{0.0422501f,-0.0776219f,0.0340958f}, -{0.043174f,-0.0787495f,0.0340958f},{0.0434943f,-0.079407f,0.0340958f},{0.0437058f,-0.0801071f,0.0340958f}, -{0.0419168f,-0.0815253f,0.0340958f},{0.0427556f,-0.0781503f,0.0340958f},{0.0348806f,-0.0792269f,0.0340958f}, -{0.0352401f,-0.078593f,0.0340958f},{0.0445256f,-0.0807891f,0.0359602f},{0.0430471f,-0.0785406f,0.0359602f}, -{0.0415683f,-0.0762923f,0.0359602f},{0.0415683f,-0.0762923f,0.0695196f},{0.0445256f,-0.0807891f,0.0695196f}, -{0.0361953f,-0.076605f,0.0359602f},{0.0349873f,-0.0790097f,0.0359602f},{0.0361953f,-0.076605f,0.0695196f}, -{0.0388818f,-0.0764491f,0.0359602f},{0.0394234f,-0.0857546f,0.0695196f},{0.0421099f,-0.0855986f,0.0359602f}, -{0.0421099f,-0.0855986f,0.0695196f},{0.0366381f,-0.0850267f,0.071384f},{0.0360613f,-0.0845787f,0.071384f}, -{0.0437905f,-0.0815617f,0.071384f},{0.0436616f,-0.0822815f,0.071384f},{0.0372827f,-0.0853716f,0.071384f}, -{0.0379732f,-0.0856113f,0.071384f},{0.0386927f,-0.0857401f,0.071384f},{0.0394234f,-0.085755f,0.071384f}, -{0.0408481f,-0.0854431f,0.071384f},{0.0415063f,-0.0851245f,0.071384f},{0.0401481f,-0.0856551f,0.071384f}, -{0.0421062f,-0.084707f,0.071384f},{0.0355575f,-0.0840475f,0.071384f},{0.0345985f,-0.0820975f,0.071384f}, -{0.0426329f,-0.0841989f,0.071384f},{0.036388f,-0.0806799f,0.071384f},{0.0366906f,-0.0789106f,0.071384f}, -{0.0367978f,-0.0795934f,0.071384f},{0.03986f,-0.078396f,0.071384f},{0.0392817f,-0.0783082f,0.071384f}, -{0.0381339f,-0.0784974f,0.071384f},{0.0408981f,-0.0789173f,0.071384f},{0.0404068f,-0.0786023f,0.071384f}, -{0.0416367f,-0.0798172f,0.071384f},{0.0413151f,-0.0793285f,0.071384f},{0.0386977f,-0.0783426f,0.071384f}, -{0.041849f,-0.0803606f,0.071384f},{0.0365357f,-0.0801155f,0.071384f},{0.0376155f,-0.0787654f,0.071384f}, -{0.0434197f,-0.0829717f,0.071384f},{0.0348108f,-0.0827979f,0.071384f},{0.0351269f,-0.0834596f,0.071384f}, -{0.0430736f,-0.0836154f,0.071384f},{0.0371627f,-0.079137f,0.071384f},{0.0433179f,-0.0831939f,0.0695196f}, -{0.034617f,-0.0821743f,0.0695196f},{0.0358763f,-0.0844168f,0.0695196f},{0.0348715f,-0.0829407f,0.0695196f}, -{0.0384498f,-0.0857094f,0.0695196f},{0.0366357f,-0.0850242f,0.0695196f},{0.0375053f,-0.0854614f,0.0695196f}, -{0.0421074f,-0.084707f,0.0695196f},{0.0412932f,-0.0852426f,0.0695196f},{0.0403848f,-0.0855971f,0.0695196f}, -{0.0427911f,-0.0840152f,0.0695196f},{0.0436199f,-0.0824329f,0.0695196f},{0.0437826f,-0.0816416f,0.0695196f}, -{0.0416382f,-0.0798171f,0.062062f},{0.0413167f,-0.0793284f,0.062062f},{0.0418511f,-0.080362f,0.062062f}, -{0.0409005f,-0.0789169f,0.062062f},{0.0404074f,-0.0786014f,0.062062f},{0.0398596f,-0.078396f,0.062062f}, -{0.0392815f,-0.0783083f,0.062062f},{0.0386975f,-0.0783428f,0.062062f},{0.0376151f,-0.0787684f,0.062062f}, -{0.0381337f,-0.0784989f,0.062062f},{0.036799f,-0.0795948f,0.062062f},{0.0371638f,-0.0791389f,0.062062f}, -{0.0363891f,-0.0806814f,0.062062f},{0.0365371f,-0.0801166f,0.062062f},{0.0345232f,-0.0805627f,0.0359602f}, -{0.0355137f,-0.0781895f,0.0359602f},{0.0346871f,-0.0797719f,0.0359602f},{0.0379187f,-0.0766072f,0.0359602f}, -{0.0361971f,-0.0774983f,0.0359602f},{0.0370098f,-0.0769632f,0.0359602f},{0.0416687f,-0.0771778f,0.0359602f}, -{0.0407974f,-0.0767403f,0.0359602f},{0.0398536f,-0.0764937f,0.0359602f},{0.0424283f,-0.0777858f,0.0359602f}, -{0.0434354f,-0.0792615f,0.0359602f},{0.0436887f,-0.0800286f,0.0359602f},{0.0417704f,-0.0820895f,0.0434179f}, -{0.0415078f,-0.0826122f,0.0434179f},{0.0419187f,-0.0815236f,0.0434179f},{0.0411421f,-0.0830692f,0.0434179f}, -{0.040689f,-0.0834398f,0.0434179f},{0.0401687f,-0.0837073f,0.0434179f},{0.0396047f,-0.0838615f,0.0434179f}, -{0.0390206f,-0.083895f,0.0434179f},{0.0378962f,-0.0835978f,0.0434179f},{0.0384425f,-0.0838053f,0.0434179f}, -{0.0369897f,-0.0828716f,0.0434179f},{0.0374049f,-0.0832822f,0.0434179f},{0.0364565f,-0.0818399f,0.0434179f}, -{0.036669f,-0.0823837f,0.0434179f},{-0.0391526f,-0.0783052f,0.0434179f},{-0.0394438f,-0.0783204f,0.0340958f}, -{-0.0388588f,-0.0783208f,0.0340958f},{-0.038287f,-0.0784426f,0.0340958f},{-0.0386071f,-0.0783592f,0.0434179f}, -{-0.038082f,-0.0785175f,0.0434179f},{-0.0372802f,-0.0790247f,0.0340958f},{-0.0375977f,-0.0787756f,0.0434179f}, -{-0.0377538f,-0.0786801f,0.0340958f},{-0.0368894f,-0.0794592f,0.0340958f},{-0.0371735f,-0.0791238f,0.0434179f}, -{-0.0368257f,-0.079548f,0.0434179f},{-0.0365975f,-0.0799651f,0.0340958f},{-0.0364172f,-0.08052f,0.0340958f}, -{-0.0365672f,-0.0800316f,0.0434179f},{-0.036356f,-0.0811018f,0.0434179f},{-0.0364081f,-0.0805563f,0.0434179f}, -{-0.0396989f,-0.0783596f,0.0434179f},{-0.040016f,-0.0784417f,0.0340958f},{-0.0402234f,-0.0785201f,0.0434179f}, -{-0.0407062f,-0.0787792f,0.0434179f},{-0.0405499f,-0.0786794f,0.0340958f},{-0.0411295f,-0.0791268f,0.0434179f}, -{-0.0410221f,-0.0790223f,0.0340958f},{-0.0414145f,-0.0794572f,0.0340958f},{-0.041477f,-0.0795501f,0.0434179f}, -{-0.0417351f,-0.0800331f,0.0434179f},{-0.0417072f,-0.0799637f,0.0340958f},{-0.0418944f,-0.0805572f,0.0434179f}, -{-0.0418875f,-0.0805185f,0.0340958f},{-0.0419492f,-0.0811018f,0.0434179f},{-0.0391526f,-0.0811018f,0.0450982f}, -{-0.0426161f,-0.0842218f,0.0359602f},{-0.0431891f,-0.0834323f,0.0359602f},{-0.0429243f,-0.08384f,0.0340958f}, -{-0.0391526f,-0.0857628f,0.0359602f},{-0.0391526f,-0.0857628f,0.0340958f},{-0.0384183f,-0.0857044f,0.0340958f}, -{-0.0433059f,-0.0832175f,0.0340958f},{-0.0435344f,-0.0826925f,0.0359602f},{-0.0435842f,-0.0825456f,0.0340958f}, -{-0.0437429f,-0.0819115f,0.0359602f},{-0.0437552f,-0.0818361f,0.0340958f},{-0.0438134f,-0.0811018f,0.0359602f}, -{-0.0438136f,-0.0811018f,0.0340958f},{-0.0424484f,-0.0843976f,0.0340958f},{-0.0418879f,-0.0848756f,0.0340958f}, -{-0.0418906f,-0.084874f,0.0359602f},{-0.0412653f,-0.0852564f,0.0340958f},{-0.0410478f,-0.0853604f,0.0359602f}, -{-0.0405934f,-0.0855347f,0.0340958f},{-0.040121f,-0.0856612f,0.0359602f},{-0.0398834f,-0.085705f,0.0340958f}, -{-0.0372558f,-0.0853588f,0.0359602f},{-0.0381819f,-0.0856603f,0.0359602f},{-0.0377088f,-0.0855335f,0.0340958f}, -{-0.0358568f,-0.0843976f,0.0340958f},{-0.0364134f,-0.0848727f,0.0359602f},{-0.0364144f,-0.0848735f,0.0340958f}, -{-0.0370369f,-0.0852551f,0.0340958f},{-0.0347725f,-0.0826912f,0.0359602f},{-0.0351159f,-0.0834324f,0.0359602f}, -{-0.034998f,-0.0832145f,0.0340958f},{-0.0356886f,-0.0842194f,0.0359602f},{-0.0353788f,-0.0838371f,0.0340958f}, -{-0.03455f,-0.0818361f,0.0340958f},{-0.0345625f,-0.0819107f,0.0359602f},{-0.0347197f,-0.0825427f,0.0340958f}, -{-0.0344916f,-0.0811018f,0.0340958f},{-0.0344918f,-0.0811018f,0.0359602f},{-0.0391526f,-0.0838984f,0.062062f}, -{-0.0394438f,-0.0838832f,0.071384f},{-0.0388588f,-0.0838828f,0.071384f},{-0.038287f,-0.083761f,0.071384f}, -{-0.0386071f,-0.0838444f,0.062062f},{-0.038082f,-0.0836861f,0.062062f},{-0.0372802f,-0.0831789f,0.071384f}, -{-0.0375977f,-0.083428f,0.062062f},{-0.0377538f,-0.0835236f,0.071384f},{-0.0368894f,-0.0827444f,0.071384f}, -{-0.0371735f,-0.0830798f,0.062062f},{-0.0368257f,-0.0826556f,0.062062f},{-0.0365975f,-0.0822385f,0.071384f}, -{-0.0364172f,-0.0816837f,0.071384f},{-0.0365672f,-0.082172f,0.062062f},{-0.036356f,-0.0811018f,0.071384f}, -{-0.036356f,-0.0811018f,0.062062f},{-0.0364081f,-0.0816473f,0.062062f},{-0.0396989f,-0.083844f,0.062062f}, -{-0.040016f,-0.0837619f,0.071384f},{-0.0402234f,-0.0836835f,0.062062f},{-0.0407062f,-0.0834244f,0.062062f}, -{-0.0405499f,-0.0835242f,0.071384f},{-0.0411295f,-0.0830768f,0.062062f},{-0.0410221f,-0.0831813f,0.071384f}, -{-0.0414145f,-0.0827465f,0.071384f},{-0.041477f,-0.0826535f,0.062062f},{-0.0417351f,-0.0821705f,0.062062f}, -{-0.0417072f,-0.0822399f,0.071384f},{-0.0418944f,-0.0816464f,0.062062f},{-0.0418875f,-0.0816851f,0.071384f}, -{-0.0419492f,-0.0811018f,0.071384f},{-0.0419492f,-0.0811018f,0.062062f},{-0.0391526f,-0.0811018f,0.0603816f}, -{-0.0426161f,-0.0779818f,0.0695196f},{-0.0431891f,-0.0787713f,0.0695196f},{-0.0429243f,-0.0783636f,0.071384f}, -{-0.0391526f,-0.0764408f,0.0695196f},{-0.0391526f,-0.0764408f,0.071384f},{-0.0384183f,-0.0764992f,0.071384f}, -{-0.0433059f,-0.0789861f,0.071384f},{-0.0435344f,-0.0795111f,0.0695196f},{-0.0435842f,-0.079658f,0.071384f}, -{-0.0437429f,-0.0802921f,0.0695196f},{-0.0437552f,-0.0803675f,0.071384f},{-0.0438134f,-0.0811018f,0.0695196f}, -{-0.0438136f,-0.0811018f,0.071384f},{-0.0424484f,-0.077806f,0.071384f},{-0.0418879f,-0.077328f,0.071384f}, -{-0.0418906f,-0.0773296f,0.0695196f},{-0.0412653f,-0.0769472f,0.071384f},{-0.0410478f,-0.0768432f,0.0695196f}, -{-0.0405934f,-0.0766689f,0.071384f},{-0.040121f,-0.0765424f,0.0695196f},{-0.0398834f,-0.0764986f,0.071384f}, -{-0.0372558f,-0.0768448f,0.0695196f},{-0.0381819f,-0.0765433f,0.0695196f},{-0.0377088f,-0.0766702f,0.071384f}, -{-0.0358568f,-0.077806f,0.071384f},{-0.0364134f,-0.0773309f,0.0695196f},{-0.0364144f,-0.0773301f,0.071384f}, -{-0.0370369f,-0.0769485f,0.071384f},{-0.0347725f,-0.0795124f,0.0695196f},{-0.0351159f,-0.0787712f,0.0695196f}, -{-0.034998f,-0.0789891f,0.071384f},{-0.0356886f,-0.0779842f,0.0695196f},{-0.0353788f,-0.0783665f,0.071384f}, -{-0.03455f,-0.0803675f,0.071384f},{-0.0345625f,-0.0802929f,0.0695196f},{-0.0347197f,-0.079661f,0.071384f}, -{-0.0344916f,-0.0811018f,0.071384f},{-0.0344918f,-0.0811018f,0.0695196f},{-0.0445347f,-0.0811018f,0.0359602f}, -{-0.0431893f,-0.0834324f,0.0695196f},{-0.0418436f,-0.0857628f,0.0359602f},{-0.0418436f,-0.0857628f,0.0695196f}, -{-0.0445347f,-0.0811018f,0.0695196f},{-0.0394464f,-0.0838828f,0.0340958f},{-0.0388614f,-0.0838832f,0.0340958f}, -{-0.0377553f,-0.0835242f,0.0340958f},{-0.0382892f,-0.0837619f,0.0340958f},{-0.0437568f,-0.0803724f,0.0340958f}, -{-0.0435856f,-0.0796609f,0.0340958f},{-0.0417077f,-0.0822385f,0.0340958f},{-0.041888f,-0.0816837f,0.0340958f}, -{-0.0414158f,-0.0827444f,0.0340958f},{-0.041025f,-0.0831789f,0.0340958f},{-0.0405514f,-0.0835236f,0.0340958f}, -{-0.0400182f,-0.083761f,0.0340958f},{-0.0424407f,-0.0778104f,0.0340958f},{-0.0418908f,-0.0773296f,0.0340958f}, -{-0.040592f,-0.0766684f,0.0340958f},{-0.0412674f,-0.0769479f,0.0340958f},{-0.0398812f,-0.076498f,0.0340958f}, -{-0.0372831f,-0.0831813f,0.0340958f},{-0.0368221f,-0.0834323f,0.0340958f},{-0.0384233f,-0.0764984f,0.0340958f}, -{-0.0391526f,-0.0764408f,0.0340958f},{-0.0370366f,-0.0769492f,0.0340958f},{-0.0364134f,-0.0773311f,0.0340958f}, -{-0.0377121f,-0.0766694f,0.0340958f},{-0.036598f,-0.0822399f,0.0340958f},{-0.0368907f,-0.0827465f,0.0340958f}, -{-0.0358581f,-0.0778077f,0.0340958f},{-0.0350014f,-0.0789871f,0.0340958f},{-0.0347198f,-0.0796621f,0.0340958f}, -{-0.0345493f,-0.0803733f,0.0340958f},{-0.0364177f,-0.0816851f,0.0340958f},{-0.0353842f,-0.0783646f,0.0340958f}, -{-0.0433085f,-0.0789819f,0.0340958f},{-0.0429127f,-0.07837f,0.0340958f},{-0.0337705f,-0.0811018f,0.0359602f}, -{-0.0351159f,-0.0787712f,0.0359602f},{-0.0364616f,-0.0764408f,0.0359602f},{-0.0364616f,-0.0764408f,0.0695196f}, -{-0.0337705f,-0.0811018f,0.0695196f},{-0.0418436f,-0.0764408f,0.0359602f},{-0.0431893f,-0.0787712f,0.0359602f}, -{-0.0418436f,-0.0764408f,0.0695196f},{-0.0391526f,-0.0764412f,0.0359602f},{-0.0391526f,-0.0857625f,0.0695196f}, -{-0.0364616f,-0.0857628f,0.0359602f},{-0.0364616f,-0.0857628f,0.0695196f},{-0.0418908f,-0.084874f,0.071384f}, -{-0.0424407f,-0.0843932f,0.071384f},{-0.0345493f,-0.0818303f,0.071384f},{-0.0347198f,-0.0825415f,0.071384f}, -{-0.0412674f,-0.0852557f,0.071384f},{-0.040592f,-0.0855352f,0.071384f},{-0.0398812f,-0.0857056f,0.071384f}, -{-0.0391526f,-0.0857628f,0.071384f},{-0.0377121f,-0.0855343f,0.071384f},{-0.0370366f,-0.0852544f,0.071384f}, -{-0.0384233f,-0.0857052f,0.071384f},{-0.0364134f,-0.0848725f,0.071384f},{-0.0429127f,-0.0838337f,0.071384f}, -{-0.0437568f,-0.0818312f,0.071384f},{-0.0358581f,-0.0843959f,0.071384f},{-0.041888f,-0.08052f,0.071384f}, -{-0.0414831f,-0.0787713f,0.071384f},{-0.0414158f,-0.0794592f,0.071384f},{-0.0382892f,-0.0784417f,0.071384f}, -{-0.0388614f,-0.0783204f,0.071384f},{-0.0400182f,-0.0784426f,0.071384f},{-0.0372831f,-0.0790223f,0.071384f}, -{-0.0377553f,-0.0786794f,0.071384f},{-0.036598f,-0.0799637f,0.071384f},{-0.0368907f,-0.0794572f,0.071384f}, -{-0.0394464f,-0.0783208f,0.071384f},{-0.0364177f,-0.0805185f,0.071384f},{-0.0417077f,-0.0799651f,0.071384f}, -{-0.0405514f,-0.0786801f,0.071384f},{-0.0350014f,-0.0832165f,0.071384f},{-0.0435856f,-0.0825428f,0.071384f}, -{-0.0433085f,-0.0832217f,0.071384f},{-0.0353842f,-0.083839f,0.071384f},{-0.041025f,-0.0790247f,0.071384f}, -{-0.0351159f,-0.0834324f,0.0695196f},{-0.0437429f,-0.081909f,0.0695196f},{-0.0426159f,-0.0842209f,0.0695196f}, -{-0.0435333f,-0.0826889f,0.0695196f},{-0.0401218f,-0.0856608f,0.0695196f},{-0.0418931f,-0.0848714f,0.0695196f}, -{-0.0410504f,-0.0853584f,0.0695196f},{-0.0364122f,-0.0848726f,0.0695196f},{-0.0372562f,-0.08536f,0.0695196f}, -{-0.0381837f,-0.0856611f,0.0695196f},{-0.0356895f,-0.0842217f,0.0695196f},{-0.0347701f,-0.0826902f,0.0695196f}, -{-0.0345618f,-0.0819096f,0.0695196f},{-0.0365965f,-0.0799637f,0.062062f},{-0.0368892f,-0.0794571f,0.062062f}, -{-0.0364156f,-0.08052f,0.062062f},{-0.0372807f,-0.0790222f,0.062062f},{-0.0377546f,-0.0786785f,0.062062f}, -{-0.0382896f,-0.0784417f,0.062062f},{-0.0388616f,-0.0783205f,0.062062f},{-0.0394467f,-0.078321f,0.062062f}, -{-0.0405519f,-0.078683f,0.062062f},{-0.0400186f,-0.0784441f,0.062062f},{-0.0414146f,-0.0794606f,0.062062f}, -{-0.041024f,-0.0790267f,0.062062f},{-0.041887f,-0.0805216f,0.062062f},{-0.0417064f,-0.0799663f,0.062062f}, -{-0.0437429f,-0.0802946f,0.0359602f},{-0.0426161f,-0.077983f,0.0359602f},{-0.0435333f,-0.0795147f,0.0359602f}, -{-0.0401233f,-0.0765431f,0.0359602f},{-0.0418937f,-0.0773327f,0.0359602f},{-0.0410514f,-0.0768457f,0.0359602f}, -{-0.0364128f,-0.0773306f,0.0359602f},{-0.0372572f,-0.0768432f,0.0359602f},{-0.0381851f,-0.0765422f,0.0359602f}, -{-0.0356898f,-0.0779817f,0.0359602f},{-0.0347701f,-0.0795134f,0.0359602f},{-0.0345618f,-0.080294f,0.0359602f}, -{-0.0365965f,-0.0822399f,0.0434179f},{-0.0368892f,-0.0827465f,0.0434179f},{-0.0364156f,-0.0816836f,0.0434179f}, -{-0.0372807f,-0.0831814f,0.0434179f},{-0.0377546f,-0.0835251f,0.0434179f},{-0.0382896f,-0.0837619f,0.0434179f}, -{-0.0388616f,-0.0838831f,0.0434179f},{-0.0394467f,-0.0838826f,0.0434179f},{-0.0405519f,-0.0835206f,0.0434179f}, -{-0.0400186f,-0.0837595f,0.0434179f},{-0.0414146f,-0.082743f,0.0434179f},{-0.041024f,-0.0831769f,0.0434179f}, -{-0.041887f,-0.081682f,0.0434179f},{-0.0417064f,-0.0822373f,0.0434179f},{0.0391526f,0.0838984f,0.0434179f}, -{0.0388614f,0.0838832f,0.0340958f},{0.0394464f,0.0838828f,0.0340958f},{0.0400182f,0.083761f,0.0340958f}, -{0.0396981f,0.0838444f,0.0434179f},{0.0402232f,0.0836861f,0.0434179f},{0.041025f,0.0831789f,0.0340958f}, -{0.0407075f,0.083428f,0.0434179f},{0.0405514f,0.0835236f,0.0340958f},{0.0414158f,0.0827444f,0.0340958f}, -{0.0411317f,0.0830798f,0.0434179f},{0.0414795f,0.0826556f,0.0434179f},{0.0417077f,0.0822385f,0.0340958f}, -{0.041888f,0.0816837f,0.0340958f},{0.0417379f,0.082172f,0.0434179f},{0.0419492f,0.0811018f,0.0434179f}, -{0.0418971f,0.0816473f,0.0434179f},{0.0386063f,0.083844f,0.0434179f},{0.0382892f,0.0837619f,0.0340958f}, -{0.0380818f,0.0836835f,0.0434179f},{0.037599f,0.0834244f,0.0434179f},{0.0377553f,0.0835242f,0.0340958f}, -{0.0371757f,0.0830768f,0.0434179f},{0.0372831f,0.0831813f,0.0340958f},{0.0368907f,0.0827465f,0.0340958f}, -{0.0368282f,0.0826535f,0.0434179f},{0.0365701f,0.0821705f,0.0434179f},{0.036598f,0.0822399f,0.0340958f}, -{0.0364108f,0.0816464f,0.0434179f},{0.0364177f,0.0816851f,0.0340958f},{0.036356f,0.0811018f,0.0434179f}, -{0.0391526f,0.0811018f,0.0450982f},{0.035689f,0.0779818f,0.0359602f},{0.035116f,0.0787713f,0.0359602f}, -{0.0353809f,0.0783636f,0.0340958f},{0.0391526f,0.0764408f,0.0359602f},{0.0391526f,0.0764408f,0.0340958f}, -{0.0398869f,0.0764992f,0.0340958f},{0.0349993f,0.0789861f,0.0340958f},{0.0347708f,0.0795111f,0.0359602f}, -{0.0347209f,0.079658f,0.0340958f},{0.0345623f,0.0802921f,0.0359602f},{0.03455f,0.0803675f,0.0340958f}, -{0.0344918f,0.0811018f,0.0359602f},{0.0344916f,0.0811018f,0.0340958f},{0.0358568f,0.077806f,0.0340958f}, -{0.0364173f,0.077328f,0.0340958f},{0.0364146f,0.0773296f,0.0359602f},{0.0370399f,0.0769472f,0.0340958f}, -{0.0372574f,0.0768432f,0.0359602f},{0.0377117f,0.0766689f,0.0340958f},{0.0381842f,0.0765424f,0.0359602f}, -{0.0384218f,0.0764986f,0.0340958f},{0.0410494f,0.0768448f,0.0359602f},{0.0401233f,0.0765433f,0.0359602f}, -{0.0405964f,0.0766702f,0.0340958f},{0.0424484f,0.077806f,0.0340958f},{0.0418918f,0.0773309f,0.0359602f}, -{0.0418907f,0.0773301f,0.0340958f},{0.0412683f,0.0769485f,0.0340958f},{0.0435327f,0.0795124f,0.0359602f}, -{0.0431892f,0.0787712f,0.0359602f},{0.0433072f,0.0789891f,0.0340958f},{0.0426166f,0.0779842f,0.0359602f}, -{0.0429264f,0.0783665f,0.0340958f},{0.0437552f,0.0803675f,0.0340958f},{0.0437427f,0.0802929f,0.0359602f}, -{0.0435855f,0.079661f,0.0340958f},{0.0438136f,0.0811018f,0.0340958f},{0.0438134f,0.0811018f,0.0359602f}, -{0.0391526f,0.0783052f,0.062062f},{0.0388614f,0.0783204f,0.071384f},{0.0394464f,0.0783208f,0.071384f}, -{0.0400182f,0.0784426f,0.071384f},{0.0396981f,0.0783592f,0.062062f},{0.0402232f,0.0785175f,0.062062f}, -{0.041025f,0.0790247f,0.071384f},{0.0407075f,0.0787756f,0.062062f},{0.0405514f,0.0786801f,0.071384f}, -{0.0414158f,0.0794592f,0.071384f},{0.0411317f,0.0791238f,0.062062f},{0.0414795f,0.079548f,0.062062f}, -{0.0417077f,0.0799651f,0.071384f},{0.041888f,0.08052f,0.071384f},{0.0417379f,0.0800316f,0.062062f}, -{0.0419492f,0.0811018f,0.071384f},{0.0419492f,0.0811018f,0.062062f},{0.0418971f,0.0805563f,0.062062f}, -{0.0386063f,0.0783596f,0.062062f},{0.0382892f,0.0784417f,0.071384f},{0.0380818f,0.0785201f,0.062062f}, -{0.037599f,0.0787792f,0.062062f},{0.0377553f,0.0786794f,0.071384f},{0.0371757f,0.0791268f,0.062062f}, -{0.0372831f,0.0790223f,0.071384f},{0.0368907f,0.0794572f,0.071384f},{0.0368282f,0.0795501f,0.062062f}, -{0.0365701f,0.0800331f,0.062062f},{0.036598f,0.0799637f,0.071384f},{0.0364108f,0.0805572f,0.062062f}, -{0.0364177f,0.0805185f,0.071384f},{0.036356f,0.0811018f,0.071384f},{0.036356f,0.0811018f,0.062062f}, -{0.0391526f,0.0811018f,0.0603816f},{0.035689f,0.0842218f,0.0695196f},{0.035116f,0.0834323f,0.0695196f}, -{0.0353809f,0.08384f,0.071384f},{0.0391526f,0.0857628f,0.0695196f},{0.0391526f,0.0857628f,0.071384f}, -{0.0398869f,0.0857044f,0.071384f},{0.0349993f,0.0832175f,0.071384f},{0.0347708f,0.0826925f,0.0695196f}, -{0.0347209f,0.0825456f,0.071384f},{0.0345623f,0.0819115f,0.0695196f},{0.03455f,0.0818361f,0.071384f}, -{0.0344918f,0.0811018f,0.0695196f},{0.0344916f,0.0811018f,0.071384f},{0.0358568f,0.0843977f,0.071384f}, -{0.0364173f,0.0848756f,0.071384f},{0.0364146f,0.084874f,0.0695196f},{0.0370399f,0.0852564f,0.071384f}, -{0.0372574f,0.0853604f,0.0695196f},{0.0377117f,0.0855347f,0.071384f},{0.0381842f,0.0856612f,0.0695196f}, -{0.0384218f,0.085705f,0.071384f},{0.0410494f,0.0853588f,0.0695196f},{0.0401233f,0.0856603f,0.0695196f}, -{0.0405964f,0.0855335f,0.071384f},{0.0424484f,0.0843977f,0.071384f},{0.0418918f,0.0848727f,0.0695196f}, -{0.0418907f,0.0848735f,0.071384f},{0.0412683f,0.0852551f,0.071384f},{0.0435327f,0.0826912f,0.0695196f}, -{0.0431892f,0.0834324f,0.0695196f},{0.0433072f,0.0832145f,0.071384f},{0.0426166f,0.0842194f,0.0695196f}, -{0.0429264f,0.0838371f,0.071384f},{0.0437552f,0.0818361f,0.071384f},{0.0437427f,0.0819107f,0.0695196f}, -{0.0435855f,0.0825427f,0.071384f},{0.0438136f,0.0811018f,0.071384f},{0.0438134f,0.0811018f,0.0695196f}, -{0.0337705f,0.0811018f,0.0359602f},{0.0351159f,0.0787712f,0.0695196f},{0.0364616f,0.0764408f,0.0359602f}, -{0.0364616f,0.0764408f,0.0695196f},{0.0337705f,0.0811018f,0.0695196f},{0.0388588f,0.0783208f,0.0340958f}, -{0.0394438f,0.0783204f,0.0340958f},{0.0405499f,0.0786794f,0.0340958f},{0.040016f,0.0784417f,0.0340958f}, -{0.0345484f,0.0818312f,0.0340958f},{0.0347196f,0.0825428f,0.0340958f},{0.0365975f,0.0799651f,0.0340958f}, -{0.0364172f,0.08052f,0.0340958f},{0.0368894f,0.0794592f,0.0340958f},{0.0372802f,0.0790247f,0.0340958f}, -{0.0377538f,0.0786801f,0.0340958f},{0.038287f,0.0784426f,0.0340958f},{0.0358645f,0.0843932f,0.0340958f}, -{0.0364144f,0.084874f,0.0340958f},{0.0377132f,0.0855352f,0.0340958f},{0.0370378f,0.0852557f,0.0340958f}, -{0.038424f,0.0857056f,0.0340958f},{0.0410221f,0.0790223f,0.0340958f},{0.0414831f,0.0787713f,0.0340958f}, -{0.0398819f,0.0857052f,0.0340958f},{0.0391526f,0.0857628f,0.0340958f},{0.0412686f,0.0852544f,0.0340958f}, -{0.0418918f,0.0848725f,0.0340958f},{0.0405931f,0.0855343f,0.0340958f},{0.0417072f,0.0799637f,0.0340958f}, -{0.0414145f,0.0794572f,0.0340958f},{0.0424471f,0.0843959f,0.0340958f},{0.0433038f,0.0832165f,0.0340958f}, -{0.0435854f,0.0825415f,0.0340958f},{0.0437559f,0.0818303f,0.0340958f},{0.0418875f,0.0805185f,0.0340958f}, -{0.042921f,0.083839f,0.0340958f},{0.0349967f,0.0832217f,0.0340958f},{0.0353925f,0.0838337f,0.0340958f}, -{0.0445347f,0.0811018f,0.0359602f},{0.0431893f,0.0834324f,0.0359602f},{0.0418436f,0.0857628f,0.0359602f}, -{0.0418436f,0.0857628f,0.0695196f},{0.0445347f,0.0811018f,0.0695196f},{0.0364616f,0.0857628f,0.0359602f}, -{0.0351159f,0.0834324f,0.0359602f},{0.0364616f,0.0857628f,0.0695196f},{0.0391526f,0.0857624f,0.0359602f}, -{0.0391526f,0.0764411f,0.0695196f},{0.0418436f,0.0764408f,0.0359602f},{0.0418436f,0.0764408f,0.0695196f}, -{0.0364144f,0.0773296f,0.071384f},{0.0358645f,0.0778104f,0.071384f},{0.0437559f,0.0803733f,0.071384f}, -{0.0435854f,0.0796621f,0.071384f},{0.0370378f,0.0769479f,0.071384f},{0.0377132f,0.0766684f,0.071384f}, -{0.038424f,0.076498f,0.071384f},{0.0391526f,0.0764408f,0.071384f},{0.0405931f,0.0766694f,0.071384f}, -{0.0412686f,0.0769492f,0.071384f},{0.0398819f,0.0764984f,0.071384f},{0.0418918f,0.0773311f,0.071384f}, -{0.0353925f,0.07837f,0.071384f},{0.0345484f,0.0803724f,0.071384f},{0.0424471f,0.0778077f,0.071384f}, -{0.0364172f,0.0816837f,0.071384f},{0.0368221f,0.0834323f,0.071384f},{0.0368894f,0.0827444f,0.071384f}, -{0.040016f,0.0837619f,0.071384f},{0.0394438f,0.0838832f,0.071384f},{0.038287f,0.083761f,0.071384f}, -{0.0410221f,0.0831813f,0.071384f},{0.0405499f,0.0835242f,0.071384f},{0.0417072f,0.0822399f,0.071384f}, -{0.0414145f,0.0827465f,0.071384f},{0.0388588f,0.0838828f,0.071384f},{0.0418875f,0.0816851f,0.071384f}, -{0.0365975f,0.0822385f,0.071384f},{0.0377538f,0.0835236f,0.071384f},{0.0433038f,0.0789871f,0.071384f}, -{0.0347196f,0.0796609f,0.071384f},{0.0349967f,0.0789819f,0.071384f},{0.042921f,0.0783646f,0.071384f}, -{0.0372802f,0.0831789f,0.071384f},{0.0431893f,0.0787712f,0.0695196f},{0.0345623f,0.0802946f,0.0695196f}, -{0.0356893f,0.0779827f,0.0695196f},{0.0347719f,0.0795147f,0.0695196f},{0.0381833f,0.0765428f,0.0695196f}, -{0.0364121f,0.0773322f,0.0695196f},{0.0372548f,0.0768453f,0.0695196f},{0.041893f,0.0773311f,0.0695196f}, -{0.041049f,0.0768436f,0.0695196f},{0.0401215f,0.0765425f,0.0695196f},{0.0426157f,0.077982f,0.0695196f}, -{0.0435351f,0.0795134f,0.0695196f},{0.0437434f,0.080294f,0.0695196f},{0.0417086f,0.0822399f,0.062062f}, -{0.041416f,0.0827465f,0.062062f},{0.0418896f,0.0816836f,0.062062f},{0.0410244f,0.0831814f,0.062062f}, -{0.0405506f,0.0835251f,0.062062f},{0.0400156f,0.0837619f,0.062062f},{0.0394436f,0.0838831f,0.062062f}, -{0.0388585f,0.0838826f,0.062062f},{0.0377533f,0.0835206f,0.062062f},{0.0382866f,0.0837595f,0.062062f}, -{0.0368906f,0.082743f,0.062062f},{0.0372812f,0.0831769f,0.062062f},{0.0364182f,0.081682f,0.062062f}, -{0.0365988f,0.0822373f,0.062062f},{0.0345623f,0.081909f,0.0359602f},{0.035689f,0.0842206f,0.0359602f}, -{0.0347719f,0.0826889f,0.0359602f},{0.0381819f,0.0856605f,0.0359602f},{0.0364115f,0.0848709f,0.0359602f}, -{0.0372538f,0.0853579f,0.0359602f},{0.0418924f,0.084873f,0.0359602f},{0.041048f,0.0853604f,0.0359602f}, -{0.0401201f,0.0856614f,0.0359602f},{0.0426154f,0.0842219f,0.0359602f},{0.0435351f,0.0826902f,0.0359602f}, -{0.0437434f,0.0819096f,0.0359602f},{0.0417086f,0.0799637f,0.0434179f},{0.041416f,0.0794571f,0.0434179f}, -{0.0418896f,0.08052f,0.0434179f},{0.0410244f,0.0790222f,0.0434179f},{0.0405506f,0.0786785f,0.0434179f}, -{0.0400156f,0.0784417f,0.0434179f},{0.0394436f,0.0783205f,0.0434179f},{0.0388585f,0.078321f,0.0434179f}, -{0.0377533f,0.078683f,0.0434179f},{0.0382866f,0.0784441f,0.0434179f},{0.0368906f,0.0794606f,0.0434179f}, -{0.0372812f,0.0790267f,0.0434179f},{0.0364182f,0.0805216f,0.0434179f},{0.0365988f,0.0799663f,0.0434179f}, -{-0.023239f,-0.071786f,0.071384f},{-0.0231144f,-0.0708235f,0.0732484f},{-0.023239f,-0.0717882f,0.0732484f}, -{-0.0231106f,-0.0727502f,0.071384f},{-0.0231103f,-0.0727513f,0.0732484f},{-0.0227371f,-0.0736484f,0.071384f}, -{-0.0227371f,-0.0736484f,0.0732484f},{-0.0231141f,-0.0708224f,0.071384f},{-0.0227444f,-0.0699238f,0.0732484f}, -{-0.0227444f,-0.0699238f,0.071384f},{-0.0225127f,-0.00424291f,0.071384f},{-0.0216035f,-0.00385992f,0.0732484f}, -{-0.0225146f,-0.00424405f,0.0732484f},{-0.0232912f,-0.00485238f,0.071384f},{-0.023292f,-0.00485321f,0.0732484f}, -{-0.0238822f,-0.00564511f,0.071384f},{-0.0238822f,-0.00564511f,0.0732484f},{-0.0216024f,-0.00385961f,0.071384f}, -{-0.0206235f,-0.00372882f,0.0732484f},{-0.0206235f,-0.00372882f,0.071384f},{-0.0243511f,0.0075482f,0.071384f}, -{-0.024197f,0.00852259f,0.0732484f},{-0.0243512f,0.00754595f,0.0732484f},{-0.024244f,0.0065653f,0.071384f}, -{-0.0242437f,0.00656417f,0.0732484f},{-0.0238822f,0.00564511f,0.071384f},{-0.0238822f,0.00564511f,0.0732484f}, -{-0.0241967f,0.00852371f,0.071384f},{-0.0237915f,0.00942436f,0.0732484f},{-0.0237915f,0.00942436f,0.071384f}, -{-0.0213716f,0.0750107f,0.071384f},{-0.0204747f,0.0753817f,0.0732484f},{-0.0213735f,0.0750096f,0.0732484f}, -{-0.022144f,0.0744194f,0.071384f},{-0.0221448f,0.0744186f,0.0732484f},{-0.0227371f,0.0736484f,0.071384f}, -{-0.0227371f,0.0736484f,0.0732484f},{-0.0204736f,0.075382f,0.071384f},{-0.0195103f,0.0755086f,0.0732484f}, -{-0.0195103f,0.0755086f,0.071384f},{-0.0391526f,-0.00279661f,0.071384f},{-0.0397007f,-0.00274238f,0.0732484f}, -{-0.0391526f,-0.00279661f,0.0732484f},{-0.0380824f,-0.00258373f,0.0732484f},{-0.0380824f,-0.00258373f,0.071384f}, -{-0.0386045f,-0.00274238f,0.0732484f},{-0.0386045f,-0.00274238f,0.071384f},{-0.037601f,-0.00232674f,0.071384f}, -{-0.0371751f,-0.00197751f,0.071384f},{-0.0371751f,-0.00197751f,0.0732484f},{-0.0368259f,-0.00155157f,0.071384f}, -{-0.0368259f,-0.00155157f,0.0732484f},{-0.037601f,-0.00232674f,0.0732484f},{-0.036356f,3.97423e-017f,0.071384f}, -{-0.0364102f,-0.000548134f,0.071384f},{-0.0364102f,-0.000548134f,0.0732484f},{-0.0365689f,-0.00107022f,0.0732484f}, -{-0.0365689f,-0.00107022f,0.071384f},{-0.036356f,3.97423e-017f,0.0732484f},{-0.0397007f,-0.00274238f,0.071384f}, -{-0.0402228f,-0.00258373f,0.0732484f},{-0.0402228f,-0.00258373f,0.071384f},{-0.0407042f,-0.00232674f,0.071384f}, -{-0.0407042f,-0.00232674f,0.0732484f},{-0.0411301f,-0.00197751f,0.071384f},{-0.0411301f,-0.00197751f,0.0732484f}, -{-0.0414793f,-0.00155157f,0.0732484f},{-0.0414793f,-0.00155157f,0.071384f},{-0.0417363f,-0.00107022f,0.071384f}, -{-0.0417363f,-0.00107022f,0.0732484f},{-0.041895f,-0.000548134f,0.071384f},{-0.041895f,-0.000548134f,0.0732484f}, -{-0.0419492f,3.97423e-017f,0.0732484f},{-0.0419492f,3.97423e-017f,0.071384f},{0.0391526f,-0.00279661f,0.071384f}, -{0.0386045f,-0.00274238f,0.0732484f},{0.0391526f,-0.00279661f,0.0732484f},{0.0402228f,-0.00258373f,0.0732484f}, -{0.0402228f,-0.00258373f,0.071384f},{0.0397007f,-0.00274238f,0.0732484f},{0.0397007f,-0.00274238f,0.071384f}, -{0.0407042f,-0.00232674f,0.071384f},{0.0411301f,-0.00197751f,0.071384f},{0.0411301f,-0.00197751f,0.0732484f}, -{0.0414793f,-0.00155157f,0.071384f},{0.0414793f,-0.00155157f,0.0732484f},{0.0407042f,-0.00232674f,0.0732484f}, -{0.0419492f,3.97423e-017f,0.071384f},{0.041895f,-0.000548134f,0.071384f},{0.041895f,-0.000548134f,0.0732484f}, -{0.0417363f,-0.00107022f,0.0732484f},{0.0417363f,-0.00107022f,0.071384f},{0.0419492f,3.97423e-017f,0.0732484f}, -{0.0386045f,-0.00274238f,0.071384f},{0.0380824f,-0.00258373f,0.0732484f},{0.0380824f,-0.00258373f,0.071384f}, -{0.037601f,-0.00232674f,0.071384f},{0.037601f,-0.00232674f,0.0732484f},{0.0371751f,-0.00197751f,0.071384f}, -{0.0371751f,-0.00197751f,0.0732484f},{0.0368259f,-0.00155157f,0.0732484f},{0.0368259f,-0.00155157f,0.071384f}, -{0.0365689f,-0.00107022f,0.071384f},{0.0365689f,-0.00107022f,0.0732484f},{0.0364102f,-0.000548134f,0.071384f}, -{0.0364102f,-0.000548134f,0.0732484f},{0.036356f,3.97423e-017f,0.0732484f},{0.036356f,3.97423e-017f,0.071384f}, -{-0.0391526f,0.0783052f,0.071384f},{-0.0397007f,0.0783594f,0.0732484f},{-0.0391526f,0.0783052f,0.0732484f}, -{-0.0380824f,0.0785181f,0.0732484f},{-0.0380824f,0.0785181f,0.071384f},{-0.0386045f,0.0783594f,0.0732484f}, -{-0.0386045f,0.0783594f,0.071384f},{-0.037601f,0.0787751f,0.071384f},{-0.0371751f,0.0791243f,0.071384f}, -{-0.0371751f,0.0791243f,0.0732484f},{-0.0368259f,0.0795502f,0.071384f},{-0.0368259f,0.0795502f,0.0732484f}, -{-0.037601f,0.0787751f,0.0732484f},{-0.0364102f,0.0805537f,0.071384f},{-0.0364102f,0.0805537f,0.0732484f}, -{-0.0365689f,0.0800316f,0.0732484f},{-0.0365689f,0.0800316f,0.071384f},{-0.036356f,0.0811018f,0.0732484f}, -{-0.0397007f,0.0783594f,0.071384f},{-0.0402228f,0.0785181f,0.0732484f},{-0.0402228f,0.0785181f,0.071384f}, -{-0.0407042f,0.0787751f,0.071384f},{-0.0407042f,0.0787751f,0.0732484f},{-0.0411301f,0.0791243f,0.071384f}, -{-0.0411301f,0.0791243f,0.0732484f},{-0.0414793f,0.0795502f,0.0732484f},{-0.0414793f,0.0795502f,0.071384f}, -{-0.0417363f,0.0800316f,0.071384f},{-0.0417363f,0.0800316f,0.0732484f},{-0.041895f,0.0805537f,0.071384f}, -{-0.041895f,0.0805537f,0.0732484f},{-0.0419492f,0.0811018f,0.0732484f},{0.0391526f,0.0783052f,0.071384f}, -{0.0386045f,0.0783594f,0.0732484f},{0.0391526f,0.0783052f,0.0732484f},{0.0402228f,0.0785181f,0.0732484f}, -{0.0402228f,0.0785181f,0.071384f},{0.0397007f,0.0783594f,0.0732484f},{0.0397007f,0.0783594f,0.071384f}, -{0.0407042f,0.0787751f,0.071384f},{0.0411301f,0.0791243f,0.071384f},{0.0411301f,0.0791243f,0.0732484f}, -{0.0414793f,0.0795502f,0.071384f},{0.0414793f,0.0795502f,0.0732484f},{0.0407042f,0.0787751f,0.0732484f}, -{0.041895f,0.0805537f,0.071384f},{0.041895f,0.0805537f,0.0732484f},{0.0417363f,0.0800316f,0.0732484f}, -{0.0417363f,0.0800316f,0.071384f},{0.0419492f,0.0811018f,0.0732484f},{0.0386045f,0.0783594f,0.071384f}, -{0.0380824f,0.0785181f,0.0732484f},{0.0380824f,0.0785181f,0.071384f},{0.037601f,0.0787751f,0.071384f}, -{0.037601f,0.0787751f,0.0732484f},{0.0371751f,0.0791243f,0.071384f},{0.0371751f,0.0791243f,0.0732484f}, -{0.0368259f,0.0795502f,0.0732484f},{0.0368259f,0.0795502f,0.071384f},{0.0365689f,0.0800316f,0.071384f}, -{0.0365689f,0.0800316f,0.0732484f},{0.0364102f,0.0805537f,0.071384f},{0.0364102f,0.0805537f,0.0732484f}, -{0.036356f,0.0811018f,0.0732484f},{0.0391526f,-0.0838984f,0.071384f},{0.0386045f,-0.0838442f,0.0732484f}, -{0.0391526f,-0.0838984f,0.0732484f},{0.0402228f,-0.0836855f,0.0732484f},{0.0402228f,-0.0836855f,0.071384f}, -{0.0397007f,-0.0838442f,0.0732484f},{0.0397007f,-0.0838442f,0.071384f},{0.0407042f,-0.0834285f,0.071384f}, -{0.0411301f,-0.0830793f,0.071384f},{0.0411301f,-0.0830793f,0.0732484f},{0.0414793f,-0.0826534f,0.071384f}, -{0.0414793f,-0.0826534f,0.0732484f},{0.0407042f,-0.0834285f,0.0732484f},{0.0419492f,-0.0811018f,0.071384f}, -{0.041895f,-0.0816499f,0.071384f},{0.041895f,-0.0816499f,0.0732484f},{0.0417363f,-0.082172f,0.0732484f}, -{0.0417363f,-0.082172f,0.071384f},{0.0419492f,-0.0811018f,0.0732484f},{0.0386045f,-0.0838442f,0.071384f}, -{0.0380824f,-0.0836855f,0.0732484f},{0.0380824f,-0.0836855f,0.071384f},{0.037601f,-0.0834285f,0.071384f}, -{0.037601f,-0.0834285f,0.0732484f},{0.0371751f,-0.0830793f,0.071384f},{0.0371751f,-0.0830793f,0.0732484f}, -{0.0368259f,-0.0826534f,0.0732484f},{0.0368259f,-0.0826534f,0.071384f},{0.0365689f,-0.082172f,0.071384f}, -{0.0365689f,-0.082172f,0.0732484f},{0.0364102f,-0.0816499f,0.071384f},{0.0364102f,-0.0816499f,0.0732484f}, -{0.036356f,-0.0811018f,0.0732484f},{0.036356f,-0.0811018f,0.071384f},{-0.0391526f,-0.0838984f,0.071384f}, -{-0.0397007f,-0.0838442f,0.0732484f},{-0.0391526f,-0.0838984f,0.0732484f},{-0.0380824f,-0.0836855f,0.0732484f}, -{-0.0380824f,-0.0836855f,0.071384f},{-0.0386045f,-0.0838442f,0.0732484f},{-0.0386045f,-0.0838442f,0.071384f}, -{-0.037601f,-0.0834285f,0.071384f},{-0.0371751f,-0.0830793f,0.071384f},{-0.0371751f,-0.0830793f,0.0732484f}, -{-0.0368259f,-0.0826534f,0.071384f},{-0.0368259f,-0.0826534f,0.0732484f},{-0.037601f,-0.0834285f,0.0732484f}, -{-0.0364102f,-0.0816499f,0.071384f},{-0.0364102f,-0.0816499f,0.0732484f},{-0.0365689f,-0.082172f,0.0732484f}, -{-0.0365689f,-0.082172f,0.071384f},{-0.036356f,-0.0811018f,0.0732484f},{-0.0397007f,-0.0838442f,0.071384f}, -{-0.0402228f,-0.0836855f,0.0732484f},{-0.0402228f,-0.0836855f,0.071384f},{-0.0407042f,-0.0834285f,0.071384f}, -{-0.0407042f,-0.0834285f,0.0732484f},{-0.0411301f,-0.0830793f,0.071384f},{-0.0411301f,-0.0830793f,0.0732484f}, -{-0.0414793f,-0.0826534f,0.0732484f},{-0.0414793f,-0.0826534f,0.071384f},{-0.0417363f,-0.082172f,0.071384f}, -{-0.0417363f,-0.082172f,0.0732484f},{-0.041895f,-0.0816499f,0.071384f},{-0.041895f,-0.0816499f,0.0732484f}, -{-0.0419492f,-0.0811018f,0.0732484f},{0.0225785f,-0.0258241f,0.071384f},{0.0237254f,-0.0222932f,0.071384f}, -{0.0237253f,-0.0222933f,0.0732484f},{0.0216792f,-0.0294283f,0.071384f},{0.0225785f,-0.0258242f,0.0732484f}, -{0.0216792f,-0.0294286f,0.0732484f},{0.0210317f,-0.0330928f,0.071384f},{0.0206399f,-0.0368049f,0.0732484f}, -{0.0205085f,-0.0405509f,0.071384f},{0.02064f,-0.0368047f,0.071384f},{0.0210316f,-0.0330931f,0.0732484f}, -{0.0205085f,-0.0405509f,0.0732484f},{0.0251155f,-0.0188485f,0.0732484f},{0.0267447f,-0.0155029f,0.0732484f}, -{0.0251156f,-0.0188483f,0.071384f},{0.0267448f,-0.0155026f,0.071384f},{0.0286089f,-0.0122693f,0.0732484f}, -{0.028609f,-0.0122691f,0.071384f},{0.0307038f,-0.00916071f,0.0732484f},{0.0307038f,-0.00916071f,0.071384f}, -{-0.03984f,-0.0885276f,0.0732484f},{-0.0398371f,-0.0885279f,0.071384f},{-0.0387004f,-0.0885456f,0.071384f}, -{-0.0409568f,-0.0883379f,0.071384f},{-0.0409588f,-0.0883374f,0.0732484f},{-0.0420378f,-0.0879786f,0.0732484f}, -{-0.042035f,-0.0879797f,0.071384f},{-0.0430486f,-0.0874608f,0.0732484f},{-0.043047f,-0.0874618f,0.071384f}, -{-0.0439672f,-0.0867969f,0.071384f},{-0.0439685f,-0.086796f,0.0732484f},{-0.0447784f,-0.0859974f,0.0732484f}, -{-0.0447773f,-0.0859985f,0.071384f},{-0.045456f,-0.0850872f,0.0732484f},{-0.0454557f,-0.0850877f,0.071384f}, -{-0.0459883f,-0.0840833f,0.0732484f},{-0.0459883f,-0.0840833f,0.071384f},{-0.0387033f,-0.0885458f,0.0732484f}, -{-0.037576f,-0.0883909f,0.071384f},{-0.0375781f,-0.0883913f,0.0732484f},{-0.0364863f,-0.0880664f,0.071384f}, -{-0.0364891f,-0.0880674f,0.0732484f},{-0.0354613f,-0.0875818f,0.0732484f},{-0.0354596f,-0.0875808f,0.071384f}, -{-0.0345192f,-0.0869454f,0.071384f},{-0.0345204f,-0.0869463f,0.0732484f},{-0.0336844f,-0.0861728f,0.071384f}, -{-0.0336855f,-0.0861739f,0.0732484f},{-0.0329787f,-0.085285f,0.0732484f},{-0.0329784f,-0.0852846f,0.071384f}, -{-0.0324146f,-0.0842979f,0.071384f},{-0.0324146f,-0.0842979f,0.0732484f},{-0.0440592f,-0.00561614f,0.071384f}, -{-0.0430328f,-0.00636862f,0.071384f},{-0.0440603f,-0.00561515f,0.0732484f},{-0.044941f,-0.00470215f,0.0732484f}, -{-0.0449406f,-0.00470266f,0.071384f},{-0.0456552f,-0.0036514f,0.0732484f},{-0.0456542f,-0.00365287f,0.071384f}, -{-0.046181f,-0.00249363f,0.071384f},{-0.0461811f,-0.00249326f,0.0732484f},{-0.046502f,-0.00126624f,0.0732484f}, -{-0.0465017f,-0.00126733f,0.071384f},{-0.0466102f,3.97423e-017f,0.0732484f},{-0.0466102f,3.97423e-017f,0.071384f}, -{-0.0430341f,-0.00636786f,0.0732484f},{-0.0418973f,-0.00693419f,0.071384f},{-0.0418979f,-0.00693393f,0.0732484f}, -{-0.0406822f,-0.00729899f,0.0732484f},{-0.0406805f,-0.00729943f,0.071384f},{-0.0394178f,-0.00745289f,0.071384f}, -{-0.0394182f,-0.00745292f,0.0732484f},{-0.0381511f,-0.00739011f,0.071384f},{-0.0381522f,-0.00739019f,0.0732484f}, -{-0.0369109f,-0.00711273f,0.071384f},{-0.0369109f,-0.00711273f,0.0732484f},{-0.0450626f,0.0765535f,0.0732484f}, -{-0.0450608f,0.0765512f,0.071384f},{-0.0443005f,0.075706f,0.071384f},{-0.0456834f,0.0775011f,0.071384f}, -{-0.0456844f,0.0775029f,0.0732484f},{-0.0461555f,0.0785378f,0.0732484f},{-0.0461544f,0.078535f,0.071384f}, -{-0.0464637f,0.0796309f,0.0732484f},{-0.0464633f,0.079629f,0.071384f},{-0.0466021f,0.0807558f,0.071384f}, -{-0.0466023f,0.0807574f,0.0732484f},{-0.046568f,0.0818943f,0.0732484f},{-0.0465681f,0.0818927f,0.071384f}, -{-0.046362f,0.0830101f,0.0732484f},{-0.0463621f,0.0830096f,0.071384f},{-0.0459883f,0.0840833f,0.0732484f}, -{-0.0459883f,0.0840833f,0.071384f},{-0.0443026f,0.0757081f,0.0732484f},{-0.0434222f,0.0749873f,0.071384f}, -{-0.0434238f,0.0749885f,0.0732484f},{-0.0424429f,0.0744094f,0.071384f},{-0.0424456f,0.0744107f,0.0732484f}, -{-0.0413904f,0.0739879f,0.0732484f},{-0.0413886f,0.0739873f,0.071384f},{-0.040283f,0.0737303f,0.071384f}, -{-0.0402846f,0.0737307f,0.0732484f},{-0.0391489f,0.0736442f,0.071384f},{-0.0391504f,0.0736443f,0.0732484f}, -{-0.0380181f,0.073731f,0.0732484f},{-0.0380175f,0.073731f,0.071384f},{-0.0369109f,0.0739891f,0.071384f}, -{-0.0369109f,0.0739891f,0.0732484f},{0.0225785f,0.0552777f,0.071384f},{0.0237254f,0.0588086f,0.071384f}, -{0.0237253f,0.0588085f,0.0732484f},{0.0216792f,0.0516735f,0.071384f},{0.0225785f,0.0552776f,0.0732484f}, -{0.0216792f,0.0516732f,0.0732484f},{0.0210317f,0.048009f,0.071384f},{0.0206399f,0.0442969f,0.0732484f}, -{0.0205085f,0.0405509f,0.071384f},{0.02064f,0.0442971f,0.071384f},{0.0210316f,0.0480087f,0.0732484f}, -{0.0205085f,0.0405509f,0.0732484f},{0.0251155f,0.0622533f,0.0732484f},{0.0267447f,0.0655989f,0.0732484f}, -{0.0251156f,0.0622535f,0.071384f},{0.0267448f,0.0655992f,0.071384f},{0.0286089f,0.0688326f,0.0732484f}, -{0.028609f,0.0688327f,0.071384f},{0.0307038f,0.0719411f,0.0732484f},{0.0307038f,0.0719411f,0.071384f}, -{0.0167768f,-0.0552561f,0.0732484f},{0.0159195f,-0.0513911f,0.0732484f},{0.0167768f,-0.0552561f,0.071384f}, -{0.0159195f,-0.0513911f,0.071384f},{0.0153227f,-0.0474729f,0.0732484f},{0.0149897f,-0.0435148f,0.0732484f}, -{0.0153227f,-0.0474729f,0.071384f},{0.0149241f,-0.0395297f,0.0732484f},{0.0149897f,-0.0435148f,0.071384f}, -{0.0149241f,-0.0395297f,0.071384f},{0.0178914f,-0.059055f,0.071384f},{0.0192597f,-0.0627747f,0.071384f}, -{0.0178914f,-0.059055f,0.0732484f},{0.0208785f,-0.066402f,0.071384f},{0.0192597f,-0.0627747f,0.0732484f}, -{0.0208785f,-0.066402f,0.0732484f},{0.0227444f,-0.0699238f,0.071384f},{0.0227444f,-0.0699238f,0.0732484f}, -{0.0173199f,0.0238768f,0.0732484f},{0.0163293f,0.0277099f,0.0732484f},{0.0173199f,0.0238768f,0.071384f}, -{0.0163293f,0.0277099f,0.071384f},{0.0155973f,0.031605f,0.0732484f},{0.0151276f,0.0355493f,0.0732484f}, -{0.0155973f,0.031605f,0.071384f},{0.0149241f,0.0395297f,0.0732484f},{0.0151276f,0.0355493f,0.071384f}, -{0.0149241f,0.0395297f,0.071384f},{0.0185653f,0.0201187f,0.071384f},{0.0200615f,0.0164487f,0.071384f}, -{0.0185653f,0.0201187f,0.0732484f},{0.0218049f,0.0128796f,0.071384f},{0.0200615f,0.0164487f,0.0732484f}, -{0.0218049f,0.0128796f,0.0732484f},{0.0237915f,0.00942436f,0.071384f},{0.0237915f,0.00942436f,0.0732484f}, -{0.0149897f,0.0435148f,0.0732484f},{0.0167768f,0.0552561f,0.0732484f},{0.0159195f,0.0513911f,0.071384f}, -{0.0159195f,0.0513911f,0.0732484f},{0.0153227f,0.0474729f,0.0732484f},{0.0153227f,0.0474729f,0.071384f}, -{0.0149897f,0.0435148f,0.071384f},{0.0192597f,0.0627747f,0.071384f},{0.0192597f,0.0627747f,0.0732484f}, -{0.0208785f,0.066402f,0.0732484f},{0.0167768f,0.0552561f,0.071384f},{0.0178914f,0.059055f,0.0732484f}, -{0.0178914f,0.059055f,0.071384f},{0.0227444f,0.0699238f,0.0732484f},{0.0208785f,0.066402f,0.071384f}, -{0.0227444f,0.0699238f,0.071384f},{-0.0206235f,0.00372882f,0.071384f},{-0.0206235f,0.00372882f,0.0732484f}, -{0.0206235f,0.00372882f,0.0732484f},{0.0206235f,0.00372882f,0.071384f},{-0.0149256f,0.0416576f,0.0732484f}, -{-0.0149993f,0.0374031f,0.0732484f},{-0.0149257f,0.0416577f,0.071384f},{-0.0151577f,0.0458938f,0.071384f}, -{-0.0151576f,0.0458937f,0.0732484f},{-0.0156914f,0.0500904f,0.071384f},{-0.0156914f,0.0500902f,0.0732484f}, -{-0.0165229f,0.0542313f,0.0732484f},{-0.016523f,0.0542315f,0.071384f},{-0.0176481f,0.0583013f,0.071384f}, -{-0.017648f,0.0583011f,0.0732484f},{-0.0190628f,0.0622838f,0.071384f},{-0.0190627f,0.0622837f,0.0732484f}, -{-0.0207629f,0.0661632f,0.0732484f},{-0.0207629f,0.0661633f,0.071384f},{-0.0227444f,0.0699238f,0.071384f}, -{-0.0227444f,0.0699238f,0.0732484f},{-0.0149993f,0.0374031f,0.071384f},{-0.0153777f,0.0331776f,0.071384f}, -{-0.0153777f,0.0331775f,0.0732484f},{-0.0160564f,0.0290019f,0.0732484f},{-0.0160564f,0.0290021f,0.071384f}, -{-0.0170307f,0.024892f,0.0732484f},{-0.0170307f,0.0248922f,0.071384f},{-0.018296f,0.0208638f,0.071384f}, -{-0.018296f,0.0208636f,0.0732484f},{-0.0198477f,0.0169324f,0.0732484f},{-0.0198476f,0.0169326f,0.071384f}, -{-0.021681f,0.0131141f,0.0732484f},{-0.021681f,0.0131142f,0.071384f},{0.0151276f,-0.0355493f,0.0732484f}, -{0.0173199f,-0.0238768f,0.0732484f},{0.0163293f,-0.0277099f,0.071384f},{0.0163293f,-0.0277099f,0.0732484f}, -{0.0155973f,-0.031605f,0.0732484f},{0.0155973f,-0.031605f,0.071384f},{0.0151276f,-0.0355493f,0.071384f}, -{0.0200615f,-0.0164487f,0.071384f},{0.0200615f,-0.0164487f,0.0732484f},{0.0218049f,-0.0128796f,0.0732484f}, -{0.0173199f,-0.0238768f,0.071384f},{0.0185653f,-0.0201187f,0.0732484f},{0.0185653f,-0.0201187f,0.071384f}, -{0.0237915f,-0.00942436f,0.0732484f},{0.0218049f,-0.0128796f,0.071384f},{0.0237915f,-0.00942436f,0.071384f}, -{-0.0195103f,-0.0755086f,0.071384f},{0.0195103f,-0.0755086f,0.0732484f},{0.0195103f,-0.0755086f,0.071384f}, -{-0.0195103f,-0.0755086f,0.0732484f},{-0.0149993f,-0.0374031f,0.0732484f},{-0.0149257f,-0.0416576f,0.0732484f}, -{-0.0149993f,-0.0374031f,0.071384f},{-0.0153777f,-0.0331775f,0.071384f},{-0.0153777f,-0.0331776f,0.0732484f}, -{-0.0160564f,-0.0290019f,0.071384f},{-0.0160564f,-0.0290021f,0.0732484f},{-0.0170307f,-0.0248922f,0.0732484f}, -{-0.0170307f,-0.024892f,0.071384f},{-0.018296f,-0.0208636f,0.071384f},{-0.018296f,-0.0208638f,0.0732484f}, -{-0.0198477f,-0.0169324f,0.071384f},{-0.0198476f,-0.0169326f,0.0732484f},{-0.021681f,-0.0131142f,0.0732484f}, -{-0.021681f,-0.0131141f,0.071384f},{-0.0237915f,-0.00942436f,0.071384f},{-0.0237915f,-0.00942436f,0.0732484f}, -{-0.0149256f,-0.0416576f,0.071384f},{-0.0151576f,-0.0458937f,0.071384f},{-0.0151577f,-0.0458938f,0.0732484f}, -{-0.0156914f,-0.0500904f,0.0732484f},{-0.0156914f,-0.0500902f,0.071384f},{-0.016523f,-0.0542315f,0.0732484f}, -{-0.0165229f,-0.0542313f,0.071384f},{-0.017648f,-0.0583011f,0.071384f},{-0.0176481f,-0.0583013f,0.0732484f}, -{-0.0190628f,-0.0622838f,0.0732484f},{-0.0190627f,-0.0622837f,0.071384f},{-0.0207629f,-0.0661633f,0.0732484f}, -{-0.0207629f,-0.0661632f,0.071384f},{0.02064f,0.0368047f,0.0732484f},{0.0206399f,0.0368049f,0.071384f}, -{0.0225785f,0.0258241f,0.0732484f},{0.0225785f,0.0258242f,0.071384f},{0.0216792f,0.0294283f,0.0732484f}, -{0.0216792f,0.0294286f,0.071384f},{0.0210316f,0.0330931f,0.071384f},{0.0210317f,0.0330928f,0.0732484f}, -{0.0267447f,0.0155029f,0.071384f},{0.0251156f,0.0188483f,0.0732484f},{0.0267448f,0.0155026f,0.0732484f}, -{0.0237253f,0.0222933f,0.071384f},{0.0237254f,0.0222932f,0.0732484f},{0.0251155f,0.0188485f,0.071384f}, -{0.028609f,0.0122691f,0.0732484f},{0.0286089f,0.0122693f,0.071384f},{0.0307038f,0.00916071f,0.0732484f}, -{0.0307038f,0.00916071f,0.071384f},{0.0462025f,0.0835337f,0.0732484f},{0.0457312f,0.0846141f,0.071384f}, -{0.0457326f,0.0846116f,0.0732484f},{0.0450998f,0.0856014f,0.0732484f},{0.0450987f,0.085603f,0.071384f}, -{0.044317f,0.0864818f,0.071384f},{0.0443187f,0.0864801f,0.0732484f},{0.0434093f,0.0872252f,0.0732484f}, -{0.0434083f,0.0872259f,0.071384f},{0.0423945f,0.087818f,0.071384f},{0.0423947f,0.0878178f,0.0732484f}, -{0.0412975f,0.0882443f,0.071384f},{0.041298f,0.0882442f,0.0732484f},{0.040151f,0.0884923f,0.0732484f}, -{0.0401493f,0.0884924f,0.071384f},{0.0389772f,0.0885573f,0.0732484f},{0.0389749f,0.0885572f,0.071384f}, -{0.0378063f,0.0884369f,0.071384f},{0.0378083f,0.0884373f,0.0732484f},{0.0366734f,0.0881351f,0.0732484f}, -{0.0366703f,0.0881341f,0.071384f},{0.0355963f,0.0876568f,0.071384f},{0.0355984f,0.087658f,0.0732484f}, -{0.0346116f,0.0870176f,0.071384f},{0.0346134f,0.0870188f,0.0732484f},{0.0337395f,0.0862314f,0.0732484f}, -{0.0337379f,0.0862299f,0.071384f},{0.0330004f,0.0853169f,0.071384f},{0.0330008f,0.0853175f,0.0732484f}, -{0.0324146f,0.0842979f,0.071384f},{0.0324146f,0.0842979f,0.0732484f},{0.0462016f,0.0835364f,0.071384f}, -{0.0464969f,0.0823973f,0.0732484f},{0.0464965f,0.0823992f,0.071384f},{0.0466091f,0.0812265f,0.0732484f}, -{0.046609f,0.0812289f,0.071384f},{0.0465363f,0.0800543f,0.0732484f},{0.0465364f,0.0800555f,0.071384f}, -{0.0462805f,0.0789088f,0.071384f},{0.0462804f,0.0789085f,0.0732484f},{0.0458466f,0.0778144f,0.0732484f}, -{0.0458468f,0.0778149f,0.071384f},{0.0452473f,0.0768042f,0.0732484f},{0.0452483f,0.0768055f,0.071384f}, -{0.0444957f,0.0758993f,0.0732484f},{0.0444974f,0.075901f,0.071384f},{0.0436142f,0.075126f,0.071384f}, -{0.0436125f,0.0751248f,0.0732484f},{0.0426177f,0.0744982f,0.0732484f},{0.0426206f,0.0744998f,0.071384f}, -{0.0415395f,0.0740365f,0.071384f},{0.0415373f,0.0740358f,0.0732484f},{0.0403988f,0.073749f,0.0732484f}, -{0.0404009f,0.0737495f,0.071384f},{0.0392271f,0.0736446f,0.0732484f},{0.0392293f,0.0736447f,0.071384f}, -{0.038057f,0.0737251f,0.071384f},{0.0380562f,0.0737252f,0.0732484f},{0.0369109f,0.0739891f,0.0732484f}, -{0.0369109f,0.0739891f,0.071384f},{0.027361f,0.0811018f,0.071384f},{-0.027361f,0.0811018f,0.071384f}, -{-0.027361f,0.0811018f,0.0732484f},{0.027361f,0.0811018f,0.0732484f},{-0.0454557f,0.0850877f,0.0732484f}, -{-0.043047f,0.0874618f,0.0732484f},{-0.0430486f,0.0874608f,0.071384f},{-0.0439672f,0.0867969f,0.0732484f}, -{-0.0447773f,0.0859985f,0.0732484f},{-0.0439685f,0.086796f,0.071384f},{-0.0447784f,0.0859974f,0.071384f}, -{-0.03984f,0.0885276f,0.071384f},{-0.0409568f,0.0883379f,0.0732484f},{-0.0398371f,0.0885279f,0.0732484f}, -{-0.0420378f,0.0879786f,0.071384f},{-0.042035f,0.0879797f,0.0732484f},{-0.0409588f,0.0883374f,0.071384f}, -{-0.037576f,0.0883909f,0.0732484f},{-0.0364863f,0.0880664f,0.0732484f},{-0.0364891f,0.0880674f,0.071384f}, -{-0.0387004f,0.0885456f,0.0732484f},{-0.0375781f,0.0883913f,0.071384f},{-0.0387033f,0.0885458f,0.071384f}, -{-0.0354596f,0.0875809f,0.0732484f},{-0.0345192f,0.0869454f,0.0732484f},{-0.0345204f,0.0869463f,0.071384f}, -{-0.0354613f,0.0875818f,0.071384f},{-0.0336855f,0.0861739f,0.071384f},{-0.0336844f,0.0861728f,0.0732484f}, -{-0.0329784f,0.0852846f,0.0732484f},{-0.0329787f,0.085285f,0.071384f},{-0.0324146f,0.0842979f,0.0732484f}, -{-0.0324146f,0.0842979f,0.071384f},{-0.045456f,0.0850872f,0.071384f},{-0.021027f,0.0331264f,0.0732484f}, -{-0.0206381f,0.0368319f,0.0732484f},{-0.0206381f,0.0368317f,0.071384f},{-0.0205085f,0.0405509f,0.0732484f}, -{-0.0205085f,0.0405509f,0.071384f},{-0.021027f,0.0331261f,0.071384f},{-0.0216751f,0.0294476f,0.071384f}, -{-0.0216749f,0.0294486f,0.0732484f},{-0.0237299f,0.0222807f,0.0732484f},{-0.0225785f,0.0258242f,0.0732484f}, -{-0.0225785f,0.025824f,0.071384f},{-0.0237299f,0.0222806f,0.071384f},{-0.0267542f,0.0154851f,0.0732484f}, -{-0.0251237f,0.01883f,0.071384f},{-0.0267544f,0.0154848f,0.071384f},{-0.0286161f,0.0122577f,0.0732484f}, -{-0.0251236f,0.0188302f,0.0732484f},{-0.0286162f,0.0122575f,0.071384f},{-0.0307038f,0.00916071f,0.0732484f}, -{-0.0307038f,0.00916071f,0.071384f},{-0.0206381f,0.0442701f,0.0732484f},{-0.0206381f,0.0442699f,0.071384f}, -{-0.021027f,0.0479754f,0.071384f},{-0.021027f,0.0479757f,0.0732484f},{-0.0216751f,0.0516542f,0.0732484f}, -{-0.0216749f,0.0516532f,0.071384f},{-0.0225785f,0.0552778f,0.0732484f},{-0.0225785f,0.0552777f,0.071384f}, -{-0.0237299f,0.0588211f,0.071384f},{-0.0237299f,0.0588212f,0.0732484f},{-0.0251237f,0.0622718f,0.0732484f}, -{-0.0251236f,0.0622716f,0.071384f},{-0.0267544f,0.065617f,0.0732484f},{-0.0267542f,0.0656167f,0.071384f}, -{-0.0286161f,0.0688441f,0.071384f},{-0.0286162f,0.0688443f,0.0732484f},{-0.0307038f,0.0719411f,0.071384f}, -{-0.0307038f,0.0719411f,0.0732484f},{-0.0465017f,0.00126733f,0.0732484f},{-0.044941f,0.00470215f,0.071384f}, -{-0.0456552f,0.0036514f,0.071384f},{-0.0449406f,0.00470266f,0.0732484f},{-0.0456542f,0.00365287f,0.0732484f}, -{-0.0461811f,0.00249326f,0.071384f},{-0.046181f,0.00249363f,0.0732484f},{-0.0430341f,0.00636786f,0.071384f}, -{-0.0418973f,0.00693419f,0.0732484f},{-0.0418979f,0.00693393f,0.071384f},{-0.0440592f,0.00561614f,0.0732484f}, -{-0.0430328f,0.00636862f,0.0732484f},{-0.0440603f,0.00561515f,0.071384f},{-0.0406822f,0.00729899f,0.071384f}, -{-0.0394178f,0.00745289f,0.0732484f},{-0.0394182f,0.00745292f,0.071384f},{-0.0406805f,0.00729943f,0.0732484f}, -{-0.0381522f,0.00739019f,0.071384f},{-0.0381511f,0.00739011f,0.0732484f},{-0.0369109f,0.00711273f,0.0732484f}, -{-0.0369109f,0.00711273f,0.071384f},{-0.046502f,0.00126624f,0.071384f},{-0.021027f,-0.0479754f,0.0732484f}, -{-0.0206381f,-0.0442699f,0.0732484f},{-0.0206381f,-0.0442701f,0.071384f},{-0.0205085f,-0.0405509f,0.0732484f}, -{-0.0205085f,-0.0405509f,0.071384f},{-0.021027f,-0.0479757f,0.071384f},{-0.0216751f,-0.0516542f,0.071384f}, -{-0.0216749f,-0.0516532f,0.0732484f},{-0.0237299f,-0.0588211f,0.0732484f},{-0.0225785f,-0.0552777f,0.0732484f}, -{-0.0225785f,-0.0552778f,0.071384f},{-0.0237299f,-0.0588212f,0.071384f},{-0.0267542f,-0.0656167f,0.0732484f}, -{-0.0251237f,-0.0622718f,0.071384f},{-0.0267544f,-0.065617f,0.071384f},{-0.0286161f,-0.0688441f,0.0732484f}, -{-0.0251236f,-0.0622716f,0.0732484f},{-0.0286162f,-0.0688443f,0.071384f},{-0.0307038f,-0.0719411f,0.0732484f}, -{-0.0307038f,-0.0719411f,0.071384f},{-0.0206381f,-0.0368317f,0.0732484f},{-0.0206381f,-0.0368319f,0.071384f}, -{-0.021027f,-0.0331264f,0.071384f},{-0.021027f,-0.0331261f,0.0732484f},{-0.0216751f,-0.0294476f,0.0732484f}, -{-0.0216749f,-0.0294486f,0.071384f},{-0.0225785f,-0.025824f,0.0732484f},{-0.0225785f,-0.0258241f,0.071384f}, -{-0.0237299f,-0.0222807f,0.071384f},{-0.0237299f,-0.0222806f,0.0732484f},{-0.0251237f,-0.01883f,0.0732484f}, -{-0.0251236f,-0.0188302f,0.071384f},{-0.0267544f,-0.0154848f,0.0732484f},{-0.0267542f,-0.0154851f,0.071384f}, -{-0.0286161f,-0.0122577f,0.071384f},{-0.0286162f,-0.0122575f,0.0732484f},{-0.0307038f,-0.00916071f,0.071384f}, -{-0.0307038f,-0.00916071f,0.0732484f},{-0.0463621f,-0.0830096f,0.0732484f},{-0.0464633f,-0.079629f,0.0732484f}, -{-0.0464637f,-0.0796309f,0.071384f},{-0.0466021f,-0.0807558f,0.0732484f},{-0.0465681f,-0.0818927f,0.0732484f}, -{-0.0466023f,-0.0807574f,0.071384f},{-0.046568f,-0.0818943f,0.071384f},{-0.0450626f,-0.0765535f,0.071384f}, -{-0.0456834f,-0.0775011f,0.0732484f},{-0.0450608f,-0.0765512f,0.0732484f},{-0.0461555f,-0.0785378f,0.071384f}, -{-0.0461544f,-0.078535f,0.0732484f},{-0.0456844f,-0.0775029f,0.071384f},{-0.0434222f,-0.0749873f,0.0732484f}, -{-0.0424429f,-0.0744094f,0.0732484f},{-0.0424456f,-0.0744108f,0.071384f},{-0.0443005f,-0.075706f,0.0732484f}, -{-0.0434238f,-0.0749885f,0.071384f},{-0.0443026f,-0.0757081f,0.071384f},{-0.0413886f,-0.0739873f,0.0732484f}, -{-0.040283f,-0.0737303f,0.0732484f},{-0.0402846f,-0.0737307f,0.071384f},{-0.0413904f,-0.0739879f,0.071384f}, -{-0.0391504f,-0.0736443f,0.071384f},{-0.0391489f,-0.0736442f,0.0732484f},{-0.0380175f,-0.073731f,0.0732484f}, -{-0.0380181f,-0.073731f,0.071384f},{-0.0369109f,-0.0739891f,0.0732484f},{-0.0369109f,-0.0739891f,0.071384f}, -{-0.046362f,-0.0830101f,0.071384f},{0.027361f,-0.0811018f,0.0732484f},{-0.027361f,-0.0811018f,0.071384f}, -{0.027361f,-0.0811018f,0.071384f},{-0.027361f,-0.0811018f,0.0732484f},{0.0457312f,-0.0846141f,0.0732484f}, -{0.0462025f,-0.0835337f,0.071384f},{0.0462016f,-0.0835364f,0.0732484f},{0.0464965f,-0.0823992f,0.0732484f}, -{0.0464969f,-0.0823973f,0.071384f},{0.0466091f,-0.0812265f,0.071384f},{0.046609f,-0.0812289f,0.0732484f}, -{0.0465364f,-0.0800555f,0.0732484f},{0.0465363f,-0.0800543f,0.071384f},{0.0462804f,-0.0789085f,0.071384f}, -{0.0462805f,-0.0789088f,0.0732484f},{0.0458466f,-0.0778144f,0.071384f},{0.0458468f,-0.0778149f,0.0732484f}, -{0.0452483f,-0.0768055f,0.0732484f},{0.0452473f,-0.0768041f,0.071384f},{0.0444974f,-0.075901f,0.0732484f}, -{0.0444957f,-0.0758994f,0.071384f},{0.0436125f,-0.0751248f,0.071384f},{0.0436142f,-0.075126f,0.0732484f}, -{0.0426206f,-0.0744997f,0.0732484f},{0.0426177f,-0.0744982f,0.071384f},{0.0415373f,-0.0740358f,0.071384f}, -{0.0415395f,-0.0740365f,0.0732484f},{0.0403988f,-0.073749f,0.071384f},{0.0404009f,-0.0737495f,0.0732484f}, -{0.0392293f,-0.0736447f,0.0732484f},{0.0392271f,-0.0736446f,0.071384f},{0.0380562f,-0.0737252f,0.071384f}, -{0.038057f,-0.0737251f,0.0732484f},{0.0369109f,-0.0739891f,0.071384f},{0.0369109f,-0.0739891f,0.0732484f}, -{0.0457326f,-0.0846116f,0.071384f},{0.0450987f,-0.085603f,0.0732484f},{0.0450998f,-0.0856014f,0.071384f}, -{0.044317f,-0.0864818f,0.0732484f},{0.0443187f,-0.0864801f,0.071384f},{0.0434083f,-0.0872259f,0.0732484f}, -{0.0434093f,-0.0872252f,0.071384f},{0.0423947f,-0.0878178f,0.071384f},{0.0423945f,-0.087818f,0.0732484f}, -{0.0412975f,-0.0882443f,0.0732484f},{0.041298f,-0.0882442f,0.071384f},{0.0401493f,-0.0884924f,0.0732484f}, -{0.040151f,-0.0884923f,0.071384f},{0.0389749f,-0.0885572f,0.0732484f},{0.0389772f,-0.0885573f,0.071384f}, -{0.0378083f,-0.0884373f,0.071384f},{0.0378063f,-0.0884369f,0.0732484f},{0.0366703f,-0.088134f,0.0732484f}, -{0.0366734f,-0.0881351f,0.071384f},{0.0355984f,-0.087658f,0.071384f},{0.0355963f,-0.0876568f,0.0732484f}, -{0.0346116f,-0.0870176f,0.0732484f},{0.0346134f,-0.0870188f,0.071384f},{0.0337379f,-0.0862299f,0.0732484f}, -{0.0337395f,-0.0862314f,0.071384f},{0.0330008f,-0.0853175f,0.071384f},{0.0330004f,-0.0853169f,0.0732484f}, -{0.0324146f,-0.0842979f,0.0732484f},{0.0324146f,-0.0842979f,0.071384f},{0.02064f,-0.0442971f,0.0732484f}, -{0.0206399f,-0.0442969f,0.071384f},{0.0225785f,-0.0552777f,0.0732484f},{0.0225785f,-0.0552776f,0.071384f}, -{0.0216792f,-0.0516735f,0.0732484f},{0.0216792f,-0.0516732f,0.071384f},{0.0210316f,-0.0480087f,0.071384f}, -{0.0210317f,-0.048009f,0.0732484f},{0.0267447f,-0.0655989f,0.071384f},{0.0251156f,-0.0622535f,0.0732484f}, -{0.0267448f,-0.0655992f,0.0732484f},{0.0237253f,-0.0588085f,0.071384f},{0.0237254f,-0.0588086f,0.0732484f}, -{0.0251155f,-0.0622533f,0.071384f},{0.028609f,-0.0688327f,0.0732484f},{0.0286089f,-0.0688325f,0.071384f}, -{0.0307038f,-0.0719411f,0.0732484f},{0.0307038f,-0.0719411f,0.071384f},{0.0206235f,-0.00372882f,0.071384f}, -{0.0206235f,-0.00372882f,0.0732484f},{0.0466102f,3.97423e-017f,0.0732484f},{0.0466102f,3.97423e-017f,0.071384f}, -{0.0465018f,0.00126639f,0.071384f},{0.0461802f,0.00249579f,0.071384f},{0.0465022f,0.00126441f,0.0732484f}, -{0.0456552f,0.00365135f,0.071384f},{0.0461804f,0.00249531f,0.0732484f},{0.0456558f,0.00365019f,0.0732484f}, -{0.0449402f,0.00470316f,0.071384f},{0.0440587f,0.00561661f,0.071384f},{0.0449409f,0.00470218f,0.0732484f}, -{0.043034f,0.00636795f,0.071384f},{0.0440594f,0.00561601f,0.0732484f},{0.0430353f,0.00636709f,0.0732484f}, -{0.0418963f,0.00693455f,0.071384f},{0.040681f,0.00729936f,0.071384f},{0.0418969f,0.00693434f,0.0732484f}, -{0.0394182f,0.00745287f,0.071384f},{0.0406822f,0.00729903f,0.0732484f},{0.0394186f,0.0074529f,0.0732484f}, -{0.0381506f,0.00739003f,0.071384f},{0.0369109f,0.00711273f,0.071384f},{0.0381517f,0.00739014f,0.0732484f}, -{0.0369109f,0.00711273f,0.0732484f},{0.0465018f,-0.00126639f,0.0732484f},{0.0465022f,-0.00126441f,0.071384f}, -{0.0461802f,-0.00249579f,0.0732484f},{0.0456552f,-0.00365135f,0.0732484f},{0.0461804f,-0.00249531f,0.071384f}, -{0.0449402f,-0.00470316f,0.0732484f},{0.0456558f,-0.00365019f,0.071384f},{0.0449409f,-0.00470218f,0.071384f}, -{0.0440587f,-0.00561661f,0.0732484f},{0.043034f,-0.00636795f,0.0732484f},{0.0440594f,-0.00561601f,0.071384f}, -{0.0418963f,-0.00693455f,0.0732484f},{0.0430353f,-0.00636709f,0.071384f},{0.0418969f,-0.00693434f,0.071384f}, -{0.040681f,-0.00729936f,0.0732484f},{0.0394182f,-0.00745287f,0.0732484f},{0.0406822f,-0.00729903f,0.071384f}, -{0.0381506f,-0.00739003f,0.0732484f},{0.0394186f,-0.0074529f,0.071384f},{0.0381517f,-0.00739014f,0.071384f}, -{0.0369109f,-0.00711273f,0.0732484f},{0.0369109f,-0.00711273f,0.071384f},{0.0195103f,0.0755086f,0.071384f}, -{0.0195103f,0.0755086f,0.0732484f},{0.0418944f,0.000544649f,0.0732484f},{-0.0396981f,0.00274259f,0.0732484f}, -{-0.0346445f,-0.00688452f,0.0732484f},{-0.033477f,-0.00713571f,0.0732484f},{0.0417351f,0.00106869f,0.0732484f}, -{-0.0323894f,-0.0734732f,0.0732484f},{-0.033477f,-0.0739661f,0.0732484f},{-0.029784f,-0.081654f,0.0732484f}, -{0.0396989f,-0.0783596f,0.0732484f},{0.0402234f,-0.0785201f,0.0732484f},{0.038082f,0.0836861f,0.0732484f}, -{0.0386071f,0.0838444f,0.0732484f},{0.041477f,0.00155172f,0.0732484f},{0.041477f,-0.0795501f,0.0732484f}, -{0.0411295f,-0.0791268f,0.0732484f},{0.0417351f,-0.0800331f,0.0732484f},{0.0411295f,0.00197505f,0.0732484f}, -{0.0418944f,-0.0805572f,0.0732484f},{0.0407062f,0.00232262f,0.0732484f},{0.0402234f,0.00258168f,0.0732484f}, -{0.0396989f,0.00274216f,0.0732484f},{0.0391526f,0.00279661f,0.0732484f},{0.0386071f,0.00274259f,0.0732484f}, -{0.038082f,0.00258432f,0.0732484f},{0.0358134f,0.00688407f,0.0732484f},{0.0375977f,0.00232618f,0.0732484f}, -{0.0364081f,0.000545524f,0.0732484f},{0.0236456f,0.00527349f,0.0732484f},{0.0365672f,0.00107021f,0.0732484f}, -{0.033477f,0.00713571f,0.0732484f},{0.0371735f,0.00197799f,0.0732484f},{0.0346445f,0.00688452f,0.0732484f}, -{0.0346482f,-0.00688511f,0.0732484f},{0.0241643f,0.0086281f,0.0732484f},{0.0243399f,0.00776655f,0.0732484f}, -{0.0230511f,-0.00462716f,0.0732484f},{0.023646f,-0.00527393f,0.0732484f},{-0.0396981f,0.0838444f,0.0732484f}, -{-0.0402232f,0.0836861f,0.0732484f},{-0.0386063f,0.083844f,0.0732484f},{-0.0380818f,0.0836835f,0.0732484f}, -{-0.0346445f,0.0742173f,0.0732484f},{-0.0308772f,0.0823454f,0.0732484f},{0.0211824f,0.075113f,0.0732484f}, -{0.0219051f,0.0746381f,0.0732484f},{0.0358165f,0.0742161f,0.0732484f},{0.0323894f,0.0734732f,0.0732484f}, -{0.033477f,0.0739661f,0.0732484f},{0.029784f,0.081654f,0.0732484f},{0.03177f,0.0832527f,0.0732484f}, -{0.0364081f,0.0816473f,0.0732484f},{0.0375977f,0.083428f,0.0732484f},{0.0371735f,0.0830798f,0.0732484f}, -{0.0407062f,0.0834244f,0.0732484f},{0.0417351f,0.0821705f,0.0732484f},{0.0418944f,0.0816464f,0.0732484f}, -{0.041477f,0.0826535f,0.0732484f},{0.0411295f,0.0830768f,0.0732484f},{0.0396989f,0.083844f,0.0732484f}, -{0.0402234f,0.0836835f,0.0732484f},{0.0391526f,0.0838984f,0.0732484f},{0.0365672f,0.082172f,0.0732484f}, -{0.0368257f,0.0826556f,0.0732484f},{0.0346482f,0.0742167f,0.0732484f},{0.0308757f,0.0823441f,0.0732484f}, -{0.0285789f,0.0812367f,0.0732484f},{0.0314497f,0.072778f,0.0732484f},{0.0224988f,0.0740097f,0.0732484f}, -{0.0229321f,0.0732614f,0.0732484f},{0.0203695f,0.0754087f,0.0732484f},{-0.0314481f,0.0727748f,0.0732484f}, -{-0.0285817f,0.0812363f,0.0732484f},{-0.0231141f,0.0708224f,0.0732484f},{-0.0407075f,0.083428f,0.0732484f}, -{-0.0411317f,0.0830798f,0.0732484f},{-0.0417379f,0.082172f,0.0732484f},{-0.0418971f,0.0816473f,0.0732484f}, -{-0.0414795f,0.0826556f,0.0732484f},{-0.0391526f,0.0838984f,0.0732484f},{-0.0358134f,0.0742177f,0.0732484f}, -{-0.037599f,0.0834244f,0.0732484f},{-0.033477f,0.0739661f,0.0732484f},{-0.0418971f,0.000545524f,0.0732484f}, -{-0.0371757f,0.0830768f,0.0732484f},{-0.0368282f,0.0826535f,0.0732484f},{-0.0365701f,0.0821705f,0.0732484f}, -{-0.0323867f,0.0734705f,0.0732484f},{-0.0297859f,0.0816548f,0.0732484f},{-0.0231106f,0.0727502f,0.0732484f}, -{-0.0241967f,-0.00852371f,0.0732484f},{-0.0323867f,-0.00763125f,0.0732484f},{-0.0314481f,-0.00832702f,0.0732484f}, -{-0.033477f,0.00713571f,0.0732484f},{-0.0365701f,0.00106869f,0.0732484f},{-0.0364108f,0.000544649f,0.0732484f}, -{-0.0323894f,0.00762858f,0.0732484f},{-0.0386063f,0.00274216f,0.0732484f},{-0.0391526f,0.00279661f,0.0732484f}, -{-0.0368282f,0.00155172f,0.0732484f},{-0.0417379f,0.00107021f,0.0732484f},{-0.0414795f,0.0015538f,0.0732484f}, -{-0.0411317f,0.00197799f,0.0732484f},{-0.0407075f,0.00232618f,0.0732484f},{-0.0402232f,0.00258432f,0.0732484f}, -{-0.0418971f,-0.0805563f,0.0732484f},{-0.0417379f,-0.0800316f,0.0732484f},{-0.0358134f,-0.00688407f,0.0732484f}, -{-0.0225127f,0.00424291f,0.0732484f},{-0.0380818f,0.00258168f,0.0732484f},{-0.0358165f,0.00688568f,0.0732484f}, -{0.0214967f,-0.00383203f,0.0732484f},{0.0223196f,0.0041374f,0.0732484f},{0.0214955f,0.00383263f,0.0732484f}, -{-0.0216024f,0.00385961f,0.0732484f},{-0.024244f,-0.0065653f,0.0732484f},{0.0314497f,-0.00832383f,0.0732484f}, -{0.0243085f,-0.00688932f,0.0732484f},{0.0364081f,-0.0805563f,0.0732484f},{0.0308772f,-0.0823454f,0.0732484f}, -{0.0314481f,-0.0727748f,0.0732484f},{0.0285817f,-0.0812363f,0.0732484f},{0.0230854f,-0.0707188f,0.0732484f}, -{-0.0285788f,-0.0812367f,0.0732484f},{-0.0213716f,-0.0750107f,0.0732484f},{-0.022144f,-0.0744194f,0.0732484f}, -{-0.0365701f,-0.0800331f,0.0732484f},{-0.0391526f,-0.0783052f,0.0732484f},{-0.03177f,-0.0832527f,0.0732484f}, -{-0.0308757f,-0.0823441f,0.0732484f},{-0.0364108f,-0.0805572f,0.0732484f},{-0.0414795f,-0.079548f,0.0732484f}, -{-0.0411317f,-0.0791238f,0.0732484f},{-0.0407075f,-0.0787756f,0.0732484f},{-0.0402232f,-0.0785175f,0.0732484f}, -{-0.0396981f,-0.0783592f,0.0732484f},{-0.0386063f,-0.0783596f,0.0732484f},{-0.0368282f,-0.0795501f,0.0732484f}, -{-0.0371757f,-0.0791268f,0.0732484f},{-0.0346482f,-0.0742167f,0.0732484f},{-0.0358165f,-0.0742161f,0.0732484f}, -{0.0386071f,-0.0783592f,0.0732484f},{0.038082f,-0.0785175f,0.0732484f},{-0.0314497f,-0.072778f,0.0732484f}, -{0.0391526f,-0.0783052f,0.0732484f},{0.0407062f,-0.0787792f,0.0732484f},{0.0358134f,-0.0742177f,0.0732484f}, -{0.0375977f,-0.0787756f,0.0732484f},{0.0368257f,-0.079548f,0.0732484f},{0.0346445f,-0.0742173f,0.0732484f}, -{0.0365672f,-0.0800316f,0.0732484f},{0.0371735f,-0.0791238f,0.0732484f},{0.0297859f,-0.0816548f,0.0732484f}, -{0.033477f,-0.0739661f,0.0732484f},{0.0317708f,-0.0832554f,0.0732484f},{0.0323867f,-0.0734706f,0.0732484f}, -{0.0229318f,-0.0732619f,0.0732484f},{0.0223212f,-0.0041373f,0.0732484f},{0.0240731f,-0.00604206f,0.0732484f}, -{0.0323894f,-0.00762858f,0.0732484f},{0.0243087f,0.00688805f,0.0732484f},{0.0314481f,0.00832702f,0.0732484f}, -{0.0323867f,0.00763125f,0.0732484f},{0.0358165f,-0.00688568f,0.0732484f},{-0.023239f,0.071786f,0.0732484f}, -{0.0232328f,0.0715697f,0.0732484f},{0.0230844f,0.0707181f,0.0732484f},{0.0231812f,0.072433f,0.0732484f}, -{0.0240729f,0.00604156f,0.0732484f},{0.02305f,0.00462664f,0.0732484f},{0.033477f,-0.00713571f,0.0732484f}, -{0.024339f,-0.00776783f,0.0732484f},{0.0241632f,-0.00862874f,0.0732484f},{-0.0314497f,0.00832383f,0.0732484f}, -{-0.0346482f,0.00688511f,0.0732484f},{0.0231813f,-0.0724342f,0.0732484f},{0.0232336f,-0.071571f,0.0732484f}, -{0.021904f,-0.0746385f,0.0732484f},{0.0224985f,-0.0740101f,0.0732484f},{0.0203684f,-0.0754081f,0.0732484f}, -{0.0211809f,-0.0751129f,0.0732484f},{-0.0204736f,-0.075382f,0.0732484f},{-0.0243511f,-0.0075482f,0.0732484f}, -{-0.0232912f,0.00485238f,0.0732484f},{-0.0380818f,-0.0785201f,0.0732484f},{-0.037599f,-0.0787792f,0.0732484f}, -{-0.0364108f,0.0816464f,0.0732484f},{-0.0317708f,0.0832554f,0.0732484f},{0.0368257f,0.0015538f,0.0732484f}, -{-0.037599f,0.00232262f,0.0732484f},{-0.0371757f,0.00197505f,0.0732484f},{0.0314481f,0.0727748f,0.071384f}, -{0.0229318f,0.0732619f,0.071384f},{-0.0358134f,-0.0742177f,0.071384f},{-0.0375977f,-0.0787756f,0.071384f}, -{-0.038082f,-0.0785175f,0.071384f},{-0.0391526f,-0.0783052f,0.071384f},{0.0243399f,-0.00776655f,0.071384f}, -{0.0243087f,-0.00688805f,0.071384f},{0.0358165f,0.00688568f,0.071384f},{0.0380818f,0.00258168f,0.071384f}, -{0.037599f,0.00232262f,0.071384f},{0.0241643f,-0.0086281f,0.071384f},{0.033477f,-0.00713571f,0.071384f}, -{0.0323867f,-0.00763125f,0.071384f},{0.0396981f,0.00274259f,0.071384f},{0.0391526f,0.00279661f,0.071384f}, -{0.0407075f,0.00232618f,0.071384f},{0.0402232f,0.00258432f,0.071384f},{0.0417379f,0.00107021f,0.071384f}, -{0.0358134f,-0.00688407f,0.071384f},{0.0346445f,-0.00688452f,0.071384f},{0.0417379f,0.082172f,0.071384f}, -{0.0407075f,0.083428f,0.071384f},{0.0402232f,0.0836861f,0.071384f},{0.0396981f,0.0838444f,0.071384f}, -{0.0418971f,0.000545524f,0.071384f},{0.0414795f,0.0015538f,0.071384f},{0.0411317f,0.00197799f,0.071384f}, -{0.0386063f,0.00274216f,0.071384f},{0.033477f,0.00713571f,0.071384f},{0.0364108f,0.000544649f,0.071384f}, -{0.0323894f,0.00762858f,0.071384f},{0.0240729f,-0.00604156f,0.071384f},{0.0236456f,-0.00527349f,0.071384f}, -{0.0223212f,0.0041373f,0.071384f},{0.0230511f,0.00462716f,0.071384f},{0.0223196f,-0.0041374f,0.071384f}, -{0.0346482f,0.00688511f,0.071384f},{0.0368282f,0.00155172f,0.071384f},{0.0365701f,0.00106869f,0.071384f}, -{-0.0346445f,-0.0742173f,0.071384f},{-0.0371735f,-0.0791238f,0.071384f},{-0.0386071f,-0.0783592f,0.071384f}, -{-0.0396989f,-0.0783596f,0.071384f},{-0.0402234f,-0.0785201f,0.071384f},{-0.0417351f,-0.0800331f,0.071384f}, -{-0.0407062f,-0.0787792f,0.071384f},{-0.0411295f,-0.0791268f,0.071384f},{-0.041477f,-0.0795501f,0.071384f}, -{-0.0285817f,-0.0812363f,0.071384f},{-0.0323867f,-0.0734706f,0.071384f},{-0.0314481f,-0.0727748f,0.071384f}, -{-0.0365672f,-0.0800316f,0.071384f},{-0.0308772f,-0.0823454f,0.071384f},{-0.0364081f,-0.0805563f,0.071384f}, -{0.029784f,-0.081654f,0.071384f},{0.0323894f,-0.0734732f,0.071384f},{0.033477f,-0.0739661f,0.071384f}, -{0.0219051f,-0.0746381f,0.071384f},{0.0211824f,-0.075113f,0.071384f},{0.0391526f,-0.0783052f,0.071384f}, -{0.0396981f,-0.0783592f,0.071384f},{0.0386063f,-0.0783596f,0.071384f},{0.0411317f,-0.0791238f,0.071384f}, -{0.0407075f,-0.0787756f,0.071384f},{0.0414795f,-0.079548f,0.071384f},{0.0365701f,-0.0800331f,0.071384f}, -{0.0417379f,-0.0800316f,0.071384f},{0.0418971f,-0.0805563f,0.071384f},{0.03177f,-0.0832527f,0.071384f}, -{0.0308757f,-0.0823441f,0.071384f},{0.0364108f,-0.0805572f,0.071384f},{0.0402232f,-0.0785175f,0.071384f}, -{0.0380818f,-0.0785201f,0.071384f},{0.0346482f,-0.0742167f,0.071384f},{0.0368282f,-0.0795501f,0.071384f}, -{0.0371757f,-0.0791268f,0.071384f},{0.0285789f,-0.0812367f,0.071384f},{0.0314497f,-0.072778f,0.071384f}, -{0.0224988f,-0.0740097f,0.071384f},{0.0229321f,-0.0732614f,0.071384f},{0.0230844f,-0.0707181f,0.071384f}, -{-0.0418944f,-0.0805572f,0.071384f},{-0.033477f,-0.0739661f,0.071384f},{-0.0297859f,-0.0816548f,0.071384f}, -{-0.0317708f,-0.0832554f,0.071384f},{-0.0243512f,-0.00754595f,0.071384f},{-0.0242437f,-0.00656417f,0.071384f}, -{-0.0216035f,0.00385992f,0.071384f},{-0.024197f,-0.00852259f,0.071384f},{-0.0323867f,0.00763125f,0.071384f}, -{-0.0364081f,0.000545524f,0.071384f},{-0.0418944f,0.000544649f,0.071384f},{-0.0411295f,0.00197505f,0.071384f}, -{-0.0407062f,0.00232262f,0.071384f},{-0.0386071f,0.00274259f,0.071384f},{-0.0391526f,0.00279661f,0.071384f}, -{-0.0358134f,0.00688407f,0.071384f},{-0.0375977f,0.00232618f,0.071384f},{-0.038082f,0.00258432f,0.071384f}, -{-0.041477f,0.00155172f,0.071384f},{-0.0417351f,0.00106869f,0.071384f},{-0.0402234f,0.00258168f,0.071384f}, -{-0.0371735f,0.00197799f,0.071384f},{-0.0346445f,0.00688452f,0.071384f},{-0.0396989f,0.00274216f,0.071384f}, -{-0.0358165f,-0.00688568f,0.071384f},{-0.033477f,0.00713571f,0.071384f},{-0.023292f,0.00485321f,0.071384f}, -{-0.0346482f,-0.00688511f,0.071384f},{0.0314497f,0.00832383f,0.071384f},{0.0243085f,0.00688932f,0.071384f}, -{0.0230854f,0.0707188f,0.071384f},{-0.0346482f,0.0742167f,0.071384f},{-0.033477f,0.0739661f,0.071384f}, -{-0.0231144f,0.0708235f,0.071384f},{-0.0368257f,0.0826556f,0.071384f},{-0.0396989f,0.083844f,0.071384f}, -{-0.0391526f,0.0838984f,0.071384f},{-0.0375977f,0.083428f,0.071384f},{-0.038082f,0.0836861f,0.071384f}, -{-0.0411295f,0.0830768f,0.071384f},{-0.041477f,0.0826535f,0.071384f},{-0.0371735f,0.0830798f,0.071384f}, -{-0.0418944f,0.0816464f,0.071384f},{-0.0417351f,0.0821705f,0.071384f},{-0.0402234f,0.0836835f,0.071384f}, -{-0.0386071f,0.0838444f,0.071384f},{-0.0407062f,0.0834244f,0.071384f},{-0.0364081f,0.0816473f,0.071384f}, -{-0.0365672f,0.082172f,0.071384f},{-0.03177f,0.0832527f,0.071384f},{-0.0308757f,0.0823441f,0.071384f}, -{-0.0358165f,0.0742161f,0.071384f},{-0.029784f,0.081654f,0.071384f},{-0.0323894f,0.0734732f,0.071384f}, -{-0.0285788f,0.0812367f,0.071384f},{-0.0314497f,0.072778f,0.071384f},{-0.0231103f,0.0727513f,0.071384f}, -{0.0391526f,0.0838984f,0.071384f},{0.0380818f,0.0836835f,0.071384f},{0.0386063f,0.083844f,0.071384f}, -{0.0414795f,0.0826556f,0.071384f},{0.0411317f,0.0830798f,0.071384f},{0.0418971f,0.0816473f,0.071384f}, -{0.0358134f,0.0742177f,0.071384f},{0.0346445f,0.0742173f,0.071384f},{0.033477f,0.0739661f,0.071384f}, -{0.0371757f,0.0830768f,0.071384f},{0.037599f,0.0834244f,0.071384f},{0.0368282f,0.0826535f,0.071384f}, -{0.0308772f,0.0823454f,0.071384f},{0.0323867f,0.0734705f,0.071384f},{0.0297859f,0.0816548f,0.071384f}, -{0.0285817f,0.0812363f,0.071384f},{0.0187991f,0.0422603f,0.071384f},{0.0232336f,0.071571f,0.071384f}, -{0.0231813f,0.0724342f,0.071384f},{0.021904f,0.0746385f,0.071384f},{0.0224985f,0.0740101f,0.071384f}, -{0.0203684f,0.0754081f,0.071384f},{0.0211809f,0.0751129f,0.071384f},{-0.023239f,0.0717882f,0.071384f}, -{0.024339f,0.00776783f,0.071384f},{0.0241632f,0.00862874f,0.071384f},{-0.0314481f,0.00832702f,0.071384f}, -{-0.0225146f,0.00424405f,0.071384f},{-0.0323894f,-0.00762858f,0.071384f},{-0.0314497f,-0.00832383f,0.071384f}, -{0.023646f,0.00527393f,0.071384f},{0.0240731f,0.00604206f,0.071384f},{0.0314481f,-0.00832702f,0.071384f}, -{0.02305f,-0.00462664f,0.071384f},{0.0214955f,-0.00383263f,0.071384f},{0.0214967f,0.00383203f,0.071384f}, -{-0.033477f,-0.00713571f,0.071384f},{-0.0213735f,-0.0750096f,0.071384f},{-0.0221448f,-0.0744186f,0.071384f}, -{-0.0204747f,-0.0753817f,0.071384f},{0.0232328f,-0.0715697f,0.071384f},{0.0231812f,-0.072433f,0.071384f}, -{0.0203695f,-0.0754087f,0.071384f},{-0.0368257f,-0.079548f,0.071384f},{0.0358165f,-0.0742161f,0.071384f}, -{0.037599f,-0.0787792f,0.071384f},{0.0365701f,0.0821705f,0.071384f},{0.0364108f,0.0816464f,0.071384f}, -{0.0317708f,0.0832554f,0.071384f},{0.0371757f,0.00197505f,0.071384f},{-0.0368257f,0.0015538f,0.071384f}, -{-0.0365672f,0.00107021f,0.071384f},{0.0386654f,0.0838556f,0.0732484f},{0.0391526f,0.0838984f,0.080706f}, -{0.0396411f,0.0838554f,0.0732484f},{0.040109f,0.0837298f,0.080706f},{0.0396398f,0.0838556f,0.080706f}, -{0.0401103f,0.0837293f,0.0732484f},{0.0405482f,0.0835251f,0.080706f},{0.0405499f,0.0835245f,0.0732484f}, -{0.0409476f,0.0832459f,0.080706f},{0.0412967f,0.0828968f,0.0732484f},{0.0412948f,0.0828995f,0.080706f}, -{0.0409503f,0.083244f,0.0732484f},{0.0415759f,0.0824974f,0.0732484f},{0.0415753f,0.0824991f,0.080706f}, -{0.0417806f,0.0820583f,0.0732484f},{0.0417801f,0.0820595f,0.080706f},{0.0419062f,0.0815903f,0.080706f}, -{0.0419062f,0.0815903f,0.0732484f},{0.0419492f,0.0811018f,0.080706f},{0.0386641f,0.0838554f,0.080706f}, -{0.0381949f,0.0837293f,0.080706f},{0.0381961f,0.0837298f,0.0732484f},{0.037757f,0.0835251f,0.0732484f}, -{0.0377553f,0.0835245f,0.080706f},{0.0373549f,0.083244f,0.080706f},{0.0373576f,0.0832459f,0.0732484f}, -{0.0370085f,0.0828968f,0.080706f},{0.0370104f,0.0828995f,0.0732484f},{0.0367299f,0.0824991f,0.0732484f}, -{0.0367293f,0.0824974f,0.080706f},{0.0365246f,0.0820583f,0.080706f},{0.0365251f,0.0820595f,0.0732484f}, -{0.036399f,0.0815903f,0.080706f},{0.036399f,0.0815903f,0.0732484f},{0.036356f,0.0811018f,0.080706f}, -{0.0351171f,0.0787719f,0.0751128f},{0.0351836f,0.0786864f,0.0732484f},{0.0355373f,0.0781593f,0.0732484f}, -{0.0394705f,0.0764554f,0.0732484f},{0.0391526f,0.0764408f,0.0751128f},{0.0388355f,0.076451f,0.0732484f}, -{0.0348819f,0.0792468f,0.0732484f},{0.034847f,0.0793182f,0.0751128f},{0.034664f,0.0798436f,0.0732484f}, -{0.0346475f,0.079899f,0.0751128f},{0.0345395f,0.080468f,0.0732484f},{0.0345304f,0.0804959f,0.0751128f}, -{0.0344916f,0.0811018f,0.0732484f},{0.0344918f,0.0811018f,0.0751128f},{0.0356898f,0.0779809f,0.0751128f}, -{0.0364147f,0.0773294f,0.0751128f},{0.0359728f,0.0776969f,0.0732484f},{0.0370083f,0.076961f,0.0732484f}, -{0.0364669f,0.0772961f,0.0732484f},{0.037596f,0.0767216f,0.0732484f},{0.0372582f,0.0768428f,0.0751128f}, -{0.0381846f,0.0765423f,0.0751128f},{0.0382078f,0.0765464f,0.0732484f},{0.0407151f,0.0767081f,0.0732484f}, -{0.041049f,0.0768446f,0.0751128f},{0.0401226f,0.0765432f,0.0751128f},{0.0401013f,0.0765401f,0.0732484f}, -{0.0423348f,0.0776954f,0.0732484f},{0.0418908f,0.0773301f,0.0751128f},{0.0418394f,0.0772978f,0.0732484f}, -{0.0412894f,0.0769789f,0.0732484f},{0.0431881f,0.0787719f,0.0751128f},{0.0431347f,0.0786808f,0.0732484f}, -{0.0434289f,0.0792447f,0.0732484f},{0.0426156f,0.0779832f,0.0751128f},{0.0427645f,0.0781631f,0.0732484f}, -{0.0436546f,0.079901f,0.0751128f},{0.0436222f,0.0798502f,0.0732484f},{0.0437699f,0.0804677f,0.0732484f}, -{0.0434582f,0.0793181f,0.0751128f},{0.0438136f,0.0811018f,0.0732484f},{0.0437742f,0.0804963f,0.0751128f}, -{0.0438134f,0.0811018f,0.0751128f},{0.0391526f,0.0857628f,0.0900281f},{0.0418436f,0.0857628f,0.0751128f}, -{0.0391526f,0.0857628f,0.0751128f},{0.0364616f,0.0857628f,0.0751128f},{0.0364616f,0.0857628f,0.0900281f}, -{0.0418436f,0.0857628f,0.0900281f},{0.0386654f,0.078348f,0.0918925f},{0.0391526f,0.0783052f,0.0918925f}, -{0.0391526f,0.0783052f,0.0844349f},{0.0396411f,0.0783482f,0.0918925f},{0.040109f,0.0784738f,0.0844349f}, -{0.0396398f,0.078348f,0.0844349f},{0.0401103f,0.0784743f,0.0918925f},{0.0405482f,0.0786785f,0.0844349f}, -{0.0405499f,0.0786791f,0.0918925f},{0.0409476f,0.0789577f,0.0844349f},{0.0412967f,0.0793068f,0.0918925f}, -{0.0412948f,0.0793041f,0.0844349f},{0.0409503f,0.0789596f,0.0918925f},{0.0415759f,0.0797062f,0.0918925f}, -{0.0415753f,0.0797045f,0.0844349f},{0.0417806f,0.0801454f,0.0918925f},{0.0417801f,0.0801441f,0.0844349f}, -{0.0419062f,0.0806133f,0.0844349f},{0.0419062f,0.0806133f,0.0918925f},{0.0419492f,0.0811018f,0.0918925f}, -{0.0419492f,0.0811018f,0.0844349f},{0.0386641f,0.0783482f,0.0844349f},{0.0381949f,0.0784743f,0.0844349f}, -{0.0381961f,0.0784738f,0.0918925f},{0.037757f,0.0786785f,0.0918925f},{0.0377553f,0.0786791f,0.0844349f}, -{0.0373549f,0.0789596f,0.0844349f},{0.0373576f,0.0789577f,0.0918925f},{0.0370085f,0.0793068f,0.0844349f}, -{0.0370104f,0.0793041f,0.0918925f},{0.0367299f,0.0797045f,0.0918925f},{0.0367293f,0.0797062f,0.0844349f}, -{0.0365246f,0.0801454f,0.0844349f},{0.0365251f,0.0801441f,0.0918925f},{0.036399f,0.0806133f,0.0844349f}, -{0.036399f,0.0806133f,0.0918925f},{0.036356f,0.0811018f,0.0918925f},{0.036356f,0.0811018f,0.0844349f}, -{0.0351171f,0.0834317f,0.0900281f},{0.0351836f,0.0835172f,0.0918925f},{0.0355373f,0.0840443f,0.0918925f}, -{0.0394705f,0.0857482f,0.0918925f},{0.0388355f,0.0857526f,0.0918925f},{0.0348819f,0.0829568f,0.0918925f}, -{0.034847f,0.0828854f,0.0900281f},{0.034664f,0.08236f,0.0918925f},{0.0346475f,0.0823046f,0.0900281f}, -{0.0345395f,0.0817356f,0.0918925f},{0.0345304f,0.0817077f,0.0900281f},{0.0344916f,0.0811018f,0.0918925f}, -{0.0344917f,0.0811018f,0.0900281f},{0.0356898f,0.0842227f,0.0900281f},{0.0364147f,0.0848742f,0.0900281f}, -{0.0359728f,0.0845067f,0.0918925f},{0.0370083f,0.0852426f,0.0918925f},{0.0364669f,0.0849075f,0.0918925f}, -{0.037596f,0.0854821f,0.0918925f},{0.0372582f,0.0853608f,0.0900281f},{0.0381846f,0.0856613f,0.0900281f}, -{0.0382078f,0.0856572f,0.0918925f},{0.0407151f,0.0854955f,0.0918925f},{0.041049f,0.0853591f,0.0900281f}, -{0.0401226f,0.0856604f,0.0900281f},{0.0401013f,0.0856635f,0.0918925f},{0.0423348f,0.0845082f,0.0918925f}, -{0.0418908f,0.0848735f,0.0900281f},{0.0418394f,0.0849058f,0.0918925f},{0.0412894f,0.0852247f,0.0918925f}, -{0.0431881f,0.0834317f,0.0900281f},{0.0431347f,0.0835228f,0.0918925f},{0.0434289f,0.0829589f,0.0918925f}, -{0.0426156f,0.0842204f,0.0900281f},{0.0427645f,0.0840405f,0.0918925f},{0.0436546f,0.0823026f,0.0900281f}, -{0.0436222f,0.0823534f,0.0918925f},{0.0437699f,0.0817359f,0.0918925f},{0.0434582f,0.0828855f,0.0900281f}, -{0.0438136f,0.0811018f,0.0918925f},{0.0437742f,0.0817073f,0.0900281f},{0.0438134f,0.0811018f,0.0900281f}, -{0.0337705f,0.0811018f,0.0751128f},{0.0351171f,0.0787719f,0.0900281f},{0.0364616f,0.0764408f,0.0751128f}, -{0.0364616f,0.0764408f,0.0900281f},{0.0337705f,0.0811018f,0.0900281f},{0.0417795f,0.0801478f,0.0732484f}, -{0.0419056f,0.0806167f,0.0732484f},{0.0359715f,0.0845087f,0.0732484f},{0.0364649f,0.0849099f,0.0732484f}, -{0.0409507f,0.0789629f,0.0732484f},{0.041295f,0.0793075f,0.0732484f},{0.0396393f,0.0783484f,0.0732484f}, -{0.0401104f,0.0784759f,0.0732484f},{0.0405519f,0.078683f,0.0732484f},{0.0386677f,0.0783479f,0.0732484f}, -{0.0381969f,0.0784733f,0.0732484f},{0.0377546f,0.0786785f,0.0732484f},{0.0365233f,0.0801446f,0.0732484f}, -{0.0373546f,0.0789579f,0.0732484f},{0.0367296f,0.0797026f,0.0732484f},{0.0370095f,0.079303f,0.0732484f}, -{0.036397f,0.0806159f,0.0732484f},{0.0345334f,0.0817376f,0.0732484f},{0.0351704f,0.0835247f,0.0732484f}, -{0.0348854f,0.0829569f,0.0732484f},{0.0346707f,0.0823578f,0.0732484f},{0.0355373f,0.0840442f,0.0732484f}, -{0.0370084f,0.0852404f,0.0732484f},{0.0382048f,0.0856654f,0.0732484f},{0.0388351f,0.085752f,0.0732484f}, -{0.0394712f,0.0857519f,0.0732484f},{0.0375921f,0.0854939f,0.0732484f},{0.0401013f,0.0856652f,0.0732484f}, -{0.0407137f,0.0854936f,0.0732484f},{0.0418405f,0.0849096f,0.0732484f},{0.0412969f,0.0852402f,0.0732484f}, -{0.042334f,0.084508f,0.0732484f},{0.0434248f,0.0829572f,0.0732484f},{0.0427684f,0.0840431f,0.0732484f}, -{0.0431324f,0.0835222f,0.0732484f},{0.0436384f,0.0823587f,0.0732484f},{0.0437705f,0.0817364f,0.0732484f}, -{0.041574f,0.0797065f,0.0732484f},{0.0445347f,0.0811018f,0.0751128f},{0.0431881f,0.0834317f,0.0751128f}, -{0.0445347f,0.0811018f,0.0900281f},{0.0351171f,0.0834317f,0.0751128f},{0.0419082f,0.0806159f,0.080706f}, -{0.0412957f,0.079303f,0.080706f},{0.0415756f,0.0797026f,0.080706f},{0.0417819f,0.0801446f,0.080706f}, -{0.0401082f,0.0784733f,0.080706f},{0.0396375f,0.0783479f,0.080706f},{0.0405506f,0.0786785f,0.080706f}, -{0.0381948f,0.0784759f,0.080706f},{0.0386659f,0.0783484f,0.080706f},{0.0391526f,0.0783052f,0.080706f}, -{0.0373545f,0.0789629f,0.080706f},{0.0377533f,0.078683f,0.080706f},{0.0367312f,0.0797065f,0.080706f}, -{0.0370102f,0.0793075f,0.080706f},{0.0365256f,0.0801478f,0.080706f},{0.0363996f,0.0806167f,0.080706f}, -{0.0409506f,0.0789579f,0.080706f},{0.0391526f,0.0764408f,0.0900281f},{0.0418436f,0.0764408f,0.0751128f}, -{0.0418436f,0.0764408f,0.0900281f},{0.0346707f,0.0798458f,0.0918925f},{0.0391526f,0.0838984f,0.0918925f}, -{0.0359715f,0.0776949f,0.0918925f},{0.0364649f,0.0772937f,0.0918925f},{0.0355373f,0.0781595f,0.0918925f}, -{0.0351704f,0.0786789f,0.0918925f},{0.0388351f,0.0764516f,0.0918925f},{0.0382048f,0.0765382f,0.0918925f}, -{0.0375921f,0.0767097f,0.0918925f},{0.0407137f,0.07671f,0.0918925f},{0.0401013f,0.0765384f,0.0918925f}, -{0.0370084f,0.0769632f,0.0918925f},{0.0394712f,0.0764517f,0.0918925f},{0.0412969f,0.0769634f,0.0918925f}, -{0.0418405f,0.077294f,0.0918925f},{0.042334f,0.0776957f,0.0918925f},{0.0431324f,0.0786814f,0.0918925f}, -{0.0434248f,0.0792464f,0.0918925f},{0.0436384f,0.0798449f,0.0918925f},{0.0367296f,0.082501f,0.0918925f}, -{0.0365233f,0.082059f,0.0918925f},{0.0377546f,0.0835251f,0.0918925f},{0.0437705f,0.0804672f,0.0918925f}, -{0.0419056f,0.0815869f,0.0918925f},{0.0417795f,0.0820558f,0.0918925f},{0.041295f,0.0828961f,0.0918925f}, -{0.041574f,0.0824971f,0.0918925f},{0.0373546f,0.0832457f,0.0918925f},{0.0405519f,0.0835206f,0.0918925f}, -{0.0409507f,0.0832407f,0.0918925f},{0.0396393f,0.0838552f,0.0918925f},{0.0401104f,0.0837277f,0.0918925f}, -{0.0381969f,0.0837303f,0.0918925f},{0.0386677f,0.0838558f,0.0918925f},{0.0370095f,0.0829006f,0.0918925f}, -{0.036397f,0.0815877f,0.0918925f},{0.0345334f,0.080466f,0.0918925f},{0.0348854f,0.0792467f,0.0918925f}, -{0.0427684f,0.0781605f,0.0918925f},{0.0431881f,0.0787719f,0.0900281f},{0.034531f,0.0804963f,0.0900281f}, -{0.034847f,0.0793181f,0.0900281f},{0.0346506f,0.079901f,0.0900281f},{0.0356896f,0.0779832f,0.0900281f}, -{0.0381825f,0.0765432f,0.0900281f},{0.0372562f,0.0768446f,0.0900281f},{0.0418905f,0.0773294f,0.0900281f}, -{0.0401206f,0.0765423f,0.0900281f},{0.0426154f,0.0779809f,0.0900281f},{0.0434581f,0.0793182f,0.0900281f}, -{0.0436577f,0.079899f,0.0900281f},{0.0437748f,0.0804959f,0.0900281f},{0.041047f,0.0768428f,0.0900281f}, -{0.0364144f,0.0773301f,0.0900281f},{0.0401082f,0.0837303f,0.0844349f},{0.0386659f,0.0838552f,0.0844349f}, -{0.0381948f,0.0837277f,0.0844349f},{0.0365256f,0.0820558f,0.0844349f},{0.0391526f,0.0838984f,0.0844349f}, -{0.0396375f,0.0838558f,0.0844349f},{0.0370102f,0.0828961f,0.0844349f},{0.0367312f,0.0824971f,0.0844349f}, -{0.0377533f,0.0835206f,0.0844349f},{0.0373545f,0.0832407f,0.0844349f},{0.0363996f,0.0815869f,0.0844349f}, -{0.0405506f,0.0835251f,0.0844349f},{0.0412957f,0.0829006f,0.0844349f},{0.0409506f,0.0832457f,0.0844349f}, -{0.0415756f,0.082501f,0.0844349f},{0.0417819f,0.082059f,0.0844349f},{0.0419082f,0.0815877f,0.0844349f}, -{0.034531f,0.0817073f,0.0751128f},{0.034847f,0.0828855f,0.0751128f},{0.0346506f,0.0823026f,0.0751128f}, -{0.0356896f,0.0842204f,0.0751128f},{0.0381825f,0.0856604f,0.0751128f},{0.0372562f,0.0853591f,0.0751128f}, -{0.0418905f,0.0848742f,0.0751128f},{0.0401206f,0.0856613f,0.0751128f},{0.0426154f,0.0842227f,0.0751128f}, -{0.0434581f,0.0828854f,0.0751128f},{0.0436577f,0.0823046f,0.0751128f},{0.0437748f,0.0817077f,0.0751128f}, -{0.041047f,0.0853608f,0.0751128f},{0.0364144f,0.0848735f,0.0751128f},{-0.0396398f,-0.078348f,0.0732484f}, -{-0.0391526f,-0.0783052f,0.080706f},{-0.0386641f,-0.0783482f,0.0732484f},{-0.0381961f,-0.0784738f,0.080706f}, -{-0.0386654f,-0.078348f,0.080706f},{-0.0381949f,-0.0784743f,0.0732484f},{-0.037757f,-0.0786785f,0.080706f}, -{-0.0377553f,-0.0786791f,0.0732484f},{-0.0373576f,-0.0789577f,0.080706f},{-0.0370085f,-0.0793068f,0.0732484f}, -{-0.0370104f,-0.0793041f,0.080706f},{-0.0373549f,-0.0789596f,0.0732484f},{-0.0367293f,-0.0797062f,0.0732484f}, -{-0.0367299f,-0.0797045f,0.080706f},{-0.0365246f,-0.0801454f,0.0732484f},{-0.0365251f,-0.0801441f,0.080706f}, -{-0.036399f,-0.0806133f,0.080706f},{-0.036399f,-0.0806133f,0.0732484f},{-0.036356f,-0.0811018f,0.080706f}, -{-0.0396411f,-0.0783482f,0.080706f},{-0.0401103f,-0.0784743f,0.080706f},{-0.040109f,-0.0784738f,0.0732484f}, -{-0.0405482f,-0.0786785f,0.0732484f},{-0.0405499f,-0.0786791f,0.080706f},{-0.0409503f,-0.0789596f,0.080706f}, -{-0.0409476f,-0.0789577f,0.0732484f},{-0.0412967f,-0.0793068f,0.080706f},{-0.0412948f,-0.0793041f,0.0732484f}, -{-0.0415753f,-0.0797045f,0.0732484f},{-0.0415759f,-0.0797062f,0.080706f},{-0.0417806f,-0.0801454f,0.080706f}, -{-0.0417801f,-0.0801441f,0.0732484f},{-0.0419062f,-0.0806133f,0.080706f},{-0.0419062f,-0.0806133f,0.0732484f}, -{-0.0419492f,-0.0811018f,0.080706f},{-0.0431881f,-0.0834317f,0.0751128f},{-0.0431216f,-0.0835172f,0.0732484f}, -{-0.0427679f,-0.0840443f,0.0732484f},{-0.0388347f,-0.0857482f,0.0732484f},{-0.0391526f,-0.0857628f,0.0751128f}, -{-0.0394697f,-0.0857526f,0.0732484f},{-0.0434233f,-0.0829568f,0.0732484f},{-0.0434581f,-0.0828854f,0.0751128f}, -{-0.0436412f,-0.08236f,0.0732484f},{-0.0436577f,-0.0823046f,0.0751128f},{-0.0437656f,-0.0817356f,0.0732484f}, -{-0.0437748f,-0.0817077f,0.0751128f},{-0.0438136f,-0.0811018f,0.0732484f},{-0.0438134f,-0.0811018f,0.0751128f}, -{-0.0426154f,-0.0842227f,0.0751128f},{-0.0418905f,-0.0848742f,0.0751128f},{-0.0423324f,-0.0845067f,0.0732484f}, -{-0.0412969f,-0.0852426f,0.0732484f},{-0.0418383f,-0.0849075f,0.0732484f},{-0.0407092f,-0.0854821f,0.0732484f}, -{-0.041047f,-0.0853608f,0.0751128f},{-0.0401206f,-0.0856613f,0.0751128f},{-0.0400974f,-0.0856572f,0.0732484f}, -{-0.0375901f,-0.0854955f,0.0732484f},{-0.0372562f,-0.0853591f,0.0751128f},{-0.0381825f,-0.0856604f,0.0751128f}, -{-0.0382039f,-0.0856635f,0.0732484f},{-0.0359704f,-0.0845082f,0.0732484f},{-0.0364144f,-0.0848735f,0.0751128f}, -{-0.0364658f,-0.0849058f,0.0732484f},{-0.0370158f,-0.0852247f,0.0732484f},{-0.0351171f,-0.0834317f,0.0751128f}, -{-0.0351705f,-0.0835228f,0.0732484f},{-0.0348763f,-0.0829589f,0.0732484f},{-0.0356896f,-0.0842204f,0.0751128f}, -{-0.0355407f,-0.0840405f,0.0732484f},{-0.0346506f,-0.0823026f,0.0751128f},{-0.034683f,-0.0823534f,0.0732484f}, -{-0.0345353f,-0.0817359f,0.0732484f},{-0.034847f,-0.0828855f,0.0751128f},{-0.0344916f,-0.0811018f,0.0732484f}, -{-0.034531f,-0.0817073f,0.0751128f},{-0.0344918f,-0.0811018f,0.0751128f},{-0.0391526f,-0.0764408f,0.0900281f}, -{-0.0364616f,-0.0764408f,0.0751128f},{-0.0391526f,-0.0764408f,0.0751128f},{-0.0418436f,-0.0764408f,0.0751128f}, -{-0.0418436f,-0.0764408f,0.0900281f},{-0.0364616f,-0.0764408f,0.0900281f},{-0.0396398f,-0.0838556f,0.0918925f}, -{-0.0391526f,-0.0838984f,0.0918925f},{-0.0391526f,-0.0838984f,0.0844349f},{-0.0386641f,-0.0838554f,0.0918925f}, -{-0.0381961f,-0.0837298f,0.0844349f},{-0.0386654f,-0.0838556f,0.0844349f},{-0.0381949f,-0.0837293f,0.0918925f}, -{-0.037757f,-0.0835251f,0.0844349f},{-0.0377553f,-0.0835245f,0.0918925f},{-0.0373576f,-0.0832459f,0.0844349f}, -{-0.0370085f,-0.0828968f,0.0918925f},{-0.0370104f,-0.0828995f,0.0844349f},{-0.0373549f,-0.083244f,0.0918925f}, -{-0.0367293f,-0.0824974f,0.0918925f},{-0.0367299f,-0.0824991f,0.0844349f},{-0.0365246f,-0.0820583f,0.0918925f}, -{-0.0365251f,-0.0820595f,0.0844349f},{-0.036399f,-0.0815903f,0.0844349f},{-0.036399f,-0.0815903f,0.0918925f}, -{-0.036356f,-0.0811018f,0.0918925f},{-0.036356f,-0.0811018f,0.0844349f},{-0.0396411f,-0.0838554f,0.0844349f}, -{-0.0401103f,-0.0837293f,0.0844349f},{-0.040109f,-0.0837298f,0.0918925f},{-0.0405482f,-0.0835251f,0.0918925f}, -{-0.0405499f,-0.0835245f,0.0844349f},{-0.0409503f,-0.083244f,0.0844349f},{-0.0409476f,-0.0832459f,0.0918925f}, -{-0.0412967f,-0.0828968f,0.0844349f},{-0.0412948f,-0.0828995f,0.0918925f},{-0.0415753f,-0.0824991f,0.0918925f}, -{-0.0415759f,-0.0824974f,0.0844349f},{-0.0417806f,-0.0820583f,0.0844349f},{-0.0417801f,-0.0820595f,0.0918925f}, -{-0.0419062f,-0.0815903f,0.0844349f},{-0.0419062f,-0.0815903f,0.0918925f},{-0.0419492f,-0.0811018f,0.0918925f}, -{-0.0419492f,-0.0811018f,0.0844349f},{-0.0431881f,-0.0787719f,0.0900281f},{-0.0431216f,-0.0786864f,0.0918925f}, -{-0.0427679f,-0.0781593f,0.0918925f},{-0.0388347f,-0.0764554f,0.0918925f},{-0.0394697f,-0.076451f,0.0918925f}, -{-0.0434233f,-0.0792468f,0.0918925f},{-0.0434581f,-0.0793182f,0.0900281f},{-0.0436412f,-0.0798436f,0.0918925f}, -{-0.0436577f,-0.079899f,0.0900281f},{-0.0437656f,-0.080468f,0.0918925f},{-0.0437748f,-0.0804959f,0.0900281f}, -{-0.0438136f,-0.0811018f,0.0918925f},{-0.0438134f,-0.0811018f,0.0900281f},{-0.0426154f,-0.0779809f,0.0900281f}, -{-0.0418905f,-0.0773294f,0.0900281f},{-0.0423324f,-0.0776969f,0.0918925f},{-0.0412969f,-0.076961f,0.0918925f}, -{-0.0418383f,-0.0772961f,0.0918925f},{-0.0407092f,-0.0767215f,0.0918925f},{-0.041047f,-0.0768428f,0.0900281f}, -{-0.0401206f,-0.0765423f,0.0900281f},{-0.0400974f,-0.0765464f,0.0918925f},{-0.0375901f,-0.0767081f,0.0918925f}, -{-0.0372562f,-0.0768445f,0.0900281f},{-0.0381825f,-0.0765432f,0.0900281f},{-0.0382039f,-0.0765401f,0.0918925f}, -{-0.0359704f,-0.0776954f,0.0918925f},{-0.0364144f,-0.0773301f,0.0900281f},{-0.0364658f,-0.0772978f,0.0918925f}, -{-0.0370158f,-0.0769789f,0.0918925f},{-0.0351171f,-0.0787719f,0.0900281f},{-0.0351705f,-0.0786808f,0.0918925f}, -{-0.0348763f,-0.0792447f,0.0918925f},{-0.0356896f,-0.0779832f,0.0900281f},{-0.0355407f,-0.0781631f,0.0918925f}, -{-0.0346506f,-0.079901f,0.0900281f},{-0.034683f,-0.0798502f,0.0918925f},{-0.0345353f,-0.0804677f,0.0918925f}, -{-0.034847f,-0.0793181f,0.0900281f},{-0.0344916f,-0.0811018f,0.0918925f},{-0.034531f,-0.0804963f,0.0900281f}, -{-0.0344917f,-0.0811018f,0.0900281f},{-0.0445347f,-0.0811018f,0.0751128f},{-0.0431881f,-0.0834317f,0.0900281f}, -{-0.0418436f,-0.0857628f,0.0751128f},{-0.0418436f,-0.0857628f,0.0900281f},{-0.0445347f,-0.0811018f,0.0900281f}, -{-0.0365256f,-0.0820558f,0.0732484f},{-0.0363996f,-0.0815869f,0.0732484f},{-0.0423336f,-0.0776949f,0.0732484f}, -{-0.0418403f,-0.0772937f,0.0732484f},{-0.0373545f,-0.0832407f,0.0732484f},{-0.0370102f,-0.0828961f,0.0732484f}, -{-0.0386659f,-0.0838552f,0.0732484f},{-0.0381948f,-0.0837277f,0.0732484f},{-0.0377533f,-0.0835206f,0.0732484f}, -{-0.0396375f,-0.0838558f,0.0732484f},{-0.0401082f,-0.0837303f,0.0732484f},{-0.0405506f,-0.0835251f,0.0732484f}, -{-0.0417819f,-0.082059f,0.0732484f},{-0.0409506f,-0.0832457f,0.0732484f},{-0.0415756f,-0.082501f,0.0732484f}, -{-0.0412957f,-0.0829006f,0.0732484f},{-0.0419082f,-0.0815877f,0.0732484f},{-0.0437718f,-0.080466f,0.0732484f}, -{-0.0431348f,-0.0786789f,0.0732484f},{-0.0434198f,-0.0792467f,0.0732484f},{-0.0436345f,-0.0798458f,0.0732484f}, -{-0.0427679f,-0.0781594f,0.0732484f},{-0.0412968f,-0.0769632f,0.0732484f},{-0.0401004f,-0.0765382f,0.0732484f}, -{-0.0394701f,-0.0764516f,0.0732484f},{-0.038834f,-0.0764517f,0.0732484f},{-0.0407131f,-0.0767097f,0.0732484f}, -{-0.0382039f,-0.0765384f,0.0732484f},{-0.0375915f,-0.07671f,0.0732484f},{-0.0364646f,-0.077294f,0.0732484f}, -{-0.0370082f,-0.0769634f,0.0732484f},{-0.0359712f,-0.0776957f,0.0732484f},{-0.0348804f,-0.0792464f,0.0732484f}, -{-0.0355368f,-0.0781605f,0.0732484f},{-0.0351728f,-0.0786814f,0.0732484f},{-0.0346667f,-0.0798449f,0.0732484f}, -{-0.0345346f,-0.0804672f,0.0732484f},{-0.0367312f,-0.0824971f,0.0732484f},{-0.0337705f,-0.0811018f,0.0751128f}, -{-0.0351171f,-0.0787719f,0.0751128f},{-0.0337705f,-0.0811018f,0.0900281f},{-0.0431881f,-0.0787719f,0.0751128f}, -{-0.036397f,-0.0815877f,0.080706f},{-0.0370095f,-0.0829006f,0.080706f},{-0.0367296f,-0.082501f,0.080706f}, -{-0.0365233f,-0.082059f,0.080706f},{-0.0381969f,-0.0837303f,0.080706f},{-0.0386677f,-0.0838558f,0.080706f}, -{-0.0377546f,-0.0835251f,0.080706f},{-0.0401104f,-0.0837277f,0.080706f},{-0.0396392f,-0.0838552f,0.080706f}, -{-0.0391526f,-0.0838984f,0.080706f},{-0.0409507f,-0.0832407f,0.080706f},{-0.0405519f,-0.0835206f,0.080706f}, -{-0.041574f,-0.0824971f,0.080706f},{-0.041295f,-0.0828961f,0.080706f},{-0.0417795f,-0.0820558f,0.080706f}, -{-0.0419056f,-0.0815869f,0.080706f},{-0.0373546f,-0.0832457f,0.080706f},{-0.0391526f,-0.0857628f,0.0900281f}, -{-0.0364616f,-0.0857628f,0.0751128f},{-0.0364616f,-0.0857628f,0.0900281f},{-0.0436345f,-0.0823578f,0.0918925f}, -{-0.0391526f,-0.0783052f,0.0918925f},{-0.0423336f,-0.0845087f,0.0918925f},{-0.0418403f,-0.0849099f,0.0918925f}, -{-0.0427679f,-0.0840442f,0.0918925f},{-0.0431348f,-0.0835247f,0.0918925f},{-0.0394701f,-0.085752f,0.0918925f}, -{-0.0401004f,-0.0856654f,0.0918925f},{-0.0407131f,-0.0854939f,0.0918925f},{-0.0375915f,-0.0854936f,0.0918925f}, -{-0.0382039f,-0.0856652f,0.0918925f},{-0.0412968f,-0.0852404f,0.0918925f},{-0.038834f,-0.0857519f,0.0918925f}, -{-0.0370082f,-0.0852402f,0.0918925f},{-0.0364646f,-0.0849096f,0.0918925f},{-0.0359712f,-0.084508f,0.0918925f}, -{-0.0351728f,-0.0835222f,0.0918925f},{-0.0348804f,-0.0829572f,0.0918925f},{-0.0346667f,-0.0823587f,0.0918925f}, -{-0.0415756f,-0.0797026f,0.0918925f},{-0.0417819f,-0.0801446f,0.0918925f},{-0.0405506f,-0.0786785f,0.0918925f}, -{-0.0345346f,-0.0817364f,0.0918925f},{-0.0363996f,-0.0806167f,0.0918925f},{-0.0365256f,-0.0801478f,0.0918925f}, -{-0.0370102f,-0.0793075f,0.0918925f},{-0.0367312f,-0.0797065f,0.0918925f},{-0.0409506f,-0.0789579f,0.0918925f}, -{-0.0377533f,-0.078683f,0.0918925f},{-0.0373545f,-0.0789629f,0.0918925f},{-0.0386659f,-0.0783484f,0.0918925f}, -{-0.0381948f,-0.0784759f,0.0918925f},{-0.0401082f,-0.0784733f,0.0918925f},{-0.0396375f,-0.0783479f,0.0918925f}, -{-0.0412957f,-0.079303f,0.0918925f},{-0.0419082f,-0.0806159f,0.0918925f},{-0.0437718f,-0.0817376f,0.0918925f}, -{-0.0434198f,-0.0829569f,0.0918925f},{-0.0355368f,-0.0840431f,0.0918925f},{-0.0351171f,-0.0834317f,0.0900281f}, -{-0.0437742f,-0.0817073f,0.0900281f},{-0.0434582f,-0.0828855f,0.0900281f},{-0.0436546f,-0.0823026f,0.0900281f}, -{-0.0426156f,-0.0842204f,0.0900281f},{-0.0401226f,-0.0856604f,0.0900281f},{-0.041049f,-0.0853591f,0.0900281f}, -{-0.0364147f,-0.0848742f,0.0900281f},{-0.0381846f,-0.0856613f,0.0900281f},{-0.0356898f,-0.0842227f,0.0900281f}, -{-0.034847f,-0.0828854f,0.0900281f},{-0.0346475f,-0.0823046f,0.0900281f},{-0.0345304f,-0.0817077f,0.0900281f}, -{-0.0372582f,-0.0853608f,0.0900281f},{-0.0418908f,-0.0848735f,0.0900281f},{-0.0381969f,-0.0784733f,0.0844349f}, -{-0.0396392f,-0.0783484f,0.0844349f},{-0.0401104f,-0.0784759f,0.0844349f},{-0.0417795f,-0.0801478f,0.0844349f}, -{-0.0391526f,-0.0783052f,0.0844349f},{-0.0386677f,-0.0783479f,0.0844349f},{-0.041295f,-0.0793075f,0.0844349f}, -{-0.041574f,-0.0797065f,0.0844349f},{-0.0405519f,-0.078683f,0.0844349f},{-0.0409507f,-0.0789629f,0.0844349f}, -{-0.0419056f,-0.0806167f,0.0844349f},{-0.0377546f,-0.0786785f,0.0844349f},{-0.0370095f,-0.079303f,0.0844349f}, -{-0.0373546f,-0.0789579f,0.0844349f},{-0.0367296f,-0.0797026f,0.0844349f},{-0.0365233f,-0.0801446f,0.0844349f}, -{-0.036397f,-0.0806159f,0.0844349f},{-0.0437742f,-0.0804963f,0.0751128f},{-0.0434582f,-0.0793181f,0.0751128f}, -{-0.0436546f,-0.079901f,0.0751128f},{-0.0426156f,-0.0779832f,0.0751128f},{-0.0401226f,-0.0765432f,0.0751128f}, -{-0.041049f,-0.0768445f,0.0751128f},{-0.0364147f,-0.0773294f,0.0751128f},{-0.0381846f,-0.0765423f,0.0751128f}, -{-0.0356898f,-0.0779809f,0.0751128f},{-0.034847f,-0.0793182f,0.0751128f},{-0.0346475f,-0.079899f,0.0751128f}, -{-0.0345304f,-0.0804959f,0.0751128f},{-0.0372582f,-0.0768428f,0.0751128f},{-0.0418908f,-0.0773301f,0.0751128f}, -{-0.0396398f,0.0838556f,0.0732484f},{-0.0391526f,0.0838984f,0.080706f},{-0.0386641f,0.0838554f,0.0732484f}, -{-0.0381961f,0.0837298f,0.080706f},{-0.0386654f,0.0838556f,0.080706f},{-0.0381949f,0.0837293f,0.0732484f}, -{-0.037757f,0.0835251f,0.080706f},{-0.0377553f,0.0835245f,0.0732484f},{-0.0373576f,0.0832459f,0.080706f}, -{-0.0370085f,0.0828968f,0.0732484f},{-0.0370104f,0.0828995f,0.080706f},{-0.0373549f,0.083244f,0.0732484f}, -{-0.0367293f,0.0824974f,0.0732484f},{-0.0367299f,0.0824991f,0.080706f},{-0.0365246f,0.0820583f,0.0732484f}, -{-0.0365251f,0.0820595f,0.080706f},{-0.036399f,0.0815903f,0.080706f},{-0.036399f,0.0815903f,0.0732484f}, -{-0.036356f,0.0811018f,0.080706f},{-0.0396411f,0.0838554f,0.080706f},{-0.0401103f,0.0837293f,0.080706f}, -{-0.040109f,0.0837298f,0.0732484f},{-0.0405482f,0.0835251f,0.0732484f},{-0.0405499f,0.0835245f,0.080706f}, -{-0.0409503f,0.083244f,0.080706f},{-0.0409476f,0.0832459f,0.0732484f},{-0.0412967f,0.0828968f,0.080706f}, -{-0.0412948f,0.0828995f,0.0732484f},{-0.0415753f,0.0824991f,0.0732484f},{-0.0415759f,0.0824974f,0.080706f}, -{-0.0417806f,0.0820583f,0.080706f},{-0.0417801f,0.0820595f,0.0732484f},{-0.0419062f,0.0815903f,0.080706f}, -{-0.0419062f,0.0815903f,0.0732484f},{-0.0419492f,0.0811018f,0.080706f},{-0.0431881f,0.0787719f,0.0751128f}, -{-0.0431216f,0.0786864f,0.0732484f},{-0.0427679f,0.0781593f,0.0732484f},{-0.0388347f,0.0764554f,0.0732484f}, -{-0.0391526f,0.0764408f,0.0751128f},{-0.0394697f,0.076451f,0.0732484f},{-0.0434233f,0.0792468f,0.0732484f}, -{-0.0434581f,0.0793182f,0.0751128f},{-0.0436412f,0.0798436f,0.0732484f},{-0.0436577f,0.079899f,0.0751128f}, -{-0.0437656f,0.080468f,0.0732484f},{-0.0437748f,0.0804959f,0.0751128f},{-0.0438136f,0.0811018f,0.0732484f}, -{-0.0438134f,0.0811018f,0.0751128f},{-0.0426154f,0.0779809f,0.0751128f},{-0.0418905f,0.0773294f,0.0751128f}, -{-0.0423324f,0.0776969f,0.0732484f},{-0.0412969f,0.076961f,0.0732484f},{-0.0418383f,0.0772961f,0.0732484f}, -{-0.0407092f,0.0767216f,0.0732484f},{-0.041047f,0.0768428f,0.0751128f},{-0.0401206f,0.0765423f,0.0751128f}, -{-0.0400974f,0.0765464f,0.0732484f},{-0.0375901f,0.0767081f,0.0732484f},{-0.0372562f,0.0768446f,0.0751128f}, -{-0.0381825f,0.0765432f,0.0751128f},{-0.0382039f,0.0765401f,0.0732484f},{-0.0359704f,0.0776954f,0.0732484f}, -{-0.0364144f,0.0773301f,0.0751128f},{-0.0364658f,0.0772978f,0.0732484f},{-0.0370158f,0.0769789f,0.0732484f}, -{-0.0351171f,0.0787719f,0.0751128f},{-0.0351705f,0.0786808f,0.0732484f},{-0.0348763f,0.0792447f,0.0732484f}, -{-0.0356896f,0.0779832f,0.0751128f},{-0.0355407f,0.0781631f,0.0732484f},{-0.0346506f,0.079901f,0.0751128f}, -{-0.034683f,0.0798502f,0.0732484f},{-0.0345353f,0.0804677f,0.0732484f},{-0.034847f,0.0793181f,0.0751128f}, -{-0.0344916f,0.0811018f,0.0732484f},{-0.034531f,0.0804963f,0.0751128f},{-0.0344918f,0.0811018f,0.0751128f}, -{-0.0391526f,0.0857628f,0.0900281f},{-0.0364616f,0.0857628f,0.0751128f},{-0.0391526f,0.0857628f,0.0751128f}, -{-0.0418436f,0.0857628f,0.0751128f},{-0.0418436f,0.0857628f,0.0900281f},{-0.0364616f,0.0857628f,0.0900281f}, -{-0.0396398f,0.078348f,0.0918925f},{-0.0391526f,0.0783052f,0.0918925f},{-0.0391526f,0.0783052f,0.0844349f}, -{-0.0386641f,0.0783482f,0.0918925f},{-0.0381961f,0.0784738f,0.0844349f},{-0.0386654f,0.078348f,0.0844349f}, -{-0.0381949f,0.0784743f,0.0918925f},{-0.037757f,0.0786785f,0.0844349f},{-0.0377553f,0.0786791f,0.0918925f}, -{-0.0373576f,0.0789577f,0.0844349f},{-0.0370085f,0.0793068f,0.0918925f},{-0.0370104f,0.0793041f,0.0844349f}, -{-0.0373549f,0.0789596f,0.0918925f},{-0.0367293f,0.0797062f,0.0918925f},{-0.0367299f,0.0797045f,0.0844349f}, -{-0.0365246f,0.0801454f,0.0918925f},{-0.0365251f,0.0801441f,0.0844349f},{-0.036399f,0.0806133f,0.0844349f}, -{-0.036399f,0.0806133f,0.0918925f},{-0.036356f,0.0811018f,0.0918925f},{-0.036356f,0.0811018f,0.0844349f}, -{-0.0396411f,0.0783482f,0.0844349f},{-0.0401103f,0.0784743f,0.0844349f},{-0.040109f,0.0784738f,0.0918925f}, -{-0.0405482f,0.0786785f,0.0918925f},{-0.0405499f,0.0786791f,0.0844349f},{-0.0409503f,0.0789596f,0.0844349f}, -{-0.0409476f,0.0789577f,0.0918925f},{-0.0412967f,0.0793068f,0.0844349f},{-0.0412948f,0.0793041f,0.0918925f}, -{-0.0415753f,0.0797045f,0.0918925f},{-0.0415759f,0.0797062f,0.0844349f},{-0.0417806f,0.0801454f,0.0844349f}, -{-0.0417801f,0.0801441f,0.0918925f},{-0.0419062f,0.0806133f,0.0844349f},{-0.0419062f,0.0806133f,0.0918925f}, -{-0.0419492f,0.0811018f,0.0918925f},{-0.0419492f,0.0811018f,0.0844349f},{-0.0431881f,0.0834317f,0.0900281f}, -{-0.0431216f,0.0835172f,0.0918925f},{-0.0427679f,0.0840443f,0.0918925f},{-0.0388347f,0.0857482f,0.0918925f}, -{-0.0394697f,0.0857526f,0.0918925f},{-0.0434233f,0.0829568f,0.0918925f},{-0.0434581f,0.0828854f,0.0900281f}, -{-0.0436412f,0.08236f,0.0918925f},{-0.0436577f,0.0823046f,0.0900281f},{-0.0437656f,0.0817356f,0.0918925f}, -{-0.0437748f,0.0817077f,0.0900281f},{-0.0438136f,0.0811018f,0.0918925f},{-0.0438134f,0.0811018f,0.0900281f}, -{-0.0426154f,0.0842227f,0.0900281f},{-0.0418905f,0.0848742f,0.0900281f},{-0.0423324f,0.0845067f,0.0918925f}, -{-0.0412969f,0.0852426f,0.0918925f},{-0.0418383f,0.0849075f,0.0918925f},{-0.0407092f,0.0854821f,0.0918925f}, -{-0.041047f,0.0853608f,0.0900281f},{-0.0401206f,0.0856613f,0.0900281f},{-0.0400974f,0.0856572f,0.0918925f}, -{-0.0375901f,0.0854955f,0.0918925f},{-0.0372562f,0.0853591f,0.0900281f},{-0.0381825f,0.0856604f,0.0900281f}, -{-0.0382039f,0.0856635f,0.0918925f},{-0.0359704f,0.0845082f,0.0918925f},{-0.0364144f,0.0848735f,0.0900281f}, -{-0.0364658f,0.0849058f,0.0918925f},{-0.0370158f,0.0852247f,0.0918925f},{-0.0351171f,0.0834317f,0.0900281f}, -{-0.0351705f,0.0835228f,0.0918925f},{-0.0348763f,0.0829589f,0.0918925f},{-0.0356896f,0.0842204f,0.0900281f}, -{-0.0355407f,0.0840405f,0.0918925f},{-0.0346506f,0.0823026f,0.0900281f},{-0.034683f,0.0823534f,0.0918925f}, -{-0.0345353f,0.0817359f,0.0918925f},{-0.034847f,0.0828855f,0.0900281f},{-0.0344916f,0.0811018f,0.0918925f}, -{-0.034531f,0.0817073f,0.0900281f},{-0.0344917f,0.0811018f,0.0900281f},{-0.0445347f,0.0811018f,0.0751128f}, -{-0.0431881f,0.0787719f,0.0900281f},{-0.0418436f,0.0764408f,0.0751128f},{-0.0418436f,0.0764408f,0.0900281f}, -{-0.0445347f,0.0811018f,0.0900281f},{-0.0365256f,0.0801478f,0.0732484f},{-0.0363996f,0.0806167f,0.0732484f}, -{-0.0423336f,0.0845087f,0.0732484f},{-0.0418403f,0.0849099f,0.0732484f},{-0.0373545f,0.0789629f,0.0732484f}, -{-0.0370102f,0.0793075f,0.0732484f},{-0.0386659f,0.0783484f,0.0732484f},{-0.0381948f,0.0784759f,0.0732484f}, -{-0.0377533f,0.078683f,0.0732484f},{-0.0396375f,0.0783479f,0.0732484f},{-0.0401082f,0.0784733f,0.0732484f}, -{-0.0405506f,0.0786785f,0.0732484f},{-0.0417819f,0.0801446f,0.0732484f},{-0.0409506f,0.0789579f,0.0732484f}, -{-0.0415756f,0.0797026f,0.0732484f},{-0.0412957f,0.079303f,0.0732484f},{-0.0419082f,0.0806159f,0.0732484f}, -{-0.0437718f,0.0817376f,0.0732484f},{-0.0431348f,0.0835247f,0.0732484f},{-0.0434198f,0.0829569f,0.0732484f}, -{-0.0436345f,0.0823578f,0.0732484f},{-0.0427679f,0.0840442f,0.0732484f},{-0.0412968f,0.0852404f,0.0732484f}, -{-0.0401004f,0.0856654f,0.0732484f},{-0.0394701f,0.085752f,0.0732484f},{-0.038834f,0.0857519f,0.0732484f}, -{-0.0407131f,0.0854939f,0.0732484f},{-0.0382039f,0.0856652f,0.0732484f},{-0.0375915f,0.0854936f,0.0732484f}, -{-0.0364646f,0.0849096f,0.0732484f},{-0.0370082f,0.0852402f,0.0732484f},{-0.0359712f,0.084508f,0.0732484f}, -{-0.0348804f,0.0829572f,0.0732484f},{-0.0355368f,0.0840431f,0.0732484f},{-0.0351728f,0.0835222f,0.0732484f}, -{-0.0346667f,0.0823587f,0.0732484f},{-0.0345346f,0.0817364f,0.0732484f},{-0.0367312f,0.0797065f,0.0732484f}, -{-0.0337705f,0.0811018f,0.0751128f},{-0.0351171f,0.0834317f,0.0751128f},{-0.0337705f,0.0811018f,0.0900281f}, -{-0.0431881f,0.0834317f,0.0751128f},{-0.036397f,0.0806159f,0.080706f},{-0.0370095f,0.079303f,0.080706f}, -{-0.0367296f,0.0797026f,0.080706f},{-0.0365233f,0.0801446f,0.080706f},{-0.0381969f,0.0784733f,0.080706f}, -{-0.0386677f,0.0783479f,0.080706f},{-0.0377546f,0.0786785f,0.080706f},{-0.0401104f,0.0784759f,0.080706f}, -{-0.0396392f,0.0783484f,0.080706f},{-0.0391526f,0.0783052f,0.080706f},{-0.0409507f,0.0789629f,0.080706f}, -{-0.0405519f,0.078683f,0.080706f},{-0.041574f,0.0797065f,0.080706f},{-0.041295f,0.0793075f,0.080706f}, -{-0.0417795f,0.0801478f,0.080706f},{-0.0419056f,0.0806167f,0.080706f},{-0.0373546f,0.0789579f,0.080706f}, -{-0.0391526f,0.0764408f,0.0900281f},{-0.0364616f,0.0764408f,0.0751128f},{-0.0364616f,0.0764408f,0.0900281f}, -{-0.0436345f,0.0798458f,0.0918925f},{-0.0391526f,0.0838984f,0.0918925f},{-0.0423336f,0.0776949f,0.0918925f}, -{-0.0418403f,0.0772937f,0.0918925f},{-0.0427679f,0.0781595f,0.0918925f},{-0.0431348f,0.0786789f,0.0918925f}, -{-0.0394701f,0.0764516f,0.0918925f},{-0.0401004f,0.0765382f,0.0918925f},{-0.0407131f,0.0767097f,0.0918925f}, -{-0.0375915f,0.07671f,0.0918925f},{-0.0382039f,0.0765384f,0.0918925f},{-0.0412968f,0.0769632f,0.0918925f}, -{-0.038834f,0.0764517f,0.0918925f},{-0.0370082f,0.0769634f,0.0918925f},{-0.0364646f,0.077294f,0.0918925f}, -{-0.0359712f,0.0776957f,0.0918925f},{-0.0351728f,0.0786814f,0.0918925f},{-0.0348804f,0.0792464f,0.0918925f}, -{-0.0346667f,0.0798449f,0.0918925f},{-0.0415756f,0.082501f,0.0918925f},{-0.0417819f,0.082059f,0.0918925f}, -{-0.0405506f,0.0835251f,0.0918925f},{-0.0345346f,0.0804672f,0.0918925f},{-0.0363996f,0.0815869f,0.0918925f}, -{-0.0365256f,0.0820558f,0.0918925f},{-0.0370102f,0.0828961f,0.0918925f},{-0.0367312f,0.0824971f,0.0918925f}, -{-0.0409506f,0.0832457f,0.0918925f},{-0.0377533f,0.0835206f,0.0918925f},{-0.0373545f,0.0832407f,0.0918925f}, -{-0.0386659f,0.0838552f,0.0918925f},{-0.0381948f,0.0837277f,0.0918925f},{-0.0401082f,0.0837303f,0.0918925f}, -{-0.0396375f,0.0838558f,0.0918925f},{-0.0412957f,0.0829006f,0.0918925f},{-0.0419082f,0.0815877f,0.0918925f}, -{-0.0437718f,0.080466f,0.0918925f},{-0.0434198f,0.0792467f,0.0918925f},{-0.0355368f,0.0781605f,0.0918925f}, -{-0.0351171f,0.0787719f,0.0900281f},{-0.0437742f,0.0804963f,0.0900281f},{-0.0434582f,0.0793181f,0.0900281f}, -{-0.0436546f,0.079901f,0.0900281f},{-0.0426156f,0.0779832f,0.0900281f},{-0.0401226f,0.0765432f,0.0900281f}, -{-0.041049f,0.0768446f,0.0900281f},{-0.0364147f,0.0773294f,0.0900281f},{-0.0381846f,0.0765423f,0.0900281f}, -{-0.0356898f,0.0779809f,0.0900281f},{-0.034847f,0.0793182f,0.0900281f},{-0.0346475f,0.079899f,0.0900281f}, -{-0.0345304f,0.0804959f,0.0900281f},{-0.0372582f,0.0768428f,0.0900281f},{-0.0418908f,0.0773301f,0.0900281f}, -{-0.0381969f,0.0837303f,0.0844349f},{-0.0396392f,0.0838552f,0.0844349f},{-0.0401104f,0.0837277f,0.0844349f}, -{-0.0417795f,0.0820558f,0.0844349f},{-0.0391526f,0.0838984f,0.0844349f},{-0.0386677f,0.0838558f,0.0844349f}, -{-0.041295f,0.0828961f,0.0844349f},{-0.041574f,0.0824971f,0.0844349f},{-0.0405519f,0.0835206f,0.0844349f}, -{-0.0409507f,0.0832407f,0.0844349f},{-0.0419056f,0.0815869f,0.0844349f},{-0.0377546f,0.0835251f,0.0844349f}, -{-0.0370095f,0.0829006f,0.0844349f},{-0.0373546f,0.0832457f,0.0844349f},{-0.0367296f,0.082501f,0.0844349f}, -{-0.0365233f,0.082059f,0.0844349f},{-0.036397f,0.0815877f,0.0844349f},{-0.0437742f,0.0817073f,0.0751128f}, -{-0.0434582f,0.0828855f,0.0751128f},{-0.0436546f,0.0823026f,0.0751128f},{-0.0426156f,0.0842204f,0.0751128f}, -{-0.0401226f,0.0856604f,0.0751128f},{-0.041049f,0.0853591f,0.0751128f},{-0.0364147f,0.0848742f,0.0751128f}, -{-0.0381846f,0.0856613f,0.0751128f},{-0.0356898f,0.0842227f,0.0751128f},{-0.034847f,0.0828854f,0.0751128f}, -{-0.0346475f,0.0823046f,0.0751128f},{-0.0345304f,0.0817077f,0.0751128f},{-0.0372582f,0.0853608f,0.0751128f}, -{-0.0418908f,0.0848735f,0.0751128f},{0.0386654f,-0.078348f,0.0732484f},{0.0391526f,-0.0783052f,0.080706f}, -{0.0396411f,-0.0783482f,0.0732484f},{0.040109f,-0.0784738f,0.080706f},{0.0396398f,-0.078348f,0.080706f}, -{0.0401103f,-0.0784743f,0.0732484f},{0.0405482f,-0.0786785f,0.080706f},{0.0405499f,-0.0786791f,0.0732484f}, -{0.0409476f,-0.0789577f,0.080706f},{0.0412967f,-0.0793068f,0.0732484f},{0.0412948f,-0.0793041f,0.080706f}, -{0.0409503f,-0.0789596f,0.0732484f},{0.0415759f,-0.0797062f,0.0732484f},{0.0415753f,-0.0797045f,0.080706f}, -{0.0417806f,-0.0801454f,0.0732484f},{0.0417801f,-0.0801441f,0.080706f},{0.0419062f,-0.0806133f,0.080706f}, -{0.0419062f,-0.0806133f,0.0732484f},{0.0419492f,-0.0811018f,0.080706f},{0.0386641f,-0.0783482f,0.080706f}, -{0.0381949f,-0.0784743f,0.080706f},{0.0381961f,-0.0784738f,0.0732484f},{0.037757f,-0.0786785f,0.0732484f}, -{0.0377553f,-0.0786791f,0.080706f},{0.0373549f,-0.0789596f,0.080706f},{0.0373576f,-0.0789577f,0.0732484f}, -{0.0370085f,-0.0793068f,0.080706f},{0.0370104f,-0.0793041f,0.0732484f},{0.0367299f,-0.0797045f,0.0732484f}, -{0.0367293f,-0.0797062f,0.080706f},{0.0365246f,-0.0801454f,0.080706f},{0.0365251f,-0.0801441f,0.0732484f}, -{0.036399f,-0.0806133f,0.080706f},{0.036399f,-0.0806133f,0.0732484f},{0.036356f,-0.0811018f,0.080706f}, -{0.0351171f,-0.0834317f,0.0751128f},{0.0351836f,-0.0835172f,0.0732484f},{0.0355373f,-0.0840443f,0.0732484f}, -{0.0394705f,-0.0857482f,0.0732484f},{0.0391526f,-0.0857628f,0.0751128f},{0.0388355f,-0.0857526f,0.0732484f}, -{0.0348819f,-0.0829568f,0.0732484f},{0.034847f,-0.0828854f,0.0751128f},{0.034664f,-0.08236f,0.0732484f}, -{0.0346475f,-0.0823046f,0.0751128f},{0.0345395f,-0.0817356f,0.0732484f},{0.0345304f,-0.0817077f,0.0751128f}, -{0.0344916f,-0.0811018f,0.0732484f},{0.0344918f,-0.0811018f,0.0751128f},{0.0356898f,-0.0842227f,0.0751128f}, -{0.0364147f,-0.0848742f,0.0751128f},{0.0359728f,-0.0845067f,0.0732484f},{0.0370083f,-0.0852426f,0.0732484f}, -{0.0364669f,-0.0849075f,0.0732484f},{0.037596f,-0.0854821f,0.0732484f},{0.0372582f,-0.0853608f,0.0751128f}, -{0.0381846f,-0.0856613f,0.0751128f},{0.0382078f,-0.0856572f,0.0732484f},{0.0407151f,-0.0854955f,0.0732484f}, -{0.041049f,-0.0853591f,0.0751128f},{0.0401226f,-0.0856604f,0.0751128f},{0.0401013f,-0.0856635f,0.0732484f}, -{0.0423348f,-0.0845082f,0.0732484f},{0.0418908f,-0.0848735f,0.0751128f},{0.0418394f,-0.0849058f,0.0732484f}, -{0.0412894f,-0.0852247f,0.0732484f},{0.0431881f,-0.0834317f,0.0751128f},{0.0431347f,-0.0835228f,0.0732484f}, -{0.0434289f,-0.0829589f,0.0732484f},{0.0426156f,-0.0842204f,0.0751128f},{0.0427645f,-0.0840405f,0.0732484f}, -{0.0436546f,-0.0823026f,0.0751128f},{0.0436222f,-0.0823534f,0.0732484f},{0.0437699f,-0.0817359f,0.0732484f}, -{0.0434582f,-0.0828855f,0.0751128f},{0.0438136f,-0.0811018f,0.0732484f},{0.0437742f,-0.0817073f,0.0751128f}, -{0.0438134f,-0.0811018f,0.0751128f},{0.0391526f,-0.0764408f,0.0900281f},{0.0418436f,-0.0764408f,0.0751128f}, -{0.0391526f,-0.0764408f,0.0751128f},{0.0364616f,-0.0764408f,0.0751128f},{0.0364616f,-0.0764408f,0.0900281f}, -{0.0418436f,-0.0764408f,0.0900281f},{0.0386654f,-0.0838556f,0.0918925f},{0.0391526f,-0.0838984f,0.0918925f}, -{0.0391526f,-0.0838984f,0.0844349f},{0.0396411f,-0.0838554f,0.0918925f},{0.040109f,-0.0837298f,0.0844349f}, -{0.0396398f,-0.0838556f,0.0844349f},{0.0401103f,-0.0837293f,0.0918925f},{0.0405482f,-0.0835251f,0.0844349f}, -{0.0405499f,-0.0835245f,0.0918925f},{0.0409476f,-0.0832459f,0.0844349f},{0.0412967f,-0.0828968f,0.0918925f}, -{0.0412948f,-0.0828995f,0.0844349f},{0.0409503f,-0.083244f,0.0918925f},{0.0415759f,-0.0824974f,0.0918925f}, -{0.0415753f,-0.0824991f,0.0844349f},{0.0417806f,-0.0820583f,0.0918925f},{0.0417801f,-0.0820595f,0.0844349f}, -{0.0419062f,-0.0815903f,0.0844349f},{0.0419062f,-0.0815903f,0.0918925f},{0.0419492f,-0.0811018f,0.0918925f}, -{0.0419492f,-0.0811018f,0.0844349f},{0.0386641f,-0.0838554f,0.0844349f},{0.0381949f,-0.0837293f,0.0844349f}, -{0.0381961f,-0.0837298f,0.0918925f},{0.037757f,-0.0835251f,0.0918925f},{0.0377553f,-0.0835245f,0.0844349f}, -{0.0373549f,-0.083244f,0.0844349f},{0.0373576f,-0.0832459f,0.0918925f},{0.0370085f,-0.0828968f,0.0844349f}, -{0.0370104f,-0.0828995f,0.0918925f},{0.0367299f,-0.0824991f,0.0918925f},{0.0367293f,-0.0824974f,0.0844349f}, -{0.0365246f,-0.0820583f,0.0844349f},{0.0365251f,-0.0820595f,0.0918925f},{0.036399f,-0.0815903f,0.0844349f}, -{0.036399f,-0.0815903f,0.0918925f},{0.036356f,-0.0811018f,0.0918925f},{0.036356f,-0.0811018f,0.0844349f}, -{0.0351171f,-0.0787719f,0.0900281f},{0.0351836f,-0.0786864f,0.0918925f},{0.0355373f,-0.0781593f,0.0918925f}, -{0.0394705f,-0.0764554f,0.0918925f},{0.0388355f,-0.076451f,0.0918925f},{0.0348819f,-0.0792468f,0.0918925f}, -{0.034847f,-0.0793182f,0.0900281f},{0.034664f,-0.0798436f,0.0918925f},{0.0346475f,-0.079899f,0.0900281f}, -{0.0345395f,-0.080468f,0.0918925f},{0.0345304f,-0.0804959f,0.0900281f},{0.0344916f,-0.0811018f,0.0918925f}, -{0.0344917f,-0.0811018f,0.0900281f},{0.0356898f,-0.0779809f,0.0900281f},{0.0364147f,-0.0773294f,0.0900281f}, -{0.0359728f,-0.0776969f,0.0918925f},{0.0370083f,-0.076961f,0.0918925f},{0.0364669f,-0.0772961f,0.0918925f}, -{0.037596f,-0.0767215f,0.0918925f},{0.0372582f,-0.0768428f,0.0900281f},{0.0381846f,-0.0765423f,0.0900281f}, -{0.0382078f,-0.0765464f,0.0918925f},{0.0407151f,-0.0767081f,0.0918925f},{0.041049f,-0.0768445f,0.0900281f}, -{0.0401226f,-0.0765432f,0.0900281f},{0.0401013f,-0.0765401f,0.0918925f},{0.0423348f,-0.0776954f,0.0918925f}, -{0.0418908f,-0.0773301f,0.0900281f},{0.0418394f,-0.0772978f,0.0918925f},{0.0412894f,-0.0769789f,0.0918925f}, -{0.0431881f,-0.0787719f,0.0900281f},{0.0431347f,-0.0786808f,0.0918925f},{0.0434289f,-0.0792447f,0.0918925f}, -{0.0426156f,-0.0779832f,0.0900281f},{0.0427645f,-0.0781631f,0.0918925f},{0.0436546f,-0.079901f,0.0900281f}, -{0.0436222f,-0.0798502f,0.0918925f},{0.0437699f,-0.0804677f,0.0918925f},{0.0434582f,-0.0793181f,0.0900281f}, -{0.0438136f,-0.0811018f,0.0918925f},{0.0437742f,-0.0804963f,0.0900281f},{0.0438134f,-0.0811018f,0.0900281f}, -{0.0337705f,-0.0811018f,0.0751128f},{0.0351171f,-0.0834317f,0.0900281f},{0.0364616f,-0.0857628f,0.0751128f}, -{0.0364616f,-0.0857628f,0.0900281f},{0.0337705f,-0.0811018f,0.0900281f},{0.0417795f,-0.0820558f,0.0732484f}, -{0.0419056f,-0.0815869f,0.0732484f},{0.0359715f,-0.0776949f,0.0732484f},{0.0364649f,-0.0772937f,0.0732484f}, -{0.0409507f,-0.0832407f,0.0732484f},{0.041295f,-0.0828961f,0.0732484f},{0.0396393f,-0.0838552f,0.0732484f}, -{0.0401104f,-0.0837277f,0.0732484f},{0.0405519f,-0.0835206f,0.0732484f},{0.0386677f,-0.0838558f,0.0732484f}, -{0.0381969f,-0.0837303f,0.0732484f},{0.0377546f,-0.0835251f,0.0732484f},{0.0365233f,-0.082059f,0.0732484f}, -{0.0373546f,-0.0832457f,0.0732484f},{0.0367296f,-0.082501f,0.0732484f},{0.0370095f,-0.0829006f,0.0732484f}, -{0.036397f,-0.0815877f,0.0732484f},{0.0345334f,-0.080466f,0.0732484f},{0.0351704f,-0.0786789f,0.0732484f}, -{0.0348854f,-0.0792467f,0.0732484f},{0.0346707f,-0.0798458f,0.0732484f},{0.0355373f,-0.0781594f,0.0732484f}, -{0.0370084f,-0.0769632f,0.0732484f},{0.0382048f,-0.0765382f,0.0732484f},{0.0388351f,-0.0764516f,0.0732484f}, -{0.0394712f,-0.0764517f,0.0732484f},{0.0375921f,-0.0767097f,0.0732484f},{0.0401013f,-0.0765384f,0.0732484f}, -{0.0407137f,-0.07671f,0.0732484f},{0.0418405f,-0.077294f,0.0732484f},{0.0412969f,-0.0769634f,0.0732484f}, -{0.042334f,-0.0776957f,0.0732484f},{0.0434248f,-0.0792464f,0.0732484f},{0.0427684f,-0.0781605f,0.0732484f}, -{0.0431324f,-0.0786814f,0.0732484f},{0.0436384f,-0.0798449f,0.0732484f},{0.0437705f,-0.0804672f,0.0732484f}, -{0.041574f,-0.0824971f,0.0732484f},{0.0445347f,-0.0811018f,0.0751128f},{0.0431881f,-0.0787719f,0.0751128f}, -{0.0445347f,-0.0811018f,0.0900281f},{0.0351171f,-0.0787719f,0.0751128f},{0.0419082f,-0.0815877f,0.080706f}, -{0.0412957f,-0.0829006f,0.080706f},{0.0415756f,-0.082501f,0.080706f},{0.0417819f,-0.082059f,0.080706f}, -{0.0401082f,-0.0837303f,0.080706f},{0.0396375f,-0.0838558f,0.080706f},{0.0405506f,-0.0835251f,0.080706f}, -{0.0381948f,-0.0837277f,0.080706f},{0.0386659f,-0.0838552f,0.080706f},{0.0391526f,-0.0838984f,0.080706f}, -{0.0373545f,-0.0832407f,0.080706f},{0.0377533f,-0.0835206f,0.080706f},{0.0367312f,-0.0824971f,0.080706f}, -{0.0370102f,-0.0828961f,0.080706f},{0.0365256f,-0.0820558f,0.080706f},{0.0363996f,-0.0815869f,0.080706f}, -{0.0409506f,-0.0832457f,0.080706f},{0.0391526f,-0.0857628f,0.0900281f},{0.0418436f,-0.0857628f,0.0751128f}, -{0.0418436f,-0.0857628f,0.0900281f},{0.0346707f,-0.0823578f,0.0918925f},{0.0391526f,-0.0783052f,0.0918925f}, -{0.0359715f,-0.0845087f,0.0918925f},{0.0364649f,-0.0849099f,0.0918925f},{0.0355373f,-0.0840442f,0.0918925f}, -{0.0351704f,-0.0835247f,0.0918925f},{0.0388351f,-0.085752f,0.0918925f},{0.0382048f,-0.0856654f,0.0918925f}, -{0.0375921f,-0.0854939f,0.0918925f},{0.0407137f,-0.0854936f,0.0918925f},{0.0401013f,-0.0856652f,0.0918925f}, -{0.0370084f,-0.0852404f,0.0918925f},{0.0394712f,-0.0857519f,0.0918925f},{0.0412969f,-0.0852402f,0.0918925f}, -{0.0418405f,-0.0849096f,0.0918925f},{0.042334f,-0.084508f,0.0918925f},{0.0431324f,-0.0835222f,0.0918925f}, -{0.0434248f,-0.0829572f,0.0918925f},{0.0436384f,-0.0823587f,0.0918925f},{0.0367296f,-0.0797026f,0.0918925f}, -{0.0365233f,-0.0801446f,0.0918925f},{0.0377546f,-0.0786785f,0.0918925f},{0.0437705f,-0.0817364f,0.0918925f}, -{0.0419056f,-0.0806167f,0.0918925f},{0.0417795f,-0.0801478f,0.0918925f},{0.041295f,-0.0793075f,0.0918925f}, -{0.041574f,-0.0797065f,0.0918925f},{0.0373546f,-0.0789579f,0.0918925f},{0.0405519f,-0.078683f,0.0918925f}, -{0.0409507f,-0.0789629f,0.0918925f},{0.0396393f,-0.0783484f,0.0918925f},{0.0401104f,-0.0784759f,0.0918925f}, -{0.0381969f,-0.0784733f,0.0918925f},{0.0386677f,-0.0783479f,0.0918925f},{0.0370095f,-0.079303f,0.0918925f}, -{0.036397f,-0.0806159f,0.0918925f},{0.0345334f,-0.0817376f,0.0918925f},{0.0348854f,-0.0829569f,0.0918925f}, -{0.0427684f,-0.0840431f,0.0918925f},{0.0431881f,-0.0834317f,0.0900281f},{0.034531f,-0.0817073f,0.0900281f}, -{0.034847f,-0.0828855f,0.0900281f},{0.0346506f,-0.0823026f,0.0900281f},{0.0356896f,-0.0842204f,0.0900281f}, -{0.0381825f,-0.0856604f,0.0900281f},{0.0372562f,-0.0853591f,0.0900281f},{0.0418905f,-0.0848742f,0.0900281f}, -{0.0401206f,-0.0856613f,0.0900281f},{0.0426154f,-0.0842227f,0.0900281f},{0.0434581f,-0.0828854f,0.0900281f}, -{0.0436577f,-0.0823046f,0.0900281f},{0.0437748f,-0.0817077f,0.0900281f},{0.041047f,-0.0853608f,0.0900281f}, -{0.0364144f,-0.0848735f,0.0900281f},{0.0401082f,-0.0784733f,0.0844349f},{0.0386659f,-0.0783484f,0.0844349f}, -{0.0381948f,-0.0784759f,0.0844349f},{0.0365256f,-0.0801478f,0.0844349f},{0.0391526f,-0.0783052f,0.0844349f}, -{0.0396375f,-0.0783479f,0.0844349f},{0.0370102f,-0.0793075f,0.0844349f},{0.0367312f,-0.0797065f,0.0844349f}, -{0.0377533f,-0.078683f,0.0844349f},{0.0373545f,-0.0789629f,0.0844349f},{0.0363996f,-0.0806167f,0.0844349f}, -{0.0405506f,-0.0786785f,0.0844349f},{0.0412957f,-0.079303f,0.0844349f},{0.0409506f,-0.0789579f,0.0844349f}, -{0.0415756f,-0.0797026f,0.0844349f},{0.0417819f,-0.0801446f,0.0844349f},{0.0419082f,-0.0806159f,0.0844349f}, -{0.034531f,-0.0804963f,0.0751128f},{0.034847f,-0.0793181f,0.0751128f},{0.0346506f,-0.079901f,0.0751128f}, -{0.0356896f,-0.0779832f,0.0751128f},{0.0381825f,-0.0765432f,0.0751128f},{0.0372562f,-0.0768445f,0.0751128f}, -{0.0418905f,-0.0773294f,0.0751128f},{0.0401206f,-0.0765423f,0.0751128f},{0.0426154f,-0.0779809f,0.0751128f}, -{0.0434581f,-0.0793182f,0.0751128f},{0.0436577f,-0.079899f,0.0751128f},{0.0437748f,-0.0804959f,0.0751128f}, -{0.041047f,-0.0768428f,0.0751128f},{0.0364144f,-0.0773301f,0.0751128f},{0.0205353f,-0.305423f,0.0918925f}, -{0.0197119f,-0.306322f,0.0918925f},{0.0197119f,-0.306322f,0.100469f},{0.018681f,-0.306977f,0.0918925f}, -{0.0175301f,-0.30734f,0.100469f},{0.0186838f,-0.306976f,0.100469f},{0.0163096f,-0.307394f,0.0918925f}, -{0.0163096f,-0.307394f,0.100469f},{0.0175273f,-0.307341f,0.0918925f},{0.0205366f,-0.30542f,0.100469f}, -{0.0210952f,-0.304347f,0.100469f},{0.0210939f,-0.30435f,0.0918925f},{0.0213591f,-0.303157f,0.0918925f}, -{0.0213591f,-0.303157f,0.100469f},{0.0124916f,-0.297856f,0.0918925f},{0.0131454f,-0.29683f,0.0918925f}, -{0.0131452f,-0.29683f,0.100469f},{0.014044f,-0.296007f,0.0918925f},{0.01512f,-0.295447f,0.100469f}, -{0.0140418f,-0.296008f,0.100469f},{0.0163096f,-0.295183f,0.0918925f},{0.0163096f,-0.295183f,0.100469f}, -{0.0151227f,-0.295446f,0.0918925f},{0.0124909f,-0.297858f,0.100469f},{0.0121253f,-0.299018f,0.100469f}, -{0.0121261f,-0.299015f,0.0918925f},{0.012073f,-0.300232f,0.0918925f},{0.012073f,-0.300232f,0.100469f}, -{-0.305423f,-0.0205353f,0.0918925f},{-0.306322f,-0.0197119f,0.0918925f},{-0.306322f,-0.0197119f,0.100469f}, -{-0.306977f,-0.018681f,0.0918925f},{-0.30734f,-0.0175301f,0.100469f},{-0.306976f,-0.0186838f,0.100469f}, -{-0.307394f,-0.0163096f,0.0918925f},{-0.307394f,-0.0163096f,0.100469f},{-0.307341f,-0.0175273f,0.0918925f}, -{-0.30542f,-0.0205366f,0.100469f},{-0.304347f,-0.0210952f,0.100469f},{-0.30435f,-0.0210939f,0.0918925f}, -{-0.303157f,-0.0213591f,0.0918925f},{-0.303157f,-0.0213591f,0.100469f},{-0.297855f,-0.0124921f,0.0918925f}, -{-0.29683f,-0.0131453f,0.0918925f},{-0.29683f,-0.0131452f,0.100469f},{-0.296007f,-0.0140439f,0.0918925f}, -{-0.295447f,-0.01512f,0.100469f},{-0.296009f,-0.0140413f,0.100469f},{-0.295183f,-0.0163096f,0.0918925f}, -{-0.295183f,-0.0163096f,0.100469f},{-0.295446f,-0.0151233f,0.0918925f},{-0.297858f,-0.0124909f,0.100469f}, -{-0.299018f,-0.0121254f,0.100469f},{-0.299015f,-0.012126f,0.0918925f},{-0.300232f,-0.012073f,0.0918925f}, -{-0.300232f,-0.012073f,0.100469f},{-0.0205353f,0.305423f,0.0918925f},{-0.0197119f,0.306322f,0.0918925f}, -{-0.0197119f,0.306322f,0.100469f},{-0.018681f,0.306977f,0.0918925f},{-0.0175301f,0.30734f,0.100469f}, -{-0.0186838f,0.306976f,0.100469f},{-0.0163096f,0.307394f,0.0918925f},{-0.0163096f,0.307394f,0.100469f}, -{-0.0175273f,0.307341f,0.0918925f},{-0.0205366f,0.30542f,0.100469f},{-0.0210952f,0.304347f,0.100469f}, -{-0.0210939f,0.30435f,0.0918925f},{-0.0213591f,0.303157f,0.0918925f},{-0.0213591f,0.303157f,0.100469f}, -{-0.0124916f,0.297856f,0.0918925f},{-0.0131454f,0.29683f,0.0918925f},{-0.0131452f,0.29683f,0.100469f}, -{-0.014044f,0.296007f,0.0918925f},{-0.01512f,0.295447f,0.100469f},{-0.0140418f,0.296008f,0.100469f}, -{-0.0163096f,0.295183f,0.0918925f},{-0.0163096f,0.295183f,0.100469f},{-0.0151227f,0.295446f,0.0918925f}, -{-0.0124909f,0.297858f,0.100469f},{-0.0121253f,0.299018f,0.100469f},{-0.0121261f,0.299015f,0.0918925f}, -{-0.012073f,0.300232f,0.0918925f},{-0.012073f,0.300232f,0.100469f},{-0.00413429f,-0.321824f,0.0918925f}, -{-0.005033f,-0.321f,0.0918925f},{-0.005033f,-0.321f,0.100469f},{-0.00568869f,-0.31997f,0.0918925f}, -{-0.00605158f,-0.318819f,0.100469f},{-0.00568781f,-0.319972f,0.100469f},{-0.00610573f,-0.317598f,0.0918925f}, -{-0.00610573f,-0.317598f,0.100469f},{-0.00605247f,-0.318816f,0.0918925f},{-0.00413168f,-0.321825f,0.100469f}, -{-0.00305863f,-0.322384f,0.100469f},{-0.00306124f,-0.322382f,0.0918925f},{-0.00186868f,-0.322648f,0.0918925f}, -{-0.00186868f,-0.322648f,0.100469f},{0.00343343f,-0.313781f,0.0918925f},{0.00445856f,-0.314434f,0.0918925f}, -{0.00445842f,-0.314434f,0.100469f},{0.00528145f,-0.315332f,0.0918925f},{0.00584165f,-0.316409f,0.100469f}, -{0.0052798f,-0.31533f,0.100469f},{0.00610573f,-0.317598f,0.0918925f},{0.00610573f,-0.317598f,0.100469f}, -{0.00584289f,-0.316412f,0.0918925f},{0.00343061f,-0.313779f,0.100469f},{0.00227009f,-0.313414f,0.100469f}, -{0.00227354f,-0.313415f,0.0918925f},{0.00105623f,-0.313362f,0.0918925f},{0.00105623f,-0.313362f,0.100469f}, -{-0.321824f,0.00413429f,0.0918925f},{-0.321f,0.005033f,0.0918925f},{-0.321f,0.005033f,0.100469f}, -{-0.31997f,0.00568869f,0.0918925f},{-0.318819f,0.00605158f,0.100469f},{-0.319972f,0.00568781f,0.100469f}, -{-0.317598f,0.00610573f,0.0918925f},{-0.317598f,0.00610573f,0.100469f},{-0.318816f,0.00605247f,0.0918925f}, -{-0.321825f,0.00413168f,0.100469f},{-0.322384f,0.00305863f,0.100469f},{-0.322382f,0.00306124f,0.0918925f}, -{-0.322648f,0.00186868f,0.0918925f},{-0.322648f,0.00186868f,0.100469f},{-0.313781f,-0.00343343f,0.0918925f}, -{-0.314434f,-0.00445856f,0.0918925f},{-0.314434f,-0.00445842f,0.100469f},{-0.315332f,-0.00528145f,0.0918925f}, -{-0.316409f,-0.00584165f,0.100469f},{-0.31533f,-0.0052798f,0.100469f},{-0.317598f,-0.00610573f,0.0918925f}, -{-0.317598f,-0.00610573f,0.100469f},{-0.316412f,-0.00584289f,0.0918925f},{-0.313779f,-0.00343061f,0.100469f}, -{-0.313414f,-0.00227009f,0.100469f},{-0.313415f,-0.00227354f,0.0918925f},{-0.313362f,-0.00105623f,0.0918925f}, -{-0.313362f,-0.00105623f,0.100469f},{0.00413429f,0.321824f,0.0918925f},{0.005033f,0.321f,0.0918925f}, -{0.005033f,0.321f,0.100469f},{0.00568869f,0.31997f,0.0918925f},{0.00605158f,0.318819f,0.100469f}, -{0.00568781f,0.319972f,0.100469f},{0.00610573f,0.317598f,0.0918925f},{0.00610573f,0.317598f,0.100469f}, -{0.00605247f,0.318816f,0.0918925f},{0.00413168f,0.321825f,0.100469f},{0.00305863f,0.322384f,0.100469f}, -{0.00306124f,0.322382f,0.0918925f},{0.00186868f,0.322648f,0.0918925f},{0.00186868f,0.322648f,0.100469f}, -{-0.00343343f,0.313781f,0.0918925f},{-0.00445856f,0.314434f,0.0918925f},{-0.00445842f,0.314434f,0.100469f}, -{-0.00528145f,0.315332f,0.0918925f},{-0.00584165f,0.316409f,0.100469f},{-0.0052798f,0.31533f,0.100469f}, -{-0.00610573f,0.317598f,0.0918925f},{-0.00610573f,0.317598f,0.100469f},{-0.00584289f,0.316412f,0.0918925f}, -{-0.00343061f,0.313779f,0.100469f},{-0.00227009f,0.313414f,0.100469f},{-0.00227354f,0.313415f,0.0918925f}, -{-0.00105623f,0.313362f,0.0918925f},{-0.00105623f,0.313362f,0.100469f},{-0.0205353f,-0.297154f,0.0918925f}, -{-0.0197119f,-0.296256f,0.0918925f},{-0.0197119f,-0.296256f,0.100469f},{-0.018681f,-0.2956f,0.0918925f}, -{-0.0175301f,-0.295237f,0.100469f},{-0.0186838f,-0.295601f,0.100469f},{-0.0163096f,-0.295183f,0.0918925f}, -{-0.0163096f,-0.295183f,0.100469f},{-0.0175273f,-0.295236f,0.0918925f},{-0.0205366f,-0.297157f,0.100469f}, -{-0.0210952f,-0.29823f,0.100469f},{-0.0210939f,-0.298227f,0.0918925f},{-0.0213591f,-0.29942f,0.0918925f}, -{-0.0213591f,-0.29942f,0.100469f},{-0.0124916f,-0.304721f,0.0918925f},{-0.0131454f,-0.305747f,0.0918925f}, -{-0.0131452f,-0.305747f,0.100469f},{-0.014044f,-0.30657f,0.0918925f},{-0.01512f,-0.30713f,0.100469f}, -{-0.0140418f,-0.306569f,0.100469f},{-0.0163096f,-0.307394f,0.0918925f},{-0.0163096f,-0.307394f,0.100469f}, -{-0.0151227f,-0.307131f,0.0918925f},{-0.0124909f,-0.304719f,0.100469f},{-0.0121253f,-0.303559f,0.100469f}, -{-0.0121261f,-0.303562f,0.0918925f},{-0.012073f,-0.302345f,0.0918925f},{-0.012073f,-0.302345f,0.100469f}, -{-0.297154f,0.0205353f,0.0918925f},{-0.296256f,0.0197119f,0.0918925f},{-0.296256f,0.0197119f,0.100469f}, -{-0.2956f,0.018681f,0.0918925f},{-0.295237f,0.0175301f,0.100469f},{-0.295601f,0.0186838f,0.100469f}, -{-0.295183f,0.0163096f,0.0918925f},{-0.295183f,0.0163096f,0.100469f},{-0.295236f,0.0175273f,0.0918925f}, -{-0.297157f,0.0205366f,0.100469f},{-0.29823f,0.0210952f,0.100469f},{-0.298227f,0.0210939f,0.0918925f}, -{-0.29942f,0.0213591f,0.0918925f},{-0.29942f,0.0213591f,0.100469f},{-0.304721f,0.0124916f,0.0918925f}, -{-0.305747f,0.0131454f,0.0918925f},{-0.305747f,0.0131452f,0.100469f},{-0.30657f,0.014044f,0.0918925f}, -{-0.30713f,0.01512f,0.100469f},{-0.306569f,0.0140418f,0.100469f},{-0.307394f,0.0163096f,0.0918925f}, -{-0.307394f,0.0163096f,0.100469f},{-0.307131f,0.0151227f,0.0918925f},{-0.304719f,0.0124909f,0.100469f}, -{-0.303559f,0.0121253f,0.100469f},{-0.303562f,0.0121261f,0.0918925f},{-0.302345f,0.012073f,0.0918925f}, -{-0.302345f,0.012073f,0.100469f},{0.0205329f,0.297151f,0.0918925f},{0.0197119f,0.296256f,0.0918925f}, -{0.0197119f,0.296256f,0.100469f},{0.0186836f,0.295601f,0.0918925f},{0.0175301f,0.295237f,0.100469f}, -{0.0186838f,0.295601f,0.100469f},{0.0163096f,0.295183f,0.0918925f},{0.0163096f,0.295183f,0.100469f}, -{0.0175235f,0.295236f,0.0918925f},{0.0205366f,0.297157f,0.100469f},{0.0210952f,0.29823f,0.100469f}, -{0.0210948f,0.29823f,0.0918925f},{0.0213591f,0.29942f,0.0918925f},{0.0213591f,0.29942f,0.100469f}, -{0.0124921f,0.304722f,0.0918925f},{0.0131453f,0.305747f,0.0918925f},{0.0131452f,0.305747f,0.100469f}, -{0.0140439f,0.30657f,0.0918925f},{0.01512f,0.30713f,0.100469f},{0.0140413f,0.306568f,0.100469f}, -{0.0163096f,0.307394f,0.0918925f},{0.0163096f,0.307394f,0.100469f},{0.0151233f,0.307131f,0.0918925f}, -{0.0124909f,0.304719f,0.100469f},{0.0121254f,0.303559f,0.100469f},{0.012126f,0.303562f,0.0918925f}, -{0.012073f,0.302345f,0.0918925f},{0.012073f,0.302345f,0.100469f},{0.00413429f,-0.280753f,0.0918925f}, -{0.005033f,-0.281577f,0.0918925f},{0.005033f,-0.281577f,0.100469f},{0.00568869f,-0.282607f,0.0918925f}, -{0.00605158f,-0.283758f,0.100469f},{0.00568781f,-0.282605f,0.100469f},{0.00610573f,-0.284979f,0.0918925f}, -{0.00610573f,-0.284979f,0.100469f},{0.00605247f,-0.283761f,0.0918925f},{0.00413168f,-0.280752f,0.100469f}, -{0.00305863f,-0.280193f,0.100469f},{0.00306124f,-0.280195f,0.0918925f},{0.00186868f,-0.279929f,0.0918925f}, -{0.00186868f,-0.279929f,0.100469f},{-0.00343343f,-0.288796f,0.0918925f},{-0.00445856f,-0.288143f,0.0918925f}, -{-0.00445842f,-0.288143f,0.100469f},{-0.00528145f,-0.287245f,0.0918925f},{-0.00584165f,-0.286169f,0.100469f}, -{-0.0052798f,-0.287247f,0.100469f},{-0.00610573f,-0.284979f,0.0918925f},{-0.00610573f,-0.284979f,0.100469f}, -{-0.00584289f,-0.286165f,0.0918925f},{-0.00343061f,-0.288798f,0.100469f},{-0.00227009f,-0.289163f,0.100469f}, -{-0.00227354f,-0.289162f,0.0918925f},{-0.00105623f,-0.289216f,0.0918925f},{-0.00105623f,-0.289216f,0.100469f}, -{-0.280753f,-0.00413429f,0.0918925f},{-0.281577f,-0.005033f,0.0918925f},{-0.281577f,-0.005033f,0.100469f}, -{-0.282607f,-0.00568869f,0.0918925f},{-0.283758f,-0.00605158f,0.100469f},{-0.282605f,-0.00568781f,0.100469f}, -{-0.284979f,-0.00610573f,0.0918925f},{-0.284979f,-0.00610573f,0.100469f},{-0.283761f,-0.00605247f,0.0918925f}, -{-0.280752f,-0.00413168f,0.100469f},{-0.280193f,-0.00305863f,0.100469f},{-0.280195f,-0.00306124f,0.0918925f}, -{-0.279929f,-0.00186868f,0.0918925f},{-0.279929f,-0.00186868f,0.100469f},{-0.288796f,0.00343343f,0.0918925f}, -{-0.288143f,0.00445856f,0.0918925f},{-0.288143f,0.00445842f,0.100469f},{-0.287245f,0.00528145f,0.0918925f}, -{-0.286169f,0.00584165f,0.100469f},{-0.287247f,0.0052798f,0.100469f},{-0.284979f,0.00610573f,0.0918925f}, -{-0.284979f,0.00610573f,0.100469f},{-0.286165f,0.00584289f,0.0918925f},{-0.288798f,0.00343061f,0.100469f}, -{-0.289163f,0.00227009f,0.100469f},{-0.289162f,0.00227354f,0.0918925f},{-0.289216f,0.00105623f,0.0918925f}, -{-0.289216f,0.00105623f,0.100469f},{-0.00413429f,0.280753f,0.0918925f},{-0.005033f,0.281577f,0.0918925f}, -{-0.005033f,0.281577f,0.100469f},{-0.00568869f,0.282607f,0.0918925f},{-0.00605158f,0.283758f,0.100469f}, -{-0.00568781f,0.282605f,0.100469f},{-0.00610573f,0.284979f,0.0918925f},{-0.00610573f,0.284979f,0.100469f}, -{-0.00605247f,0.283761f,0.0918925f},{-0.00413168f,0.280752f,0.100469f},{-0.00305863f,0.280193f,0.100469f}, -{-0.00306124f,0.280195f,0.0918925f},{-0.00186868f,0.279929f,0.0918925f},{-0.00186868f,0.279929f,0.100469f}, -{0.00343343f,0.288796f,0.0918925f},{0.00445856f,0.288143f,0.0918925f},{0.00445842f,0.288143f,0.100469f}, -{0.00528145f,0.287245f,0.0918925f},{0.00584165f,0.286169f,0.100469f},{0.0052798f,0.287247f,0.100469f}, -{0.00610573f,0.284979f,0.0918925f},{0.00610573f,0.284979f,0.100469f},{0.00584289f,0.286165f,0.0918925f}, -{0.00343061f,0.288798f,0.100469f},{0.00227009f,0.289163f,0.100469f},{0.00227354f,0.289162f,0.0918925f}, -{0.00105623f,0.289216f,0.0918925f},{0.00105623f,0.289216f,0.100469f},{0.305423f,0.0205353f,0.0918925f}, -{0.306322f,0.0197119f,0.0918925f},{0.306322f,0.0197119f,0.100469f},{0.306977f,0.018681f,0.0918925f}, -{0.30734f,0.0175301f,0.100469f},{0.306976f,0.0186838f,0.100469f},{0.307394f,0.0163096f,0.0918925f}, -{0.307394f,0.0163096f,0.100469f},{0.307341f,0.0175273f,0.0918925f},{0.30542f,0.0205366f,0.100469f}, -{0.304347f,0.0210952f,0.100469f},{0.30435f,0.0210939f,0.0918925f},{0.303157f,0.0213591f,0.0918925f}, -{0.303157f,0.0213591f,0.100469f},{0.297856f,0.0124916f,0.0918925f},{0.29683f,0.0131454f,0.0918925f}, -{0.29683f,0.0131452f,0.100469f},{0.296007f,0.014044f,0.0918925f},{0.295447f,0.01512f,0.100469f}, -{0.296008f,0.0140418f,0.100469f},{0.295183f,0.0163096f,0.0918925f},{0.295183f,0.0163096f,0.100469f}, -{0.295446f,0.0151227f,0.0918925f},{0.297858f,0.0124909f,0.100469f},{0.299018f,0.0121253f,0.100469f}, -{0.299015f,0.0121261f,0.0918925f},{0.300232f,0.012073f,0.0918925f},{0.300232f,0.012073f,0.100469f}, -{0.321824f,-0.00413429f,0.0918925f},{0.321f,-0.005033f,0.0918925f},{0.321f,-0.005033f,0.100469f}, -{0.31997f,-0.00568869f,0.0918925f},{0.318819f,-0.00605158f,0.100469f},{0.319972f,-0.00568781f,0.100469f}, -{0.317598f,-0.00610573f,0.0918925f},{0.317598f,-0.00610573f,0.100469f},{0.318816f,-0.00605247f,0.0918925f}, -{0.321825f,-0.00413168f,0.100469f},{0.322384f,-0.00305863f,0.100469f},{0.322382f,-0.00306124f,0.0918925f}, -{0.322648f,-0.00186868f,0.0918925f},{0.322648f,-0.00186868f,0.100469f},{0.313781f,0.00343343f,0.0918925f}, -{0.314434f,0.00445856f,0.0918925f},{0.314434f,0.00445842f,0.100469f},{0.315332f,0.00528145f,0.0918925f}, -{0.316409f,0.00584165f,0.100469f},{0.31533f,0.0052798f,0.100469f},{0.317598f,0.00610573f,0.0918925f}, -{0.317598f,0.00610573f,0.100469f},{0.316412f,0.00584289f,0.0918925f},{0.313779f,0.00343061f,0.100469f}, -{0.313414f,0.00227009f,0.100469f},{0.313415f,0.00227354f,0.0918925f},{0.313362f,0.00105623f,0.0918925f}, -{0.313362f,0.00105623f,0.100469f},{0.297151f,-0.0205329f,0.0918925f},{0.296256f,-0.0197119f,0.0918925f}, -{0.296256f,-0.0197119f,0.100469f},{0.295601f,-0.0186836f,0.0918925f},{0.295237f,-0.0175301f,0.100469f}, -{0.295601f,-0.0186838f,0.100469f},{0.295183f,-0.0163096f,0.0918925f},{0.295183f,-0.0163096f,0.100469f}, -{0.295236f,-0.0175235f,0.0918925f},{0.297157f,-0.0205366f,0.100469f},{0.29823f,-0.0210952f,0.100469f}, -{0.29823f,-0.0210948f,0.0918925f},{0.29942f,-0.0213591f,0.0918925f},{0.29942f,-0.0213591f,0.100469f}, -{0.304721f,-0.0124916f,0.0918925f},{0.305747f,-0.0131454f,0.0918925f},{0.305747f,-0.0131452f,0.100469f}, -{0.30657f,-0.014044f,0.0918925f},{0.30713f,-0.01512f,0.100469f},{0.306569f,-0.0140418f,0.100469f}, -{0.307394f,-0.0163096f,0.0918925f},{0.307394f,-0.0163096f,0.100469f},{0.307131f,-0.0151227f,0.0918925f}, -{0.304719f,-0.0124909f,0.100469f},{0.303559f,-0.0121253f,0.100469f},{0.303562f,-0.0121261f,0.0918925f}, -{0.302345f,-0.012073f,0.0918925f},{0.302345f,-0.012073f,0.100469f},{-0.313522f,-0.0153056f,0.0918925f}, -{-0.314107f,-0.015305f,0.0918925f},{-0.314104f,-0.0153056f,0.100469f},{-0.313518f,-0.015305f,0.100469f}, -{-0.312949f,-0.0151842f,0.0918925f},{-0.312948f,-0.0151836f,0.100469f},{-0.312414f,-0.014946f,0.100469f}, -{-0.311943f,-0.0146037f,0.0918925f},{-0.312416f,-0.0149467f,0.0918925f},{-0.31194f,-0.0146009f,0.100469f}, -{-0.311551f,-0.0141686f,0.0918925f},{-0.31155f,-0.0141674f,0.100469f},{-0.311258f,-0.0136627f,0.0918925f}, -{-0.311257f,-0.0136603f,0.100469f},{-0.311078f,-0.0131075f,0.0918925f},{-0.311077f,-0.013106f,0.100469f}, -{-0.311016f,-0.0125242f,0.100469f},{-0.311016f,-0.0125242f,0.0918925f},{-0.314676f,-0.0151842f,0.100469f}, -{-0.31521f,-0.0149467f,0.100469f},{-0.314678f,-0.0151836f,0.0918925f},{-0.315212f,-0.014946f,0.0918925f}, -{-0.315682f,-0.0146037f,0.100469f},{-0.315685f,-0.0146009f,0.0918925f},{-0.316075f,-0.0141686f,0.100469f}, -{-0.316367f,-0.0136627f,0.100469f},{-0.316076f,-0.0141674f,0.0918925f},{-0.316368f,-0.0136603f,0.0918925f}, -{-0.316548f,-0.0131075f,0.100469f},{-0.316548f,-0.013106f,0.0918925f},{-0.316609f,-0.0125242f,0.100469f}, -{-0.316609f,-0.0125242f,0.0918925f},{-0.313522f,0.00974281f,0.0918925f},{-0.314107f,0.0097434f,0.0918925f}, -{-0.314104f,0.00974281f,0.100469f},{-0.313518f,0.0097434f,0.100469f},{-0.312949f,0.00986419f,0.0918925f}, -{-0.312948f,0.00986481f,0.100469f},{-0.312414f,0.0101024f,0.100469f},{-0.311943f,0.0104447f,0.0918925f}, -{-0.312416f,0.0101017f,0.0918925f},{-0.31194f,0.0104475f,0.100469f},{-0.311551f,0.0108798f,0.0918925f}, -{-0.31155f,0.010881f,0.100469f},{-0.311258f,0.0113857f,0.0918925f},{-0.311257f,0.0113881f,0.100469f}, -{-0.311078f,0.0119409f,0.0918925f},{-0.311077f,0.0119424f,0.100469f},{-0.311016f,0.0125242f,0.100469f}, -{-0.314676f,0.00986419f,0.100469f},{-0.31521f,0.0101017f,0.100469f},{-0.314678f,0.00986481f,0.0918925f}, -{-0.315212f,0.0101024f,0.0918925f},{-0.315682f,0.0104447f,0.100469f},{-0.315685f,0.0104475f,0.0918925f}, -{-0.316075f,0.0108798f,0.100469f},{-0.316367f,0.0113857f,0.100469f},{-0.316076f,0.010881f,0.0918925f}, -{-0.316368f,0.0113881f,0.0918925f},{-0.316548f,0.0119409f,0.100469f},{-0.316548f,0.0119424f,0.0918925f}, -{-0.316609f,0.0125242f,0.100469f},{-0.288473f,0.00974281f,0.0918925f},{-0.289059f,0.0097434f,0.0918925f}, -{-0.289055f,0.00974281f,0.100469f},{-0.28847f,0.0097434f,0.100469f},{-0.287901f,0.00986419f,0.0918925f}, -{-0.287899f,0.00986481f,0.100469f},{-0.287366f,0.0101024f,0.100469f},{-0.286895f,0.0104447f,0.0918925f}, -{-0.287367f,0.0101017f,0.0918925f},{-0.286892f,0.0104475f,0.100469f},{-0.286502f,0.0108798f,0.0918925f}, -{-0.286501f,0.010881f,0.100469f},{-0.28621f,0.0113857f,0.0918925f},{-0.286209f,0.0113881f,0.100469f}, -{-0.286029f,0.0119409f,0.0918925f},{-0.286029f,0.0119424f,0.100469f},{-0.285968f,0.0125242f,0.100469f}, -{-0.285968f,0.0125242f,0.0918925f},{-0.289628f,0.00986419f,0.100469f},{-0.290161f,0.0101017f,0.100469f}, -{-0.289629f,0.00986481f,0.0918925f},{-0.290163f,0.0101024f,0.0918925f},{-0.290634f,0.0104447f,0.100469f}, -{-0.290637f,0.0104475f,0.0918925f},{-0.291026f,0.0108798f,0.100469f},{-0.291319f,0.0113857f,0.100469f}, -{-0.291027f,0.010881f,0.0918925f},{-0.29132f,0.0113881f,0.0918925f},{-0.291499f,0.0119409f,0.100469f}, -{-0.2915f,0.0119424f,0.0918925f},{-0.291561f,0.0125242f,0.100469f},{-0.291561f,0.0125242f,0.0918925f}, -{-0.288473f,-0.0153056f,0.0918925f},{-0.289059f,-0.015305f,0.0918925f},{-0.289055f,-0.0153056f,0.100469f}, -{-0.28847f,-0.015305f,0.100469f},{-0.287901f,-0.0151842f,0.0918925f},{-0.287899f,-0.0151836f,0.100469f}, -{-0.287366f,-0.014946f,0.100469f},{-0.286895f,-0.0146037f,0.0918925f},{-0.287367f,-0.0149467f,0.0918925f}, -{-0.286892f,-0.0146009f,0.100469f},{-0.286502f,-0.0141686f,0.0918925f},{-0.286501f,-0.0141674f,0.100469f}, -{-0.28621f,-0.0136627f,0.0918925f},{-0.286209f,-0.0136603f,0.100469f},{-0.286029f,-0.0131075f,0.0918925f}, -{-0.286029f,-0.013106f,0.100469f},{-0.285968f,-0.0125242f,0.100469f},{-0.289628f,-0.0151842f,0.100469f}, -{-0.290161f,-0.0149467f,0.100469f},{-0.289629f,-0.0151836f,0.0918925f},{-0.290163f,-0.014946f,0.0918925f}, -{-0.290634f,-0.0146037f,0.100469f},{-0.290637f,-0.0146009f,0.0918925f},{-0.291026f,-0.0141686f,0.100469f}, -{-0.291319f,-0.0136627f,0.100469f},{-0.291027f,-0.0141674f,0.0918925f},{-0.29132f,-0.0136603f,0.0918925f}, -{-0.291499f,-0.0131075f,0.100469f},{-0.2915f,-0.013106f,0.0918925f},{-0.291561f,-0.0125242f,0.100469f}, -{0.0128153f,0.311031f,0.0918925f},{0.0122298f,0.311032f,0.0918925f},{0.0122331f,0.311031f,0.100469f}, -{0.0128186f,0.311032f,0.100469f},{0.0133877f,0.311153f,0.0918925f},{0.0133893f,0.311153f,0.100469f}, -{0.013923f,0.311391f,0.100469f},{0.0143937f,0.311733f,0.0918925f},{0.0139213f,0.31139f,0.0918925f}, -{0.0143968f,0.311736f,0.100469f},{0.0147862f,0.312168f,0.0918925f},{0.0147871f,0.312169f,0.100469f}, -{0.0150786f,0.312674f,0.0918925f},{0.0150796f,0.312677f,0.100469f},{0.0152591f,0.313229f,0.0918925f}, -{0.0152596f,0.313231f,0.100469f},{0.0153208f,0.313813f,0.100469f},{0.0116607f,0.311153f,0.100469f}, -{0.0111271f,0.31139f,0.100469f},{0.0116591f,0.311153f,0.0918925f},{0.0111254f,0.311391f,0.0918925f}, -{0.0106546f,0.311733f,0.100469f},{0.0106515f,0.311736f,0.0918925f},{0.0102622f,0.312168f,0.100469f}, -{0.00996978f,0.312674f,0.100469f},{0.0102613f,0.312169f,0.0918925f},{0.00996883f,0.312677f,0.0918925f}, -{0.00978928f,0.313229f,0.100469f},{0.0097888f,0.313231f,0.0918925f},{0.00972758f,0.313813f,0.100469f}, -{0.0128153f,0.285983f,0.0918925f},{0.0122298f,0.285984f,0.0918925f},{0.0122331f,0.285983f,0.100469f}, -{0.0128186f,0.285984f,0.100469f},{0.0133877f,0.286104f,0.0918925f},{0.0133893f,0.286105f,0.100469f}, -{0.013923f,0.286343f,0.100469f},{0.0143937f,0.286685f,0.0918925f},{0.0139213f,0.286342f,0.0918925f}, -{0.0143968f,0.286688f,0.100469f},{0.0147862f,0.28712f,0.0918925f},{0.0147871f,0.287121f,0.100469f}, -{0.0150786f,0.287626f,0.0918925f},{0.0150796f,0.287628f,0.100469f},{0.0152591f,0.288181f,0.0918925f}, -{0.0152596f,0.288183f,0.100469f},{0.0153208f,0.288764f,0.100469f},{0.0153208f,0.288764f,0.0918925f}, -{0.0116607f,0.286104f,0.100469f},{0.0111271f,0.286342f,0.100469f},{0.0116591f,0.286105f,0.0918925f}, -{0.0111254f,0.286343f,0.0918925f},{0.0106546f,0.286685f,0.100469f},{0.0106515f,0.286688f,0.0918925f}, -{0.0102622f,0.28712f,0.100469f},{0.00996978f,0.287626f,0.100469f},{0.0102613f,0.287121f,0.0918925f}, -{0.00996883f,0.287628f,0.0918925f},{0.00978928f,0.288181f,0.100469f},{0.0097888f,0.288183f,0.0918925f}, -{0.00972758f,0.288764f,0.100469f},{0.00972758f,0.288764f,0.0918925f},{-0.0122331f,0.311031f,0.0918925f}, -{-0.0128186f,0.311032f,0.0918925f},{-0.0128153f,0.311031f,0.100469f},{-0.0122298f,0.311032f,0.100469f}, -{-0.0116607f,0.311153f,0.0918925f},{-0.0116591f,0.311153f,0.100469f},{-0.0111254f,0.311391f,0.100469f}, -{-0.0106546f,0.311733f,0.0918925f},{-0.0111271f,0.31139f,0.0918925f},{-0.0106515f,0.311736f,0.100469f}, -{-0.0102622f,0.312168f,0.0918925f},{-0.0102613f,0.312169f,0.100469f},{-0.00996978f,0.312674f,0.0918925f}, -{-0.00996883f,0.312677f,0.100469f},{-0.00978928f,0.313229f,0.0918925f},{-0.0097888f,0.313231f,0.100469f}, -{-0.00972758f,0.313813f,0.100469f},{-0.00972758f,0.313813f,0.0918925f},{-0.0133877f,0.311153f,0.100469f}, -{-0.0139213f,0.31139f,0.100469f},{-0.0133893f,0.311153f,0.0918925f},{-0.013923f,0.311391f,0.0918925f}, -{-0.0143937f,0.311733f,0.100469f},{-0.0143968f,0.311736f,0.0918925f},{-0.0147862f,0.312168f,0.100469f}, -{-0.0150786f,0.312674f,0.100469f},{-0.0147871f,0.312169f,0.0918925f},{-0.0150796f,0.312677f,0.0918925f}, -{-0.0152591f,0.313229f,0.100469f},{-0.0152596f,0.313231f,0.0918925f},{-0.0153208f,0.313813f,0.100469f}, -{-0.0153208f,0.313813f,0.0918925f},{-0.0122331f,0.285983f,0.0918925f},{-0.0128186f,0.285984f,0.0918925f}, -{-0.0128153f,0.285983f,0.100469f},{-0.0122298f,0.285984f,0.100469f},{-0.0116607f,0.286104f,0.0918925f}, -{-0.0116591f,0.286105f,0.100469f},{-0.0111254f,0.286343f,0.100469f},{-0.0106546f,0.286685f,0.0918925f}, -{-0.0111271f,0.286342f,0.0918925f},{-0.0106515f,0.286688f,0.100469f},{-0.0102622f,0.28712f,0.0918925f}, -{-0.0102613f,0.287121f,0.100469f},{-0.00996978f,0.287626f,0.0918925f},{-0.00996883f,0.287628f,0.100469f}, -{-0.00978928f,0.288181f,0.0918925f},{-0.0097888f,0.288183f,0.100469f},{-0.00972758f,0.288764f,0.100469f}, -{-0.0133877f,0.286104f,0.100469f},{-0.0139213f,0.286342f,0.100469f},{-0.0133893f,0.286105f,0.0918925f}, -{-0.013923f,0.286343f,0.0918925f},{-0.0143937f,0.286685f,0.100469f},{-0.0143968f,0.286688f,0.0918925f}, -{-0.0147862f,0.28712f,0.100469f},{-0.0150786f,0.287626f,0.100469f},{-0.0147871f,0.287121f,0.0918925f}, -{-0.0150796f,0.287628f,0.0918925f},{-0.0152591f,0.288181f,0.100469f},{-0.0152596f,0.288183f,0.0918925f}, -{-0.0153208f,0.288764f,0.100469f},{0.314104f,0.00974281f,0.0918925f},{0.313518f,0.0097434f,0.0918925f}, -{0.313522f,0.00974281f,0.100469f},{0.314107f,0.0097434f,0.100469f},{0.314676f,0.00986419f,0.0918925f}, -{0.314678f,0.00986481f,0.100469f},{0.315212f,0.0101024f,0.100469f},{0.315682f,0.0104447f,0.0918925f}, -{0.31521f,0.0101017f,0.0918925f},{0.315685f,0.0104475f,0.100469f},{0.316075f,0.0108798f,0.0918925f}, -{0.316076f,0.010881f,0.100469f},{0.316367f,0.0113857f,0.0918925f},{0.316368f,0.0113881f,0.100469f}, -{0.316548f,0.0119409f,0.0918925f},{0.316548f,0.0119424f,0.100469f},{0.316609f,0.0125242f,0.100469f}, -{0.316609f,0.0125242f,0.0918925f},{0.312949f,0.00986419f,0.100469f},{0.312416f,0.0101017f,0.100469f}, -{0.312948f,0.00986481f,0.0918925f},{0.312414f,0.0101024f,0.0918925f},{0.311943f,0.0104447f,0.100469f}, -{0.31194f,0.0104475f,0.0918925f},{0.311551f,0.0108798f,0.100469f},{0.311258f,0.0113857f,0.100469f}, -{0.31155f,0.010881f,0.0918925f},{0.311257f,0.0113881f,0.0918925f},{0.311078f,0.0119409f,0.100469f}, -{0.311077f,0.0119424f,0.0918925f},{0.311016f,0.0125242f,0.100469f},{0.311016f,0.0125242f,0.0918925f}, -{0.289055f,0.00974281f,0.0918925f},{0.28847f,0.0097434f,0.0918925f},{0.288473f,0.00974281f,0.100469f}, -{0.289059f,0.0097434f,0.100469f},{0.289628f,0.00986419f,0.0918925f},{0.289629f,0.00986481f,0.100469f}, -{0.290163f,0.0101024f,0.100469f},{0.290634f,0.0104447f,0.0918925f},{0.290161f,0.0101017f,0.0918925f}, -{0.290637f,0.0104475f,0.100469f},{0.291026f,0.0108798f,0.0918925f},{0.291027f,0.010881f,0.100469f}, -{0.291319f,0.0113857f,0.0918925f},{0.29132f,0.0113881f,0.100469f},{0.291499f,0.0119409f,0.0918925f}, -{0.2915f,0.0119424f,0.100469f},{0.291561f,0.0125242f,0.100469f},{0.287901f,0.00986419f,0.100469f}, -{0.287367f,0.0101017f,0.100469f},{0.287899f,0.00986481f,0.0918925f},{0.287366f,0.0101024f,0.0918925f}, -{0.286895f,0.0104447f,0.100469f},{0.286892f,0.0104475f,0.0918925f},{0.286502f,0.0108798f,0.100469f}, -{0.28621f,0.0113857f,0.100469f},{0.286501f,0.010881f,0.0918925f},{0.286209f,0.0113881f,0.0918925f}, -{0.286029f,0.0119409f,0.100469f},{0.286029f,0.0119424f,0.0918925f},{0.285968f,0.0125242f,0.100469f}, -{0.289055f,-0.0153056f,0.0918925f},{0.28847f,-0.015305f,0.0918925f},{0.288473f,-0.0153056f,0.100469f}, -{0.289059f,-0.015305f,0.100469f},{0.289628f,-0.0151842f,0.0918925f},{0.289629f,-0.0151836f,0.100469f}, -{0.290163f,-0.014946f,0.100469f},{0.290634f,-0.0146037f,0.0918925f},{0.290161f,-0.0149467f,0.0918925f}, -{0.290637f,-0.0146009f,0.100469f},{0.291026f,-0.0141686f,0.0918925f},{0.291027f,-0.0141674f,0.100469f}, -{0.291319f,-0.0136627f,0.0918925f},{0.29132f,-0.0136603f,0.100469f},{0.291499f,-0.0131075f,0.0918925f}, -{0.2915f,-0.013106f,0.100469f},{0.291561f,-0.0125242f,0.100469f},{0.291561f,-0.0125242f,0.0918925f}, -{0.287901f,-0.0151842f,0.100469f},{0.287367f,-0.0149467f,0.100469f},{0.287899f,-0.0151836f,0.0918925f}, -{0.287366f,-0.014946f,0.0918925f},{0.286895f,-0.0146037f,0.100469f},{0.286892f,-0.0146009f,0.0918925f}, -{0.286502f,-0.0141686f,0.100469f},{0.28621f,-0.0136627f,0.100469f},{0.286501f,-0.0141674f,0.0918925f}, -{0.286209f,-0.0136603f,0.0918925f},{0.286029f,-0.0131075f,0.100469f},{0.286029f,-0.013106f,0.0918925f}, -{0.285968f,-0.0125242f,0.100469f},{0.285968f,-0.0125242f,0.0918925f},{0.314104f,-0.0153056f,0.0918925f}, -{0.313518f,-0.015305f,0.0918925f},{0.313522f,-0.0153056f,0.100469f},{0.314107f,-0.015305f,0.100469f}, -{0.314676f,-0.0151842f,0.0918925f},{0.314678f,-0.0151836f,0.100469f},{0.315212f,-0.014946f,0.100469f}, -{0.315682f,-0.0146037f,0.0918925f},{0.31521f,-0.0149467f,0.0918925f},{0.315685f,-0.0146009f,0.100469f}, -{0.316075f,-0.0141686f,0.0918925f},{0.316076f,-0.0141674f,0.100469f},{0.316367f,-0.0136627f,0.0918925f}, -{0.316368f,-0.0136603f,0.100469f},{0.316548f,-0.0131075f,0.0918925f},{0.316548f,-0.013106f,0.100469f}, -{0.316609f,-0.0125242f,0.100469f},{0.312949f,-0.0151842f,0.100469f},{0.312416f,-0.0149467f,0.100469f}, -{0.312948f,-0.0151836f,0.0918925f},{0.312414f,-0.014946f,0.0918925f},{0.311943f,-0.0146037f,0.100469f}, -{0.31194f,-0.0146009f,0.0918925f},{0.311551f,-0.0141686f,0.100469f},{0.311258f,-0.0136627f,0.100469f}, -{0.31155f,-0.0141674f,0.0918925f},{0.311257f,-0.0136603f,0.0918925f},{0.311078f,-0.0131075f,0.100469f}, -{0.311077f,-0.013106f,0.0918925f},{0.311016f,-0.0125242f,0.100469f},{-0.0122331f,-0.316594f,0.0918925f}, -{-0.0128186f,-0.316594f,0.0918925f},{-0.0128153f,-0.316594f,0.100469f},{-0.0122298f,-0.316594f,0.100469f}, -{-0.0116607f,-0.316473f,0.0918925f},{-0.0116591f,-0.316472f,0.100469f},{-0.0111254f,-0.316235f,0.100469f}, -{-0.0106546f,-0.315892f,0.0918925f},{-0.0111271f,-0.316235f,0.0918925f},{-0.0106515f,-0.315889f,0.100469f}, -{-0.0102622f,-0.315457f,0.0918925f},{-0.0102613f,-0.315456f,0.100469f},{-0.00996978f,-0.314951f,0.0918925f}, -{-0.00996883f,-0.314949f,0.100469f},{-0.00978928f,-0.314396f,0.0918925f},{-0.0097888f,-0.314395f,0.100469f}, -{-0.00972758f,-0.313813f,0.100469f},{-0.0133877f,-0.316473f,0.100469f},{-0.0139213f,-0.316235f,0.100469f}, -{-0.0133893f,-0.316472f,0.0918925f},{-0.013923f,-0.316235f,0.0918925f},{-0.0143937f,-0.315892f,0.100469f}, -{-0.0143968f,-0.315889f,0.0918925f},{-0.0147862f,-0.315457f,0.100469f},{-0.0150786f,-0.314951f,0.100469f}, -{-0.0147871f,-0.315456f,0.0918925f},{-0.0150796f,-0.314949f,0.0918925f},{-0.0152591f,-0.314396f,0.100469f}, -{-0.0152596f,-0.314395f,0.0918925f},{-0.0153208f,-0.313813f,0.100469f},{-0.0122331f,-0.291546f,0.0918925f}, -{-0.0128186f,-0.291545f,0.0918925f},{-0.0128153f,-0.291546f,0.100469f},{-0.0122298f,-0.291545f,0.100469f}, -{-0.0116607f,-0.291424f,0.0918925f},{-0.0116591f,-0.291424f,0.100469f},{-0.0111254f,-0.291186f,0.100469f}, -{-0.0106546f,-0.290844f,0.0918925f},{-0.0111271f,-0.291187f,0.0918925f},{-0.0106515f,-0.290841f,0.100469f}, -{-0.0102622f,-0.290409f,0.0918925f},{-0.0102613f,-0.290408f,0.100469f},{-0.00996978f,-0.289903f,0.0918925f}, -{-0.00996883f,-0.2899f,0.100469f},{-0.00978928f,-0.289348f,0.0918925f},{-0.0097888f,-0.289346f,0.100469f}, -{-0.00972758f,-0.288764f,0.100469f},{-0.00972758f,-0.288764f,0.0918925f},{-0.0133877f,-0.291424f,0.100469f}, -{-0.0139213f,-0.291187f,0.100469f},{-0.0133893f,-0.291424f,0.0918925f},{-0.013923f,-0.291186f,0.0918925f}, -{-0.0143937f,-0.290844f,0.100469f},{-0.0143968f,-0.290841f,0.0918925f},{-0.0147862f,-0.290409f,0.100469f}, -{-0.0150786f,-0.289903f,0.100469f},{-0.0147871f,-0.290408f,0.0918925f},{-0.0150796f,-0.2899f,0.0918925f}, -{-0.0152591f,-0.289348f,0.100469f},{-0.0152596f,-0.289346f,0.0918925f},{-0.0153208f,-0.288764f,0.100469f}, -{-0.0153208f,-0.288764f,0.0918925f},{0.0128153f,-0.291546f,0.0918925f},{0.0122298f,-0.291545f,0.0918925f}, -{0.0122331f,-0.291546f,0.100469f},{0.0128186f,-0.291545f,0.100469f},{0.0133877f,-0.291424f,0.0918925f}, -{0.0133893f,-0.291424f,0.100469f},{0.013923f,-0.291186f,0.100469f},{0.0143937f,-0.290844f,0.0918925f}, -{0.0139213f,-0.291187f,0.0918925f},{0.0143968f,-0.290841f,0.100469f},{0.0147862f,-0.290409f,0.0918925f}, -{0.0147871f,-0.290408f,0.100469f},{0.0150786f,-0.289903f,0.0918925f},{0.0150796f,-0.2899f,0.100469f}, -{0.0152591f,-0.289348f,0.0918925f},{0.0152596f,-0.289346f,0.100469f},{0.0153208f,-0.288764f,0.100469f}, -{0.0116607f,-0.291424f,0.100469f},{0.0111271f,-0.291187f,0.100469f},{0.0116591f,-0.291424f,0.0918925f}, -{0.0111254f,-0.291186f,0.0918925f},{0.0106546f,-0.290844f,0.100469f},{0.0106515f,-0.290841f,0.0918925f}, -{0.0102622f,-0.290409f,0.100469f},{0.00996978f,-0.289903f,0.100469f},{0.0102613f,-0.290408f,0.0918925f}, -{0.00996883f,-0.2899f,0.0918925f},{0.00978928f,-0.289348f,0.100469f},{0.0097888f,-0.289346f,0.0918925f}, -{0.00972758f,-0.288764f,0.100469f},{0.0128153f,-0.316594f,0.0918925f},{0.0122298f,-0.316594f,0.0918925f}, -{0.0122331f,-0.316594f,0.100469f},{0.0128186f,-0.316594f,0.100469f},{0.0133877f,-0.316473f,0.0918925f}, -{0.0133893f,-0.316472f,0.100469f},{0.013923f,-0.316235f,0.100469f},{0.0143937f,-0.315892f,0.0918925f}, -{0.0139213f,-0.316235f,0.0918925f},{0.0143968f,-0.315889f,0.100469f},{0.0147862f,-0.315457f,0.0918925f}, -{0.0147871f,-0.315456f,0.100469f},{0.0150786f,-0.314951f,0.0918925f},{0.0150796f,-0.314949f,0.100469f}, -{0.0152591f,-0.314396f,0.0918925f},{0.0152596f,-0.314395f,0.100469f},{0.0153208f,-0.313813f,0.100469f}, -{0.0153208f,-0.313813f,0.0918925f},{0.0116607f,-0.316473f,0.100469f},{0.0111271f,-0.316235f,0.100469f}, -{0.0116591f,-0.316472f,0.0918925f},{0.0111254f,-0.316235f,0.0918925f},{0.0106546f,-0.315892f,0.100469f}, -{0.0106515f,-0.315889f,0.0918925f},{0.0102622f,-0.315457f,0.100469f},{0.00996978f,-0.314951f,0.100469f}, -{0.0102613f,-0.315456f,0.0918925f},{0.00996883f,-0.314949f,0.0918925f},{0.00978928f,-0.314396f,0.100469f}, -{0.0097888f,-0.314395f,0.0918925f},{0.00972758f,-0.313813f,0.100469f},{0.00972758f,-0.313813f,0.0918925f}, -{-0.254583f,-0.00139831f,0.0918925f},{-0.255011f,-0.00133018f,0.100469f},{-0.254583f,-0.00139831f,0.100469f}, -{-0.253766f,-0.0011336f,0.0918925f},{-0.254148f,-0.00132889f,0.100469f},{-0.253758f,-0.00112806f,0.100469f}, -{-0.254155f,-0.00133018f,0.0918925f},{-0.253455f,-0.000825358f,0.0918925f},{-0.253254f,-0.000434603f,0.100469f}, -{-0.253185f,2.35333e-017f,0.0918925f},{-0.253254f,-0.000434603f,0.0918925f},{-0.253449f,-0.00081707f,0.100469f}, -{-0.253185f,2.35333e-017f,0.100469f},{-0.255018f,-0.00132889f,0.0918925f},{-0.2554f,-0.0011336f,0.100469f}, -{-0.255408f,-0.00112806f,0.0918925f},{-0.255717f,-0.00081707f,0.0918925f},{-0.255711f,-0.000825358f,0.100469f}, -{-0.255912f,-0.000434603f,0.0918925f},{-0.255912f,-0.000434603f,0.100469f},{-0.255981f,2.33621e-017f,0.100469f}, -{-0.255981f,2.33621e-017f,0.0918925f},{0.217061f,-0.00139831f,0.0918925f},{0.216633f,-0.00133018f,0.100469f}, -{0.217061f,-0.00139831f,0.100469f},{0.217878f,-0.0011336f,0.0918925f},{0.217496f,-0.00132889f,0.100469f}, -{0.217886f,-0.00112806f,0.100469f},{0.217489f,-0.00133018f,0.0918925f},{0.218189f,-0.000825358f,0.0918925f}, -{0.21839f,-0.000434603f,0.100469f},{0.218459f,1.5386e-017f,0.0918925f},{0.21839f,-0.000434603f,0.0918925f}, -{0.218195f,-0.00081707f,0.100469f},{0.218459f,1.5386e-017f,0.100469f},{0.216626f,-0.00132889f,0.0918925f}, -{0.216244f,-0.0011336f,0.100469f},{0.216236f,-0.00112806f,0.0918925f},{0.215927f,-0.00081707f,0.0918925f}, -{0.215933f,-0.000825358f,0.100469f},{0.215732f,-0.000434603f,0.0918925f},{0.215732f,-0.000434603f,0.100469f}, -{0.215663f,1.52148e-017f,0.100469f},{0.215663f,1.52148e-017f,0.0918925f},{2.89787e-017f,0.254546f,0.0918925f}, -{-0.000428086f,0.254614f,0.100469f},{2.89787e-017f,0.254546f,0.100469f},{0.00081707f,0.254811f,0.0918925f}, -{0.000434603f,0.254616f,0.100469f},{0.000825358f,0.254817f,0.100469f},{0.000428086f,0.254614f,0.0918925f}, -{0.00112806f,0.255119f,0.0918925f},{0.00132889f,0.25551f,0.100469f},{0.00139831f,0.255945f,0.0918925f}, -{0.00132889f,0.25551f,0.0918925f},{0.0011336f,0.255128f,0.100469f},{0.00139831f,0.255945f,0.100469f}, -{-0.000434603f,0.254616f,0.0918925f},{-0.00081707f,0.254811f,0.100469f},{-0.000825358f,0.254817f,0.0918925f}, -{-0.0011336f,0.255128f,0.0918925f},{-0.00112806f,0.255119f,0.100469f},{-0.00132889f,0.25551f,0.0918925f}, -{-0.00132889f,0.25551f,0.100469f},{-0.00139831f,0.255945f,0.100469f},{-0.00139831f,0.255945f,0.0918925f}, -{2.89787e-017f,0.217258f,0.0918925f},{-0.000428086f,0.217326f,0.100469f},{2.89787e-017f,0.217258f,0.100469f}, -{0.00081707f,0.217523f,0.0918925f},{0.000434603f,0.217328f,0.100469f},{0.000825358f,0.217528f,0.100469f}, -{0.000428086f,0.217326f,0.0918925f},{0.00112806f,0.217831f,0.0918925f},{0.00132889f,0.218222f,0.100469f}, -{0.00139831f,0.218656f,0.0918925f},{0.00132889f,0.218222f,0.0918925f},{0.0011336f,0.217839f,0.100469f}, -{0.00139831f,0.218656f,0.100469f},{-0.000434603f,0.217328f,0.0918925f},{-0.00081707f,0.217523f,0.100469f}, -{-0.000825358f,0.217528f,0.0918925f},{-0.0011336f,0.217839f,0.0918925f},{-0.00112806f,0.217831f,0.100469f}, -{-0.00132889f,0.218222f,0.0918925f},{-0.00132889f,0.218222f,0.100469f},{-0.00139831f,0.218656f,0.100469f}, -{-0.00139831f,0.218656f,0.0918925f},{0.254583f,-0.00139831f,0.0918925f},{0.254155f,-0.00133018f,0.100469f}, -{0.254583f,-0.00139831f,0.100469f},{0.2554f,-0.0011336f,0.0918925f},{0.255018f,-0.00132889f,0.100469f}, -{0.255408f,-0.00112806f,0.100469f},{0.255011f,-0.00133018f,0.0918925f},{0.255711f,-0.000825358f,0.0918925f}, -{0.255912f,-0.000434603f,0.100469f},{0.255981f,2.35333e-017f,0.0918925f},{0.255912f,-0.000434603f,0.0918925f}, -{0.255717f,-0.00081707f,0.100469f},{0.255981f,2.35333e-017f,0.100469f},{0.254148f,-0.00132889f,0.0918925f}, -{0.253766f,-0.0011336f,0.100469f},{0.253758f,-0.00112806f,0.0918925f},{0.253449f,-0.00081707f,0.0918925f}, -{0.253455f,-0.000825358f,0.100469f},{0.253254f,-0.000434603f,0.0918925f},{0.253254f,-0.000434603f,0.100469f}, -{0.253185f,2.33621e-017f,0.100469f},{0.253185f,2.33621e-017f,0.0918925f},{5.54736e-017f,-0.257343f,0.0918925f}, -{-0.000428086f,-0.257275f,0.100469f},{2.89787e-017f,-0.257343f,0.100469f},{0.00081707f,-0.257078f,0.0918925f}, -{0.000434603f,-0.257274f,0.100469f},{0.000825358f,-0.257073f,0.100469f},{0.000428086f,-0.257275f,0.0918925f}, -{0.00112806f,-0.25677f,0.0918925f},{0.00132889f,-0.256379f,0.100469f},{0.00139831f,-0.255945f,0.0918925f}, -{0.00132889f,-0.256379f,0.0918925f},{0.0011336f,-0.256762f,0.100469f},{0.00139831f,-0.255945f,0.100469f}, -{-0.000434603f,-0.257274f,0.0918925f},{-0.00081707f,-0.257078f,0.100469f},{-0.000825358f,-0.257073f,0.0918925f}, -{-0.0011336f,-0.256762f,0.0918925f},{-0.00112806f,-0.25677f,0.100469f},{-0.00132889f,-0.256379f,0.0918925f}, -{-0.00132889f,-0.256379f,0.100469f},{-0.00139831f,-0.255945f,0.100469f},{-0.00139831f,-0.255945f,0.0918925f}, -{5.54736e-017f,-0.220055f,0.0918925f},{-0.000428086f,-0.219987f,0.100469f},{2.89787e-017f,-0.220055f,0.100469f}, -{0.00081707f,-0.21979f,0.0918925f},{0.000434603f,-0.219985f,0.100469f},{0.000825358f,-0.219785f,0.100469f}, -{0.000428086f,-0.219987f,0.0918925f},{0.00112806f,-0.219482f,0.0918925f},{0.00132889f,-0.219091f,0.100469f}, -{0.00139831f,-0.218656f,0.0918925f},{0.00132889f,-0.219091f,0.0918925f},{0.0011336f,-0.219474f,0.100469f}, -{0.00139831f,-0.218656f,0.100469f},{-0.000434603f,-0.219985f,0.0918925f},{-0.00081707f,-0.21979f,0.100469f}, -{-0.000825358f,-0.219785f,0.0918925f},{-0.0011336f,-0.219474f,0.0918925f},{-0.00112806f,-0.219482f,0.100469f}, -{-0.00132889f,-0.219091f,0.0918925f},{-0.00132889f,-0.219091f,0.100469f},{-0.00139831f,-0.218656f,0.100469f}, -{-0.00139831f,-0.218656f,0.0918925f},{-0.217061f,-0.00139831f,0.0918925f},{-0.217489f,-0.00133018f,0.100469f}, -{-0.217061f,-0.00139831f,0.100469f},{-0.216244f,-0.0011336f,0.0918925f},{-0.216626f,-0.00132889f,0.100469f}, -{-0.216236f,-0.00112806f,0.100469f},{-0.216633f,-0.00133018f,0.0918925f},{-0.215933f,-0.000825358f,0.0918925f}, -{-0.215732f,-0.000434603f,0.100469f},{-0.215663f,1.5386e-017f,0.0918925f},{-0.215732f,-0.000434603f,0.0918925f}, -{-0.215927f,-0.00081707f,0.100469f},{-0.215663f,1.5386e-017f,0.100469f},{-0.217496f,-0.00132889f,0.0918925f}, -{-0.217878f,-0.0011336f,0.100469f},{-0.217886f,-0.00112806f,0.0918925f},{-0.218195f,-0.00081707f,0.0918925f}, -{-0.218189f,-0.000825358f,0.100469f},{-0.21839f,-0.000434603f,0.0918925f},{-0.21839f,-0.000434603f,0.100469f}, -{-0.218459f,1.52148e-017f,0.100469f},{-0.218459f,1.52148e-017f,0.0918925f},{-0.0206412f,-0.0600622f,0.0918925f}, -{-0.0218566f,-0.0614015f,0.0918925f},{-0.0218559f,-0.0614007f,0.100469f},{-0.0446572f,-0.069784f,0.100469f}, -{-0.0428559f,-0.0699006f,0.0918925f},{-0.0446573f,-0.069784f,0.0918925f},{-0.0410436f,-0.0699007f,0.0918925f}, -{-0.0428548f,-0.0699007f,0.100469f},{-0.0464389f,-0.0695527f,0.100469f},{-0.0464391f,-0.0695526f,0.0918925f}, -{-0.0481956f,-0.0692089f,0.100469f},{-0.0481959f,-0.0692088f,0.0918925f},{-0.0499225f,-0.0687547f,0.100469f}, -{-0.0499226f,-0.0687546f,0.0918925f},{-0.0516141f,-0.0681921f,0.100469f},{-0.0564273f,-0.065876f,0.100469f}, -{-0.0548716f,-0.0667507f,0.100469f},{-0.0548718f,-0.0667507f,0.0918925f},{-0.0516143f,-0.0681921f,0.0918925f}, -{-0.0532658f,-0.0675234f,0.0918925f},{-0.0532655f,-0.0675235f,0.100469f},{-0.0579272f,-0.0649016f,0.100469f}, -{-0.0564274f,-0.065876f,0.0918925f},{-0.0579275f,-0.0649015f,0.0918925f},{-0.0593666f,-0.0638294f,0.100469f}, -{-0.0607404f,-0.0626615f,0.0918925f},{-0.0607403f,-0.0626615f,0.100469f},{-0.0593668f,-0.0638293f,0.0918925f}, -{-0.0620418f,-0.0614015f,0.100469f},{-0.0620425f,-0.0614007f,0.0918925f},{-0.0632572f,-0.0600622f,0.100469f}, -{-0.0632573f,-0.0600619f,0.0918925f},{-0.0643775f,-0.0586549f,0.0918925f},{-0.0643775f,-0.058655f,0.100469f}, -{-0.0693947f,-0.0473208f,0.100469f},{-0.0689955f,-0.0490631f,0.0918925f},{-0.0693947f,-0.0473207f,0.0918925f}, -{-0.066326f,-0.055656f,0.0918925f},{-0.0671499f,-0.0540747f,0.100469f},{-0.0663259f,-0.0556563f,0.100469f}, -{-0.0654011f,-0.0571847f,0.100469f},{-0.0654012f,-0.0571845f,0.0918925f},{-0.06715f,-0.0540746f,0.0918925f}, -{-0.0678709f,-0.0524453f,0.100469f},{-0.067871f,-0.0524451f,0.0918925f},{-0.0684867f,-0.0507732f,0.100469f}, -{-0.0684868f,-0.0507729f,0.0918925f},{-0.0689954f,-0.0490633f,0.100469f},{-0.0696826f,-0.0455508f,0.0918925f}, -{-0.0698568f,-0.0437586f,0.0918925f},{-0.0698567f,-0.0437588f,0.100469f},{-0.0696825f,-0.045551f,0.100469f}, -{-0.0699153f,-0.0419492f,0.100469f},{-0.0699153f,-0.0419492f,0.0918925f},{-0.0410425f,-0.0699006f,0.100469f}, -{-0.0392411f,-0.069784f,0.100469f},{-0.0392412f,-0.069784f,0.0918925f},{-0.0374596f,-0.0695527f,0.0918925f}, -{-0.0374593f,-0.0695526f,0.100469f},{-0.0357025f,-0.0692088f,0.100469f},{-0.0357028f,-0.0692089f,0.0918925f}, -{-0.0339758f,-0.0687546f,0.100469f},{-0.033976f,-0.0687547f,0.0918925f},{-0.0322843f,-0.0681921f,0.0918925f}, -{-0.0322841f,-0.0681921f,0.100469f},{-0.0306327f,-0.0675234f,0.100469f},{-0.030633f,-0.0675235f,0.0918925f}, -{-0.0290267f,-0.0667507f,0.100469f},{-0.0290268f,-0.0667507f,0.0918925f},{-0.0274712f,-0.065876f,0.0918925f}, -{-0.027471f,-0.065876f,0.100469f},{-0.0259709f,-0.0649015f,0.100469f},{-0.0259712f,-0.0649016f,0.0918925f}, -{-0.0245316f,-0.0638293f,0.100469f},{-0.0245318f,-0.0638294f,0.0918925f},{-0.0231581f,-0.0626615f,0.0918925f}, -{-0.023158f,-0.0626615f,0.100469f},{-0.0206411f,-0.0600619f,0.100469f},{-0.0195209f,-0.0586549f,0.100469f}, -{-0.0195209f,-0.058655f,0.0918925f},{-0.0184973f,-0.0571847f,0.0918925f},{-0.0184973f,-0.0571845f,0.100469f}, -{-0.0175724f,-0.055656f,0.100469f},{-0.0175725f,-0.0556563f,0.0918925f},{-0.0167485f,-0.0540746f,0.100469f}, -{-0.0167485f,-0.0540747f,0.0918925f},{-0.0160275f,-0.0524453f,0.0918925f},{-0.0160275f,-0.0524451f,0.100469f}, -{-0.0154116f,-0.0507729f,0.100469f},{-0.0154117f,-0.0507732f,0.0918925f},{-0.014903f,-0.0490631f,0.100469f}, -{-0.014903f,-0.0490633f,0.0918925f},{-0.0145037f,-0.0473208f,0.0918925f},{-0.0145037f,-0.0473207f,0.100469f}, -{-0.0142158f,-0.0455508f,0.100469f},{-0.0142159f,-0.045551f,0.0918925f},{-0.0140416f,-0.0437586f,0.100469f}, -{-0.0140417f,-0.0437588f,0.0918925f},{-0.0139831f,-0.0419492f,0.0918925f},{-0.0139831f,-0.0419492f,0.100469f}, -{-0.0206412f,0.0238362f,0.0918925f},{-0.0218566f,0.0224969f,0.0918925f},{-0.0218559f,0.0224977f,0.100469f}, -{-0.0446572f,0.0141144f,0.100469f},{-0.0428559f,0.0139978f,0.0918925f},{-0.0446573f,0.0141144f,0.0918925f}, -{-0.0410436f,0.0139977f,0.0918925f},{-0.0428548f,0.0139977f,0.100469f},{-0.0464389f,0.0143457f,0.100469f}, -{-0.0464391f,0.0143458f,0.0918925f},{-0.0481956f,0.0146895f,0.100469f},{-0.0481959f,0.0146896f,0.0918925f}, -{-0.0499225f,0.0151437f,0.100469f},{-0.0499226f,0.0151438f,0.0918925f},{-0.0516141f,0.0157063f,0.100469f}, -{-0.0564273f,0.0180224f,0.100469f},{-0.0548716f,0.0171477f,0.100469f},{-0.0548718f,0.0171478f,0.0918925f}, -{-0.0516143f,0.0157063f,0.0918925f},{-0.0532658f,0.016375f,0.0918925f},{-0.0532655f,0.0163749f,0.100469f}, -{-0.0579272f,0.0189968f,0.100469f},{-0.0564274f,0.0180224f,0.0918925f},{-0.0579275f,0.018997f,0.0918925f}, -{-0.0593666f,0.020069f,0.100469f},{-0.0607404f,0.0212369f,0.0918925f},{-0.0607403f,0.0212369f,0.100469f}, -{-0.0593668f,0.0200691f,0.0918925f},{-0.0620418f,0.0224969f,0.100469f},{-0.0620425f,0.0224977f,0.0918925f}, -{-0.0632572f,0.0238362f,0.100469f},{-0.0632573f,0.0238365f,0.0918925f},{-0.0643775f,0.0252435f,0.0918925f}, -{-0.0643775f,0.0252434f,0.100469f},{-0.0693947f,0.0365776f,0.100469f},{-0.0689955f,0.0348353f,0.0918925f}, -{-0.0693947f,0.0365777f,0.0918925f},{-0.066326f,0.0282424f,0.0918925f},{-0.0671499f,0.0298237f,0.100469f}, -{-0.0663259f,0.0282422f,0.100469f},{-0.0654011f,0.0267137f,0.100469f},{-0.0654012f,0.0267139f,0.0918925f}, -{-0.06715f,0.0298238f,0.0918925f},{-0.0678709f,0.0314531f,0.100469f},{-0.067871f,0.0314533f,0.0918925f}, -{-0.0684867f,0.0331252f,0.100469f},{-0.0684868f,0.0331255f,0.0918925f},{-0.0689954f,0.0348351f,0.100469f}, -{-0.0696826f,0.0383477f,0.0918925f},{-0.0698568f,0.0401399f,0.0918925f},{-0.0698567f,0.0401396f,0.100469f}, -{-0.0696825f,0.0383474f,0.100469f},{-0.0699153f,0.0419492f,0.100469f},{-0.0699153f,0.0419492f,0.0918925f}, -{-0.0410425f,0.0139978f,0.100469f},{-0.0392411f,0.0141144f,0.100469f},{-0.0392412f,0.0141144f,0.0918925f}, -{-0.0374596f,0.0143457f,0.0918925f},{-0.0374593f,0.0143458f,0.100469f},{-0.0357025f,0.0146896f,0.100469f}, -{-0.0357028f,0.0146895f,0.0918925f},{-0.0339758f,0.0151438f,0.100469f},{-0.033976f,0.0151437f,0.0918925f}, -{-0.0322843f,0.0157063f,0.0918925f},{-0.0322841f,0.0157063f,0.100469f},{-0.0306327f,0.016375f,0.100469f}, -{-0.030633f,0.0163749f,0.0918925f},{-0.0290267f,0.0171478f,0.100469f},{-0.0290268f,0.0171477f,0.0918925f}, -{-0.0274712f,0.0180224f,0.0918925f},{-0.027471f,0.0180224f,0.100469f},{-0.0259709f,0.018997f,0.100469f}, -{-0.0259712f,0.0189968f,0.0918925f},{-0.0245316f,0.0200691f,0.100469f},{-0.0245318f,0.020069f,0.0918925f}, -{-0.0231581f,0.0212369f,0.0918925f},{-0.023158f,0.0212369f,0.100469f},{-0.0206411f,0.0238365f,0.100469f}, -{-0.0195209f,0.0252435f,0.100469f},{-0.0195209f,0.0252434f,0.0918925f},{-0.0184973f,0.0267137f,0.0918925f}, -{-0.0184973f,0.0267139f,0.100469f},{-0.0175724f,0.0282424f,0.100469f},{-0.0175725f,0.0282422f,0.0918925f}, -{-0.0167485f,0.0298238f,0.100469f},{-0.0167485f,0.0298237f,0.0918925f},{-0.0160275f,0.0314531f,0.0918925f}, -{-0.0160275f,0.0314533f,0.100469f},{-0.0154116f,0.0331255f,0.100469f},{-0.0154117f,0.0331252f,0.0918925f}, -{-0.014903f,0.0348353f,0.100469f},{-0.014903f,0.0348351f,0.0918925f},{-0.0145037f,0.0365776f,0.0918925f}, -{-0.0145037f,0.0365777f,0.100469f},{-0.0142158f,0.0383477f,0.100469f},{-0.0142159f,0.0383474f,0.0918925f}, -{-0.0140416f,0.0401399f,0.100469f},{-0.0140417f,0.0401396f,0.0918925f},{-0.0139831f,0.0419492f,0.0918925f}, -{-0.0139831f,0.0419492f,0.100469f},{0.0632572f,-0.0600622f,0.0918925f},{0.0620418f,-0.0614015f,0.0918925f}, -{0.0620425f,-0.0614007f,0.100469f},{0.0392412f,-0.069784f,0.100469f},{0.0410425f,-0.0699006f,0.0918925f}, -{0.0392411f,-0.069784f,0.0918925f},{0.0428548f,-0.0699007f,0.0918925f},{0.0410436f,-0.0699007f,0.100469f}, -{0.0374596f,-0.0695527f,0.100469f},{0.0374593f,-0.0695526f,0.0918925f},{0.0357028f,-0.0692089f,0.100469f}, -{0.0357025f,-0.0692088f,0.0918925f},{0.033976f,-0.0687547f,0.100469f},{0.0339758f,-0.0687546f,0.0918925f}, -{0.0322843f,-0.0681921f,0.100469f},{0.0274712f,-0.065876f,0.100469f},{0.0290268f,-0.0667507f,0.100469f}, -{0.0290267f,-0.0667507f,0.0918925f},{0.0322841f,-0.0681921f,0.0918925f},{0.0306327f,-0.0675234f,0.0918925f}, -{0.030633f,-0.0675235f,0.100469f},{0.0259712f,-0.0649016f,0.100469f},{0.027471f,-0.065876f,0.0918925f}, -{0.0259709f,-0.0649015f,0.0918925f},{0.0245318f,-0.0638294f,0.100469f},{0.023158f,-0.0626615f,0.0918925f}, -{0.0231581f,-0.0626615f,0.100469f},{0.0245316f,-0.0638293f,0.0918925f},{0.0218566f,-0.0614015f,0.100469f}, -{0.0218559f,-0.0614007f,0.0918925f},{0.0206412f,-0.0600622f,0.100469f},{0.0206411f,-0.0600619f,0.0918925f}, -{0.0195209f,-0.0586549f,0.0918925f},{0.0195209f,-0.058655f,0.100469f},{0.0145037f,-0.0473208f,0.100469f}, -{0.014903f,-0.0490631f,0.0918925f},{0.0145037f,-0.0473207f,0.0918925f},{0.0175724f,-0.055656f,0.0918925f}, -{0.0167485f,-0.0540747f,0.100469f},{0.0175725f,-0.0556563f,0.100469f},{0.0184973f,-0.0571847f,0.100469f}, -{0.0184973f,-0.0571845f,0.0918925f},{0.0167485f,-0.0540746f,0.0918925f},{0.0160275f,-0.0524453f,0.100469f}, -{0.0160275f,-0.0524451f,0.0918925f},{0.0154117f,-0.0507732f,0.100469f},{0.0154116f,-0.0507729f,0.0918925f}, -{0.014903f,-0.0490633f,0.100469f},{0.0142158f,-0.0455508f,0.0918925f},{0.0140416f,-0.0437586f,0.0918925f}, -{0.0140417f,-0.0437588f,0.100469f},{0.0142159f,-0.045551f,0.100469f},{0.0139831f,-0.0419492f,0.100469f}, -{0.0139831f,-0.0419492f,0.0918925f},{0.0428559f,-0.0699006f,0.100469f},{0.0446573f,-0.069784f,0.100469f}, -{0.0446572f,-0.069784f,0.0918925f},{0.0464389f,-0.0695527f,0.0918925f},{0.0464391f,-0.0695526f,0.100469f}, -{0.0481959f,-0.0692088f,0.100469f},{0.0481956f,-0.0692089f,0.0918925f},{0.0499226f,-0.0687546f,0.100469f}, -{0.0499225f,-0.0687547f,0.0918925f},{0.0516141f,-0.0681921f,0.0918925f},{0.0516143f,-0.0681921f,0.100469f}, -{0.0532658f,-0.0675234f,0.100469f},{0.0532655f,-0.0675235f,0.0918925f},{0.0548718f,-0.0667507f,0.100469f}, -{0.0548716f,-0.0667507f,0.0918925f},{0.0564273f,-0.065876f,0.0918925f},{0.0564274f,-0.065876f,0.100469f}, -{0.0579275f,-0.0649015f,0.100469f},{0.0579272f,-0.0649016f,0.0918925f},{0.0593668f,-0.0638293f,0.100469f}, -{0.0593666f,-0.0638294f,0.0918925f},{0.0607403f,-0.0626615f,0.0918925f},{0.0607404f,-0.0626615f,0.100469f}, -{0.0632573f,-0.0600619f,0.100469f},{0.0643775f,-0.0586549f,0.100469f},{0.0643775f,-0.058655f,0.0918925f}, -{0.0654011f,-0.0571847f,0.0918925f},{0.0654012f,-0.0571845f,0.100469f},{0.066326f,-0.055656f,0.100469f}, -{0.0663259f,-0.0556563f,0.0918925f},{0.06715f,-0.0540746f,0.100469f},{0.0671499f,-0.0540747f,0.0918925f}, -{0.0678709f,-0.0524453f,0.0918925f},{0.067871f,-0.0524451f,0.100469f},{0.0684868f,-0.0507729f,0.100469f}, -{0.0684867f,-0.0507732f,0.0918925f},{0.0689955f,-0.0490631f,0.100469f},{0.0689954f,-0.0490633f,0.0918925f}, -{0.0693947f,-0.0473208f,0.0918925f},{0.0693947f,-0.0473207f,0.100469f},{0.0696826f,-0.0455508f,0.100469f}, -{0.0696825f,-0.045551f,0.0918925f},{0.0698568f,-0.0437586f,0.100469f},{0.0698567f,-0.0437588f,0.0918925f}, -{0.0699153f,-0.0419492f,0.0918925f},{0.0699153f,-0.0419492f,0.100469f},{0.0632572f,0.0238362f,0.0918925f}, -{0.0620418f,0.0224969f,0.0918925f},{0.0620425f,0.0224977f,0.100469f},{0.0392412f,0.0141144f,0.100469f}, -{0.0410425f,0.0139978f,0.0918925f},{0.0392411f,0.0141144f,0.0918925f},{0.0428548f,0.0139977f,0.0918925f}, -{0.0410436f,0.0139977f,0.100469f},{0.0374596f,0.0143457f,0.100469f},{0.0374593f,0.0143458f,0.0918925f}, -{0.0357028f,0.0146895f,0.100469f},{0.0357025f,0.0146896f,0.0918925f},{0.033976f,0.0151437f,0.100469f}, -{0.0339758f,0.0151438f,0.0918925f},{0.0322843f,0.0157063f,0.100469f},{0.0274712f,0.0180224f,0.100469f}, -{0.0290268f,0.0171477f,0.100469f},{0.0290267f,0.0171478f,0.0918925f},{0.0322841f,0.0157063f,0.0918925f}, -{0.0306327f,0.016375f,0.0918925f},{0.030633f,0.0163749f,0.100469f},{0.0259712f,0.0189968f,0.100469f}, -{0.027471f,0.0180224f,0.0918925f},{0.0259709f,0.018997f,0.0918925f},{0.0245318f,0.020069f,0.100469f}, -{0.023158f,0.0212369f,0.0918925f},{0.0231581f,0.0212369f,0.100469f},{0.0245316f,0.0200691f,0.0918925f}, -{0.0218566f,0.0224969f,0.100469f},{0.0218559f,0.0224977f,0.0918925f},{0.0206412f,0.0238362f,0.100469f}, -{0.0206411f,0.0238365f,0.0918925f},{0.0195209f,0.0252435f,0.0918925f},{0.0195209f,0.0252434f,0.100469f}, -{0.0145037f,0.0365776f,0.100469f},{0.014903f,0.0348353f,0.0918925f},{0.0145037f,0.0365777f,0.0918925f}, -{0.0175724f,0.0282424f,0.0918925f},{0.0167485f,0.0298237f,0.100469f},{0.0175725f,0.0282422f,0.100469f}, -{0.0184973f,0.0267137f,0.100469f},{0.0184973f,0.0267139f,0.0918925f},{0.0167485f,0.0298238f,0.0918925f}, -{0.0160275f,0.0314531f,0.100469f},{0.0160275f,0.0314533f,0.0918925f},{0.0154117f,0.0331252f,0.100469f}, -{0.0154116f,0.0331255f,0.0918925f},{0.014903f,0.0348351f,0.100469f},{0.0142158f,0.0383477f,0.0918925f}, -{0.0140416f,0.0401399f,0.0918925f},{0.0140417f,0.0401396f,0.100469f},{0.0142159f,0.0383474f,0.100469f}, -{0.0139831f,0.0419492f,0.100469f},{0.0139831f,0.0419492f,0.0918925f},{0.0428559f,0.0139978f,0.100469f}, -{0.0446573f,0.0141144f,0.100469f},{0.0446572f,0.0141144f,0.0918925f},{0.0464389f,0.0143457f,0.0918925f}, -{0.0464391f,0.0143458f,0.100469f},{0.0481959f,0.0146896f,0.100469f},{0.0481956f,0.0146895f,0.0918925f}, -{0.0499226f,0.0151438f,0.100469f},{0.0499225f,0.0151437f,0.0918925f},{0.0516141f,0.0157063f,0.0918925f}, -{0.0516143f,0.0157063f,0.100469f},{0.0532658f,0.016375f,0.100469f},{0.0532655f,0.0163749f,0.0918925f}, -{0.0548718f,0.0171478f,0.100469f},{0.0548716f,0.0171477f,0.0918925f},{0.0564273f,0.0180224f,0.0918925f}, -{0.0564274f,0.0180224f,0.100469f},{0.0579275f,0.018997f,0.100469f},{0.0579272f,0.0189968f,0.0918925f}, -{0.0593668f,0.0200691f,0.100469f},{0.0593666f,0.020069f,0.0918925f},{0.0607403f,0.0212369f,0.0918925f}, -{0.0607404f,0.0212369f,0.100469f},{0.0632573f,0.0238365f,0.100469f},{0.0643775f,0.0252435f,0.100469f}, -{0.0643775f,0.0252434f,0.0918925f},{0.0654011f,0.0267137f,0.0918925f},{0.0654012f,0.0267139f,0.100469f}, -{0.066326f,0.0282424f,0.100469f},{0.0663259f,0.0282422f,0.0918925f},{0.06715f,0.0298238f,0.100469f}, -{0.0671499f,0.0298237f,0.0918925f},{0.0678709f,0.0314531f,0.0918925f},{0.067871f,0.0314533f,0.100469f}, -{0.0684868f,0.0331255f,0.100469f},{0.0684867f,0.0331252f,0.0918925f},{0.0689955f,0.0348353f,0.100469f}, -{0.0689954f,0.0348351f,0.0918925f},{0.0693947f,0.0365776f,0.0918925f},{0.0693947f,0.0365777f,0.100469f}, -{0.0696826f,0.0383477f,0.100469f},{0.0696825f,0.0383474f,0.0918925f},{0.0698568f,0.0401399f,0.100469f}, -{0.0698567f,0.0401396f,0.0918925f},{0.0699153f,0.0419492f,0.0918925f},{0.0699153f,0.0419492f,0.100469f}, -{0.0394436f,-0.0838832f,0.0918925f},{0.0388582f,-0.0838826f,0.0918925f},{0.0388615f,-0.0838832f,0.100469f}, -{0.039447f,-0.0838826f,0.100469f},{0.0400161f,-0.0837618f,0.0918925f},{0.0400177f,-0.0837612f,0.100469f}, -{0.0405514f,-0.0835236f,0.100469f},{0.0410221f,-0.0831813f,0.0918925f},{0.0405497f,-0.0835243f,0.0918925f}, -{0.0410252f,-0.0831785f,0.100469f},{0.0414146f,-0.0827462f,0.0918925f},{0.0414155f,-0.082745f,0.100469f}, -{0.041707f,-0.0822403f,0.0918925f},{0.041708f,-0.0822379f,0.100469f},{0.0418875f,-0.0816851f,0.0918925f}, -{0.041888f,-0.0816836f,0.100469f},{0.0419492f,-0.0811018f,0.100469f},{0.0382891f,-0.0837618f,0.100469f}, -{0.0377555f,-0.0835243f,0.100469f},{0.0382875f,-0.0837612f,0.0918925f},{0.0377538f,-0.0835236f,0.0918925f}, -{0.037283f,-0.0831813f,0.100469f},{0.0372799f,-0.0831785f,0.0918925f},{0.0368906f,-0.0827462f,0.100469f}, -{0.0365982f,-0.0822403f,0.100469f},{0.0368897f,-0.082745f,0.0918925f},{0.0365972f,-0.0822379f,0.0918925f}, -{0.0364177f,-0.0816851f,0.100469f},{0.0364172f,-0.0816836f,0.0918925f},{0.036356f,-0.0811018f,0.100469f}, -{-0.0388615f,-0.0838832f,0.0918925f},{-0.039447f,-0.0838826f,0.0918925f},{-0.0394436f,-0.0838832f,0.100469f}, -{-0.0388582f,-0.0838826f,0.100469f},{-0.0382891f,-0.0837618f,0.0918925f},{-0.0382875f,-0.0837612f,0.100469f}, -{-0.0377538f,-0.0835236f,0.100469f},{-0.037283f,-0.0831813f,0.0918925f},{-0.0377555f,-0.0835243f,0.0918925f}, -{-0.0372799f,-0.0831785f,0.100469f},{-0.0368906f,-0.0827462f,0.0918925f},{-0.0368897f,-0.082745f,0.100469f}, -{-0.0365982f,-0.0822403f,0.0918925f},{-0.0365972f,-0.0822379f,0.100469f},{-0.0364177f,-0.0816851f,0.0918925f}, -{-0.0364172f,-0.0816836f,0.100469f},{-0.036356f,-0.0811018f,0.100469f},{-0.0400161f,-0.0837618f,0.100469f}, -{-0.0405497f,-0.0835243f,0.100469f},{-0.0400177f,-0.0837612f,0.0918925f},{-0.0405514f,-0.0835236f,0.0918925f}, -{-0.0410221f,-0.0831813f,0.100469f},{-0.0410252f,-0.0831785f,0.0918925f},{-0.0414146f,-0.0827462f,0.100469f}, -{-0.041707f,-0.0822403f,0.100469f},{-0.0414155f,-0.082745f,0.0918925f},{-0.041708f,-0.0822379f,0.0918925f}, -{-0.0418875f,-0.0816851f,0.100469f},{-0.041888f,-0.0816836f,0.0918925f},{-0.0419492f,-0.0811018f,0.100469f}, -{0.0394436f,0.0783204f,0.0918925f},{0.0388582f,0.078321f,0.0918925f},{0.0388615f,0.0783204f,0.100469f}, -{0.039447f,0.078321f,0.100469f},{0.0400161f,0.0784418f,0.0918925f},{0.0400177f,0.0784424f,0.100469f}, -{0.0405514f,0.07868f,0.100469f},{0.0410221f,0.0790223f,0.0918925f},{0.0405497f,0.0786793f,0.0918925f}, -{0.0410252f,0.0790251f,0.100469f},{0.0414146f,0.0794574f,0.0918925f},{0.0414155f,0.0794586f,0.100469f}, -{0.041707f,0.0799633f,0.0918925f},{0.041708f,0.0799657f,0.100469f},{0.0418875f,0.0805185f,0.0918925f}, -{0.041888f,0.08052f,0.100469f},{0.0419492f,0.0811018f,0.100469f},{0.0382891f,0.0784418f,0.100469f}, -{0.0377555f,0.0786793f,0.100469f},{0.0382875f,0.0784424f,0.0918925f},{0.0377538f,0.07868f,0.0918925f}, -{0.037283f,0.0790223f,0.100469f},{0.0372799f,0.0790251f,0.0918925f},{0.0368906f,0.0794574f,0.100469f}, -{0.0365982f,0.0799633f,0.100469f},{0.0368897f,0.0794586f,0.0918925f},{0.0365972f,0.0799657f,0.0918925f}, -{0.0364177f,0.0805185f,0.100469f},{0.0364172f,0.08052f,0.0918925f},{0.036356f,0.0811018f,0.100469f}, -{-0.0388615f,0.0783204f,0.0918925f},{-0.039447f,0.078321f,0.0918925f},{-0.0394436f,0.0783204f,0.100469f}, -{-0.0388582f,0.078321f,0.100469f},{-0.0382891f,0.0784418f,0.0918925f},{-0.0382875f,0.0784424f,0.100469f}, -{-0.0377538f,0.07868f,0.100469f},{-0.037283f,0.0790223f,0.0918925f},{-0.0377555f,0.0786793f,0.0918925f}, -{-0.0372799f,0.0790251f,0.100469f},{-0.0368906f,0.0794574f,0.0918925f},{-0.0368897f,0.0794586f,0.100469f}, -{-0.0365982f,0.0799633f,0.0918925f},{-0.0365972f,0.0799657f,0.100469f},{-0.0364177f,0.0805185f,0.0918925f}, -{-0.0364172f,0.08052f,0.100469f},{-0.036356f,0.0811018f,0.100469f},{-0.0400161f,0.0784418f,0.100469f}, -{-0.0405497f,0.0786793f,0.100469f},{-0.0400177f,0.0784424f,0.0918925f},{-0.0405514f,0.07868f,0.0918925f}, -{-0.0410221f,0.0790223f,0.100469f},{-0.0410252f,0.0790251f,0.0918925f},{-0.0414146f,0.0794574f,0.100469f}, -{-0.041707f,0.0799633f,0.100469f},{-0.0414155f,0.0794586f,0.0918925f},{-0.041708f,0.0799657f,0.0918925f}, -{-0.0418875f,0.0805185f,0.100469f},{-0.041888f,0.08052f,0.0918925f},{-0.0419492f,0.0811018f,0.100469f}, -{-0.0808108f,0.0783204f,0.0918925f},{-0.0813962f,0.078321f,0.0918925f},{-0.0813929f,0.0783204f,0.100469f}, -{-0.0808074f,0.078321f,0.100469f},{-0.0802383f,0.0784418f,0.0918925f},{-0.0802367f,0.0784424f,0.100469f}, -{-0.079703f,0.07868f,0.100469f},{-0.0792323f,0.0790223f,0.0918925f},{-0.0797047f,0.0786793f,0.0918925f}, -{-0.0792292f,0.0790251f,0.100469f},{-0.0788398f,0.0794574f,0.0918925f},{-0.0788389f,0.0794586f,0.100469f}, -{-0.0785474f,0.0799633f,0.0918925f},{-0.0785464f,0.0799657f,0.100469f},{-0.0783669f,0.0805185f,0.0918925f}, -{-0.0783664f,0.08052f,0.100469f},{-0.0783052f,0.0811018f,0.100469f},{-0.0783052f,0.0811018f,0.0918925f}, -{-0.0819653f,0.0784418f,0.100469f},{-0.0824989f,0.0786793f,0.100469f},{-0.0819669f,0.0784424f,0.0918925f}, -{-0.0825006f,0.07868f,0.0918925f},{-0.0829714f,0.0790223f,0.100469f},{-0.0829744f,0.0790251f,0.0918925f}, -{-0.0833638f,0.0794574f,0.100469f},{-0.0836562f,0.0799633f,0.100469f},{-0.0833647f,0.0794586f,0.0918925f}, -{-0.0836572f,0.0799657f,0.0918925f},{-0.0838367f,0.0805185f,0.100469f},{-0.0838372f,0.08052f,0.0918925f}, -{-0.0838984f,0.0811018f,0.100469f},{-0.0838984f,0.0811018f,0.0918925f},{0.0813929f,0.0783204f,0.0918925f}, -{0.0808074f,0.078321f,0.0918925f},{0.0808108f,0.0783204f,0.100469f},{0.0813962f,0.078321f,0.100469f}, -{0.0819653f,0.0784418f,0.0918925f},{0.0819669f,0.0784424f,0.100469f},{0.0825006f,0.07868f,0.100469f}, -{0.0829714f,0.0790223f,0.0918925f},{0.0824989f,0.0786793f,0.0918925f},{0.0829744f,0.0790251f,0.100469f}, -{0.0833638f,0.0794574f,0.0918925f},{0.0833647f,0.0794586f,0.100469f},{0.0836562f,0.0799633f,0.0918925f}, -{0.0836572f,0.0799657f,0.100469f},{0.0838367f,0.0805185f,0.0918925f},{0.0838372f,0.08052f,0.100469f}, -{0.0838984f,0.0811018f,0.100469f},{0.0838984f,0.0811018f,0.0918925f},{0.0802383f,0.0784418f,0.100469f}, -{0.0797047f,0.0786793f,0.100469f},{0.0802367f,0.0784424f,0.0918925f},{0.079703f,0.07868f,0.0918925f}, -{0.0792323f,0.0790223f,0.100469f},{0.0792292f,0.0790251f,0.0918925f},{0.0788398f,0.0794574f,0.100469f}, -{0.0785474f,0.0799633f,0.100469f},{0.0788389f,0.0794586f,0.0918925f},{0.0785464f,0.0799657f,0.0918925f}, -{0.0783669f,0.0805185f,0.100469f},{0.0783664f,0.08052f,0.0918925f},{0.0783052f,0.0811018f,0.100469f}, -{0.0783052f,0.0811018f,0.0918925f},{0.0813929f,-0.0838832f,0.0918925f},{0.0808074f,-0.0838826f,0.0918925f}, -{0.0808108f,-0.0838832f,0.100469f},{0.0813962f,-0.0838826f,0.100469f},{0.0819653f,-0.0837618f,0.0918925f}, -{0.0819669f,-0.0837612f,0.100469f},{0.0825006f,-0.0835236f,0.100469f},{0.0829714f,-0.0831813f,0.0918925f}, -{0.0824989f,-0.0835243f,0.0918925f},{0.0829744f,-0.0831785f,0.100469f},{0.0833638f,-0.0827462f,0.0918925f}, -{0.0833647f,-0.082745f,0.100469f},{0.0836562f,-0.0822403f,0.0918925f},{0.0836572f,-0.0822379f,0.100469f}, -{0.0838367f,-0.0816851f,0.0918925f},{0.0838372f,-0.0816836f,0.100469f},{0.0838984f,-0.0811018f,0.100469f}, -{0.0838984f,-0.0811018f,0.0918925f},{0.0802383f,-0.0837618f,0.100469f},{0.0797047f,-0.0835243f,0.100469f}, -{0.0802367f,-0.0837612f,0.0918925f},{0.079703f,-0.0835236f,0.0918925f},{0.0792323f,-0.0831813f,0.100469f}, -{0.0792292f,-0.0831785f,0.0918925f},{0.0788398f,-0.0827462f,0.100469f},{0.0785474f,-0.0822403f,0.100469f}, -{0.0788389f,-0.082745f,0.0918925f},{0.0785464f,-0.0822379f,0.0918925f},{0.0783669f,-0.0816851f,0.100469f}, -{0.0783664f,-0.0816836f,0.0918925f},{0.0783052f,-0.0811018f,0.100469f},{0.0783052f,-0.0811018f,0.0918925f}, -{-0.0603023f,-0.0838832f,0.0918925f},{-0.0608877f,-0.0838826f,0.0918925f},{-0.0608844f,-0.0838832f,0.100469f}, -{-0.0602989f,-0.0838826f,0.100469f},{-0.0597298f,-0.0837618f,0.0918925f},{-0.0597282f,-0.0837612f,0.100469f}, -{-0.0591945f,-0.0835236f,0.100469f},{-0.0587238f,-0.0831813f,0.0918925f},{-0.0591962f,-0.0835243f,0.0918925f}, -{-0.0587207f,-0.0831785f,0.100469f},{-0.0583313f,-0.0827462f,0.0918925f},{-0.0583304f,-0.082745f,0.100469f}, -{-0.0580389f,-0.0822403f,0.0918925f},{-0.0580379f,-0.0822379f,0.100469f},{-0.0578584f,-0.0816851f,0.0918925f}, -{-0.0578579f,-0.0816836f,0.100469f},{-0.0577967f,-0.0811018f,0.100469f},{-0.0577967f,-0.0811018f,0.0918925f}, -{-0.0614568f,-0.0837618f,0.100469f},{-0.0619904f,-0.0835243f,0.100469f},{-0.0614584f,-0.0837612f,0.0918925f}, -{-0.0619921f,-0.0835236f,0.0918925f},{-0.0624629f,-0.0831813f,0.100469f},{-0.0624659f,-0.0831785f,0.0918925f}, -{-0.0628553f,-0.0827462f,0.100469f},{-0.0631477f,-0.0822403f,0.100469f},{-0.0628562f,-0.082745f,0.0918925f}, -{-0.0631487f,-0.0822379f,0.0918925f},{-0.0633282f,-0.0816851f,0.100469f},{-0.0633287f,-0.0816836f,0.0918925f}, -{-0.0633899f,-0.0811018f,0.100469f},{-0.0633899f,-0.0811018f,0.0918925f},{0.280753f,0.00413429f,0.0918925f}, -{0.281577f,0.005033f,0.0918925f},{0.281577f,0.005033f,0.100469f},{0.282607f,0.00568869f,0.0918925f}, -{0.283758f,0.00605158f,0.100469f},{0.282605f,0.00568781f,0.100469f},{0.284979f,0.00610573f,0.0918925f}, -{0.284979f,0.00610573f,0.100469f},{0.283761f,0.00605247f,0.0918925f},{0.280752f,0.00413168f,0.100469f}, -{0.280193f,0.00305863f,0.100469f},{0.280195f,0.00306124f,0.0918925f},{0.279929f,0.00186868f,0.0918925f}, -{0.279929f,0.00186868f,0.100469f},{0.288796f,-0.00343343f,0.0918925f},{0.288143f,-0.00445856f,0.0918925f}, -{0.288143f,-0.00445842f,0.100469f},{0.287245f,-0.00528145f,0.0918925f},{0.286169f,-0.00584165f,0.100469f}, -{0.287247f,-0.0052798f,0.100469f},{0.284979f,-0.00610573f,0.0918925f},{0.284979f,-0.00610573f,0.100469f}, -{0.286165f,-0.00584289f,0.0918925f},{0.288798f,-0.00343061f,0.100469f},{0.289163f,-0.00227009f,0.100469f}, -{0.289162f,-0.00227354f,0.0918925f},{0.289216f,-0.00105623f,0.0918925f},{0.289216f,-0.00105623f,0.100469f}, -{-0.301706f,-0.00557749f,0.100469f},{-0.300865f,-0.00557653f,0.100469f},{-0.300871f,-0.00557749f,0.0918925f}, -{-0.302537f,-0.00545222f,0.100469f},{-0.301712f,-0.00557653f,0.0918925f},{-0.302539f,-0.00545147f,0.0918925f}, -{-0.303332f,-0.00520667f,0.100469f},{-0.303333f,-0.00520615f,0.0918925f},{-0.304083f,-0.00484531f,0.0918925f}, -{-0.30408f,-0.00484666f,0.100469f},{-0.30477f,-0.00437673f,0.100469f},{-0.305913f,-0.00314621f,0.0918925f}, -{-0.306328f,-0.0024268f,0.100469f},{-0.305912f,-0.00314718f,0.100469f},{-0.304776f,-0.00437292f,0.0918925f}, -{-0.305388f,-0.00380457f,0.100469f},{-0.305391f,-0.00380129f,0.0918925f},{-0.306329f,-0.0024238f,0.0918925f}, -{-0.306632f,-0.00165337f,0.100469f},{-0.306633f,-0.00164971f,0.0918925f},{-0.306818f,-0.000839977f,0.0918925f}, -{-0.306882f,1.19421e-018f,0.100469f},{-0.306818f,-0.000839977f,0.100469f},{-0.306882f,1.19421e-018f,0.0918925f}, -{-0.30004f,-0.00545222f,0.0918925f},{-0.299245f,-0.00520667f,0.0918925f},{-0.300038f,-0.00545147f,0.100469f}, -{-0.299244f,-0.00520615f,0.100469f},{-0.298497f,-0.00484666f,0.0918925f},{-0.298494f,-0.00484531f,0.100469f}, -{-0.297807f,-0.00437673f,0.0918925f},{-0.297189f,-0.00380457f,0.0918925f},{-0.297802f,-0.00437292f,0.100469f}, -{-0.297186f,-0.00380129f,0.100469f},{-0.296665f,-0.00314718f,0.0918925f},{-0.296664f,-0.00314621f,0.100469f}, -{-0.296249f,-0.0024268f,0.0918925f},{-0.295945f,-0.00165337f,0.0918925f},{-0.296248f,-0.0024238f,0.100469f}, -{-0.295944f,-0.00164971f,0.100469f},{-0.295759f,-0.000839977f,0.0918925f},{-0.295759f,-0.000839977f,0.100469f}, -{-0.295695f,5.09237e-019f,0.0918925f},{-0.295695f,5.09237e-019f,0.100469f},{-0.000417625f,0.295711f,0.100469f}, -{0.000423769f,0.295712f,0.100469f},{0.000417625f,0.295711f,0.0918925f},{-0.00124862f,0.295836f,0.100469f}, -{-0.000423769f,0.295712f,0.0918925f},{-0.00125042f,0.295837f,0.0918925f},{-0.00204323f,0.296082f,0.100469f}, -{-0.0020445f,0.296082f,0.0918925f},{-0.00279455f,0.296443f,0.0918925f},{-0.00279128f,0.296442f,0.100469f}, -{-0.00348179f,0.296912f,0.100469f},{-0.00462441f,0.298142f,0.0918925f},{-0.00503944f,0.298862f,0.100469f}, -{-0.00462371f,0.298141f,0.100469f},{-0.00348701f,0.296916f,0.0918925f},{-0.00409988f,0.297484f,0.100469f}, -{-0.00410228f,0.297487f,0.0918925f},{-0.00504068f,0.298865f,0.0918925f},{-0.00534308f,0.299635f,0.100469f}, -{-0.0053446f,0.299639f,0.0918925f},{-0.00552953f,0.300449f,0.0918925f},{-0.00559323f,0.301289f,0.100469f}, -{-0.00552953f,0.300449f,0.100469f},{-0.00559323f,0.301289f,0.0918925f},{0.00124862f,0.295836f,0.0918925f}, -{0.00204323f,0.296082f,0.0918925f},{0.00125042f,0.295837f,0.100469f},{0.0020445f,0.296082f,0.100469f}, -{0.00279128f,0.296442f,0.0918925f},{0.00279455f,0.296443f,0.100469f},{0.00348179f,0.296912f,0.0918925f}, -{0.00409988f,0.297484f,0.0918925f},{0.00348701f,0.296916f,0.100469f},{0.00410228f,0.297487f,0.100469f}, -{0.00462371f,0.298141f,0.0918925f},{0.00462441f,0.298142f,0.100469f},{0.00503944f,0.298862f,0.0918925f}, -{0.00534308f,0.299635f,0.0918925f},{0.00504068f,0.298865f,0.100469f},{0.0053446f,0.299639f,0.100469f}, -{0.00552953f,0.300449f,0.0918925f},{0.00552953f,0.300449f,0.100469f},{0.00559323f,0.301289f,0.0918925f}, -{0.00559323f,0.301289f,0.100469f},{0.300871f,-0.00557749f,0.100469f},{0.301712f,-0.00557653f,0.100469f}, -{0.301706f,-0.00557749f,0.0918925f},{0.30004f,-0.00545222f,0.100469f},{0.300865f,-0.00557653f,0.0918925f}, -{0.300038f,-0.00545147f,0.0918925f},{0.299245f,-0.00520667f,0.100469f},{0.299244f,-0.00520615f,0.0918925f}, -{0.298494f,-0.00484531f,0.0918925f},{0.298497f,-0.00484666f,0.100469f},{0.297807f,-0.00437673f,0.100469f}, -{0.296664f,-0.00314621f,0.0918925f},{0.296249f,-0.0024268f,0.100469f},{0.296665f,-0.00314718f,0.100469f}, -{0.297802f,-0.00437292f,0.0918925f},{0.297189f,-0.00380457f,0.100469f},{0.297186f,-0.00380129f,0.0918925f}, -{0.296248f,-0.0024238f,0.0918925f},{0.295945f,-0.00165337f,0.100469f},{0.295944f,-0.00164971f,0.0918925f}, -{0.295759f,-0.000839977f,0.0918925f},{0.295695f,1.19421e-018f,0.100469f},{0.295759f,-0.000839977f,0.100469f}, -{0.295695f,1.19421e-018f,0.0918925f},{0.302537f,-0.00545222f,0.0918925f},{0.303332f,-0.00520667f,0.0918925f}, -{0.302539f,-0.00545147f,0.100469f},{0.303333f,-0.00520615f,0.100469f},{0.30408f,-0.00484666f,0.0918925f}, -{0.304083f,-0.00484531f,0.100469f},{0.30477f,-0.00437673f,0.0918925f},{0.305388f,-0.00380457f,0.0918925f}, -{0.304776f,-0.00437292f,0.100469f},{0.305391f,-0.00380129f,0.100469f},{0.305912f,-0.00314718f,0.0918925f}, -{0.305913f,-0.00314621f,0.100469f},{0.306328f,-0.0024268f,0.0918925f},{0.306632f,-0.00165337f,0.0918925f}, -{0.306329f,-0.0024238f,0.100469f},{0.306633f,-0.00164971f,0.100469f},{0.306818f,-0.000839977f,0.0918925f}, -{0.306818f,-0.000839977f,0.100469f},{0.306882f,5.09237e-019f,0.0918925f},{0.306882f,5.09237e-019f,0.100469f}, -{-0.000417625f,-0.306866f,0.100469f},{0.000423769f,-0.306865f,0.100469f},{0.000417625f,-0.306866f,0.0918925f}, -{-0.00124862f,-0.306741f,0.100469f},{-0.000423769f,-0.306865f,0.0918925f},{-0.00125042f,-0.30674f,0.0918925f}, -{-0.00204323f,-0.306495f,0.100469f},{-0.0020445f,-0.306495f,0.0918925f},{-0.00279455f,-0.306134f,0.0918925f}, -{-0.00279128f,-0.306135f,0.100469f},{-0.00348179f,-0.305665f,0.100469f},{-0.00462441f,-0.304435f,0.0918925f}, -{-0.00503944f,-0.303715f,0.100469f},{-0.00462371f,-0.304436f,0.100469f},{-0.00348701f,-0.305661f,0.0918925f}, -{-0.00409988f,-0.305093f,0.100469f},{-0.00410228f,-0.30509f,0.0918925f},{-0.00504068f,-0.303712f,0.0918925f}, -{-0.00534308f,-0.302942f,0.100469f},{-0.0053446f,-0.302938f,0.0918925f},{-0.00552953f,-0.302129f,0.0918925f}, -{-0.00559323f,-0.301289f,0.100469f},{-0.00552953f,-0.302129f,0.100469f},{-0.00559323f,-0.301289f,0.0918925f}, -{0.00124862f,-0.306741f,0.0918925f},{0.00204323f,-0.306495f,0.0918925f},{0.00125042f,-0.30674f,0.100469f}, -{0.0020445f,-0.306495f,0.100469f},{0.00279128f,-0.306135f,0.0918925f},{0.00279455f,-0.306134f,0.100469f}, -{0.00348179f,-0.305665f,0.0918925f},{0.00409988f,-0.305093f,0.0918925f},{0.00348701f,-0.305661f,0.100469f}, -{0.00410228f,-0.30509f,0.100469f},{0.00462371f,-0.304436f,0.0918925f},{0.00462441f,-0.304435f,0.100469f}, -{0.00503944f,-0.303715f,0.0918925f},{0.00534308f,-0.302942f,0.0918925f},{0.00504068f,-0.303712f,0.100469f}, -{0.0053446f,-0.302938f,0.100469f},{0.00552953f,-0.302129f,0.0918925f},{0.00552953f,-0.302129f,0.100469f}, -{0.00559323f,-0.301289f,0.0918925f},{0.00559323f,-0.301289f,0.100469f},{-0.0348217f,0.314624f,0.0918925f}, -{-0.0337164f,0.317214f,0.100469f},{-0.0337175f,0.317211f,0.0918925f},{-0.0324231f,0.319705f,0.0918925f}, -{-0.0324223f,0.319706f,0.100469f},{-0.0309468f,0.32209f,0.100469f},{-0.0309475f,0.322089f,0.0918925f}, -{-0.0292965f,0.324356f,0.100469f},{-0.0292972f,0.324355f,0.0918925f},{-0.0274788f,0.326494f,0.0918925f}, -{-0.0274777f,0.326495f,0.100469f},{-0.0254989f,0.328495f,0.100469f},{-0.0255009f,0.328493f,0.0918925f}, -{-0.0233785f,0.330338f,0.100469f},{-0.0233795f,0.330337f,0.0918925f},{-0.0211301f,0.332012f,0.0918925f}, -{-0.0211293f,0.332013f,0.100469f},{-0.0187614f,0.333513f,0.100469f},{-0.0187622f,0.333513f,0.0918925f}, -{-0.0162847f,0.334833f,0.100469f},{-0.0162855f,0.334832f,0.0918925f},{-0.0137109f,0.335964f,0.0918925f}, -{-0.0137094f,0.335965f,0.100469f},{-0.0110591f,0.336899f,0.100469f},{-0.0110599f,0.336899f,0.0918925f}, -{-0.00835103f,0.33763f,0.100469f},{-0.00835149f,0.337629f,0.0918925f},{-0.00559768f,0.338154f,0.0918925f}, -{-0.00559736f,0.338154f,0.100469f},{-0.00280978f,0.338471f,0.100469f},{-0.00280994f,0.338471f,0.0918925f}, -{-6.08556e-017f,0.338577f,0.100469f},{-6.08556e-017f,0.338577f,0.0918925f},{-0.0348209f,0.314627f,0.100469f}, -{-0.0357267f,0.311966f,0.0918925f},{-0.0357264f,0.311967f,0.100469f},{-0.036428f,0.309251f,0.0918925f}, -{-0.0364278f,0.309253f,0.100469f},{-0.0369231f,0.306493f,0.100469f},{-0.0369234f,0.306492f,0.0918925f}, -{-0.0372102f,0.303699f,0.0918925f},{-0.03721f,0.303701f,0.100469f},{-0.0372859f,0.300887f,0.0918925f}, -{-0.037286f,0.300889f,0.100469f},{-0.0371501f,0.298082f,0.100469f},{-0.0371499f,0.298081f,0.0918925f}, -{-0.0368038f,0.295298f,0.0918925f},{-0.036804f,0.295299f,0.100469f},{-0.0362498f,0.29255f,0.0918925f}, -{-0.03625f,0.292551f,0.100469f},{-0.0354901f,0.289849f,0.100469f},{-0.0354899f,0.289848f,0.0918925f}, -{-0.0345264f,0.287205f,0.0918925f},{-0.034527f,0.287207f,0.100469f},{-0.0333678f,0.284645f,0.0918925f}, -{-0.0333682f,0.284646f,0.100469f},{-0.0320226f,0.282185f,0.100469f},{-0.0320224f,0.282184f,0.0918925f}, -{-0.0304967f,0.279833f,0.0918925f},{-0.0304969f,0.279833f,0.100469f},{-0.0287972f,0.2776f,0.0918925f}, -{-0.0287973f,0.2776f,0.100469f},{-0.0269304f,0.275498f,0.0918925f},{-0.0269304f,0.275498f,0.100469f}, -{-0.314624f,-0.0348217f,0.0918925f},{-0.317214f,-0.0337164f,0.100469f},{-0.317211f,-0.0337175f,0.0918925f}, -{-0.319705f,-0.0324231f,0.0918925f},{-0.319706f,-0.0324223f,0.100469f},{-0.32209f,-0.0309468f,0.100469f}, -{-0.322089f,-0.0309475f,0.0918925f},{-0.324356f,-0.0292965f,0.100469f},{-0.324355f,-0.0292972f,0.0918925f}, -{-0.326494f,-0.0274788f,0.0918925f},{-0.326495f,-0.0274777f,0.100469f},{-0.328495f,-0.0254989f,0.100469f}, -{-0.328493f,-0.0255009f,0.0918925f},{-0.330338f,-0.0233785f,0.100469f},{-0.330337f,-0.0233795f,0.0918925f}, -{-0.332012f,-0.0211301f,0.0918925f},{-0.332013f,-0.0211293f,0.100469f},{-0.333513f,-0.0187614f,0.100469f}, -{-0.333513f,-0.0187622f,0.0918925f},{-0.334833f,-0.0162847f,0.100469f},{-0.334832f,-0.0162855f,0.0918925f}, -{-0.335964f,-0.0137109f,0.0918925f},{-0.335965f,-0.0137094f,0.100469f},{-0.336899f,-0.0110591f,0.100469f}, -{-0.336899f,-0.0110599f,0.0918925f},{-0.33763f,-0.00835103f,0.100469f},{-0.337629f,-0.00835149f,0.0918925f}, -{-0.338154f,-0.00559768f,0.0918925f},{-0.338154f,-0.00559736f,0.100469f},{-0.338471f,-0.00280978f,0.100469f}, -{-0.338471f,-0.00280994f,0.0918925f},{-0.338577f,5.09237e-019f,0.100469f},{-0.338577f,5.09237e-019f,0.0918925f}, -{-0.314627f,-0.0348209f,0.100469f},{-0.311966f,-0.0357267f,0.0918925f},{-0.311967f,-0.0357264f,0.100469f}, -{-0.309251f,-0.036428f,0.0918925f},{-0.309253f,-0.0364278f,0.100469f},{-0.306493f,-0.0369231f,0.100469f}, -{-0.306492f,-0.0369234f,0.0918925f},{-0.303699f,-0.0372102f,0.0918925f},{-0.303701f,-0.03721f,0.100469f}, -{-0.300887f,-0.0372859f,0.0918925f},{-0.300889f,-0.037286f,0.100469f},{-0.298082f,-0.0371501f,0.100469f}, -{-0.298081f,-0.0371499f,0.0918925f},{-0.295298f,-0.0368038f,0.0918925f},{-0.295299f,-0.036804f,0.100469f}, -{-0.29255f,-0.0362498f,0.0918925f},{-0.292551f,-0.03625f,0.100469f},{-0.289849f,-0.0354901f,0.100469f}, -{-0.289848f,-0.0354899f,0.0918925f},{-0.287205f,-0.0345264f,0.0918925f},{-0.287207f,-0.034527f,0.100469f}, -{-0.284645f,-0.0333678f,0.0918925f},{-0.284646f,-0.0333682f,0.100469f},{-0.282185f,-0.0320226f,0.100469f}, -{-0.282184f,-0.0320224f,0.0918925f},{-0.279833f,-0.0304967f,0.0918925f},{-0.279833f,-0.0304969f,0.100469f}, -{-0.2776f,-0.0287972f,0.0918925f},{-0.2776f,-0.0287973f,0.100469f},{-0.275498f,-0.0269304f,0.0918925f}, -{-0.275498f,-0.0269304f,0.100469f},{0.0348217f,-0.314624f,0.0918925f},{0.0337164f,-0.317214f,0.100469f}, -{0.0337175f,-0.317211f,0.0918925f},{0.0324231f,-0.319705f,0.0918925f},{0.0324223f,-0.319706f,0.100469f}, -{0.0309468f,-0.32209f,0.100469f},{0.0309475f,-0.322089f,0.0918925f},{0.0292965f,-0.324356f,0.100469f}, -{0.0292972f,-0.324355f,0.0918925f},{0.0274788f,-0.326494f,0.0918925f},{0.0274777f,-0.326495f,0.100469f}, -{0.0254989f,-0.328495f,0.100469f},{0.0255009f,-0.328493f,0.0918925f},{0.0233785f,-0.330338f,0.100469f}, -{0.0233795f,-0.330337f,0.0918925f},{0.0211301f,-0.332012f,0.0918925f},{0.0211293f,-0.332013f,0.100469f}, -{0.0187614f,-0.333513f,0.100469f},{0.0187622f,-0.333513f,0.0918925f},{0.0162847f,-0.334833f,0.100469f}, -{0.0162855f,-0.334832f,0.0918925f},{0.0137109f,-0.335964f,0.0918925f},{0.0137094f,-0.335965f,0.100469f}, -{0.0110591f,-0.336899f,0.100469f},{0.0110599f,-0.336899f,0.0918925f},{0.00835103f,-0.33763f,0.100469f}, -{0.00835149f,-0.337629f,0.0918925f},{0.00559768f,-0.338154f,0.0918925f},{0.00559736f,-0.338154f,0.100469f}, -{0.00280978f,-0.338471f,0.100469f},{0.00280994f,-0.338471f,0.0918925f},{5.51904e-017f,-0.338577f,0.100469f}, -{5.51904e-017f,-0.338577f,0.0918925f},{0.0348209f,-0.314627f,0.100469f},{0.0357267f,-0.311966f,0.0918925f}, -{0.0357264f,-0.311967f,0.100469f},{0.036428f,-0.309251f,0.0918925f},{0.0364278f,-0.309253f,0.100469f}, -{0.0369231f,-0.306493f,0.100469f},{0.0369234f,-0.306492f,0.0918925f},{0.0372102f,-0.303699f,0.0918925f}, -{0.03721f,-0.303701f,0.100469f},{0.0372859f,-0.300887f,0.0918925f},{0.037286f,-0.300889f,0.100469f}, -{0.0371501f,-0.298082f,0.100469f},{0.0371499f,-0.298081f,0.0918925f},{0.0368038f,-0.295298f,0.0918925f}, -{0.036804f,-0.295299f,0.100469f},{0.0362498f,-0.29255f,0.0918925f},{0.03625f,-0.292551f,0.100469f}, -{0.0354901f,-0.289849f,0.100469f},{0.0354899f,-0.289848f,0.0918925f},{0.0345264f,-0.287205f,0.0918925f}, -{0.034527f,-0.287207f,0.100469f},{0.0333678f,-0.284645f,0.0918925f},{0.0333682f,-0.284646f,0.100469f}, -{0.0320226f,-0.282185f,0.100469f},{0.0320224f,-0.282184f,0.0918925f},{0.0304967f,-0.279833f,0.0918925f}, -{0.0304969f,-0.279833f,0.100469f},{0.0287972f,-0.2776f,0.0918925f},{0.0287973f,-0.2776f,0.100469f}, -{0.0269304f,-0.275498f,0.0918925f},{0.0269304f,-0.275498f,0.100469f},{-0.0768194f,-0.0930843f,0.100469f}, -{-0.079125f,-0.0926561f,0.100469f},{0.0167528f,-0.0298143f,0.100469f},{-0.0167532f,-0.0298151f,0.100469f}, -{-0.0160285f,-0.0314546f,0.100469f},{-0.107313f,-0.0145465f,0.100469f},{-0.107316f,0.0145474f,0.100469f}, -{-0.109619f,-0.0141179f,0.100469f},{-0.0745764f,-0.0932205f,0.100469f},{-0.0932205f,-0.0326272f,0.100469f}, -{-0.0696868f,-0.0383722f,0.100469f},{-0.0694022f,-0.0366018f,0.100469f},{-0.306315f,0.00242058f,0.100469f}, -{-0.313415f,0.00227358f,0.100469f},{-0.306637f,0.00165192f,0.100469f},{-0.27258f,-0.0243605f,0.100469f}, -{-0.29667f,0.00314874f,0.100469f},{-0.296252f,0.00242484f,0.100469f},{0.0145465f,-0.107313f,0.100469f}, -{-0.0145474f,-0.107316f,0.100469f},{-0.0141193f,-0.109622f,0.100469f},{-0.0628562f,-0.0794586f,0.100469f}, -{-0.0932205f,-0.0745764f,0.100469f},{-0.0631487f,-0.0799657f,0.100469f},{-0.2915f,-0.0119424f,0.100469f}, -{-0.304721f,-0.0124916f,0.100469f},{-0.0326272f,-0.0932205f,0.100469f},{-0.0877597f,-0.0877597f,0.100469f}, -{-0.0858213f,-0.089447f,0.100469f},{-0.0633287f,-0.08052f,0.100469f},{-0.0365982f,-0.0799633f,0.100469f}, -{-0.0368906f,-0.0794574f,0.100469f},{-0.0213792f,-0.0969955f,0.100469f},{-0.0194438f,-0.0986812f,0.100469f}, -{-0.0259491f,-0.0190126f,0.100469f},{-0.0274515f,-0.0180347f,0.100469f},{0.0213822f,-0.0969939f,0.100469f}, -{0.0194438f,-0.0986812f,0.100469f},{-0.0177565f,-0.10062f,0.100469f},{0.0177581f,-0.100617f,0.100469f}, -{0.0745764f,-0.0932205f,0.100469f},{-0.0152921f,-0.105002f,0.100469f},{0.0152921f,-0.105002f,0.100469f}, -{0.0163653f,-0.102745f,0.100469f},{-0.0163644f,-0.102748f,0.100469f},{0.0141179f,-0.109619f,0.100469f}, -{-0.00227358f,-0.313415f,0.100469f},{-0.00105623f,-0.313362f,0.100469f},{-0.00343287f,-0.31378f,0.100469f}, -{0.0213591f,-0.29942f,0.100469f},{0.0186351f,-0.295578f,0.100469f},{0.0131454f,-0.305747f,0.100469f}, -{0.0122298f,-0.311032f,0.100469f},{0.014044f,-0.30657f,0.100469f},{-0.0116607f,-0.311153f,0.100469f}, -{-0.0111271f,-0.31139f,0.100469f},{0.00298716f,-0.322407f,0.100469f},{0.00408405f,-0.321856f,0.100469f}, -{-0.0151227f,-0.295446f,0.100469f},{-0.00461423f,-0.29814f,0.100469f},{-0.0131454f,-0.29683f,0.100469f}, -{-0.0324248f,-0.319702f,0.100469f},{-0.0309477f,-0.322089f,0.100469f},{-0.0292931f,-0.324357f,0.100469f}, -{-0.0274755f,-0.326496f,0.100469f},{-0.0121261f,-0.299015f,0.100469f},{-0.00502626f,-0.298868f,0.100469f}, -{-0.0124916f,-0.297856f,0.100469f},{-0.0102622f,-0.312168f,0.100469f},{-0.0211299f,-0.332011f,0.100469f}, -{-0.0187591f,-0.333514f,0.100469f},{-0.295223f,-0.0174585f,0.100469f},{-0.29719f,0.00380369f,0.100469f}, -{-0.301289f,-0.0214407f,0.100469f},{-0.29942f,-0.0213591f,0.100469f},{-0.00584288f,-0.316411f,0.100469f}, -{0.00571052f,-0.319924f,0.100469f},{-0.297802f,0.0043727f,0.100469f},{-0.297856f,0.0124916f,0.100469f}, -{-0.298493f,0.00484368f,0.100469f},{0.0139213f,-0.31139f,0.100469f},{0.0143937f,-0.311733f,0.100469f}, -{-0.302532f,0.00545321f,0.100469f},{-0.301706f,0.00557763f,0.100469f},{-0.312949f,-0.00986419f,0.100469f}, -{-0.312416f,-0.0101017f,0.100469f},{0.0106515f,-0.311736f,0.100469f},{0.0111254f,-0.311391f,0.100469f}, -{-0.30087f,0.00557747f,0.100469f},{-0.301289f,0.0121187f,0.100469f},{-0.31378f,0.00343287f,0.100469f}, -{5.8201e-009f,-0.313407f,0.100469f},{0.0214407f,-0.301289f,0.100469f},{0.0174585f,-0.295223f,0.100469f}, -{0.0197119f,-0.296256f,0.100469f},{0.0121261f,-0.303562f,0.100469f},{0.0147862f,-0.312168f,0.100469f}, -{0.005033f,-0.321f,0.100469f},{0.0147862f,-0.28712f,0.100469f},{0.00409889f,-0.297485f,0.100469f}, -{0.0046188f,-0.29814f,0.100469f},{0.00503626f,-0.298864f,0.100469f},{0.0364172f,-0.08052f,0.100469f}, -{-0.00996978f,-0.312674f,0.100469f},{-0.00445857f,-0.314434f,0.100469f},{-0.00835238f,-0.337628f,0.100469f}, -{-0.0110628f,-0.336897f,0.100469f},{0.00186868f,-0.322648f,0.100469f},{-6.42929e-017f,-0.322729f,0.100469f}, -{-0.00534833f,-0.299637f,0.100469f},{-0.00409933f,-0.297483f,0.100469f},{-0.00348669f,-0.296915f,0.100469f}, -{-0.0255017f,-0.328493f,0.100469f},{-0.0233817f,-0.330334f,0.100469f},{-0.00553085f,-0.300454f,0.100469f}, -{-0.00132352f,-0.218226f,0.100469f},{-0.0139831f,-0.243259f,0.100469f},{-0.00124367f,-0.295835f,0.100469f}, -{-0.00041711f,-0.295711f,0.100469f},{-0.0139831f,-0.111865f,0.100469f},{0.0139831f,-0.111865f,0.100469f}, -{0.0166349f,-0.258757f,0.100469f},{0.0154692f,-0.254935f,0.100469f},{-0.0214407f,-0.301289f,0.100469f}, -{-0.0372872f,-0.300891f,0.100469f},{-0.0371926f,-0.303697f,0.100469f},{-0.00132352f,-0.255514f,0.100469f}, -{-0.00112134f,-0.255125f,0.100469f},{-0.0146388f,-0.25105f,0.100469f},{0.00584288f,-0.286166f,0.100469f}, -{0.0102613f,-0.287121f,0.100469f},{0.0146388f,-0.251049f,0.100469f},{0.0013304f,-0.255513f,0.100469f}, -{0.0139831f,-0.243259f,0.100469f},{0.000433147f,-0.254615f,0.100469f},{0.0141453f,-0.247143f,0.100469f}, -{0.000819963f,-0.254817f,0.100469f},{0.00112493f,-0.255127f,0.100469f},{-0.0154693f,-0.254936f,0.100469f}, -{3.01689e-017f,-0.254546f,0.100469f},{-0.000431051f,-0.254614f,0.100469f},{0.0372799f,-0.0790251f,0.100469f}, -{0.0836959f,-0.0908383f,0.100469f},{0.0814392f,-0.0919114f,0.100469f},{0.0768218f,-0.0930856f,0.100469f}, -{0.0937839f,-0.0280757f,0.100469f},{0.0663164f,-0.0282257f,0.100469f},{0.0671452f,-0.0298151f,0.100469f}, -{0.089447f,-0.0858213f,0.100469f},{0.0908391f,-0.0836927f,0.100469f},{0.0919114f,-0.0814392f,0.100469f}, -{0.0926561f,-0.079125f,0.100469f},{0.0836562f,-0.0799633f,0.100469f},{0.0838367f,-0.0805185f,0.100469f}, -{0.0932205f,-0.0745764f,0.100469f},{0.0829714f,-0.0790223f,0.100469f},{0.0833638f,-0.0794574f,0.100469f}, -{0.0877597f,-0.0877597f,0.100469f},{0.107313f,0.0145465f,0.100469f},{0.105002f,-0.0152921f,0.100469f}, -{0.107316f,-0.0145474f,0.100469f},{0.0819653f,-0.0784418f,0.100469f},{0.0813929f,-0.0783204f,0.100469f}, -{0.0858243f,-0.0894455f,0.100469f},{0.0932205f,-0.0326272f,0.100469f},{-0.0142141f,-0.0383731f,0.100469f}, -{0.0144962f,-0.0366018f,0.100469f},{-0.0145004f,-0.0366037f,0.100469f},{0.0932205f,0.0326272f,0.100469f}, -{0.102748f,-0.0163644f,0.100469f},{0.105002f,0.0152921f,0.100469f},{0.102745f,0.0163653f,0.100469f}, -{0.0986812f,-0.0194438f,0.100469f},{0.100617f,0.0177581f,0.100469f},{0.0986812f,0.0194438f,0.100469f}, -{0.109619f,0.0141179f,0.100469f},{0.109622f,-0.0141193f,0.100469f},{0.290634f,0.0146037f,0.100469f}, -{0.291026f,0.0141686f,0.100469f},{0.111865f,0.0139831f,0.100469f},{0.311372f,-0.035899f,0.100469f}, -{0.314002f,-0.0350539f,0.100469f},{0.305373f,-0.0205678f,0.100469f},{0.305907f,0.00314874f,0.100469f}, -{0.306325f,0.00242484f,0.100469f},{0.319924f,0.00571052f,0.100469f},{0.313415f,-0.00227358f,0.100469f}, -{0.315682f,-0.0104447f,0.100469f},{0.316075f,-0.0108798f,0.100469f},{0.299015f,-0.0121261f,0.100469f}, -{0.300232f,-0.012073f,0.100469f},{0.335522f,0.0147828f,0.100469f},{0.334333f,0.0172772f,0.100469f}, -{0.321f,0.005033f,0.100469f},{0.31194f,-0.0104475f,0.100469f},{0.331418f,-0.0219665f,0.100469f}, -{0.337328f,-0.00956357f,0.100469f},{0.335521f,-0.0147817f,0.100469f},{0.334333f,-0.0172761f,0.100469f}, -{0.322729f,-7.81484e-018f,0.100469f},{0.338551f,-0.00138096f,0.100469f},{0.338551f,0.00138181f,0.100469f}, -{0.332963f,-0.0196753f,0.100469f},{0.33733f,0.00956509f,0.100469f},{0.321856f,0.00408405f,0.100469f}, -{0.322407f,0.00298716f,0.100469f},{0.337939f,0.00686983f,0.100469f},{0.322648f,0.00186868f,0.100469f}, -{0.338347f,0.00413689f,0.100469f},{0.312414f,-0.0101024f,0.100469f},{0.329709f,-0.024138f,0.100469f}, -{0.314434f,-0.00445857f,0.100469f},{0.313518f,-0.0097434f,0.100469f},{0.315333f,-0.00528144f,0.100469f}, -{0.327844f,-0.0261764f,0.100469f},{0.325832f,-0.0280694f,0.100469f},{0.297856f,-0.0124916f,0.100469f}, -{0.31521f,-0.0101017f,0.100469f},{0.323687f,-0.0298108f,0.100469f},{0.295446f,-0.0151227f,0.100469f}, -{0.319039f,-0.032792f,0.100469f},{0.321418f,-0.0313879f,0.100469f},{0.307354f,-0.0174585f,0.100469f}, -{0.306322f,-0.0197119f,0.100469f},{0.321418f,0.0313882f,0.100469f},{0.314676f,0.0151842f,0.100469f}, -{0.323687f,0.0298117f,0.100469f},{0.325828f,0.0280668f,0.100469f},{0.31521f,0.0149467f,0.100469f}, -{0.315682f,0.0146037f,0.100469f},{0.305959f,0.0369915f,0.100469f},{0.303208f,0.0372381f,0.100469f}, -{0.294948f,0.0367442f,0.100469f},{0.29942f,0.0213591f,0.100469f},{0.297686f,0.037113f,0.100469f}, -{0.312414f,0.014946f,0.100469f},{0.31194f,0.0146009f,0.100469f},{0.296256f,0.0197119f,0.100469f}, -{0.28847f,0.015305f,0.100469f},{0.289055f,0.0153056f,0.100469f},{0.30657f,0.014044f,0.100469f}, -{0.305747f,0.0131454f,0.100469f},{0.303562f,0.0121261f,0.100469f},{0.302345f,0.012073f,0.100469f}, -{0.302534f,0.00545274f,0.100469f},{0.290161f,0.0149467f,0.100469f},{0.295223f,0.0174585f,0.100469f}, -{0.289628f,0.0151842f,0.100469f},{0.286209f,0.0136603f,0.100469f},{0.27258f,0.0243605f,0.100469f}, -{0.286029f,0.013106f,0.100469f},{0.288143f,0.00445857f,0.100469f},{0.269417f,0.0220151f,0.100469f}, -{0.287245f,0.00528144f,0.100469f},{0.297802f,0.00437403f,0.100469f},{0.255403f,0.00112774f,0.100469f}, -{0.254935f,0.0154692f,0.100469f},{0.255016f,0.00132937f,0.100469f},{0.297189f,0.00380587f,0.100469f}, -{0.289162f,0.00227358f,0.100469f},{0.296262f,0.00242058f,0.100469f},{0.288797f,0.00343287f,0.100469f}, -{0.300045f,0.00545321f,0.100469f},{0.282071f,-0.0319552f,0.100469f},{0.28449f,-0.0332908f,0.100469f}, -{0.289216f,0.00105623f,0.100469f},{0.28917f,-5.8201e-009f,0.100469f},{0.28383f,-0.00606509f,0.100469f}, -{0.286209f,-0.0113881f,0.100469f},{0.286501f,-0.010881f,0.100469f},{0.111865f,-0.0139831f,0.100469f}, -{0.291026f,-0.0108798f,0.100469f},{0.269418f,-0.0220158f,0.100469f},{0.281577f,-0.005033f,0.100469f}, -{0.275498f,-0.0269304f,0.100469f},{0.243259f,0.0139831f,0.100469f},{0.243259f,-0.0139831f,0.100469f}, -{0.279848f,1.74344e-017f,0.100469f},{0.295758f,0.000834183f,0.100469f},{0.29594f,0.00165192f,0.100469f}, -{0.27258f,-0.024361f,0.100469f},{0.258757f,-0.016635f,0.100469f},{0.254936f,-0.0154693f,0.100469f}, -{0.279929f,-0.00186868f,0.100469f},{0.28017f,-0.00298716f,0.100469f},{0.253259f,0.000430548f,0.100469f}, -{0.253462f,0.000819718f,0.100469f},{0.247143f,0.0141453f,0.100469f},{0.25105f,-0.0146388f,0.100469f}, -{0.247144f,-0.0141452f,0.100469f},{0.218391f,0.000431293f,0.100469f},{0.218186f,0.000817561f,0.100469f}, -{0.10062f,-0.0177565f,0.100469f},{0.0933567f,0.0303842f,0.100469f},{0.0418875f,0.0816851f,0.100469f}, -{0.0516079f,0.0681943f,0.100469f},{0.0709097f,0.0709097f,0.100469f},{0.0548849f,0.0667435f,0.100469f}, -{0.0564469f,0.0658638f,0.100469f},{-0.0245125f,0.0638136f,0.100469f},{-0.0235109f,0.0956018f,0.100469f}, -{-0.0259491f,0.0648858f,0.100469f},{-0.0185115f,-0.0266927f,0.100469f},{0.0195369f,-0.0252221f,0.100469f}, -{-0.019537f,-0.0252222f,0.100469f},{0.0185112f,-0.0266922f,0.100469f},{0.0548849f,-0.0171549f,0.100469f}, -{0.0175819f,-0.028225f,0.100469f},{-0.0175821f,-0.0282257f,0.100469f},{0.0838367f,0.0816851f,0.100469f}, -{0.0894455f,0.0858243f,0.100469f},{0.0836562f,0.0822403f,0.100469f},{0.092657f,0.0791278f,0.100469f}, -{0.0919114f,0.0814392f,0.100469f},{0.0908383f,0.0836959f,0.100469f},{0.0792292f,0.0831785f,0.100469f}, -{0.079703f,0.0835236f,0.100469f},{0.0768194f,0.0930843f,0.100469f},{0.0829714f,0.0831813f,0.100469f}, -{0.0877597f,0.0877597f,0.100469f},{0.0824989f,0.0835243f,0.100469f},{0.0326272f,0.0932205f,0.100469f}, -{0.0388582f,0.0838826f,0.100469f},{0.0394436f,0.0838832f,0.100469f},{0.0745764f,0.0932205f,0.100469f}, -{0.0783664f,0.0816836f,0.100469f},{0.079125f,0.0926561f,0.100469f},{0.0802367f,0.0837612f,0.100469f}, -{0.0785464f,0.0822379f,0.100469f},{0.0788389f,0.082745f,0.100469f},{0.0808074f,0.0838826f,0.100469f}, -{0.0813929f,0.0838832f,0.100469f},{0.0836927f,0.0908391f,0.100469f},{0.0930856f,0.0768218f,0.100469f}, -{0.0481725f,-0.0146844f,0.100469f},{0.0499065f,-0.0151392f,0.100469f},{-0.0339919f,0.0687593f,0.100469f}, -{-0.0306287f,0.0675214f,0.100469f},{-0.0290135f,0.0667435f,0.100469f},{-0.0969939f,-0.0213822f,0.100469f}, -{-0.0632437f,-0.0238204f,0.100469f},{-0.0620385f,-0.0224931f,0.100469f},{0.0163644f,0.102748f,0.100469f}, -{-0.0163653f,0.102745f,0.100469f},{-0.0177581f,0.100617f,0.100469f},{-0.0218598f,0.0614045f,0.100469f}, -{-0.0213822f,0.0969939f,0.100469f},{-0.0231475f,0.0626516f,0.100469f},{0.0152921f,0.105002f,0.100469f}, -{0.0145474f,0.107316f,0.100469f},{-0.0152921f,0.105002f,0.100469f},{-0.0145465f,0.107313f,0.100469f}, -{0.0141193f,0.109622f,0.100469f},{0.0139831f,0.111865f,0.100469f},{-0.0141179f,0.109619f,0.100469f}, -{-0.0139831f,0.111865f,0.100469f},{-0.00584288f,0.286166f,0.100469f},{-0.0131454f,0.305747f,0.100469f}, -{-0.0147871f,0.290408f,0.100469f},{-0.0143968f,0.290841f,0.100469f},{-0.00348669f,0.305663f,0.100469f}, -{-0.00279621f,0.306133f,0.100469f},{-0.0220151f,0.269417f,0.100469f},{-0.00124367f,0.306742f,0.100469f}, -{7.81291e-017f,0.322729f,0.100469f},{-0.00186868f,0.322648f,0.100469f},{0.0121261f,0.299015f,0.100469f}, -{0.0143937f,0.290844f,0.100469f},{0.0147862f,0.290409f,0.100469f},{0.0106515f,0.290841f,0.100469f}, -{0.0372872f,0.300891f,0.100469f},{0.0371926f,0.303697f,0.100469f},{0.0214407f,0.301289f,0.100469f}, -{0.0111254f,0.291186f,0.100469f},{0.0152591f,0.289348f,0.100469f},{0.0122298f,0.291545f,0.100469f}, -{0.014044f,0.296007f,0.100469f},{0.0131454f,0.29683f,0.100469f},{0.0197119f,0.306322f,0.100469f}, -{0.0324248f,0.319702f,0.100469f},{0.0174585f,0.307354f,0.100469f},{0.0186351f,0.306999f,0.100469f}, -{0.033718f,0.31721f,0.100469f},{0.0116591f,0.316472f,0.100469f},{0.0122298f,0.316594f,0.100469f}, -{0.0150786f,0.314951f,0.100469f},{0.0292931f,0.324357f,0.100469f},{0.0147862f,0.315457f,0.100469f}, -{-0.005033f,0.321f,0.100469f},{0.0269304f,0.275498f,0.100469f},{-0.0147871f,0.315456f,0.100469f}, -{-0.0122331f,0.316594f,0.100469f},{-0.00571052f,0.319924f,0.100469f},{-0.014044f,0.30657f,0.100469f}, -{-0.0213591f,0.29942f,0.100469f},{-0.0214407f,0.301289f,0.100469f},{-0.00409933f,0.305094f,0.100469f}, -{-0.0150796f,0.2899f,0.100469f},{-0.0186351f,0.295578f,0.100469f},{-0.0152596f,0.289346f,0.100469f}, -{-0.00204265f,0.306496f,0.100469f},{-0.0152596f,0.314395f,0.100469f},{-0.0243605f,0.27258f,0.100469f}, -{-5.8201e-009f,0.313407f,0.100469f},{-0.00041711f,0.306866f,0.100469f},{0.000418664f,0.306866f,0.100469f}, -{-0.0111271f,0.291187f,0.100469f},{-0.0116607f,0.291424f,0.100469f},{-0.0121261f,0.303562f,0.100469f}, -{-0.00534833f,0.30294f,0.100469f},{-0.00502626f,0.303709f,0.100469f},{-0.0128186f,0.316594f,0.100469f}, -{-0.0133893f,0.316472f,0.100469f},{0.00528144f,0.315333f,0.100469f},{0.0097888f,0.314395f,0.100469f}, -{-0.00445857f,0.288143f,0.100469f},{-0.00343287f,0.288797f,0.100469f},{-0.00996978f,0.289903f,0.100469f}, -{0.000819963f,0.257072f,0.100469f},{0.0181266f,0.262471f,0.100469f},{0.00298716f,0.28017f,0.100469f}, -{-0.00082033f,0.257077f,0.100469f},{-0.0181265f,0.262471f,0.100469f},{-0.0166349f,0.258757f,0.100469f}, -{-0.00978928f,0.314396f,0.100469f},{-0.305903f,0.00314864f,0.100469f},{0.00559444f,0.338154f,0.100469f}, -{0.00280508f,0.338471f,0.100469f},{0.0046188f,0.304437f,0.100469f},{0.00503626f,0.303713f,0.100469f}, -{0.00553077f,0.302122f,0.100469f},{0.0139213f,0.291187f,0.100469f},{0.0097888f,0.289346f,0.100469f}, -{0.0354896f,0.289845f,0.100469f},{0.0345284f,0.287208f,0.100469f},{0.0154693f,0.254936f,0.100469f}, -{0.0146388f,0.25105f,0.100469f},{0.0320239f,0.282186f,0.100469f},{0.0333708f,0.284649f,0.100469f}, -{-0.0548845f,-0.0171541f,0.100469f},{0.0304957f,0.279831f,0.100469f},{0.0013304f,0.256376f,0.100469f}, -{-0.00132352f,0.256375f,0.100469f},{-0.00112134f,0.256764f,0.100469f},{-0.0154692f,0.254935f,0.100469f}, -{-0.0141453f,0.247143f,0.100469f},{0.0139831f,0.243259f,0.100469f},{0.016635f,0.258757f,0.100469f}, -{0.0141452f,0.247144f,0.100469f},{0.00112493f,0.256762f,0.100469f},{-0.0139831f,0.243259f,0.100469f}, -{-0.00082033f,0.219789f,0.100469f},{-0.000431051f,0.219987f,0.100469f},{0.0177565f,0.10062f,0.100469f}, -{-0.0194438f,0.0986812f,0.100469f},{0.0194438f,0.0986812f,0.100469f},{-0.0357259f,0.069214f,0.100469f}, -{-0.0322905f,0.0681943f,0.100469f},{-0.0306287f,-0.016377f,0.100469f},{-0.0322905f,-0.0157041f,0.100469f}, -{-0.0339919f,-0.0151392f,0.100469f},{-0.0671457f,-0.0298143f,0.100469f},{-0.0663166f,-0.028225f,0.100469f}, -{-0.0937848f,-0.0280785f,0.100469f},{-0.0532694f,-0.0163764f,0.100469f},{-0.0516077f,-0.0157037f,0.100469f}, -{-0.0877597f,0.0877597f,0.100469f},{-0.0829744f,0.0831785f,0.100469f},{-0.0825006f,0.0835236f,0.100469f}, -{-0.0919114f,0.0814392f,0.100469f},{-0.0926561f,0.079125f,0.100469f},{-0.0930843f,0.0768194f,0.100469f}, -{-0.0932205f,0.0745764f,0.100469f},{-0.0908391f,0.0836927f,0.100469f},{-0.0838372f,0.0816836f,0.100469f}, -{-0.089447f,0.0858213f,0.100469f},{-0.0836572f,0.0822379f,0.100469f},{-0.0819669f,0.0837612f,0.100469f}, -{-0.0836959f,0.0908383f,0.100469f},{-0.0858243f,0.0894455f,0.100469f},{-0.0932205f,0.0326272f,0.100469f}, -{-0.0933553f,0.0303817f,0.100469f},{-0.0814392f,0.0919114f,0.100469f},{-0.0813962f,0.0838826f,0.100469f}, -{-0.0808108f,0.0838832f,0.100469f},{-0.0696868f,0.0455262f,0.100469f},{-0.0694022f,0.0472966f,0.100469f}, -{-0.0797047f,0.0835243f,0.100469f},{-0.0791278f,0.092657f,0.100469f},{-0.0802383f,0.0837618f,0.100469f}, -{-0.0579489f,-0.0190117f,0.100469f},{-0.0593856f,-0.0200839f,0.100469f},{-0.0956018f,-0.0235109f,0.100469f}, -{-0.0643615f,-0.0252221f,0.100469f},{-0.0933567f,-0.0303842f,0.100469f},{-0.0678671f,-0.0314549f,0.100469f}, -{-0.105002f,-0.0152921f,0.100469f},{-0.102745f,-0.0163653f,0.100469f},{-0.102748f,0.0163644f,0.100469f}, -{-0.100617f,-0.0177581f,0.100469f},{-0.10062f,0.0177565f,0.100469f},{-0.109622f,0.0141193f,0.100469f}, -{-0.105002f,0.0152921f,0.100469f},{-0.111865f,0.0139831f,0.100469f},{-0.111865f,-0.0139831f,0.100469f}, -{-0.254936f,0.0154693f,0.100469f},{-0.258757f,0.016635f,0.100469f},{-0.255403f,0.00113282f,0.100469f}, -{-0.247143f,-0.0141453f,0.100469f},{-0.316411f,0.00584288f,0.100469f},{-0.322648f,-0.00186868f,0.100469f}, -{-0.322407f,-0.00298716f,0.100469f},{-0.321f,-0.005033f,0.100469f},{-0.304775f,0.00437403f,0.100469f}, -{-0.305388f,0.00380587f,0.100469f},{-0.304085f,0.00484444f,0.100469f},{-0.336897f,0.0110628f,0.100469f}, -{-0.335964f,0.0137103f,0.100469f},{-0.303331f,0.00520701f,0.100469f},{-0.315212f,0.014946f,0.100469f}, -{-0.326496f,0.0274755f,0.100469f},{-0.315685f,0.0146009f,0.100469f},{-0.314107f,0.015305f,0.100469f}, -{-0.319702f,0.0324248f,0.100469f},{-0.314678f,0.0151836f,0.100469f},{-0.313522f,0.0153056f,0.100469f}, -{-0.306999f,0.0186351f,0.100469f},{-0.306322f,0.0197119f,0.100469f},{-0.311551f,-0.0108798f,0.100469f}, -{-0.311943f,-0.0104447f,0.100469f},{-0.311258f,-0.0113857f,0.100469f},{-0.305747f,-0.0131454f,0.100469f}, -{-0.311943f,0.0146037f,0.100469f},{-0.307354f,0.0174585f,0.100469f},{-0.312416f,0.0149467f,0.100469f}, -{-0.289059f,0.015305f,0.100469f},{-0.289629f,0.0151836f,0.100469f},{-0.307131f,-0.0151227f,0.100469f}, -{-0.269417f,-0.0220151f,0.100469f},{-0.290637f,-0.0104475f,0.100469f},{-0.262471f,-0.0181265f,0.100469f}, -{-0.266037f,-0.0199275f,0.100469f},{-0.302345f,-0.012073f,0.100469f},{-0.303562f,-0.0121261f,0.100469f}, -{-0.295758f,0.000833312f,0.100469f},{-0.290163f,-0.0101024f,0.100469f},{-0.295946f,0.00164777f,0.100469f}, -{-0.262471f,0.0181266f,0.100469f},{-0.266037f,0.019928f,0.100469f},{-0.28017f,0.00298716f,0.100469f}, -{-0.28383f,0.00606509f,0.100469f},{-0.282653f,0.00571052f,0.100469f},{-0.287367f,-0.0101017f,0.100469f}, -{-0.286895f,-0.0104447f,0.100469f},{-0.287245f,-0.00528144f,0.100469f},{-0.288143f,-0.00445857f,0.100469f}, -{-0.289059f,-0.0097434f,0.100469f},{-0.269418f,0.0220158f,0.100469f},{-0.281577f,0.005033f,0.100469f}, -{-0.258757f,-0.0166349f,0.100469f},{-0.255704f,0.000819718f,0.100469f},{-0.255906f,0.000430548f,0.100469f}, -{-0.25105f,0.0146388f,0.100469f},{-0.254583f,0.00139831f,0.100469f},{-0.255014f,0.00133028f,0.100469f}, -{-0.243259f,0.0139831f,0.100469f},{-0.253253f,0.000431293f,0.100469f},{-0.216628f,0.00132937f,0.100469f}, -{-0.216241f,0.00112774f,0.100469f},{-0.0986812f,0.0194438f,0.100469f},{-0.0945295f,-0.0257644f,0.100469f}, -{-0.0653872f,-0.0266922f,0.100469f},{-0.0986812f,-0.0194438f,0.100469f},{-0.0684765f,-0.0331407f,0.100469f}, -{-0.0464123f,-0.0143415f,0.100469f},{-0.048172f,-0.0146841f,0.100469f},{-0.0698583f,-0.040157f,0.100469f}, -{0.0235109f,-0.0956018f,0.100469f},{-0.0908383f,-0.0836959f,0.100469f},{-0.0894455f,-0.0858243f,0.100469f}, -{0.0257644f,-0.0945295f,0.100469f},{0.0388582f,-0.078321f,0.100469f},{0.0410221f,-0.0790223f,0.100469f}, -{0.0303842f,-0.0933567f,0.100469f},{-0.0235077f,-0.0956027f,0.100469f},{-0.0257644f,-0.0945295f,0.100469f}, -{-0.0280757f,-0.0937839f,0.100469f},{-0.0364177f,-0.0805185f,0.100469f},{-0.037283f,-0.0790223f,0.100469f}, -{-0.0388615f,-0.0783204f,0.100469f},{-0.039447f,-0.078321f,0.100469f},{-0.0382891f,-0.0784418f,0.100469f}, -{-0.0377555f,-0.0786793f,0.100469f},{-0.0414155f,-0.0794586f,0.100469f},{-0.0405514f,-0.07868f,0.100469f}, -{-0.0400177f,-0.0784424f,0.100469f},{-0.041708f,-0.0799657f,0.100469f},{-0.0578584f,-0.0805185f,0.100469f}, -{-0.0580389f,-0.0799633f,0.100469f},{-0.0587238f,-0.0790223f,0.100469f},{-0.0591962f,-0.0786793f,0.100469f}, -{-0.0583313f,-0.0794574f,0.100469f},{-0.0614584f,-0.0784424f,0.100469f},{-0.0608877f,-0.078321f,0.100469f}, -{-0.0603023f,-0.0783204f,0.100469f},{-0.0597298f,-0.0784418f,0.100469f},{-0.0624659f,-0.0790251f,0.100469f}, -{-0.0619921f,-0.07868f,0.100469f},{-0.0814392f,-0.0919114f,0.100469f},{-0.0836927f,-0.0908391f,0.100469f}, -{-0.0689986f,-0.0348554f,0.100469f},{-0.0607507f,-0.021246f,0.100469f},{-0.0564465f,-0.0180338f,0.100469f}, -{-0.0499063f,-0.0151388f,0.100469f},{-0.0428452f,-0.0139974f,0.100469f},{-0.0357259f,-0.0146844f,0.100469f}, -{-0.0392635f,-0.0141124f,0.100469f},{0.0306291f,-0.0163764f,0.100469f},{-0.0653872f,0.0572063f,0.100469f}, -{-0.0326272f,0.0932205f,0.100469f},{-0.0377555f,0.0835243f,0.100469f},{-0.037283f,0.0831813f,0.100469f}, -{0.0290139f,-0.0171541f,0.100469f},{0.0306291f,0.0675221f,0.100469f},{0.0290139f,0.0667443f,0.100469f}, -{-0.0365982f,0.0822403f,0.100469f},{-0.0364177f,0.0816851f,0.100469f},{-0.0303842f,0.0933567f,0.100469f}, -{0.0374861f,-0.0143415f,0.100469f},{-0.0257644f,0.0945295f,0.100469f},{-0.0280785f,0.0937848f,0.100469f}, -{0.0322907f,-0.0157037f,0.100469f},{0.0245128f,-0.0200839f,0.100469f},{0.0206547f,-0.0238204f,0.100469f}, -{-0.0154086f,-0.033137f,0.100469f},{0.0160313f,-0.0314549f,0.100469f},{-0.0148988f,-0.034856f,0.100469f}, -{0.0154219f,-0.0331407f,0.100469f},{0.0148999f,-0.0348554f,0.100469f},{0.0140401f,-0.040157f,0.100469f}, -{0.0142116f,-0.0383722f,0.100469f},{-0.0140402f,-0.0401574f,0.100469f},{0.0937848f,0.0280785f,0.100469f}, -{0.0956018f,0.0235109f,0.100469f},{0.0632438f,-0.0238208f,0.100469f},{0.0643614f,-0.0252222f,0.100469f}, -{0.0956027f,-0.0235077f,0.100469f},{0.0802367f,-0.0784424f,0.100469f},{0.0788389f,-0.0794586f,0.100469f}, -{0.0785464f,-0.0799657f,0.100469f},{0.0792292f,-0.0790251f,0.100469f},{0.0783664f,-0.08052f,0.100469f}, -{0.0791278f,-0.092657f,0.100469f},{0.0418875f,-0.0805185f,0.100469f},{0.0414146f,-0.0794574f,0.100469f}, -{0.041707f,-0.0799633f,0.100469f},{0.0394436f,-0.0783204f,0.100469f},{0.0400161f,-0.0784418f,0.100469f}, -{0.0365972f,-0.0799657f,0.100469f},{0.0368897f,-0.0794586f,0.100469f},{0.0326272f,-0.0932205f,0.100469f}, -{0.0280785f,-0.0937848f,0.100469f},{0.0945295f,0.0257644f,0.100469f},{0.0322907f,0.0681947f,0.100469f}, -{-0.0245125f,-0.0200848f,0.100469f},{-0.0206546f,-0.0238208f,0.100469f},{0.0218599f,-0.0224931f,0.100469f}, -{0.0231477f,-0.021246f,0.100469f},{-0.0218598f,-0.0224939f,0.100469f},{0.0274519f,-0.0180338f,0.100469f}, -{0.0357264f,-0.0146841f,0.100469f},{0.0392642f,-0.0141123f,0.100469f},{0.0410532f,-0.0139974f,0.100469f}, -{-0.0446342f,0.0697861f,0.100469f},{0.0428459f,-0.0139975f,0.100469f},{0.0678699f,0.0524438f,0.100469f}, -{0.0932205f,0.0745764f,0.100469f},{0.0374861f,0.069557f,0.100469f},{0.0357264f,0.0692143f,0.100469f}, -{0.0428459f,0.069901f,0.100469f},{0.0446349f,0.0697861f,0.100469f},{0.0392642f,0.0697861f,0.100469f}, -{0.0579493f,-0.0190126f,0.100469f},{0.0410532f,0.069901f,0.100469f},{0.0593859f,-0.0200848f,0.100469f}, -{0.0607509f,-0.0212468f,0.100469f},{0.0969939f,0.0213822f,0.100469f},{0.0620386f,-0.0224939f,0.100469f}, -{0.0969955f,-0.0213792f,0.100469f},{0.0653869f,-0.0266927f,0.100469f},{0.0945295f,-0.0257644f,0.100469f}, -{0.0678699f,-0.0314546f,0.100469f},{0.0933553f,-0.0303817f,0.100469f},{0.0684898f,-0.033137f,0.100469f}, -{0.0689996f,-0.034856f,0.100469f},{0.0696843f,-0.0383731f,0.100469f},{0.069398f,-0.0366037f,0.100469f}, -{0.0698582f,-0.0401574f,0.100469f},{0.0097888f,-0.313231f,0.100469f},{-3.0178e-017f,-0.279848f,0.100469f}, -{-0.0213591f,-0.303157f,0.100469f},{-0.0369236f,-0.30649f,0.100469f},{-0.0211188f,-0.304276f,0.100469f}, -{0.00606509f,-0.318747f,0.100469f},{-0.0106546f,-0.311733f,0.100469f},{-0.0162807f,-0.334834f,0.100469f}, -{-0.0205678f,-0.305373f,0.100469f},{-0.0357252f,-0.311971f,0.100469f},{-0.0348202f,-0.314629f,0.100469f}, -{-0.014044f,-0.296007f,0.100469f},{0.00227358f,-0.289162f,0.100469f},{0.00105623f,-0.289216f,0.100469f}, -{0.00124497f,-0.295836f,0.100469f},{-0.00279621f,-0.296444f,0.100469f},{-0.0362494f,-0.292548f,0.100469f}, -{-0.0368049f,-0.295301f,0.100469f},{-0.00204265f,-0.296082f,0.100469f},{-0.0345284f,-0.287208f,0.100469f}, -{-0.0354896f,-0.289845f,0.100469f},{0.000418664f,-0.295711f,0.100469f},{-5.8201e-009f,-0.28917f,0.100469f}, -{-0.0150796f,-0.287628f,0.100469f},{-0.0287947f,-0.277597f,0.100469f},{-0.0304957f,-0.279831f,0.100469f}, -{0.00348695f,-0.296916f,0.100469f},{0.00343287f,-0.288797f,0.100469f},{0.002796f,-0.296445f,0.100469f}, -{0.0181265f,-0.262471f,0.100469f},{-0.0143968f,-0.286688f,0.100469f},{-0.013923f,-0.286343f,0.100469f}, -{-0.024361f,-0.27258f,0.100469f},{-0.00298716f,-0.28017f,0.100469f},{-0.0181266f,-0.262471f,0.100469f}, -{0.00553077f,-0.300455f,0.100469f},{0.0143937f,-0.286685f,0.100469f},{0.0243605f,-0.27258f,0.100469f}, -{0.0150786f,-0.287626f,0.100469f},{0.0152591f,-0.288181f,0.100469f},{0.0124916f,-0.304721f,0.100469f}, -{0.306819f,0.000833312f,0.100469f},{0.295578f,0.0186351f,0.100469f},{0.306999f,-0.0186351f,0.100469f}, -{0.291319f,-0.0113857f,0.100469f},{0.29683f,-0.0131454f,0.100469f},{0.297687f,-0.0371146f,0.100469f}, -{0.294949f,-0.0367459f,0.100469f},{0.287899f,-0.00986481f,0.100469f},{0.287366f,-0.0101024f,0.100469f}, -{0.289628f,-0.00986419f,0.100469f},{0.290161f,-0.0101017f,0.100469f},{0.289591f,-0.0354067f,0.100469f}, -{0.292245f,-0.036175f,0.100469f},{0.287001f,-0.0344436f,0.100469f},{0.258757f,0.0166349f,0.100469f}, -{0.255708f,0.000817561f,0.100469f},{0.262471f,0.0181265f,0.100469f},{0.254152f,0.00133028f,0.100469f}, -{0.251049f,0.0146388f,0.100469f},{0.253763f,0.00113282f,0.100469f},{0.266037f,0.0199275f,0.100469f}, -{0.286166f,0.00584288f,0.100469f},{0.287899f,0.0151836f,0.100469f},{0.282071f,0.0319538f,0.100469f}, -{0.279758f,0.0304433f,0.100469f},{0.311077f,0.013106f,0.100469f},{0.28449f,0.0332889f,0.100469f}, -{0.287001f,0.0344412f,0.100469f},{0.304776f,0.0043727f,0.100469f},{0.304721f,0.0124916f,0.100469f}, -{0.304085f,0.00484368f,0.100469f},{0.297204f,0.0205678f,0.100469f},{0.298301f,0.0211188f,0.100469f}, -{0.292244f,0.0361745f,0.100469f},{0.312948f,0.0151836f,0.100469f},{0.313518f,0.015305f,0.100469f}, -{0.300444f,0.0372784f,0.100469f},{0.314002f,0.035054f,0.100469f},{0.311371f,0.0358991f,0.100469f}, -{0.319038f,0.0327925f,0.100469f},{0.316562f,0.0340166f,0.100469f},{0.306631f,0.00164777f,0.100469f}, -{0.316367f,0.0136627f,0.100469f},{0.316548f,0.0131075f,0.100469f},{0.331419f,0.0219685f,0.100469f}, -{0.332963f,0.0196768f,0.100469f},{0.31378f,-0.00343287f,0.100469f},{0.318747f,0.00606509f,0.100469f}, -{0.00606509f,0.28383f,0.100469f},{0.0139213f,0.316235f,0.100469f},{0.0233817f,0.330334f,0.100469f}, -{0.0133877f,0.316473f,0.100469f},{0.00124497f,0.306741f,0.100469f},{0.00227358f,0.313415f,0.100469f}, -{0.00105623f,0.313362f,0.100469f},{-0.00105623f,0.289216f,0.100469f},{-0.00227358f,0.289162f,0.100469f}, -{0.0287947f,0.277597f,0.100469f},{-0.0106546f,0.290844f,0.100469f},{-0.0197119f,0.296256f,0.100469f}, -{-0.0211188f,0.298301f,0.100469f},{-0.0143968f,0.315889f,0.100469f},{-0.013923f,0.316235f,0.100469f}, -{-0.00606509f,0.318747f,0.100469f},{-0.0116607f,0.316473f,0.100469f},{-0.0111271f,0.316235f,0.100469f}, -{0.00445857f,0.314434f,0.100469f},{-0.0106546f,0.315892f,0.100469f},{-0.0102622f,0.315457f,0.100469f}, -{0.00343287f,0.31378f,0.100469f},{-0.00408405f,0.321856f,0.100469f},{-0.00298716f,0.322407f,0.100469f}, -{0.0110628f,0.336897f,0.100469f},{0.00835238f,0.337628f,0.100469f},{0.0187591f,0.333514f,0.100469f}, -{0.0128153f,0.316594f,0.100469f},{0.0309477f,0.322089f,0.100469f},{0.0152591f,0.314396f,0.100469f}, -{0.0124916f,0.297856f,0.100469f},{0.0205678f,0.305373f,0.100469f},{0.0357252f,0.311971f,0.100469f}, -{0.0348202f,0.314629f,0.100469f},{-0.296256f,-0.0197119f,0.100469f},{-0.300232f,0.012073f,0.100469f}, -{-0.300044f,0.00545274f,0.100469f},{-0.299015f,0.0121261f,0.100469f},{-0.295578f,-0.0186351f,0.100469f}, -{-0.298301f,-0.0211188f,0.100469f},{-0.297204f,-0.0205678f,0.100469f},{-0.316076f,-0.010881f,0.100469f}, -{-0.315685f,-0.0104475f,0.100469f},{-0.318747f,-0.00606509f,0.100469f},{-0.316368f,-0.0113881f,0.100469f}, -{-0.322729f,1.62449e-016f,0.100469f},{-0.337628f,0.00835238f,0.100469f},{-0.338154f,0.00559444f,0.100469f}, -{-0.316548f,0.013106f,0.100469f},{-0.333514f,0.0187591f,0.100469f},{-0.328493f,0.0255017f,0.100469f}, -{-0.330334f,0.0233817f,0.100469f},{-0.316076f,0.0141674f,0.100469f},{-0.324357f,0.0292931f,0.100469f}, -{-0.311551f,0.0141686f,0.100469f},{-0.291027f,0.0141674f,0.100469f},{-0.290637f,0.0146009f,0.100469f}, -{-0.296007f,0.014044f,0.100469f},{-0.299245f,0.00520628f,0.100469f},{-0.30649f,0.0369236f,0.100469f}, -{-0.309253f,0.0364276f,0.100469f},{-0.304276f,0.0211188f,0.100469f},{-0.303697f,0.0371926f,0.100469f}, -{-0.301289f,0.0214407f,0.100469f},{-0.300891f,0.0372872f,0.100469f},{-0.298087f,0.0371512f,0.100469f}, -{-0.295301f,0.0368049f,0.100469f},{-0.287208f,0.0345284f,0.100469f},{-0.289845f,0.0354896f,0.100469f}, -{-0.286895f,0.0146037f,0.100469f},{-0.275498f,0.0269304f,0.100469f},{-0.277597f,0.0287947f,0.100469f}, -{-0.282186f,0.0320239f,0.100469f},{-0.288473f,0.0153056f,0.100469f},{-0.287901f,0.0151842f,0.100469f}, -{-0.288797f,-0.00343287f,0.100469f},{-0.289162f,-0.00227358f,0.100469f},{-0.27258f,0.024361f,0.100469f}, -{-0.28621f,0.0136627f,0.100469f},{-0.286029f,0.0131075f,0.100469f},{-0.286029f,-0.0119409f,0.100469f}, -{-0.28621f,-0.0113857f,0.100469f},{0.255913f,0.000431293f,0.100469f},{0.279758f,-0.0304444f,0.100469f}, -{0.280721f,-0.00408405f,0.100469f},{0.266037f,-0.019928f,0.100469f},{0.262471f,-0.0181266f,0.100469f}, -{0.254583f,0.00139831f,0.100469f},{0.299246f,0.00520701f,0.100469f},{0.300871f,0.00557763f,0.100469f}, -{0.301707f,0.00557747f,0.100469f},{0.301289f,0.0121187f,0.100469f},{0.296674f,0.00314864f,0.100469f}, -{0.277562f,0.0287659f,0.100469f},{0.287366f,0.014946f,0.100469f},{0.275498f,0.0269304f,0.100469f}, -{0.286501f,0.0141674f,0.100469f},{0.286892f,0.0146009f,0.100469f},{0.289055f,-0.00974281f,0.100469f}, -{0.290634f,-0.0104447f,0.100469f},{0.300445f,-0.0372813f,0.100469f},{0.303207f,-0.0372145f,0.100469f}, -{0.282653f,-0.00571052f,0.100469f},{0.286029f,-0.0119424f,0.100469f},{-0.041888f,-0.08052f,0.100469f}, -{-0.0410252f,-0.0790251f,0.100469f},{-0.0930856f,-0.0768218f,0.100469f},{-0.0919114f,-0.0814392f,0.100469f}, -{-0.092657f,-0.0791278f,0.100469f},{0.0808074f,-0.078321f,0.100469f},{0.079703f,-0.07868f,0.100469f}, -{0.0824989f,-0.0786793f,0.100469f},{0.0930843f,-0.0768194f,0.100469f},{0.0814392f,0.0919114f,0.100469f}, -{0.0632438f,0.0600777f,0.100469f},{0.0643614f,0.0586762f,0.100469f},{0.0653869f,0.0572057f,0.100469f}, -{0.0663164f,0.0556727f,0.100469f},{0.0464129f,0.0695568f,0.100469f},{0.0481725f,0.069214f,0.100469f}, -{0.0499065f,0.0687593f,0.100469f},{0.0819653f,0.0837618f,0.100469f},{0.0858213f,0.089447f,0.100469f}, -{0.0833638f,0.0827462f,0.100469f},{-0.0689986f,0.0490431f,0.100469f},{-0.0684765f,0.0507578f,0.100469f}, -{-0.0833647f,0.082745f,0.100469f},{-0.0698583f,0.0437414f,0.100469f},{-0.041888f,0.0816836f,0.100469f}, -{-0.0516077f,0.0681947f,0.100469f},{-0.0969955f,0.0213792f,0.100469f},{-0.0499063f,0.0687596f,0.100469f}, -{-0.0937839f,0.0280757f,0.100469f},{-0.0768218f,0.0930856f,0.100469f},{-0.0745764f,0.0932205f,0.100469f}, -{-0.0792323f,0.0831813f,0.100469f},{-0.0785474f,0.0822403f,0.100469f},{-0.0788398f,0.0827462f,0.100469f}, -{-0.0783669f,0.0816851f,0.100469f},{-0.0410252f,0.0831785f,0.100469f},{-0.0405514f,0.0835236f,0.100469f}, -{-0.0290135f,-0.0171549f,0.100469f},{-0.0620385f,0.0614053f,0.100469f},{-0.0632437f,0.0600781f,0.100469f}, -{-0.0607507f,0.0626525f,0.100469f},{-0.0593856f,0.0638145f,0.100469f},{-0.0579489f,0.0648867f,0.100469f}, -{-0.0564465f,0.0658647f,0.100469f},{-0.041708f,0.0822379f,0.100469f},{-0.0548845f,0.0667443f,0.100469f}, -{-0.0532694f,0.0675221f,0.100469f},{-0.0414155f,0.082745f,0.100469f},{-0.0400177f,0.0837612f,0.100469f}, -{-0.0388615f,0.0838832f,0.100469f},{-0.039447f,0.0838826f,0.100469f},{-0.0382891f,0.0837618f,0.100469f}, -{-0.0368906f,0.0827462f,0.100469f},{0.0257644f,0.0945295f,0.100469f},{0.0280757f,0.0937839f,0.100469f}, -{0.0303817f,0.0933553f,0.100469f},{0.0364172f,0.0816836f,0.100469f},{0.0564469f,-0.0180347f,0.100469f}, -{0.0532697f,-0.016377f,0.100469f},{0.0516079f,-0.0157041f,0.100469f},{0.0446349f,-0.0141124f,0.100469f}, -{0.0259495f,0.0648867f,0.100469f},{0.0235077f,0.0956027f,0.100469f},{-0.0231475f,-0.0212468f,0.100469f}, -{0.0245128f,0.0638145f,0.100469f},{0.0365972f,0.0822379f,0.100469f},{0.0368897f,0.082745f,0.100469f}, -{0.0372799f,0.0831785f,0.100469f},{0.0382875f,0.0837612f,0.100469f},{0.0377538f,0.0835236f,0.100469f}, -{0.0400161f,0.0837618f,0.100469f},{0.0405497f,0.0835243f,0.100469f},{0.0414146f,0.0827462f,0.100469f}, -{0.0410221f,0.0831813f,0.100469f},{0.041707f,0.0822403f,0.100469f},{-0.0303817f,-0.0933553f,0.100469f}, -{0.0377538f,-0.07868f,0.100469f},{0.0382875f,-0.0784424f,0.100469f},{0.0405497f,-0.0786793f,0.100469f}, -{0.0339921f,0.0687596f,0.100469f},{0.0464129f,-0.0143416f,0.100469f},{0.0274519f,0.0658647f,0.100469f}, -{0.0339921f,-0.0151388f,0.100469f},{0.0259495f,-0.0190117f,0.100469f},{0.0213792f,0.0969955f,0.100469f}, -{0.0231477f,0.0626525f,0.100469f},{-0.0142141f,0.0455253f,0.100469f},{-0.0140402f,0.043741f,0.100469f}, -{0.0142116f,0.0455262f,0.100469f},{0.0140401f,0.0437414f,0.100469f},{0.0144962f,0.0472966f,0.100469f}, -{0.0148999f,0.0490431f,0.100469f},{-0.0145004f,0.0472947f,0.100469f},{-0.0410525f,0.069901f,0.100469f}, -{-0.0428452f,0.069901f,0.100469f},{-0.0392635f,0.0697861f,0.100469f},{0.0154219f,0.0507578f,0.100469f}, -{0.0160313f,0.0524435f,0.100469f},{-0.0154086f,0.0507615f,0.100469f},{-0.0167532f,0.0540833f,0.100469f}, -{-0.0160285f,0.0524438f,0.100469f},{0.0167528f,0.0540841f,0.100469f},{-0.0374855f,0.0695568f,0.100469f}, -{0.0185112f,0.0572063f,0.100469f},{-0.0185115f,0.0572057f,0.100469f},{-0.0175821f,0.0556727f,0.100469f}, -{0.0206547f,0.0600781f,0.100469f},{-0.0206546f,0.0600777f,0.100469f},{-0.019537f,0.0586762f,0.100469f}, -{-0.0274515f,0.0658638f,0.100469f},{0.0218599f,0.0614053f,0.100469f},{0.0532697f,0.0675214f,0.100469f}, -{0.0579493f,0.0648858f,0.100469f},{0.0593859f,0.0638136f,0.100469f},{0.0607509f,0.0626516f,0.100469f}, -{0.0620386f,0.0614045f,0.100469f},{0.0671452f,0.0540833f,0.100469f},{0.0684898f,0.0507615f,0.100469f}, -{0.0689996f,0.0490425f,0.100469f},{0.0696843f,0.0455253f,0.100469f},{0.069398f,0.0472947f,0.100469f}, -{0.0698582f,0.043741f,0.100469f},{-0.048172f,0.0692143f,0.100469f},{-0.0464123f,0.069557f,0.100469f}, -{-0.0374855f,-0.0143416f,0.100469f},{-0.0410525f,-0.0139975f,0.100469f},{-0.0446342f,-0.0141123f,0.100469f}, -{-0.0956027f,0.0235077f,0.100469f},{-0.0945295f,0.0257644f,0.100469f},{-0.0678671f,0.0524435f,0.100469f}, -{-0.0671457f,0.0540841f,0.100469f},{-0.0663166f,0.0556734f,0.100469f},{-0.0643615f,0.0586764f,0.100469f}, -{0.0195369f,0.0586764f,0.100469f},{0.0175819f,0.0556734f,0.100469f},{-0.0148988f,0.0490425f,0.100469f}, -{-0.243259f,-0.0139831f,0.100469f},{-0.218182f,0.000819718f,0.100469f},{-0.218384f,0.000430548f,0.100469f}, -{-0.217492f,0.00133028f,0.100469f},{-0.217881f,0.00113282f,0.100469f},{-0.217061f,0.00139831f,0.100469f}, -{-0.215936f,0.000817561f,0.100469f},{-0.215731f,0.000431293f,0.100469f},{-0.00112134f,-0.217837f,0.100469f}, -{-0.00082033f,-0.217524f,0.100469f},{-0.000431051f,-0.217326f,0.100469f},{3.14109e-017f,-0.217258f,0.100469f}, -{0.000819963f,-0.217529f,0.100469f},{0.000433147f,-0.217327f,0.100469f},{0.0013304f,-0.218225f,0.100469f}, -{0.00112493f,-0.217839f,0.100469f},{-0.016635f,-0.258757f,0.100469f},{-0.005033f,-0.281577f,0.100469f}, -{-0.0128186f,-0.285984f,0.100469f},{-0.0122331f,-0.285983f,0.100469f},{-0.0141452f,-0.247144f,0.100469f}, -{-0.00082033f,-0.254812f,0.100469f},{0.0106515f,-0.286688f,0.100469f},{0.00204334f,-0.296082f,0.100469f}, -{-0.00186868f,-0.279929f,0.100469f},{0.00445857f,-0.288143f,0.100469f},{-0.00408405f,-0.280721f,0.100469f}, -{-0.019928f,-0.266037f,0.100469f},{-0.00112134f,0.219476f,0.100469f},{-0.00132352f,0.219087f,0.100469f}, -{2.64296e-017f,0.220055f,0.100469f},{0.000819963f,0.219784f,0.100469f},{0.000433147f,0.219986f,0.100469f}, -{0.0013304f,0.219088f,0.100469f},{0.00112493f,0.219474f,0.100469f},{-0.0146388f,0.251049f,0.100469f}, -{0.019928f,0.266037f,0.100469f},{0.00408405f,0.280721f,0.100469f},{0.000433147f,0.257274f,0.100469f}, -{0.00186868f,0.279929f,0.100469f},{2.76524e-017f,0.257343f,0.100469f},{-0.000431051f,0.257275f,0.100469f}, -{0.005033f,0.281577f,0.100469f},{0.0220158f,0.269418f,0.100469f},{0.21663f,0.00133028f,0.100469f}, -{0.217061f,0.00139831f,0.100469f},{0.21594f,0.000819718f,0.100469f},{0.215737f,0.000430548f,0.100469f}, -{0.216241f,0.00113282f,0.100469f},{0.217881f,0.00112774f,0.100469f},{0.217494f,0.00132937f,0.100469f}, -{-0.254935f,-0.0154692f,0.100469f},{-0.251049f,-0.0146388f,0.100469f},{-0.25415f,0.00132937f,0.100469f}, -{-0.253763f,0.00112774f,0.100469f},{-0.247144f,0.0141452f,0.100469f},{-0.253458f,0.000817561f,0.100469f}, -{0.00996883f,-0.312677f,0.100469f},{0.0102613f,-0.312169f,0.100469f},{0.0116591f,-0.311153f,0.100469f}, -{0.0128153f,-0.311031f,0.100469f},{0.0151227f,-0.307131f,0.100469f},{0.0205678f,-0.297204f,0.100469f}, -{0.0211188f,-0.298301f,0.100469f},{0.00534277f,-0.299641f,0.100469f},{0.0150786f,-0.312674f,0.100469f}, -{0.012073f,-0.302345f,0.100469f},{0.0121187f,-0.301289f,0.100469f},{0.00528144f,-0.287245f,0.100469f}, -{0.0097888f,-0.288183f,0.100469f},{-0.0102622f,-0.28712f,0.100469f},{-0.00996978f,-0.287626f,0.100469f}, -{-0.0116607f,-0.286104f,0.100469f},{-0.00606509f,-0.28383f,0.100469f},{-0.00571052f,-0.282653f,0.100469f}, -{-0.0220158f,-0.269418f,0.100469f},{-0.0133893f,-0.286105f,0.100469f},{0.0133877f,-0.286104f,0.100469f}, -{0.0220151f,-0.269417f,0.100469f},{0.0128153f,-0.285983f,0.100469f},{0.0199275f,-0.266037f,0.100469f}, -{0.0139213f,-0.286342f,0.100469f},{-0.0320239f,-0.282186f,0.100469f},{-0.0152596f,-0.288183f,0.100469f}, -{-0.0147871f,-0.312169f,0.100469f},{-0.0143968f,-0.311736f,0.100469f},{-0.0150796f,-0.312677f,0.100469f}, -{-0.0174585f,-0.307354f,0.100469f},{-0.0186351f,-0.306999f,0.100469f},{-0.0364276f,-0.309253f,0.100469f}, -{-0.0371512f,-0.298087f,0.100469f},{-0.0333708f,-0.284649f,0.100469f},{-0.0147871f,-0.287121f,0.100469f}, -{-0.0269304f,-0.275498f,0.100469f},{-0.0111271f,-0.286342f,0.100469f},{-0.0106546f,-0.286685f,0.100469f}, -{0.0116591f,-0.286105f,0.100469f},{0.0111254f,-0.286343f,0.100469f},{-0.00978928f,-0.288181f,0.100469f}, -{-0.0137103f,-0.335964f,0.100469f},{-0.00280508f,-0.338471f,0.100469f},{-0.00559444f,-0.338154f,0.100469f}, -{-0.0152596f,-0.313231f,0.100469f},{-0.0197119f,-0.306322f,0.100469f},{-0.033718f,-0.31721f,0.100469f}, -{-0.013923f,-0.311391f,0.100469f},{-0.0133893f,-0.311153f,0.100469f},{-0.0122331f,-0.311031f,0.100469f}, -{-0.0128186f,-0.311032f,0.100469f},{-0.012073f,-0.300232f,0.100469f},{-0.0121187f,-0.301289f,0.100469f}, -{-0.00978928f,-0.313229f,0.100469f},{-0.00528144f,-0.315333f,0.100469f},{0.301289f,-0.0121187f,0.100469f}, -{0.316563f,-0.0340163f,0.100469f},{0.311077f,-0.0119424f,0.100469f},{0.311257f,-0.0113881f,0.100469f}, -{0.31155f,-0.010881f,0.100469f},{0.312948f,-0.00986481f,0.100469f},{0.314104f,-0.00974281f,0.100469f}, -{0.316411f,-0.00584288f,0.100469f},{0.316548f,-0.0119409f,0.100469f},{0.338346f,-0.00413651f,0.100469f}, -{0.308687f,-0.036547f,0.100469f},{0.304276f,-0.0211188f,0.100469f},{0.30596f,-0.0369944f,0.100469f}, -{0.286892f,-0.0104475f,0.100469f},{0.303157f,-0.0213591f,0.100469f},{0.277563f,-0.0287664f,0.100469f}, -{0.28847f,-0.0097434f,0.100469f},{0.291499f,-0.0119409f,0.100469f},{0.296007f,-0.014044f,0.100469f}, -{0.298492f,0.00484444f,0.100469f},{0.303332f,0.00520628f,0.100469f},{0.291499f,0.0131075f,0.100469f}, -{0.305387f,0.00380369f,0.100469f},{0.31155f,0.0141674f,0.100469f},{0.316075f,0.0141686f,0.100469f}, -{0.32971f,0.0241396f,0.100469f},{0.327834f,0.0261674f,0.100469f},{0.316367f,-0.0113857f,0.100469f}, -{0.336523f,0.0122076f,0.100469f},{0.313362f,-0.00105623f,0.100469f},{0.313407f,5.8201e-009f,0.100469f}, -{0.307131f,0.0151227f,0.100469f},{0.28959f,0.035405f,0.100469f},{0.314104f,0.0153056f,0.100469f}, -{5.35539e-017f,0.279848f,0.100469f},{-0.0102622f,0.290409f,0.100469f},{0.024361f,0.27258f,0.100469f}, -{-0.0199275f,0.266037f,0.100469f},{-0.0174585f,0.295223f,0.100469f},{-0.00553085f,0.302123f,0.100469f}, -{-0.0128186f,0.291545f,0.100469f},{-0.0122331f,0.291546f,0.100469f},{-0.00461423f,0.304437f,0.100469f}, -{-0.012073f,0.302345f,0.100469f},{-0.0121187f,0.301289f,0.100469f},{-0.00978928f,0.289348f,0.100469f}, -{-0.00528144f,0.287245f,0.100469f},{-0.0150796f,0.314949f,0.100469f},{-0.0151227f,0.307131f,0.100469f}, -{-0.0124916f,0.304721f,0.100469f},{-0.013923f,0.291186f,0.100469f},{-0.0133893f,0.291424f,0.100469f}, -{-0.0205678f,0.297204f,0.100469f},{0.00204334f,0.306495f,0.100469f},{0.00348695f,0.305661f,0.100469f}, -{0.00409889f,0.305092f,0.100469f},{0.002796f,0.306132f,0.100469f},{5.8201e-009f,0.28917f,0.100469f}, -{0.00571052f,0.282653f,0.100469f},{0.00996883f,0.2899f,0.100469f},{0.0102613f,0.290408f,0.100469f}, -{0.0116591f,0.291424f,0.100469f},{0.0128153f,0.291546f,0.100469f},{0.0151227f,0.295446f,0.100469f}, -{0.0211188f,0.304276f,0.100469f},{0.0369236f,0.30649f,0.100469f},{0.0364276f,0.309253f,0.100469f}, -{0.0213591f,0.303157f,0.100469f},{0.0371512f,0.298087f,0.100469f},{0.0368049f,0.295301f,0.100469f}, -{0.0362494f,0.292548f,0.100469f},{0.00534277f,0.302936f,0.100469f},{0.0143937f,0.315892f,0.100469f}, -{0.0274755f,0.326496f,0.100469f},{0.0255017f,0.328493f,0.100469f},{0.0150786f,0.289903f,0.100469f}, -{0.012073f,0.300232f,0.100469f},{0.0121187f,0.301289f,0.100469f},{0.0137103f,0.335964f,0.100469f}, -{0.00584288f,0.316411f,0.100469f},{0.0106515f,0.315889f,0.100469f},{0.0111254f,0.316235f,0.100469f}, -{0.0102613f,0.315456f,0.100469f},{0.0162807f,0.334834f,0.100469f},{0.0211299f,0.332011f,0.100469f}, -{-0.301289f,-0.0121187f,0.100469f},{-0.29132f,-0.0113881f,0.100469f},{-0.291027f,-0.010881f,0.100469f}, -{-0.289629f,-0.00986481f,0.100469f},{-0.288473f,-0.00974281f,0.100469f},{-0.286166f,-0.00584288f,0.100469f}, -{-0.286502f,-0.0108798f,0.100469f},{-0.280721f,0.00408405f,0.100469f},{-0.279848f,6.36295e-017f,0.100469f}, -{-0.279929f,0.00186868f,0.100469f},{-0.289216f,-0.00105623f,0.100469f},{-0.28917f,5.8201e-009f,0.100469f}, -{-0.29683f,0.0131454f,0.100469f},{-0.2915f,0.013106f,0.100469f},{-0.295446f,0.0151227f,0.100469f}, -{-0.312949f,0.0151842f,0.100469f},{-0.31721f,0.033718f,0.100469f},{-0.303157f,0.0213591f,0.100469f}, -{-0.292548f,0.0362494f,0.100469f},{-0.284649f,0.0333708f,0.100469f},{-0.279831f,0.0304957f,0.100469f}, -{-0.287367f,0.0149467f,0.100469f},{-0.286502f,0.0141686f,0.100469f},{-0.316368f,0.0136603f,0.100469f}, -{-0.332011f,0.0211299f,0.100469f},{-0.314434f,0.00445857f,0.100469f},{-0.315333f,0.00528144f,0.100469f}, -{-0.306819f,0.000834183f,0.100469f},{-0.316548f,-0.0119424f,0.100469f},{-0.319924f,-0.00571052f,0.100469f}, -{-0.321856f,-0.00408405f,0.100469f},{-0.338471f,0.00280508f,0.100469f},{-0.334834f,0.0162807f,0.100469f}, -{-0.322089f,0.0309477f,0.100469f},{-0.314629f,0.0348202f,0.100469f},{-0.305373f,0.0205678f,0.100469f}, -{-0.311971f,0.0357252f,0.100469f},{-0.290163f,0.014946f,0.100469f},{-0.311078f,0.0131075f,0.100469f}, -{-0.315212f,-0.0101024f,0.100469f},{-0.314678f,-0.00986481f,0.100469f},{-0.313522f,-0.00974281f,0.100469f}, -{-0.314107f,-0.0097434f,0.100469f},{-0.313362f,0.00105623f,0.100469f},{-0.313407f,-5.8201e-009f,0.100469f}, -{-0.311078f,-0.0119409f,0.100469f},{-0.30657f,-0.014044f,0.100469f},{0.337938f,-0.00686904f,0.100469f}, -{0.336521f,-0.0122059f,0.100469f},{0.314676f,-0.00986419f,0.100469f},{0.291319f,0.0136627f,0.100469f}, -{0.308686f,0.0365475f,0.100469f},{0.311257f,0.0136603f,0.100469f},{-0.287901f,-0.00986419f,0.100469f}, -{0.0122298f,-0.285984f,0.100469f},{0.00996883f,-0.287628f,0.100469f},{0.0133877f,0.291424f,0.100469f}, -{-0.311258f,0.0136627f,0.100469f},{-0.29132f,0.0136603f,0.100469f},{-0.00996978f,0.314951f,0.100469f}, -{0.00996883f,0.314949f,0.100469f},{0.0152591f,-0.313229f,0.100469f},{0.0133877f,-0.311153f,0.100469f}, -{-0.0836959f,-0.0908383f,0.0918925f},{-0.0858243f,-0.0894455f,0.0918925f},{-0.0633282f,-0.0805185f,0.0918925f}, -{-0.0671452f,-0.0298151f,0.0918925f},{-0.0937839f,-0.0280757f,0.0918925f},{-0.0663164f,-0.0282257f,0.0918925f}, -{-0.0580379f,-0.0799657f,0.0918925f},{0.0145474f,-0.107316f,0.0918925f},{-0.0141179f,-0.109619f,0.0918925f}, -{-0.0145465f,-0.107313f,0.0918925f},{-0.089447f,-0.0858213f,0.0918925f},{-0.0908391f,-0.0836927f,0.0918925f}, -{-0.0877597f,-0.0877597f,0.0918925f},{-0.005033f,-0.281577f,0.0918925f},{-0.0057111f,-0.28266f,0.0918925f}, -{-0.0122298f,-0.285984f,0.0918925f},{-0.0919114f,-0.0814392f,0.0918925f},{-0.0631477f,-0.0799633f,0.0918925f}, -{-0.0619904f,-0.0786793f,0.0918925f},{-0.0624629f,-0.0790223f,0.0918925f},{-0.0932205f,-0.0745764f,0.0918925f}, -{-0.0628553f,-0.0794574f,0.0918925f},{-0.0362489f,-0.292548f,0.0918925f},{-0.0333688f,-0.28465f,0.0918925f}, -{-0.0320225f,-0.282186f,0.0918925f},{-0.0926561f,-0.079125f,0.0918925f},{-0.0930843f,-0.0768194f,0.0918925f}, -{-0.0932205f,-0.0326272f,0.0918925f},{-0.0602989f,-0.078321f,0.0918925f},{-0.0597282f,-0.0784424f,0.0918925f}, -{-0.100617f,0.0177581f,0.0918925f},{-0.0986812f,0.0194438f,0.0918925f},{-0.10062f,-0.0177565f,0.0918925f}, -{0.0194438f,0.0986812f,0.0918925f},{0.0206546f,0.0600777f,0.0918925f},{-0.0206547f,0.0600781f,0.0918925f}, -{-0.105002f,0.0152921f,0.0918925f},{-0.102745f,0.0163653f,0.0918925f},{-0.105002f,-0.0152921f,0.0918925f}, -{-0.102748f,-0.0163644f,0.0918925f},{-0.107316f,-0.0145474f,0.0918925f},{-0.109622f,-0.0141193f,0.0918925f}, -{-0.107313f,0.0145465f,0.0918925f},{-0.312414f,-0.0101024f,0.0918925f},{-0.312948f,-0.00986481f,0.0918925f}, -{-0.109619f,0.0141179f,0.0918925f},{-0.313414f,0.00227064f,0.0918925f},{-0.306819f,0.000833312f,0.0918925f}, -{-0.313362f,0.00105623f,0.0918925f},{-0.313518f,0.015305f,0.0918925f},{-0.307f,0.0186287f,0.0918925f}, -{-0.312948f,0.0151836f,0.0918925f},{-0.287207f,0.034526f,0.0918925f},{-0.28465f,0.0333688f,0.0918925f}, -{-0.287366f,0.014946f,0.0918925f},{-0.27983f,0.0304947f,0.0918925f},{-0.277597f,0.0287942f,0.0918925f}, -{-0.313779f,0.00343053f,0.0918925f},{-0.306325f,0.00242484f,0.0918925f},{-0.322729f,1.62449e-016f,0.0918925f}, -{-0.322648f,-0.00186868f,0.0918925f},{-0.300045f,0.00545321f,0.0918925f},{-0.300232f,0.012073f,0.0918925f}, -{-0.299018f,0.0121253f,0.0918925f},{-0.304719f,-0.0124909f,0.0918925f},{-0.311257f,-0.0113881f,0.0918925f}, -{-0.31155f,-0.010881f,0.0918925f},{-0.30713f,-0.01512f,0.0918925f},{-0.295577f,-0.0186287f,0.0918925f}, -{0.0152596f,-0.313231f,0.0918925f},{-0.316075f,-0.0108798f,0.0918925f},{-0.316367f,-0.0113857f,0.0918925f}, -{-0.318741f,-0.00606332f,0.0918925f},{-0.00105623f,-0.313362f,0.0918925f},{-0.00227064f,-0.313414f,0.0918925f}, -{0.00348669f,-0.296915f,0.0918925f},{0.00409933f,-0.297483f,0.0918925f},{-0.316548f,-0.0119409f,0.0918925f}, -{-0.319917f,-0.0057111f,0.0918925f},{-0.298492f,0.00484444f,0.0918925f},{-0.297858f,0.0124909f,0.0918925f}, -{-0.297802f,0.00437403f,0.0918925f},{-0.301289f,0.0121187f,0.0918925f},{-0.300871f,0.00557763f,0.0918925f}, -{-0.301707f,0.00557747f,0.0918925f},{-0.0274641f,-0.326484f,0.0918925f},{-0.314104f,0.0153056f,0.0918925f}, -{-0.314676f,0.0151842f,0.0918925f},{-0.319701f,0.0324249f,0.0918925f},{-0.00343053f,-0.313779f,0.0918925f}, -{-0.0102613f,-0.312169f,0.0918925f},{-0.0211319f,-0.332012f,0.0918925f},{-0.0233837f,-0.330334f,0.0918925f}, -{-0.305907f,0.00314874f,0.0918925f},{-0.311077f,0.013106f,0.0918925f},{-0.0131452f,-0.29683f,0.0918925f}, -{-0.0140418f,-0.296008f,0.0918925f},{-0.292548f,0.0362489f,0.0918925f},{-0.2953f,0.0368031f,0.0918925f}, -{-0.306322f,0.0197119f,0.0918925f},{-0.289055f,0.0153056f,0.0918925f},{-0.291499f,0.0131075f,0.0918925f}, -{-0.296008f,0.0140418f,0.0918925f},{-0.302534f,0.00545274f,0.0918925f},{-0.303332f,0.00520628f,0.0918925f}, -{-0.332012f,0.0211319f,0.0918925f},{-0.316367f,0.0136627f,0.0918925f},{-0.316548f,0.0131075f,0.0918925f}, -{-0.313518f,-0.0097434f,0.0918925f},{-0.27258f,0.0243605f,0.0918925f},{-0.286209f,0.0136603f,0.0918925f}, -{-0.286501f,0.0141674f,0.0918925f},{-0.255913f,0.000431293f,0.0918925f},{-0.279929f,0.00186868f,0.0918925f}, -{-0.280169f,0.00299304f,0.0918925f},{-0.266037f,0.0199275f,0.0918925f},{-0.280722f,0.00409024f,0.0918925f}, -{-0.334835f,0.0162821f,0.0918925f},{-0.335965f,0.0137123f,0.0918925f},{-0.31521f,-0.0101017f,0.0918925f}, -{-0.279848f,6.36295e-017f,0.0918925f},{-0.305379f,0.0205661f,0.0918925f},{-0.314628f,0.0348205f,0.0918925f}, -{-0.311971f,0.0357253f,0.0918925f},{-0.336898f,0.0110641f,0.0918925f},{-0.31194f,-0.0104475f,0.0918925f}, -{0.0128186f,0.316594f,0.0918925f},{0.0187595f,0.333514f,0.0918925f},{0.0133893f,0.316472f,0.0918925f}, -{-0.291319f,-0.0113857f,0.0918925f},{0.036428f,0.309253f,0.0918925f},{0.0369213f,0.306489f,0.0918925f}, -{0.0211196f,0.304282f,0.0918925f},{-0.291026f,-0.0108798f,0.0918925f},{-0.243259f,-0.0139831f,0.0918925f}, -{-0.281577f,0.005033f,0.0918925f},{-0.28266f,0.0057111f,0.0918925f},{-0.111865f,-0.0139831f,0.0918925f}, -{-0.111865f,0.0139831f,0.0918925f},{-0.254935f,0.0154692f,0.0918925f},{-0.254583f,0.00139831f,0.0918925f}, -{-0.255016f,0.00132937f,0.0918925f},{-0.296262f,0.00242058f,0.0918925f},{-0.29594f,0.00165192f,0.0918925f}, -{-0.251049f,0.0146388f,0.0918925f},{-0.297189f,0.00380587f,0.0918925f},{-0.247144f,-0.0141452f,0.0918925f}, -{-0.253763f,0.00113282f,0.0918925f},{-0.254152f,0.00133028f,0.0918925f},{-0.262471f,0.0181265f,0.0918925f}, -{-0.258757f,0.0166349f,0.0918925f},{-0.255708f,0.000817561f,0.0918925f},{-0.253462f,0.000819718f,0.0918925f}, -{-0.247143f,0.0141453f,0.0918925f},{-0.243259f,0.0139831f,0.0918925f},{-0.253259f,0.000430548f,0.0918925f}, -{-0.258757f,-0.016635f,0.0918925f},{-0.25105f,-0.0146388f,0.0918925f},{-0.254936f,-0.0154693f,0.0918925f}, -{-0.0956018f,0.0235109f,0.0918925f},{-0.0986812f,-0.0194438f,0.0918925f},{-0.0564469f,0.0658638f,0.0918925f}, -{-0.0339921f,0.0687596f,0.0918925f},{-0.0322907f,0.0681947f,0.0918925f},{-0.0933567f,0.0303842f,0.0918925f}, -{-0.0932205f,0.0326272f,0.0918925f},{-0.0357264f,0.0692143f,0.0918925f},{-0.0374861f,0.069557f,0.0918925f}, -{-0.0937848f,0.0280785f,0.0918925f},{0.0175821f,0.0556727f,0.0918925f},{-0.0167528f,0.0540841f,0.0918925f}, -{-0.0175819f,0.0556734f,0.0918925f},{0.0937848f,-0.0280785f,0.0918925f},{0.0663166f,-0.028225f,0.0918925f}, -{0.0945295f,-0.0257644f,0.0918925f},{-0.079125f,0.0926561f,0.0918925f},{-0.079703f,0.0835236f,0.0918925f}, -{-0.0802367f,0.0837612f,0.0918925f},{-0.0516079f,-0.0157041f,0.0918925f},{-0.0813929f,0.0838832f,0.0918925f}, -{-0.0836927f,0.0908391f,0.0918925f},{-0.0814392f,0.0919114f,0.0918925f},{-0.0768194f,0.0930843f,0.0918925f}, -{-0.0792292f,0.0831785f,0.0918925f},{-0.0829714f,0.0831813f,0.0918925f},{-0.0877597f,0.0877597f,0.0918925f}, -{-0.0824989f,0.0835243f,0.0918925f},{-0.0745764f,0.0932205f,0.0918925f},{-0.0785464f,0.0822379f,0.0918925f}, -{-0.0788389f,0.082745f,0.0918925f},{-0.0836562f,0.0822403f,0.0918925f},{-0.0838367f,0.0816851f,0.0918925f}, -{-0.0894455f,0.0858243f,0.0918925f},{-0.0783664f,0.0816836f,0.0918925f},{-0.0919114f,0.0814392f,0.0918925f}, -{-0.0908383f,0.0836959f,0.0918925f},{-0.092657f,0.0791278f,0.0918925f},{-0.0808074f,0.0838826f,0.0918925f}, -{-0.0388582f,0.0838826f,0.0918925f},{-0.0394436f,0.0838832f,0.0918925f},{-0.0326272f,0.0932205f,0.0918925f}, -{-0.0930856f,0.0768218f,0.0918925f},{-0.0339921f,-0.0151388f,0.0918925f},{-0.0322907f,-0.0157037f,0.0918925f}, -{-0.0464129f,-0.0143416f,0.0918925f},{0.0322905f,0.0681943f,0.0918925f},{0.0339919f,0.0687593f,0.0918925f}, -{0.0932205f,-0.0745764f,0.0918925f},{0.0825006f,-0.07868f,0.0918925f},{0.0819669f,-0.0784424f,0.0918925f}, -{-0.0163644f,0.102748f,0.0918925f},{0.0152921f,0.105002f,0.0918925f},{0.0163653f,0.102745f,0.0918925f}, -{-0.0194438f,0.0986812f,0.0918925f},{0.0177581f,0.100617f,0.0918925f},{-0.0152921f,0.105002f,0.0918925f}, -{0.0145465f,0.107313f,0.0918925f},{0.0141179f,0.109619f,0.0918925f},{-0.0145474f,0.107316f,0.0918925f}, -{-0.0141193f,0.109622f,0.0918925f},{0.0139831f,0.111865f,0.0918925f},{0.00348669f,0.305663f,0.0918925f}, -{0.00343053f,0.313779f,0.0918925f},{0.0140418f,0.296008f,0.0918925f},{0.0122331f,0.291546f,0.0918925f}, -{0.0131452f,0.29683f,0.0918925f},{0.0372093f,0.303697f,0.0918925f},{0.0372859f,0.30089f,0.0918925f}, -{0.0214407f,0.301289f,0.0918925f},{0.0152596f,0.314395f,0.0918925f},{0.0309479f,0.322088f,0.0918925f}, -{0.0324249f,0.319701f,0.0918925f},{0.00227064f,0.313414f,0.0918925f},{0.00124367f,0.306742f,0.0918925f}, -{0.00105623f,0.313362f,0.0918925f},{0.0292956f,0.324358f,0.0918925f},{0.0147871f,0.315456f,0.0918925f}, -{0.0274641f,0.326484f,0.0918925f},{-0.00553077f,0.302122f,0.0918925f},{-0.012073f,0.302345f,0.0918925f}, -{-0.00348695f,0.305661f,0.0918925f},{-0.002796f,0.306132f,0.0918925f},{0.0106546f,0.315892f,0.0918925f}, -{-0.0121253f,0.303559f,0.0918925f},{-0.0124909f,0.304719f,0.0918925f},{-0.00503626f,0.303713f,0.0918925f}, -{-0.0046188f,0.304437f,0.0918925f},{7.81291e-017f,0.322729f,0.0918925f},{0.00280586f,0.338471f,0.0918925f}, -{-0.00409889f,0.305092f,0.0918925f},{-0.00186868f,0.322648f,0.0918925f},{-0.00409024f,0.321855f,0.0918925f}, -{-0.00204334f,0.306495f,0.0918925f},{-0.00124497f,0.306741f,0.0918925f},{-5.8201e-009f,0.313407f,0.0918925f}, -{0.00041711f,0.306866f,0.0918925f},{-0.0152591f,0.314396f,0.0918925f},{-0.0150786f,0.314951f,0.0918925f}, -{-0.000418664f,0.306866f,0.0918925f},{-0.0131452f,0.305747f,0.0918925f},{-0.0143937f,0.290844f,0.0918925f}, -{-0.0139213f,0.291187f,0.0918925f},{-0.0133877f,0.291424f,0.0918925f},{-0.0122298f,0.291545f,0.0918925f}, -{0.0213591f,0.303157f,0.0918925f},{0.00279621f,0.306133f,0.0918925f},{0.0371496f,0.298086f,0.0918925f}, -{0.0186287f,0.307f,0.0918925f},{0.00409933f,0.305094f,0.0918925f},{0.01512f,0.295447f,0.0918925f}, -{0.013923f,0.291186f,0.0918925f},{0.0362489f,0.292548f,0.0918925f},{0.0152596f,0.289346f,0.0918925f}, -{0.0333688f,0.28465f,0.0918925f},{0.034526f,0.287207f,0.0918925f},{0.00082033f,0.257077f,0.0918925f}, -{0.000431051f,0.257275f,0.0918925f},{0.00299304f,0.280169f,0.0918925f},{0.00534833f,0.30294f,0.0918925f}, -{0.00553085f,0.302123f,0.0918925f},{0.00996978f,0.289903f,0.0918925f},{0.0269304f,0.275498f,0.0918925f}, -{0.0220151f,0.269417f,0.0918925f},{0.0320225f,0.282186f,0.0918925f},{0.0287942f,0.277597f,0.0918925f}, -{-0.0213591f,0.29942f,0.0918925f},{0.00606332f,0.283836f,0.0918925f},{-0.0579493f,-0.0190126f,0.0918925f}, -{-0.0593859f,-0.0200848f,0.0918925f},{-0.0139831f,0.111865f,0.0918925f},{-0.0106515f,0.290841f,0.0918925f}, -{-0.0141452f,0.247144f,0.0918925f},{0.00112134f,0.256764f,0.0918925f},{0.0166349f,0.258757f,0.0918925f}, -{0.00132352f,0.256375f,0.0918925f},{0.00186868f,0.279929f,0.0918925f},{2.7892e-017f,0.257343f,0.0918925f}, -{0.0154692f,0.254935f,0.0918925f},{-0.024361f,0.27258f,0.0918925f},{0.0146388f,0.251049f,0.0918925f}, -{-0.00343053f,0.288798f,0.0918925f},{-0.0102613f,0.290408f,0.0918925f},{0.0141453f,0.247143f,0.0918925f}, -{-0.0181266f,0.262471f,0.0918925f},{-0.000819963f,0.257072f,0.0918925f},{-0.016635f,0.258757f,0.0918925f}, -{-0.0139831f,0.243259f,0.0918925f},{-0.00112493f,0.256762f,0.0918925f},{-0.0013304f,0.256376f,0.0918925f}, -{-0.0146388f,0.25105f,0.0918925f},{-0.0177565f,0.10062f,0.0918925f},{0.0257644f,0.0945295f,0.0918925f}, -{0.0259491f,0.0648858f,0.0918925f},{0.0235109f,0.0956018f,0.0918925f},{0.0245125f,0.0638136f,0.0918925f}, -{0.0290135f,0.0667435f,0.0918925f},{0.0274515f,0.0658638f,0.0918925f},{0.0154086f,-0.033137f,0.0918925f}, -{-0.0154219f,-0.0331407f,0.0918925f},{0.0160285f,-0.0314546f,0.0918925f},{0.0357259f,0.069214f,0.0918925f}, -{0.0548845f,-0.0171541f,0.0918925f},{0.0564465f,-0.0180338f,0.0918925f},{0.089447f,0.0858213f,0.0918925f}, -{0.0838372f,0.0816836f,0.0918925f},{0.0836572f,0.0822379f,0.0918925f},{0.0836959f,0.0908383f,0.0918925f}, -{0.0808108f,0.0838832f,0.0918925f},{0.0814392f,0.0919114f,0.0918925f},{0.0829744f,0.0831785f,0.0918925f}, -{0.0825006f,0.0835236f,0.0918925f},{0.0877597f,0.0877597f,0.0918925f},{0.0819669f,0.0837612f,0.0918925f}, -{0.0858243f,0.0894455f,0.0918925f},{0.0930843f,0.0768194f,0.0918925f},{0.0908391f,0.0836927f,0.0918925f}, -{0.107313f,-0.0145465f,0.0918925f},{0.107316f,0.0145474f,0.0918925f},{0.109622f,0.0141193f,0.0918925f}, -{0.0932205f,0.0745764f,0.0918925f},{0.0932205f,0.0326272f,0.0918925f},{0.0919114f,0.0814392f,0.0918925f}, -{0.0926561f,0.079125f,0.0918925f},{0.0698583f,0.0437414f,0.0918925f},{0.0696868f,0.0455262f,0.0918925f}, -{0.0833647f,0.082745f,0.0918925f},{0.0932205f,-0.0326272f,0.0918925f},{0.100617f,-0.0177581f,0.0918925f}, -{0.102748f,0.0163644f,0.0918925f},{0.102745f,-0.0163653f,0.0918925f},{0.0653872f,-0.0266922f,0.0918925f}, -{0.0956018f,-0.0235109f,0.0918925f},{0.105002f,-0.0152921f,0.0918925f},{0.105002f,0.0152921f,0.0918925f}, -{0.111865f,0.0139831f,0.0918925f},{0.109619f,-0.0141179f,0.0918925f},{0.111865f,-0.0139831f,0.0918925f}, -{0.290637f,-0.0104475f,0.0918925f},{0.32971f,-0.0241396f,0.0918925f},{0.301289f,-0.0214407f,0.0918925f}, -{0.303157f,-0.0213591f,0.0918925f},{0.303208f,-0.0372381f,0.0918925f},{0.306637f,0.00165192f,0.0918925f}, -{0.306315f,0.00242058f,0.0918925f},{0.316076f,-0.010881f,0.0918925f},{0.315685f,-0.0104475f,0.0918925f}, -{0.279758f,-0.0304433f,0.0918925f},{0.312949f,-0.00986419f,0.0918925f},{0.314434f,-0.00445839f,0.0918925f}, -{0.313522f,-0.00974281f,0.0918925f},{0.304719f,0.0124909f,0.0918925f},{0.325832f,0.0280694f,0.0918925f}, -{0.315685f,0.0146009f,0.0918925f},{0.315212f,0.014946f,0.0918925f},{0.29719f,0.00380369f,0.0918925f}, -{0.297802f,0.0043727f,0.0918925f},{0.306569f,0.0140418f,0.0918925f},{0.305747f,0.0131452f,0.0918925f}, -{0.300044f,0.00545274f,0.0918925f},{0.299245f,0.00520628f,0.0918925f},{0.314107f,0.015305f,0.0918925f}, -{0.319039f,0.032792f,0.0918925f},{0.321418f,0.0313879f,0.0918925f},{0.332963f,0.0196753f,0.0918925f}, -{0.334333f,0.0172761f,0.0918925f},{0.316548f,0.013106f,0.0918925f},{0.302345f,0.012073f,0.0918925f}, -{0.301706f,0.00557763f,0.0918925f},{0.301289f,0.0121187f,0.0918925f},{0.338551f,0.00138096f,0.0918925f}, -{0.322648f,0.00186868f,0.0918925f},{0.338346f,0.00413651f,0.0918925f},{0.335521f,0.0147817f,0.0918925f}, -{0.321855f,0.00409024f,0.0918925f},{0.321f,0.005033f,0.0918925f},{0.338551f,-0.00138181f,0.0918925f}, -{0.322729f,-7.81484e-018f,0.0918925f},{0.287367f,-0.0101017f,0.0918925f},{0.286895f,-0.0104447f,0.0918925f}, -{0.306819f,0.000834183f,0.0918925f},{0.319038f,-0.0327925f,0.0918925f},{0.316562f,-0.0340166f,0.0918925f}, -{0.306322f,-0.0197119f,0.0918925f},{0.292244f,-0.0361745f,0.0918925f},{0.304282f,-0.0211196f,0.0918925f}, -{0.305959f,-0.0369915f,0.0918925f},{0.311258f,-0.0113857f,0.0918925f},{0.307f,-0.0186287f,0.0918925f}, -{0.313414f,-0.00227064f,0.0918925f},{0.313362f,-0.00105623f,0.0918925f},{0.323687f,-0.0298117f,0.0918925f}, -{0.325828f,-0.0280668f,0.0918925f},{0.29132f,-0.0113881f,0.0918925f},{0.291027f,-0.010881f,0.0918925f}, -{0.297858f,-0.0124909f,0.0918925f},{0.295447f,-0.01512f,0.0918925f},{0.289629f,-0.00986481f,0.0918925f}, -{0.289059f,-0.0097434f,0.0918925f},{0.331419f,-0.0219685f,0.0918925f},{0.316548f,-0.0119424f,0.0918925f}, -{0.277562f,-0.0287659f,0.0918925f},{0.275498f,-0.0269304f,0.0918925f},{0.27258f,-0.0243605f,0.0918925f}, -{0.269417f,-0.0220151f,0.0918925f},{0.316368f,-0.0113881f,0.0918925f},{0.338347f,-0.00413689f,0.0918925f}, -{0.305388f,0.00380587f,0.0918925f},{0.304775f,0.00437403f,0.0918925f},{0.31533f,-0.00528033f,0.0918925f}, -{0.337938f,0.00686904f,0.0918925f},{0.322408f,0.00299304f,0.0918925f},{0.304085f,0.00484444f,0.0918925f}, -{0.336521f,0.0122059f,0.0918925f},{0.303559f,0.0121253f,0.0918925f},{0.302532f,0.00545321f,0.0918925f}, -{0.0877597f,-0.0877597f,0.0918925f},{0.30087f,0.00557747f,0.0918925f},{0.316368f,0.0136603f,0.0918925f}, -{0.329709f,0.024138f,0.0918925f},{0.331418f,0.0219665f,0.0918925f},{0.28917f,-5.8201e-009f,0.0918925f}, -{0.314002f,0.0350539f,0.0918925f},{0.29667f,0.00314874f,0.0918925f},{0.254583f,0.00139831f,0.0918925f}, -{0.254936f,0.0154693f,0.0918925f},{0.255014f,0.00133028f,0.0918925f},{0.287247f,0.00528033f,0.0918925f}, -{0.288143f,0.00445839f,0.0918925f},{0.0678671f,-0.0314549f,0.0918925f},{0.0933567f,-0.0303842f,0.0918925f}, -{0.0684765f,-0.0331407f,0.0918925f},{0.266037f,0.019928f,0.0918925f},{0.279848f,1.74344e-017f,0.0918925f}, -{0.279929f,-0.00186868f,0.0918925f},{0.254935f,-0.0154692f,0.0918925f},{0.251049f,-0.0146388f,0.0918925f}, -{0.255906f,0.000430548f,0.0918925f},{0.262471f,0.0181266f,0.0918925f},{0.243259f,0.0139831f,0.0918925f}, -{0.253253f,0.000431293f,0.0918925f},{0.255704f,0.000819718f,0.0918925f},{0.258757f,0.016635f,0.0918925f}, -{0.25105f,0.0146388f,0.0918925f},{0.255403f,0.00113282f,0.0918925f},{0.218384f,0.000430548f,0.0918925f}, -{0.10062f,0.0177565f,0.0918925f},{0.0986812f,-0.0194438f,0.0918925f},{0.0986812f,0.0194438f,0.0918925f}, -{0.0643615f,-0.0252221f,0.0918925f},{0.0698583f,-0.040157f,0.0918925f},{-0.0372799f,-0.0790251f,0.0918925f}, -{-0.0377538f,-0.07868f,0.0918925f},{0.0814392f,-0.0919114f,0.0918925f},{0.079125f,-0.0926561f,0.0918925f}, -{0.0768194f,-0.0930843f,0.0918925f},{0.0836927f,-0.0908391f,0.0918925f},{0.0919114f,-0.0814392f,0.0918925f}, -{0.0908383f,-0.0836959f,0.0918925f},{0.0858213f,-0.089447f,0.0918925f},{0.0745764f,-0.0932205f,0.0918925f}, -{0.0894455f,-0.0858243f,0.0918925f},{0.0194438f,-0.0986812f,0.0918925f},{0.0213792f,-0.0969955f,0.0918925f}, -{0.0280757f,-0.0937839f,0.0918925f},{0.0257644f,-0.0945295f,0.0918925f},{-0.0583304f,-0.0794586f,0.0918925f}, -{-0.0235109f,-0.0956018f,0.0918925f},{-0.0326272f,-0.0932205f,0.0918925f},{-0.0152921f,-0.105002f,0.0918925f}, -{-0.0163653f,-0.102745f,0.0918925f},{0.0163644f,-0.102748f,0.0918925f},{-0.0177581f,-0.100617f,0.0918925f}, -{0.0177565f,-0.10062f,0.0918925f},{0.0141193f,-0.109622f,0.0918925f},{0.0152921f,-0.105002f,0.0918925f}, -{0.0139831f,-0.111865f,0.0918925f},{-0.0139831f,-0.111865f,0.0918925f},{0.00132352f,-0.255514f,0.0918925f}, -{0.0146388f,-0.25105f,0.0918925f},{0.0154693f,-0.254936f,0.0918925f},{-0.00996883f,-0.312677f,0.0918925f}, -{-0.0292956f,-0.324358f,0.0918925f},{-0.0187595f,-0.333514f,0.0918925f},{-0.00559549f,-0.338155f,0.0918925f}, -{-0.00835325f,-0.33763f,0.0918925f},{-0.0137123f,-0.335965f,0.0918925f},{-0.0110641f,-0.336898f,0.0918925f}, -{0.0121253f,-0.303559f,0.0918925f},{0.012073f,-0.302345f,0.0918925f},{-6.42929e-017f,-0.322729f,0.0918925f}, -{0.00186868f,-0.322648f,0.0918925f},{0.00996978f,-0.312674f,0.0918925f},{0.0057111f,-0.319917f,0.0918925f}, -{0.00553085f,-0.300454f,0.0918925f},{0.00534833f,-0.299637f,0.0918925f},{5.8201e-009f,-0.313407f,0.0918925f}, -{0.013923f,-0.311391f,0.0918925f},{0.01512f,-0.30713f,0.0918925f},{0.0122331f,-0.311031f,0.0918925f}, -{0.0131452f,-0.305747f,0.0918925f},{0.0140418f,-0.306569f,0.0918925f},{-0.0324249f,-0.319701f,0.0918925f}, -{-0.0337184f,-0.31721f,0.0918925f},{-0.0197119f,-0.306322f,0.0918925f},{-0.0186287f,-0.307f,0.0918925f}, -{-0.0152591f,-0.313229f,0.0918925f},{-0.0116591f,-0.311153f,0.0918925f},{-0.0111254f,-0.311391f,0.0918925f}, -{-0.0139213f,-0.31139f,0.0918925f},{-0.0122298f,-0.311032f,0.0918925f},{-0.0121253f,-0.299018f,0.0918925f}, -{-0.0124909f,-0.297858f,0.0918925f},{-0.00503626f,-0.298864f,0.0918925f},{-0.00186868f,-0.279929f,0.0918925f}, -{0.0102622f,-0.28712f,0.0918925f},{0.00584159f,-0.286169f,0.0918925f},{-0.0128153f,-0.285983f,0.0918925f}, -{-0.0097888f,-0.288183f,0.0918925f},{-0.0269304f,-0.275498f,0.0918925f},{-0.0147862f,-0.28712f,0.0918925f}, -{-0.0287942f,-0.277597f,0.0918925f},{-0.012073f,-0.300232f,0.0918925f},{-0.00553077f,-0.300455f,0.0918925f}, -{0.00279621f,-0.296444f,0.0918925f},{0.00343053f,-0.288798f,0.0918925f},{0.0211196f,-0.298295f,0.0918925f}, -{0.0213591f,-0.29942f,0.0918925f},{-0.00124497f,-0.295836f,0.0918925f},{-0.00204334f,-0.296082f,0.0918925f}, -{-5.8201e-009f,-0.28917f,0.0918925f},{0.00105623f,-0.289216f,0.0918925f},{0.00041711f,-0.295711f,0.0918925f}, -{-3.0178e-017f,-0.279848f,0.0918925f},{0.0122331f,-0.285983f,0.0918925f},{-0.0166349f,-0.258757f,0.0918925f}, -{-0.0154692f,-0.254935f,0.0918925f},{0.019928f,-0.266037f,0.0918925f},{-0.0146388f,-0.251049f,0.0918925f}, -{-0.0013304f,-0.255513f,0.0918925f},{0.016635f,-0.258757f,0.0918925f},{0.0141452f,-0.247144f,0.0918925f}, -{0.00112134f,-0.255125f,0.0918925f},{-0.000433147f,-0.254615f,0.0918925f},{-0.0139831f,-0.243259f,0.0918925f}, -{3.00981e-017f,-0.254546f,0.0918925f},{0.0139831f,-0.243259f,0.0918925f},{0.000431051f,-0.254614f,0.0918925f}, -{0.00132352f,-0.218226f,0.0918925f},{-0.0257644f,-0.0945295f,0.0918925f},{-0.0194438f,-0.0986812f,0.0918925f}, -{-0.0364172f,-0.08052f,0.0918925f},{-0.0365972f,-0.0799657f,0.0918925f},{-0.0368897f,-0.0794586f,0.0918925f}, -{-0.0956027f,-0.0235077f,0.0918925f},{-0.0969955f,-0.0213792f,0.0918925f},{-0.0632438f,-0.0238208f,0.0918925f}, -{-0.0945295f,0.0257644f,0.0918925f},{-0.0608844f,-0.0783204f,0.0918925f},{-0.0814392f,-0.0919114f,0.0918925f}, -{-0.0791278f,-0.092657f,0.0918925f},{-0.0768218f,-0.0930856f,0.0918925f},{-0.0614568f,-0.0784418f,0.0918925f}, -{-0.0591945f,-0.07868f,0.0918925f},{-0.0587207f,-0.0790251f,0.0918925f},{-0.0418875f,-0.0805185f,0.0918925f}, -{-0.0578579f,-0.08052f,0.0918925f},{-0.041707f,-0.0799633f,0.0918925f},{-0.0414146f,-0.0794574f,0.0918925f}, -{-0.0400161f,-0.0784418f,0.0918925f},{-0.0745764f,-0.0932205f,0.0918925f},{-0.0213822f,-0.0969939f,0.0918925f}, -{-0.0303842f,-0.0933567f,0.0918925f},{-0.0280785f,-0.0937848f,0.0918925f},{0.0833647f,-0.0794586f,0.0918925f}, -{0.0930856f,-0.0768218f,0.0918925f},{0.0836572f,-0.0799657f,0.0918925f},{0.0808108f,-0.0783204f,0.0918925f}, -{-0.0144962f,-0.0366018f,0.0918925f},{-0.0148999f,-0.0348554f,0.0918925f},{0.0148988f,-0.034856f,0.0918925f}, -{0.0145004f,-0.0366037f,0.0918925f},{0.0142141f,-0.0383731f,0.0918925f},{-0.0142116f,-0.0383722f,0.0918925f}, -{0.0167532f,-0.0298151f,0.0918925f},{-0.0167528f,-0.0298143f,0.0918925f},{0.0175821f,-0.0282257f,0.0918925f}, -{-0.0195369f,-0.0252221f,0.0918925f},{-0.0206547f,-0.0238204f,0.0918925f},{0.0206546f,-0.0238208f,0.0918925f}, -{0.0185115f,-0.0266927f,0.0918925f},{-0.0175819f,-0.028225f,0.0918925f},{-0.0185112f,-0.0266922f,0.0918925f}, -{0.0694022f,-0.0366018f,0.0918925f},{0.0696868f,-0.0383722f,0.0918925f},{-0.0392642f,-0.0141123f,0.0918925f}, -{-0.0410532f,-0.0139974f,0.0918925f},{0.0231475f,0.0626516f,0.0918925f},{0.0218598f,0.0614045f,0.0918925f}, -{0.0213822f,0.0969939f,0.0918925f},{0.0969939f,-0.0213822f,0.0918925f},{0.0632437f,-0.0238204f,0.0918925f}, -{0.0620385f,-0.0224931f,0.0918925f},{0.0516077f,-0.0157037f,0.0918925f},{0.0357259f,-0.0146844f,0.0918925f}, -{0.0339919f,-0.0151392f,0.0918925f},{-0.0218599f,-0.0224931f,0.0918925f},{0.0218598f,-0.0224939f,0.0918925f}, -{0.0290135f,-0.0171549f,0.0918925f},{0.0306287f,-0.016377f,0.0918925f},{0.0303842f,0.0933567f,0.0918925f}, -{0.0365982f,0.0822403f,0.0918925f},{0.0364177f,0.0816851f,0.0918925f},{0.0428452f,0.069901f,0.0918925f}, -{0.0410525f,0.069901f,0.0918925f},{-0.0290139f,0.0667443f,0.0918925f},{-0.0306291f,0.0675221f,0.0918925f}, -{-0.0418875f,0.0816851f,0.0918925f},{-0.0516079f,0.0681943f,0.0918925f},{-0.0428459f,0.069901f,0.0918925f}, -{-0.0410532f,0.069901f,0.0918925f},{-0.0392642f,0.0697861f,0.0918925f},{-0.0607509f,-0.0212468f,0.0918925f}, -{-0.0969939f,0.0213822f,0.0918925f},{-0.0620386f,-0.0224939f,0.0918925f},{-0.0643614f,-0.0252222f,0.0918925f}, -{-0.0653869f,-0.0266927f,0.0918925f},{-0.0945295f,-0.0257644f,0.0918925f},{-0.0678699f,-0.0314546f,0.0918925f}, -{-0.0933553f,-0.0303817f,0.0918925f},{-0.0684898f,-0.033137f,0.0918925f},{-0.0689996f,-0.034856f,0.0918925f}, -{-0.0696843f,-0.0383731f,0.0918925f},{-0.069398f,-0.0366037f,0.0918925f},{-0.0698582f,-0.0401574f,0.0918925f}, -{0.0140402f,-0.0401574f,0.0918925f},{-0.0140401f,-0.040157f,0.0918925f},{0.041888f,-0.08052f,0.0918925f}, -{0.0235077f,-0.0956027f,0.0918925f},{0.0368906f,-0.0794574f,0.0918925f},{0.0365982f,-0.0799633f,0.0918925f}, -{0.0364177f,-0.0805185f,0.0918925f},{0.037283f,-0.0790223f,0.0918925f},{0.0388615f,-0.0783204f,0.0918925f}, -{0.039447f,-0.078321f,0.0918925f},{0.0382891f,-0.0784418f,0.0918925f},{0.0377555f,-0.0786793f,0.0918925f}, -{0.041708f,-0.0799657f,0.0918925f},{0.0414155f,-0.0794586f,0.0918925f},{0.0405514f,-0.07868f,0.0918925f}, -{0.0400177f,-0.0784424f,0.0918925f},{0.0410252f,-0.0790251f,0.0918925f},{0.0326272f,-0.0932205f,0.0918925f}, -{0.0788398f,-0.0794574f,0.0918925f},{0.0785474f,-0.0799633f,0.0918925f},{0.0783669f,-0.0805185f,0.0918925f}, -{0.0797047f,-0.0786793f,0.0918925f},{0.0792323f,-0.0790223f,0.0918925f},{0.0813962f,-0.078321f,0.0918925f}, -{0.0829744f,-0.0790251f,0.0918925f},{0.0689986f,-0.0348554f,0.0918925f},{0.0671457f,-0.0298143f,0.0918925f}, -{0.0607507f,-0.021246f,0.0918925f},{0.048172f,0.0692143f,0.0918925f},{0.0464123f,0.069557f,0.0918925f}, -{0.0532694f,-0.0163764f,0.0918925f},{0.0593856f,-0.0200839f,0.0918925f},{0.0579489f,-0.0190117f,0.0918925f}, -{-0.0532697f,-0.016377f,0.0918925f},{-0.0548849f,-0.0171549f,0.0918925f},{0.0464123f,-0.0143415f,0.0918925f}, -{0.048172f,-0.0146841f,0.0918925f},{0.0499063f,-0.0151388f,0.0918925f},{0.0428452f,-0.0139974f,0.0918925f}, -{0.0446342f,-0.0141123f,0.0918925f},{0.0280785f,0.0937848f,0.0918925f},{0.0392635f,-0.0141124f,0.0918925f}, -{-0.0160313f,0.0524435f,0.0918925f},{0.0167532f,0.0540833f,0.0918925f},{0.0160285f,0.0524438f,0.0918925f}, -{0.0274515f,-0.0180347f,0.0918925f},{0.0322905f,-0.0157041f,0.0918925f},{-0.0140401f,0.0437414f,0.0918925f}, -{-0.0142116f,0.0455262f,0.0918925f},{0.0142141f,0.0455253f,0.0918925f},{0.0446342f,0.0697861f,0.0918925f}, -{0.037283f,0.0831813f,0.0918925f},{0.0326272f,0.0932205f,0.0918925f},{0.0377555f,0.0835243f,0.0918925f}, -{-0.0259495f,-0.0190117f,0.0918925f},{-0.0274519f,-0.0180338f,0.0918925f},{0.0374855f,0.0695568f,0.0918925f}, -{-0.0564469f,-0.0180347f,0.0918925f},{-0.0306291f,-0.0163764f,0.0918925f},{-0.0428459f,-0.0139975f,0.0918925f}, -{-0.0446349f,-0.0141124f,0.0918925f},{-0.0290139f,-0.0171541f,0.0918925f},{0.019537f,-0.0252222f,0.0918925f}, -{-0.0160313f,-0.0314549f,0.0918925f},{-0.0106515f,-0.311736f,0.0918925f},{0.0186287f,-0.295577f,0.0918925f}, -{0.00606332f,-0.318741f,0.0918925f},{0.00124367f,-0.295835f,0.0918925f},{0.00227064f,-0.289163f,0.0918925f}, -{0.0152596f,-0.288183f,0.0918925f},{0.0205661f,-0.297198f,0.0918925f},{0.0197119f,-0.296256f,0.0918925f}, -{0.0150796f,-0.287628f,0.0918925f},{0.024361f,-0.27258f,0.0918925f},{0.0143968f,-0.286688f,0.0918925f}, -{0.013923f,-0.286343f,0.0918925f},{-0.0046188f,-0.29814f,0.0918925f},{-0.0152591f,-0.288181f,0.0918925f}, -{-0.0304947f,-0.27983f,0.0918925f},{-0.0150786f,-0.287626f,0.0918925f},{-0.034526f,-0.287207f,0.0918925f}, -{-0.0354881f,-0.289845f,0.0918925f},{-0.0213591f,-0.303157f,0.0918925f},{-0.0372093f,-0.303697f,0.0918925f}, -{-0.0214407f,-0.301289f,0.0918925f},{-0.0211196f,-0.304282f,0.0918925f},{-0.0205661f,-0.305379f,0.0918925f}, -{-0.0357253f,-0.311971f,0.0918925f},{-0.0309479f,-0.322088f,0.0918925f},{-0.0255029f,-0.328493f,0.0918925f}, -{-0.00584159f,-0.316409f,0.0918925f},{-0.00280586f,-0.338471f,0.0918925f},{-0.0162821f,-0.334835f,0.0918925f}, -{0.005033f,-0.321f,0.0918925f},{0.0102622f,-0.312168f,0.0918925f},{0.00409024f,-0.321855f,0.0918925f}, -{0.00502626f,-0.298868f,0.0918925f},{0.0150796f,-0.312677f,0.0918925f},{0.319917f,0.0057111f,0.0918925f}, -{0.327844f,0.0261764f,0.0918925f},{0.316076f,0.0141674f,0.0918925f},{0.314678f,0.0151836f,0.0918925f}, -{0.323687f,0.0298108f,0.0918925f},{0.313522f,0.0153056f,0.0918925f},{0.291027f,0.0141674f,0.0918925f}, -{0.30713f,0.01512f,0.0918925f},{0.311551f,0.0141686f,0.0918925f},{0.289629f,0.0151836f,0.0918925f}, -{0.289059f,0.015305f,0.0918925f},{0.295577f,0.0186287f,0.0918925f},{0.288798f,0.00343053f,0.0918925f}, -{0.296252f,0.00242484f,0.0918925f},{0.295946f,0.00164777f,0.0918925f},{0.289163f,0.00227064f,0.0918925f}, -{0.311078f,0.0131075f,0.0918925f},{0.295758f,0.000833312f,0.0918925f},{0.289216f,0.00105623f,0.0918925f}, -{0.258757f,-0.0166349f,0.0918925f},{0.262471f,-0.0181265f,0.0918925f},{0.266037f,-0.0199275f,0.0918925f}, -{0.280169f,-0.00299304f,0.0918925f},{0.280722f,-0.00409024f,0.0918925f},{0.283836f,-0.00606332f,0.0918925f}, -{0.28621f,-0.0113857f,0.0918925f},{0.28266f,-0.0057111f,0.0918925f},{0.281577f,-0.005033f,0.0918925f}, -{0.307352f,-0.0174528f,0.0918925f},{0.282071f,-0.0319538f,0.0918925f},{0.297686f,-0.037113f,0.0918925f}, -{0.294948f,-0.0367442f,0.0918925f},{0.28449f,-0.0332889f,0.0918925f},{0.311551f,-0.0108798f,0.0918925f}, -{0.308686f,-0.0365475f,0.0918925f},{0.321418f,-0.0313882f,0.0918925f},{0.327834f,-0.0261674f,0.0918925f}, -{0.332963f,-0.0196768f,0.0918925f},{0.334333f,-0.0172772f,0.0918925f},{-0.0111254f,0.291186f,0.0918925f}, -{-0.0116591f,0.291424f,0.0918925f},{-0.0205661f,0.297198f,0.0918925f},{0.013923f,0.316235f,0.0918925f}, -{0.0255029f,0.328493f,0.0918925f},{0.0143968f,0.315889f,0.0918925f},{0.0233837f,0.330334f,0.0918925f}, -{0.0122331f,0.316594f,0.0918925f},{-0.0102613f,0.315456f,0.0918925f},{0.0102622f,0.315457f,0.0918925f}, -{0.00584159f,0.316409f,0.0918925f},{-0.0122298f,0.316594f,0.0918925f},{-0.0057111f,0.319917f,0.0918925f}, -{-0.0116591f,0.316472f,0.0918925f},{-0.005033f,0.321f,0.0918925f},{-0.0133877f,0.316473f,0.0918925f}, -{-0.0128153f,0.316594f,0.0918925f},{-0.0147862f,0.315457f,0.0918925f},{-0.01512f,0.30713f,0.0918925f}, -{-0.0147862f,0.290409f,0.0918925f},{-0.0152591f,0.289348f,0.0918925f},{-0.0186287f,0.295577f,0.0918925f}, -{-0.00105623f,0.289216f,0.0918925f},{-0.00227064f,0.289163f,0.0918925f},{0.0181265f,0.262471f,0.0918925f}, -{0.005033f,0.281577f,0.0918925f},{0.0057111f,0.28266f,0.0918925f},{0.0121253f,0.299018f,0.0918925f}, -{0.012073f,0.300232f,0.0918925f},{0.00502626f,0.303709f,0.0918925f},{0.0243605f,0.27258f,0.0918925f}, -{0.0304947f,0.27983f,0.0918925f},{0.0150796f,0.2899f,0.0918925f},{-0.303559f,-0.0121253f,0.0918925f}, -{-0.302345f,-0.012073f,0.0918925f},{-0.321855f,-0.00409024f,0.0918925f},{-0.295225f,-0.0174528f,0.0918925f}, -{-0.286892f,0.0146009f,0.0918925f},{-0.275498f,0.0269304f,0.0918925f},{-0.287899f,0.0151836f,0.0918925f}, -{-0.28847f,0.015305f,0.0918925f},{-0.282186f,0.0320225f,0.0918925f},{-0.289628f,0.0151842f,0.0918925f}, -{-0.290161f,0.0149467f,0.0918925f},{-0.289845f,0.0354881f,0.0918925f},{-0.291319f,0.0136627f,0.0918925f}, -{-0.295447f,0.01512f,0.0918925f},{-0.307352f,0.0174528f,0.0918925f},{-0.31194f,0.0146009f,0.0918925f}, -{-0.312414f,0.014946f,0.0918925f},{-0.298086f,0.0371496f,0.0918925f},{-0.301289f,0.0214407f,0.0918925f}, -{-0.30089f,0.0372859f,0.0918925f},{-0.303157f,0.0213591f,0.0918925f},{-0.303697f,0.0372093f,0.0918925f}, -{-0.304282f,0.0211196f,0.0918925f},{-0.324358f,0.0292956f,0.0918925f},{-0.31521f,0.0149467f,0.0918925f}, -{-0.330334f,0.0233837f,0.0918925f},{-0.316075f,0.0141686f,0.0918925f},{-0.333514f,0.0187595f,0.0918925f}, -{-0.316409f,0.00584159f,0.0918925f},{-0.296256f,-0.0197119f,0.0918925f},{-0.29942f,-0.0213591f,0.0918925f}, -{-0.298295f,-0.0211196f,0.0918925f},{-0.289216f,-0.00105623f,0.0918925f},{-0.289163f,-0.00227064f,0.0918925f}, -{-0.295758f,0.000834183f,0.0918925f},{-0.262471f,-0.0181266f,0.0918925f},{0.269418f,0.0220158f,0.0918925f}, -{0.290163f,-0.0101024f,0.0918925f},{0.288473f,-0.00974281f,0.0918925f},{0.287901f,-0.00986419f,0.0918925f}, -{0.301289f,-0.0121187f,0.0918925f},{0.287001f,0.0344436f,0.0918925f},{0.296256f,0.0197119f,0.0918925f}, -{0.28449f,0.0332908f,0.0918925f},{0.298295f,0.0211196f,0.0918925f},{0.292245f,0.036175f,0.0918925f}, -{0.294949f,0.0367459f,0.0918925f},{0.279758f,0.0304444f,0.0918925f},{0.282071f,0.0319552f,0.0918925f}, -{0.287901f,0.0151842f,0.0918925f},{0.286895f,0.0146037f,0.0918925f},{0.277563f,0.0287664f,0.0918925f}, -{0.287367f,0.0149467f,0.0918925f},{0.27258f,0.024361f,0.0918925f},{0.28621f,0.0136627f,0.0918925f}, -{0.286029f,0.0131075f,0.0918925f},{-0.0410221f,-0.0790223f,0.0918925f},{0.0802383f,-0.0784418f,0.0918925f}, -{0.0838372f,-0.08052f,0.0918925f},{0.092657f,-0.0791278f,0.0918925f},{0.0678671f,0.0524435f,0.0918925f}, -{0.0684765f,0.0507578f,0.0918925f},{0.0797047f,0.0835243f,0.0918925f},{0.0791278f,0.092657f,0.0918925f}, -{0.0802383f,0.0837618f,0.0918925f},{0.0694022f,0.0472966f,0.0918925f},{0.0689986f,0.0490431f,0.0918925f}, -{0.0516077f,0.0681947f,0.0918925f},{0.041888f,0.0816836f,0.0918925f},{0.0969955f,0.0213792f,0.0918925f}, -{0.0956027f,0.0235077f,0.0918925f},{0.0259491f,-0.0190126f,0.0918925f},{0.0813962f,0.0838826f,0.0918925f}, -{0.0768218f,0.0930856f,0.0918925f},{0.0745764f,0.0932205f,0.0918925f},{0.0792323f,0.0831813f,0.0918925f}, -{0.0785474f,0.0822403f,0.0918925f},{0.0788398f,0.0827462f,0.0918925f},{0.0709097f,0.0709097f,0.0918925f}, -{0.0783669f,0.0816851f,0.0918925f},{-0.0446349f,0.0697861f,0.0918925f},{-0.0932205f,0.0745764f,0.0918925f}, -{-0.0643614f,0.0586762f,0.0918925f},{-0.0653869f,0.0572057f,0.0918925f},{-0.0593859f,0.0638136f,0.0918925f}, -{-0.0620386f,0.0614045f,0.0918925f},{-0.0632438f,0.0600777f,0.0918925f},{-0.0464129f,0.0695568f,0.0918925f}, -{-0.0481725f,0.069214f,0.0918925f},{-0.0499065f,0.0687593f,0.0918925f},{-0.0819653f,0.0837618f,0.0918925f}, -{-0.0858213f,0.089447f,0.0918925f},{-0.0833638f,0.0827462f,0.0918925f},{-0.0257644f,0.0945295f,0.0918925f}, -{-0.0280757f,0.0937839f,0.0918925f},{-0.0364172f,0.0816836f,0.0918925f},{-0.0303817f,0.0933553f,0.0918925f}, -{0.0306287f,0.0675214f,0.0918925f},{-0.0235077f,0.0956027f,0.0918925f},{-0.0259495f,0.0648867f,0.0918925f}, -{-0.0365972f,0.0822379f,0.0918925f},{-0.0368897f,0.082745f,0.0918925f},{-0.0372799f,0.0831785f,0.0918925f}, -{-0.0382875f,0.0837612f,0.0918925f},{-0.0377538f,0.0835236f,0.0918925f},{-0.0400161f,0.0837618f,0.0918925f}, -{-0.0405497f,0.0835243f,0.0918925f},{-0.0414146f,0.0827462f,0.0918925f},{-0.0410221f,0.0831813f,0.0918925f}, -{-0.041707f,0.0822403f,0.0918925f},{0.0643615f,0.0586764f,0.0918925f},{0.0653872f,0.0572063f,0.0918925f}, -{0.0410252f,0.0831785f,0.0918925f},{0.0405514f,0.0835236f,0.0918925f},{0.0245125f,-0.0200848f,0.0918925f}, -{0.0231475f,-0.0212468f,0.0918925f},{0.0499063f,0.0687596f,0.0918925f},{0.0632437f,0.0600781f,0.0918925f}, -{0.0620385f,0.0614053f,0.0918925f},{0.0579489f,0.0648867f,0.0918925f},{0.0564465f,0.0658647f,0.0918925f}, -{0.0548845f,0.0667443f,0.0918925f},{0.041708f,0.0822379f,0.0918925f},{0.0414155f,0.082745f,0.0918925f}, -{0.0400177f,0.0837612f,0.0918925f},{0.0388615f,0.0838832f,0.0918925f},{0.039447f,0.0838826f,0.0918925f}, -{0.0382891f,0.0837618f,0.0918925f},{0.0368906f,0.0827462f,0.0918925f},{-0.0388582f,-0.078321f,0.0918925f}, -{-0.0382875f,-0.0784424f,0.0918925f},{-0.0394436f,-0.0783204f,0.0918925f},{-0.0405497f,-0.0786793f,0.0918925f}, -{0.0303817f,-0.0933553f,0.0918925f},{-0.0499065f,-0.0151392f,0.0918925f},{0.0392635f,0.0697861f,0.0918925f}, -{-0.0357264f,-0.0146841f,0.0918925f},{-0.0374861f,-0.0143415f,0.0918925f},{-0.0231477f,-0.021246f,0.0918925f}, -{-0.0245128f,-0.0200839f,0.0918925f},{0.0374855f,-0.0143416f,0.0918925f},{0.0410525f,-0.0139975f,0.0918925f}, -{0.0945295f,0.0257644f,0.0918925f},{0.0937839f,0.0280757f,0.0918925f},{0.0933553f,0.0303817f,0.0918925f}, -{0.0671457f,0.0540841f,0.0918925f},{0.0663166f,0.0556734f,0.0918925f},{0.0532694f,0.0675221f,0.0918925f}, -{0.0593856f,0.0638145f,0.0918925f},{-0.0195369f,0.0586764f,0.0918925f},{0.019537f,0.0586762f,0.0918925f}, -{-0.0185112f,0.0572063f,0.0918925f},{0.0185115f,0.0572057f,0.0918925f},{-0.0154219f,0.0507578f,0.0918925f}, -{0.0154086f,0.0507615f,0.0918925f},{-0.0148999f,0.0490431f,0.0918925f},{0.0145004f,0.0472947f,0.0918925f}, -{-0.0144962f,0.0472966f,0.0918925f},{0.0148988f,0.0490425f,0.0918925f},{0.0140402f,0.043741f,0.0918925f}, -{-0.0671452f,0.0540833f,0.0918925f},{-0.0678699f,0.0524438f,0.0918925f},{-0.0481725f,-0.0146844f,0.0918925f}, -{-0.0274519f,0.0658647f,0.0918925f},{-0.0245128f,0.0638145f,0.0918925f},{-0.0213792f,0.0969955f,0.0918925f}, -{-0.0231477f,0.0626525f,0.0918925f},{-0.0218599f,0.0614053f,0.0918925f},{-0.0532697f,0.0675214f,0.0918925f}, -{-0.0548849f,0.0667435f,0.0918925f},{-0.0579493f,0.0648858f,0.0918925f},{-0.0607509f,0.0626516f,0.0918925f}, -{-0.0663164f,0.0556727f,0.0918925f},{-0.0684898f,0.0507615f,0.0918925f},{-0.0689996f,0.0490425f,0.0918925f}, -{-0.0696843f,0.0455253f,0.0918925f},{-0.069398f,0.0472947f,0.0918925f},{-0.0698582f,0.043741f,0.0918925f}, -{-0.21663f,0.00133028f,0.0918925f},{-0.217061f,0.00139831f,0.0918925f},{-0.218391f,0.000431293f,0.0918925f}, -{-0.218186f,0.000817561f,0.0918925f},{-0.21594f,0.000819718f,0.0918925f},{-0.215737f,0.000430548f,0.0918925f}, -{-0.216241f,0.00113282f,0.0918925f},{-0.217881f,0.00112774f,0.0918925f},{-0.217494f,0.00132937f,0.0918925f}, -{0.00112134f,-0.217837f,0.0918925f},{0.00082033f,-0.217524f,0.0918925f},{0.000431051f,-0.217326f,0.0918925f}, -{3.13209e-017f,-0.217258f,0.0918925f},{-0.000819963f,-0.217529f,0.0918925f},{-0.000433147f,-0.217327f,0.0918925f}, -{-0.0013304f,-0.218225f,0.0918925f},{-0.00112493f,-0.217839f,0.0918925f},{-0.000819963f,-0.254817f,0.0918925f}, -{-0.00112493f,-0.255127f,0.0918925f},{-0.0141453f,-0.247143f,0.0918925f},{0.00082033f,-0.254812f,0.0918925f}, -{0.0128186f,-0.285984f,0.0918925f},{0.0220158f,-0.269418f,0.0918925f},{0.0133893f,-0.286105f,0.0918925f}, -{-0.0181265f,-0.262471f,0.0918925f},{0.00445839f,-0.288143f,0.0918925f},{0.00528033f,-0.287247f,0.0918925f}, -{0.0181266f,-0.262471f,0.0918925f},{0.247143f,-0.0141453f,0.0918925f},{0.243259f,-0.0139831f,0.0918925f}, -{0.25415f,0.00132937f,0.0918925f},{0.253763f,0.00112774f,0.0918925f},{0.247144f,0.0141452f,0.0918925f}, -{0.253458f,0.000817561f,0.0918925f},{0.000431051f,0.219987f,0.0918925f},{0.0139831f,0.243259f,0.0918925f}, -{0.00082033f,0.219789f,0.0918925f},{0.00112134f,0.219476f,0.0918925f},{0.00132352f,0.219087f,0.0918925f}, -{2.65983e-017f,0.220055f,0.0918925f},{-0.000819963f,0.219784f,0.0918925f},{-0.000433147f,0.219986f,0.0918925f}, -{-0.0013304f,0.219088f,0.0918925f},{-0.00112493f,0.219474f,0.0918925f},{-0.0154693f,0.254936f,0.0918925f}, -{-0.000433147f,0.257274f,0.0918925f},{5.35539e-017f,0.279848f,0.0918925f},{-0.0220158f,0.269418f,0.0918925f}, -{-0.019928f,0.266037f,0.0918925f},{0.216628f,0.00132937f,0.0918925f},{0.216241f,0.00112774f,0.0918925f}, -{0.217881f,0.00113282f,0.0918925f},{0.218182f,0.000819718f,0.0918925f},{0.217061f,0.00139831f,0.0918925f}, -{0.217492f,0.00133028f,0.0918925f},{0.215936f,0.000817561f,0.0918925f},{0.215731f,0.000431293f,0.0918925f}, -{-0.255403f,0.00112774f,0.0918925f},{-0.286029f,-0.0119424f,0.0918925f},{-0.286209f,-0.0113881f,0.0918925f}, -{-0.27258f,-0.024361f,0.0918925f},{-0.269418f,-0.0220158f,0.0918925f},{-0.266037f,-0.019928f,0.0918925f}, -{0.0111271f,-0.31139f,0.0918925f},{0.0106546f,-0.311733f,0.0918925f},{0.00299304f,-0.322408f,0.0918925f}, -{0.0147871f,-0.312169f,0.0918925f},{0.0143968f,-0.311736f,0.0918925f},{0.0174528f,-0.295225f,0.0918925f}, -{0.0124909f,-0.304719f,0.0918925f},{0.00978928f,-0.313229f,0.0918925f},{0.00204265f,-0.296082f,0.0918925f}, -{-0.000418664f,-0.295711f,0.0918925f},{0.00461423f,-0.29814f,0.0918925f},{0.0116607f,-0.311153f,0.0918925f}, -{0.0147871f,-0.287121f,0.0918925f},{0.0116607f,-0.286104f,0.0918925f},{0.0111271f,-0.286342f,0.0918925f}, -{0.0106546f,-0.286685f,0.0918925f},{-0.0102613f,-0.287121f,0.0918925f},{-0.00409889f,-0.297485f,0.0918925f}, -{-0.0106515f,-0.286688f,0.0918925f},{-0.0111254f,-0.286343f,0.0918925f},{-0.00606332f,-0.283836f,0.0918925f}, -{-0.0243605f,-0.27258f,0.0918925f},{-0.0139213f,-0.286342f,0.0918925f},{-0.0143937f,-0.286685f,0.0918925f}, -{-0.0368031f,-0.2953f,0.0918925f},{-0.0371496f,-0.298086f,0.0918925f},{-0.01512f,-0.295447f,0.0918925f}, -{-0.0150786f,-0.312674f,0.0918925f},{-0.0174528f,-0.307352f,0.0918925f},{-0.0147862f,-0.312168f,0.0918925f}, -{-0.0128153f,-0.311031f,0.0918925f},{-0.00534277f,-0.299641f,0.0918925f},{-0.00348695f,-0.296916f,0.0918925f}, -{0.00978928f,-0.288181f,0.0918925f},{-0.002796f,-0.296445f,0.0918925f},{-0.0116591f,-0.286105f,0.0918925f}, -{0.00996978f,-0.287626f,0.0918925f},{-0.00299304f,-0.280169f,0.0918925f},{-0.0133877f,-0.286104f,0.0918925f}, -{-0.0220151f,-0.269417f,0.0918925f},{-0.0199275f,-0.266037f,0.0918925f},{-0.00528033f,-0.31533f,0.0918925f}, -{-0.0097888f,-0.313231f,0.0918925f},{-0.00445839f,-0.314434f,0.0918925f},{-0.0133877f,-0.311153f,0.0918925f}, -{-0.0143937f,-0.311733f,0.0918925f},{-0.0372859f,-0.30089f,0.0918925f},{-0.0369213f,-0.306489f,0.0918925f}, -{-0.036428f,-0.309253f,0.0918925f},{-0.0348205f,-0.314628f,0.0918925f},{0.312416f,-0.0101017f,0.0918925f}, -{0.311943f,-0.0104447f,0.0918925f},{0.305379f,-0.0205661f,0.0918925f},{0.311371f,-0.0358991f,0.0918925f}, -{0.300444f,-0.0372784f,0.0918925f},{0.314002f,-0.035054f,0.0918925f},{0.33733f,-0.00956509f,0.0918925f}, -{0.335522f,-0.0147828f,0.0918925f},{0.336523f,-0.0122076f,0.0918925f},{0.315212f,-0.0101024f,0.0918925f}, -{0.316409f,-0.00584159f,0.0918925f},{0.337939f,-0.00686983f,0.0918925f},{0.313779f,-0.00343053f,0.0918925f}, -{0.311078f,-0.0119409f,0.0918925f},{0.287001f,-0.0344412f,0.0918925f},{0.28959f,-0.035405f,0.0918925f}, -{0.296008f,-0.0140418f,0.0918925f},{0.2915f,-0.0119424f,0.0918925f},{0.29683f,-0.0131452f,0.0918925f}, -{0.300232f,-0.012073f,0.0918925f},{0.299018f,-0.0121253f,0.0918925f},{0.286502f,-0.0108798f,0.0918925f}, -{0.286029f,-0.0119409f,0.0918925f},{0.300445f,0.0372813f,0.0918925f},{0.303207f,0.0372145f,0.0918925f}, -{0.286169f,0.00584159f,0.0918925f},{0.297687f,0.0371146f,0.0918925f},{0.29942f,0.0213591f,0.0918925f}, -{0.30596f,0.0369944f,0.0918925f},{0.298493f,0.00484368f,0.0918925f},{0.290637f,0.0146009f,0.0918925f}, -{0.2915f,0.013106f,0.0918925f},{0.308687f,0.036547f,0.0918925f},{0.289591f,0.0354067f,0.0918925f}, -{0.297198f,0.0205661f,0.0918925f},{0.288473f,0.0153056f,0.0918925f},{0.275498f,0.0269304f,0.0918925f}, -{0.286502f,0.0141686f,0.0918925f},{0.303331f,0.00520701f,0.0918925f},{0.305903f,0.00314864f,0.0918925f}, -{0.318741f,0.00606332f,0.0918925f},{0.337328f,0.00956357f,0.0918925f},{0.312416f,0.0149467f,0.0918925f}, -{0.312949f,0.0151842f,0.0918925f},{0.311943f,0.0146037f,0.0918925f},{0.311372f,0.035899f,0.0918925f}, -{0.311258f,0.0136627f,0.0918925f},{0.295225f,0.0174528f,0.0918925f},{0.290163f,0.014946f,0.0918925f}, -{5.8201e-009f,0.28917f,0.0918925f},{-0.00996883f,0.2899f,0.0918925f},{-0.00528033f,0.287247f,0.0918925f}, -{-0.0097888f,0.289346f,0.0918925f},{-0.00445839f,0.288143f,0.0918925f},{-0.00584159f,0.286169f,0.0918925f}, -{-0.0128153f,0.291546f,0.0918925f},{-0.0140418f,0.306569f,0.0918925f},{-0.0211196f,0.298295f,0.0918925f}, -{-0.0197119f,0.296256f,0.0918925f},{-0.0143937f,0.315892f,0.0918925f},{-0.0139213f,0.316235f,0.0918925f}, -{-0.0150786f,0.289903f,0.0918925f},{-0.0174528f,0.295225f,0.0918925f},{-0.00534277f,0.302936f,0.0918925f}, -{0.00996978f,0.314951f,0.0918925f},{0.00978928f,0.314396f,0.0918925f},{0.00445839f,0.314434f,0.0918925f}, -{0.00528033f,0.31533f,0.0918925f},{-0.0106515f,0.315889f,0.0918925f},{-0.0097888f,0.314395f,0.0918925f}, -{0.0116607f,0.316473f,0.0918925f},{0.0111271f,0.316235f,0.0918925f},{0.0137123f,0.335965f,0.0918925f}, -{0.0110641f,0.336898f,0.0918925f},{-0.00299304f,0.322408f,0.0918925f},{0.0102622f,0.290409f,0.0918925f}, -{0.0111271f,0.291187f,0.0918925f},{0.0106546f,0.290844f,0.0918925f},{0.0199275f,0.266037f,0.0918925f}, -{0.0147871f,0.290408f,0.0918925f},{0.0143968f,0.290841f,0.0918925f},{0.0354881f,0.289845f,0.0918925f}, -{0.0174528f,0.307352f,0.0918925f},{0.0368031f,0.2953f,0.0918925f},{0.0124909f,0.297858f,0.0918925f}, -{0.00978928f,0.289348f,0.0918925f},{0.00204265f,0.306496f,0.0918925f},{0.0150796f,0.314949f,0.0918925f}, -{0.00461423f,0.304437f,0.0918925f},{0.0116607f,0.291424f,0.0918925f},{0.0205661f,0.305379f,0.0918925f}, -{0.0357253f,0.311971f,0.0918925f},{0.0337184f,0.31721f,0.0918925f},{0.0197119f,0.306322f,0.0918925f}, -{0.0211319f,0.332012f,0.0918925f},{0.0162821f,0.334835f,0.0918925f},{0.00835325f,0.33763f,0.0918925f}, -{0.00559549f,0.338155f,0.0918925f},{-0.00606332f,0.318741f,0.0918925f},{-0.0111254f,0.316235f,0.0918925f}, -{-0.290161f,-0.0101017f,0.0918925f},{-0.290634f,-0.0104447f,0.0918925f},{-0.297198f,-0.0205661f,0.0918925f}, -{-0.286501f,-0.010881f,0.0918925f},{-0.289628f,-0.00986419f,0.0918925f},{-0.288143f,-0.00445839f,0.0918925f}, -{-0.289055f,-0.00974281f,0.0918925f},{-0.286892f,-0.0104475f,0.0918925f},{-0.283836f,0.00606332f,0.0918925f}, -{-0.286029f,0.013106f,0.0918925f},{-0.288798f,-0.00343053f,0.0918925f},{-0.291499f,-0.0119409f,0.0918925f}, -{-0.299246f,0.00520701f,0.0918925f},{-0.269417f,0.0220151f,0.0918925f},{-0.296674f,0.00314864f,0.0918925f}, -{-0.287247f,-0.00528033f,0.0918925f},{-0.286169f,-0.00584159f,0.0918925f},{-0.28847f,-0.0097434f,0.0918925f}, -{-0.290634f,0.0146037f,0.0918925f},{-0.291026f,0.0141686f,0.0918925f},{-0.305387f,0.00380369f,0.0918925f}, -{-0.328493f,0.0255029f,0.0918925f},{-0.326484f,0.0274641f,0.0918925f},{-0.315682f,0.0146037f,0.0918925f}, -{-0.338471f,0.00280586f,0.0918925f},{-0.338155f,0.00559549f,0.0918925f},{-0.33763f,0.00835325f,0.0918925f}, -{-0.314434f,0.00445839f,0.0918925f},{-0.314104f,-0.00974281f,0.0918925f},{-0.306631f,0.00164777f,0.0918925f}, -{-0.304776f,0.0043727f,0.0918925f},{-0.29683f,0.0131452f,0.0918925f},{-0.31155f,0.0141674f,0.0918925f}, -{-0.304085f,0.00484368f,0.0918925f},{-0.306489f,0.0369213f,0.0918925f},{-0.309253f,0.036428f,0.0918925f}, -{-0.31721f,0.0337184f,0.0918925f},{-0.322088f,0.0309479f,0.0918925f},{-0.301289f,-0.0121187f,0.0918925f}, -{-0.306569f,-0.0140418f,0.0918925f},{-0.311077f,-0.0119424f,0.0918925f},{-0.305747f,-0.0131452f,0.0918925f}, -{-0.314676f,-0.00986419f,0.0918925f},{-0.315682f,-0.0104447f,0.0918925f},{-0.31533f,0.00528033f,0.0918925f}, -{-0.322408f,-0.00299304f,0.0918925f},{-0.321f,-0.005033f,0.0918925f},{0.314107f,-0.0097434f,0.0918925f}, -{0.313407f,5.8201e-009f,0.0918925f},{0.314678f,-0.00986481f,0.0918925f},{0.29132f,0.0136603f,0.0918925f}, -{0.316563f,0.0340163f,0.0918925f},{0.00409024f,0.280722f,0.0918925f},{-0.287366f,-0.0101024f,0.0918925f}, -{-0.28917f,5.8201e-009f,0.0918925f},{-0.287899f,-0.00986481f,0.0918925f},{-0.00409024f,-0.280722f,0.0918925f}, -{-0.00996883f,-0.287628f,0.0918925f},{0.0128186f,0.291545f,0.0918925f},{0.0348205f,0.314628f,0.0918925f}, -{0.0121187f,0.301289f,0.0918925f},{0.0133893f,0.291424f,0.0918925f},{-0.311257f,0.0136603f,0.0918925f}, -{-0.0121187f,-0.301289f,0.0918925f},{-0.00996883f,0.314949f,0.0918925f},{-0.313407f,-5.8201e-009f,0.0918925f}, -{-0.0121187f,0.301289f,0.0918925f},{0.0128186f,-0.311032f,0.0918925f},{0.0121187f,-0.301289f,0.0918925f}, -{0.0133893f,-0.311153f,0.0918925f},{0.0607507f,0.0626525f,0.0918925f} -}; -static GLfloat normals [22155][3] = { -{0.999998f,0.00196876f,-9.24455e-016f},{0.965341f,-0.260991f,9.65861e-017f},{0.964306f,0.26479f,-7.4874e-016f}, -{0.865368f,0.501136f,0.0f},{0.867335f,-0.497725f,0.0f},{0.506909f,-0.862f,-5.55448e-015f}, -{0.258065f,-0.966128f,2.28729e-015f},{0.718867f,-0.695147f,-9.80072e-016f},{0.873911f,-0.486086f,0.0f}, -{0.258065f,-0.966128f,-3.05132e-015f},{7.00858e-015f,-1.0f,0.0f},{1.40172e-014f,-1.0f,0.0f}, -{0.999712f,-0.0239869f,-3.77413e-016f},{0.956928f,-0.290324f,-1.0624e-015f},{0.969751f,0.244096f,7.01312e-016f}, -{0.873911f,0.486086f,0.0f},{0.849592f,-0.52744f,0.0f},{0.499432f,-0.866353f,8.15683e-015f}, -{0.254108f,-0.967176f,-5.91491e-015f},{0.709621f,-0.704584f,7.54622e-015f},{0.865368f,-0.501136f,0.0f}, -{0.0f,-1.0f,0.0f},{1.18424e-015f,1.0f,1.4803e-015f},{0.194654f,0.980872f,-4.34694e-015f}, -{-1.18424e-015f,1.0f,1.4803e-015f},{-0.384009f,0.923329f,-2.06797e-015f},{-0.382179f,0.924088f,-2.06073e-015f}, -{-0.196168f,0.98057f,-1.46061e-015f},{-0.194653f,0.980872f,-5.09094e-015f},{-0.555293f,0.831655f,2.44935e-015f}, -{-0.707075f,0.707139f,2.06083e-015f},{-0.707765f,0.706447f,-1.38061e-015f},{-0.831545f,0.555458f,-3.09244e-016f}, -{-0.831851f,0.554999f,-1.04211e-015f},{-0.556611f,0.830773f,-3.07448e-016f},{-1.0f,-1.4803e-016f,0.0f}, -{-0.980825f,0.19489f,6.04239e-016f},{-0.98085f,0.194766f,-2.58442e-016f},{-0.924075f,0.382212f,1.80893e-016f}, -{-0.923954f,0.382504f,2.12633e-015f},{-1.0f,-1.66533e-016f,0.0f},{0.196168f,0.98057f,-1.81492e-017f}, -{0.382179f,0.924088f,2.66513e-015f},{0.384009f,0.923329f,-2.7336e-015f},{0.556611f,0.830773f,4.91917e-015f}, -{0.555293f,0.831655f,-5.13749e-017f},{0.707766f,0.706447f,-2.0915e-015f},{0.707075f,0.707139f,0.0f}, -{0.831545f,0.555458f,1.64449e-015f},{0.831851f,0.554999f,3.13233e-015f},{0.924075f,0.382212f,2.26315e-015f}, -{0.923954f,0.382504f,2.09391e-015f},{0.98085f,0.194766f,1.81494e-016f},{0.980825f,0.19489f,0.0f}, -{1.0f,7.40149e-017f,0.0f},{0.194654f,0.980872f,-5.22038e-015f},{-0.384009f,0.923329f,-2.90287e-015f}, -{-0.382179f,0.924088f,-2.05189e-015f},{-0.196168f,0.98057f,-1.16115e-015f},{-0.194653f,0.980872f,-5.08194e-015f}, -{-0.555293f,0.831655f,2.46219e-015f},{-0.707075f,0.707139f,1.9627e-015f},{-0.707765f,0.706447f,-1.17598e-015f}, -{-0.831545f,0.555458f,4.25627e-015f},{-0.831851f,0.554999f,-1.00122e-015f},{-0.556611f,0.830773f,1.04527e-016f}, -{-1.0f,2.36848e-015f,0.0f},{-0.980825f,0.19489f,-1.05575e-015f},{-0.98085f,0.194766f,-2.81743e-015f}, -{-0.924075f,0.382212f,4.08156e-015f},{-0.923954f,0.382504f,5.81678e-015f},{0.196168f,0.98057f,0.0f}, -{0.382179f,0.924088f,3.86733e-015f},{0.556611f,0.830773f,3.27127e-015f},{0.555293f,0.831655f,1.644e-015f}, -{0.707075f,0.707139f,2.09336e-015f},{0.831545f,0.555458f,4.10635e-015f},{0.831851f,0.554999f,5.74903e-015f}, -{0.923954f,0.382504f,7.73578e-015f},{0.98085f,0.194766f,0.0f},{0.980825f,0.19489f,-5.80765e-015f}, -{1.0f,1.4803e-016f,0.0f},{1.0f,0.0f,0.0f},{2.36848e-015f,1.0f,2.96059e-015f}, -{0.194654f,0.980872f,-2.90396e-015f},{-2.36848e-015f,1.0f,2.96059e-015f},{-0.384009f,0.923329f,6.90506e-015f}, -{-0.382179f,0.924088f,1.3856e-015f},{-0.196168f,0.98057f,2.91215e-015f},{-0.194653f,0.980872f,-1.46099e-015f}, -{-0.555293f,0.831655f,-9.90657e-015f},{-0.707075f,0.707139f,4.01536e-015f},{-0.707765f,0.706447f,-3.98705e-015f}, -{-0.831545f,0.555458f,-4.559e-015f},{-0.831851f,0.554999f,-1.44976e-015f},{-0.556611f,0.830773f,1.79963e-015f}, -{-1.0f,-7.40149e-017f,0.0f},{-0.980825f,0.19489f,-6.37078e-016f},{-0.98085f,0.194766f,4.68159e-016f}, -{-0.924075f,0.382212f,-2.81417e-015f},{-0.923954f,0.382504f,2.58471e-015f},{-1.0f,-8.32667e-017f,0.0f}, -{0.196168f,0.98057f,9.0746e-018f},{0.382179f,0.924088f,-5.43634e-015f},{0.384009f,0.923329f,0.0f}, -{0.556611f,0.830773f,9.78684e-015f},{0.555293f,0.831655f,0.0f},{0.707766f,0.706447f,-4.11753e-015f}, -{0.707075f,0.707139f,-4.1871e-015f},{0.831545f,0.555458f,9.86691e-015f},{0.831851f,0.554999f,-3.13233e-015f}, -{0.924075f,0.382212f,0.0f},{0.923954f,0.382504f,1.70966e-016f},{0.98085f,0.194766f,-1.81494e-016f}, -{0.980825f,0.19489f,-1.81489e-016f},{0.194654f,0.980872f,-2.03953e-015f},{-0.384009f,0.923329f,6.83401e-015f}, -{-0.382179f,0.924088f,1.08506e-015f},{-0.196168f,0.98057f,2.61268e-015f},{-0.194653f,0.980872f,-1.45198e-015f}, -{-0.555293f,0.831655f,-1.12873e-014f},{-0.707075f,0.707139f,6.67295e-015f},{-0.707765f,0.706447f,-5.10024e-015f}, -{-0.831545f,0.555458f,-7.65076e-015f},{-0.831851f,0.554999f,2.55421e-016f},{-0.556611f,0.830773f,3.2866e-015f}, -{-1.0f,0.0f,0.0f},{-0.980825f,0.19489f,-4.16548e-015f},{-0.98085f,0.194766f,-4.00449e-015f}, -{-0.924075f,0.382212f,-2.98516e-015f},{-0.923954f,0.382504f,2.15596e-015f},{0.196168f,0.98057f,-1.16155e-015f}, -{0.382179f,0.924088f,-4.34023e-015f},{0.384009f,0.923329f,-1.1369e-015f},{0.556611f,0.830773f,8.19043e-015f}, -{0.707766f,0.706447f,-6.27842e-015f},{0.831545f,0.555458f,1.23288e-014f},{0.831851f,0.554999f,-5.74903e-015f}, -{0.924075f,0.382212f,5.47162e-015f},{0.923954f,0.382504f,0.0f},{1.0f,-2.36848e-015f,0.0f}, -{-1.11022e-016f,1.0f,-2.46519e-030f},{0.194654f,0.980872f,9.51248e-016f},{-8.55798e-017f,1.0f,-2.50285e-030f}, -{-0.384009f,0.923329f,2.80418e-017f},{-0.382179f,0.924088f,-4.08548e-016f},{-0.196168f,0.98057f,-4.24234e-016f}, -{-0.194653f,0.980872f,-2.57762e-017f},{-0.555293f,0.831655f,-1.38085e-015f},{-0.707075f,0.707139f,2.68038e-015f}, -{-0.707765f,0.706447f,-1.1513e-015f},{-0.831545f,0.555458f,-3.26839e-015f},{-0.831851f,0.554999f,1.655e-015f}, -{-0.556611f,0.830773f,1.3746e-015f},{-0.980825f,0.19489f,-3.69749e-015f},{-0.98085f,0.194766f,-4.67541e-015f}, -{-0.924075f,0.382212f,-4.42657e-017f},{-0.923954f,0.382504f,-4.39043e-016f},{0.196168f,0.98057f,-1.23359e-015f}, -{0.382179f,0.924088f,1.04983e-015f},{0.384009f,0.923329f,-1.10337e-015f},{0.556611f,0.830773f,-1.58124e-015f}, -{0.555293f,0.831655f,1.76503e-015f},{0.707766f,0.706447f,-2.16446e-015f},{0.707075f,0.707139f,-1.46822e-016f}, -{0.831545f,0.555458f,2.45291e-015f},{0.831851f,0.554999f,-2.41485e-015f},{0.924075f,0.382212f,5.47867e-015f}, -{0.923954f,0.382504f,-1.28171e-017f},{0.98085f,0.194766f,-4.03904e-018f},{0.980825f,0.19489f,-5.81213e-015f}, -{-3.70074e-017f,1.0f,-1.71194e-033f},{0.194654f,0.980872f,9.00454e-018f},{-4.16334e-017f,1.0f,-1.92593e-033f}, -{-0.384009f,0.923329f,-1.03189e-016f},{-0.382179f,0.924088f,-9.4335e-017f},{-0.196168f,0.98057f,-9.07461e-018f}, -{-0.194653f,0.980872f,-9.97534e-017f},{-0.555293f,0.831655f,-8.97873e-017f},{-0.707075f,0.707139f,-8.87483e-021f}, -{-0.707765f,0.706447f,5.72963e-017f},{-0.831545f,0.555458f,6.3335e-017f},{-0.831851f,0.554999f,-1.05011e-016f}, -{-0.556611f,0.830773f,-3.8431e-017f},{-0.980825f,0.19489f,1.298e-016f},{-0.98085f,0.194766f,8.73054e-017f}, -{-0.924075f,0.382212f,4.8286e-017f},{-0.923954f,0.382504f,-4.12339e-017f},{0.196168f,0.98057f,7.25718e-017f}, -{0.382179f,0.924088f,1.47781e-017f},{0.556611f,0.830773f,-7.6862e-017f},{0.707766f,0.706447f,0.0f}, -{0.707075f,0.707139f,-6.54235e-017f},{0.831545f,0.555458f,0.0f},{0.831851f,0.554999f,-1.53923e-016f}, -{0.923954f,0.382504f,-1.53271e-016f},{0.961369f,-0.275264f,-5.33819e-015f},{0.939639f,-0.342168f,2.53256e-016f}, -{0.978324f,-0.207082f,-3.06688e-015f},{0.990413f,-0.138135f,5.26556e-015f},{0.997621f,-0.068939f,2.88059e-015f}, -{1.0f,-8.02768e-016f,0.0f},{0.913294f,-0.4073f,-1.80878e-015f},{0.882564f,-0.470193f,-2.7841e-015f}, -{0.847736f,-0.530418f,0.0f},{0.809153f,-0.587599f,0.0f},{-0.0920911f,-0.995751f,0.0f}, -{-0.0918041f,-0.995777f,0.0f},{0.0605578f,-0.998165f,0.0f},{-0.241953f,-0.970288f,0.0f}, -{-0.242471f,-0.970159f,0.0f},{-0.387096f,-0.92204f,0.0f},{-0.386523f,-0.92228f,0.0f}, -{-0.522668f,-0.852537f,0.0f},{-0.522154f,-0.852851f,0.0f},{-0.645678f,-0.76361f,0.0f}, -{-0.646072f,-0.763276f,0.0f},{-0.754469f,-0.656336f,0.0f},{-0.754213f,-0.65663f,0.0f}, -{-0.84535f,-0.534213f,0.0f},{-0.845231f,-0.5344f,0.0f},{-0.916608f,-0.399787f,0.0f}, -{0.0602701f,-0.998182f,0.0f},{0.211672f,-0.977341f,0.0f},{0.21115f,-0.977454f,0.0f}, -{0.357746f,-0.933819f,0.0f},{0.357166f,-0.934041f,0.0f},{0.494924f,-0.868936f,0.0f}, -{0.495448f,-0.868638f,0.0f},{0.621613f,-0.783324f,0.0f},{0.621208f,-0.783646f,0.0f}, -{0.733337f,-0.679865f,0.0f},{0.733072f,-0.680151f,0.0f},{0.82791f,-0.560861f,0.0f}, -{0.828034f,-0.560677f,0.0f},{0.903508f,-0.428571f,0.0f},{-0.657856f,-0.753144f,0.0f}, -{-0.520449f,-0.853893f,0.0f},{-0.657957f,-0.753056f,0.0f},{-0.776263f,-0.63041f,0.0f}, -{-0.776125f,-0.630579f,0.0f},{-0.872027f,-0.489458f,0.0f},{-0.871886f,-0.489709f,0.0f}, -{-0.942365f,-0.334588f,0.0f},{-0.942433f,-0.334396f,0.0f},{-0.985518f,-0.169572f,0.0f}, -{-0.985476f,-0.169813f,0.0f},{-1.0f,6.88373e-017f,0.0f},{-0.520564f,-0.853823f,0.0f}, -{-0.367913f,-0.92986f,0.0f},{-0.368116f,-0.92978f,0.0f},{-0.204975f,-0.978767f,0.0f}, -{-0.204694f,-0.978826f,0.0f},{-0.0356397f,-0.999365f,0.0f},{-0.0358431f,-0.999357f,0.0f}, -{0.134513f,-0.990912f,0.0f},{0.13427f,-0.990945f,0.0f},{0.300596f,-0.953752f,0.0f}, -{-0.792435f,-0.609957f,0.0f},{-0.792259f,-0.610185f,0.0f},{-0.69035f,-0.723475f,0.0f}, -{-0.87573f,-0.482801f,0.0f},{-0.875988f,-0.482333f,0.0f},{-0.939116f,-0.343601f,0.0f}, -{-0.938902f,-0.344184f,0.0f},{-0.980413f,-0.196955f,0.0f},{-0.980294f,-0.197546f,0.0f}, -{-0.998928f,-0.0463011f,0.0f},{-0.998951f,-0.0457846f,0.0f},{-0.994322f,0.106415f,0.0f}, -{-0.994363f,0.106027f,0.0f},{-0.966649f,0.256106f,0.0f},{-0.966705f,0.255892f,0.0f}, -{-0.916608f,0.399787f,0.0f},{-0.690559f,-0.723276f,0.0f},{-0.57228f,-0.820058f,0.0f}, -{-0.572718f,-0.819753f,0.0f},{-0.441003f,-0.897506f,0.0f},{-0.44156f,-0.897232f,0.0f}, -{-0.300123f,-0.953901f,0.0f},{-0.299547f,-0.954081f,0.0f},{-0.151186f,-0.988505f,0.0f}, -{-0.151697f,-0.988427f,0.0f},{0.00064926f,-1.0f,0.0f},{0.000259834f,-1.0f,0.0f}, -{0.152209f,-0.988348f,0.0f},{0.152428f,-0.988315f,0.0f},{0.961369f,-0.275264f,1.42615e-015f}, -{0.939639f,-0.342168f,-2.66114e-015f},{0.978324f,-0.207082f,-4.59815e-016f},{0.990413f,-0.138135f,-2.85529e-015f}, -{0.997621f,-0.068939f,3.76161e-015f},{1.0f,-1.00346e-016f,0.0f},{0.913294f,-0.4073f,1.05976e-015f}, -{0.847736f,-0.530418f,2.5098e-015f},{-0.968457f,-0.249181f,0.0f},{-0.983089f,-0.183127f,0.0f}, -{-0.993204f,-0.116388f,0.0f},{-0.998778f,-0.0494258f,0.0f},{-0.99985f,0.0173044f,0.0f}, -{-0.99985f,0.0173044f,0.0f},{-0.949392f,-0.314094f,0.0f},{-0.926039f,-0.377427f,0.0f}, -{-0.898602f,-0.438764f,0.0f},{-0.867335f,-0.497725f,0.0f},{-0.959254f,-0.282544f,0.0f}, -{-0.976164f,-0.217036f,0.0f},{-0.988582f,-0.150687f,0.0f},{-0.996469f,-0.0839576f,0.0f}, -{-0.99985f,-0.0173044f,0.0f},{-0.99985f,-0.0173045f,0.0f},{-0.937954f,-0.346759f,0.0f}, -{-0.912424f,-0.409245f,0.0f},{-0.882881f,-0.469596f,0.0f},{-0.849592f,-0.52744f,0.0f}, -{-0.998778f,0.0494258f,0.0f},{-0.968457f,0.249181f,0.0f},{-0.983089f,0.183127f,0.0f}, -{-0.993204f,0.116388f,0.0f},{-0.926039f,0.377427f,0.0f},{-0.898602f,0.438764f,0.0f}, -{-0.949392f,0.314094f,0.0f},{-0.867335f,0.497725f,0.0f},{-0.867335f,0.497725f,0.0f}, -{0.0f,1.0f,0.0f},{0.999811f,0.0194669f,0.0f},{0.998538f,-0.0540524f,0.0f}, -{0.995686f,0.0927821f,0.0f},{0.986243f,0.165305f,0.0f},{0.986243f,0.165305f,0.0f}, -{0.971639f,0.236469f,0.0f},{0.971639f,0.236469f,0.0f},{0.952114f,0.305744f,0.0f}, -{0.927972f,0.372649f,0.0f},{0.927972f,0.372649f,0.0f},{0.899577f,0.436762f,0.0f}, -{0.867335f,0.497725f,0.0f},{0.998538f,-0.0540524f,0.0f},{0.99188f,-0.127181f,0.0f}, -{0.99188f,-0.127181f,0.0f},{0.979932f,-0.199334f,0.0f},{0.979932f,-0.199333f,0.0f}, -{0.962874f,-0.26995f,0.0f},{0.962874f,-0.269949f,0.0f},{0.940964f,-0.338508f,0.0f}, -{0.940964f,-0.338508f,0.0f},{0.914521f,-0.404537f,0.0f},{0.914521f,-0.404537f,0.0f}, -{0.883925f,-0.467629f,0.0f},{0.883925f,-0.467629f,0.0f},{0.849592f,-0.52744f,0.0f}, -{-0.996469f,0.0839576f,0.0f},{-0.959254f,0.282544f,0.0f},{-0.976164f,0.217036f,0.0f}, -{-0.988582f,0.150687f,0.0f},{-0.912424f,0.409245f,0.0f},{-0.882881f,0.469596f,0.0f}, -{-0.937954f,0.346759f,0.0f},{-0.849592f,0.52744f,0.0f},{-0.849592f,0.52744f,0.0f}, -{9.54098e-018f,1.0f,0.0f},{0.998538f,0.0540524f,0.0f},{0.999811f,-0.0194669f,0.0f}, -{0.99188f,0.127181f,0.0f},{0.979932f,0.199334f,0.0f},{0.979932f,0.199334f,0.0f}, -{0.962874f,0.26995f,0.0f},{0.962874f,0.269949f,0.0f},{0.940964f,0.338508f,0.0f}, -{0.940964f,0.338508f,0.0f},{0.914521f,0.404537f,0.0f},{0.883925f,0.467629f,0.0f}, -{0.849592f,0.52744f,0.0f},{0.999811f,-0.0194669f,0.0f},{0.995686f,-0.0927821f,0.0f}, -{0.995686f,-0.0927822f,0.0f},{0.986243f,-0.165305f,0.0f},{0.986243f,-0.165305f,0.0f}, -{0.971639f,-0.236469f,0.0f},{0.971639f,-0.236469f,0.0f},{0.952114f,-0.305744f,0.0f}, -{0.952114f,-0.305744f,0.0f},{0.927972f,-0.372649f,0.0f},{0.927972f,-0.372649f,0.0f}, -{0.899577f,-0.436762f,0.0f},{0.899577f,-0.436762f,0.0f},{0.867335f,-0.497725f,0.0f}, -{1.0f,9.53287e-016f,0.0f},{0.997621f,0.068939f,0.0f},{0.961369f,0.275264f,3.04084e-016f}, -{0.978324f,0.207082f,-2.28333e-015f},{0.990413f,0.138135f,-2.93221e-015f},{0.882564f,0.470193f,-5.05182e-015f}, -{0.913294f,0.4073f,-3.19261e-015f},{0.939639f,0.342168f,5.36697e-016f},{0.847736f,0.530418f,6.88954e-016f}, -{0.809153f,0.587599f,0.0f},{1.0f,8.02768e-016f,0.0f},{0.94476f,0.327762f,0.0f}, -{0.882975f,0.469421f,0.0f},{0.882376f,0.470545f,0.0f},{0.797544f,0.603261f,0.0f}, -{0.797239f,0.603663f,0.0f},{0.692511f,0.721407f,0.0f},{0.692894f,0.721039f,0.0f}, -{0.571027f,0.820932f,0.0f},{0.570592f,0.821233f,0.0f},{0.434522f,0.900661f,0.0f}, -{0.434952f,0.900454f,0.0f},{0.287641f,0.957738f,0.0f},{0.288064f,0.957611f,0.0f}, -{0.133924f,0.990992f,0.0f},{0.133632f,0.991031f,0.0f},{-0.0235175f,0.999723f,0.0f}, -{-0.0237111f,0.999719f,0.0f},{-0.180697f,0.983539f,0.0f},{-0.180207f,0.983629f,0.0f}, -{-0.332466f,0.943115f,0.0f},{-0.333066f,0.942903f,0.0f},{-0.477082f,0.878859f,0.0f}, -{-0.47651f,0.879169f,0.0f},{-0.609201f,0.793016f,0.0f},{-0.608742f,0.793368f,0.0f}, -{-0.725859f,0.687844f,0.0f},{-0.726169f,0.687517f,0.0f},{-0.825089f,0.565003f,0.0f}, -{-0.82494f,0.565221f,0.0f},{-0.903508f,0.428571f,0.0f},{0.945177f,0.326559f,0.0f}, -{0.984817f,0.173596f,0.0f},{0.984729f,0.174093f,0.0f},{0.99986f,0.0167358f,0.0f}, -{0.999851f,0.0172664f,0.0f},{0.990076f,-0.140534f,0.0f},{0.99015f,-0.140011f,0.0f}, -{0.955854f,-0.293842f,0.0f},{0.955714f,-0.294298f,0.0f},{0.897616f,-0.440778f,0.0f}, -{0.897811f,-0.440382f,0.0f},{0.817237f,-0.576301f,0.0f},{0.817407f,-0.57606f,0.0f}, -{0.716558f,-0.697528f,0.0f},{0.716693f,-0.697389f,0.0f},{0.598295f,-0.801276f,0.0f}, -{0.597896f,-0.801574f,0.0f},{0.464451f,-0.885599f,0.0f},{0.465014f,-0.885303f,0.0f}, -{0.32015f,-0.947367f,0.0f},{0.319533f,-0.947575f,0.0f},{0.166733f,-0.986002f,0.0f}, -{0.167304f,-0.985905f,0.0f},{0.00983556f,-0.999952f,0.0f},{0.0102859f,-0.999947f,0.0f}, -{-0.146993f,-0.989138f,0.0f},{-0.147254f,-0.989099f,0.0f},{-0.300595f,-0.953752f,0.0f}, -{-0.300596f,-0.953752f,0.0f},{-2.28983e-015f,1.0f,8.32667e-017f},{-2.28983e-015f,1.0f,0.0f}, -{-2.22045e-015f,1.0f,0.0f},{-2.22045e-015f,1.0f,8.32667e-017f},{-0.845231f,0.5344f,0.0f}, -{-0.522153f,0.852852f,0.0f},{-0.522668f,0.852537f,0.0f},{-0.645678f,0.76361f,0.0f}, -{-0.754213f,0.65663f,0.0f},{-0.646072f,0.763276f,0.0f},{-0.754469f,0.656336f,0.0f}, -{-0.0920911f,0.995751f,0.0f},{-0.241953f,0.970288f,0.0f},{-0.0918041f,0.995777f,0.0f}, -{-0.387096f,0.92204f,0.0f},{-0.386523f,0.92228f,0.0f},{-0.242471f,0.970159f,0.0f}, -{0.211672f,0.977341f,0.0f},{0.357746f,0.933819f,0.0f},{0.357166f,0.934041f,0.0f}, -{0.0605578f,0.998165f,0.0f},{0.21115f,0.977454f,0.0f},{0.0602701f,0.998182f,0.0f}, -{0.495448f,0.868638f,0.0f},{0.621613f,0.783324f,0.0f},{0.621208f,0.783646f,0.0f}, -{0.494924f,0.868936f,0.0f},{0.733072f,0.680151f,0.0f},{0.733337f,0.679865f,0.0f}, -{0.828034f,0.560677f,0.0f},{0.82791f,0.560861f,0.0f},{0.903508f,0.428571f,0.0f}, -{-0.84535f,0.534213f,0.0f},{-0.990276f,0.13912f,4.54011e-017f},{-0.997566f,0.0697293f,1.60177e-015f}, -{-0.997566f,0.0697342f,0.0f},{-1.0f,-2.07578e-015f,-1.4803e-015f},{-1.0f,-2.02806e-015f,-1.4803e-015f}, -{-0.990274f,0.139127f,-3.66475e-016f},{-0.978162f,0.207842f,5.24967e-016f},{-0.978164f,0.207833f,3.07655e-016f}, -{-0.939737f,0.341898f,-3.47773e-016f},{-0.961291f,0.275537f,6.37877e-016f},{-0.961289f,0.275544f,-1.52727e-015f}, -{-0.939735f,0.341905f,-2.37226e-015f},{-0.883033f,0.46931f,2.77887e-015f},{-0.913605f,0.406602f,-3.38102e-016f}, -{-0.883029f,0.469318f,3.10571e-015f},{-0.848158f,0.529743f,2.82283e-015f},{-0.913609f,0.406593f,-1.20376e-015f}, -{-0.848155f,0.529748f,3.45062e-015f},{-0.809153f,0.587599f,0.0f},{-0.997566f,-0.0697342f,-4.56646e-016f}, -{-0.997566f,-0.0697293f,-4.12881e-016f},{-0.990276f,-0.13912f,-3.60924e-017f},{-0.990274f,-0.139127f,-1.04149e-015f}, -{-0.978162f,-0.207842f,4.88599e-016f},{-0.978164f,-0.207833f,1.561e-015f},{-0.961289f,-0.275544f,-1.12821e-015f}, -{-0.961291f,-0.275536f,-1.92629e-015f},{-0.939737f,-0.341898f,-9.44673e-016f},{-0.939735f,-0.341905f,1.30061e-015f}, -{-0.913605f,-0.406602f,-9.66815e-016f},{-0.913609f,-0.406593f,3.57334e-015f},{-0.883029f,-0.469318f,8.53281e-016f}, -{-0.883033f,-0.46931f,1.45735e-015f},{-0.848158f,-0.529743f,7.38791e-015f},{-0.848155f,-0.529748f,-1.31471e-015f}, -{-0.809153f,-0.587599f,0.0f},{-0.985476f,0.169813f,0.0f},{-1.0f,1.78369e-011f,0.0f}, -{-0.776263f,0.630409f,0.0f},{-0.872027f,0.489458f,0.0f},{-0.776125f,0.630579f,0.0f}, -{-0.871886f,0.489709f,0.0f},{-0.942433f,0.334396f,0.0f},{-0.942365f,0.334588f,0.0f}, -{-0.520564f,0.853823f,0.0f},{-0.367913f,0.92986f,0.0f},{-0.368116f,0.92978f,0.0f}, -{-0.657856f,0.753144f,0.0f},{-0.520449f,0.853893f,0.0f},{-0.657957f,0.753056f,0.0f}, -{-0.204975f,0.978767f,0.0f},{-0.0356397f,0.999365f,0.0f},{-0.0358431f,0.999357f,0.0f}, -{-0.204694f,0.978826f,0.0f},{0.13427f,0.990945f,0.0f},{0.134513f,0.990912f,0.0f}, -{0.300596f,0.953752f,0.0f},{-0.985518f,0.169572f,0.0f},{-0.990276f,0.13912f,3.04173e-018f}, -{-0.997566f,0.0697293f,-7.25445e-016f},{-0.997566f,0.0697342f,-1.94658e-015f},{-1.0f,-8.49997e-016f,7.40149e-016f}, -{-1.0f,-8.58945e-016f,7.40149e-016f},{-0.990274f,0.139127f,9.99482e-016f},{-0.978162f,0.207842f,-1.31242e-016f}, -{-0.978164f,0.207833f,-7.23987e-016f},{-0.939737f,0.341898f,1.07513e-015f},{-0.961291f,0.275537f,4.9842e-017f}, -{-0.961289f,0.275544f,-1.06724e-015f},{-0.939735f,0.341905f,4.42483e-016f},{-0.883033f,0.46931f,-5.00468e-016f}, -{-0.913605f,0.406602f,-9.39994e-016f},{-0.883029f,0.469318f,-3.26786e-016f},{-0.848158f,0.529743f,-3.13882e-016f}, -{-0.913609f,0.406593f,1.31525e-015f},{-0.848155f,0.529748f,3.92093e-016f},{-0.997566f,-0.0697342f,-8.82967e-016f}, -{-0.997566f,-0.0697293f,-1.86325e-015f},{-0.990276f,-0.13912f,5.61064e-016f},{-0.990274f,-0.139127f,-7.12127e-016f}, -{-0.978162f,-0.207842f,1.37216e-015f},{-0.978164f,-0.207833f,7.76865e-016f},{-0.961289f,-0.275544f,-2.27402e-016f}, -{-0.961291f,-0.275536f,5.04744e-016f},{-0.939737f,-0.341898f,1.28058e-015f},{-0.939735f,-0.341905f,-4.46437e-016f}, -{-0.913605f,-0.406602f,-3.06567e-015f},{-0.913609f,-0.406593f,-3.10301e-016f},{-0.883029f,-0.469318f,2.3739e-015f}, -{-0.883033f,-0.46931f,-1.98045e-016f},{-0.848158f,-0.529743f,-1.16918e-015f},{-0.848155f,-0.529748f,-6.74661e-017f}, -{-0.966705f,-0.255892f,0.0f},{-0.980294f,0.197546f,0.0f},{-0.980413f,0.196955f,0.0f}, -{-0.998928f,0.0463011f,0.0f},{-0.994363f,-0.106027f,0.0f},{-0.998951f,0.0457847f,0.0f}, -{-0.994322f,-0.106415f,0.0f},{-0.792435f,0.609957f,0.0f},{-0.87573f,0.482801f,0.0f}, -{-0.792259f,0.610185f,0.0f},{-0.939116f,0.343601f,0.0f},{-0.938902f,0.344184f,0.0f}, -{-0.875988f,0.482333f,0.0f},{-0.57228f,0.820058f,0.0f},{-0.441003f,0.897506f,0.0f}, -{-0.44156f,0.897232f,0.0f},{-0.69035f,0.723475f,0.0f},{-0.572718f,0.819753f,0.0f}, -{-0.690559f,0.723276f,0.0f},{-0.299547f,0.954081f,0.0f},{-0.151186f,0.988505f,0.0f}, -{-0.151697f,0.988427f,0.0f},{-0.300122f,0.953901f,0.0f},{0.000259834f,1.0f,0.0f}, -{0.000649324f,1.0f,0.0f},{0.152428f,0.988315f,0.0f},{0.152209f,0.988348f,0.0f}, -{-0.966649f,-0.256106f,0.0f},{4.44835e-016f,-1.0f,0.0f},{4.44835e-016f,-1.0f,2.25528e-032f}, -{0.882975f,-0.469421f,0.0f},{0.94476f,-0.327762f,0.0f},{0.945177f,-0.326558f,0.0f}, -{0.984729f,-0.174093f,0.0f},{0.984817f,-0.173596f,0.0f},{0.99986f,-0.0167358f,0.0f}, -{0.999851f,-0.0172664f,0.0f},{0.99015f,0.140011f,0.0f},{0.990076f,0.140534f,0.0f}, -{0.955714f,0.294298f,0.0f},{0.955854f,0.293842f,0.0f},{0.897616f,0.440778f,0.0f}, -{0.897811f,0.440382f,0.0f},{0.817407f,0.57606f,0.0f},{0.817237f,0.576301f,0.0f}, -{0.716693f,0.697389f,0.0f},{0.716558f,0.697528f,0.0f},{0.597896f,0.801574f,0.0f}, -{0.598295f,0.801276f,0.0f},{0.465014f,0.885303f,0.0f},{0.464451f,0.885599f,0.0f}, -{0.319533f,0.947575f,0.0f},{0.32015f,0.947367f,0.0f},{0.166733f,0.986002f,0.0f}, -{0.167304f,0.985905f,0.0f},{0.0102858f,0.999947f,0.0f},{0.00983533f,0.999952f,0.0f}, -{-0.147254f,0.989099f,0.0f},{-0.146993f,0.989138f,0.0f},{-0.300596f,0.953752f,0.0f}, -{0.882376f,-0.470545f,0.0f},{0.797239f,-0.603663f,0.0f},{0.797544f,-0.603261f,0.0f}, -{0.692511f,-0.721407f,0.0f},{0.692894f,-0.721039f,0.0f},{0.570593f,-0.821233f,0.0f}, -{0.571027f,-0.820931f,0.0f},{0.434952f,-0.900454f,0.0f},{0.434522f,-0.900661f,0.0f}, -{0.287641f,-0.957738f,0.0f},{0.288064f,-0.957611f,0.0f},{0.133632f,-0.991031f,0.0f}, -{0.133924f,-0.990992f,0.0f},{-0.023711f,-0.999719f,0.0f},{-0.0235174f,-0.999723f,0.0f}, -{-0.180207f,-0.983629f,0.0f},{-0.180697f,-0.983539f,0.0f},{-0.333066f,-0.942903f,0.0f}, -{-0.332466f,-0.943115f,0.0f},{-0.47651f,-0.879169f,0.0f},{-0.477082f,-0.878859f,0.0f}, -{-0.609201f,-0.793016f,0.0f},{-0.608742f,-0.793368f,0.0f},{-0.726169f,-0.687517f,0.0f}, -{-0.725859f,-0.687844f,0.0f},{-0.82494f,-0.565221f,0.0f},{-0.825089f,-0.565003f,0.0f}, -{-0.903508f,-0.428572f,0.0f},{-0.903508f,-0.428571f,0.0f},{1.0f,4.36505e-015f,0.0f}, -{0.997621f,0.068939f,-5.80505e-015f},{0.961369f,0.275264f,2.84622e-015f},{0.961369f,0.275264f,-3.04084e-016f}, -{0.978324f,0.207082f,-2.58988e-015f},{0.990413f,0.138135f,-1.46611e-015f},{0.882564f,0.470193f,-4.24366e-015f}, -{0.913294f,0.4073f,5.21937e-015f},{0.939639f,0.342168f,-2.1809e-015f},{0.847736f,0.530418f,5.12961e-015f}, -{1.0f,4.01384e-015f,0.0f},{1.0f,-1.21154e-014f,0.0f},{1.0f,-1.32168e-014f,0.0f}, -{0.985476f,0.169813f,0.0f},{0.942365f,0.334588f,0.0f},{0.985518f,0.169572f,0.0f}, -{0.871886f,0.489709f,0.0f},{0.942433f,0.334396f,0.0f},{0.872027f,0.489458f,0.0f}, -{0.776125f,0.630579f,0.0f},{0.657856f,0.753144f,0.0f},{0.776263f,0.63041f,0.0f}, -{0.520449f,0.853893f,0.0f},{0.657957f,0.753055f,0.0f},{0.520564f,0.853823f,0.0f}, -{0.367913f,0.92986f,0.0f},{0.204694f,0.978826f,0.0f},{0.368116f,0.92978f,0.0f}, -{0.0356397f,0.999365f,0.0f},{0.204975f,0.978767f,0.0f},{0.0358431f,0.999357f,0.0f}, -{-0.134513f,0.990912f,0.0f},{-0.13427f,0.990945f,0.0f},{0.985476f,-0.169813f,0.0f}, -{0.985518f,-0.169572f,0.0f},{0.942365f,-0.334588f,0.0f},{0.871886f,-0.489709f,0.0f}, -{0.942433f,-0.334396f,0.0f},{0.776125f,-0.630579f,0.0f},{0.872027f,-0.489458f,0.0f}, -{0.776263f,-0.63041f,0.0f},{0.657856f,-0.753144f,0.0f},{0.520449f,-0.853893f,0.0f}, -{0.657957f,-0.753055f,0.0f},{0.367913f,-0.92986f,0.0f},{0.520564f,-0.853823f,0.0f}, -{0.368116f,-0.92978f,0.0f},{0.204694f,-0.978826f,0.0f},{0.0356397f,-0.999365f,0.0f}, -{0.204975f,-0.978767f,0.0f},{-0.134513f,-0.990912f,0.0f},{0.0358431f,-0.999357f,0.0f}, -{-0.13427f,-0.990945f,0.0f},{-0.300595f,-0.953752f,0.0f},{-4.44089e-016f,-1.0f,0.0f}, -{0.0f,0.0f,1.0f},{0.0f,-8.67362e-019f,1.0f},{0.0f,-1.73472e-018f,1.0f}, -{0.0f,1.73472e-018f,1.0f},{0.0f,0.0f,-1.0f},{-1.0f,-1.52656e-016f,0.0f}, -{-0.980825f,-0.19489f,1.45281e-019f},{-0.98085f,-0.194766f,1.81637e-016f},{-0.707075f,-0.707139f,-1.96173e-016f}, -{-0.707766f,-0.706447f,-6.53208e-017f},{-0.831545f,-0.555458f,-8.35793e-018f},{-0.831851f,-0.554999f,-8.37482e-018f}, -{-0.924075f,-0.382212f,-1.1598e-017f},{-0.923954f,-0.382504f,6.09686e-018f},{-0.196168f,-0.98057f,3.23122e-017f}, -{-0.194654f,-0.980872f,-4.92519e-017f},{4.20972e-017f,-1.0f,-3.82702e-017f},{-0.555293f,-0.831655f,-6.45083e-017f}, -{-0.382179f,-0.924088f,-8.45327e-018f},{-0.384009f,-0.923329f,-9.41977e-017f},{0.384009f,-0.923329f,-1.56138e-016f}, -{0.555293f,-0.831655f,-1.12494e-016f},{0.382179f,-0.924088f,9.4505e-017f},{0.196168f,-0.98057f,-2.71773e-017f}, -{0.194653f,-0.980872f,6.34884e-017f},{4.54604e-017f,-1.0f,-3.82702e-017f},{0.707765f,-0.706447f,1.01783e-016f}, -{0.831545f,-0.555458f,-2.48815e-017f},{0.707075f,-0.707139f,9.34854e-017f},{0.556611f,-0.830773f,-8.68647e-017f}, -{0.831851f,-0.554999f,-8.49237e-019f},{0.923954f,-0.382504f,-9.704e-017f},{0.980825f,-0.19489f,1.73729e-016f}, -{0.924075f,-0.382212f,1.6343e-016f},{0.98085f,-0.194766f,1.40245e-016f},{1.0f,-7.40149e-017f,0.0f}, -{-0.556611f,-0.830773f,-1.92896e-016f},{-1.0f,1.4803e-016f,0.0f},{-0.980825f,-0.19489f,-4.38694e-018f}, -{-0.98085f,-0.194766f,4.18233e-018f},{-0.707075f,-0.707139f,-4.93567e-017f},{-0.707766f,-0.706447f,-2.15703e-015f}, -{-0.831545f,-0.555458f,-5.07927e-017f},{-0.831851f,-0.554999f,-4.9305e-015f},{-0.924075f,-0.382212f,3.43955e-017f}, -{-0.923954f,-0.382504f,-5.46969e-015f},{-0.196168f,-0.98057f,-3.58397e-016f},{-0.194654f,-0.980872f,-7.12354e-016f}, -{1.16112e-016f,-1.0f,-3.82702e-017f},{-0.555293f,-0.831655f,1.61234e-015f},{-0.382179f,-0.924088f,1.08551e-016f}, -{-0.384009f,-0.923329f,-1.31452e-015f},{0.384009f,-0.923329f,-3.29687e-016f},{0.555293f,-0.831655f,-1.59609e-015f}, -{0.382179f,-0.924088f,-1.27979e-015f},{0.196168f,-0.98057f,-1.20008e-015f},{0.194653f,-0.980872f,-1.9888e-016f}, -{8.70936e-017f,-1.0f,-3.82702e-017f},{0.707765f,-0.706447f,2.35803e-015f},{0.831545f,-0.555458f,3.17694e-015f}, -{0.707075f,-0.707139f,-9.84182e-016f},{0.556611f,-0.830773f,1.53785e-015f},{0.831851f,-0.554999f,1.40897e-015f}, -{0.923954f,-0.382504f,-2.22899e-015f},{0.980825f,-0.19489f,3.27834e-015f},{0.924075f,-0.382212f,3.28529e-015f}, -{0.98085f,-0.194766f,-9.75854e-016f},{1.0f,2.36848e-015f,0.0f},{-0.556611f,-0.830773f,1.67042e-015f}, -{-0.980825f,-0.19489f,0.0f},{-0.98085f,-0.194766f,0.0f},{-0.707075f,-0.707139f,1.25613e-014f}, -{-0.707766f,-0.706447f,-6.27842e-015f},{-0.831545f,-0.555458f,0.0f},{-0.831851f,-0.554999f,-4.92555e-015f}, -{-0.924075f,-0.382212f,0.0f},{-0.923954f,-0.382504f,-5.47091e-015f},{-0.196168f,-0.98057f,-2.90387e-016f}, -{-0.194654f,-0.980872f,2.32767e-015f},{-2.36848e-015f,-1.0f,5.92119e-015f},{-0.555293f,-0.831655f,1.644e-015f}, -{-0.382179f,-0.924088f,0.0f},{-0.384009f,-0.923329f,-1.1369e-015f},{0.384009f,-0.923329f,-1.65103e-015f}, -{0.555293f,-0.831655f,-4.10619e-015f},{0.382179f,-0.924088f,5.70815e-015f},{0.196168f,-0.98057f,-1.30674e-015f}, -{0.194653f,-0.980872f,4.0678e-015f},{2.2084e-031f,-1.0f,5.92119e-015f},{0.707765f,-0.706447f,1.05014e-015f}, -{0.831545f,-0.555458f,1.1685e-014f},{0.707075f,-0.707139f,-5.88803e-015f},{0.556611f,-0.830773f,8.27016e-016f}, -{0.831851f,-0.554999f,2.82305e-015f},{0.923954f,-0.382504f,-2.11639e-015f},{0.980825f,-0.19489f,1.50995e-015f}, -{0.924075f,-0.382212f,3.07935e-015f},{0.98085f,-0.194766f,-2.25716e-015f},{-0.556611f,-0.830773f,1.6479e-015f}, -{-0.707075f,-0.707139f,1.24959e-014f},{-0.707766f,-0.706447f,-4.18301e-015f},{-0.831851f,-0.554999f,1.53923e-016f}, -{-0.924075f,-0.382212f,1.70988e-016f},{-0.923954f,-0.382504f,-1.70966e-016f},{-0.196168f,-0.98057f,0.0f}, -{-0.194654f,-0.980872f,2.89496e-015f},{-0.555293f,-0.831655f,5.13749e-017f},{-0.382179f,-0.924088f,-3.53586e-017f}, -{-0.384009f,-0.923329f,-3.5528e-017f},{0.384009f,-0.923329f,-1.34904e-015f},{0.555293f,-0.831655f,-2.51357e-015f}, -{0.382179f,-0.924088f,6.82195e-015f},{0.196168f,-0.98057f,9.07461e-018f},{0.194653f,-0.980872f,4.37396e-015f}, -{0.707765f,-0.706447f,-1.17623e-015f},{0.831545f,-0.555458f,8.7231e-015f},{0.707075f,-0.707139f,-4.93948e-015f}, -{0.556611f,-0.830773f,-6.85704e-016f},{0.831851f,-0.554999f,1.51229e-015f},{0.923954f,-0.382504f,1.13336e-017f}, -{0.980825f,-0.19489f,-1.84175e-015f},{0.924075f,-0.382212f,-4.11823e-017f},{0.98085f,-0.194766f,-1.37362e-015f}, -{-0.556611f,-0.830773f,-5.14968e-017f},{-1.0f,-2.36848e-015f,0.0f},{-0.980825f,-0.19489f,1.15398e-015f}, -{-0.98085f,-0.194766f,-5.8078e-015f},{-0.707075f,-0.707139f,-4.18672e-015f},{-0.707766f,-0.706447f,-3.90231e-018f}, -{-0.831545f,-0.555458f,-1.64449e-015f},{-0.831851f,-0.554999f,-1.64313e-015f},{-0.923954f,-0.382504f,0.0f}, -{-0.194654f,-0.980872f,1.16384e-015f},{-1.18424e-015f,-1.0f,2.96059e-015f},{-0.555293f,-0.831655f,-4.92439e-015f}, -{-0.382179f,-0.924088f,-3.86733e-015f},{-0.384009f,-0.923329f,0.0f},{0.384009f,-0.923329f,7.37719e-016f}, -{0.555293f,-0.831655f,6.15548e-015f},{0.382179f,-0.924088f,-1.29612e-015f},{0.196168f,-0.98057f,2.90388e-016f}, -{0.194653f,-0.980872f,8.70064e-016f},{1.1042e-031f,-1.0f,2.96059e-015f},{0.707765f,-0.706447f,5.22145e-016f}, -{0.831545f,-0.555458f,-4.18055e-015f},{0.707075f,-0.707139f,-2.09354e-015f},{0.556611f,-0.830773f,-3.39113e-015f}, -{0.831851f,-0.554999f,3.13065e-015f},{0.923954f,-0.382504f,-1.37855e-015f},{0.980825f,-0.19489f,1.62549e-015f}, -{0.924075f,-0.382212f,4.51372e-015f},{0.98085f,-0.194766f,-1.82655e-015f},{1.0f,-1.4803e-016f,0.0f}, -{-0.556611f,-0.830773f,0.0f},{-0.98085f,-0.194766f,1.81494e-016f},{-0.707075f,-0.707139f,-6.54176e-017f}, -{-0.707766f,-0.706447f,2.0915e-015f},{-0.196168f,-0.98057f,-9.0746e-018f},{-0.194654f,-0.980872f,1.45198e-015f}, -{-0.382179f,-0.924088f,-2.77121e-015f},{0.384009f,-0.923329f,-7.36693e-016f},{0.555293f,-0.831655f,6.1298e-015f}, -{0.382179f,-0.924088f,7.10482e-016f},{0.196168f,-0.98057f,0.0f},{0.194653f,-0.980872f,7.25991e-016f}, -{0.707765f,-0.706447f,1.02144e-015f},{0.831545f,-0.555458f,-2.93013e-016f},{0.707075f,-0.707139f,-1.89729e-015f}, -{0.556611f,-0.830773f,-1.57586e-015f},{0.831851f,-0.554999f,1.11762e-015f},{0.923954f,-0.382504f,-1.18487e-015f}, -{0.980825f,-0.19489f,-5.42824e-018f},{0.924075f,-0.382212f,-3.75468e-016f},{0.98085f,-0.194766f,1.1167e-015f}, -{0.964306f,-0.26479f,-8.54143e-016f},{0.965341f,0.260991f,-9.92332e-016f},{0.999998f,-0.00196876f,9.33927e-016f}, -{-0.801458f,-0.598051f,5.32077e-015f},{-0.917689f,-0.397299f,-1.49105e-015f},{-0.917616f,-0.397468f,-6.24691e-015f}, -{-0.801348f,-0.598198f,-1.4703e-015f},{-0.641892f,-0.766795f,-2.89037e-015f},{-0.642216f,-0.766524f,1.1573e-014f}, -{-0.230441f,-0.973086f,-3.46847e-015f},{-0.448409f,-0.893828f,8.3968e-015f},{-0.448005f,-0.894031f,-2.52105e-015f}, -{-0.230122f,-0.973162f,-4.53038e-015f},{-0.98448f,-0.175498f,-1.45732e-015f},{-0.998433f,0.0559597f,2.95596e-015f}, -{-0.984554f,-0.175082f,-1.87817e-015f},{-0.998408f,0.0564113f,2.28784e-015f},{-0.958688f,0.28446f,3.99223e-015f}, -{-0.958595f,0.284774f,3.98982e-015f},{0.718867f,0.695147f,4.38213e-015f},{0.718867f,0.695147f,-2.66034e-016f}, -{0.258065f,0.966128f,4.76769e-016f},{-1.40172e-014f,1.0f,0.0f},{0.506909f,0.862f,6.5491e-015f}, -{-2.10257e-014f,1.0f,0.0f},{0.969751f,-0.244096f,-3.5888e-016f},{0.956928f,0.290324f,-2.78281e-016f}, -{0.999712f,0.0239869f,-1.31722e-016f},{-0.925087f,0.379756f,3.80183e-015f},{-0.810449f,0.58581f,4.06854e-015f}, -{-0.810565f,0.585648f,-2.66995e-016f},{-0.925162f,0.379572f,1.89621e-015f},{-0.988265f,0.152747f,3.03551e-015f}, -{-0.996526f,-0.0832844f,-3.77295e-016f},{-0.996566f,-0.0828045f,-1.86673e-015f},{-0.988334f,0.152299f,-2.57409e-015f}, -{-0.949486f,-0.313809f,-5.48639e-015f},{-0.949377f,-0.314139f,1.66453e-015f},{-0.651023f,0.759058f,-4.17468e-015f}, -{-0.455278f,0.890349f,1.28807e-015f},{-0.650679f,0.759353f,-3.53307e-015f},{-0.45485f,0.890568f,-1.28999e-015f}, -{-0.234187f,0.972192f,1.38667e-015f},{-0.233849f,0.972273f,0.0f},{-5.08163e-016f,1.0f,0.0f}, -{-0.810565f,-0.585648f,-2.93375e-015f},{-0.925162f,-0.379572f,-6.84758e-016f},{-0.925087f,-0.379756f,1.3694e-015f}, -{-0.810449f,-0.58581f,-4.73361e-015f},{-0.651023f,-0.759058f,-1.72543e-015f},{-0.45485f,-0.890568f,-8.32791e-016f}, -{-0.455278f,-0.890349f,2.46088e-015f},{-0.650679f,-0.759353f,-3.9742e-015f},{4.0653e-015f,-1.0f,0.0f}, -{-0.234187f,-0.972192f,4.48967e-016f},{-0.233849f,-0.972273f,-2.92082e-015f},{-0.988265f,-0.152747f,1.23682e-015f}, -{-0.996566f,0.0828045f,2.45151e-016f},{-0.988334f,-0.152299f,4.16364e-015f},{-0.996526f,0.0832843f,4.93142e-016f}, -{-0.949486f,0.313809f,0.0f},{-0.949377f,0.314139f,-9.30039e-016f},{-0.917616f,0.397468f,1.07392e-015f}, -{-0.801348f,0.598198f,7.5915e-016f},{-0.801458f,0.598051f,3.66985e-015f},{-0.917689f,0.397299f,3.03814e-015f}, -{-0.984554f,0.175082f,-5.42488e-016f},{-0.98448f,0.175498f,-2.04441e-015f},{-0.958688f,-0.28446f,9.93802e-016f}, -{-0.998433f,-0.0559597f,8.52548e-017f},{-0.998408f,-0.0564112f,5.09934e-015f},{-0.958595f,-0.284774f,-3.46074e-015f}, -{-0.642216f,0.766524f,-1.23434e-015f},{-0.448409f,0.893828f,-1.65391e-016f},{-0.641892f,0.766795f,-1.41886e-016f}, -{-0.448005f,0.894031f,-1.65429e-016f},{-0.230441f,0.973086f,-1.04236e-015f},{-0.230122f,0.973162f,1.04144e-015f}, -{-2.5659e-016f,1.0f,0.0f},{0.709621f,0.704584f,3.94851e-016f},{0.254108f,0.967176f,9.46083e-017f}, -{0.499432f,0.866353f,4.18692e-016f},{-3.8902e-016f,1.0f,0.0f},{0.43334f,-0.90123f,-1.30162e-016f}, -{0.628551f,-0.777768f,1.84857e-017f},{0.788356f,-0.61522f,9.057e-018f},{0.788356f,-0.61522f,1.5327e-016f}, -{0.217989f,-0.975951f,2.24194e-018f},{5.05322e-016f,-1.0f,0.0f},{-0.104301f,0.994546f,1.88853e-016f}, -{-0.313328f,0.949645f,2.55439e-016f},{-0.508034f,0.861337f,-3.91932e-016f},{-0.675985f,0.736915f,5.02496e-017f}, -{0.104717f,0.994502f,9.68824e-018f},{0.104717f,0.994502f,-3.48663e-016f},{-0.508034f,-0.861337f,2.55007e-015f}, -{-0.313328f,-0.949645f,5.86924e-016f},{-0.104301f,-0.994546f,3.32457e-015f},{0.104717f,-0.994502f,-2.20034e-016f}, -{-0.675985f,-0.736915f,1.93154e-015f},{-0.104301f,0.994546f,-2.9348e-015f},{-0.313328f,0.949645f,-2.10139e-015f}, -{-0.508034f,0.861337f,2.51193e-016f},{-0.675985f,0.736915f,-2.46257e-015f},{-0.508034f,0.861337f,-1.08628e-015f}, -{0.104717f,0.994502f,-2.94432e-015f},{-0.508034f,-0.861337f,-2.36206e-015f},{-0.313328f,-0.949645f,8.49252e-015f}, -{-0.104301f,-0.994546f,3.30527e-015f},{0.104717f,-0.994502f,-8.68343e-015f},{-0.675985f,-0.736915f,2.50165e-016f}, -{0.628551f,0.777768f,-2.30266e-015f},{0.433341f,0.90123f,8.09474e-015f},{0.217989f,0.975951f,-9.69688e-015f}, -{0.788356f,0.61522f,7.28566e-015f},{-0.43334f,0.90123f,2.77046e-015f},{-0.628551f,0.777768f,1.84916e-015f}, -{-0.788356f,0.61522f,-2.91035e-015f},{-0.217989f,0.975951f,1.29075e-015f},{1.10775e-015f,1.0f,0.0f}, -{0.104301f,-0.994546f,-8.67894e-015f},{0.313328f,-0.949645f,4.68109e-015f},{0.508034f,-0.861337f,-8.439e-015f}, -{0.675985f,-0.736915f,-1.0665e-015f},{-0.104717f,-0.994502f,1.73559e-014f},{0.508034f,0.861337f,2.93947e-016f}, -{0.313328f,0.949645f,-4.18867e-015f},{0.104301f,0.994546f,-1.47222e-015f},{-0.104717f,0.994502f,7.95314e-016f}, -{0.675985f,0.736915f,-4.00264e-015f},{0.104301f,-0.994546f,-1.54397e-016f},{0.313328f,-0.949645f,7.14982e-018f}, -{0.508034f,-0.861337f,-9.40051e-017f},{0.675985f,-0.736915f,1.6011e-015f},{-0.104717f,-0.994502f,3.10024e-016f}, -{0.508034f,0.861337f,0.0f},{0.313328f,0.949645f,-1.4405e-016f},{0.104301f,0.994546f,-4.17183e-016f}, -{-0.104717f,0.994502f,2.05762e-016f},{0.675985f,0.736915f,0.0f},{0.675985f,0.736915f,2.27403e-015f}, -{-0.628551f,-0.777768f,1.89686e-015f},{-0.433341f,-0.90123f,1.60368e-015f},{-0.217989f,-0.975951f,5.05612e-016f}, -{-0.217989f,-0.975951f,4.12034e-016f},{6.12323e-017f,-1.0f,0.0f},{-0.788356f,-0.61522f,2.39092e-015f}, -{-0.980872f,0.194654f,-1.44073e-016f},{-1.0f,-2.96059e-016f,-3.28692e-031f},{-0.923329f,-0.384009f,-2.13958e-016f}, -{-0.924088f,-0.382179f,9.40449e-016f},{-0.98057f,-0.196168f,-7.62016e-016f},{-0.980872f,-0.194653f,6.1653e-016f}, -{-0.831655f,-0.555293f,6.67161e-016f},{-0.707139f,-0.707075f,-4.57955e-016f},{-0.706447f,-0.707765f,4.57334e-016f}, -{-0.555458f,-0.831545f,8.32431e-017f},{-0.554999f,-0.831851f,-2.05391e-016f},{-0.830773f,-0.556611f,-3.85076e-016f}, -{-0.19489f,-0.980825f,-3.63028e-018f},{-0.194766f,-0.98085f,-2.22141e-016f},{-0.382212f,-0.924075f,5.86375e-016f}, -{-0.382504f,-0.923954f,-2.95917e-016f},{-1.85037e-017f,-1.0f,0.0f},{-0.98057f,0.196168f,-1.01605e-015f}, -{-0.924088f,0.382179f,-1.22649e-015f},{-0.923329f,0.384009f,-1.99588e-016f},{-0.830773f,0.556611f,-1.04527e-016f}, -{-0.831655f,0.555293f,-4.10999e-016f},{-0.706447f,0.707766f,5.22876e-016f},{-0.707139f,0.707075f,5.23388e-016f}, -{-0.555458f,0.831545f,-6.15467e-016f},{-0.554999f,0.831851f,-4.10782e-016f},{-0.382212f,0.924075f,-1.36791e-015f}, -{-0.382504f,0.923954f,0.0f},{-0.194766f,0.98085f,-8.7013e-016f},{-0.19489f,0.980825f,0.0f}, -{-3.33067e-016f,1.0f,0.0f},{-2.96059e-016f,1.0f,0.0f},{-0.980872f,0.194654f,0.0f}, -{-0.923329f,-0.384009f,7.57929e-018f},{-0.924088f,-0.382179f,2.41708e-016f},{-0.98057f,-0.196168f,-1.26994e-016f}, -{-0.980872f,-0.194653f,-9.14525e-017f},{-0.831655f,-0.555293f,4.10524e-016f},{-0.707139f,-0.707075f,1.14487e-016f}, -{-0.706447f,-0.707765f,-5.72353e-016f},{-0.555458f,-0.831545f,-9.69264e-018f},{-0.554999f,-0.831851f,4.97064e-016f}, -{-0.830773f,-0.556611f,5.13819e-016f},{-2.96059e-016f,-1.0f,0.0f},{-0.19489f,-0.980825f,-1.02781e-015f}, -{-0.194766f,-0.98085f,8.39508e-016f},{-0.382212f,-0.924075f,4.37371e-016f},{-0.382504f,-0.923954f,1.06278e-016f}, -{-5.92119e-016f,-1.0f,0.0f},{-0.98057f,0.196168f,-7.25968e-017f},{-0.924088f,0.382179f,0.0f}, -{-0.923329f,0.384009f,-1.42112e-016f},{-0.830773f,0.556611f,-5.13435e-016f},{-0.831655f,0.555293f,2.055e-016f}, -{-0.706447f,0.707766f,-1.04673e-015f},{-0.707139f,0.707075f,2.6167e-016f},{-0.555458f,0.831545f,6.15467e-016f}, -{-0.382212f,0.924075f,0.0f},{-0.194766f,0.98085f,7.25975e-016f},{-0.19489f,0.980825f,-8.70204e-016f}, -{-1.85037e-017f,1.0f,0.0f},{-0.144611f,0.989489f,-3.80291e-017f},{0.0759712f,0.99711f,-5.623e-017f}, -{-0.358149f,0.933664f,-9.55933e-016f},{-0.358149f,0.933664f,1.99014e-016f},{-0.549837f,0.835272f,0.0f}, -{0.2878f,0.957691f,0.0f},{0.707107f,-0.707107f,0.0f},{0.54721f,-0.836995f,0.0f}, -{0.368095f,-0.929788f,0.0f},{0.181963f,-0.983305f,0.0f},{1.53707e-012f,-1.0f,0.0f}, -{8.42952e-008f,-1.0f,0.0f},{0.836995f,-0.54721f,0.0f},{0.929788f,-0.368095f,0.0f}, -{0.983305f,-0.181963f,0.0f},{1.0f,3.07487e-012f,0.0f},{1.0f,3.07526e-012f,0.0f}, -{-0.739259f,0.673422f,0.0f},{-0.710614f,0.703582f,0.0f},{-0.739259f,0.673421f,0.0f}, -{-0.766626f,0.642094f,0.0f},{-0.766624f,0.642096f,0.0f},{-0.792665f,0.609658f,0.0f}, -{-0.792663f,0.60966f,0.0f},{-0.817331f,0.576168f,0.0f},{-0.817333f,0.576166f,0.0f}, -{-0.840587f,0.541677f,0.0f},{-0.840585f,0.54168f,0.0f},{-0.862386f,0.506252f,0.0f}, -{-0.862384f,0.506254f,0.0f},{-0.882691f,0.469953f,0.0f},{-0.882693f,0.46995f,0.0f}, -{-0.901473f,0.432835f,0.0f},{-0.901471f,0.432838f,0.0f},{-0.918693f,0.394972f,0.0f}, -{-0.918692f,0.394974f,0.0f},{-0.934323f,0.356428f,0.0f},{-0.934324f,0.356425f,0.0f}, -{-0.948338f,0.317262f,0.0f},{-0.948337f,0.317264f,0.0f},{-0.960711f,0.277549f,0.0f}, -{-0.960711f,0.277552f,0.0f},{-0.971422f,0.237359f,0.0f},{-0.971423f,0.237356f,0.0f}, -{-0.980453f,0.196753f,0.0f},{-0.980453f,0.196756f,0.0f},{-0.987787f,0.155809f,0.0f}, -{-0.987787f,0.155812f,0.0f},{-0.993412f,0.114599f,0.0f},{-0.993412f,0.114596f,0.0f}, -{-0.997318f,0.0731848f,0.0f},{-0.997318f,0.073187f,0.0f},{-0.999499f,0.0316463f,0.0f}, -{-0.999499f,0.0316489f,0.0f},{-0.999951f,-0.00994395f,0.0f},{-0.999951f,-0.00994627f,0.0f}, -{-0.998672f,-0.0515206f,0.0f},{-0.710614f,0.703582f,0.0f},{-0.680741f,0.732525f,0.0f}, -{-0.680739f,0.732526f,0.0f},{-0.649687f,0.760202f,0.0f},{-0.649688f,0.760201f,0.0f}, -{-0.61751f,0.786563f,0.0f},{-0.617513f,0.786561f,0.0f},{-0.584268f,0.811561f,0.0f}, -{-0.584265f,0.811563f,0.0f},{-0.55001f,0.835158f,0.0f},{-0.550013f,0.835156f,0.0f}, -{-0.514803f,0.857309f,0.0f},{-0.514806f,0.857307f,0.0f},{-0.478708f,0.877974f,0.0f}, -{-0.478705f,0.877976f,0.0f},{-0.441779f,0.897124f,0.0f},{-0.441782f,0.897123f,0.0f}, -{-0.404088f,0.91472f,0.0f},{-0.404092f,0.914719f,0.0f},{-0.365702f,0.930732f,0.0f}, -{-0.365699f,0.930733f,0.0f},{-0.326677f,0.945136f,0.0f},{-0.326679f,0.945135f,0.0f}, -{-0.287089f,0.957904f,0.0f},{-0.287092f,0.957903f,0.0f},{-0.247008f,0.969013f,0.0f}, -{-0.247006f,0.969014f,0.0f},{-0.206494f,0.978448f,0.0f},{-0.206496f,0.978447f,0.0f}, -{-0.165625f,0.986189f,0.0f},{-0.165628f,0.986188f,0.0f},{-0.124472f,0.992223f,0.0f}, -{-0.12447f,0.992223f,0.0f},{-0.0830991f,0.996541f,0.0f},{-0.0831017f,0.996541f,0.0f}, -{-0.041585f,0.999135f,0.0f},{-0.0415873f,0.999135f,0.0f},{-1.92868e-016f,1.0f,0.0f}, -{-8.64379e-008f,1.0f,0.0f},{-0.0572333f,0.998361f,1.89979e-016f},{3.3736e-016f,1.0f,0.0f}, -{-0.114279f,0.993449f,0.0f},{-0.707107f,0.707107f,0.0f},{-0.822154f,0.569266f,0.0f}, -{-0.910446f,0.413628f,0.0f},{-0.821945f,0.569567f,0.0f},{-0.910644f,0.413191f,0.0f}, -{-0.969699f,0.244303f,0.0f},{-0.969779f,0.243984f,0.0f},{-0.997734f,0.0672808f,0.0f}, -{-0.993705f,-0.11203f,0.0f},{-0.997765f,0.0668255f,0.0f},{-0.957691f,-0.2878f,0.0f}, -{-0.993663f,-0.112396f,0.0f},{-0.569266f,0.822154f,0.0f},{-0.569567f,0.821945f,0.0f}, -{-0.413628f,0.910446f,0.0f},{-0.244303f,0.969699f,0.0f},{-0.413191f,0.910644f,0.0f}, -{-0.243985f,0.969779f,0.0f},{-0.0672808f,0.997734f,0.0f},{-0.0668255f,0.997765f,0.0f}, -{0.11203f,0.993705f,0.0f},{0.112396f,0.993663f,0.0f},{-0.823338f,-0.567551f,2.91569e-016f}, -{-0.877128f,-0.480256f,-1.36506e-015f},{-0.877118f,-0.480275f,1.00957e-015f},{-0.823334f,-0.567558f,5.00925e-017f}, -{-0.760897f,-0.648872f,1.44361e-016f},{-0.921684f,-0.387941f,1.25621e-016f},{-0.921695f,-0.387915f,6.82191e-016f}, -{-0.956563f,-0.291525f,-6.81027e-016f},{-0.956571f,-0.291499f,-7.61943e-016f},{-0.981386f,-0.192047f,6.553e-016f}, -{-0.98139f,-0.192025f,1.77659e-017f},{-0.995897f,-0.0904984f,-8.37279e-018f},{-0.995893f,-0.0905325f,-1.67519e-017f}, -{-0.999929f,0.0119218f,1.48019e-015f},{-0.993449f,0.114279f,0.0f},{-0.999926f,0.0121699f,0.0f}, -{-0.690461f,-0.723369f,-9.58068e-017f},{-0.760892f,-0.648879f,1.7081e-016f},{-0.690446f,-0.723384f,-1.49808e-016f}, -{-0.612765f,-0.790265f,1.16954e-016f},{-0.612743f,-0.790282f,-1.7266e-016f},{-0.528625f,-0.848856f,3.32998e-016f}, -{-0.438929f,-0.898522f,-5.4393e-016f},{-0.528601f,-0.84887f,4.57239e-016f},{-0.438908f,-0.898532f,-2.60926e-016f}, -{-0.344602f,-0.938749f,1.75687e-016f},{-0.34457f,-0.938761f,5.73784e-016f},{-0.246664f,-0.969101f,-5.54286e-016f}, -{-0.146104f,-0.989269f,0.0f},{-0.246424f,-0.969162f,-8.55909e-016f},{0.505064f,-0.863082f,-2.96041e-016f}, -{0.342733f,-0.939433f,-1.39064e-015f},{0.653412f,-0.757002f,-4.80673e-016f},{0.174993f,-0.98457f,-7.12538e-016f}, -{0.00988645f,-0.999951f,0.0f},{0.780028f,-0.625744f,-1.42742e-017f},{0.879277f,-0.47631f,-1.99991e-016f}, -{0.948437f,-0.316965f,-3.53543e-016f},{0.987776f,-0.155878f,8.15532e-017f},{1.0f,-1.95899e-012f,0.0f}, -{1.0f,-1.95907e-012f,0.0f},{-0.181963f,-0.983305f,0.0f},{-4.18691e-016f,-1.0f,0.0f}, -{-2.09346e-016f,-1.0f,0.0f},{-0.707107f,-0.707107f,0.0f},{-0.54721f,-0.836995f,0.0f}, -{-0.368095f,-0.929788f,0.0f},{-0.929788f,-0.368095f,0.0f},{-0.983305f,-0.181963f,0.0f}, -{-0.836995f,-0.54721f,0.0f},{-1.0f,-2.61682e-016f,0.0f},{-1.0f,-8.42937e-008f,0.0f}, -{-0.901678f,-0.432409f,-4.8007e-016f},{-0.823027f,-0.568002f,1.63014e-016f},{-0.957351f,-0.288928f,2.01882e-015f}, -{-0.957351f,-0.288928f,0.0f},{-0.989708f,-0.143098f,7.32531e-016f},{-0.72348f,-0.690346f,-1.05257e-015f}, -{-1.0f,-4.36853e-016f,0.0f},{-1.0f,-9.28313e-016f,0.0f},{-0.60671f,-0.794923f,-3.38738e-016f}, -{-0.477546f,-0.878607f,-8.64155e-016f},{-0.341342f,-0.939939f,-3.74916e-016f},{-0.203325f,-0.979111f,0.0f}, -{-0.791675f,-0.610942f,0.0f},{-0.765522f,-0.64341f,0.0f},{-0.738038f,-0.674759f,0.0f}, -{-0.765522f,-0.643409f,0.0f},{-0.709271f,-0.704936f,0.0f},{-0.738039f,-0.674758f,0.0f}, -{-0.709273f,-0.704934f,0.0f},{-0.679272f,-0.733887f,0.0f},{-0.648092f,-0.761562f,0.0f}, -{-0.679273f,-0.733885f,0.0f},{-0.615785f,-0.787914f,0.0f},{-0.648094f,-0.761561f,0.0f}, -{-0.615787f,-0.787913f,0.0f},{-0.582409f,-0.812896f,0.0f},{-0.54802f,-0.836465f,0.0f}, -{-0.58241f,-0.812895f,0.0f},{-0.512678f,-0.858581f,0.0f},{-0.548021f,-0.836464f,0.0f}, -{-0.51268f,-0.85858f,0.0f},{-0.476445f,-0.879204f,0.0f},{-0.439385f,-0.898299f,0.0f}, -{-0.476447f,-0.879203f,0.0f},{-0.40156f,-0.915833f,0.0f},{-0.439387f,-0.898298f,0.0f}, -{-0.401562f,-0.915832f,0.0f},{-0.363038f,-0.931774f,0.0f},{-0.323885f,-0.946097f,0.0f}, -{-0.36304f,-0.931774f,0.0f},{-0.284168f,-0.958774f,0.0f},{-0.323886f,-0.946096f,0.0f}, -{-0.28417f,-0.958774f,0.0f},{-0.243959f,-0.969786f,0.0f},{-0.24396f,-0.969785f,0.0f}, -{-0.816453f,-0.577412f,0.0f},{-0.816452f,-0.577413f,0.0f},{-0.839811f,-0.542879f,0.0f}, -{-0.861709f,-0.507402f,0.0f},{-0.83981f,-0.54288f,0.0f},{-0.88211f,-0.471044f,0.0f}, -{-0.861708f,-0.507404f,0.0f},{-0.882109f,-0.471046f,0.0f},{-0.900977f,-0.433866f,0.0f}, -{-0.918278f,-0.395935f,0.0f},{-0.900976f,-0.433869f,0.0f},{-0.933984f,-0.357316f,0.0f}, -{-0.918278f,-0.395937f,0.0f},{-0.933983f,-0.357318f,0.0f},{-0.948065f,-0.318075f,0.0f}, -{-0.960499f,-0.278282f,0.0f},{-0.948065f,-0.318077f,0.0f},{-0.971264f,-0.238005f,0.0f}, -{-0.960499f,-0.278284f,0.0f},{-0.971263f,-0.238007f,0.0f},{-0.98034f,-0.197314f,0.0f}, -{-0.987713f,-0.15628f,0.0f},{-0.98034f,-0.197316f,0.0f},{-0.993368f,-0.114975f,0.0f}, -{-0.987712f,-0.156283f,0.0f},{-0.993368f,-0.114977f,0.0f},{-0.997297f,-0.0734701f,0.0f}, -{-0.999493f,-0.0318375f,0.0f},{-0.997297f,-0.0734722f,0.0f},{-0.999951f,0.00985025f,0.0f}, -{-0.999493f,-0.0318392f,0.0f},{-0.999951f,0.00984923f,0.0f},{-0.998672f,0.0515206f,0.0f}, -{-0.5f,-0.866025f,0.0f},{-0.5f,-0.866025f,-4.07254e-016f},{0.997498f,-0.0706974f,4.22047e-015f}, -{0.999099f,-0.042441f,-4.49972e-015f},{0.999099f,-0.0424415f,-8.87378e-015f},{0.9999f,0.0141508f,-1.48015e-015f}, -{0.9999f,-0.014151f,0.0f},{0.9999f,-0.0141508f,-7.42169e-015f},{0.997498f,-0.0706979f,1.47659e-015f}, -{0.995098f,-0.0988972f,5.89216e-015f},{0.995098f,-0.0988976f,5.59937e-015f},{0.9919f,-0.127018f,-1.17465e-014f}, -{0.9919f,-0.127018f,-1.72436e-014f},{0.987909f,-0.155036f,-5.3906e-015f},{0.987909f,-0.155037f,5.84959e-015f}, -{0.983126f,-0.182932f,-2.36905e-015f},{0.983126f,-0.182931f,8.73191e-015f},{0.971202f,-0.238259f,8.626e-015f}, -{0.96407f,-0.265648f,-7.28139e-015f},{0.96407f,-0.265647f,-1.29898e-014f},{0.977555f,-0.210679f,-4.54082e-015f}, -{0.977555f,-0.21068f,0.0f},{0.971202f,-0.238258f,-1.29121e-014f},{0.956167f,-0.292823f,-1.73386e-015f}, -{0.956167f,-0.292823f,0.0f},{0.947497f,-0.319764f,5.61031e-015f},{0.947497f,-0.319764f,-1.89338e-015f}, -{0.938069f,-0.346449f,0.0f},{0.938069f,-0.346449f,7.60587e-015f},{0.927889f,-0.372856f,9.90971e-015f}, -{0.905308f,-0.424755f,5.3605e-015f},{0.905309f,-0.424755f,3.304e-016f},{0.916966f,-0.398966f,4.7247e-015f}, -{0.916966f,-0.398965f,5.42953e-015f},{0.927889f,-0.372857f,-7.70196e-015f},{0.892926f,-0.450204f,0.0f}, -{0.892926f,-0.450204f,5.33148e-015f},{0.879828f,-0.475292f,1.04193e-014f},{0.879828f,-0.475292f,1.04193e-014f}, -{0.866025f,-0.5f,0.0f},{0.9999f,0.014151f,8.90184e-015f},{0.999099f,0.042441f,-1.04784e-014f}, -{0.999099f,0.0424415f,-1.61429e-014f},{0.997498f,0.0706974f,8.65025e-015f},{0.995098f,0.0988972f,2.94608e-015f}, -{0.997498f,0.0706979f,-1.09175e-014f},{0.995098f,0.0988976f,1.39984e-015f},{0.9919f,0.127018f,-1.06363e-014f}, -{0.9919f,0.127018f,9.63801e-015f},{0.987909f,0.155036f,-7.40539e-015f},{0.983126f,0.182931f,-7.57272e-015f}, -{0.987909f,0.155037f,-2.5165e-015f},{0.983126f,0.182932f,2.18298e-015f},{0.977555f,0.210679f,7.64703e-015f}, -{0.977555f,0.21068f,-4.23518e-015f},{0.971202f,0.238258f,-1.03144e-014f},{0.96407f,0.265647f,-7.60334e-015f}, -{0.971202f,0.238259f,1.75636e-015f},{0.96407f,0.265648f,1.0869e-014f},{0.956167f,0.292823f,5.12754e-015f}, -{0.956167f,0.292823f,-8.24033e-015f},{0.947497f,0.319764f,3.07966e-016f},{0.938069f,0.346449f,-1.05337e-014f}, -{0.947497f,0.319764f,-8.2576e-015f},{0.938069f,0.346449f,-1.87656e-015f},{0.927889f,0.372856f,3.1746e-015f}, -{0.927889f,0.372857f,-3.31849e-015f},{0.916966f,0.398965f,3.06056e-015f},{0.905309f,0.424755f,7.49538e-015f}, -{0.916966f,0.398966f,4.02549e-015f},{0.905308f,0.424755f,1.46943e-015f},{0.892926f,0.450204f,-1.18685e-014f}, -{0.892926f,0.450204f,1.25672e-015f},{0.879828f,0.475292f,4.58408e-015f},{0.866025f,0.5f,0.0f}, -{0.879828f,0.475292f,1.83809e-015f},{0.5f,0.866025f,0.0f},{0.78179f,0.623541f,-1.15728e-015f}, -{0.807718f,0.589568f,-2.39133e-015f},{0.807717f,0.589571f,9.60223e-017f},{0.754434f,0.656376f,-5.72909e-015f}, -{0.754433f,0.656377f,-7.23689e-015f},{0.7257f,0.688011f,1.01846e-015f},{0.832169f,0.554522f,1.64171e-015f}, -{0.781789f,0.623543f,4.8494e-015f},{0.832171f,0.554519f,4.10543e-015f},{0.855102f,0.51846f,-9.96661e-016f}, -{0.855104f,0.518456f,1.53494e-015f},{0.876475f,0.481448f,-5.18977e-015f},{0.876473f,0.48145f,-4.02026e-015f}, -{0.896244f,0.443562f,-2.65341e-015f},{0.896245f,0.443559f,-3.96662e-015f},{0.914379f,0.40486f,0.0f}, -{0.930841f,0.365425f,0.0f},{0.914377f,0.404864f,-2.39728e-015f},{0.930842f,0.365423f,0.0f}, -{0.945605f,0.325317f,-3.67284e-015f},{0.945604f,0.32532f,0.0f},{0.97944f,0.201738f,3.58358e-015f}, -{0.969926f,0.243399f,-1.44121e-015f},{0.97944f,0.201735f,-3.41043e-015f},{0.95864f,0.284621f,7.36158e-015f}, -{0.958641f,0.284618f,-5.6763e-015f},{0.969926f,0.243401f,5.74311e-015f},{0.987165f,0.159705f,9.45645e-016f}, -{0.993087f,0.117381f,-1.03704e-014f},{0.987165f,0.159703f,-4.89956e-015f},{0.993087f,0.117378f,-6.9502e-016f}, -{0.997196f,0.07484f,0.0f},{0.999483f,0.0321655f,6.29904e-015f},{0.999482f,0.032168f,-5.91813e-015f}, -{0.997195f,0.0748434f,-8.86324e-016f},{0.999944f,-0.0105685f,-5.7957e-015f},{0.999944f,-0.0105657f,5.92086e-015f}, -{0.99858f,-0.0532826f,0.0f},{0.99858f,-0.05328f,0.0f},{0.995391f,-0.0958981f,0.0f}, -{0.695642f,0.718389f,-2.12686e-015f},{0.725699f,0.688012f,-3.16696e-015f},{0.69564f,0.718391f,6.73571e-017f}, -{0.664312f,0.747455f,3.69231e-016f},{0.66431f,0.747457f,-4.91688e-015f},{0.631769f,0.775156f,-3.61476e-016f}, -{0.598073f,0.801442f,-8.85326e-016f},{0.631767f,0.775159f,-5.10676e-016f},{0.59807f,0.801444f,-2.51436e-015f}, -{0.563284f,0.826264f,-2.63707e-016f},{0.563281f,0.826266f,-4.79448e-015f},{0.527466f,0.849576f,2.47204e-015f}, -{0.490685f,0.871337f,-7.45068e-016f},{0.527463f,0.849578f,6.28814e-016f},{0.490682f,0.871339f,-4.66609e-016f}, -{0.453007f,0.891507f,-5.36872e-018f},{0.453005f,0.891508f,1.90646e-015f},{0.414503f,0.910048f,-9.01947e-016f}, -{0.375241f,0.926927f,-7.55498e-016f},{0.414499f,0.91005f,-3.44627e-015f},{0.375238f,0.926928f,-8.26493e-018f}, -{0.335293f,0.942114f,7.4317e-016f},{0.335291f,0.942115f,-1.38718e-015f},{0.294734f,0.955579f,-6.60361e-018f}, -{0.253636f,0.9673f,1.39186e-016f},{0.294731f,0.95558f,-4.80822e-016f},{0.253634f,0.9673f,-1.1694e-015f}, -{0.212076f,0.977253f,-1.09093e-015f},{0.212073f,0.977254f,-1.42807e-015f},{0.170128f,0.985422f,-8.58064e-016f}, -{0.127868f,0.991791f,1.21011e-015f},{0.170124f,0.985423f,3.47036e-015f},{0.127866f,0.991791f,2.85545e-016f}, -{0.0853758f,0.996349f,-4.87227e-016f},{0.0853729f,0.996349f,3.21028e-015f},{0.0427275f,0.999087f,-3.76158e-016f}, -{1.41083e-016f,1.0f,0.0f},{0.0427249f,0.999087f,-2.9625e-015f},{1.54309e-016f,1.0f,0.0f}, -{1.0f,5.04647e-017f,0.0f},{1.0f,5.3829e-017f,0.0f},{0.998532f,0.0541567f,0.0f}, -{0.994135f,0.108145f,0.0f},{0.998534f,0.0541301f,0.0f},{0.986822f,0.161808f,0.0f}, -{0.99414f,0.108105f,0.0f},{0.986829f,0.161767f,0.0f},{0.976616f,0.214992f,0.0f}, -{0.963545f,0.267546f,0.0f},{0.976622f,0.214964f,0.0f},{0.947644f,0.319328f,0.0f}, -{0.963549f,0.267531f,0.0f},{0.947653f,0.319303f,0.0f},{0.928963f,0.370172f,0.0f}, -{0.90756f,0.419923f,0.0f},{0.928977f,0.370136f,0.0f},{0.883495f,0.46844f,0.0f}, -{0.907577f,0.419887f,0.0f},{0.883512f,0.468409f,0.0f},{0.856841f,0.515581f,0.0f}, -{0.827674f,0.56121f,0.0f},{0.856854f,0.515559f,0.0f},{0.796076f,0.605197f,0.0f}, -{0.827681f,0.561199f,0.0f},{0.796082f,0.605188f,0.0f},{0.762141f,0.647411f,0.0f}, -{0.725973f,0.687723f,0.0f},{0.762151f,0.6474f,0.0f},{0.687676f,0.726018f,0.0f}, -{0.725983f,0.687712f,0.0f},{0.687687f,0.726007f,0.0f},{0.647361f,0.762183f,0.0f}, -{0.605148f,0.796113f,0.0f},{0.647375f,0.762171f,0.0f},{0.56116f,0.827707f,0.0f}, -{0.605164f,0.796101f,0.0f},{0.561178f,0.827695f,0.0f},{0.515527f,0.856873f,0.0f}, -{0.468383f,0.883526f,0.0f},{0.515545f,0.856862f,0.0f},{0.419866f,0.907586f,0.0f}, -{0.4684f,0.883516f,0.0f},{0.419884f,0.907578f,0.0f},{0.370116f,0.928986f,0.0f}, -{0.319279f,0.947661f,0.0f},{0.370136f,0.928977f,0.0f},{0.267507f,0.963556f,0.0f}, -{0.319301f,0.947653f,0.0f},{0.267528f,0.96355f,0.0f},{0.214954f,0.976624f,0.0f}, -{0.16177f,0.986829f,0.0f},{0.214973f,0.97662f,0.0f},{0.108111f,0.994139f,0.0f}, -{0.161786f,0.986826f,0.0f},{0.108145f,0.994135f,0.0f},{0.0538298f,0.99855f,0.0f}, -{-2.15316e-016f,1.0f,0.0f},{0.0538044f,0.998551f,0.0f},{-2.35502e-016f,1.0f,0.0f}, -{0.998532f,-0.0541566f,0.0f},{0.998534f,-0.0541302f,0.0f},{0.994135f,-0.108145f,0.0f}, -{0.986822f,-0.161808f,0.0f},{0.99414f,-0.108105f,0.0f},{0.976616f,-0.214992f,0.0f}, -{0.986829f,-0.161767f,0.0f},{0.976622f,-0.214964f,0.0f},{0.963545f,-0.267546f,0.0f}, -{0.947644f,-0.319328f,0.0f},{0.963549f,-0.267531f,0.0f},{0.928963f,-0.370172f,0.0f}, -{0.947653f,-0.319303f,0.0f},{0.928977f,-0.370136f,0.0f},{0.90756f,-0.419923f,0.0f}, -{0.883495f,-0.46844f,0.0f},{0.907577f,-0.419887f,0.0f},{0.856841f,-0.515581f,0.0f}, -{0.883512f,-0.468409f,0.0f},{0.856854f,-0.515559f,0.0f},{0.827674f,-0.56121f,0.0f}, -{0.796076f,-0.605197f,0.0f},{0.827681f,-0.561199f,0.0f},{0.762141f,-0.647411f,0.0f}, -{0.796082f,-0.605188f,0.0f},{0.762151f,-0.6474f,0.0f},{0.725973f,-0.687723f,0.0f}, -{0.687676f,-0.726018f,0.0f},{0.725983f,-0.687712f,0.0f},{0.647361f,-0.762183f,0.0f}, -{0.687687f,-0.726007f,0.0f},{0.647375f,-0.762171f,0.0f},{0.605148f,-0.796113f,0.0f}, -{0.56116f,-0.827707f,0.0f},{0.605164f,-0.796101f,0.0f},{0.515527f,-0.856873f,0.0f}, -{0.561178f,-0.827695f,0.0f},{0.515545f,-0.856862f,0.0f},{0.468383f,-0.883526f,0.0f}, -{0.419866f,-0.907586f,0.0f},{0.468401f,-0.883516f,0.0f},{0.370116f,-0.928986f,0.0f}, -{0.419884f,-0.907578f,0.0f},{0.370136f,-0.928977f,0.0f},{0.319279f,-0.947661f,0.0f}, -{0.267507f,-0.963556f,0.0f},{0.319301f,-0.947653f,0.0f},{0.214954f,-0.976624f,0.0f}, -{0.267528f,-0.96355f,0.0f},{0.214973f,-0.97662f,0.0f},{0.16177f,-0.986829f,0.0f}, -{0.108111f,-0.994139f,0.0f},{0.161786f,-0.986826f,0.0f},{0.0538298f,-0.99855f,0.0f}, -{0.108145f,-0.994135f,0.0f},{0.0538045f,-0.998551f,0.0f},{1.19209e-007f,-1.0f,0.0f}, -{0.69564f,-0.718391f,-2.2967e-015f},{0.66431f,-0.747457f,4.30948e-015f},{0.664312f,-0.747455f,-2.35972e-015f}, -{0.725699f,-0.688012f,-2.11837e-015f},{0.7257f,-0.688011f,-4.7761e-015f},{0.754433f,-0.656377f,-3.42054e-015f}, -{0.631769f,-0.775156f,1.02241e-015f},{0.695642f,-0.718389f,1.63365e-016f},{0.631766f,-0.775159f,1.30928e-015f}, -{0.598073f,-0.801442f,-4.02386e-016f},{0.59807f,-0.801444f,3.14782e-015f},{0.563281f,-0.826266f,2.05014e-015f}, -{0.563284f,-0.826264f,2.15457e-016f},{0.527466f,-0.849576f,3.68245e-015f},{0.527463f,-0.849578f,-9.04405e-017f}, -{0.490682f,-0.871339f,2.82586e-015f},{0.453007f,-0.891507f,-1.11336e-015f},{0.490685f,-0.871337f,-3.98744e-016f}, -{0.453005f,-0.891508f,8.87668e-016f},{0.414499f,-0.91005f,3.62163e-016f},{0.414503f,-0.910048f,-2.33213e-015f}, -{0.294734f,-0.955579f,1.39294e-015f},{0.335291f,-0.942115f,1.29026e-015f},{0.294731f,-0.95558f,9.56661e-016f}, -{0.375241f,-0.926927f,3.09815e-015f},{0.375238f,-0.926928f,3.53892e-016f},{0.335293f,-0.942114f,1.78659e-015f}, -{0.253636f,-0.9673f,4.48455e-017f},{0.212075f,-0.977253f,9.31315e-017f},{0.253634f,-0.9673f,-3.87537e-015f}, -{0.212073f,-0.977254f,1.53976e-015f},{0.170124f,-0.985423f,-1.33727e-015f},{0.127866f,-0.991791f,1.31222e-015f}, -{0.127868f,-0.991791f,-1.43479e-015f},{0.170128f,-0.985422f,-1.08544e-015f},{0.0853729f,-0.996349f,-2.96511e-015f}, -{0.0853758f,-0.996349f,1.45956e-015f},{0.0427249f,-0.999087f,-1.45746e-015f},{0.0427275f,-0.999087f,2.97938e-015f}, -{1.41083e-016f,-1.0f,0.0f},{1.54309e-016f,-1.0f,0.0f},{0.781789f,-0.623543f,-8.12728e-016f}, -{0.754434f,-0.656376f,-2.4015e-015f},{0.78179f,-0.623541f,-9.35104e-016f},{0.807717f,-0.589571f,-3.8494e-015f}, -{0.807718f,-0.589569f,8.37214e-016f},{0.832169f,-0.554522f,-3.65599e-015f},{0.855102f,-0.51846f,-4.07623e-015f}, -{0.832171f,-0.554519f,2.81113e-015f},{0.855104f,-0.518456f,2.96789e-016f},{0.876473f,-0.48145f,3.95802e-015f}, -{0.876475f,-0.481448f,6.89284e-016f},{0.896244f,-0.443562f,7.12651e-016f},{0.914377f,-0.404864f,-1.93578e-015f}, -{0.896245f,-0.443559f,5.43092e-015f},{0.914379f,-0.40486f,-5.84661e-015f},{0.930841f,-0.365425f,1.20115e-015f}, -{0.930842f,-0.365423f,3.55128e-015f},{0.945604f,-0.32532f,2.23888e-015f},{0.95864f,-0.284621f,5.39664e-015f}, -{0.945605f,-0.325317f,4.0151e-015f},{0.958641f,-0.284618f,-2.22393e-015f},{0.969926f,-0.243401f,4.33048e-015f}, -{0.969926f,-0.243399f,4.23515e-015f},{0.97944f,-0.201738f,4.2777e-015f},{0.987165f,-0.159705f,5.95984e-015f}, -{0.97944f,-0.201735f,6.68731e-016f},{0.987165f,-0.159703f,-8.70338e-015f},{0.993087f,-0.117381f,-6.76187e-015f}, -{0.993087f,-0.117378f,7.13795e-015f},{0.997195f,-0.0748434f,-4.49833e-016f},{0.999482f,-0.0321679f,5.88869e-015f}, -{0.997196f,-0.07484f,-1.11652e-015f},{0.999483f,-0.0321656f,-2.74195e-016f},{0.999944f,0.0105657f,5.2388e-015f}, -{0.999944f,0.0105686f,-6.15843e-016f},{0.99858f,0.05328f,7.92959e-015f},{0.995391f,0.0958981f,0.0f}, -{0.99858f,0.0532825f,4.50329e-015f},{0.5f,-0.866025f,0.0f},{-0.9999f,-0.0141122f,0.0f}, -{-0.9999f,0.0141124f,0.0f},{-0.9999f,-0.0141125f,0.0f},{-0.999104f,-0.0423259f,0.0f}, -{-0.999104f,-0.0423254f,0.0f},{-0.997511f,-0.0705055f,0.0f},{-0.997511f,-0.0705051f,0.0f}, -{-0.995124f,-0.0986284f,0.0f},{-0.995124f,-0.0986291f,0.0f},{-0.991944f,-0.126674f,0.0f}, -{-0.991944f,-0.126673f,0.0f},{-0.987974f,-0.154618f,0.0f},{-0.987974f,-0.154617f,0.0f}, -{-0.983217f,-0.182438f,0.0f},{-0.983217f,-0.182439f,0.0f},{-0.977677f,-0.210114f,0.0f}, -{-0.977677f,-0.210113f,0.0f},{-0.971358f,-0.237622f,0.0f},{-0.971358f,-0.237622f,0.0f}, -{-0.964265f,-0.26494f,0.0f},{-0.964265f,-0.264941f,0.0f},{-0.956403f,-0.292049f,0.0f}, -{-0.956404f,-0.292048f,0.0f},{-0.94778f,-0.318924f,0.0f},{-0.947781f,-0.318923f,0.0f}, -{-0.938403f,-0.345544f,0.0f},{-0.938402f,-0.345545f,0.0f},{-0.928277f,-0.371891f,0.0f}, -{-0.928277f,-0.37189f,0.0f},{-0.917411f,-0.39794f,0.0f},{-0.917412f,-0.397939f,0.0f}, -{-0.905816f,-0.423672f,0.0f},{-0.905815f,-0.423672f,0.0f},{-0.893498f,-0.449067f,0.0f}, -{-0.893498f,-0.449067f,0.0f},{-0.880469f,-0.474105f,0.0f},{-0.880469f,-0.474104f,0.0f}, -{-0.866738f,-0.498763f,0.0f},{-0.866738f,-0.498764f,0.0f},{-0.852317f,-0.523026f,0.0f}, -{-0.9999f,0.0141122f,0.0f},{-0.999104f,0.0423254f,0.0f},{-0.999104f,0.0423259f,0.0f}, -{-0.997511f,0.0705055f,0.0f},{-0.997511f,0.0705051f,0.0f},{-0.995124f,0.0986291f,0.0f}, -{-0.995124f,0.0986285f,0.0f},{-0.991944f,0.126673f,0.0f},{-0.991944f,0.126674f,0.0f}, -{-0.987974f,0.154618f,0.0f},{-0.987974f,0.154617f,0.0f},{-0.983217f,0.182439f,0.0f}, -{-0.983217f,0.182438f,0.0f},{-0.977677f,0.210113f,0.0f},{-0.977677f,0.210114f,0.0f}, -{-0.971358f,0.237622f,0.0f},{-0.971358f,0.237622f,0.0f},{-0.964265f,0.264941f,0.0f}, -{-0.964265f,0.26494f,0.0f},{-0.956404f,0.292048f,0.0f},{-0.956403f,0.292049f,0.0f}, -{-0.94778f,0.318924f,0.0f},{-0.947781f,0.318923f,0.0f},{-0.938402f,0.345545f,0.0f}, -{-0.938403f,0.345544f,0.0f},{-0.928277f,0.37189f,0.0f},{-0.928277f,0.371891f,0.0f}, -{-0.917411f,0.39794f,0.0f},{-0.917412f,0.397939f,0.0f},{-0.905815f,0.423672f,0.0f}, -{-0.905816f,0.423672f,0.0f},{-0.893498f,0.449067f,0.0f},{-0.893498f,0.449067f,0.0f}, -{-0.880469f,0.474104f,0.0f},{-0.880469f,0.474104f,0.0f},{-0.866738f,0.498764f,0.0f}, -{-0.866738f,0.498764f,0.0f},{-0.852317f,0.523026f,0.0f},{-0.5f,0.866025f,0.0f}, -{-0.5f,0.866025f,-7.6671e-016f},{0.0f,-4.33681e-019f,1.0f},{0.0f,4.33681e-019f,1.0f}, -{-0.884642f,0.466272f,2.20644e-016f},{-0.777982f,0.628286f,5.89571e-016f},{-0.778033f,0.628223f,-5.53502e-016f}, -{-0.957996f,0.286781f,1.48116e-016f},{-0.88468f,0.466199f,-5.1317e-016f},{-0.958053f,0.286593f,-1.63827e-016f}, -{-0.995238f,-0.0974696f,3.44802e-016f},{-0.995356f,0.0962625f,-1.06856e-016f},{-0.995222f,-0.097635f,-4.56953e-017f}, -{-0.995334f,0.0964852f,-1.31963e-016f},{-0.642168f,0.766564f,0.0f},{-0.482138f,0.876095f,-7.37654e-016f}, -{-0.642017f,0.76669f,-1.10523e-015f},{-0.481942f,0.876203f,7.37698e-016f},{-0.303947f,0.952689f,0.0f}, -{-0.303789f,0.952739f,0.0f},{-0.715999f,0.698102f,1.29175e-016f},{-0.945908f,0.324434f,-5.70109e-016f}, -{-0.945908f,0.324434f,-3.35048e-016f},{-0.851699f,0.524032f,7.27349e-016f},{3.33067e-016f,-1.0f,0.0f}, -{0.19489f,-0.980825f,0.0f},{0.194766f,-0.98085f,-8.7013e-016f},{0.707139f,-0.707075f,5.23388e-016f}, -{0.706447f,-0.707766f,5.22876e-016f},{0.555458f,-0.831545f,-6.15467e-016f},{0.554999f,-0.831851f,-4.10782e-016f}, -{0.382212f,-0.924075f,-1.36791e-015f},{0.382504f,-0.923954f,0.0f},{0.98057f,-0.196168f,-1.01605e-015f}, -{0.980872f,-0.194654f,-1.44073e-016f},{0.831655f,-0.555293f,-4.10999e-016f},{0.924088f,-0.382179f,-1.22649e-015f}, -{0.923329f,-0.384009f,-1.99588e-016f},{0.923329f,0.384009f,-2.13958e-016f},{0.831655f,0.555293f,6.67161e-016f}, -{0.924088f,0.382179f,9.40449e-016f},{0.98057f,0.196168f,-7.62016e-016f},{0.980872f,0.194653f,6.1653e-016f}, -{1.0f,2.96059e-016f,-3.28692e-031f},{0.706447f,0.707765f,4.57334e-016f},{0.555458f,0.831545f,8.32431e-017f}, -{0.707139f,0.707075f,-4.57955e-016f},{0.830773f,0.556611f,-3.85076e-016f},{0.554999f,0.831851f,-2.05391e-016f}, -{0.382504f,0.923954f,-2.95917e-016f},{0.19489f,0.980825f,-3.63028e-018f},{0.382212f,0.924075f,5.86375e-016f}, -{0.194766f,0.98085f,-2.22141e-016f},{1.85037e-017f,1.0f,0.0f},{0.830773f,-0.556611f,-1.04527e-016f}, -{2.96059e-016f,-1.0f,0.0f},{1.85037e-017f,-1.0f,0.0f},{0.19489f,-0.980825f,-8.70204e-016f}, -{0.194766f,-0.98085f,7.25975e-016f},{0.707139f,-0.707075f,2.6167e-016f},{0.706447f,-0.707766f,-1.04673e-015f}, -{0.555458f,-0.831545f,6.15467e-016f},{0.382212f,-0.924075f,0.0f},{0.98057f,-0.196168f,-7.25968e-017f}, -{0.980872f,-0.194654f,0.0f},{0.831655f,-0.555293f,2.055e-016f},{0.924088f,-0.382179f,0.0f}, -{0.923329f,-0.384009f,-1.42112e-016f},{0.923329f,0.384009f,7.57929e-018f},{0.831655f,0.555293f,4.10524e-016f}, -{0.924088f,0.382179f,2.41708e-016f},{0.98057f,0.196168f,-1.26994e-016f},{0.980872f,0.194653f,-9.14525e-017f}, -{0.706447f,0.707765f,-5.72353e-016f},{0.555458f,0.831545f,-9.69264e-018f},{0.707139f,0.707075f,1.14487e-016f}, -{0.830773f,0.556611f,5.13819e-016f},{0.554999f,0.831851f,4.97064e-016f},{0.382504f,0.923954f,1.06278e-016f}, -{0.19489f,0.980825f,-1.02781e-015f},{0.382212f,0.924075f,4.37371e-016f},{0.194766f,0.98085f,8.39508e-016f}, -{2.96059e-016f,1.0f,0.0f},{5.92119e-016f,1.0f,0.0f},{0.830773f,-0.556611f,-5.13435e-016f}, -{0.144611f,-0.989489f,-3.80291e-017f},{-0.0759712f,-0.99711f,-5.623e-017f},{0.358149f,-0.933664f,-9.55933e-016f}, -{0.358149f,-0.933664f,1.99014e-016f},{0.549837f,-0.835272f,0.0f},{-0.2878f,-0.957691f,0.0f}, -{-0.54721f,0.836995f,0.0f},{-0.368095f,0.929788f,0.0f},{-0.181963f,0.983305f,0.0f}, -{-1.53707e-012f,1.0f,0.0f},{-8.42952e-008f,1.0f,0.0f},{-0.836995f,0.54721f,0.0f}, -{-0.929788f,0.368095f,0.0f},{-0.983305f,0.181963f,0.0f},{-1.0f,-3.07487e-012f,0.0f}, -{-1.0f,-3.07526e-012f,0.0f},{0.739259f,-0.673422f,0.0f},{0.710614f,-0.703582f,0.0f}, -{0.739259f,-0.673421f,0.0f},{0.766626f,-0.642094f,0.0f},{0.766624f,-0.642096f,0.0f}, -{0.792665f,-0.609658f,0.0f},{0.792663f,-0.60966f,0.0f},{0.817331f,-0.576168f,0.0f}, -{0.817333f,-0.576166f,0.0f},{0.840587f,-0.541677f,0.0f},{0.840585f,-0.54168f,0.0f}, -{0.862386f,-0.506252f,0.0f},{0.862384f,-0.506254f,0.0f},{0.882691f,-0.469953f,0.0f}, -{0.882693f,-0.46995f,0.0f},{0.901473f,-0.432835f,0.0f},{0.901471f,-0.432838f,0.0f}, -{0.918693f,-0.394972f,0.0f},{0.918692f,-0.394974f,0.0f},{0.934323f,-0.356428f,0.0f}, -{0.934324f,-0.356425f,0.0f},{0.948338f,-0.317262f,0.0f},{0.948337f,-0.317264f,0.0f}, -{0.960711f,-0.277549f,0.0f},{0.960711f,-0.277552f,0.0f},{0.971422f,-0.237359f,0.0f}, -{0.971423f,-0.237356f,0.0f},{0.980453f,-0.196753f,0.0f},{0.980453f,-0.196756f,0.0f}, -{0.987787f,-0.155809f,0.0f},{0.987787f,-0.155812f,0.0f},{0.993412f,-0.114599f,0.0f}, -{0.993412f,-0.114596f,0.0f},{0.997318f,-0.0731848f,0.0f},{0.997318f,-0.073187f,0.0f}, -{0.999499f,-0.0316463f,0.0f},{0.999499f,-0.0316489f,0.0f},{0.999951f,0.00994395f,0.0f}, -{0.999951f,0.00994627f,0.0f},{0.998672f,0.0515206f,0.0f},{0.710614f,-0.703582f,0.0f}, -{0.680741f,-0.732525f,0.0f},{0.680739f,-0.732526f,0.0f},{0.649687f,-0.760202f,0.0f}, -{0.649688f,-0.760201f,0.0f},{0.61751f,-0.786563f,0.0f},{0.617513f,-0.786561f,0.0f}, -{0.584268f,-0.811561f,0.0f},{0.584265f,-0.811563f,0.0f},{0.55001f,-0.835158f,0.0f}, -{0.550013f,-0.835156f,0.0f},{0.514803f,-0.857309f,0.0f},{0.514806f,-0.857307f,0.0f}, -{0.478708f,-0.877974f,0.0f},{0.478705f,-0.877976f,0.0f},{0.441779f,-0.897124f,0.0f}, -{0.441782f,-0.897123f,0.0f},{0.404088f,-0.91472f,0.0f},{0.404092f,-0.914719f,0.0f}, -{0.365702f,-0.930732f,0.0f},{0.365699f,-0.930733f,0.0f},{0.326677f,-0.945136f,0.0f}, -{0.326679f,-0.945135f,0.0f},{0.287089f,-0.957904f,0.0f},{0.287092f,-0.957903f,0.0f}, -{0.247008f,-0.969013f,0.0f},{0.247006f,-0.969014f,0.0f},{0.206494f,-0.978448f,0.0f}, -{0.206496f,-0.978447f,0.0f},{0.165625f,-0.986189f,0.0f},{0.165628f,-0.986188f,0.0f}, -{0.124472f,-0.992223f,0.0f},{0.12447f,-0.992223f,0.0f},{0.0830991f,-0.996541f,0.0f}, -{0.0831017f,-0.996541f,0.0f},{0.041585f,-0.999135f,0.0f},{0.0415873f,-0.999135f,0.0f}, -{1.92868e-016f,-1.0f,0.0f},{8.64379e-008f,-1.0f,0.0f},{0.0572333f,-0.998361f,1.89979e-016f}, -{-3.3736e-016f,-1.0f,0.0f},{0.114279f,-0.993449f,0.0f},{0.822154f,-0.569266f,0.0f}, -{0.910446f,-0.413628f,0.0f},{0.821945f,-0.569567f,0.0f},{0.910644f,-0.413191f,0.0f}, -{0.969699f,-0.244303f,0.0f},{0.969779f,-0.243984f,0.0f},{0.997734f,-0.0672808f,0.0f}, -{0.993705f,0.11203f,0.0f},{0.997765f,-0.0668255f,0.0f},{0.957691f,0.2878f,0.0f}, -{0.993663f,0.112396f,0.0f},{0.569266f,-0.822154f,0.0f},{0.569567f,-0.821945f,0.0f}, -{0.413628f,-0.910446f,0.0f},{0.244303f,-0.969699f,0.0f},{0.413191f,-0.910644f,0.0f}, -{0.243985f,-0.969779f,0.0f},{0.0672808f,-0.997734f,0.0f},{0.0668255f,-0.997765f,0.0f}, -{-0.11203f,-0.993705f,0.0f},{-0.112396f,-0.993663f,0.0f},{0.823338f,0.567551f,2.91569e-016f}, -{0.877128f,0.480256f,-1.36506e-015f},{0.877118f,0.480275f,1.00957e-015f},{0.823334f,0.567558f,5.00925e-017f}, -{0.760897f,0.648872f,1.44361e-016f},{0.921684f,0.387941f,1.25621e-016f},{0.921695f,0.387915f,6.82191e-016f}, -{0.956563f,0.291525f,-6.81027e-016f},{0.956571f,0.291499f,-7.61943e-016f},{0.981386f,0.192047f,6.553e-016f}, -{0.98139f,0.192025f,1.77659e-017f},{0.995897f,0.0904984f,-8.37279e-018f},{0.995893f,0.0905325f,-1.67519e-017f}, -{0.999929f,-0.0119218f,1.48019e-015f},{0.993449f,-0.114279f,0.0f},{0.999926f,-0.0121699f,0.0f}, -{0.690461f,0.723369f,-9.58068e-017f},{0.760892f,0.648879f,1.7081e-016f},{0.690446f,0.723384f,-1.49808e-016f}, -{0.612765f,0.790265f,1.16954e-016f},{0.612743f,0.790282f,-1.7266e-016f},{0.528625f,0.848856f,3.32998e-016f}, -{0.438929f,0.898522f,-5.4393e-016f},{0.528601f,0.84887f,4.57239e-016f},{0.438908f,0.898532f,-2.60926e-016f}, -{0.344602f,0.938749f,1.75687e-016f},{0.34457f,0.938761f,5.73784e-016f},{0.246664f,0.969101f,-5.54286e-016f}, -{0.146104f,0.989269f,0.0f},{0.246424f,0.969162f,-8.55909e-016f},{-0.505064f,0.863082f,-2.96041e-016f}, -{-0.342733f,0.939433f,-1.39064e-015f},{-0.653412f,0.757002f,-4.80673e-016f},{-0.174993f,0.98457f,-7.12538e-016f}, -{-0.00988645f,0.999951f,0.0f},{-0.780028f,0.625744f,-1.42742e-017f},{-0.879277f,0.47631f,-1.99991e-016f}, -{-0.948437f,0.316965f,-3.53543e-016f},{-0.987776f,0.155878f,8.15532e-017f},{-1.0f,1.95899e-012f,0.0f}, -{-1.0f,1.95907e-012f,0.0f},{0.181963f,0.983305f,0.0f},{4.18691e-016f,1.0f,0.0f}, -{2.09346e-016f,1.0f,0.0f},{0.707107f,0.707107f,0.0f},{0.54721f,0.836995f,0.0f}, -{0.368095f,0.929788f,0.0f},{0.929788f,0.368095f,0.0f},{0.983305f,0.181963f,0.0f}, -{0.836995f,0.54721f,0.0f},{1.0f,2.61682e-016f,0.0f},{1.0f,8.42937e-008f,0.0f}, -{0.901678f,0.432409f,-4.8007e-016f},{0.823027f,0.568002f,1.63014e-016f},{0.957351f,0.288928f,2.01882e-015f}, -{0.957351f,0.288928f,0.0f},{0.989708f,0.143098f,7.32531e-016f},{0.72348f,0.690346f,-1.05257e-015f}, -{1.0f,4.36853e-016f,0.0f},{1.0f,9.28313e-016f,0.0f},{0.60671f,0.794923f,-3.38738e-016f}, -{0.477546f,0.878607f,-8.64155e-016f},{0.341342f,0.939939f,-3.74916e-016f},{0.203325f,0.979111f,0.0f}, -{0.791675f,0.610942f,0.0f},{0.765522f,0.64341f,0.0f},{0.738038f,0.674759f,0.0f}, -{0.765522f,0.643409f,0.0f},{0.709271f,0.704936f,0.0f},{0.738039f,0.674758f,0.0f}, -{0.709273f,0.704934f,0.0f},{0.679272f,0.733887f,0.0f},{0.648092f,0.761562f,0.0f}, -{0.679273f,0.733885f,0.0f},{0.615785f,0.787914f,0.0f},{0.648094f,0.761561f,0.0f}, -{0.615787f,0.787913f,0.0f},{0.582409f,0.812896f,0.0f},{0.54802f,0.836465f,0.0f}, -{0.58241f,0.812895f,0.0f},{0.512678f,0.858581f,0.0f},{0.548021f,0.836464f,0.0f}, -{0.51268f,0.85858f,0.0f},{0.476445f,0.879204f,0.0f},{0.439385f,0.898299f,0.0f}, -{0.476447f,0.879203f,0.0f},{0.40156f,0.915833f,0.0f},{0.439387f,0.898298f,0.0f}, -{0.401562f,0.915832f,0.0f},{0.363038f,0.931774f,0.0f},{0.323885f,0.946097f,0.0f}, -{0.36304f,0.931774f,0.0f},{0.284168f,0.958774f,0.0f},{0.323886f,0.946096f,0.0f}, -{0.28417f,0.958774f,0.0f},{0.243959f,0.969786f,0.0f},{0.24396f,0.969785f,0.0f}, -{0.816453f,0.577412f,0.0f},{0.816452f,0.577413f,0.0f},{0.839811f,0.542879f,0.0f}, -{0.861709f,0.507402f,0.0f},{0.83981f,0.54288f,0.0f},{0.88211f,0.471044f,0.0f}, -{0.861708f,0.507404f,0.0f},{0.882109f,0.471046f,0.0f},{0.900977f,0.433866f,0.0f}, -{0.918278f,0.395935f,0.0f},{0.900976f,0.433869f,0.0f},{0.933984f,0.357316f,0.0f}, -{0.918278f,0.395937f,0.0f},{0.933983f,0.357318f,0.0f},{0.948065f,0.318075f,0.0f}, -{0.960499f,0.278282f,0.0f},{0.948065f,0.318077f,0.0f},{0.971264f,0.238005f,0.0f}, -{0.960499f,0.278284f,0.0f},{0.971263f,0.238007f,0.0f},{0.98034f,0.197314f,0.0f}, -{0.987713f,0.15628f,0.0f},{0.98034f,0.197316f,0.0f},{0.993368f,0.114975f,0.0f}, -{0.987712f,0.156283f,0.0f},{0.993368f,0.114977f,0.0f},{0.997297f,0.0734701f,0.0f}, -{0.999493f,0.0318375f,0.0f},{0.997297f,0.0734722f,0.0f},{0.999951f,-0.00985025f,0.0f}, -{0.999493f,0.0318392f,0.0f},{0.999951f,-0.00984923f,0.0f},{0.998672f,-0.0515206f,0.0f}, -{0.5f,0.866025f,-4.07254e-016f},{-0.997498f,0.0706974f,4.22047e-015f},{-0.999099f,0.042441f,-4.49972e-015f}, -{-0.999099f,0.0424415f,-8.87378e-015f},{-0.9999f,-0.0141508f,-1.48015e-015f},{-0.9999f,0.014151f,0.0f}, -{-0.9999f,0.0141508f,-7.42169e-015f},{-0.997498f,0.0706979f,1.47659e-015f},{-0.995098f,0.0988972f,5.89216e-015f}, -{-0.995098f,0.0988976f,5.59937e-015f},{-0.9919f,0.127018f,-1.17465e-014f},{-0.9919f,0.127018f,-1.72436e-014f}, -{-0.987909f,0.155036f,-5.3906e-015f},{-0.987909f,0.155037f,5.84959e-015f},{-0.983126f,0.182932f,-2.36905e-015f}, -{-0.983126f,0.182931f,8.73191e-015f},{-0.971202f,0.238259f,8.626e-015f},{-0.96407f,0.265648f,-7.28139e-015f}, -{-0.96407f,0.265647f,-1.29898e-014f},{-0.977555f,0.210679f,-4.54082e-015f},{-0.977555f,0.21068f,0.0f}, -{-0.971202f,0.238258f,-1.29121e-014f},{-0.956167f,0.292823f,-1.73386e-015f},{-0.956167f,0.292823f,0.0f}, -{-0.947497f,0.319764f,5.61031e-015f},{-0.947497f,0.319764f,-1.89338e-015f},{-0.938069f,0.346449f,0.0f}, -{-0.938069f,0.346449f,7.60587e-015f},{-0.927889f,0.372856f,9.90971e-015f},{-0.905308f,0.424755f,5.3605e-015f}, -{-0.905309f,0.424755f,3.304e-016f},{-0.916966f,0.398966f,4.7247e-015f},{-0.916966f,0.398965f,5.42953e-015f}, -{-0.927889f,0.372857f,-7.70196e-015f},{-0.892926f,0.450204f,0.0f},{-0.892926f,0.450204f,5.33148e-015f}, -{-0.879828f,0.475292f,1.04193e-014f},{-0.879828f,0.475292f,1.04193e-014f},{-0.866025f,0.5f,0.0f}, -{-0.9999f,-0.014151f,8.90184e-015f},{-0.999099f,-0.042441f,-1.04784e-014f},{-0.999099f,-0.0424415f,-1.61429e-014f}, -{-0.997498f,-0.0706974f,8.65025e-015f},{-0.995098f,-0.0988972f,2.94608e-015f},{-0.997498f,-0.0706979f,-1.09175e-014f}, -{-0.995098f,-0.0988976f,1.39984e-015f},{-0.9919f,-0.127018f,-1.06363e-014f},{-0.9919f,-0.127018f,9.63801e-015f}, -{-0.987909f,-0.155036f,-7.40539e-015f},{-0.983126f,-0.182931f,-7.57272e-015f},{-0.987909f,-0.155037f,-2.5165e-015f}, -{-0.983126f,-0.182932f,2.18298e-015f},{-0.977555f,-0.210679f,7.64703e-015f},{-0.977555f,-0.21068f,-4.23518e-015f}, -{-0.971202f,-0.238258f,-1.03144e-014f},{-0.96407f,-0.265647f,-7.60334e-015f},{-0.971202f,-0.238259f,1.75636e-015f}, -{-0.96407f,-0.265648f,1.0869e-014f},{-0.956167f,-0.292823f,5.12754e-015f},{-0.956167f,-0.292823f,-8.24033e-015f}, -{-0.947497f,-0.319764f,3.07966e-016f},{-0.938069f,-0.346449f,-1.05337e-014f},{-0.947497f,-0.319764f,-8.2576e-015f}, -{-0.938069f,-0.346449f,-1.87656e-015f},{-0.927889f,-0.372856f,3.1746e-015f},{-0.927889f,-0.372857f,-3.31849e-015f}, -{-0.916966f,-0.398965f,3.06056e-015f},{-0.905309f,-0.424755f,7.49538e-015f},{-0.916966f,-0.398966f,4.02549e-015f}, -{-0.905308f,-0.424755f,1.46943e-015f},{-0.892926f,-0.450204f,-1.18685e-014f},{-0.892926f,-0.450204f,1.25672e-015f}, -{-0.879828f,-0.475292f,4.58408e-015f},{-0.866025f,-0.5f,0.0f},{-0.879828f,-0.475292f,1.83809e-015f}, -{-0.78179f,-0.623541f,-1.15728e-015f},{-0.807718f,-0.589568f,-2.39133e-015f},{-0.807717f,-0.589571f,9.60223e-017f}, -{-0.754434f,-0.656376f,-5.72909e-015f},{-0.754433f,-0.656377f,-7.23689e-015f},{-0.7257f,-0.688011f,1.01846e-015f}, -{-0.832169f,-0.554522f,1.64171e-015f},{-0.781789f,-0.623543f,4.8494e-015f},{-0.832171f,-0.554519f,4.10543e-015f}, -{-0.855102f,-0.51846f,-9.96661e-016f},{-0.855104f,-0.518456f,1.53494e-015f},{-0.876475f,-0.481448f,-5.18977e-015f}, -{-0.876473f,-0.48145f,-4.02026e-015f},{-0.896244f,-0.443562f,-2.65341e-015f},{-0.896245f,-0.443559f,-3.96662e-015f}, -{-0.914379f,-0.40486f,0.0f},{-0.930841f,-0.365425f,0.0f},{-0.914377f,-0.404864f,-2.39728e-015f}, -{-0.930842f,-0.365423f,0.0f},{-0.945605f,-0.325317f,-3.67284e-015f},{-0.945604f,-0.32532f,0.0f}, -{-0.97944f,-0.201738f,3.58358e-015f},{-0.969926f,-0.243399f,-1.44121e-015f},{-0.97944f,-0.201735f,-3.41043e-015f}, -{-0.95864f,-0.284621f,7.36158e-015f},{-0.958641f,-0.284618f,-5.6763e-015f},{-0.969926f,-0.243401f,5.74311e-015f}, -{-0.987165f,-0.159705f,9.45645e-016f},{-0.993087f,-0.117381f,-1.03704e-014f},{-0.987165f,-0.159703f,-4.89956e-015f}, -{-0.993087f,-0.117378f,-6.9502e-016f},{-0.997196f,-0.07484f,0.0f},{-0.999483f,-0.0321655f,6.29904e-015f}, -{-0.999482f,-0.032168f,-5.91813e-015f},{-0.997195f,-0.0748434f,-8.86324e-016f},{-0.999944f,0.0105685f,-5.7957e-015f}, -{-0.999944f,0.0105657f,5.92086e-015f},{-0.99858f,0.0532826f,0.0f},{-0.99858f,0.05328f,0.0f}, -{-0.995391f,0.0958981f,0.0f},{-0.695642f,-0.718389f,-2.12686e-015f},{-0.725699f,-0.688012f,-3.16696e-015f}, -{-0.69564f,-0.718391f,6.73571e-017f},{-0.664312f,-0.747455f,3.69231e-016f},{-0.66431f,-0.747457f,-4.91688e-015f}, -{-0.631769f,-0.775156f,-3.61476e-016f},{-0.598073f,-0.801442f,-8.85326e-016f},{-0.631767f,-0.775159f,-5.10676e-016f}, -{-0.59807f,-0.801444f,-2.51436e-015f},{-0.563284f,-0.826264f,-2.63707e-016f},{-0.563281f,-0.826266f,-4.79448e-015f}, -{-0.527466f,-0.849576f,2.47204e-015f},{-0.490685f,-0.871337f,-7.45068e-016f},{-0.527463f,-0.849578f,6.28814e-016f}, -{-0.490682f,-0.871339f,-4.66609e-016f},{-0.453007f,-0.891507f,-5.36872e-018f},{-0.453005f,-0.891508f,1.90646e-015f}, -{-0.414503f,-0.910048f,-9.01947e-016f},{-0.375241f,-0.926927f,-7.55498e-016f},{-0.414499f,-0.91005f,-3.44627e-015f}, -{-0.375238f,-0.926928f,-8.26493e-018f},{-0.335293f,-0.942114f,7.4317e-016f},{-0.335291f,-0.942115f,-1.38718e-015f}, -{-0.294734f,-0.955579f,-6.60361e-018f},{-0.253636f,-0.9673f,1.39186e-016f},{-0.294731f,-0.95558f,-4.80822e-016f}, -{-0.253634f,-0.9673f,-1.1694e-015f},{-0.212076f,-0.977253f,-1.09093e-015f},{-0.212073f,-0.977254f,-1.42807e-015f}, -{-0.170128f,-0.985422f,-8.58064e-016f},{-0.127868f,-0.991791f,1.21011e-015f},{-0.170124f,-0.985423f,3.47036e-015f}, -{-0.127866f,-0.991791f,2.85545e-016f},{-0.0853758f,-0.996349f,-4.87227e-016f},{-0.0853729f,-0.996349f,3.21028e-015f}, -{-0.0427275f,-0.999087f,-3.76158e-016f},{-1.41083e-016f,-1.0f,0.0f},{-0.0427249f,-0.999087f,-2.9625e-015f}, -{-1.54309e-016f,-1.0f,0.0f},{-1.0f,-5.04647e-017f,0.0f},{-1.0f,-5.3829e-017f,0.0f}, -{-0.998532f,-0.0541567f,0.0f},{-0.994135f,-0.108145f,0.0f},{-0.998534f,-0.0541301f,0.0f}, -{-0.986822f,-0.161808f,0.0f},{-0.99414f,-0.108105f,0.0f},{-0.986829f,-0.161767f,0.0f}, -{-0.976616f,-0.214992f,0.0f},{-0.963545f,-0.267546f,0.0f},{-0.976622f,-0.214964f,0.0f}, -{-0.947644f,-0.319328f,0.0f},{-0.963549f,-0.267531f,0.0f},{-0.947653f,-0.319303f,0.0f}, -{-0.928963f,-0.370172f,0.0f},{-0.90756f,-0.419923f,0.0f},{-0.928977f,-0.370136f,0.0f}, -{-0.883495f,-0.46844f,0.0f},{-0.907577f,-0.419887f,0.0f},{-0.883512f,-0.468409f,0.0f}, -{-0.856841f,-0.515581f,0.0f},{-0.827674f,-0.56121f,0.0f},{-0.856854f,-0.515559f,0.0f}, -{-0.796076f,-0.605197f,0.0f},{-0.827681f,-0.561199f,0.0f},{-0.796082f,-0.605188f,0.0f}, -{-0.762141f,-0.647411f,0.0f},{-0.725973f,-0.687723f,0.0f},{-0.762151f,-0.6474f,0.0f}, -{-0.687676f,-0.726018f,0.0f},{-0.725983f,-0.687712f,0.0f},{-0.687687f,-0.726007f,0.0f}, -{-0.647361f,-0.762183f,0.0f},{-0.605148f,-0.796113f,0.0f},{-0.647375f,-0.762171f,0.0f}, -{-0.56116f,-0.827707f,0.0f},{-0.605164f,-0.796101f,0.0f},{-0.561178f,-0.827695f,0.0f}, -{-0.515527f,-0.856873f,0.0f},{-0.468383f,-0.883526f,0.0f},{-0.515545f,-0.856862f,0.0f}, -{-0.419866f,-0.907586f,0.0f},{-0.4684f,-0.883516f,0.0f},{-0.419884f,-0.907578f,0.0f}, -{-0.370116f,-0.928986f,0.0f},{-0.319279f,-0.947661f,0.0f},{-0.370136f,-0.928977f,0.0f}, -{-0.267507f,-0.963556f,0.0f},{-0.319301f,-0.947653f,0.0f},{-0.267528f,-0.96355f,0.0f}, -{-0.214954f,-0.976624f,0.0f},{-0.16177f,-0.986829f,0.0f},{-0.214973f,-0.97662f,0.0f}, -{-0.108111f,-0.994139f,0.0f},{-0.161786f,-0.986826f,0.0f},{-0.108145f,-0.994135f,0.0f}, -{-0.0538298f,-0.99855f,0.0f},{2.15316e-016f,-1.0f,0.0f},{-0.0538044f,-0.998551f,0.0f}, -{2.35502e-016f,-1.0f,0.0f},{-0.998532f,0.0541566f,0.0f},{-0.998534f,0.0541302f,0.0f}, -{-0.994135f,0.108145f,0.0f},{-0.986822f,0.161808f,0.0f},{-0.99414f,0.108105f,0.0f}, -{-0.976616f,0.214992f,0.0f},{-0.986829f,0.161767f,0.0f},{-0.976622f,0.214964f,0.0f}, -{-0.963545f,0.267546f,0.0f},{-0.947644f,0.319328f,0.0f},{-0.963549f,0.267531f,0.0f}, -{-0.928963f,0.370172f,0.0f},{-0.947653f,0.319303f,0.0f},{-0.928977f,0.370136f,0.0f}, -{-0.90756f,0.419923f,0.0f},{-0.883495f,0.46844f,0.0f},{-0.907577f,0.419887f,0.0f}, -{-0.856841f,0.515581f,0.0f},{-0.883512f,0.468409f,0.0f},{-0.856854f,0.515559f,0.0f}, -{-0.827674f,0.56121f,0.0f},{-0.796076f,0.605197f,0.0f},{-0.827681f,0.561199f,0.0f}, -{-0.762141f,0.647411f,0.0f},{-0.796082f,0.605188f,0.0f},{-0.762151f,0.6474f,0.0f}, -{-0.725973f,0.687723f,0.0f},{-0.687676f,0.726018f,0.0f},{-0.725983f,0.687712f,0.0f}, -{-0.647361f,0.762183f,0.0f},{-0.687687f,0.726007f,0.0f},{-0.647375f,0.762171f,0.0f}, -{-0.605148f,0.796113f,0.0f},{-0.56116f,0.827707f,0.0f},{-0.605164f,0.796101f,0.0f}, -{-0.515527f,0.856873f,0.0f},{-0.561178f,0.827695f,0.0f},{-0.515545f,0.856862f,0.0f}, -{-0.468383f,0.883526f,0.0f},{-0.419866f,0.907586f,0.0f},{-0.468401f,0.883516f,0.0f}, -{-0.370116f,0.928986f,0.0f},{-0.419884f,0.907578f,0.0f},{-0.370136f,0.928977f,0.0f}, -{-0.319279f,0.947661f,0.0f},{-0.267507f,0.963556f,0.0f},{-0.319301f,0.947653f,0.0f}, -{-0.214954f,0.976624f,0.0f},{-0.267528f,0.96355f,0.0f},{-0.214973f,0.97662f,0.0f}, -{-0.16177f,0.986829f,0.0f},{-0.108111f,0.994139f,0.0f},{-0.161786f,0.986826f,0.0f}, -{-0.0538298f,0.99855f,0.0f},{-0.108145f,0.994135f,0.0f},{-0.0538045f,0.998551f,0.0f}, -{-1.19209e-007f,1.0f,0.0f},{-0.69564f,0.718391f,-2.2967e-015f},{-0.66431f,0.747457f,4.30948e-015f}, -{-0.664312f,0.747455f,-2.35972e-015f},{-0.725699f,0.688012f,-2.11837e-015f},{-0.7257f,0.688011f,-4.7761e-015f}, -{-0.754433f,0.656377f,-3.42054e-015f},{-0.631769f,0.775156f,1.02241e-015f},{-0.695642f,0.718389f,1.63365e-016f}, -{-0.631766f,0.775159f,1.30928e-015f},{-0.598073f,0.801442f,-4.02386e-016f},{-0.59807f,0.801444f,3.14782e-015f}, -{-0.563281f,0.826266f,2.05014e-015f},{-0.563284f,0.826264f,2.15457e-016f},{-0.527466f,0.849576f,3.68245e-015f}, -{-0.527463f,0.849578f,-9.04405e-017f},{-0.490682f,0.871339f,2.82586e-015f},{-0.453007f,0.891507f,-1.11336e-015f}, -{-0.490685f,0.871337f,-3.98744e-016f},{-0.453005f,0.891508f,8.87668e-016f},{-0.414499f,0.91005f,3.62163e-016f}, -{-0.414503f,0.910048f,-2.33213e-015f},{-0.294734f,0.955579f,1.39294e-015f},{-0.335291f,0.942115f,1.29026e-015f}, -{-0.294731f,0.95558f,9.56661e-016f},{-0.375241f,0.926927f,3.09815e-015f},{-0.375238f,0.926928f,3.53892e-016f}, -{-0.335293f,0.942114f,1.78659e-015f},{-0.253636f,0.9673f,4.48455e-017f},{-0.212075f,0.977253f,9.31315e-017f}, -{-0.253634f,0.9673f,-3.87537e-015f},{-0.212073f,0.977254f,1.53976e-015f},{-0.170124f,0.985423f,-1.33727e-015f}, -{-0.127866f,0.991791f,1.31222e-015f},{-0.127868f,0.991791f,-1.43479e-015f},{-0.170128f,0.985422f,-1.08544e-015f}, -{-0.0853729f,0.996349f,-2.96511e-015f},{-0.0853758f,0.996349f,1.45956e-015f},{-0.0427249f,0.999087f,-1.45746e-015f}, -{-0.0427275f,0.999087f,2.97938e-015f},{-1.41083e-016f,1.0f,0.0f},{-1.54309e-016f,1.0f,0.0f}, -{-0.781789f,0.623543f,-8.12728e-016f},{-0.754434f,0.656376f,-2.4015e-015f},{-0.78179f,0.623541f,-9.35104e-016f}, -{-0.807717f,0.589571f,-3.8494e-015f},{-0.807718f,0.589569f,8.37214e-016f},{-0.832169f,0.554522f,-3.65599e-015f}, -{-0.855102f,0.51846f,-4.07623e-015f},{-0.832171f,0.554519f,2.81113e-015f},{-0.855104f,0.518456f,2.96789e-016f}, -{-0.876473f,0.48145f,3.95802e-015f},{-0.876475f,0.481448f,6.89284e-016f},{-0.896244f,0.443562f,7.12651e-016f}, -{-0.914377f,0.404864f,-1.93578e-015f},{-0.896245f,0.443559f,5.43092e-015f},{-0.914379f,0.40486f,-5.84661e-015f}, -{-0.930841f,0.365425f,1.20115e-015f},{-0.930842f,0.365423f,3.55128e-015f},{-0.945604f,0.32532f,2.23888e-015f}, -{-0.95864f,0.284621f,5.39664e-015f},{-0.945605f,0.325317f,4.0151e-015f},{-0.958641f,0.284618f,-2.22393e-015f}, -{-0.969926f,0.243401f,4.33048e-015f},{-0.969926f,0.243399f,4.23515e-015f},{-0.97944f,0.201738f,4.2777e-015f}, -{-0.987165f,0.159705f,5.95984e-015f},{-0.97944f,0.201735f,6.68731e-016f},{-0.987165f,0.159703f,-8.70338e-015f}, -{-0.993087f,0.117381f,-6.76187e-015f},{-0.993087f,0.117378f,7.13795e-015f},{-0.997195f,0.0748434f,-4.49833e-016f}, -{-0.999482f,0.0321679f,5.88869e-015f},{-0.997196f,0.07484f,-1.11652e-015f},{-0.999483f,0.0321656f,-2.74195e-016f}, -{-0.999944f,-0.0105657f,5.2388e-015f},{-0.999944f,-0.0105686f,-6.15843e-016f},{-0.99858f,-0.05328f,7.92959e-015f}, -{-0.995391f,-0.0958981f,0.0f},{-0.99858f,-0.0532825f,4.50329e-015f},{0.9999f,0.0141122f,0.0f}, -{0.9999f,-0.0141124f,0.0f},{0.9999f,0.0141125f,0.0f},{0.999104f,0.0423259f,0.0f}, -{0.999104f,0.0423254f,0.0f},{0.997511f,0.0705055f,0.0f},{0.997511f,0.0705051f,0.0f}, -{0.995124f,0.0986284f,0.0f},{0.995124f,0.0986291f,0.0f},{0.991944f,0.126674f,0.0f}, -{0.991944f,0.126673f,0.0f},{0.987974f,0.154618f,0.0f},{0.987974f,0.154617f,0.0f}, -{0.983217f,0.182438f,0.0f},{0.983217f,0.182439f,0.0f},{0.977677f,0.210114f,0.0f}, -{0.977677f,0.210113f,0.0f},{0.971358f,0.237622f,0.0f},{0.971358f,0.237622f,0.0f}, -{0.964265f,0.26494f,0.0f},{0.964265f,0.264941f,0.0f},{0.956403f,0.292049f,0.0f}, -{0.956404f,0.292048f,0.0f},{0.94778f,0.318924f,0.0f},{0.947781f,0.318923f,0.0f}, -{0.938403f,0.345544f,0.0f},{0.938402f,0.345545f,0.0f},{0.928277f,0.371891f,0.0f}, -{0.928277f,0.37189f,0.0f},{0.917411f,0.39794f,0.0f},{0.917412f,0.397939f,0.0f}, -{0.905816f,0.423672f,0.0f},{0.905815f,0.423672f,0.0f},{0.893498f,0.449067f,0.0f}, -{0.893498f,0.449067f,0.0f},{0.880469f,0.474105f,0.0f},{0.880469f,0.474104f,0.0f}, -{0.866738f,0.498763f,0.0f},{0.866738f,0.498764f,0.0f},{0.852317f,0.523026f,0.0f}, -{0.9999f,-0.0141122f,0.0f},{0.999104f,-0.0423254f,0.0f},{0.999104f,-0.0423259f,0.0f}, -{0.997511f,-0.0705055f,0.0f},{0.997511f,-0.0705051f,0.0f},{0.995124f,-0.0986291f,0.0f}, -{0.995124f,-0.0986285f,0.0f},{0.991944f,-0.126673f,0.0f},{0.991944f,-0.126674f,0.0f}, -{0.987974f,-0.154618f,0.0f},{0.987974f,-0.154617f,0.0f},{0.983217f,-0.182439f,0.0f}, -{0.983217f,-0.182438f,0.0f},{0.977677f,-0.210113f,0.0f},{0.977677f,-0.210114f,0.0f}, -{0.971358f,-0.237622f,0.0f},{0.971358f,-0.237622f,0.0f},{0.964265f,-0.264941f,0.0f}, -{0.964265f,-0.26494f,0.0f},{0.956404f,-0.292048f,0.0f},{0.956403f,-0.292049f,0.0f}, -{0.94778f,-0.318924f,0.0f},{0.947781f,-0.318923f,0.0f},{0.938402f,-0.345545f,0.0f}, -{0.938403f,-0.345544f,0.0f},{0.928277f,-0.37189f,0.0f},{0.928277f,-0.371891f,0.0f}, -{0.917411f,-0.39794f,0.0f},{0.917412f,-0.397939f,0.0f},{0.905815f,-0.423672f,0.0f}, -{0.905816f,-0.423672f,0.0f},{0.893498f,-0.449067f,0.0f},{0.893498f,-0.449067f,0.0f}, -{0.880469f,-0.474104f,0.0f},{0.880469f,-0.474104f,0.0f},{0.866738f,-0.498764f,0.0f}, -{0.866738f,-0.498764f,0.0f},{0.852317f,-0.523026f,0.0f},{0.5f,-0.866025f,-7.6671e-016f}, -{0.884642f,-0.466272f,2.20644e-016f},{0.777982f,-0.628286f,5.89571e-016f},{0.778033f,-0.628223f,-5.53502e-016f}, -{0.957996f,-0.286781f,1.48116e-016f},{0.88468f,-0.466199f,-5.1317e-016f},{0.958053f,-0.286593f,-1.63827e-016f}, -{0.995238f,0.0974696f,3.44802e-016f},{0.995356f,-0.0962625f,-1.06856e-016f},{0.995222f,0.097635f,-4.56953e-017f}, -{0.995334f,-0.0964852f,-1.31963e-016f},{0.642168f,-0.766564f,0.0f},{0.482138f,-0.876095f,-7.37654e-016f}, -{0.642017f,-0.76669f,-1.10523e-015f},{0.481942f,-0.876203f,7.37698e-016f},{0.303947f,-0.952689f,0.0f}, -{0.303789f,-0.952739f,0.0f},{0.715999f,-0.698102f,1.29175e-016f},{0.945908f,-0.324434f,-5.70109e-016f}, -{0.945908f,-0.324434f,-3.35048e-016f},{0.851699f,-0.524032f,7.27349e-016f},{0.194654f,0.980872f,-1.44073e-016f}, -{-2.96059e-016f,1.0f,-3.28692e-031f},{-0.384009f,0.923329f,-2.13958e-016f},{-0.382179f,0.924088f,9.40449e-016f}, -{-0.196168f,0.98057f,-7.62016e-016f},{-0.194653f,0.980872f,6.1653e-016f},{-0.555293f,0.831655f,6.67161e-016f}, -{-0.707075f,0.707139f,-4.57955e-016f},{-0.707765f,0.706447f,4.57334e-016f},{-0.831545f,0.555458f,8.32431e-017f}, -{-0.831851f,0.554999f,-2.05391e-016f},{-0.556611f,0.830773f,-3.85076e-016f},{-0.980825f,0.19489f,-3.63028e-018f}, -{-0.98085f,0.194766f,-2.22141e-016f},{-0.924075f,0.382212f,5.86375e-016f},{-0.923954f,0.382504f,-2.95917e-016f}, -{-1.0f,1.85037e-017f,0.0f},{0.196168f,0.98057f,-1.01605e-015f},{0.382179f,0.924088f,-1.22649e-015f}, -{0.384009f,0.923329f,-1.99588e-016f},{0.556611f,0.830773f,-1.04527e-016f},{0.555293f,0.831655f,-4.10999e-016f}, -{0.707766f,0.706447f,5.22876e-016f},{0.707075f,0.707139f,5.23388e-016f},{0.831545f,0.555458f,-6.15467e-016f}, -{0.831851f,0.554999f,-4.10782e-016f},{0.924075f,0.382212f,-1.36791e-015f},{0.98085f,0.194766f,-8.7013e-016f}, -{1.0f,3.33067e-016f,0.0f},{1.0f,2.96059e-016f,0.0f},{0.194654f,0.980872f,0.0f}, -{-0.384009f,0.923329f,7.57929e-018f},{-0.382179f,0.924088f,2.41708e-016f},{-0.196168f,0.98057f,-1.26994e-016f}, -{-0.194653f,0.980872f,-9.14525e-017f},{-0.555293f,0.831655f,4.10524e-016f},{-0.707075f,0.707139f,1.14487e-016f}, -{-0.707765f,0.706447f,-5.72353e-016f},{-0.831545f,0.555458f,-9.69264e-018f},{-0.831851f,0.554999f,4.97064e-016f}, -{-0.556611f,0.830773f,5.13819e-016f},{-1.0f,2.96059e-016f,0.0f},{-0.980825f,0.19489f,-1.02781e-015f}, -{-0.98085f,0.194766f,8.39508e-016f},{-0.924075f,0.382212f,4.37371e-016f},{-0.923954f,0.382504f,1.06278e-016f}, -{-1.0f,5.92119e-016f,0.0f},{0.196168f,0.98057f,-7.25968e-017f},{0.382179f,0.924088f,0.0f}, -{0.384009f,0.923329f,-1.42112e-016f},{0.556611f,0.830773f,-5.13435e-016f},{0.555293f,0.831655f,2.055e-016f}, -{0.707766f,0.706447f,-1.04673e-015f},{0.707075f,0.707139f,2.6167e-016f},{0.831545f,0.555458f,6.15467e-016f}, -{0.98085f,0.194766f,7.25975e-016f},{0.980825f,0.19489f,-8.70204e-016f},{1.0f,1.85037e-017f,0.0f}, -{0.989489f,0.144611f,-3.80291e-017f},{0.99711f,-0.0759712f,-5.623e-017f},{0.933664f,0.358149f,-9.55933e-016f}, -{0.933664f,0.358149f,1.99014e-016f},{0.835272f,0.549837f,0.0f},{0.957691f,-0.2878f,0.0f}, -{-1.0f,-1.53707e-012f,0.0f},{-1.0f,-8.42952e-008f,0.0f},{3.07487e-012f,-1.0f,0.0f}, -{3.07526e-012f,-1.0f,0.0f},{0.673422f,0.739259f,0.0f},{0.703582f,0.710614f,0.0f}, -{0.673421f,0.739259f,0.0f},{0.642094f,0.766626f,0.0f},{0.642096f,0.766624f,0.0f}, -{0.609658f,0.792665f,0.0f},{0.60966f,0.792663f,0.0f},{0.576168f,0.817331f,0.0f}, -{0.576166f,0.817333f,0.0f},{0.541677f,0.840587f,0.0f},{0.54168f,0.840585f,0.0f}, -{0.506252f,0.862386f,0.0f},{0.506254f,0.862384f,0.0f},{0.469953f,0.882691f,0.0f}, -{0.46995f,0.882693f,0.0f},{0.432835f,0.901473f,0.0f},{0.432838f,0.901471f,0.0f}, -{0.394972f,0.918693f,0.0f},{0.394974f,0.918692f,0.0f},{0.356428f,0.934323f,0.0f}, -{0.356425f,0.934324f,0.0f},{0.317262f,0.948338f,0.0f},{0.317264f,0.948337f,0.0f}, -{0.277549f,0.960711f,0.0f},{0.277552f,0.960711f,0.0f},{0.237359f,0.971422f,0.0f}, -{0.237356f,0.971423f,0.0f},{0.196753f,0.980453f,0.0f},{0.196756f,0.980453f,0.0f}, -{0.155809f,0.987787f,0.0f},{0.155812f,0.987787f,0.0f},{0.114599f,0.993412f,0.0f}, -{0.114596f,0.993412f,0.0f},{0.0731848f,0.997318f,0.0f},{0.073187f,0.997318f,0.0f}, -{0.0316463f,0.999499f,0.0f},{0.0316489f,0.999499f,0.0f},{-0.00994395f,0.999951f,0.0f}, -{-0.00994627f,0.999951f,0.0f},{-0.0515206f,0.998672f,0.0f},{0.703582f,0.710614f,0.0f}, -{0.732525f,0.680741f,0.0f},{0.732526f,0.680739f,0.0f},{0.760202f,0.649687f,0.0f}, -{0.760201f,0.649688f,0.0f},{0.786563f,0.61751f,0.0f},{0.786561f,0.617513f,0.0f}, -{0.811561f,0.584268f,0.0f},{0.811563f,0.584265f,0.0f},{0.835158f,0.55001f,0.0f}, -{0.835156f,0.550013f,0.0f},{0.857309f,0.514803f,0.0f},{0.857307f,0.514806f,0.0f}, -{0.877974f,0.478708f,0.0f},{0.877976f,0.478705f,0.0f},{0.897124f,0.441779f,0.0f}, -{0.897123f,0.441782f,0.0f},{0.91472f,0.404088f,0.0f},{0.914719f,0.404092f,0.0f}, -{0.930732f,0.365702f,0.0f},{0.930733f,0.365699f,0.0f},{0.945136f,0.326677f,0.0f}, -{0.945135f,0.326679f,0.0f},{0.957904f,0.287089f,0.0f},{0.957903f,0.287092f,0.0f}, -{0.969013f,0.247008f,0.0f},{0.969014f,0.247006f,0.0f},{0.978448f,0.206494f,0.0f}, -{0.978447f,0.206496f,0.0f},{0.986189f,0.165625f,0.0f},{0.986188f,0.165628f,0.0f}, -{0.992223f,0.124472f,0.0f},{0.992223f,0.12447f,0.0f},{0.996541f,0.0830991f,0.0f}, -{0.996541f,0.0831017f,0.0f},{0.999135f,0.041585f,0.0f},{0.999135f,0.0415873f,0.0f}, -{1.0f,1.92868e-016f,0.0f},{1.0f,8.64379e-008f,0.0f},{0.998361f,0.0572333f,1.89979e-016f}, -{1.0f,-3.3736e-016f,0.0f},{0.993449f,0.114279f,0.0f},{0.569266f,0.822154f,0.0f}, -{0.413628f,0.910446f,0.0f},{0.569567f,0.821945f,0.0f},{0.413191f,0.910644f,0.0f}, -{0.244303f,0.969699f,0.0f},{0.243984f,0.969779f,0.0f},{0.0672808f,0.997734f,0.0f}, -{-0.11203f,0.993705f,0.0f},{0.0668255f,0.997765f,0.0f},{-0.2878f,0.957691f,0.0f}, -{-0.112396f,0.993663f,0.0f},{0.822154f,0.569266f,0.0f},{0.821945f,0.569567f,0.0f}, -{0.910446f,0.413628f,0.0f},{0.969699f,0.244303f,0.0f},{0.910644f,0.413191f,0.0f}, -{0.969779f,0.243985f,0.0f},{0.997734f,0.0672808f,0.0f},{0.997765f,0.0668255f,0.0f}, -{0.993705f,-0.11203f,0.0f},{0.993663f,-0.112396f,0.0f},{-0.567551f,0.823338f,2.91569e-016f}, -{-0.480256f,0.877128f,-1.36506e-015f},{-0.480275f,0.877118f,1.00957e-015f},{-0.567558f,0.823334f,5.00925e-017f}, -{-0.648872f,0.760897f,1.44361e-016f},{-0.387941f,0.921684f,1.25621e-016f},{-0.387915f,0.921695f,6.82191e-016f}, -{-0.291525f,0.956563f,-6.81027e-016f},{-0.291499f,0.956571f,-7.61943e-016f},{-0.192047f,0.981386f,6.553e-016f}, -{-0.192025f,0.98139f,1.77659e-017f},{-0.0904984f,0.995897f,-8.37279e-018f},{-0.0905325f,0.995893f,-1.67519e-017f}, -{0.0119218f,0.999929f,1.48019e-015f},{0.114279f,0.993449f,0.0f},{0.0121699f,0.999926f,0.0f}, -{-0.723369f,0.690461f,-9.58068e-017f},{-0.648879f,0.760892f,1.7081e-016f},{-0.723384f,0.690446f,-1.49808e-016f}, -{-0.790265f,0.612765f,1.16954e-016f},{-0.790282f,0.612743f,-1.7266e-016f},{-0.848856f,0.528625f,3.32998e-016f}, -{-0.898522f,0.438929f,-5.4393e-016f},{-0.84887f,0.528601f,4.57239e-016f},{-0.898532f,0.438908f,-2.60926e-016f}, -{-0.938749f,0.344602f,1.75687e-016f},{-0.938761f,0.34457f,5.73784e-016f},{-0.969101f,0.246664f,-5.54286e-016f}, -{-0.989269f,0.146104f,0.0f},{-0.969162f,0.246424f,-8.55909e-016f},{-0.863082f,-0.505064f,-2.96041e-016f}, -{-0.939433f,-0.342733f,-1.39064e-015f},{-0.757002f,-0.653412f,-4.80673e-016f},{-0.98457f,-0.174993f,-7.12538e-016f}, -{-0.999951f,-0.00988645f,0.0f},{-0.625744f,-0.780028f,-1.42742e-017f},{-0.47631f,-0.879277f,-1.99991e-016f}, -{-0.316965f,-0.948437f,-3.53543e-016f},{-0.155878f,-0.987776f,8.15532e-017f},{-1.95899e-012f,-1.0f,0.0f}, -{-1.95907e-012f,-1.0f,0.0f},{-1.0f,4.18691e-016f,0.0f},{-1.0f,2.09346e-016f,0.0f}, -{-2.61682e-016f,1.0f,0.0f},{-8.42937e-008f,1.0f,0.0f},{-0.432409f,0.901678f,-4.8007e-016f}, -{-0.568002f,0.823027f,1.63014e-016f},{-0.288928f,0.957351f,2.01882e-015f},{-0.288928f,0.957351f,0.0f}, -{-0.143098f,0.989708f,7.32531e-016f},{-0.690346f,0.72348f,-1.05257e-015f},{-4.36853e-016f,1.0f,0.0f}, -{-9.28313e-016f,1.0f,0.0f},{-0.794923f,0.60671f,-3.38738e-016f},{-0.878607f,0.477546f,-8.64155e-016f}, -{-0.939939f,0.341342f,-3.74916e-016f},{-0.979111f,0.203325f,0.0f},{-0.610942f,0.791675f,0.0f}, -{-0.64341f,0.765522f,0.0f},{-0.674759f,0.738038f,0.0f},{-0.643409f,0.765522f,0.0f}, -{-0.704936f,0.709271f,0.0f},{-0.674758f,0.738039f,0.0f},{-0.704934f,0.709273f,0.0f}, -{-0.733887f,0.679272f,0.0f},{-0.761562f,0.648092f,0.0f},{-0.733885f,0.679273f,0.0f}, -{-0.787914f,0.615785f,0.0f},{-0.761561f,0.648094f,0.0f},{-0.787913f,0.615787f,0.0f}, -{-0.812896f,0.582409f,0.0f},{-0.836465f,0.54802f,0.0f},{-0.812895f,0.58241f,0.0f}, -{-0.858581f,0.512678f,0.0f},{-0.836464f,0.548021f,0.0f},{-0.85858f,0.51268f,0.0f}, -{-0.879204f,0.476445f,0.0f},{-0.898299f,0.439385f,0.0f},{-0.879203f,0.476447f,0.0f}, -{-0.915833f,0.40156f,0.0f},{-0.898298f,0.439387f,0.0f},{-0.915832f,0.401562f,0.0f}, -{-0.931774f,0.363038f,0.0f},{-0.946097f,0.323885f,0.0f},{-0.931774f,0.36304f,0.0f}, -{-0.958774f,0.284168f,0.0f},{-0.946096f,0.323886f,0.0f},{-0.958774f,0.28417f,0.0f}, -{-0.969786f,0.243959f,0.0f},{-0.969785f,0.24396f,0.0f},{-0.577412f,0.816453f,0.0f}, -{-0.577413f,0.816452f,0.0f},{-0.542879f,0.839811f,0.0f},{-0.507402f,0.861709f,0.0f}, -{-0.54288f,0.83981f,0.0f},{-0.471044f,0.88211f,0.0f},{-0.507404f,0.861708f,0.0f}, -{-0.471046f,0.882109f,0.0f},{-0.433866f,0.900977f,0.0f},{-0.395935f,0.918278f,0.0f}, -{-0.433869f,0.900976f,0.0f},{-0.357316f,0.933984f,0.0f},{-0.395937f,0.918278f,0.0f}, -{-0.357318f,0.933983f,0.0f},{-0.318075f,0.948065f,0.0f},{-0.278282f,0.960499f,0.0f}, -{-0.318077f,0.948065f,0.0f},{-0.238005f,0.971264f,0.0f},{-0.278284f,0.960499f,0.0f}, -{-0.238007f,0.971263f,0.0f},{-0.197314f,0.98034f,0.0f},{-0.15628f,0.987713f,0.0f}, -{-0.197316f,0.98034f,0.0f},{-0.114975f,0.993368f,0.0f},{-0.156283f,0.987712f,0.0f}, -{-0.114977f,0.993368f,0.0f},{-0.0734701f,0.997297f,0.0f},{-0.0318375f,0.999493f,0.0f}, -{-0.0734722f,0.997297f,0.0f},{0.00985025f,0.999951f,0.0f},{-0.0318392f,0.999493f,0.0f}, -{0.00984923f,0.999951f,0.0f},{0.0515206f,0.998672f,0.0f},{-0.866025f,0.5f,-4.07254e-016f}, -{-0.0706974f,-0.997498f,4.22047e-015f},{-0.042441f,-0.999099f,-4.49972e-015f},{-0.0424415f,-0.999099f,-8.87378e-015f}, -{0.0141508f,-0.9999f,-1.48015e-015f},{-0.014151f,-0.9999f,0.0f},{-0.0141508f,-0.9999f,-7.42169e-015f}, -{-0.0706979f,-0.997498f,1.47659e-015f},{-0.0988972f,-0.995098f,5.89216e-015f},{-0.0988976f,-0.995098f,5.59937e-015f}, -{-0.127018f,-0.9919f,-1.17465e-014f},{-0.127018f,-0.9919f,-1.72436e-014f},{-0.155036f,-0.987909f,-5.3906e-015f}, -{-0.155037f,-0.987909f,5.84959e-015f},{-0.182932f,-0.983126f,-2.36905e-015f},{-0.182931f,-0.983126f,8.73191e-015f}, -{-0.238259f,-0.971202f,8.626e-015f},{-0.265648f,-0.96407f,-7.28139e-015f},{-0.265647f,-0.96407f,-1.29898e-014f}, -{-0.210679f,-0.977555f,-4.54082e-015f},{-0.21068f,-0.977555f,0.0f},{-0.238258f,-0.971202f,-1.29121e-014f}, -{-0.292823f,-0.956167f,-1.73386e-015f},{-0.292823f,-0.956167f,0.0f},{-0.319764f,-0.947497f,5.61031e-015f}, -{-0.319764f,-0.947497f,-1.89338e-015f},{-0.346449f,-0.938069f,0.0f},{-0.346449f,-0.938069f,7.60587e-015f}, -{-0.372856f,-0.927889f,9.90971e-015f},{-0.424755f,-0.905308f,5.3605e-015f},{-0.424755f,-0.905309f,3.304e-016f}, -{-0.398966f,-0.916966f,4.7247e-015f},{-0.398965f,-0.916966f,5.42953e-015f},{-0.372857f,-0.927889f,-7.70196e-015f}, -{-0.450204f,-0.892926f,0.0f},{-0.450204f,-0.892926f,5.33148e-015f},{-0.475292f,-0.879828f,1.04193e-014f}, -{-0.475292f,-0.879828f,1.04193e-014f},{0.014151f,-0.9999f,8.90184e-015f},{0.042441f,-0.999099f,-1.04784e-014f}, -{0.0424415f,-0.999099f,-1.61429e-014f},{0.0706974f,-0.997498f,8.65025e-015f},{0.0988972f,-0.995098f,2.94608e-015f}, -{0.0706979f,-0.997498f,-1.09175e-014f},{0.0988976f,-0.995098f,1.39984e-015f},{0.127018f,-0.9919f,-1.06363e-014f}, -{0.127018f,-0.9919f,9.63801e-015f},{0.155036f,-0.987909f,-7.40539e-015f},{0.182931f,-0.983126f,-7.57272e-015f}, -{0.155037f,-0.987909f,-2.5165e-015f},{0.182932f,-0.983126f,2.18298e-015f},{0.210679f,-0.977555f,7.64703e-015f}, -{0.21068f,-0.977555f,-4.23518e-015f},{0.238258f,-0.971202f,-1.03144e-014f},{0.265647f,-0.96407f,-7.60334e-015f}, -{0.238259f,-0.971202f,1.75636e-015f},{0.265648f,-0.96407f,1.0869e-014f},{0.292823f,-0.956167f,5.12754e-015f}, -{0.292823f,-0.956167f,-8.24033e-015f},{0.319764f,-0.947497f,3.07966e-016f},{0.346449f,-0.938069f,-1.05337e-014f}, -{0.319764f,-0.947497f,-8.2576e-015f},{0.346449f,-0.938069f,-1.87656e-015f},{0.372856f,-0.927889f,3.1746e-015f}, -{0.372857f,-0.927889f,-3.31849e-015f},{0.398965f,-0.916966f,3.06056e-015f},{0.424755f,-0.905309f,7.49538e-015f}, -{0.398966f,-0.916966f,4.02549e-015f},{0.424755f,-0.905308f,1.46943e-015f},{0.450204f,-0.892926f,-1.18685e-014f}, -{0.450204f,-0.892926f,1.25672e-015f},{0.475292f,-0.879828f,4.58408e-015f},{0.475292f,-0.879828f,1.83809e-015f}, -{0.623541f,-0.78179f,-1.15728e-015f},{0.589568f,-0.807718f,-2.39133e-015f},{0.589571f,-0.807717f,9.60223e-017f}, -{0.656376f,-0.754434f,-5.72909e-015f},{0.656377f,-0.754433f,-7.23689e-015f},{0.688011f,-0.7257f,1.01846e-015f}, -{0.554522f,-0.832169f,1.64171e-015f},{0.623543f,-0.781789f,4.8494e-015f},{0.554519f,-0.832171f,4.10543e-015f}, -{0.51846f,-0.855102f,-9.96661e-016f},{0.518456f,-0.855104f,1.53494e-015f},{0.481448f,-0.876475f,-5.18977e-015f}, -{0.48145f,-0.876473f,-4.02026e-015f},{0.443562f,-0.896244f,-2.65341e-015f},{0.443559f,-0.896245f,-3.96662e-015f}, -{0.40486f,-0.914379f,0.0f},{0.365425f,-0.930841f,0.0f},{0.404864f,-0.914377f,-2.39728e-015f}, -{0.365423f,-0.930842f,0.0f},{0.325317f,-0.945605f,-3.67284e-015f},{0.32532f,-0.945604f,0.0f}, -{0.201738f,-0.97944f,3.58358e-015f},{0.243399f,-0.969926f,-1.44121e-015f},{0.201735f,-0.97944f,-3.41043e-015f}, -{0.284621f,-0.95864f,7.36158e-015f},{0.284618f,-0.958641f,-5.6763e-015f},{0.243401f,-0.969926f,5.74311e-015f}, -{0.159705f,-0.987165f,9.45645e-016f},{0.117381f,-0.993087f,-1.03704e-014f},{0.159703f,-0.987165f,-4.89956e-015f}, -{0.117378f,-0.993087f,-6.9502e-016f},{0.07484f,-0.997196f,0.0f},{0.0321655f,-0.999483f,6.29904e-015f}, -{0.032168f,-0.999482f,-5.91813e-015f},{0.0748434f,-0.997195f,-8.86324e-016f},{-0.0105685f,-0.999944f,-5.7957e-015f}, -{-0.0105657f,-0.999944f,5.92086e-015f},{-0.0532826f,-0.99858f,0.0f},{-0.05328f,-0.99858f,0.0f}, -{-0.0958981f,-0.995391f,0.0f},{0.718389f,-0.695642f,-2.12686e-015f},{0.688012f,-0.725699f,-3.16696e-015f}, -{0.718391f,-0.69564f,6.73571e-017f},{0.747455f,-0.664312f,3.69231e-016f},{0.747457f,-0.66431f,-4.91688e-015f}, -{0.775156f,-0.631769f,-3.61476e-016f},{0.801442f,-0.598073f,-8.85326e-016f},{0.775159f,-0.631767f,-5.10676e-016f}, -{0.801444f,-0.59807f,-2.51436e-015f},{0.826264f,-0.563284f,-2.63707e-016f},{0.826266f,-0.563281f,-4.79448e-015f}, -{0.849576f,-0.527466f,2.47204e-015f},{0.871337f,-0.490685f,-7.45068e-016f},{0.849578f,-0.527463f,6.28814e-016f}, -{0.871339f,-0.490682f,-4.66609e-016f},{0.891507f,-0.453007f,-5.36872e-018f},{0.891508f,-0.453005f,1.90646e-015f}, -{0.910048f,-0.414503f,-9.01947e-016f},{0.926927f,-0.375241f,-7.55498e-016f},{0.91005f,-0.414499f,-3.44627e-015f}, -{0.926928f,-0.375238f,-8.26493e-018f},{0.942114f,-0.335293f,7.4317e-016f},{0.942115f,-0.335291f,-1.38718e-015f}, -{0.955579f,-0.294734f,-6.60361e-018f},{0.9673f,-0.253636f,1.39186e-016f},{0.95558f,-0.294731f,-4.80822e-016f}, -{0.9673f,-0.253634f,-1.1694e-015f},{0.977253f,-0.212076f,-1.09093e-015f},{0.977254f,-0.212073f,-1.42807e-015f}, -{0.985422f,-0.170128f,-8.58064e-016f},{0.991791f,-0.127868f,1.21011e-015f},{0.985423f,-0.170124f,3.47036e-015f}, -{0.991791f,-0.127866f,2.85545e-016f},{0.996349f,-0.0853758f,-4.87227e-016f},{0.996349f,-0.0853729f,3.21028e-015f}, -{0.999087f,-0.0427275f,-3.76158e-016f},{1.0f,-1.41083e-016f,0.0f},{0.999087f,-0.0427249f,-2.9625e-015f}, -{1.0f,-1.54309e-016f,0.0f},{5.04647e-017f,-1.0f,0.0f},{5.3829e-017f,-1.0f,0.0f}, -{0.0541567f,-0.998532f,0.0f},{0.108145f,-0.994135f,0.0f},{0.0541301f,-0.998534f,0.0f}, -{0.161808f,-0.986822f,0.0f},{0.108105f,-0.99414f,0.0f},{0.161767f,-0.986829f,0.0f}, -{0.214992f,-0.976616f,0.0f},{0.267546f,-0.963545f,0.0f},{0.214964f,-0.976622f,0.0f}, -{0.319328f,-0.947644f,0.0f},{0.267531f,-0.963549f,0.0f},{0.319303f,-0.947653f,0.0f}, -{0.370172f,-0.928963f,0.0f},{0.419923f,-0.90756f,0.0f},{0.370136f,-0.928977f,0.0f}, -{0.46844f,-0.883495f,0.0f},{0.419887f,-0.907577f,0.0f},{0.468409f,-0.883512f,0.0f}, -{0.515581f,-0.856841f,0.0f},{0.56121f,-0.827674f,0.0f},{0.515559f,-0.856854f,0.0f}, -{0.605197f,-0.796076f,0.0f},{0.561199f,-0.827681f,0.0f},{0.605188f,-0.796082f,0.0f}, -{0.647411f,-0.762141f,0.0f},{0.687723f,-0.725973f,0.0f},{0.6474f,-0.762151f,0.0f}, -{0.726018f,-0.687676f,0.0f},{0.687712f,-0.725983f,0.0f},{0.726007f,-0.687687f,0.0f}, -{0.762183f,-0.647361f,0.0f},{0.796113f,-0.605148f,0.0f},{0.762171f,-0.647375f,0.0f}, -{0.827707f,-0.56116f,0.0f},{0.796101f,-0.605164f,0.0f},{0.827695f,-0.561178f,0.0f}, -{0.856873f,-0.515527f,0.0f},{0.883526f,-0.468383f,0.0f},{0.856862f,-0.515545f,0.0f}, -{0.907586f,-0.419866f,0.0f},{0.883516f,-0.4684f,0.0f},{0.907578f,-0.419884f,0.0f}, -{0.928986f,-0.370116f,0.0f},{0.947661f,-0.319279f,0.0f},{0.928977f,-0.370136f,0.0f}, -{0.963556f,-0.267507f,0.0f},{0.947653f,-0.319301f,0.0f},{0.96355f,-0.267528f,0.0f}, -{0.976624f,-0.214954f,0.0f},{0.986829f,-0.16177f,0.0f},{0.97662f,-0.214973f,0.0f}, -{0.994139f,-0.108111f,0.0f},{0.986826f,-0.161786f,0.0f},{0.994135f,-0.108145f,0.0f}, -{0.99855f,-0.0538298f,0.0f},{1.0f,2.15316e-016f,0.0f},{0.998551f,-0.0538044f,0.0f}, -{1.0f,2.35502e-016f,0.0f},{-0.0541566f,-0.998532f,0.0f},{-0.0541302f,-0.998534f,0.0f}, -{-0.108145f,-0.994135f,0.0f},{-0.161808f,-0.986822f,0.0f},{-0.108105f,-0.99414f,0.0f}, -{-0.214992f,-0.976616f,0.0f},{-0.161767f,-0.986829f,0.0f},{-0.214964f,-0.976622f,0.0f}, -{-0.267546f,-0.963545f,0.0f},{-0.319328f,-0.947644f,0.0f},{-0.267531f,-0.963549f,0.0f}, -{-0.370172f,-0.928963f,0.0f},{-0.319303f,-0.947653f,0.0f},{-0.370136f,-0.928977f,0.0f}, -{-0.419923f,-0.90756f,0.0f},{-0.46844f,-0.883495f,0.0f},{-0.419887f,-0.907577f,0.0f}, -{-0.515581f,-0.856841f,0.0f},{-0.468409f,-0.883512f,0.0f},{-0.515559f,-0.856854f,0.0f}, -{-0.56121f,-0.827674f,0.0f},{-0.605197f,-0.796076f,0.0f},{-0.561199f,-0.827681f,0.0f}, -{-0.647411f,-0.762141f,0.0f},{-0.605188f,-0.796082f,0.0f},{-0.6474f,-0.762151f,0.0f}, -{-0.687723f,-0.725973f,0.0f},{-0.726018f,-0.687676f,0.0f},{-0.687712f,-0.725983f,0.0f}, -{-0.762183f,-0.647361f,0.0f},{-0.726007f,-0.687687f,0.0f},{-0.762171f,-0.647375f,0.0f}, -{-0.796113f,-0.605148f,0.0f},{-0.827707f,-0.56116f,0.0f},{-0.796101f,-0.605164f,0.0f}, -{-0.856873f,-0.515527f,0.0f},{-0.827695f,-0.561178f,0.0f},{-0.856862f,-0.515545f,0.0f}, -{-0.883526f,-0.468383f,0.0f},{-0.907586f,-0.419866f,0.0f},{-0.883516f,-0.468401f,0.0f}, -{-0.928986f,-0.370116f,0.0f},{-0.907578f,-0.419884f,0.0f},{-0.928977f,-0.370136f,0.0f}, -{-0.947661f,-0.319279f,0.0f},{-0.963556f,-0.267507f,0.0f},{-0.947653f,-0.319301f,0.0f}, -{-0.976624f,-0.214954f,0.0f},{-0.96355f,-0.267528f,0.0f},{-0.97662f,-0.214973f,0.0f}, -{-0.986829f,-0.16177f,0.0f},{-0.994139f,-0.108111f,0.0f},{-0.986826f,-0.161786f,0.0f}, -{-0.99855f,-0.0538298f,0.0f},{-0.994135f,-0.108145f,0.0f},{-0.998551f,-0.0538045f,0.0f}, -{-1.0f,-1.19209e-007f,0.0f},{-0.718391f,-0.69564f,-2.2967e-015f},{-0.747457f,-0.66431f,4.30948e-015f}, -{-0.747455f,-0.664312f,-2.35972e-015f},{-0.688012f,-0.725699f,-2.11837e-015f},{-0.688011f,-0.7257f,-4.7761e-015f}, -{-0.656377f,-0.754433f,-3.42054e-015f},{-0.775156f,-0.631769f,1.02241e-015f},{-0.718389f,-0.695642f,1.63365e-016f}, -{-0.775159f,-0.631766f,1.30928e-015f},{-0.801442f,-0.598073f,-4.02386e-016f},{-0.801444f,-0.59807f,3.14782e-015f}, -{-0.826266f,-0.563281f,2.05014e-015f},{-0.826264f,-0.563284f,2.15457e-016f},{-0.849576f,-0.527466f,3.68245e-015f}, -{-0.849578f,-0.527463f,-9.04405e-017f},{-0.871339f,-0.490682f,2.82586e-015f},{-0.891507f,-0.453007f,-1.11336e-015f}, -{-0.871337f,-0.490685f,-3.98744e-016f},{-0.891508f,-0.453005f,8.87668e-016f},{-0.91005f,-0.414499f,3.62163e-016f}, -{-0.910048f,-0.414503f,-2.33213e-015f},{-0.955579f,-0.294734f,1.39294e-015f},{-0.942115f,-0.335291f,1.29026e-015f}, -{-0.95558f,-0.294731f,9.56661e-016f},{-0.926927f,-0.375241f,3.09815e-015f},{-0.926928f,-0.375238f,3.53892e-016f}, -{-0.942114f,-0.335293f,1.78659e-015f},{-0.9673f,-0.253636f,4.48455e-017f},{-0.977253f,-0.212075f,9.31315e-017f}, -{-0.9673f,-0.253634f,-3.87537e-015f},{-0.977254f,-0.212073f,1.53976e-015f},{-0.985423f,-0.170124f,-1.33727e-015f}, -{-0.991791f,-0.127866f,1.31222e-015f},{-0.991791f,-0.127868f,-1.43479e-015f},{-0.985422f,-0.170128f,-1.08544e-015f}, -{-0.996349f,-0.0853729f,-2.96511e-015f},{-0.996349f,-0.0853758f,1.45956e-015f},{-0.999087f,-0.0427249f,-1.45746e-015f}, -{-0.999087f,-0.0427275f,2.97938e-015f},{-1.0f,-1.41083e-016f,0.0f},{-1.0f,-1.54309e-016f,0.0f}, -{-0.623543f,-0.781789f,-8.12728e-016f},{-0.656376f,-0.754434f,-2.4015e-015f},{-0.623541f,-0.78179f,-9.35104e-016f}, -{-0.589571f,-0.807717f,-3.8494e-015f},{-0.589569f,-0.807718f,8.37214e-016f},{-0.554522f,-0.832169f,-3.65599e-015f}, -{-0.51846f,-0.855102f,-4.07623e-015f},{-0.554519f,-0.832171f,2.81113e-015f},{-0.518456f,-0.855104f,2.96789e-016f}, -{-0.48145f,-0.876473f,3.95802e-015f},{-0.481448f,-0.876475f,6.89284e-016f},{-0.443562f,-0.896244f,7.12651e-016f}, -{-0.404864f,-0.914377f,-1.93578e-015f},{-0.443559f,-0.896245f,5.43092e-015f},{-0.40486f,-0.914379f,-5.84661e-015f}, -{-0.365425f,-0.930841f,1.20115e-015f},{-0.365423f,-0.930842f,3.55128e-015f},{-0.32532f,-0.945604f,2.23888e-015f}, -{-0.284621f,-0.95864f,5.39664e-015f},{-0.325317f,-0.945605f,4.0151e-015f},{-0.284618f,-0.958641f,-2.22393e-015f}, -{-0.243401f,-0.969926f,4.33048e-015f},{-0.243399f,-0.969926f,4.23515e-015f},{-0.201738f,-0.97944f,4.2777e-015f}, -{-0.159705f,-0.987165f,5.95984e-015f},{-0.201735f,-0.97944f,6.68731e-016f},{-0.159703f,-0.987165f,-8.70338e-015f}, -{-0.117381f,-0.993087f,-6.76187e-015f},{-0.117378f,-0.993087f,7.13795e-015f},{-0.0748434f,-0.997195f,-4.49833e-016f}, -{-0.0321679f,-0.999482f,5.88869e-015f},{-0.07484f,-0.997196f,-1.11652e-015f},{-0.0321656f,-0.999483f,-2.74195e-016f}, -{0.0105657f,-0.999944f,5.2388e-015f},{0.0105686f,-0.999944f,-6.15843e-016f},{0.05328f,-0.99858f,7.92959e-015f}, -{0.0958981f,-0.995391f,0.0f},{0.0532825f,-0.99858f,4.50329e-015f},{-0.0141122f,0.9999f,0.0f}, -{0.0141124f,0.9999f,0.0f},{-0.0141125f,0.9999f,0.0f},{-0.0423259f,0.999104f,0.0f}, -{-0.0423254f,0.999104f,0.0f},{-0.0705055f,0.997511f,0.0f},{-0.0705051f,0.997511f,0.0f}, -{-0.0986284f,0.995124f,0.0f},{-0.0986291f,0.995124f,0.0f},{-0.126674f,0.991944f,0.0f}, -{-0.126673f,0.991944f,0.0f},{-0.154618f,0.987974f,0.0f},{-0.154617f,0.987974f,0.0f}, -{-0.182438f,0.983217f,0.0f},{-0.182439f,0.983217f,0.0f},{-0.210114f,0.977677f,0.0f}, -{-0.210113f,0.977677f,0.0f},{-0.237622f,0.971358f,0.0f},{-0.237622f,0.971358f,0.0f}, -{-0.26494f,0.964265f,0.0f},{-0.264941f,0.964265f,0.0f},{-0.292049f,0.956403f,0.0f}, -{-0.292048f,0.956404f,0.0f},{-0.318924f,0.94778f,0.0f},{-0.318923f,0.947781f,0.0f}, -{-0.345544f,0.938403f,0.0f},{-0.345545f,0.938402f,0.0f},{-0.371891f,0.928277f,0.0f}, -{-0.37189f,0.928277f,0.0f},{-0.39794f,0.917411f,0.0f},{-0.397939f,0.917412f,0.0f}, -{-0.423672f,0.905816f,0.0f},{-0.423672f,0.905815f,0.0f},{-0.449067f,0.893498f,0.0f}, -{-0.449067f,0.893498f,0.0f},{-0.474105f,0.880469f,0.0f},{-0.474104f,0.880469f,0.0f}, -{-0.498763f,0.866738f,0.0f},{-0.498764f,0.866738f,0.0f},{-0.523026f,0.852317f,0.0f}, -{0.0141122f,0.9999f,0.0f},{0.0423254f,0.999104f,0.0f},{0.0423259f,0.999104f,0.0f}, -{0.0705055f,0.997511f,0.0f},{0.0705051f,0.997511f,0.0f},{0.0986291f,0.995124f,0.0f}, -{0.0986285f,0.995124f,0.0f},{0.126673f,0.991944f,0.0f},{0.126674f,0.991944f,0.0f}, -{0.154618f,0.987974f,0.0f},{0.154617f,0.987974f,0.0f},{0.182439f,0.983217f,0.0f}, -{0.182438f,0.983217f,0.0f},{0.210113f,0.977677f,0.0f},{0.210114f,0.977677f,0.0f}, -{0.237622f,0.971358f,0.0f},{0.237622f,0.971358f,0.0f},{0.264941f,0.964265f,0.0f}, -{0.26494f,0.964265f,0.0f},{0.292048f,0.956404f,0.0f},{0.292049f,0.956403f,0.0f}, -{0.318924f,0.94778f,0.0f},{0.318923f,0.947781f,0.0f},{0.345545f,0.938402f,0.0f}, -{0.345544f,0.938403f,0.0f},{0.37189f,0.928277f,0.0f},{0.371891f,0.928277f,0.0f}, -{0.39794f,0.917411f,0.0f},{0.397939f,0.917412f,0.0f},{0.423672f,0.905815f,0.0f}, -{0.423672f,0.905816f,0.0f},{0.449067f,0.893498f,0.0f},{0.449067f,0.893498f,0.0f}, -{0.474104f,0.880469f,0.0f},{0.474104f,0.880469f,0.0f},{0.498764f,0.866738f,0.0f}, -{0.498764f,0.866738f,0.0f},{0.523026f,0.852317f,0.0f},{0.866025f,0.5f,-7.6671e-016f}, -{-4.33681e-019f,0.0f,1.0f},{4.33681e-019f,0.0f,1.0f},{0.466272f,0.884642f,2.20644e-016f}, -{0.628286f,0.777982f,5.89571e-016f},{0.628223f,0.778033f,-5.53502e-016f},{0.286781f,0.957996f,1.48116e-016f}, -{0.466199f,0.88468f,-5.1317e-016f},{0.286593f,0.958053f,-1.63827e-016f},{-0.0974696f,0.995238f,3.44802e-016f}, -{0.0962625f,0.995356f,-1.06856e-016f},{-0.097635f,0.995222f,-4.56953e-017f},{0.0964852f,0.995334f,-1.31963e-016f}, -{0.766564f,0.642168f,0.0f},{0.876095f,0.482138f,-7.37654e-016f},{0.76669f,0.642017f,-1.10523e-015f}, -{0.876203f,0.481942f,7.37698e-016f},{0.952689f,0.303947f,0.0f},{0.952739f,0.303789f,0.0f}, -{0.698102f,0.715999f,1.29175e-016f},{0.324434f,0.945908f,-5.70109e-016f},{0.324434f,0.945908f,-3.35048e-016f}, -{0.524032f,0.851699f,7.27349e-016f},{-1.0f,-3.33067e-016f,0.0f},{-0.98085f,-0.194766f,-8.7013e-016f}, -{-0.707075f,-0.707139f,5.23388e-016f},{-0.707766f,-0.706447f,5.22876e-016f},{-0.831545f,-0.555458f,-6.15467e-016f}, -{-0.831851f,-0.554999f,-4.10782e-016f},{-0.924075f,-0.382212f,-1.36791e-015f},{-0.196168f,-0.98057f,-1.01605e-015f}, -{-0.194654f,-0.980872f,-1.44073e-016f},{-0.555293f,-0.831655f,-4.10999e-016f},{-0.382179f,-0.924088f,-1.22649e-015f}, -{-0.384009f,-0.923329f,-1.99588e-016f},{0.384009f,-0.923329f,-2.13958e-016f},{0.555293f,-0.831655f,6.67161e-016f}, -{0.382179f,-0.924088f,9.40449e-016f},{0.196168f,-0.98057f,-7.62016e-016f},{0.194653f,-0.980872f,6.1653e-016f}, -{2.96059e-016f,-1.0f,-3.28692e-031f},{0.707765f,-0.706447f,4.57334e-016f},{0.831545f,-0.555458f,8.32431e-017f}, -{0.707075f,-0.707139f,-4.57955e-016f},{0.556611f,-0.830773f,-3.85076e-016f},{0.831851f,-0.554999f,-2.05391e-016f}, -{0.923954f,-0.382504f,-2.95917e-016f},{0.980825f,-0.19489f,-3.63028e-018f},{0.924075f,-0.382212f,5.86375e-016f}, -{0.98085f,-0.194766f,-2.22141e-016f},{1.0f,-1.85037e-017f,0.0f},{-0.556611f,-0.830773f,-1.04527e-016f}, -{-1.0f,-2.96059e-016f,0.0f},{-1.0f,-1.85037e-017f,0.0f},{-0.980825f,-0.19489f,-8.70204e-016f}, -{-0.98085f,-0.194766f,7.25975e-016f},{-0.707075f,-0.707139f,2.6167e-016f},{-0.707766f,-0.706447f,-1.04673e-015f}, -{-0.831545f,-0.555458f,6.15467e-016f},{-0.196168f,-0.98057f,-7.25968e-017f},{-0.194654f,-0.980872f,0.0f}, -{-0.555293f,-0.831655f,2.055e-016f},{-0.384009f,-0.923329f,-1.42112e-016f},{0.384009f,-0.923329f,7.57929e-018f}, -{0.555293f,-0.831655f,4.10524e-016f},{0.382179f,-0.924088f,2.41708e-016f},{0.196168f,-0.98057f,-1.26994e-016f}, -{0.194653f,-0.980872f,-9.14525e-017f},{0.707765f,-0.706447f,-5.72353e-016f},{0.831545f,-0.555458f,-9.69264e-018f}, -{0.707075f,-0.707139f,1.14487e-016f},{0.556611f,-0.830773f,5.13819e-016f},{0.831851f,-0.554999f,4.97064e-016f}, -{0.923954f,-0.382504f,1.06278e-016f},{0.980825f,-0.19489f,-1.02781e-015f},{0.924075f,-0.382212f,4.37371e-016f}, -{0.98085f,-0.194766f,8.39508e-016f},{1.0f,-2.96059e-016f,0.0f},{1.0f,-5.92119e-016f,0.0f}, -{-0.556611f,-0.830773f,-5.13435e-016f},{-0.989489f,-0.144611f,-3.80291e-017f},{-0.99711f,0.0759712f,-5.623e-017f}, -{-0.933664f,-0.358149f,-9.55933e-016f},{-0.933664f,-0.358149f,1.99014e-016f},{-0.835272f,-0.549837f,0.0f}, -{-0.957691f,0.2878f,0.0f},{1.0f,1.53707e-012f,0.0f},{1.0f,8.42952e-008f,0.0f}, -{-3.07487e-012f,1.0f,0.0f},{-3.07526e-012f,1.0f,0.0f},{-0.673422f,-0.739259f,0.0f}, -{-0.703582f,-0.710614f,0.0f},{-0.673421f,-0.739259f,0.0f},{-0.642094f,-0.766626f,0.0f}, -{-0.642096f,-0.766624f,0.0f},{-0.609658f,-0.792665f,0.0f},{-0.60966f,-0.792663f,0.0f}, -{-0.576168f,-0.817331f,0.0f},{-0.576166f,-0.817333f,0.0f},{-0.541677f,-0.840587f,0.0f}, -{-0.54168f,-0.840585f,0.0f},{-0.506252f,-0.862386f,0.0f},{-0.506254f,-0.862384f,0.0f}, -{-0.469953f,-0.882691f,0.0f},{-0.46995f,-0.882693f,0.0f},{-0.432835f,-0.901473f,0.0f}, -{-0.432838f,-0.901471f,0.0f},{-0.394972f,-0.918693f,0.0f},{-0.394974f,-0.918692f,0.0f}, -{-0.356428f,-0.934323f,0.0f},{-0.356425f,-0.934324f,0.0f},{-0.317262f,-0.948338f,0.0f}, -{-0.317264f,-0.948337f,0.0f},{-0.277549f,-0.960711f,0.0f},{-0.277552f,-0.960711f,0.0f}, -{-0.237359f,-0.971422f,0.0f},{-0.237356f,-0.971423f,0.0f},{-0.196753f,-0.980453f,0.0f}, -{-0.196756f,-0.980453f,0.0f},{-0.155809f,-0.987787f,0.0f},{-0.155812f,-0.987787f,0.0f}, -{-0.114599f,-0.993412f,0.0f},{-0.114596f,-0.993412f,0.0f},{-0.0731848f,-0.997318f,0.0f}, -{-0.073187f,-0.997318f,0.0f},{-0.0316463f,-0.999499f,0.0f},{-0.0316489f,-0.999499f,0.0f}, -{0.00994395f,-0.999951f,0.0f},{0.00994627f,-0.999951f,0.0f},{0.0515206f,-0.998672f,0.0f}, -{-0.703582f,-0.710614f,0.0f},{-0.732525f,-0.680741f,0.0f},{-0.732526f,-0.680739f,0.0f}, -{-0.760202f,-0.649687f,0.0f},{-0.760201f,-0.649688f,0.0f},{-0.786563f,-0.61751f,0.0f}, -{-0.786561f,-0.617513f,0.0f},{-0.811561f,-0.584268f,0.0f},{-0.811563f,-0.584265f,0.0f}, -{-0.835158f,-0.55001f,0.0f},{-0.835156f,-0.550013f,0.0f},{-0.857309f,-0.514803f,0.0f}, -{-0.857307f,-0.514806f,0.0f},{-0.877974f,-0.478708f,0.0f},{-0.877976f,-0.478705f,0.0f}, -{-0.897124f,-0.441779f,0.0f},{-0.897123f,-0.441782f,0.0f},{-0.91472f,-0.404088f,0.0f}, -{-0.914719f,-0.404092f,0.0f},{-0.930732f,-0.365702f,0.0f},{-0.930733f,-0.365699f,0.0f}, -{-0.945136f,-0.326677f,0.0f},{-0.945135f,-0.326679f,0.0f},{-0.957904f,-0.287089f,0.0f}, -{-0.957903f,-0.287092f,0.0f},{-0.969013f,-0.247008f,0.0f},{-0.969014f,-0.247006f,0.0f}, -{-0.978448f,-0.206494f,0.0f},{-0.978447f,-0.206496f,0.0f},{-0.986189f,-0.165625f,0.0f}, -{-0.986188f,-0.165628f,0.0f},{-0.992223f,-0.124472f,0.0f},{-0.992223f,-0.12447f,0.0f}, -{-0.996541f,-0.0830991f,0.0f},{-0.996541f,-0.0831017f,0.0f},{-0.999135f,-0.041585f,0.0f}, -{-0.999135f,-0.0415873f,0.0f},{-1.0f,-1.92868e-016f,0.0f},{-1.0f,-8.64379e-008f,0.0f}, -{-0.998361f,-0.0572333f,1.89979e-016f},{-1.0f,3.3736e-016f,0.0f},{-0.993449f,-0.114279f,0.0f}, -{-0.569266f,-0.822154f,0.0f},{-0.413628f,-0.910446f,0.0f},{-0.569567f,-0.821945f,0.0f}, -{-0.413191f,-0.910644f,0.0f},{-0.244303f,-0.969699f,0.0f},{-0.243984f,-0.969779f,0.0f}, -{-0.0672808f,-0.997734f,0.0f},{0.11203f,-0.993705f,0.0f},{-0.0668255f,-0.997765f,0.0f}, -{0.2878f,-0.957691f,0.0f},{0.112396f,-0.993663f,0.0f},{-0.822154f,-0.569266f,0.0f}, -{-0.821945f,-0.569567f,0.0f},{-0.910446f,-0.413628f,0.0f},{-0.969699f,-0.244303f,0.0f}, -{-0.910644f,-0.413191f,0.0f},{-0.969779f,-0.243985f,0.0f},{-0.997734f,-0.0672808f,0.0f}, -{-0.997765f,-0.0668255f,0.0f},{-0.993705f,0.11203f,0.0f},{-0.993663f,0.112396f,0.0f}, -{0.567551f,-0.823338f,2.91569e-016f},{0.480256f,-0.877128f,-1.36506e-015f},{0.480275f,-0.877118f,1.00957e-015f}, -{0.567558f,-0.823334f,5.00925e-017f},{0.648872f,-0.760897f,1.44361e-016f},{0.387941f,-0.921684f,1.25621e-016f}, -{0.387915f,-0.921695f,6.82191e-016f},{0.291525f,-0.956563f,-6.81027e-016f},{0.291499f,-0.956571f,-7.61943e-016f}, -{0.192047f,-0.981386f,6.553e-016f},{0.192025f,-0.98139f,1.77659e-017f},{0.0904984f,-0.995897f,-8.37279e-018f}, -{0.0905325f,-0.995893f,-1.67519e-017f},{-0.0119218f,-0.999929f,1.48019e-015f},{-0.114279f,-0.993449f,0.0f}, -{-0.0121699f,-0.999926f,0.0f},{0.723369f,-0.690461f,-9.58068e-017f},{0.648879f,-0.760892f,1.7081e-016f}, -{0.723384f,-0.690446f,-1.49808e-016f},{0.790265f,-0.612765f,1.16954e-016f},{0.790282f,-0.612743f,-1.7266e-016f}, -{0.848856f,-0.528625f,3.32998e-016f},{0.898522f,-0.438929f,-5.4393e-016f},{0.84887f,-0.528601f,4.57239e-016f}, -{0.898532f,-0.438908f,-2.60926e-016f},{0.938749f,-0.344602f,1.75687e-016f},{0.938761f,-0.34457f,5.73784e-016f}, -{0.969101f,-0.246664f,-5.54286e-016f},{0.989269f,-0.146104f,0.0f},{0.969162f,-0.246424f,-8.55909e-016f}, -{0.863082f,0.505064f,-2.96041e-016f},{0.939433f,0.342733f,-1.39064e-015f},{0.757002f,0.653412f,-4.80673e-016f}, -{0.98457f,0.174993f,-7.12538e-016f},{0.999951f,0.00988645f,0.0f},{0.625744f,0.780028f,-1.42742e-017f}, -{0.47631f,0.879277f,-1.99991e-016f},{0.316965f,0.948437f,-3.53543e-016f},{0.155878f,0.987776f,8.15532e-017f}, -{1.95899e-012f,1.0f,0.0f},{1.95907e-012f,1.0f,0.0f},{1.0f,-4.18691e-016f,0.0f}, -{1.0f,-2.09346e-016f,0.0f},{2.61682e-016f,-1.0f,0.0f},{8.42937e-008f,-1.0f,0.0f}, -{0.432409f,-0.901678f,-4.8007e-016f},{0.568002f,-0.823027f,1.63014e-016f},{0.288928f,-0.957351f,2.01882e-015f}, -{0.288928f,-0.957351f,0.0f},{0.143098f,-0.989708f,7.32531e-016f},{0.690346f,-0.72348f,-1.05257e-015f}, -{4.36853e-016f,-1.0f,0.0f},{9.28313e-016f,-1.0f,0.0f},{0.794923f,-0.60671f,-3.38738e-016f}, -{0.878607f,-0.477546f,-8.64155e-016f},{0.939939f,-0.341342f,-3.74916e-016f},{0.979111f,-0.203325f,0.0f}, -{0.610942f,-0.791675f,0.0f},{0.64341f,-0.765522f,0.0f},{0.674759f,-0.738038f,0.0f}, -{0.643409f,-0.765522f,0.0f},{0.704936f,-0.709271f,0.0f},{0.674758f,-0.738039f,0.0f}, -{0.704934f,-0.709273f,0.0f},{0.733887f,-0.679272f,0.0f},{0.761562f,-0.648092f,0.0f}, -{0.733885f,-0.679273f,0.0f},{0.787914f,-0.615785f,0.0f},{0.761561f,-0.648094f,0.0f}, -{0.787913f,-0.615787f,0.0f},{0.812896f,-0.582409f,0.0f},{0.836465f,-0.54802f,0.0f}, -{0.812895f,-0.58241f,0.0f},{0.858581f,-0.512678f,0.0f},{0.836464f,-0.548021f,0.0f}, -{0.85858f,-0.51268f,0.0f},{0.879204f,-0.476445f,0.0f},{0.898299f,-0.439385f,0.0f}, -{0.879203f,-0.476447f,0.0f},{0.915833f,-0.40156f,0.0f},{0.898298f,-0.439387f,0.0f}, -{0.915832f,-0.401562f,0.0f},{0.931774f,-0.363038f,0.0f},{0.946097f,-0.323885f,0.0f}, -{0.931774f,-0.36304f,0.0f},{0.958774f,-0.284168f,0.0f},{0.946096f,-0.323886f,0.0f}, -{0.958774f,-0.28417f,0.0f},{0.969786f,-0.243959f,0.0f},{0.969785f,-0.24396f,0.0f}, -{0.577412f,-0.816453f,0.0f},{0.577413f,-0.816452f,0.0f},{0.542879f,-0.839811f,0.0f}, -{0.507402f,-0.861709f,0.0f},{0.54288f,-0.83981f,0.0f},{0.471044f,-0.88211f,0.0f}, -{0.507404f,-0.861708f,0.0f},{0.471046f,-0.882109f,0.0f},{0.433866f,-0.900977f,0.0f}, -{0.395935f,-0.918278f,0.0f},{0.433869f,-0.900976f,0.0f},{0.357316f,-0.933984f,0.0f}, -{0.395937f,-0.918278f,0.0f},{0.357318f,-0.933983f,0.0f},{0.318075f,-0.948065f,0.0f}, -{0.278282f,-0.960499f,0.0f},{0.318077f,-0.948065f,0.0f},{0.238005f,-0.971264f,0.0f}, -{0.278284f,-0.960499f,0.0f},{0.238007f,-0.971263f,0.0f},{0.197314f,-0.98034f,0.0f}, -{0.15628f,-0.987713f,0.0f},{0.197316f,-0.98034f,0.0f},{0.114975f,-0.993368f,0.0f}, -{0.156283f,-0.987712f,0.0f},{0.114977f,-0.993368f,0.0f},{0.0734701f,-0.997297f,0.0f}, -{0.0318375f,-0.999493f,0.0f},{0.0734722f,-0.997297f,0.0f},{-0.00985025f,-0.999951f,0.0f}, -{0.0318392f,-0.999493f,0.0f},{-0.00984923f,-0.999951f,0.0f},{-0.0515206f,-0.998672f,0.0f}, -{0.866025f,-0.5f,-4.07254e-016f},{0.0706974f,0.997498f,4.22047e-015f},{0.042441f,0.999099f,-4.49972e-015f}, -{0.0424415f,0.999099f,-8.87378e-015f},{-0.0141508f,0.9999f,-1.48015e-015f},{0.014151f,0.9999f,0.0f}, -{0.0141508f,0.9999f,-7.42169e-015f},{0.0706979f,0.997498f,1.47659e-015f},{0.0988972f,0.995098f,5.89216e-015f}, -{0.0988976f,0.995098f,5.59937e-015f},{0.127018f,0.9919f,-1.17465e-014f},{0.127018f,0.9919f,-1.72436e-014f}, -{0.155036f,0.987909f,-5.3906e-015f},{0.155037f,0.987909f,5.84959e-015f},{0.182932f,0.983126f,-2.36905e-015f}, -{0.182931f,0.983126f,8.73191e-015f},{0.238259f,0.971202f,8.626e-015f},{0.265648f,0.96407f,-7.28139e-015f}, -{0.265647f,0.96407f,-1.29898e-014f},{0.210679f,0.977555f,-4.54082e-015f},{0.21068f,0.977555f,0.0f}, -{0.238258f,0.971202f,-1.29121e-014f},{0.292823f,0.956167f,-1.73386e-015f},{0.292823f,0.956167f,0.0f}, -{0.319764f,0.947497f,5.61031e-015f},{0.319764f,0.947497f,-1.89338e-015f},{0.346449f,0.938069f,0.0f}, -{0.346449f,0.938069f,7.60587e-015f},{0.372856f,0.927889f,9.90971e-015f},{0.424755f,0.905308f,5.3605e-015f}, -{0.424755f,0.905309f,3.304e-016f},{0.398966f,0.916966f,4.7247e-015f},{0.398965f,0.916966f,5.42953e-015f}, -{0.372857f,0.927889f,-7.70196e-015f},{0.450204f,0.892926f,0.0f},{0.450204f,0.892926f,5.33148e-015f}, -{0.475292f,0.879828f,1.04193e-014f},{0.475292f,0.879828f,1.04193e-014f},{-0.014151f,0.9999f,8.90184e-015f}, -{-0.042441f,0.999099f,-1.04784e-014f},{-0.0424415f,0.999099f,-1.61429e-014f},{-0.0706974f,0.997498f,8.65025e-015f}, -{-0.0988972f,0.995098f,2.94608e-015f},{-0.0706979f,0.997498f,-1.09175e-014f},{-0.0988976f,0.995098f,1.39984e-015f}, -{-0.127018f,0.9919f,-1.06363e-014f},{-0.127018f,0.9919f,9.63801e-015f},{-0.155036f,0.987909f,-7.40539e-015f}, -{-0.182931f,0.983126f,-7.57272e-015f},{-0.155037f,0.987909f,-2.5165e-015f},{-0.182932f,0.983126f,2.18298e-015f}, -{-0.210679f,0.977555f,7.64703e-015f},{-0.21068f,0.977555f,-4.23518e-015f},{-0.238258f,0.971202f,-1.03144e-014f}, -{-0.265647f,0.96407f,-7.60334e-015f},{-0.238259f,0.971202f,1.75636e-015f},{-0.265648f,0.96407f,1.0869e-014f}, -{-0.292823f,0.956167f,5.12754e-015f},{-0.292823f,0.956167f,-8.24033e-015f},{-0.319764f,0.947497f,3.07966e-016f}, -{-0.346449f,0.938069f,-1.05337e-014f},{-0.319764f,0.947497f,-8.2576e-015f},{-0.346449f,0.938069f,-1.87656e-015f}, -{-0.372856f,0.927889f,3.1746e-015f},{-0.372857f,0.927889f,-3.31849e-015f},{-0.398965f,0.916966f,3.06056e-015f}, -{-0.424755f,0.905309f,7.49538e-015f},{-0.398966f,0.916966f,4.02549e-015f},{-0.424755f,0.905308f,1.46943e-015f}, -{-0.450204f,0.892926f,-1.18685e-014f},{-0.450204f,0.892926f,1.25672e-015f},{-0.475292f,0.879828f,4.58408e-015f}, -{-0.475292f,0.879828f,1.83809e-015f},{-0.623541f,0.78179f,-1.15728e-015f},{-0.589568f,0.807718f,-2.39133e-015f}, -{-0.589571f,0.807717f,9.60223e-017f},{-0.656376f,0.754434f,-5.72909e-015f},{-0.656377f,0.754433f,-7.23689e-015f}, -{-0.688011f,0.7257f,1.01846e-015f},{-0.554522f,0.832169f,1.64171e-015f},{-0.623543f,0.781789f,4.8494e-015f}, -{-0.554519f,0.832171f,4.10543e-015f},{-0.51846f,0.855102f,-9.96661e-016f},{-0.518456f,0.855104f,1.53494e-015f}, -{-0.481448f,0.876475f,-5.18977e-015f},{-0.48145f,0.876473f,-4.02026e-015f},{-0.443562f,0.896244f,-2.65341e-015f}, -{-0.443559f,0.896245f,-3.96662e-015f},{-0.40486f,0.914379f,0.0f},{-0.365425f,0.930841f,0.0f}, -{-0.404864f,0.914377f,-2.39728e-015f},{-0.365423f,0.930842f,0.0f},{-0.325317f,0.945605f,-3.67284e-015f}, -{-0.32532f,0.945604f,0.0f},{-0.201738f,0.97944f,3.58358e-015f},{-0.243399f,0.969926f,-1.44121e-015f}, -{-0.201735f,0.97944f,-3.41043e-015f},{-0.284621f,0.95864f,7.36158e-015f},{-0.284618f,0.958641f,-5.6763e-015f}, -{-0.243401f,0.969926f,5.74311e-015f},{-0.159705f,0.987165f,9.45645e-016f},{-0.117381f,0.993087f,-1.03704e-014f}, -{-0.159703f,0.987165f,-4.89956e-015f},{-0.117378f,0.993087f,-6.9502e-016f},{-0.07484f,0.997196f,0.0f}, -{-0.0321655f,0.999483f,6.29904e-015f},{-0.032168f,0.999482f,-5.91813e-015f},{-0.0748434f,0.997195f,-8.86324e-016f}, -{0.0105685f,0.999944f,-5.7957e-015f},{0.0105657f,0.999944f,5.92086e-015f},{0.0532826f,0.99858f,0.0f}, -{0.05328f,0.99858f,0.0f},{0.0958981f,0.995391f,0.0f},{-0.718389f,0.695642f,-2.12686e-015f}, -{-0.688012f,0.725699f,-3.16696e-015f},{-0.718391f,0.69564f,6.73571e-017f},{-0.747455f,0.664312f,3.69231e-016f}, -{-0.747457f,0.66431f,-4.91688e-015f},{-0.775156f,0.631769f,-3.61476e-016f},{-0.801442f,0.598073f,-8.85326e-016f}, -{-0.775159f,0.631767f,-5.10676e-016f},{-0.801444f,0.59807f,-2.51436e-015f},{-0.826264f,0.563284f,-2.63707e-016f}, -{-0.826266f,0.563281f,-4.79448e-015f},{-0.849576f,0.527466f,2.47204e-015f},{-0.871337f,0.490685f,-7.45068e-016f}, -{-0.849578f,0.527463f,6.28814e-016f},{-0.871339f,0.490682f,-4.66609e-016f},{-0.891507f,0.453007f,-5.36872e-018f}, -{-0.891508f,0.453005f,1.90646e-015f},{-0.910048f,0.414503f,-9.01947e-016f},{-0.926927f,0.375241f,-7.55498e-016f}, -{-0.91005f,0.414499f,-3.44627e-015f},{-0.926928f,0.375238f,-8.26493e-018f},{-0.942114f,0.335293f,7.4317e-016f}, -{-0.942115f,0.335291f,-1.38718e-015f},{-0.955579f,0.294734f,-6.60361e-018f},{-0.9673f,0.253636f,1.39186e-016f}, -{-0.95558f,0.294731f,-4.80822e-016f},{-0.9673f,0.253634f,-1.1694e-015f},{-0.977253f,0.212076f,-1.09093e-015f}, -{-0.977254f,0.212073f,-1.42807e-015f},{-0.985422f,0.170128f,-8.58064e-016f},{-0.991791f,0.127868f,1.21011e-015f}, -{-0.985423f,0.170124f,3.47036e-015f},{-0.991791f,0.127866f,2.85545e-016f},{-0.996349f,0.0853758f,-4.87227e-016f}, -{-0.996349f,0.0853729f,3.21028e-015f},{-0.999087f,0.0427275f,-3.76158e-016f},{-1.0f,1.41083e-016f,0.0f}, -{-0.999087f,0.0427249f,-2.9625e-015f},{-1.0f,1.54309e-016f,0.0f},{-5.04647e-017f,1.0f,0.0f}, -{-5.3829e-017f,1.0f,0.0f},{-0.0541567f,0.998532f,0.0f},{-0.108145f,0.994135f,0.0f}, -{-0.0541301f,0.998534f,0.0f},{-0.161808f,0.986822f,0.0f},{-0.108105f,0.99414f,0.0f}, -{-0.161767f,0.986829f,0.0f},{-0.214992f,0.976616f,0.0f},{-0.267546f,0.963545f,0.0f}, -{-0.214964f,0.976622f,0.0f},{-0.319328f,0.947644f,0.0f},{-0.267531f,0.963549f,0.0f}, -{-0.319303f,0.947653f,0.0f},{-0.370172f,0.928963f,0.0f},{-0.419923f,0.90756f,0.0f}, -{-0.370136f,0.928977f,0.0f},{-0.46844f,0.883495f,0.0f},{-0.419887f,0.907577f,0.0f}, -{-0.468409f,0.883512f,0.0f},{-0.515581f,0.856841f,0.0f},{-0.56121f,0.827674f,0.0f}, -{-0.515559f,0.856854f,0.0f},{-0.605197f,0.796076f,0.0f},{-0.561199f,0.827681f,0.0f}, -{-0.605188f,0.796082f,0.0f},{-0.647411f,0.762141f,0.0f},{-0.687723f,0.725973f,0.0f}, -{-0.6474f,0.762151f,0.0f},{-0.726018f,0.687676f,0.0f},{-0.687712f,0.725983f,0.0f}, -{-0.726007f,0.687687f,0.0f},{-0.762183f,0.647361f,0.0f},{-0.796113f,0.605148f,0.0f}, -{-0.762171f,0.647375f,0.0f},{-0.827707f,0.56116f,0.0f},{-0.796101f,0.605164f,0.0f}, -{-0.827695f,0.561178f,0.0f},{-0.856873f,0.515527f,0.0f},{-0.883526f,0.468383f,0.0f}, -{-0.856862f,0.515545f,0.0f},{-0.907586f,0.419866f,0.0f},{-0.883516f,0.4684f,0.0f}, -{-0.907578f,0.419884f,0.0f},{-0.928986f,0.370116f,0.0f},{-0.947661f,0.319279f,0.0f}, -{-0.928977f,0.370136f,0.0f},{-0.963556f,0.267507f,0.0f},{-0.947653f,0.319301f,0.0f}, -{-0.96355f,0.267528f,0.0f},{-0.976624f,0.214954f,0.0f},{-0.986829f,0.16177f,0.0f}, -{-0.97662f,0.214973f,0.0f},{-0.994139f,0.108111f,0.0f},{-0.986826f,0.161786f,0.0f}, -{-0.994135f,0.108145f,0.0f},{-0.99855f,0.0538298f,0.0f},{-1.0f,-2.15316e-016f,0.0f}, -{-0.998551f,0.0538044f,0.0f},{-1.0f,-2.35502e-016f,0.0f},{0.0541566f,0.998532f,0.0f}, -{0.0541302f,0.998534f,0.0f},{0.108145f,0.994135f,0.0f},{0.161808f,0.986822f,0.0f}, -{0.108105f,0.99414f,0.0f},{0.214992f,0.976616f,0.0f},{0.161767f,0.986829f,0.0f}, -{0.214964f,0.976622f,0.0f},{0.267546f,0.963545f,0.0f},{0.319328f,0.947644f,0.0f}, -{0.267531f,0.963549f,0.0f},{0.370172f,0.928963f,0.0f},{0.319303f,0.947653f,0.0f}, -{0.370136f,0.928977f,0.0f},{0.419923f,0.90756f,0.0f},{0.46844f,0.883495f,0.0f}, -{0.419887f,0.907577f,0.0f},{0.515581f,0.856841f,0.0f},{0.468409f,0.883512f,0.0f}, -{0.515559f,0.856854f,0.0f},{0.56121f,0.827674f,0.0f},{0.605197f,0.796076f,0.0f}, -{0.561199f,0.827681f,0.0f},{0.647411f,0.762141f,0.0f},{0.605188f,0.796082f,0.0f}, -{0.6474f,0.762151f,0.0f},{0.687723f,0.725973f,0.0f},{0.726018f,0.687676f,0.0f}, -{0.687712f,0.725983f,0.0f},{0.762183f,0.647361f,0.0f},{0.726007f,0.687687f,0.0f}, -{0.762171f,0.647375f,0.0f},{0.796113f,0.605148f,0.0f},{0.827707f,0.56116f,0.0f}, -{0.796101f,0.605164f,0.0f},{0.856873f,0.515527f,0.0f},{0.827695f,0.561178f,0.0f}, -{0.856862f,0.515545f,0.0f},{0.883526f,0.468383f,0.0f},{0.907586f,0.419866f,0.0f}, -{0.883516f,0.468401f,0.0f},{0.928986f,0.370116f,0.0f},{0.907578f,0.419884f,0.0f}, -{0.928977f,0.370136f,0.0f},{0.947661f,0.319279f,0.0f},{0.963556f,0.267507f,0.0f}, -{0.947653f,0.319301f,0.0f},{0.976624f,0.214954f,0.0f},{0.96355f,0.267528f,0.0f}, -{0.97662f,0.214973f,0.0f},{0.986829f,0.16177f,0.0f},{0.994139f,0.108111f,0.0f}, -{0.986826f,0.161786f,0.0f},{0.99855f,0.0538298f,0.0f},{0.994135f,0.108145f,0.0f}, -{0.998551f,0.0538045f,0.0f},{1.0f,1.19209e-007f,0.0f},{0.718391f,0.69564f,-2.2967e-015f}, -{0.747457f,0.66431f,4.30948e-015f},{0.747455f,0.664312f,-2.35972e-015f},{0.688012f,0.725699f,-2.11837e-015f}, -{0.688011f,0.7257f,-4.7761e-015f},{0.656377f,0.754433f,-3.42054e-015f},{0.775156f,0.631769f,1.02241e-015f}, -{0.718389f,0.695642f,1.63365e-016f},{0.775159f,0.631766f,1.30928e-015f},{0.801442f,0.598073f,-4.02386e-016f}, -{0.801444f,0.59807f,3.14782e-015f},{0.826266f,0.563281f,2.05014e-015f},{0.826264f,0.563284f,2.15457e-016f}, -{0.849576f,0.527466f,3.68245e-015f},{0.849578f,0.527463f,-9.04405e-017f},{0.871339f,0.490682f,2.82586e-015f}, -{0.891507f,0.453007f,-1.11336e-015f},{0.871337f,0.490685f,-3.98744e-016f},{0.891508f,0.453005f,8.87668e-016f}, -{0.91005f,0.414499f,3.62163e-016f},{0.910048f,0.414503f,-2.33213e-015f},{0.955579f,0.294734f,1.39294e-015f}, -{0.942115f,0.335291f,1.29026e-015f},{0.95558f,0.294731f,9.56661e-016f},{0.926927f,0.375241f,3.09815e-015f}, -{0.926928f,0.375238f,3.53892e-016f},{0.942114f,0.335293f,1.78659e-015f},{0.9673f,0.253636f,4.48455e-017f}, -{0.977253f,0.212075f,9.31315e-017f},{0.9673f,0.253634f,-3.87537e-015f},{0.977254f,0.212073f,1.53976e-015f}, -{0.985423f,0.170124f,-1.33727e-015f},{0.991791f,0.127866f,1.31222e-015f},{0.991791f,0.127868f,-1.43479e-015f}, -{0.985422f,0.170128f,-1.08544e-015f},{0.996349f,0.0853729f,-2.96511e-015f},{0.996349f,0.0853758f,1.45956e-015f}, -{0.999087f,0.0427249f,-1.45746e-015f},{0.999087f,0.0427275f,2.97938e-015f},{1.0f,1.41083e-016f,0.0f}, -{1.0f,1.54309e-016f,0.0f},{0.623543f,0.781789f,-8.12728e-016f},{0.656376f,0.754434f,-2.4015e-015f}, -{0.623541f,0.78179f,-9.35104e-016f},{0.589571f,0.807717f,-3.8494e-015f},{0.589569f,0.807718f,8.37214e-016f}, -{0.554522f,0.832169f,-3.65599e-015f},{0.51846f,0.855102f,-4.07623e-015f},{0.554519f,0.832171f,2.81113e-015f}, -{0.518456f,0.855104f,2.96789e-016f},{0.48145f,0.876473f,3.95802e-015f},{0.481448f,0.876475f,6.89284e-016f}, -{0.443562f,0.896244f,7.12651e-016f},{0.404864f,0.914377f,-1.93578e-015f},{0.443559f,0.896245f,5.43092e-015f}, -{0.40486f,0.914379f,-5.84661e-015f},{0.365425f,0.930841f,1.20115e-015f},{0.365423f,0.930842f,3.55128e-015f}, -{0.32532f,0.945604f,2.23888e-015f},{0.284621f,0.95864f,5.39664e-015f},{0.325317f,0.945605f,4.0151e-015f}, -{0.284618f,0.958641f,-2.22393e-015f},{0.243401f,0.969926f,4.33048e-015f},{0.243399f,0.969926f,4.23515e-015f}, -{0.201738f,0.97944f,4.2777e-015f},{0.159705f,0.987165f,5.95984e-015f},{0.201735f,0.97944f,6.68731e-016f}, -{0.159703f,0.987165f,-8.70338e-015f},{0.117381f,0.993087f,-6.76187e-015f},{0.117378f,0.993087f,7.13795e-015f}, -{0.0748434f,0.997195f,-4.49833e-016f},{0.0321679f,0.999482f,5.88869e-015f},{0.07484f,0.997196f,-1.11652e-015f}, -{0.0321656f,0.999483f,-2.74195e-016f},{-0.0105657f,0.999944f,5.2388e-015f},{-0.0105686f,0.999944f,-6.15843e-016f}, -{-0.05328f,0.99858f,7.92959e-015f},{-0.0958981f,0.995391f,0.0f},{-0.0532825f,0.99858f,4.50329e-015f}, -{0.0141122f,-0.9999f,0.0f},{-0.0141124f,-0.9999f,0.0f},{0.0141125f,-0.9999f,0.0f}, -{0.0423259f,-0.999104f,0.0f},{0.0423254f,-0.999104f,0.0f},{0.0705055f,-0.997511f,0.0f}, -{0.0705051f,-0.997511f,0.0f},{0.0986284f,-0.995124f,0.0f},{0.0986291f,-0.995124f,0.0f}, -{0.126674f,-0.991944f,0.0f},{0.126673f,-0.991944f,0.0f},{0.154618f,-0.987974f,0.0f}, -{0.154617f,-0.987974f,0.0f},{0.182438f,-0.983217f,0.0f},{0.182439f,-0.983217f,0.0f}, -{0.210114f,-0.977677f,0.0f},{0.210113f,-0.977677f,0.0f},{0.237622f,-0.971358f,0.0f}, -{0.237622f,-0.971358f,0.0f},{0.26494f,-0.964265f,0.0f},{0.264941f,-0.964265f,0.0f}, -{0.292049f,-0.956403f,0.0f},{0.292048f,-0.956404f,0.0f},{0.318924f,-0.94778f,0.0f}, -{0.318923f,-0.947781f,0.0f},{0.345544f,-0.938403f,0.0f},{0.345545f,-0.938402f,0.0f}, -{0.371891f,-0.928277f,0.0f},{0.37189f,-0.928277f,0.0f},{0.39794f,-0.917411f,0.0f}, -{0.397939f,-0.917412f,0.0f},{0.423672f,-0.905816f,0.0f},{0.423672f,-0.905815f,0.0f}, -{0.449067f,-0.893498f,0.0f},{0.449067f,-0.893498f,0.0f},{0.474105f,-0.880469f,0.0f}, -{0.474104f,-0.880469f,0.0f},{0.498763f,-0.866738f,0.0f},{0.498764f,-0.866738f,0.0f}, -{0.523026f,-0.852317f,0.0f},{-0.0141122f,-0.9999f,0.0f},{-0.0423254f,-0.999104f,0.0f}, -{-0.0423259f,-0.999104f,0.0f},{-0.0705055f,-0.997511f,0.0f},{-0.0705051f,-0.997511f,0.0f}, -{-0.0986291f,-0.995124f,0.0f},{-0.0986285f,-0.995124f,0.0f},{-0.126673f,-0.991944f,0.0f}, -{-0.126674f,-0.991944f,0.0f},{-0.154618f,-0.987974f,0.0f},{-0.154617f,-0.987974f,0.0f}, -{-0.182439f,-0.983217f,0.0f},{-0.182438f,-0.983217f,0.0f},{-0.210113f,-0.977677f,0.0f}, -{-0.210114f,-0.977677f,0.0f},{-0.237622f,-0.971358f,0.0f},{-0.237622f,-0.971358f,0.0f}, -{-0.264941f,-0.964265f,0.0f},{-0.26494f,-0.964265f,0.0f},{-0.292048f,-0.956404f,0.0f}, -{-0.292049f,-0.956403f,0.0f},{-0.318924f,-0.94778f,0.0f},{-0.318923f,-0.947781f,0.0f}, -{-0.345545f,-0.938402f,0.0f},{-0.345544f,-0.938403f,0.0f},{-0.37189f,-0.928277f,0.0f}, -{-0.371891f,-0.928277f,0.0f},{-0.39794f,-0.917411f,0.0f},{-0.397939f,-0.917412f,0.0f}, -{-0.423672f,-0.905815f,0.0f},{-0.423672f,-0.905816f,0.0f},{-0.449067f,-0.893498f,0.0f}, -{-0.449067f,-0.893498f,0.0f},{-0.474104f,-0.880469f,0.0f},{-0.474104f,-0.880469f,0.0f}, -{-0.498764f,-0.866738f,0.0f},{-0.498764f,-0.866738f,0.0f},{-0.523026f,-0.852317f,0.0f}, -{-0.866025f,-0.5f,-7.6671e-016f},{-0.466272f,-0.884642f,2.20644e-016f},{-0.628286f,-0.777982f,5.89571e-016f}, -{-0.628223f,-0.778033f,-5.53502e-016f},{-0.286781f,-0.957996f,1.48116e-016f},{-0.466199f,-0.88468f,-5.1317e-016f}, -{-0.286593f,-0.958053f,-1.63827e-016f},{0.0974696f,-0.995238f,3.44802e-016f},{-0.0962625f,-0.995356f,-1.06856e-016f}, -{0.097635f,-0.995222f,-4.56953e-017f},{-0.0964852f,-0.995334f,-1.31963e-016f},{-0.766564f,-0.642168f,0.0f}, -{-0.876095f,-0.482138f,-7.37654e-016f},{-0.76669f,-0.642017f,-1.10523e-015f},{-0.876203f,-0.481942f,7.37698e-016f}, -{-0.952689f,-0.303947f,0.0f},{-0.952739f,-0.303789f,0.0f},{-0.698102f,-0.715999f,1.29175e-016f}, -{-0.324434f,-0.945908f,-5.70109e-016f},{-0.324434f,-0.945908f,-3.35048e-016f},{-0.524032f,-0.851699f,7.27349e-016f}, -{-4.59243e-017f,1.0f,0.0f},{-4.12983e-017f,1.0f,0.0f},{0.173688f,0.984801f,0.0f}, -{0.342031f,0.939689f,0.0f},{0.173343f,0.984861f,0.0f},{0.341751f,0.939791f,0.0f}, -{0.499517f,0.866304f,0.0f},{0.642133f,0.766593f,0.0f},{0.50031f,0.865846f,0.0f}, -{0.64411f,0.764933f,0.0f},{0.765765f,0.64312f,0.0f},{0.766272f,0.642516f,0.0f}, -{0.865946f,0.500137f,0.0f},{0.939669f,0.342084f,0.0f},{0.866231f,0.499643f,0.0f}, -{0.939879f,0.341507f,0.0f},{0.984809f,0.173642f,0.0f},{0.984871f,0.173291f,0.0f}, -{-0.173688f,0.984801f,0.0f},{-0.342031f,0.939689f,0.0f},{-0.173343f,0.984861f,0.0f}, -{-0.499517f,0.866304f,0.0f},{-0.341751f,0.939791f,0.0f},{-0.50031f,0.865846f,0.0f}, -{-0.642133f,0.766593f,0.0f},{-0.64411f,0.764933f,0.0f},{-0.765765f,0.64312f,0.0f}, -{-0.865946f,0.500137f,0.0f},{-0.766272f,0.642516f,0.0f},{-0.866231f,0.499643f,0.0f}, -{-0.939669f,0.342084f,0.0f},{-0.939879f,0.341507f,0.0f},{-0.984809f,0.173642f,0.0f}, -{-0.984871f,0.173291f,0.0f},{-1.0f,7.40149e-017f,0.0f},{-1.0f,8.32667e-017f,0.0f}, -{0.130634f,0.991431f,0.0f},{0.258991f,0.96588f,0.0f},{0.130461f,0.991453f,0.0f}, -{0.382876f,0.9238f,0.0f},{0.258717f,0.965953f,0.0f},{0.382576f,0.923924f,0.0f}, -{0.500177f,0.865923f,0.0f},{0.608898f,0.793249f,0.0f},{0.499909f,0.866078f,0.0f}, -{0.707182f,0.707032f,0.0f},{0.608701f,0.7934f,0.0f},{0.70708f,0.707133f,0.0f}, -{0.793414f,0.608682f,0.0f},{0.866063f,0.499935f,0.0f},{0.793302f,0.608828f,0.0f}, -{0.923898f,0.38264f,0.0f},{0.865926f,0.500171f,0.0f},{0.965902f,0.258907f,0.0f}, -{0.923984f,0.382431f,0.0f},{0.966265f,0.257551f,0.0f},{0.991435f,0.130601f,0.0f}, -{0.99153f,0.129881f,0.0f},{1.0f,8.88178e-017f,0.0f},{-0.130634f,0.991431f,0.0f}, -{-0.258991f,0.96588f,0.0f},{-0.130461f,0.991453f,0.0f},{-0.258717f,0.965953f,0.0f}, -{-0.382876f,0.9238f,0.0f},{-0.500177f,0.865923f,0.0f},{-0.382576f,0.923924f,0.0f}, -{-0.608898f,0.793249f,0.0f},{-0.499909f,0.866078f,0.0f},{-0.608701f,0.7934f,0.0f}, -{-0.707182f,0.707032f,0.0f},{-0.793414f,0.608682f,0.0f},{-0.70708f,0.707134f,0.0f}, -{-0.866063f,0.499936f,0.0f},{-0.793302f,0.608828f,0.0f},{-0.865926f,0.500171f,0.0f}, -{-0.923898f,0.38264f,0.0f},{-0.965902f,0.258907f,0.0f},{-0.923984f,0.382431f,0.0f}, -{-0.966265f,0.257551f,0.0f},{-0.991435f,0.130601f,0.0f},{-0.99153f,0.129881f,0.0f}, -{0.913335f,0.40721f,7.99247e-017f},{0.808642f,0.588301f,3.74072e-017f},{0.809321f,0.587366f,1.2922e-016f}, -{0.913805f,0.406154f,-3.28816e-017f},{0.977984f,0.208678f,5.8208e-017f},{0.978488f,0.206306f,5.99861e-018f}, -{0.999999f,-0.00162857f,2.63678e-019f},{0.97822f,-0.207569f,-8.05697e-017f},{1.0f,0.000654662f,6.93738e-017f}, -{0.977876f,-0.209184f,1.45735e-017f},{0.913594f,-0.406629f,-1.15091e-016f},{0.913137f,-0.407652f,-4.53528e-017f}, -{0.809021f,-0.58778f,2.29704e-017f},{0.80856f,-0.588414f,1.22753e-016f},{0.669069f,-0.7432f,-6.9929e-017f}, -{0.668748f,-0.743489f,-3.64576e-017f},{0.669713f,0.74262f,-6.87062e-017f},{0.500567f,0.865698f,-4.63117e-017f}, -{0.66791f,0.744242f,7.06215e-018f},{0.498589f,0.866839f,1.14269e-016f},{0.30935f,0.950948f,-5.56503e-016f}, -{0.30778f,0.951458f,-4.71214e-016f},{0.104646f,0.99451f,-2.03385e-016f},{-0.104522f,0.994523f,-3.87388e-016f}, -{0.103531f,0.994626f,-1.84043e-016f},{-0.105302f,0.99444f,1.94848e-017f},{-0.309096f,0.951031f,0.0f}, -{-0.309506f,0.950897f,-5.72701e-017f},{0.900926f,0.433972f,8.6404e-017f},{0.826202f,0.563374f,-2.43165e-017f}, -{0.826294f,0.563239f,2.43374e-017f},{0.955531f,0.294892f,6.11214e-017f},{0.900997f,0.433825f,-3.70517e-017f}, -{0.955592f,0.294693f,-3.87521e-016f},{0.988805f,0.149217f,6.64494e-017f},{0.988837f,0.149001f,-2.17435e-016f}, -{1.0f,1.20654e-005f,-2.79068e-022f},{1.0f,0.000192253f,1.7787e-020f},{0.988875f,-0.148747f,1.44115e-016f}, -{0.900667f,-0.43451f,4.63232e-017f},{0.826465f,-0.562987f,2.00756e-016f},{0.901106f,-0.4336f,5.63359e-017f}, -{0.988831f,-0.14904f,-1.04015e-016f},{0.955631f,-0.294565f,-1.19073e-016f},{0.95558f,-0.294731f,1.85876e-017f}, -{0.825308f,-0.564682f,7.07051e-017f},{0.733215f,-0.679997f,6.20149e-017f},{0.733055f,-0.68017f,8.707e-017f}, -{0.623408f,-0.781897f,1.16904e-016f},{0.623556f,-0.781778f,-3.96622e-018f},{0.733149f,0.680068f,2.61498e-016f}, -{0.623627f,0.781722f,-1.73901e-016f},{0.733007f,0.680221f,-2.51732e-016f},{0.623458f,0.781857f,-4.04708e-016f}, -{0.500166f,0.865929f,9.25494e-017f},{0.500011f,0.866019f,-9.25205e-017f},{0.365619f,0.930764f,-6.76531e-017f}, -{0.222715f,0.974884f,0.0f},{0.365343f,0.930873f,-3.0745e-016f},{0.222546f,0.974922f,-3.60794e-016f}, -{0.0750445f,0.99718f,1.84515e-016f},{0.0740373f,0.997255f,0.0f},{-0.0743287f,0.997234f,0.0f}, -{-0.222287f,0.974981f,-4.43078e-016f},{-0.0763749f,0.997079f,2.82644e-017f},{-0.222517f,0.974929f,8.23479e-017f}, -{-0.365262f,0.930905f,-3.44504e-016f},{-0.365439f,0.930835f,0.0f},{0.809321f,-0.587366f,1.2922e-016f}, -{0.913805f,-0.406154f,8.45439e-017f},{0.913335f,-0.40721f,-7.99247e-017f},{0.808642f,-0.588301f,2.03856e-017f}, -{0.669713f,-0.74262f,8.75691e-017f},{0.66791f,-0.744242f,1.34181e-016f},{0.498589f,-0.866839f,2.64187e-016f}, -{0.30935f,-0.950948f,-3.88237e-017f},{0.500567f,-0.865698f,3.37814e-017f},{0.30778f,-0.951458f,4.53145e-017f}, -{0.104646f,-0.99451f,7.86897e-017f},{0.103531f,-0.994626f,8.15879e-017f},{-0.104522f,-0.994523f,4.82678e-017f}, -{-0.105302f,-0.99444f,-1.17707e-017f},{-0.309096f,-0.951031f,-6.56523e-017f},{-0.309506f,-0.950897f,3.18526e-017f}, -{0.977984f,-0.208678f,1.93066e-017f},{1.0f,-0.000654662f,0.0f},{0.978488f,-0.206306f,2.00144e-016f}, -{0.999999f,0.00162868f,-1.85338e-016f},{0.97822f,0.207569f,-7.6816e-017f},{0.977876f,0.209183f,-1.29178e-016f}, -{0.913594f,0.406629f,-7.52414e-017f},{0.809021f,0.58778f,1.49699e-016f},{0.913137f,0.407652f,2.44395e-016f}, -{0.80856f,0.588414f,3.67371e-016f},{0.669069f,0.7432f,2.75039e-016f},{0.668748f,0.743489f,-2.75146e-016f}, -{0.826294f,-0.563239f,6.1666e-017f},{0.900997f,-0.433825f,3.08521e-018f},{0.900926f,-0.433972f,-5.64113e-017f}, -{0.733149f,-0.680068f,-2.56587e-016f},{0.826202f,-0.563374f,-1.46813e-016f},{0.733007f,-0.680221f,1.63368e-016f}, -{0.623628f,-0.781722f,-7.95359e-017f},{0.623458f,-0.781857f,-7.21018e-018f},{0.50001f,-0.866019f,1.15651e-017f}, -{0.500166f,-0.865929f,1.23064e-016f},{0.365619f,-0.930764f,1.23884e-016f},{0.0740373f,-0.997256f,1.28434e-018f}, -{-0.0743287f,-0.997234f,-3.03579e-016f},{0.0750446f,-0.99718f,-2.99946e-016f},{0.365343f,-0.930873f,5.04555e-017f}, -{0.222715f,-0.974884f,4.70292e-017f},{0.222546f,-0.974922f,3.93084e-017f},{-0.0763749f,-0.997079f,-3.81629e-016f}, -{-0.222287f,-0.974981f,-8.52052e-017f},{-0.222517f,-0.974929f,8.99959e-017f},{-0.365439f,-0.930835f,-2.28984e-016f}, -{-0.365262f,-0.930905f,2.02233e-016f},{0.955531f,-0.294892f,-6.63033e-017f},{0.988805f,-0.149216f,9.47978e-018f}, -{0.955592f,-0.294693f,-1.98923e-016f},{0.988837f,-0.149002f,-1.41928e-016f},{1.0f,-0.000192142f,-2.31296e-017f}, -{1.0f,-1.21766e-005f,-2.31342e-017f},{0.988875f,0.148747f,1.00792e-016f},{0.955631f,0.294565f,1.09011e-016f}, -{0.988831f,0.14904f,5.5156e-017f},{0.95558f,0.294731f,6.48678e-017f},{0.901106f,0.4336f,0.0f}, -{0.900667f,0.43451f,0.0f},{0.826465f,0.562987f,-2.46579e-016f},{0.733215f,0.679997f,-2.85567e-016f}, -{0.825308f,0.564682f,3.81782e-017f},{0.733055f,0.68017f,3.19535e-016f},{0.623556f,0.781778f,2.88453e-017f}, -{0.623408f,0.781897f,0.0f},{-0.104013f,-0.994576f,-5.73969e-018f},{0.105163f,-0.994455f,-5.04765e-018f}, -{0.104013f,-0.994576f,-5.37603e-017f},{-0.105163f,-0.994455f,-2.56228e-017f},{-0.308272f,-0.951298f,-1.34015e-017f}, -{-0.310578f,-0.950548f,7.65272e-018f},{-0.50141f,-0.86521f,-4.26767e-017f},{-0.66887f,-0.743379f,-1.02395e-016f}, -{-0.499433f,-0.866353f,-6.51189e-017f},{-0.670096f,-0.742274f,-1.6733e-017f},{-0.808947f,-0.587881f,-4.74286e-017f}, -{-0.809606f,-0.586974f,-1.22396e-016f},{-0.913543f,-0.406743f,1.98726e-016f},{-0.913862f,-0.406026f,6.87164e-017f}, -{-0.978165f,-0.20783f,2.25061e-016f},{-0.978254f,-0.207408f,-6.67845e-017f},{-1.0f,2.22045e-016f,0.0f}, -{0.308272f,-0.951298f,-2.63823e-017f},{0.499433f,-0.866353f,-1.48319e-016f},{0.310578f,-0.950548f,8.91888e-017f}, -{0.50141f,-0.86521f,1.30238e-016f},{0.66887f,-0.743379f,-2.55902e-017f},{0.670096f,-0.742274f,9.43118e-018f}, -{0.808947f,-0.587881f,-2.24438e-017f},{0.913543f,-0.406743f,2.2274e-018f},{0.809606f,-0.586974f,-2.2055e-017f}, -{0.913862f,-0.406026f,2.39531e-018f},{0.978165f,-0.20783f,5.02738e-019f},{0.978254f,-0.207408f,-3.61477e-016f}, -{1.0f,-9.4369e-016f,0.0f},{1.0f,-4.44089e-016f,0.0f},{-0.0746326f,-0.997211f,3.23205e-017f}, -{0.074795f,-0.997199f,-1.38399e-017f},{0.0746326f,-0.997211f,-5.99401e-017f},{-0.222381f,-0.97496f,0.0f}, -{-0.074795f,-0.997199f,-4.61297e-017f},{-0.222585f,-0.974913f,4.11864e-017f},{-0.365177f,-0.930938f,-9.83825e-017f}, -{-0.365379f,-0.930859f,1.2274e-017f},{-0.49999f,-0.866031f,-4.93565e-017f},{-0.499833f,-0.866122f,-4.3155e-017f}, -{-0.623256f,-0.782018f,1.09954e-016f},{-0.82663f,-0.562746f,3.25403e-018f},{-0.900794f,-0.434246f,1.50224e-016f}, -{-0.826061f,-0.563581f,1.56111e-016f},{-0.623488f,-0.781833f,4.15463e-017f},{-0.732917f,-0.680318f,6.65918e-017f}, -{-0.733034f,-0.680192f,2.58522e-016f},{-0.901683f,-0.432397f,-2.442e-016f},{-0.955502f,-0.294984f,1.58495e-016f}, -{-0.955572f,-0.294759f,-5.2973e-017f},{-0.988846f,-0.148938f,8.9777e-017f},{-0.988818f,-0.149126f,7.06523e-017f}, -{-1.0f,1.11022e-016f,0.0f},{0.222381f,-0.97496f,-4.11488e-017f},{0.365177f,-0.930938f,-6.75713e-017f}, -{0.222585f,-0.974913f,-8.23729e-017f},{0.365379f,-0.930859f,-6.76088e-017f},{0.499834f,-0.866121f,1.7262e-016f}, -{0.499989f,-0.866031f,-8.0124e-017f},{0.623256f,-0.782018f,0.0f},{0.732917f,-0.680318f,0.0f}, -{0.623488f,-0.781833f,0.0f},{0.733034f,-0.680192f,-2.71277e-016f},{0.826061f,-0.563581f,0.0f}, -{0.82663f,-0.562746f,-1.04129e-016f},{0.900794f,-0.434246f,3.33361e-016f},{0.955502f,-0.294984f,0.0f}, -{0.901683f,-0.432397f,0.0f},{0.955572f,-0.294759f,5.45414e-017f},{0.988818f,-0.149126f,0.0f}, -{0.988846f,-0.148938f,2.75591e-017f},{1.0f,-4.996e-016f,0.0f},{1.0f,-6.66134e-016f,0.0f}, -{-0.913335f,-0.40721f,-4.22502e-017f},{-0.808642f,-0.588301f,-1.70216e-017f},{-0.809321f,-0.587366f,-2.37904e-016f}, -{-0.913805f,-0.406154f,-3.28816e-017f},{-0.977984f,-0.208678f,-4.85547e-017f},{-0.978488f,-0.206306f,5.48077e-017f}, -{-0.999999f,0.00162857f,4.59202e-017f},{-0.97822f,0.207569f,6.16976e-017f},{-1.0f,-0.000654662f,-1.21137e-019f}, -{-0.977876f,0.209184f,-1.1309e-017f},{-0.913594f,0.406629f,-1.82302e-017f},{-0.913137f,0.407652f,-6.61902e-017f}, -{-0.809021f,0.58778f,3.39878e-018f},{-0.80856f,0.588414f,-4.63496e-017f},{-0.669069f,0.7432f,-3.99078e-017f}, -{-0.668748f,0.743489f,-1.35216e-017f},{-0.669713f,-0.74262f,1.44158e-016f},{-0.500567f,-0.865698f,1.60186e-016f}, -{-0.66791f,-0.744242f,1.44775e-016f},{-0.498589f,-0.866839f,-1.14269e-016f},{-0.30935f,-0.950948f,-2.04581e-016f}, -{-0.30778f,-0.951458f,0.0f},{-0.104646f,-0.99451f,-1.84021e-016f},{0.104522f,-0.994523f,-3.87388e-016f}, -{-0.103531f,-0.994626f,3.68086e-016f},{0.105302f,-0.99444f,-3.68017e-016f},{0.309096f,-0.951031f,0.0f}, -{0.309506f,-0.950897f,-4.09173e-016f},{-0.900926f,-0.433972f,-8.03009e-017f},{-0.826202f,-0.563374f,2.29317e-016f}, -{-0.826294f,-0.563239f,5.21101e-017f},{-0.955531f,-0.294892f,6.76768e-017f},{-0.900997f,-0.433825f,-2.43906e-016f}, -{-0.955592f,-0.294693f,-1.2269e-016f},{-0.988805f,-0.149217f,-6.90265e-018f},{-0.988837f,-0.149001f,1.19057e-016f}, -{-1.0f,-1.20654e-005f,4.62596e-017f},{-1.0f,-0.000192253f,9.25097e-017f},{-0.988875f,0.148747f,1.64758e-016f}, -{-0.900667f,0.43451f,-2.6511e-016f},{-0.826465f,0.562987f,-1.78554e-016f},{-0.901106f,0.4336f,8.0232e-017f}, -{-0.988831f,0.14904f,9.49325e-017f},{-0.955631f,0.294565f,-1.18836e-017f},{-0.95558f,0.294731f,1.83741e-016f}, -{-0.825308f,0.564682f,1.30735e-016f},{-0.733215f,0.679997f,-5.59715e-017f},{-0.733055f,0.68017f,3.51996e-017f}, -{-0.623408f,0.781897f,1.10427e-016f},{-0.623556f,0.781778f,-6.84852e-018f},{-0.733149f,-0.680068f,-1.16016e-016f}, -{-0.623627f,-0.781722f,-2.89295e-016f},{-0.733007f,-0.680221f,0.0f},{-0.623458f,-0.781857f,2.30726e-016f}, -{-0.500166f,-0.865929f,-1.85099e-016f},{-0.500011f,-0.866019f,-9.25205e-017f},{-0.365619f,-0.930764f,-5.16678e-016f}, -{-0.222715f,-0.974884f,1.8039e-016f},{-0.365343f,-0.930873f,-6.7602e-017f},{-0.222546f,-0.974922f,-3.60794e-016f}, -{-0.0750445f,-0.99718f,3.96803e-016f},{-0.0740373f,-0.997255f,0.0f},{0.0743287f,-0.997234f,0.0f}, -{0.222287f,-0.974981f,-8.22628e-017f},{0.0763749f,-0.997079f,0.0f},{0.222517f,-0.974929f,-3.60796e-016f}, -{0.365262f,-0.930905f,-3.44504e-016f},{0.365439f,-0.930835f,0.0f},{-0.809321f,0.587366f,-1.63027e-016f}, -{-0.913805f,0.406154f,2.48937e-016f},{-0.913335f,0.40721f,9.15149e-018f},{-0.808642f,0.588301f,3.40432e-017f}, -{-0.669713f,0.74262f,1.58275e-016f},{-0.66791f,0.744242f,-1.89796e-017f},{-0.498589f,0.866839f,-9.04411e-018f}, -{-0.30935f,0.950948f,1.30911e-016f},{-0.500567f,0.865698f,-4.94443e-017f},{-0.30778f,0.951458f,2.91257e-017f}, -{-0.104646f,0.99451f,1.16829e-016f},{-0.103531f,0.994626f,-6.18321e-017f},{0.104522f,0.994523f,3.11622e-017f}, -{0.105302f,0.99444f,2.24587e-017f},{0.309096f,0.951031f,-1.31801e-016f},{0.309506f,0.950897f,3.8811e-017f}, -{-0.977984f,0.208678f,-9.04817e-017f},{-1.0f,0.000654662f,-1.21137e-019f},{-0.978488f,0.206306f,5.2354e-017f}, -{-0.999999f,-0.00162868f,-1.85338e-016f},{-0.97822f,-0.207569f,-9.05036e-017f},{-0.977876f,-0.209183f,-5.1765e-017f}, -{-0.913594f,-0.406629f,-7.52414e-017f},{-0.809021f,-0.58778f,-1.49699e-016f},{-0.913137f,-0.407652f,7.54309e-017f}, -{-0.80856f,-0.588414f,1.49614e-016f},{-0.669069f,-0.7432f,3.98842e-016f},{-0.668748f,-0.743489f,0.0f}, -{-0.826294f,0.563239f,-1.23332e-016f},{-0.900997f,0.433825f,6.25192e-017f},{-0.900926f,0.433972f,-6.10305e-018f}, -{-0.733149f,0.680068f,1.0888e-016f},{-0.826202f,0.563374f,3.30128e-017f},{-0.733007f,0.680221f,2.90247e-017f}, -{-0.623628f,0.781722f,2.82083e-016f},{-0.623458f,0.781857f,3.62854e-017f},{-0.50001f,0.866019f,2.14764e-016f}, -{-0.500166f,0.865929f,-6.03025e-017f},{-0.365619f,0.930764f,5.46844e-017f},{-0.0740373f,0.997256f,-1.62533e-016f}, -{0.0743287f,0.997234f,-1.15704e-016f},{-0.0750446f,0.99718f,2.87654e-016f},{-0.365343f,0.930873f,-1.82809e-016f}, -{-0.222715f,0.974884f,-6.76461e-017f},{-0.222546f,0.974922f,2.62874e-016f},{0.0763749f,0.997079f,-2.1338e-016f}, -{0.222287f,0.974981f,-2.68797e-016f},{0.222517f,0.974929f,-7.60189e-017f},{0.365439f,0.930835f,-1.46759e-016f}, -{0.365262f,0.930905f,2.96533e-016f},{-0.955531f,0.294892f,7.66671e-017f},{-0.988805f,0.149216f,6.38722e-017f}, -{-0.955592f,0.294693f,-1.10513e-016f},{-0.988837f,0.149002f,2.28714e-017f},{-1.0f,0.000192142f,0.0f}, -{-1.0f,1.21766e-005f,2.31342e-017f},{-0.988875f,-0.148747f,-4.57447e-017f},{-0.955631f,-0.294565f,1.53218e-016f}, -{-0.988831f,-0.14904f,0.0f},{-0.95558f,-0.294731f,0.0f},{-0.901106f,-0.4336f,-8.3369e-017f}, -{-0.900667f,-0.43451f,4.16642e-017f},{-0.826465f,-0.562987f,-3.82317e-017f},{-0.733215f,-0.679997f,0.0f}, -{-0.825308f,-0.564682f,-1.70796e-016f},{-0.733055f,-0.68017f,-6.78212e-017f},{-0.623556f,-0.781778f,-2.88453e-017f}, -{-0.623408f,-0.781897f,-2.88384e-017f},{0.104013f,0.994576f,7.26654e-018f},{-0.105163f,0.994455f,-2.43825e-017f}, -{-0.104013f,0.994576f,8.93001e-017f},{0.105163f,0.994455f,1.32311e-017f},{0.308272f,0.951298f,-7.55182e-017f}, -{0.310578f,0.950548f,-4.45961e-018f},{0.50141f,0.86521f,-6.50915e-017f},{0.66887f,0.743379f,1.15799e-016f}, -{0.499433f,0.866353f,-4.79524e-017f},{0.670096f,0.742274f,-6.82852e-017f},{0.808947f,0.587881f,-6.27019e-017f}, -{0.809606f,0.586974f,-1.8867e-016f},{0.913543f,0.406743f,2.68879e-016f},{0.913862f,0.406026f,5.33518e-018f}, -{0.978165f,0.20783f,-6.04996e-017f},{0.978254f,0.207408f,1.68043e-016f},{1.0f,2.498e-016f,0.0f}, -{-0.308272f,0.951298f,-7.04878e-018f},{-0.499433f,0.866353f,6.84015e-018f},{-0.310578f,0.950548f,5.99884e-018f}, -{-0.50141f,0.86521f,6.84674e-018f},{-0.66887f,0.743379f,7.13059e-018f},{-0.670096f,0.742274f,1.31123e-016f}, -{-0.808947f,0.587881f,6.66802e-018f},{-0.913543f,0.406743f,-3.42154e-016f},{-0.809606f,0.586974f,2.02398e-017f}, -{-0.913862f,0.406026f,-4.06525e-018f},{-0.978165f,0.20783f,6.87323e-019f},{-0.978254f,0.207408f,-3.6134e-016f}, -{-1.0f,-3.88578e-016f,0.0f},{-1.0f,4.44089e-016f,0.0f},{0.0746326f,0.997211f,-1.85107e-017f}, -{-0.074795f,0.997199f,-2.76797e-017f},{-0.0746326f,0.997211f,-4.61303e-017f},{0.222381f,0.97496f,-1.06824e-016f}, -{0.074795f,0.997199f,4.61297e-017f},{0.222585f,0.974913f,-2.05932e-017f},{0.365177f,0.930938f,3.37857e-017f}, -{0.365379f,0.930859f,-6.76088e-017f},{0.49999f,0.866031f,-1.32579e-016f},{0.499833f,0.866122f,1.49498e-016f}, -{0.623256f,0.782018f,-1.46129e-016f},{0.82663f,0.562746f,-2.18847e-016f},{0.900794f,0.434246f,8.55296e-017f}, -{0.826061f,0.563581f,1.43299e-016f},{0.623488f,0.781833f,2.1746e-017f},{0.732917f,0.680318f,-1.16232e-016f}, -{0.733034f,0.680192f,2.20413e-016f},{0.901683f,0.432397f,-2.49017e-016f},{0.955502f,0.294984f,-5.72353e-017f}, -{0.955572f,0.294759f,-1.44419e-016f},{0.988846f,0.148938f,-1.64846e-016f},{1.0f,-1.11022e-016f,0.0f}, -{0.988818f,0.149126f,-1.13952e-016f},{1.0f,-2.35922e-016f,0.0f},{-0.222381f,0.97496f,0.0f}, -{-0.365177f,0.930938f,-6.75713e-017f},{-0.222585f,0.974913f,-4.90112e-017f},{-0.365379f,0.930859f,6.76088e-017f}, -{-0.499834f,0.866121f,-1.04843e-016f},{-0.499989f,0.866031f,0.0f},{-0.623256f,0.782018f,2.30651e-016f}, -{-0.732917f,0.680318f,-3.97118e-016f},{-0.623488f,0.781833f,-7.23341e-017f},{-0.733034f,0.680192f,0.0f}, -{-0.826061f,0.563581f,0.0f},{-0.82663f,0.562746f,2.01786e-016f},{-0.900794f,0.434246f,-4.13713e-016f}, -{-0.955502f,0.294984f,-3.53607e-016f},{-0.901683f,0.432397f,0.0f},{-0.955572f,0.294759f,-3.53633e-016f}, -{-0.988818f,0.149126f,-3.65936e-016f},{-0.988846f,0.148938f,2.75591e-017f},{-1.0f,-2.498e-016f,0.0f}, -{4.59243e-017f,1.0f,0.0f},{4.12983e-017f,1.0f,0.0f},{-0.173688f,0.984801f,0.0f}, -{-0.342031f,0.939689f,0.0f},{-0.173343f,0.984861f,0.0f},{-0.341751f,0.939791f,0.0f}, -{-0.499517f,0.866304f,0.0f},{-0.642133f,0.766593f,0.0f},{-0.50031f,0.865846f,0.0f}, -{-0.765765f,0.64312f,0.0f},{-0.766272f,0.642516f,0.0f},{-0.865946f,0.500137f,0.0f}, -{-0.939669f,0.342084f,0.0f},{-0.866231f,0.499643f,0.0f},{-0.939879f,0.341507f,0.0f}, -{-0.984809f,0.173642f,0.0f},{-0.984871f,0.173291f,0.0f},{0.173688f,0.984801f,0.0f}, -{0.342031f,0.939689f,0.0f},{0.173343f,0.984861f,0.0f},{0.499517f,0.866304f,0.0f}, -{0.341751f,0.939791f,0.0f},{0.50031f,0.865846f,0.0f},{0.642133f,0.766593f,0.0f}, -{0.765765f,0.64312f,0.0f},{0.865946f,0.500137f,0.0f},{0.766272f,0.642516f,0.0f}, -{0.866231f,0.499643f,0.0f},{0.939669f,0.342084f,0.0f},{0.939879f,0.341507f,0.0f}, -{0.984809f,0.173642f,0.0f},{0.984871f,0.173291f,0.0f},{1.0f,8.32667e-017f,0.0f}, -{4.24548e-017f,1.0f,0.0f},{-0.0981573f,0.995171f,0.0f},{-0.0979559f,0.995191f,0.0f}, -{-0.195278f,0.980748f,0.0f},{-0.290455f,0.956889f,0.0f},{-0.194999f,0.980803f,0.0f}, -{-0.382807f,0.923829f,0.0f},{-0.290209f,0.956963f,0.0f},{-0.382668f,0.923886f,0.0f}, -{-0.471474f,0.88188f,0.0f},{-0.555711f,0.831376f,0.0f},{-0.471468f,0.881883f,0.0f}, -{-0.634547f,0.772884f,0.0f},{-0.555621f,0.831435f,0.0f},{-0.634433f,0.772978f,0.0f}, -{-0.707246f,0.706968f,0.0f},{-0.773125f,0.634253f,0.0f},{-0.707144f,0.70707f,0.0f}, -{-0.83156f,0.555435f,0.0f},{-0.773048f,0.634347f,0.0f},{-0.831507f,0.555514f,0.0f}, -{-0.881988f,0.471271f,0.0f},{-0.923925f,0.382573f,0.0f},{-0.881956f,0.471332f,0.0f}, -{-0.956966f,0.290201f,0.0f},{-0.923909f,0.382613f,0.0f},{-0.956961f,0.290216f,0.0f}, -{-0.980794f,0.195045f,0.0f},{-0.995188f,0.0979878f,0.0f},{-0.980794f,0.195048f,0.0f}, -{-1.0f,5.55112e-017f,0.0f},{-0.995188f,0.0979889f,0.0f},{0.0981573f,0.995171f,0.0f}, -{0.195278f,0.980748f,0.0f},{0.0979559f,0.995191f,0.0f},{0.290455f,0.956889f,0.0f}, -{0.194999f,0.980803f,0.0f},{0.290209f,0.956963f,0.0f},{0.382806f,0.923829f,0.0f}, -{0.471474f,0.88188f,0.0f},{0.382668f,0.923886f,0.0f},{0.555711f,0.831376f,0.0f}, -{0.471468f,0.881883f,0.0f},{0.555621f,0.831435f,0.0f},{0.634547f,0.772884f,0.0f}, -{0.707246f,0.706968f,0.0f},{0.634433f,0.772978f,0.0f},{0.773125f,0.634253f,0.0f}, -{0.707144f,0.70707f,0.0f},{0.773048f,0.634347f,0.0f},{0.83156f,0.555435f,0.0f}, -{0.881988f,0.471271f,0.0f},{0.831507f,0.555514f,0.0f},{0.923925f,0.382573f,0.0f}, -{0.881956f,0.471332f,0.0f},{0.923909f,0.382613f,0.0f},{0.956966f,0.290201f,0.0f}, -{0.980794f,0.195045f,0.0f},{0.956961f,0.290216f,0.0f},{0.995188f,0.0979878f,0.0f}, -{0.980794f,0.195048f,0.0f},{0.995188f,0.0979889f,0.0f},{1.0f,4.00033e-013f,0.0f}, -{0.991431f,-0.130634f,-1.5026e-016f},{0.991453f,-0.130461f,6.85852e-017f},{1.0f,1.04594e-016f,-3.83638e-017f}, -{0.991431f,0.130634f,-3.21402e-016f},{0.991453f,0.130461f,-2.89173e-016f},{1.0f,1.11699e-016f,-3.83638e-017f}, -{0.923924f,0.382576f,2.83996e-016f},{0.9238f,0.382876f,8.53933e-017f},{0.866078f,0.499909f,2.08963e-017f}, -{0.96588f,0.258991f,-8.55181e-017f},{0.965953f,0.258717f,-5.34314e-017f},{0.865923f,0.500177f,-5.73979e-017f}, -{0.793249f,0.608898f,1.92916e-016f},{0.7934f,0.608701f,4.93259e-016f},{0.707134f,0.70708f,4.70843e-017f}, -{0.707032f,0.707182f,-1.83528e-017f},{0.608682f,0.793414f,1.24226e-016f},{0.608828f,0.793302f,-1.11741e-017f}, -{0.500171f,0.865926f,1.14799e-016f},{0.499936f,0.866063f,-2.19067e-016f},{0.382431f,0.923984f,1.50382e-016f}, -{0.38264f,0.923898f,2.91616e-016f},{0.257551f,0.966265f,2.03303e-016f},{0.258907f,0.965902f,-1.91601e-016f}, -{-1.77636e-016f,1.0f,0.0f},{0.130601f,0.991435f,-1.66716e-016f},{0.129881f,0.99153f,1.2663e-016f}, -{0.965953f,-0.258717f,-3.26128e-016f},{0.96588f,-0.258991f,1.67594e-016f},{0.923924f,-0.382575f,3.19072e-016f}, -{0.866078f,-0.499909f,5.5648e-017f},{0.9238f,-0.382876f,5.08067e-016f},{0.865923f,-0.500177f,-5.77672e-016f}, -{0.7934f,-0.608701f,3.62925e-016f},{0.793249f,-0.608898f,3.6309e-016f},{0.707134f,-0.70708f,2.68425e-016f}, -{0.608828f,-0.793302f,-3.58676e-017f},{0.707032f,-0.707182f,-8.0417e-017f},{0.608682f,-0.793414f,-3.58121e-017f}, -{0.500171f,-0.865926f,-3.26581e-017f},{0.499936f,-0.866063f,8.52937e-016f},{0.382431f,-0.923984f,1.98887e-017f}, -{0.258907f,-0.965902f,-4.21509e-018f},{0.38264f,-0.923897f,-3.73789e-018f},{0.257551f,-0.966265f,-4.04087e-018f}, -{0.130601f,-0.991435f,1.01608e-018f},{0.129881f,-0.99153f,1.04991e-018f},{-3.9968e-016f,-1.0f,0.0f}, -{-3.55271e-016f,-1.0f,0.0f},{0.130634f,0.991431f,2.24771e-017f},{-6.81879e-017f,1.0f,-3.5727e-016f}, -{0.130461f,0.991453f,4.82088e-017f},{-0.130634f,0.991431f,-8.9037e-017f},{-2.8908e-017f,1.0f,-3.5727e-016f}, -{-0.130461f,0.991453f,-1.21252e-016f},{-0.382576f,0.923924f,-2.393e-016f},{-0.499909f,0.866078f,-4.33042e-017f}, -{-0.382876f,0.9238f,-9.77137e-017f},{-0.258991f,0.96588f,2.71446e-017f},{-0.258717f,0.965953f,-4.91388e-018f}, -{-0.500177f,0.865923f,3.49703e-017f},{-0.608701f,0.7934f,-4.24266e-016f},{-0.608898f,0.793249f,-1.2395e-016f}, -{-0.70708f,0.707134f,-3.52173e-017f},{-0.707182f,0.707032f,7.38213e-017f},{-0.793302f,0.608828f,3.61888e-017f}, -{-0.793414f,0.608682f,-9.92222e-017f},{-0.865926f,0.500171f,-1.27451e-016f},{-0.923984f,0.382431f,-1.43542e-016f}, -{-0.866063f,0.499936f,2.37252e-016f},{-0.923898f,0.38264f,-2.84771e-016f},{-0.965902f,0.258907f,1.93798e-016f}, -{-0.966265f,0.257551f,-2.0112e-016f},{-1.0f,-1.77636e-016f,0.0f},{-0.99153f,0.129881f,-1.26366e-016f}, -{-0.991435f,0.130601f,1.66981e-016f},{0.258717f,0.965953f,5.79845e-016f},{0.382575f,0.923924f,5.8645e-017f}, -{0.258991f,0.96588f,8.61504e-017f},{0.499909f,0.866078f,-1.08244e-016f},{0.382876f,0.9238f,-1.30347e-016f}, -{0.500177f,0.865923f,7.38772e-016f},{0.608701f,0.7934f,-1.95732e-016f},{0.70708f,0.707134f,-3.63162e-016f}, -{0.608898f,0.793249f,-1.95892e-016f},{0.793302f,0.608828f,-3.00139e-017f},{0.707182f,0.707032f,7.29313e-017f}, -{0.793414f,0.608682f,-3.00317e-017f},{0.865926f,0.500171f,-8.48302e-018f},{0.923984f,0.382431f,5.81523e-018f}, -{0.866063f,0.499936f,-8.32361e-016f},{0.965902f,0.258907f,-3.62871e-018f},{0.923897f,0.38264f,5.83784e-018f}, -{0.966265f,0.257551f,-3.69043e-018f},{0.991435f,0.130601f,-1.6072e-018f},{1.0f,-3.9968e-016f,0.0f}, -{0.99153f,0.129881f,-1.61926e-018f},{1.0f,-3.55271e-016f,0.0f},{-0.991453f,0.130461f,-1.07072e-016f}, -{-1.0f,-1.34854e-016f,-1.10604e-016f},{-0.997004f,0.0773514f,-4.85361e-018f},{-0.984529f,-0.17522f,8.76624e-017f}, -{-0.998781f,-0.0493566f,-2.22428e-016f},{-0.991431f,-0.130634f,-2.6656e-016f},{-0.9238f,-0.382876f,3.55937e-016f}, -{-0.865923f,-0.500177f,4.04041e-018f},{-0.909095f,-0.416588f,2.40191e-017f},{-0.954476f,-0.298289f,8.81846e-017f}, -{-0.96588f,-0.258991f,2.25831e-017f},{-0.793249f,-0.608898f,2.61332e-018f},{-0.775518f,-0.631325f,1.12436e-017f}, -{-0.849113f,-0.528211f,-2.89297e-017f},{-0.707032f,-0.707182f,2.19638e-016f},{-0.608682f,-0.793414f,3.18903e-016f}, -{-0.592379f,-0.805659f,7.30288e-018f},{-0.689484f,-0.724301f,-1.76238e-016f},{-0.499936f,-0.866063f,6.507e-017f}, -{-0.38264f,-0.923898f,2.20941e-016f},{-0.485846f,-0.874044f,2.27593e-017f},{-0.257551f,-0.966265f,1.69139e-016f}, -{-0.250953f,-0.967999f,3.56251e-016f},{-0.370923f,-0.928664f,-1.56513e-017f},{-0.126499f,-0.991967f,2.38761e-016f}, -{-0.129881f,-0.99153f,1.18458e-016f},{1.77636e-016f,-1.0f,0.0f},{-0.979208f,0.202861f,-5.41817e-017f}, -{-0.945695f,0.325055f,-2.584e-016f},{-0.965953f,0.258717f,-1.0161e-016f},{-0.923924f,0.382575f,-9.44417e-017f}, -{-0.897003f,0.442024f,5.64015e-016f},{-0.833912f,0.551898f,-3.53721e-016f},{-0.866078f,0.499909f,2.10067e-017f}, -{-0.757439f,0.652906f,3.44065e-016f},{-0.7934f,0.608701f,3.22157e-016f},{-0.707134f,0.70708f,2.17729e-017f}, -{-0.668817f,0.743427f,2.1497e-017f},{-0.569477f,0.822007f,4.2577e-016f},{-0.608828f,0.793302f,2.07916e-017f}, -{-0.461029f,0.887385f,4.62743e-017f},{-0.500171f,0.865926f,-8.66628e-016f},{-0.382431f,0.923984f,-7.93122e-018f}, -{-0.345178f,0.938537f,9.19408e-016f},{-0.221677f,0.97512f,9.65517e-016f},{-0.258907f,0.965902f,-4.49664e-018f}, -{-0.0988218f,0.995105f,2.20458e-019f},{-0.130601f,0.991435f,-1.82934e-018f},{-3.77476e-016f,1.0f,0.0f}, -{0.994576f,0.104013f,-2.37446e-016f},{0.994455f,-0.105163f,2.4662e-016f},{0.950548f,-0.310578f,3.73545e-016f}, -{0.980872f,-0.194653f,3.75714e-016f},{0.924088f,-0.382179f,3.99499e-016f},{0.742274f,-0.670096f,9.66286e-016f}, -{0.831655f,-0.555293f,7.03883e-016f},{0.86521f,-0.50141f,8.23015e-016f},{0.586974f,-0.809606f,8.82738e-016f}, -{0.707139f,-0.707075f,7.98094e-016f},{0.555458f,-0.831545f,1.00906e-015f},{0.406026f,-0.913862f,9.73266e-016f}, -{0.207408f,-0.978254f,1.11318e-015f},{0.382504f,-0.923954f,1.10236e-015f},{-9.4369e-016f,-1.0f,1.18424e-015f}, -{-4.44089e-016f,-1.0f,1.18424e-015f},{0.19489f,-0.980825f,1.0979e-015f},{0.98057f,0.196168f,-3.04887e-016f}, -{0.951298f,0.308272f,-4.35477e-016f},{0.923329f,0.384009f,-5.11603e-016f},{0.830773f,0.556611f,-7.00357e-016f}, -{0.866353f,0.499433f,-5.27324e-016f},{0.706447f,0.707766f,-8.90548e-016f},{0.743379f,0.66887f,-7.97616e-016f}, -{0.587881f,0.808947f,-9.57986e-016f},{0.554999f,0.831851f,-9.44127e-016f},{0.382212f,0.924075f,-1.23111e-015f}, -{0.406743f,0.913543f,-1.27729e-015f},{0.194766f,0.98085f,-1.13273e-015f},{0.20783f,0.978165f,-1.01358e-015f}, -{6.57384e-032f,1.0f,-1.18424e-015f},{0.0f,1.0f,-1.18424e-015f},{0.197004f,0.475871f,-0.857167f}, -{0.286082f,0.428277f,-0.857167f},{-2.0793e-011f,-0.515038f,-0.857167f},{0.100376f,0.505162f,-0.857167f}, -{8.71248e-012f,0.515038f,-0.857167f},{0.364203f,0.36417f,-0.857167f},{0.428334f,0.285997f,-0.857167f}, -{0.475941f,0.196837f,-0.857167f},{0.505186f,0.100254f,-0.857167f},{0.515038f,-1.86582e-015f,-0.857167f}, -{0.47555f,-0.19778f,-0.857167f},{0.505031f,-0.101034f,-0.857167f},{0.363847f,-0.364526f,-0.857167f}, -{0.42788f,-0.286676f,-0.857167f},{0.196854f,-0.475934f,-0.857167f},{0.285846f,-0.428435f,-0.857167f}, -{1.26614e-015f,-0.515038f,-0.857167f},{0.100312f,-0.505175f,-0.857167f},{0.994576f,0.104013f,-5.34124e-017f}, -{0.994455f,-0.105163f,4.1204e-017f},{0.950548f,-0.310578f,3.38367e-016f},{0.980872f,-0.194653f,1.90615e-016f}, -{0.924088f,-0.382179f,2.52153e-016f},{0.742274f,-0.670096f,8.23884e-016f},{0.831655f,-0.555293f,6.83239e-016f}, -{0.86521f,-0.50141f,6.78022e-016f},{0.586974f,-0.809606f,9.23936e-016f},{0.707139f,-0.707075f,8.43888e-016f}, -{0.555458f,-0.831545f,1.05336e-015f},{0.406026f,-0.913862f,1.11933e-015f},{0.207408f,-0.978254f,1.18377e-015f}, -{0.382504f,-0.923954f,1.10248e-015f},{-5.55112e-017f,-1.0f,1.18424e-015f},{0.0f,-1.0f,1.18424e-015f}, -{0.19489f,-0.980825f,1.11609e-015f},{0.98057f,0.196168f,-1.96021e-016f},{0.951298f,0.308272f,-3.17474e-016f}, -{0.923329f,0.384009f,-5.08887e-016f},{0.830773f,0.556611f,-6.79452e-016f},{0.866353f,0.499433f,-4.53393e-016f}, -{0.706447f,0.707766f,-7.3349e-016f},{0.743379f,0.66887f,-6.87574e-016f},{0.587881f,0.808947f,-9.74348e-016f}, -{0.554999f,0.831851f,-9.8511e-016f},{0.382212f,0.924075f,-1.09432e-015f},{0.406743f,0.913543f,-9.4662e-016f}, -{0.194766f,0.98085f,-9.87533e-016f},{4.16334e-016f,1.0f,-1.18424e-015f},{0.0f,-0.515038f,-0.857167f}, -{8.71235e-012f,0.515038f,-0.857167f},{0.515038f,-2.11803e-015f,-0.857167f},{7.89703e-016f,-0.515038f,-0.857167f}, -{1.0f,6.57384e-032f,7.40149e-017f},{0.994576f,0.104013f,-1.89091e-016f},{0.994455f,-0.105163f,2.07702e-016f}, -{0.950548f,-0.310578f,3.67798e-016f},{0.980872f,-0.194653f,1.0721e-016f},{0.924088f,-0.382179f,4.00133e-016f}, -{0.742274f,-0.670096f,8.8302e-016f},{0.831655f,-0.555293f,6.21707e-016f},{0.586974f,-0.809606f,8.44444e-016f}, -{0.707139f,-0.707075f,7.32676e-016f},{0.555458f,-0.831545f,8.05154e-016f},{0.406026f,-0.913862f,1.0147e-015f}, -{0.207408f,-0.978254f,9.49547e-016f},{0.382504f,-0.923954f,1.06648e-015f},{9.15934e-016f,-1.0f,1.03621e-015f}, -{0.0f,-1.0f,1.03621e-015f},{0.19489f,-0.980825f,1.15631e-015f},{0.98057f,0.196168f,-2.3231e-016f}, -{0.923329f,0.384009f,-2.61233e-016f},{0.866353f,0.499433f,-7.19693e-016f},{0.706447f,0.707766f,-7.33587e-016f}, -{0.743379f,0.66887f,-5.83047e-016f},{0.587881f,0.808947f,-1.07773e-015f},{0.554999f,0.831851f,-1.10825e-015f}, -{0.20783f,0.978165f,-1.18915e-015f},{-3.88578e-016f,1.0f,-1.18424e-015f},{4.44089e-016f,1.0f,-1.18424e-015f}, -{8.71311e-012f,0.515038f,-0.857167f},{0.515038f,-7.70404e-016f,-0.857167f},{5.42398e-016f,-0.515038f,-0.857167f}, -{1.0f,-2.22045e-016f,-7.40149e-017f},{0.994576f,0.104013f,-4.57139e-017f},{0.994455f,-0.105163f,1.02395e-017f}, -{0.950548f,-0.310578f,2.38582e-016f},{0.980872f,-0.194653f,1.6512e-016f},{0.924088f,-0.382179f,4.96816e-016f}, -{0.742274f,-0.670096f,7.74955e-016f},{0.831655f,-0.555293f,7.08878e-016f},{0.86521f,-0.50141f,4.90092e-016f}, -{0.586974f,-0.809606f,1.02824e-015f},{0.707139f,-0.707075f,9.74729e-016f},{0.555458f,-0.831545f,9.46272e-016f}, -{0.406026f,-0.913862f,1.24486e-015f},{0.207408f,-0.978254f,1.21316e-015f},{0.382504f,-0.923954f,1.12889e-015f}, -{4.44089e-016f,-1.0f,1.18424e-015f},{0.19489f,-0.980825f,1.27861e-015f},{0.98057f,0.196168f,-1.59733e-016f}, -{0.951298f,0.308272f,-2.94657e-016f},{0.923329f,0.384009f,-5.23098e-016f},{0.830773f,0.556611f,-7.61847e-016f}, -{0.706447f,0.707766f,-8.38163e-016f},{0.743379f,0.66887f,-7.3708e-016f},{0.587881f,0.808947f,-8.38238e-016f}, -{0.554999f,0.831851f,-9.44031e-016f},{0.194766f,0.98085f,-1.19039e-015f},{0.20783f,0.978165f,-1.12761e-015f}, -{-4.996e-016f,1.0f,-1.18424e-015f},{-4.44089e-016f,1.0f,-1.18424e-015f},{2.0793e-011f,-0.515038f,-0.857167f}, -{8.7127e-012f,0.515038f,-0.857167f},{0.515038f,-8.60974e-016f,-0.857167f},{5.6139e-016f,-0.515038f,-0.857167f}, -{0.130634f,0.991431f,9.00714e-017f},{0.130461f,0.991453f,6.43735e-017f},{-4.44089e-017f,1.0f,1.11862e-030f}, -{-0.130634f,0.991431f,1.22301e-016f},{-0.130461f,0.991453f,3.21868e-017f},{-4.71845e-017f,1.0f,1.11999e-030f}, -{-0.382576f,0.923924f,1.78148e-017f},{-0.382876f,0.9238f,4.72309e-017f},{-0.499909f,0.866078f,-1.52008e-016f}, -{-0.258991f,0.96588f,-2.14995e-016f},{-0.258717f,0.965953f,-6.38297e-017f},{-0.500177f,0.865923f,-2.3022e-016f}, -{-0.608898f,0.793249f,1.50225e-016f},{-0.608701f,0.7934f,4.50529e-016f},{-0.70708f,0.707134f,6.5418e-017f}, -{-0.707182f,0.707032f,-4.36183e-017f},{-0.793414f,0.608682f,7.34055e-017f},{-0.793302f,0.608828f,-6.2017e-017f}, -{-0.865926f,0.500171f,1.08892e-016f},{-0.866063f,0.499936f,-2.24963e-016f},{-0.923984f,0.382431f,1.36579e-016f}, -{-0.923898f,0.38264f,2.77802e-016f},{-0.966265f,0.257551f,1.98912e-016f},{-0.965902f,0.258907f,-1.96021e-016f}, -{-0.991435f,0.130601f,-1.67248e-016f},{-0.99153f,0.129881f,1.26101e-016f},{0.258717f,0.965953f,-2.55319e-016f}, -{0.258991f,0.96588f,-1.19149e-016f},{0.382575f,0.923924f,1.67951e-030f},{0.499909f,0.866078f,2.46671e-016f}, -{0.382876f,0.9238f,1.88923e-016f},{0.500177f,0.865923f,-3.86789e-016f},{0.608701f,0.7934f,3.00353e-016f}, -{0.608898f,0.793249f,3.0045e-016f},{0.70708f,0.707134f,2.61666e-016f},{0.793302f,0.608828f,-7.51038e-017f}, -{0.707182f,0.707032f,1.87217e-030f},{0.793414f,0.608682f,1.78765e-030f},{0.865926f,0.500171f,1.61435e-030f}, -{0.866063f,0.499936f,8.23851e-016f},{0.923984f,0.382431f,1.3463e-030f},{0.965902f,0.258907f,9.865e-031f}, -{0.923897f,0.38264f,1.34684e-030f},{0.966265f,0.257551f,9.82132e-031f},{0.991435f,0.130601f,5.35361e-031f}, -{0.99153f,0.129881f,5.32617e-031f},{0.994856f,0.101296f,0.0f},{0.998601f,0.0528865f,0.0f}, -{0.994333f,0.106314f,0.0f},{0.977365f,0.211559f,0.0f},{0.977403f,0.211384f,0.0f}, -{0.964768f,0.263101f,0.0f},{0.998775f,0.049491f,0.0f},{1.0f,1.19209e-007f,0.0f}, -{1.0f,1.93784e-016f,0.0f},{0.987859f,0.155356f,0.0f},{0.987268f,0.159066f,0.0f}, -{0.943659f,0.330919f,0.0f},{0.962422f,0.27156f,0.0f},{0.949398f,0.314075f,0.0f}, -{0.866023f,0.500004f,0.0f},{0.89538f,0.445304f,0.0f},{0.887356f,0.461084f,0.0f}, -{0.921283f,0.388894f,0.0f},{0.931337f,0.364157f,0.0f},{0.910637f,0.413206f,0.0f}, -{0.802718f,0.596359f,0.0f},{0.769841f,0.638236f,0.0f},{0.797431f,0.60341f,0.0f}, -{0.861559f,0.507658f,0.0f},{0.833319f,0.552792f,0.0f},{0.833335f,0.552769f,0.0f}, -{0.697641f,0.716448f,0.0f},{0.671898f,0.740644f,0.0f},{0.716559f,0.697526f,0.0f}, -{0.734782f,0.678303f,0.0f},{0.758457f,0.651723f,0.0f},{0.541517f,0.84069f,0.0f}, -{0.609678f,0.792649f,0.0f},{0.574801f,0.818293f,0.0f},{0.658522f,0.752561f,0.0f}, -{0.437309f,0.899311f,0.0f},{0.388825f,0.921312f,0.0f},{0.388834f,0.921308f,0.0f}, -{0.484556f,0.87476f,0.0f},{0.467738f,0.883867f,0.0f},{0.237326f,0.97143f,0.0f}, -{0.239133f,0.970987f,0.0f},{0.288698f,0.95742f,0.0f},{0.305468f,0.952202f,0.0f}, -{0.339241f,0.940699f,0.0f},{0.103293f,0.994651f,0.0f},{0.132709f,0.991155f,0.0f}, -{0.079772f,0.996813f,0.0f},{0.185276f,0.982686f,0.0f},{0.171605f,0.985166f,0.0f}, -{0.0344868f,0.999405f,0.0f},{-0.0266303f,0.999645f,0.0f},{-0.03448f,0.999405f,0.0f}, -{0.0266126f,0.999646f,0.0f},{-0.132754f,0.991149f,0.0f},{-0.185314f,0.982679f,0.0f}, -{-0.171593f,0.985168f,0.0f},{-0.10328f,0.994652f,0.0f},{-0.0798119f,0.99681f,0.0f}, -{-0.339268f,0.94069f,0.0f},{-0.305468f,0.952202f,0.0f},{-0.288713f,0.957416f,0.0f}, -{-0.239168f,0.970978f,0.0f},{-0.237346f,0.971425f,0.0f},{-0.467738f,0.883867f,0.0f}, -{-0.388834f,0.921308f,0.0f},{-0.437338f,0.899297f,0.0f},{-0.388857f,0.921298f,0.0f}, -{-0.541517f,0.84069f,0.0f},{-0.530443f,0.847721f,0.0f},{-0.574807f,0.818289f,0.0f}, -{-0.484577f,0.874749f,0.0f},{-0.658536f,0.752549f,0.0f},{-0.697657f,0.716432f,0.0f}, -{-0.671898f,0.740644f,0.0f},{-0.609678f,0.792649f,0.0f},{-0.617547f,0.786534f,0.0f}, -{-0.734799f,0.678285f,0.0f},{-0.769857f,0.638216f,0.0f},{-0.758453f,0.651728f,0.0f}, -{-0.716553f,0.697532f,0.0f},{-0.797427f,0.603416f,0.0f},{-0.802733f,0.596339f,0.0f}, -{-0.833333f,0.552771f,0.0f},{-0.833328f,0.552779f,0.0f},{-0.861571f,0.507638f,0.0f}, -{-0.866021f,0.500008f,0.0f},{-0.887366f,0.461066f,0.0f},{-0.895373f,0.445318f,0.0f}, -{-0.921279f,0.388903f,0.0f},{-0.910645f,0.413189f,0.0f},{-0.931345f,0.364138f,0.0f}, -{-0.943631f,0.330998f,0.0f},{-0.949405f,0.314055f,0.0f},{-0.962355f,0.271796f,0.0f}, -{-0.977365f,0.211559f,0.0f},{-0.964773f,0.263083f,0.0f},{-0.98727f,0.159053f,0.0f}, -{-0.977407f,0.211368f,0.0f},{-0.994335f,0.106287f,0.0f},{-0.987859f,0.155356f,0.0f}, -{-0.994856f,0.101296f,0.0f},{-0.9986f,0.0529056f,0.0f},{-0.998775f,0.049491f,0.0f}, -{0.53043f,0.847729f,0.0f},{0.617538f,0.786541f,0.0f},{0.624695f,-9.46817e-016f,-0.780869f}, -{0.624695f,-9.5349e-016f,-0.780869f},{0.623357f,-0.040871f,-0.780869f},{0.409092f,0.47211f,-0.780869f}, -{0.411878f,0.469681f,-0.780869f},{0.380282f,0.495611f,-0.780869f},{0.441714f,0.441739f,-0.780869f}, -{0.362367f,0.508856f,-0.780869f},{0.347057f,0.519418f,-0.780869f},{0.312348f,0.541002f,-0.780869f}, -{0.312341f,0.541005f,-0.780869f},{0.347056f,0.519419f,-0.780869f},{0.276286f,0.560277f,-0.780869f}, -{0.276287f,0.560276f,-0.780869f},{0.239058f,0.577144f,-0.780869f},{0.239054f,0.577146f,-0.780869f}, -{0.200802f,0.591543f,-0.780869f},{0.200803f,0.591542f,-0.780869f},{0.161685f,0.603409f,-0.780869f}, -{0.161681f,0.60341f,-0.780869f},{0.121783f,0.612709f,-0.780869f},{0.121874f,0.612691f,-0.780869f}, -{0.0815751f,0.619346f,-0.780869f},{0.0813198f,0.61938f,-0.780869f},{0.0406682f,0.62337f,-0.780869f}, -{0.0408792f,0.623356f,-0.780869f},{6.31627e-017f,0.624695f,-0.780869f},{9.6494e-017f,0.624695f,-0.780869f}, -{0.452119f,0.431082f,-0.780869f},{0.469659f,0.411903f,-0.780869f},{0.491049f,0.386154f,-0.780869f}, -{0.495594f,0.380303f,-0.780869f},{0.519406f,0.347075f,-0.780869f},{0.525532f,0.337728f,-0.780869f}, -{0.540994f,0.31236f,-0.780869f},{0.555257f,0.286241f,-0.780869f},{0.560267f,0.276306f,-0.780869f}, -{0.579951f,0.232166f,-0.780869f},{0.577139f,0.239071f,-0.780869f},{0.603409f,0.161685f,-0.780869f}, -{0.612693f,0.121866f,-0.780869f},{0.613402f,0.118247f,-0.780869f},{0.599395f,0.175983f,-0.780869f}, -{0.591539f,0.200813f,-0.780869f},{0.613408f,0.118216f,-0.780869f},{0.603405f,0.161699f,-0.780869f}, -{0.612688f,0.12189f,-0.780869f},{0.621867f,0.0593712f,-0.780869f},{0.619348f,0.0815574f,-0.780869f}, -{0.623358f,0.0408492f,-0.780869f},{0.624695f,-9.55166e-016f,-0.780869f},{0.623358f,0.0408553f,-0.780869f}, -{0.619036f,-0.0838959f,-0.780869f},{0.623279f,-0.0420416f,-0.780869f},{0.619348f,-0.0815572f,-0.780869f}, -{0.589599f,-0.206439f,-0.780869f},{0.602157f,-0.166284f,-0.780869f},{0.591537f,-0.200819f,-0.780869f}, -{0.611985f,-0.125373f,-0.780869f},{0.612689f,-0.121886f,-0.780869f},{0.603406f,-0.161693f,-0.780869f}, -{0.556524f,-0.283768f,-0.780869f},{0.540992f,-0.312365f,-0.780869f},{0.536161f,-0.320586f,-0.780869f}, -{0.577134f,-0.239082f,-0.780869f},{0.560263f,-0.276314f,-0.780869f},{0.574364f,-0.245661f,-0.780869f}, -{0.495593f,-0.380304f,-0.780869f},{0.469657f,-0.411906f,-0.780869f},{0.488247f,-0.389691f,-0.780869f}, -{0.513369f,-0.355945f,-0.780869f},{0.519405f,-0.347077f,-0.780869f},{0.380275f,-0.495616f,-0.780869f}, -{0.400096f,-0.479758f,-0.780869f},{0.411873f,-0.469686f,-0.780869f},{0.431479f,-0.451741f,-0.780869f}, -{0.460909f,-0.421672f,-0.780869f},{0.441709f,-0.441743f,-0.780869f},{0.295665f,-0.550296f,-0.780869f}, -{0.332035f,-0.529147f,-0.780869f},{0.312348f,-0.541002f,-0.780869f},{0.366898f,-0.505599f,-0.780869f}, -{0.31233f,-0.541012f,-0.780869f},{0.276304f,-0.560268f,-0.780869f},{0.239076f,-0.577137f,-0.780869f}, -{0.239048f,-0.577148f,-0.780869f},{0.200811f,-0.591539f,-0.780869f},{0.276284f,-0.560278f,-0.780869f}, -{0.161687f,-0.603408f,-0.780869f},{0.161672f,-0.603412f,-0.780869f},{0.121883f,-0.612689f,-0.780869f}, -{0.200788f,-0.591547f,-0.780869f},{0.0815507f,-0.619349f,-0.780869f},{0.121867f,-0.612693f,-0.780869f}, -{0.0815307f,-0.619352f,-0.780869f},{0.0407198f,-0.623367f,-0.780869f},{0.0408636f,-0.623357f,-0.780869f}, -{-6.68781e-017f,-0.624695f,-0.780869f},{0.0f,-0.624695f,-0.780869f},{0.347044f,-0.519427f,-0.780869f}, -{0.121858f,-0.612694f,-0.780869f},{0.13845f,-0.60916f,-0.780869f},{0.161673f,-0.603412f,-0.780869f}, -{0.0815244f,-0.619353f,-0.780869f},{0.0972037f,-0.617086f,-0.780869f},{0.0554519f,-0.622229f,-0.780869f}, -{0.040847f,-0.623358f,-0.780869f},{-3.53852e-018f,-0.624695f,-0.780869f},{0.0134175f,-0.624551f,-0.780869f}, -{0.179217f,-0.598436f,-0.780869f},{0.219081f,-0.585019f,-0.780869f},{0.238818f,-0.577243f,-0.780869f}, -{0.20082f,-0.591536f,-0.780869f},{0.257958f,-0.568948f,-0.780869f},{0.276277f,-0.560281f,-0.780869f}, -{0.624695f,-9.4344e-016f,-0.780869f},{0.362343f,0.508873f,-0.780869f},{0.31234f,0.541006f,-0.780869f}, -{0.409076f,0.472124f,-0.780869f},{0.380283f,0.49561f,-0.780869f},{0.441721f,0.441731f,-0.780869f}, -{0.411883f,0.469676f,-0.780869f},{0.452096f,0.431107f,-0.780869f},{0.49103f,0.386178f,-0.780869f}, -{0.469665f,0.411897f,-0.780869f},{0.519411f,0.347068f,-0.780869f},{0.495597f,0.3803f,-0.780869f}, -{0.525513f,0.337758f,-0.780869f},{0.555239f,0.286275f,-0.780869f},{0.541001f,0.312349f,-0.780869f}, -{0.560272f,0.276296f,-0.780869f},{0.579937f,0.232201f,-0.780869f},{0.577143f,0.23906f,-0.780869f}, -{0.599383f,0.176024f,-0.780869f},{0.591542f,0.200803f,-0.780869f},{0.621866f,0.0593873f,-0.780869f}, -{0.619352f,0.0815289f,-0.780869f},{1.0f,1.19209e-007f,-8.82326e-023f},{1.0f,3.38566e-017f,-2.50589e-032f}, -{0.998307f,-0.058159f,4.30463e-017f},{0.993236f,-0.116116f,8.5943e-017f},{0.998309f,-0.0581378f,4.30306e-017f}, -{0.984803f,-0.173675f,1.28545e-016f},{0.99324f,-0.11608f,8.59168e-017f},{0.984811f,-0.173633f,2.57028e-016f}, -{0.973038f,-0.230643f,1.7071e-016f},{0.957982f,-0.286828f,0.0f},{0.973049f,-0.2306f,1.70678e-016f}, -{0.939685f,-0.342042f,5.06323e-016f},{0.957993f,-0.28679f,0.0f},{0.939696f,-0.342012f,5.0628e-016f}, -{0.918208f,-0.396098f,5.86343e-016f},{0.893624f,-0.448816f,6.64382e-016f},{0.918216f,-0.396079f,5.86315e-016f}, -{0.866013f,-0.500021f,7.40179e-016f},{0.893631f,-0.448803f,0.0f},{0.866023f,-0.500004f,7.40154e-016f}, -{0.835473f,-0.549532f,8.13471e-016f},{0.802106f,-0.597181f,8.84005e-016f},{0.835486f,-0.549512f,0.0f}, -{0.766027f,-0.642808f,9.51547e-016f},{0.802121f,-0.597162f,8.83977e-016f},{0.766041f,-0.642791f,0.0f}, -{0.727358f,-0.686258f,0.0f},{0.686227f,-0.727388f,0.0f},{0.727369f,-0.686246f,0.0f}, -{0.642773f,-0.766057f,0.0f},{0.686238f,-0.727377f,0.0f},{0.642785f,-0.766046f,1.13398e-015f}, -{0.597145f,-0.802133f,0.0f},{0.549498f,-0.835495f,0.0f},{0.597158f,-0.802124f,0.0f}, -{0.499989f,-0.866032f,0.0f},{0.549511f,-0.835486f,0.0f},{0.500008f,-0.866021f,0.0f}, -{0.448787f,-0.893639f,0.0f},{0.396067f,-0.918221f,0.0f},{0.448811f,-0.893627f,0.0f}, -{0.342011f,-0.939696f,0.0f},{0.396094f,-0.91821f,0.0f},{0.342035f,-0.939687f,0.0f}, -{0.286798f,-0.957991f,0.0f},{0.230613f,-0.973045f,0.0f},{0.286837f,-0.957979f,0.0f}, -{0.230535f,-0.973064f,0.0f},{0.173651f,-0.984807f,0.0f},{0.116108f,-0.993237f,0.0f}, -{0.173275f,-0.984873f,0.0f},{0.0581642f,-0.998307f,0.0f},{0.11595f,-0.993255f,0.0f}, -{1.30331e-016f,-1.0f,0.0f},{0.0581517f,-0.998308f,0.0f},{1.54466e-016f,-1.0f,0.0f}, -{0.998307f,0.0581591f,-4.30464e-017f},{0.993236f,0.116116f,-8.5943e-017f},{0.998309f,0.0581377f,-4.30305e-017f}, -{0.99324f,0.11608f,0.0f},{0.984803f,0.173675f,0.0f},{0.973038f,0.230643f,-1.7071e-016f}, -{0.984811f,0.173632f,-1.28514e-016f},{0.957982f,0.286828f,-2.12296e-016f},{0.973049f,0.2306f,-1.70678e-016f}, -{0.957994f,0.28679f,-2.12267e-016f},{0.939685f,0.342042f,-2.53162e-016f},{0.918208f,0.396098f,-2.93171e-016f}, -{0.939696f,0.342012f,-2.5314e-016f},{0.893624f,0.448817f,-3.32191e-016f},{0.918216f,0.396079f,-2.93157e-016f}, -{0.893631f,0.448803f,-1.66091e-016f},{0.866013f,0.500021f,-1.85045e-016f},{0.835473f,0.549532f,-2.03368e-016f}, -{0.866023f,0.500004f,-3.70077e-016f},{0.802106f,0.597181f,-2.21001e-016f},{0.835486f,0.549512f,-2.0336e-016f}, -{0.802121f,0.597162f,-2.20994e-016f},{0.766027f,0.642808f,-2.37887e-016f},{0.727358f,0.686259f,0.0f}, -{0.766042f,0.642791f,-2.3788e-016f},{0.686227f,0.727388f,-2.69188e-016f},{0.72737f,0.686246f,-2.53962e-016f}, -{0.686238f,0.727377f,-2.69184e-016f},{0.642773f,0.766057f,-1.41749e-016f},{0.597145f,0.802133f,-1.48424e-016f}, -{0.642785f,0.766046f,-1.41747e-016f},{0.549498f,0.835495f,-1.54598e-016f},{0.597158f,0.802124f,-2.96845e-016f}, -{0.549511f,0.835486f,-1.54596e-016f},{0.499989f,0.866032f,0.0f},{0.448787f,0.893639f,-1.65356e-016f}, -{0.500008f,0.866021f,-1.60246e-016f},{0.396067f,0.918222f,-8.49526e-017f},{0.448811f,0.893627f,-8.26771e-017f}, -{0.396094f,0.91821f,-8.49515e-017f},{0.342011f,0.939696f,-8.69394e-017f},{0.286798f,0.957991f,-4.4316e-017f}, -{0.342035f,0.939687f,-8.69385e-017f},{0.230613f,0.973045f,-4.50124e-017f},{0.286837f,0.957979f,-4.43155e-017f}, -{0.173651f,0.984807f,-2.27782e-017f},{0.230535f,0.973064f,-4.50133e-017f},{0.173275f,0.984873f,-2.27798e-017f}, -{0.116108f,0.993237f,-1.14866e-017f},{0.11595f,0.993255f,-1.14868e-017f},{0.0581641f,0.998307f,-2.88631e-018f}, -{0.0581517f,0.998308f,-2.88631e-018f},{3.49254e-012f,1.0f,-9.79579e-039f},{8.206e-017f,1.0f,0.0f}, -{1.0f,7.76449e-017f,-9.195e-032f},{1.0f,6.17846e-017f,-7.31676e-032f},{0.998629f,-0.052353f,6.19984e-017f}, -{0.994519f,-0.104553f,1.34134e-016f},{0.99863f,-0.052328f,6.19688e-017f},{0.987684f,-0.156459f,2.00725e-016f}, -{0.994523f,-0.104515f,1.23771e-016f},{0.987691f,-0.156421f,2.00676e-016f},{0.978143f,-0.207932f,2.66762e-016f}, -{0.965922f,-0.258835f,3.06522e-016f},{0.978149f,-0.207904f,2.46208e-016f},{0.951049f,-0.30904f,3.65977e-016f}, -{0.965925f,-0.258822f,3.06506e-016f},{0.951055f,-0.309021f,3.65954e-016f},{0.933568f,-0.3584f,4.2443e-016f}, -{0.913531f,-0.40677f,4.81712e-016f},{0.933581f,-0.358367f,3.89026e-016f},{0.890991f,-0.454022f,5.3767e-016f}, -{0.913546f,-0.406734f,5.2181e-016f},{0.891007f,-0.453989f,5.37631e-016f},{0.866009f,-0.500028f,5.92152e-016f}, -{0.838655f,-0.544663f,6.45011e-016f},{0.866024f,-0.500002f,6.41465e-016f},{0.809001f,-0.587808f,6.38096e-016f}, -{0.838665f,-0.544647f,5.91242e-016f},{0.809009f,-0.587797f,6.96091e-016f},{0.777125f,-0.629346f,7.45295e-016f}, -{0.74312f,-0.669158f,7.92442e-016f},{0.777137f,-0.629331f,8.07384e-016f},{0.70708f,-0.707134f,8.37415e-016f}, -{0.743137f,-0.66914f,6.60351e-016f},{0.707099f,-0.707115f,8.37392e-016f},{0.669102f,-0.74317f,8.80091e-016f}, -{0.629291f,-0.777169f,9.20353e-016f},{0.669122f,-0.743152f,1.02675e-015f},{0.587756f,-0.809038f,1.11778e-015f}, -{0.629312f,-0.777153f,9.20334e-016f},{0.587776f,-0.809023f,1.11776e-015f},{0.54461f,-0.838689f,9.93208e-016f}, -{0.499972f,-0.866041f,1.0256e-015f},{0.54463f,-0.838677f,9.93193e-016f},{0.453965f,-0.891019f,1.05518e-015f}, -{0.49999f,-0.866031f,1.02559e-015f},{0.45398f,-0.891012f,1.05517e-015f},{0.406714f,-0.913555f,9.01556e-016f}, -{0.358347f,-0.933588f,1.10559e-015f},{0.406729f,-0.913549f,9.01549e-016f},{0.308997f,-0.951063f,1.12628e-015f}, -{0.358363f,-0.933582f,1.10558e-015f},{0.309013f,-0.951058f,1.12628e-015f},{0.258801f,-0.965931f,1.33454e-015f}, -{0.207899f,-0.97815f,1.35142e-015f},{0.258815f,-0.965927f,1.14389e-015f},{0.156426f,-0.98769f,9.74716e-016f}, -{0.207911f,-0.978148f,1.15836e-015f},{0.156436f,-0.987688f,1.16966e-015f},{0.104524f,-0.994522f,1.17775e-015f}, -{0.0520121f,-0.998646f,9.85529e-016f},{0.104542f,-0.99452f,1.17775e-015f},{1.58603e-016f,-1.0f,1.18424e-015f}, -{0.0519994f,-0.998647f,1.18264e-015f},{1.19209e-007f,-1.0f,1.18424e-015f},{0.998629f,0.0523531f,-6.19985e-017f}, -{0.994519f,0.104553f,-1.13498e-016f},{0.99863f,0.0523281f,-6.19689e-017f},{0.994523f,0.104515f,-1.23771e-016f}, -{0.987684f,0.156459f,-1.85285e-016f},{0.978143f,0.207932f,-2.46241e-016f},{0.987691f,0.156421f,-1.92958e-016f}, -{0.965922f,0.258835f,-3.19294e-016f},{0.978149f,0.207904f,-2.46208e-016f},{0.965925f,0.258822f,-3.19278e-016f}, -{0.951049f,0.30904f,-3.81226e-016f},{0.933568f,0.3584f,-3.71377e-016f},{0.951055f,0.309021f,-3.65954e-016f}, -{0.913531f,0.40677f,-4.81712e-016f},{0.933581f,0.358367f,-4.24392e-016f},{0.913546f,0.406734f,-5.0174e-016f}, -{0.890991f,0.454022f,-5.71274e-016f},{0.866009f,0.500028f,-6.16825e-016f},{0.891007f,0.453989f,-5.71233e-016f}, -{0.838655f,0.544663f,-6.58448e-016f},{0.866024f,0.500002f,-5.92122e-016f},{0.838665f,0.544647f,-6.31554e-016f}, -{0.809001f,0.587808f,-6.52598e-016f},{0.777125f,0.629346f,-7.60822e-016f},{0.809009f,0.587797f,-6.8884e-016f}, -{0.74312f,0.669158f,-8.50225e-016f},{0.777137f,0.629331f,-7.60804e-016f},{0.743137f,0.66914f,-8.6671e-016f}, -{0.70708f,0.707134f,-7.50184e-016f},{0.669102f,0.74317f,-9.12177e-016f},{0.707099f,0.707115f,-8.72284e-016f}, -{0.629291f,0.77717f,-9.44321e-016f},{0.669122f,0.743152f,-8.75485e-016f},{0.629312f,0.777153f,-7.71738e-016f}, -{0.587756f,0.809038f,-9.38133e-016f},{0.54461f,0.838689f,-9.46651e-016f},{0.587776f,0.809024f,-9.58076e-016f}, -{0.499972f,0.866041f,-9.66841e-016f},{0.54463f,0.838677f,-9.46637e-016f},{0.49999f,0.866031f,-9.64159e-016f}, -{0.453965f,0.891019f,-1.1541e-015f},{0.406714f,0.913555f,-1.12976e-015f},{0.45398f,0.891012f,-1.12112e-015f}, -{0.358347f,0.933588f,-1.1459e-015f},{0.406729f,0.913549f,-1.1692e-015f},{0.358363f,0.933582f,-1.09407e-015f}, -{0.308997f,0.951063f,-1.12995e-015f},{0.258801f,0.965931f,-1.09251e-015f},{0.309013f,0.951058f,-1.10648e-015f}, -{0.207899f,0.97815f,-1.09633e-015f},{0.258815f,0.965927f,-1.11335e-015f},{0.207911f,0.978148f,-1.29222e-015f}, -{0.156426f,0.98769f,-1.07876e-015f},{0.104524f,0.994522f,-1.04604e-015f},{0.156436f,0.987688f,-1.27522e-015f}, -{0.0520121f,0.998646f,-1.21422e-015f},{0.104542f,0.99452f,-1.24232e-015f},{0.0519993f,0.998647f,-1.21422e-015f}, -{5.52976e-012f,1.0f,-1.18424e-015f},{-4.7581e-017f,1.0f,-1.18424e-015f},{0.0f,1.38778e-017f,1.0f}, -{0.0f,-1.38778e-017f,1.0f},{0.0f,-2.77556e-017f,1.0f},{0.0f,2.77556e-017f,1.0f}, -{0.0f,1.04083e-017f,1.0f},{0.0f,5.20417e-018f,1.0f},{0.0f,-2.12504e-017f,1.0f}, -{0.0f,6.93889e-018f,1.0f},{0.0f,-1.73472e-017f,1.0f},{0.0f,-1.04083e-017f,1.0f}, -{0.0f,-2.08167e-017f,1.0f},{0.0f,2.42861e-017f,1.0f},{0.0f,1.73472e-017f,1.0f}, -{0.0f,-2.25514e-017f,1.0f},{0.0f,-6.93889e-018f,1.0f},{0.0f,2.08167e-017f,1.0f}, -{0.0f,-5.20417e-018f,1.0f},{0.0f,3.46945e-018f,1.0f},{0.0f,-3.46945e-018f,1.0f}, -{0.0f,-2.42861e-017f,1.0f},{0.0f,5.55112e-017f,1.0f},{0.0f,-5.55112e-017f,1.0f}, -{0.15501f,-0.0448068f,0.986896f},{0.151564f,-0.0553554f,0.986896f},{0.307074f,-0.112152f,0.945054f}, -{0.668812f,-0.559936f,0.489042f},{0.705929f,-0.51235f,0.489042f},{0.622414f,-0.451736f,0.639168f}, -{0.652262f,-0.407453f,0.639168f},{0.739783f,-0.462125f,0.489042f},{0.490087f,-0.410306f,0.769067f}, -{0.374976f,-0.313934f,0.87226f},{0.460725f,-0.443021f,0.769067f},{0.235646f,-0.226591f,0.945054f}, -{0.305444f,-0.336696f,0.890696f},{0.352511f,-0.338965f,0.87226f},{0.104942f,-0.115679f,0.987727f}, -{0.207967f,-0.229246f,0.950892f},{0.116309f,-0.11184f,0.986896f},{0.678996f,-0.361149f,0.639168f}, -{0.770104f,-0.409608f,0.489042f},{0.702422f,-0.313158f,0.639168f},{6.07606e-008f,-5.84258e-008f,1.0f}, -{5.66367e-008f,-6.24316e-008f,1.0f},{0.801521f,-0.500692f,0.326914f},{0.837008f,-0.52286f,0.161356f}, -{0.834372f,-0.443791f,0.326914f},{0.833339f,-0.552763f,1.22111e-009f},{0.866025f,-0.5f,2.96063e-015f}, -{0.798705f,-0.579685f,0.161356f},{0.797438f,-0.603401f,1.88811e-015f},{0.75671f,-0.633525f,0.161356f}, -{0.871314f,-0.46344f,0.161356f},{0.895381f,-0.445302f,8.1345e-010f},{0.716504f,-0.697583f,3.07674e-011f}, -{0.758466f,-0.651713f,3.54258e-015f},{0.711375f,-0.684039f,0.161356f},{0.671898f,-0.740644f,0.0f}, -{0.66364f,-0.731542f,0.156297f},{0.901374f,-0.401856f,0.161356f},{0.921284f,-0.38889f,4.19485e-015f}, -{0.927004f,-0.338567f,0.161356f},{0.943637f,-0.330981f,3.15625e-010f},{0.962368f,-0.27175f,4.29443e-015f}, -{0.948083f,-0.27405f,0.161356f},{0.965371f,-0.208962f,0.156188f},{0.929369f,-0.201169f,0.309522f}, -{0.796673f,-0.355178f,0.489042f},{0.628743f,-0.604582f,0.489042f},{0.589688f,-0.493693f,0.639168f}, -{0.977365f,-0.211559f,2.52172e-015f},{0.863158f,-0.384819f,0.326914f},{0.61403f,-0.177489f,0.769067f}, -{0.574515f,-0.124358f,0.808992f},{0.469808f,-0.135801f,0.87226f},{0.691102f,-0.149594f,0.707107f}, -{0.738821f,-0.213561f,0.639168f},{9.17498e-016f,3.64703e-016f,1.0f},{2.19934e-015f,-9.00417e-016f,1.0f}, -{0.431766f,-0.229651f,0.87226f},{0.446663f,-0.199134f,0.87226f},{0.298584f,-0.133117f,0.945054f}, -{0.152759f,-0.0330659f,0.98771f},{0.907886f,-0.262431f,0.326914f},{0.870535f,-0.188434f,0.454599f}, -{0.837955f,-0.242217f,0.489042f},{0.887701f,-0.324213f,0.326914f},{0.764842f,-0.555108f,0.326914f}, -{0.724627f,-0.606665f,0.326914f},{0.681215f,-0.655037f,0.326914f},{0.639091f,-0.70448f,0.308658f}, -{0.79069f,-0.171151f,0.587806f},{0.819325f,-0.29924f,0.489042f},{0.59887f,-0.660144f,0.453393f}, -{0.314057f,-0.0907801f,0.945054f},{0.44313f,-0.0959191f,0.891311f},{0.722395f,-0.263838f,0.639168f}, -{0.517285f,-0.375435f,0.769067f},{0.55436f,-0.533057f,0.639168f},{0.54356f,-0.599175f,0.58782f}, -{0.583779f,-0.260264f,0.769067f},{0.600378f,-0.219275f,0.769067f},{0.56431f,-0.300149f,0.769067f}, -{0.542092f,-0.338632f,0.769067f},{0.475103f,-0.523714f,0.707107f},{0.459363f,-0.167772f,0.87226f}, -{0.414767f,-0.259095f,0.87226f},{0.395786f,-0.287254f,0.87226f},{0.394946f,-0.435355f,0.809002f}, -{0.301672f,-0.0652993f,0.951173f},{0.288626f,-0.153517f,0.945054f},{0.277263f,-0.1732f,0.945054f}, -{0.264575f,-0.192023f,0.945054f},{0.123721f,-0.103581f,0.986896f},{0.250663f,-0.209858f,0.945054f}, -{0.147374f,-0.0657031f,0.986896f},{0.142459f,-0.075772f,0.986896f},{0.13685f,-0.085487f,0.986896f}, -{0.130587f,-0.0947778f,0.986896f},{8.87339e-016f,-1.30421e-016f,1.0f},{2.79757e-015f,-1.76166e-015f,1.0f}, -{3.59024e-015f,-1.95786e-015f,1.0f},{7.32027e-016f,-1.12982e-015f,1.0f},{6.46328e-008f,-5.41113e-008f,1.0f}, -{0.0328513f,-0.944483f,0.326914f},{0.0907435f,-0.867527f,0.489042f},{0.0303209f,-0.871733f,0.489042f}, -{0.170294f,-0.972093f,0.161356f},{0.102669f,-0.981541f,0.161356f},{0.103293f,-0.994651f,6.83652e-010f}, -{0.080008f,-0.764894f,0.639168f},{0.0344869f,-0.999405f,-3.61854e-015f},{0.226672f,-0.917468f,0.326914f}, -{0.236707f,-0.958089f,0.161356f},{0.290467f,-0.905442f,0.309522f},{0.239133f,-0.970987f,1.70293e-010f}, -{0.301719f,-0.940516f,0.156188f},{0.0387014f,-0.156646f,0.986896f},{0.0278429f,-0.158936f,0.986896f}, -{0.0564107f,-0.32201f,0.945054f},{0.305468f,-0.952202f,1.00419e-015f},{0.171605f,-0.985166f,1.49536e-016f}, -{0.215998f,-0.673309f,0.707107f},{0.153305f,-0.62051f,0.769067f},{0.184461f,-0.746618f,0.639168f}, -{0.0508762f,-0.486388f,0.87226f},{0.0340097f,-0.32514f,0.945054f},{0.0169997f,-0.488746f,0.87226f}, -{0.117297f,-0.474766f,0.87226f},{0.17956f,-0.559723f,0.808992f},{0.0343058f,-0.9863f,0.161356f}, -{0.0983164f,-0.939926f,0.326914f},{-1.84702e-016f,-8.4923e-016f,1.0f},{-5.3061e-016f,-3.14148e-015f,1.0f}, -{-0.132707f,-0.757531f,0.639168f},{-0.209212f,-0.846799f,0.489042f},{-0.150513f,-0.859176f,0.489042f}, -{0.0477436f,-0.148826f,0.98771f},{-1.3262e-015f,8.93678e-016f,1.0f},{-0.0267338f,-0.768603f,0.639168f}, -{-0.0907434f,-0.867527f,0.489042f},{-0.030321f,-0.871733f,0.489042f},{0.0267338f,-0.768603f,0.639168f}, -{-0.153305f,-0.62051f,0.769067f},{-0.110292f,-0.62958f,0.769067f},{-0.0843867f,-0.481706f,0.87226f}, -{-0.0784104f,-0.317371f,0.945054f},{-0.138865f,-0.432871f,0.890696f},{-0.117297f,-0.474767f,0.87226f}, -{-0.080008f,-0.764894f,0.639168f},{-0.0477103f,-0.148722f,0.987727f},{-0.094549f,-0.294728f,0.950892f}, -{-0.0387014f,-0.156646f,0.986896f},{-0.0343058f,-0.9863f,0.161356f},{-0.0328514f,-0.944483f,0.326914f}, -{-2.02179e-008f,-8.18332e-008f,1.0f},{-2.5749e-008f,-8.02647e-008f,1.0f},{-0.0344801f,-0.999405f,1.75276e-009f}, -{-0.102669f,-0.981541f,0.161356f},{-0.10328f,-0.994652f,2.54736e-015f},{-0.170294f,-0.972093f,0.161356f}, -{-0.171593f,-0.985168f,5.72641e-011f},{-0.239168f,-0.970978f,-9.94311e-016f},{-0.236707f,-0.958089f,0.161356f}, -{-0.305468f,-0.952202f,1.57973e-015f},{0.272079f,-0.848123f,0.454599f},{0.209212f,-0.846799f,0.489042f}, -{0.163074f,-0.930878f,0.326914f},{-0.0983163f,-0.939926f,0.326914f},{-0.226672f,-0.917468f,0.326914f}, -{-0.163074f,-0.930878f,0.326914f},{-0.301713f,-0.9405f,0.156297f},{-0.290552f,-0.905709f,0.308658f}, -{0.247124f,-0.770333f,0.587806f},{0.150513f,-0.859176f,0.489042f},{-0.272267f,-0.848708f,0.453393f}, -{0.0784104f,-0.317371f,0.945054f},{0.138497f,-0.431722f,0.891311f},{0.132707f,-0.757531f,0.639168f}, -{-0.0664942f,-0.6357f,0.769067f},{-0.184461f,-0.746618f,0.639168f},{-0.247121f,-0.770324f,0.58782f}, -{0.0664942f,-0.6357f,0.769067f},{0.110292f,-0.62958f,0.769067f},{0.0222183f,-0.638781f,0.769067f}, -{-0.0222183f,-0.638781f,0.769067f},{-0.215998f,-0.673309f,0.707107f},{0.0843867f,-0.481706f,0.87226f}, -{-0.0169997f,-0.488746f,0.87226f},{-0.0508762f,-0.486388f,0.87226f},{-0.179556f,-0.559711f,0.809002f}, -{0.0942851f,-0.293905f,0.951173f},{0.011364f,-0.326716f,0.945054f},{-0.011364f,-0.326716f,0.945054f}, -{-0.0340097f,-0.32514f,0.945054f},{-0.0278429f,-0.158936f,0.986896f},{-0.0564107f,-0.32201f,0.945054f}, -{0.0167863f,-0.160481f,0.986896f},{0.00560897f,-0.161259f,0.986896f},{-0.00560897f,-0.161259f,0.986896f}, -{-0.0167863f,-0.160481f,0.986896f},{5.91466e-017f,2.9267e-015f,1.0f},{9.34451e-017f,7.88771e-016f,1.0f}, -{-2.08722e-016f,9.49885e-016f,1.0f},{-3.51097e-016f,1.29965e-015f,1.0f},{-1.45453e-008f,-8.30293e-008f,1.0f}, -{-0.837008f,-0.52286f,0.161356f},{-0.764842f,-0.555108f,0.326914f},{-0.801521f,-0.500692f,0.326914f}, -{-0.798705f,-0.579685f,0.161356f},{-0.833333f,-0.552772f,8.1345e-010f},{-0.797431f,-0.60341f,7.34316e-016f}, -{-0.705929f,-0.51235f,0.489042f},{-0.739783f,-0.462125f,0.489042f},{-0.622414f,-0.451736f,0.639168f}, -{-0.681215f,-0.655037f,0.326914f},{-0.711375f,-0.684039f,0.161356f},{-0.638902f,-0.704273f,0.309522f}, -{-0.598457f,-0.659689f,0.454599f},{-0.123721f,-0.103581f,0.986896f},{-0.250664f,-0.209858f,0.945054f}, -{-0.116309f,-0.11184f,0.986896f},{-0.663652f,-0.731554f,0.156188f},{-0.716527f,-0.69756f,1.21528e-015f}, -{-0.671898f,-0.740644f,0.0f},{-0.75671f,-0.633525f,0.161356f},{-0.758457f,-0.651723f,3.15624e-010f}, -{-0.352511f,-0.338965f,0.87226f},{-0.460725f,-0.443021f,0.769067f},{-0.394955f,-0.435365f,0.808992f}, -{-8.27806e-016f,-2.64658e-016f,1.0f},{-2.98591e-015f,-1.11122e-015f,1.0f},{-0.414767f,-0.259095f,0.87226f}, -{-0.395786f,-0.287254f,0.87226f},{-0.264575f,-0.192023f,0.945054f},{-0.105015f,-0.11576f,0.98771f}, -{-7.33106e-016f,6.65059e-016f,1.0f},{-0.55436f,-0.533057f,0.639168f},{-0.475103f,-0.523714f,0.707107f}, -{-0.722395f,-0.263838f,0.639168f},{-0.837955f,-0.242217f,0.489042f},{-0.819325f,-0.29924f,0.489042f}, -{-0.652262f,-0.407453f,0.639168f},{-0.314057f,-0.0907802f,0.945054f},{-0.44431f,-0.0961744f,0.890696f}, -{-0.469808f,-0.135801f,0.87226f},{-0.834372f,-0.443791f,0.326914f},{-0.871314f,-0.46344f,0.161356f}, -{-0.61403f,-0.177489f,0.769067f},{-0.600378f,-0.219275f,0.769067f},{-0.459363f,-0.167772f,0.87226f}, -{-0.796673f,-0.355178f,0.489042f},{-0.702422f,-0.313158f,0.639168f},{-0.678996f,-0.361149f,0.639168f}, -{-0.770104f,-0.409608f,0.489042f},{-0.152652f,-0.0330429f,0.987727f},{-0.302516f,-0.0654821f,0.950892f}, -{-0.15501f,-0.0448068f,0.986896f},{-0.866025f,-0.5f,2.38332e-016f},{-8.09785e-008f,-2.34074e-008f,1.0f}, -{-8.23857e-008f,-1.78331e-008f,1.0f},{-0.901374f,-0.401856f,0.161356f},{-0.895376f,-0.445311f,1.22111e-009f}, -{-0.927004f,-0.338567f,0.161356f},{-0.921279f,-0.388901f,-6.39659e-016f},{-0.943633f,-0.330994f,-1.23724e-015f}, -{-0.948083f,-0.27405f,0.161356f},{-0.962377f,-0.271719f,3.07701e-011f},{-0.977365f,-0.211559f,2.38885e-015f}, -{-0.965354f,-0.208959f,0.156297f},{-0.628743f,-0.604582f,0.489042f},{-0.724627f,-0.606665f,0.326914f}, -{-0.863158f,-0.384819f,0.326914f},{-0.887701f,-0.324213f,0.326914f},{-0.907886f,-0.262431f,0.326914f}, -{-0.929644f,-0.201229f,0.308658f},{-0.543566f,-0.599182f,0.587806f},{-0.668812f,-0.559936f,0.489042f}, -{-0.871136f,-0.188564f,0.453393f},{-0.235646f,-0.226591f,0.945054f},{-0.304634f,-0.335803f,0.891311f}, -{-0.589688f,-0.493693f,0.639168f},{-0.583779f,-0.260264f,0.769067f},{-0.738821f,-0.213561f,0.639168f}, -{-0.790681f,-0.171149f,0.58782f},{-0.517285f,-0.375435f,0.769067f},{-0.490087f,-0.410306f,0.769067f}, -{-0.542092f,-0.338632f,0.769067f},{-0.56431f,-0.300149f,0.769067f},{-0.691102f,-0.149594f,0.707107f}, -{-0.374976f,-0.313934f,0.87226f},{-0.431766f,-0.229651f,0.87226f},{-0.446663f,-0.199134f,0.87226f}, -{-0.574502f,-0.124355f,0.809002f},{-0.207387f,-0.228606f,0.951173f},{-0.277263f,-0.1732f,0.945054f}, -{-0.288626f,-0.153517f,0.945054f},{-0.298584f,-0.133117f,0.945054f},{-0.151564f,-0.0553554f,0.986896f}, -{-0.307074f,-0.112152f,0.945054f},{-0.130587f,-0.0947778f,0.986896f},{-0.13685f,-0.085487f,0.986896f}, -{-0.142459f,-0.075772f,0.986896f},{-0.147374f,-0.0657031f,0.986896f},{4.59728e-015f,2.88772e-015f,1.0f}, -{1.79512e-015f,9.7893e-016f,1.0f},{4.41022e-016f,5.0824e-016f,1.0f},{9.49983e-016f,9.53884e-016f,1.0f}, -{-7.91781e-008f,-2.8918e-008f,1.0f},{-0.871314f,0.46344f,0.161356f},{-0.863158f,0.384819f,0.326914f}, -{-0.834372f,0.443791f,0.326914f},{-0.901374f,0.401856f,0.161356f},{-0.895381f,0.445302f,8.13446e-010f}, -{-0.921284f,0.38889f,9.4659e-016f},{-0.796673f,0.355178f,0.489042f},{-0.770104f,0.409608f,0.489042f}, -{-0.702422f,0.313158f,0.639168f},{-0.907886f,0.262431f,0.326914f},{-0.948083f,0.27405f,0.161356f}, -{-0.929369f,0.201169f,0.309522f},{-0.870535f,0.188434f,0.454599f},{-0.151564f,0.0553554f,0.986896f}, -{-0.307074f,0.112152f,0.945054f},{-0.15501f,0.0448068f,0.986896f},{-0.965371f,0.208962f,0.156188f}, -{-0.962368f,0.27175f,-1.62219e-016f},{-0.977365f,0.211559f,-2.45529e-015f},{-0.927004f,0.338567f,0.161356f}, -{-0.943637f,0.330981f,3.15622e-010f},{-0.469808f,0.135801f,0.87226f},{-0.61403f,0.177489f,0.769067f}, -{-0.574515f,0.124358f,0.808992f},{-6.43103e-016f,5.84572e-016f,1.0f},{-2.4553e-015f,2.03026e-015f,1.0f}, -{-0.431766f,0.229651f,0.87226f},{-0.446663f,0.199134f,0.87226f},{-0.298584f,0.133117f,0.945054f}, -{-0.152759f,0.0330659f,0.98771f},{1.43705e-015f,7.01685e-016f,1.0f},{-0.738821f,0.213561f,0.639168f}, -{-0.691102f,0.149594f,0.707107f},{-0.589688f,0.493693f,0.639168f},{-0.628743f,0.604582f,0.489042f}, -{-0.668812f,0.559936f,0.489042f},{-0.678996f,0.361149f,0.639168f},{-0.235646f,0.226591f,0.945054f}, -{-0.305444f,0.336696f,0.890696f},{-0.352511f,0.338965f,0.87226f},{-0.801521f,0.500692f,0.326914f}, -{-0.837008f,0.52286f,0.161356f},{-0.460725f,0.443021f,0.769067f},{-0.490087f,0.410306f,0.769067f}, -{-0.374976f,0.313934f,0.87226f},{-0.705929f,0.51235f,0.489042f},{-0.622414f,0.451736f,0.639168f}, -{-0.652262f,0.407453f,0.639168f},{-0.739783f,0.462125f,0.489042f},{-0.104942f,0.115679f,0.987727f}, -{-0.207967f,0.229246f,0.950892f},{-0.116309f,0.11184f,0.986896f},{-0.866025f,0.5f,1.57009e-016f}, -{-6.07606e-008f,5.84258e-008f,1.0f},{-5.66367e-008f,6.24316e-008f,1.0f},{-0.798705f,0.579685f,0.161356f}, -{-0.833339f,0.552763f,1.22111e-009f},{-0.75671f,0.633525f,0.161356f},{-0.797438f,0.603401f,8.79779e-016f}, -{-0.758466f,0.651713f,-6.70447e-017f},{-0.711375f,0.684039f,0.161356f},{-0.716504f,0.697583f,3.07702e-011f}, -{-0.66364f,0.731542f,0.156297f},{-0.837955f,0.242217f,0.489042f},{-0.887701f,0.324213f,0.326914f}, -{-0.764842f,0.555108f,0.326914f},{-0.724627f,0.606665f,0.326914f},{-0.681215f,0.655037f,0.326914f}, -{-0.639091f,0.70448f,0.308658f},{-0.79069f,0.171151f,0.587806f},{-0.819325f,0.29924f,0.489042f}, -{-0.59887f,0.660144f,0.453393f},{-0.314057f,0.0907801f,0.945054f},{-0.44313f,0.0959191f,0.891311f}, -{-0.722395f,0.263838f,0.639168f},{-0.517285f,0.375435f,0.769067f},{-0.55436f,0.533057f,0.639168f}, -{-0.54356f,0.599175f,0.58782f},{-0.583779f,0.260264f,0.769067f},{-0.600378f,0.219275f,0.769067f}, -{-0.56431f,0.300149f,0.769067f},{-0.542092f,0.338632f,0.769067f},{-0.475103f,0.523714f,0.707107f}, -{-0.459363f,0.167772f,0.87226f},{-0.414767f,0.259095f,0.87226f},{-0.395786f,0.287254f,0.87226f}, -{-0.394946f,0.435355f,0.809002f},{-0.301672f,0.0652993f,0.951173f},{-0.288626f,0.153517f,0.945054f}, -{-0.277263f,0.1732f,0.945054f},{-0.264575f,0.192023f,0.945054f},{-0.123721f,0.103581f,0.986896f}, -{-0.250663f,0.209858f,0.945054f},{-0.147374f,0.0657031f,0.986896f},{-0.142459f,0.075772f,0.986896f}, -{-0.13685f,0.085487f,0.986896f},{-0.130587f,0.0947778f,0.986896f},{2.50503e-015f,-1.51457e-015f,1.0f}, -{6.36373e-016f,-4.75311e-016f,1.0f},{9.26985e-016f,-2.94184e-016f,1.0f},{1.30108e-015f,-3.45767e-016f,1.0f}, -{-6.46328e-008f,5.41113e-008f,1.0f},{-0.0328513f,0.944483f,0.326914f},{-0.0907435f,0.867527f,0.489042f}, -{-0.0303209f,0.871733f,0.489042f},{-0.170294f,0.972093f,0.161356f},{-0.102669f,0.981541f,0.161356f}, -{-0.103293f,0.994651f,6.83653e-010f},{-0.080008f,0.764894f,0.639168f},{-0.0344869f,0.999405f,-4.77516e-016f}, -{-0.226672f,0.917468f,0.326914f},{-0.236707f,0.958089f,0.161356f},{-0.290467f,0.905442f,0.309522f}, -{-0.239133f,0.970987f,1.70296e-010f},{-0.301719f,0.940516f,0.156188f},{-0.0387014f,0.156646f,0.986896f}, -{-0.0278429f,0.158936f,0.986896f},{-0.0564107f,0.32201f,0.945054f},{-0.305468f,0.952202f,1.19604e-015f}, -{-0.171605f,0.985166f,5.25413e-016f},{-0.215998f,0.673309f,0.707107f},{-0.153305f,0.62051f,0.769067f}, -{-0.184461f,0.746618f,0.639168f},{-0.0508762f,0.486388f,0.87226f},{-0.0340097f,0.32514f,0.945054f}, -{-0.0169997f,0.488746f,0.87226f},{-0.117297f,0.474766f,0.87226f},{-0.17956f,0.559723f,0.808992f}, -{-0.0343058f,0.9863f,0.161356f},{-0.0983164f,0.939926f,0.326914f},{1.84702e-016f,8.4923e-016f,1.0f}, -{5.3061e-016f,3.14148e-015f,1.0f},{0.132707f,0.757531f,0.639168f},{0.209212f,0.846799f,0.489042f}, -{0.150513f,0.859176f,0.489042f},{-0.0477436f,0.148826f,0.98771f},{1.3262e-015f,-8.93678e-016f,1.0f}, -{0.0267338f,0.768603f,0.639168f},{0.0907434f,0.867527f,0.489042f},{0.030321f,0.871733f,0.489042f}, -{-0.0267338f,0.768603f,0.639168f},{0.153305f,0.62051f,0.769067f},{0.110292f,0.62958f,0.769067f}, -{0.0843867f,0.481706f,0.87226f},{0.0784104f,0.317371f,0.945054f},{0.138865f,0.432871f,0.890696f}, -{0.117297f,0.474767f,0.87226f},{0.080008f,0.764894f,0.639168f},{0.0477103f,0.148722f,0.987727f}, -{0.094549f,0.294728f,0.950892f},{0.0387014f,0.156646f,0.986896f},{0.0343058f,0.9863f,0.161356f}, -{0.0328514f,0.944483f,0.326914f},{2.02179e-008f,8.18332e-008f,1.0f},{2.5749e-008f,8.02647e-008f,1.0f}, -{0.0344801f,0.999405f,1.75276e-009f},{0.102669f,0.981541f,0.161356f},{0.10328f,0.994652f,1.28179e-015f}, -{0.170294f,0.972093f,0.161356f},{0.171593f,0.985168f,5.7267e-011f},{0.239168f,0.970978f,-1.14452e-015f}, -{0.236707f,0.958089f,0.161356f},{0.305468f,0.952202f,1.19604e-015f},{-0.272079f,0.848123f,0.454599f}, -{-0.209212f,0.846799f,0.489042f},{-0.163074f,0.930878f,0.326914f},{0.0983163f,0.939926f,0.326914f}, -{0.226672f,0.917468f,0.326914f},{0.163074f,0.930878f,0.326914f},{0.301713f,0.9405f,0.156297f}, -{0.290552f,0.905709f,0.308658f},{-0.247124f,0.770333f,0.587806f},{-0.150513f,0.859176f,0.489042f}, -{0.272267f,0.848708f,0.453393f},{-0.0784104f,0.317371f,0.945054f},{-0.138497f,0.431722f,0.891311f}, -{-0.132707f,0.757531f,0.639168f},{0.0664942f,0.6357f,0.769067f},{0.184461f,0.746618f,0.639168f}, -{0.247121f,0.770324f,0.58782f},{-0.0664942f,0.6357f,0.769067f},{-0.110292f,0.62958f,0.769067f}, -{-0.0222183f,0.638781f,0.769067f},{0.0222183f,0.638781f,0.769067f},{0.215998f,0.673309f,0.707107f}, -{-0.0843867f,0.481706f,0.87226f},{0.0169997f,0.488746f,0.87226f},{0.0508762f,0.486388f,0.87226f}, -{0.179556f,0.559711f,0.809002f},{-0.0942851f,0.293905f,0.951173f},{-0.011364f,0.326716f,0.945054f}, -{0.011364f,0.326716f,0.945054f},{0.0340097f,0.32514f,0.945054f},{0.0278429f,0.158936f,0.986896f}, -{0.0564107f,0.32201f,0.945054f},{-0.0167863f,0.160481f,0.986896f},{-0.00560897f,0.161259f,0.986896f}, -{0.00560897f,0.161259f,0.986896f},{0.0167863f,0.160481f,0.986896f},{-5.91466e-017f,-2.9267e-015f,1.0f}, -{-9.34451e-017f,-7.88771e-016f,1.0f},{2.08722e-016f,-9.49885e-016f,1.0f},{3.51097e-016f,-1.29965e-015f,1.0f}, -{1.45453e-008f,8.30293e-008f,1.0f},{0.837008f,0.52286f,0.161356f},{0.764842f,0.555108f,0.326914f}, -{0.801521f,0.500692f,0.326914f},{0.798705f,0.579685f,0.161356f},{0.833333f,0.552772f,8.13449e-010f}, -{0.797431f,0.60341f,4.1114e-016f},{0.705929f,0.51235f,0.489042f},{0.739783f,0.462125f,0.489042f}, -{0.622414f,0.451736f,0.639168f},{0.681215f,0.655037f,0.326914f},{0.711375f,0.684039f,0.161356f}, -{0.638902f,0.704273f,0.309522f},{0.598457f,0.659689f,0.454599f},{0.123721f,0.103581f,0.986896f}, -{0.250664f,0.209858f,0.945054f},{0.116309f,0.11184f,0.986896f},{0.663652f,0.731554f,0.156188f}, -{0.716527f,0.69756f,2.35065e-015f},{0.75671f,0.633525f,0.161356f},{0.758457f,0.651723f,3.1562e-010f}, -{0.352511f,0.338965f,0.87226f},{0.460725f,0.443021f,0.769067f},{0.394955f,0.435365f,0.808992f}, -{8.27806e-016f,2.64658e-016f,1.0f},{2.98591e-015f,1.11122e-015f,1.0f},{0.414767f,0.259095f,0.87226f}, -{0.395786f,0.287254f,0.87226f},{0.264575f,0.192023f,0.945054f},{0.105015f,0.11576f,0.98771f}, -{7.33106e-016f,-6.65059e-016f,1.0f},{0.55436f,0.533057f,0.639168f},{0.475103f,0.523714f,0.707107f}, -{0.722395f,0.263838f,0.639168f},{0.837955f,0.242217f,0.489042f},{0.819325f,0.29924f,0.489042f}, -{0.652262f,0.407453f,0.639168f},{0.314057f,0.0907802f,0.945054f},{0.44431f,0.0961744f,0.890696f}, -{0.469808f,0.135801f,0.87226f},{0.834372f,0.443791f,0.326914f},{0.871314f,0.46344f,0.161356f}, -{0.61403f,0.177489f,0.769067f},{0.600378f,0.219275f,0.769067f},{0.459363f,0.167772f,0.87226f}, -{0.796673f,0.355178f,0.489042f},{0.702422f,0.313158f,0.639168f},{0.678996f,0.361149f,0.639168f}, -{0.770104f,0.409608f,0.489042f},{0.152652f,0.0330429f,0.987727f},{0.302516f,0.0654821f,0.950892f}, -{0.15501f,0.0448068f,0.986896f},{0.866025f,0.5f,1.11024e-015f},{8.09785e-008f,2.34074e-008f,1.0f}, -{8.23857e-008f,1.78331e-008f,1.0f},{0.901374f,0.401856f,0.161356f},{0.895376f,0.445311f,1.22111e-009f}, -{0.927004f,0.338567f,0.161356f},{0.921279f,0.388901f,-2.25333e-015f},{0.943633f,0.330994f,-1.1333e-015f}, -{0.948083f,0.27405f,0.161356f},{0.962377f,0.271719f,3.07706e-011f},{0.977365f,0.211559f,-6.64333e-017f}, -{0.965354f,0.208959f,0.156297f},{0.628743f,0.604582f,0.489042f},{0.724627f,0.606665f,0.326914f}, -{0.863158f,0.384819f,0.326914f},{0.887701f,0.324213f,0.326914f},{0.907886f,0.262431f,0.326914f}, -{0.929644f,0.201229f,0.308658f},{0.543566f,0.599182f,0.587806f},{0.668812f,0.559936f,0.489042f}, -{0.871136f,0.188564f,0.453393f},{0.235646f,0.226591f,0.945054f},{0.304634f,0.335803f,0.891311f}, -{0.589688f,0.493693f,0.639168f},{0.583779f,0.260264f,0.769067f},{0.738821f,0.213561f,0.639168f}, -{0.790681f,0.171149f,0.58782f},{0.517285f,0.375435f,0.769067f},{0.490087f,0.410306f,0.769067f}, -{0.542092f,0.338632f,0.769067f},{0.56431f,0.300149f,0.769067f},{0.691102f,0.149594f,0.707107f}, -{0.374976f,0.313934f,0.87226f},{0.431766f,0.229651f,0.87226f},{0.446663f,0.199134f,0.87226f}, -{0.574502f,0.124355f,0.809002f},{0.207387f,0.228606f,0.951173f},{0.277263f,0.1732f,0.945054f}, -{0.288626f,0.153517f,0.945054f},{0.298584f,0.133117f,0.945054f},{0.151564f,0.0553554f,0.986896f}, -{0.307074f,0.112152f,0.945054f},{0.130587f,0.0947778f,0.986896f},{0.13685f,0.085487f,0.986896f}, -{0.142459f,0.075772f,0.986896f},{0.147374f,0.0657031f,0.986896f},{-4.59728e-015f,-2.88772e-015f,1.0f}, -{-1.79512e-015f,-9.7893e-016f,1.0f},{-4.41022e-016f,-5.0824e-016f,1.0f},{-9.49983e-016f,-9.53884e-016f,1.0f}, -{7.91781e-008f,2.8918e-008f,1.0f},{3.46945e-018f,0.0f,-1.0f},{2.38524e-018f,0.0f,-1.0f}, -{1.95156e-018f,0.0f,-1.0f},{-5.42101e-019f,0.0f,-1.0f},{-4.33681e-019f,0.0f,-1.0f}, -{2.60209e-018f,0.0f,-1.0f},{-2.98156e-018f,0.0f,-1.0f},{-1.73472e-018f,0.0f,-1.0f}, -{1.73472e-018f,0.0f,-1.0f},{-1.6263e-019f,0.0f,-1.0f},{-7.70988e-019f,0.0f,-1.0f}, -{-3.46945e-018f,0.0f,-1.0f},{-2.60209e-018f,0.0f,-1.0f},{-2.20326e-031f,-1.17145e-015f,-1.0f}, -{-2.03378e-031f,-1.17145e-015f,-1.0f},{-1.95674e-031f,-1.17145e-015f,-1.0f},{-2.00297e-031f,-1.17145e-015f,-1.0f}, -{-1.57156e-031f,-1.17145e-015f,-1.0f},{-1.77186e-031f,-1.17145e-015f,-1.0f},{-1.89512e-031f,-1.17145e-015f,-1.0f}, -{-2.80415e-031f,-1.17145e-015f,-1.0f},{-2.39586e-031f,-1.17145e-015f,-1.0f},{-2.31112e-031f,-1.17145e-015f,-1.0f}, -{-1.91052e-031f,-1.17145e-015f,-1.0f},{-1.52534e-031f,-1.17145e-015f,-1.0f},{-2.77255e-031f,-1.17145e-015f,-1.0f}, -{-1.92514e-031f,-1.17145e-015f,-1.0f},{-2.11003e-031f,-1.17145e-015f,-1.0f},{-1.83349e-031f,-1.17145e-015f,-1.0f}, -{-2.09541e-031f,-1.17145e-015f,-1.0f},{-1.81808e-031f,-1.17145e-015f,-1.0f},{-2.0646e-031f,-1.17145e-015f,-1.0f}, -{-1.78726e-031f,-1.17145e-015f,-1.0f},{-2.51141e-031f,-1.17145e-015f,-1.0f},{-2.41897e-031f,-1.17145e-015f,-1.0f}, -{-2.65008e-031f,-1.17145e-015f,-1.0f},{-1.67941e-031f,-1.17145e-015f,-1.0f},{-2.18786e-031f,-1.17145e-015f,-1.0f}, -{-2.25719e-031f,-1.17145e-015f,-1.0f},{-1.75645e-031f,-1.17145e-015f,-1.0f},{-1.74104e-031f,-1.17145e-015f,-1.0f}, -{-1.38667e-031f,-1.17145e-015f,-1.0f},{-1.43289e-031f,-1.17145e-015f,-1.0f},{-1.41748e-031f,-1.17145e-015f,-1.0f}, -{-2.94282e-031f,-1.17145e-015f,-1.0f},{-2.32652e-031f,-1.17145e-015f,-1.0f},{-2.60386e-031f,-1.17145e-015f,-1.0f}, -{-1.37126e-031f,-1.17145e-015f,-1.0f},{-2.26489e-031f,-1.17145e-015f,-1.0f},{-2.24949e-031f,-1.17145e-015f,-1.0f}, -{-1.50993e-031f,-1.17145e-015f,-1.0f},{-1.47911e-031f,-1.17145e-015f,-1.0f},{-2.38815e-031f,-1.17145e-015f,-1.0f}, -{-2.15704e-031f,-1.17145e-015f,-1.0f},{-2.11082e-031f,-1.17145e-015f,-1.0f},{-2.12623e-031f,-1.17145e-015f,-1.0f}, -{-3.23556e-031f,-1.17145e-015f,-1.0f},{-2.36504e-031f,-1.17145e-015f,-1.0f},{-2.4883e-031f,-1.17145e-015f,-1.0f}, -{-2.14934e-031f,-1.17145e-015f,-1.0f},{-2.37275e-031f,-1.17145e-015f,-1.0f},{-2.71171e-031f,-1.17145e-015f,-1.0f}, -{-1.72563e-031f,-1.17145e-015f,-1.0f},{-1.87971e-031f,-1.17145e-015f,-1.0f},{-2.66549e-031f,-1.17145e-015f,-1.0f}, -{-2.51912e-031f,-1.17145e-015f,-1.0f},{-3.0969e-031f,-1.17145e-015f,-1.0f},{-2.76564e-031f,-1.17145e-015f,-1.0f}, -{-2.21867e-031f,-1.17145e-015f,-1.0f},{-1.55615e-031f,-1.17145e-015f,-1.0f},{-3.26638e-031f,-1.17145e-015f,-1.0f}, -{-2.98904e-031f,-1.17145e-015f,-1.0f},{-2.74252e-031f,-1.17145e-015f,-1.0f},{-1.46371e-031f,-1.17145e-015f,-1.0f}, -{-3.03527e-031f,-1.17145e-015f,-1.0f},{-2.96593e-031f,-1.17145e-015f,-1.0f},{-1.60237e-031f,-1.17145e-015f,-1.0f}, -{-2.68089e-031f,-1.17145e-015f,-1.0f},{-3.18934e-031f,-1.17145e-015f,-1.0f},{-2.81956e-031f,-1.17145e-015f,-1.0f}, -{-3.20475e-031f,-1.17145e-015f,-1.0f},{-2.41126e-031f,-1.17145e-015f,-1.0f},{-2.55763e-031f,-1.17145e-015f,-1.0f}, -{-1.54074e-031f,-1.17145e-015f,-1.0f},{-1.4483e-031f,-1.17145e-015f,-1.0f},{-1.35585e-031f,-1.17145e-015f,-1.0f}, -{-3.05838e-031f,-1.17145e-015f,-1.0f},{-2.58845e-031f,-1.17145e-015f,-1.0f},{-1.69482e-031f,-1.17145e-015f,-1.0f}, -{-1.49452e-031f,-1.17145e-015f,-1.0f},{-2.69551e-031f,-1.17145e-015f,-1.0f},{-3.92278e-031f,-1.17145e-015f,-1.0f}, -{-3.2802e-031f,-1.17145e-015f,-1.0f},{-1.71023e-031f,-1.17145e-015f,-1.0f},{-1.58697e-031f,-1.17145e-015f,-1.0f}, -{-2.64238e-031f,-1.17145e-015f,-1.0f},{-2.45749e-031f,-1.17145e-015f,-1.0f},{-2.54223e-031f,-1.17145e-015f,-1.0f}, -{-1.80267e-031f,-1.17145e-015f,-1.0f},{-1.63319e-031f,-1.17145e-015f,-1.0f},{-2.01837e-031f,-1.17145e-015f,-1.0f}, -{-2.17245e-031f,-1.17145e-015f,-1.0f},{-2.04919e-031f,-1.17145e-015f,-1.0f},{-2.2803e-031f,-1.17145e-015f,-1.0f}, -{-1.94134e-031f,-1.17145e-015f,-1.0f},{-2.14163e-031f,-1.17145e-015f,-1.0f},{-1.98756e-031f,-1.17145e-015f,-1.0f}, -{-2.23408e-031f,-1.17145e-015f,-1.0f},{-2.50371e-031f,-1.17145e-015f,-1.0f},{-2.44208e-031f,-1.17145e-015f,-1.0f}, -{-1.8643e-031f,-1.17145e-015f,-1.0f},{-1.97215e-031f,-1.17145e-015f,-1.0f},{-3.12001e-031f,-1.17145e-015f,-1.0f}, -{-2.99833e-031f,-1.17145e-015f,-1.0f},{-2.57304e-031f,-1.17145e-015f,-1.0f},{-2.6963e-031f,-1.17145e-015f,-1.0f}, -{-2.47289e-031f,-1.17145e-015f,-1.0f},{-2.47369e-031f,-1.17145e-015f,-1.0f},{-3.32959e-031f,-1.17145e-015f,-1.0f}, -{-2.01679e-031f,-1.17145e-015f,-1.0f},{-3.32721e-031f,-1.17145e-015f,-1.0f},{-2.62697e-031f,-1.17145e-015f,-1.0f}, -{-4.06836e-031f,-1.17145e-015f,-1.0f},{-2.87428e-031f,-1.17145e-015f,-1.0f},{-2.64929e-031f,-1.17145e-015f,-1.0f}, -{-1.664e-031f,-1.17145e-015f,-1.0f},{-3.01215e-031f,-1.17145e-015f,-1.0f},{-2.10232e-031f,-1.17145e-015f,-1.0f}, -{-2.94973e-031f,-1.17145e-015f,-1.0f},{-3.87656e-031f,-1.17145e-015f,-1.0f},{-3.62686e-031f,-1.17145e-015f,-1.0f}, -{-2.21097e-031f,-1.17145e-015f,-1.0f},{-2.61156e-031f,-1.17145e-015f,-1.0f},{-3.06608e-031f,-1.17145e-015f,-1.0f}, -{-3.08149e-031f,-1.17145e-015f,-1.0f},{-3.05067e-031f,-1.17145e-015f,-1.0f},{-2.93512e-031f,-1.17145e-015f,-1.0f}, -{-1.96445e-031f,-1.17145e-015f,-1.0f},{-2.95823e-031f,-1.17145e-015f,-1.0f},{-1.61778e-031f,-1.17145e-015f,-1.0f}, -{-2.87349e-031f,-1.17145e-015f,-1.0f},{-2.79645e-031f,-1.17145e-015f,-1.0f},{-2.92741e-031f,-1.17145e-015f,-1.0f}, -{-3.5129e-031f,-1.17145e-015f,-1.0f},{-2.84267e-031f,-1.17145e-015f,-1.0f},{-2.85038e-031f,-1.17145e-015f,-1.0f}, -{-2.34963e-031f,-1.17145e-015f,-1.0f},{-2.2726e-031f,-1.17145e-015f,-1.0f},{-2.02449e-031f,-1.17145e-015f,-1.0f}, -{-2.89819e-031f,-1.17145e-015f,-1.0f},{-3.02145e-031f,-1.17145e-015f,-1.0f},{-2.6562e-031f,-1.17145e-015f,-1.0f}, -{-2.44287e-031f,-1.17145e-015f,-1.0f},{-3.66776e-031f,-1.17145e-015f,-1.0f},{-3.23715e-031f,-1.17145e-015f,-1.0f}, -{-2.31723e-031f,-1.17145e-015f,-1.0f},{-2.20938e-031f,-1.17145e-015f,-1.0f},{-3.99211e-031f,-1.17145e-015f,-1.0f}, -{-2.30262e-031f,-1.17145e-015f,-1.0f},{-2.12702e-031f,-1.17145e-015f,-1.0f},{-2.62006e-031f,-1.17145e-015f,-1.0f}, -{-1.87812e-031f,-1.17145e-015f,-1.0f},{-3.71399e-031f,-1.17145e-015f,-1.0f},{-2.52682e-031f,-1.17145e-015f,-1.0f}, -{-2.98134e-031f,-1.17145e-015f,-1.0f},{-2.77334e-031f,-1.17145e-015f,-1.0f},{-2.44978e-031f,-1.17145e-015f,-1.0f}, -{-2.30341e-031f,-1.17145e-015f,-1.0f},{-1.4406e-031f,-1.17145e-015f,-1.0f},{-2.35734e-031f,-1.17145e-015f,-1.0f}, -{-2.72712e-031f,-1.17145e-015f,-1.0f},{-2.67319e-031f,-1.17145e-015f,-1.0f},{-1.47141e-031f,-1.17145e-015f,-1.0f}, -{-1.34815e-031f,-1.17145e-015f,-1.0f},{-2.54993e-031f,-1.17145e-015f,-1.0f},{-3.28949e-031f,-1.17145e-015f,-1.0f}, -{-3.7363e-031f,-1.17145e-015f,-1.0f},{-1.73175e-031f,-1.17145e-015f,-1.0f},{-2.34034e-031f,-1.17145e-015f,-1.0f}, -{-2.33423e-031f,-1.17145e-015f,-1.0f},{-2.46519e-031f,-1.17145e-015f,-1.0f},{-1.92593e-031f,-1.17145e-015f,-1.0f}, -{-7.67197e-032f,-1.17145e-015f,-1.0f},{-1.6486e-031f,-1.17145e-015f,-1.0f},{-1.84889e-031f,-1.17145e-015f,-1.0f}, -{-7.98012e-032f,-1.17145e-015f,-1.0f},{-1.40208e-031f,-1.17145e-015f,-1.0f},{-2.16475e-031f,-1.17145e-015f,-1.0f}, -{-2.88889e-031f,-1.17145e-015f,-1.0f},{-2.43438e-031f,-1.17145e-015f,-1.0f},{-3.00445e-031f,-1.17145e-015f,-1.0f}, -{-2.38045e-031f,-1.17145e-015f,-1.0f},{-3.22786e-031f,-1.17145e-015f,-1.0f},{-2.78875e-031f,-1.17145e-015f,-1.0f}, -{-2.56534e-031f,-1.17145e-015f,-1.0f},{0.0f,1.17961e-015f,1.0f},{0.0f,1.20737e-015f,1.0f}, -{0.0f,1.19349e-015f,1.0f},{1.38778e-017f,1.19349e-015f,1.0f},{1.04083e-017f,1.19349e-015f,1.0f}, -{-1.38778e-017f,1.16573e-015f,1.0f},{-5.20417e-018f,1.19349e-015f,1.0f},{8.67362e-018f,1.19349e-015f,1.0f}, -{1.38778e-017f,1.16573e-015f,1.0f},{-2.60209e-018f,1.16573e-015f,1.0f},{1.21431e-017f,1.16573e-015f,1.0f}, -{-1.38778e-017f,1.20737e-015f,1.0f},{5.63785e-018f,1.16573e-015f,1.0f},{3.46945e-018f,1.19349e-015f,1.0f}, -{-4.33681e-018f,1.16573e-015f,1.0f},{1.12757e-017f,1.19349e-015f,1.0f},{5.20417e-018f,1.19349e-015f,1.0f}, -{-1.21431e-017f,1.19349e-015f,1.0f},{0.0f,1.16573e-015f,1.0f},{-1.30917e-017f,1.22125e-015f,1.0f}, -{-3.08998e-018f,1.16573e-015f,1.0f},{1.0842e-017f,1.16573e-015f,1.0f},{-1.73472e-018f,1.19349e-015f,1.0f}, -{-5.20417e-018f,1.16573e-015f,1.0f},{-9.21572e-019f,1.16573e-015f,1.0f},{6.93889e-018f,1.16573e-015f,1.0f}, -{6.93889e-018f,1.17961e-015f,1.0f},{6.07153e-018f,1.19349e-015f,1.0f},{-1.30104e-017f,1.16573e-015f,1.0f}, -{-2.27741e-032f,1.19349e-015f,1.0f},{-6.93889e-018f,1.16573e-015f,1.0f},{-1.73472e-018f,1.17961e-015f,1.0f}, -{8.67362e-018f,1.16573e-015f,1.0f},{-1.04083e-017f,1.17961e-015f,1.0f},{-1.38778e-017f,1.15186e-015f,1.0f}, -{-1.04083e-017f,1.16573e-015f,1.0f},{6.93889e-018f,1.20737e-015f,1.0f},{1.04083e-017f,1.17961e-015f,1.0f}, -{1.73472e-018f,1.16573e-015f,1.0f},{-1.67556e-032f,1.20737e-015f,1.0f},{1.21431e-017f,1.19349e-015f,1.0f}, -{-1.21431e-017f,1.17961e-015f,1.0f},{-1.38778e-017f,1.19349e-015f,1.0f},{-1.12757e-017f,1.16573e-015f,1.0f}, -{-3.90313e-018f,1.16573e-015f,1.0f},{-1.73472e-018f,1.16573e-015f,1.0f},{-2.60209e-018f,1.19349e-015f,1.0f}, -{1.14925e-017f,1.22125e-015f,1.0f},{-2.1684e-018f,1.19349e-015f,1.0f},{-6.93889e-018f,1.20737e-015f,1.0f}, -{-6.93889e-018f,1.17961e-015f,1.0f},{4.33681e-018f,1.16573e-015f,1.0f},{-1.17094e-017f,1.16573e-015f,1.0f}, -{-7.88757e-018f,1.16573e-015f,1.0f},{6.93889e-018f,1.19349e-015f,1.0f},{-6.93889e-018f,1.19349e-015f,1.0f}, -{-1.51788e-018f,1.19349e-015f,1.0f},{-1.38778e-017f,1.17961e-015f,1.0f},{0.0f,1.22125e-015f,1.0f}, -{1.38778e-017f,1.20737e-015f,1.0f},{9.97466e-018f,1.19349e-015f,1.0f},{4.33681e-018f,1.19349e-015f,1.0f}, -{1.38778e-017f,1.17961e-015f,1.0f},{1.04083e-017f,1.16573e-015f,1.0f},{1.69482e-032f,1.22125e-015f,1.0f}, -{3.46945e-018f,1.16573e-015f,1.0f},{-2.77556e-017f,1.19349e-015f,1.0f},{6.54816e-032f,1.17961e-015f,1.0f}, -{2.77556e-017f,1.17961e-015f,1.0f},{2.77556e-017f,1.19349e-015f,1.0f},{2.77556e-017f,1.22125e-015f,1.0f}, -{2.77556e-017f,1.16573e-015f,1.0f},{6.6252e-032f,1.19349e-015f,1.0f},{-6.6252e-032f,1.19349e-015f,1.0f}, -{6.47112e-032f,1.16573e-015f,1.0f},{-0.0519993f,-0.998647f,1.21442e-015f},{-5.52964e-012f,-1.0f,1.18424e-015f}, -{2.37905e-016f,-1.0f,1.18424e-015f},{-0.207899f,-0.97815f,1.07201e-015f},{-0.156426f,-0.98769f,1.24943e-015f}, -{-0.207911f,-0.978148f,1.26828e-015f},{-0.156436f,-0.987688f,1.05591e-015f},{-0.104524f,-0.994522f,1.24233e-015f}, -{-0.104542f,-0.99452f,1.04524e-015f},{-0.358363f,-0.933582f,1.14589e-015f},{-0.406729f,-0.913549f,9.49444e-016f}, -{-0.358347f,-0.933588f,1.09983e-015f},{-0.258815f,-0.965927f,1.09287e-015f},{-0.309013f,-0.951058f,1.10648e-015f}, -{-0.258801f,-0.965931f,1.11634e-015f},{-0.54461f,-0.838689f,1.11736e-015f},{-0.499972f,-0.866041f,9.21437e-016f}, -{-0.54463f,-0.838677f,1.11734e-015f},{-0.453965f,-0.891019f,9.34273e-016f},{-0.406714f,-0.913555f,1.12976e-015f}, -{-0.45398f,-0.891012f,1.15409e-015f},{-0.669122f,-0.743152f,7.83812e-016f},{-0.707099f,-0.707115f,8.89729e-016f}, -{-0.669102f,-0.74317f,9.12177e-016f},{-0.587776f,-0.809024f,9.38116e-016f},{-0.629312f,-0.777153f,9.10747e-016f}, -{-0.587756f,-0.809038f,9.58094e-016f},{-0.809001f,-0.587808f,6.81602e-016f},{-0.777125f,-0.629346f,7.29768e-016f}, -{-0.809009f,-0.587797f,6.52585e-016f},{-0.74312f,-0.669158f,7.51169e-016f},{-0.70708f,-0.707134f,8.89753e-016f}, -{-0.743137f,-0.66914f,7.3464e-016f},{-0.891007f,-0.453989f,5.26431e-016f},{-0.913546f,-0.406734f,4.71636e-016f}, -{-0.890991f,-0.454022f,5.04065e-016f},{-0.838665f,-0.544647f,6.44992e-016f},{-0.866024f,-0.500002f,6.16793e-016f}, -{-0.838655f,-0.544663f,6.45011e-016f},{-0.965922f,-0.258835f,3.06522e-016f},{-0.951049f,-0.30904f,3.81226e-016f}, -{-0.965925f,-0.258822f,2.93736e-016f},{-0.933568f,-0.3584f,4.42115e-016f},{-0.913531f,-0.40677f,4.51605e-016f}, -{-0.933581f,-0.358367f,4.24392e-016f},{-0.987684f,-0.156459f,1.77565e-016f},{-0.994523f,-0.104515f,1.23771e-016f}, -{-0.994519f,-0.104553f,1.18657e-016f},{-0.978149f,-0.207904f,2.3595e-016f},{-0.987691f,-0.156421f,1.85239e-016f}, -{-0.978143f,-0.207932f,2.56501e-016f},{-0.998629f,0.052353f,-6.19984e-017f},{-0.99863f,0.052328f,-6.19688e-017f}, -{-1.0f,-3.17207e-017f,3.75648e-032f},{-1.0f,-1.58603e-017f,1.87824e-032f},{-0.998629f,-0.0523531f,5.94153e-017f}, -{-0.99863f,-0.0523281f,6.19689e-017f},{-0.978149f,0.207904f,-2.46208e-016f},{-0.987691f,0.156421f,-1.85239e-016f}, -{-0.978143f,0.207932f,-2.46241e-016f},{-0.994523f,0.104515f,-1.23771e-016f},{-0.994519f,0.104553f,-1.23816e-016f}, -{-0.987684f,0.156459f,-1.85285e-016f},{-0.951055f,0.309021f,-3.65954e-016f},{-0.951049f,0.30904f,-3.96476e-016f}, -{-0.933568f,0.3584f,-4.2443e-016f},{-0.965922f,0.258835f,-3.32066e-016f},{-0.965925f,0.258822f,-3.06506e-016f}, -{-0.913546f,0.406734f,-4.8167e-016f},{-0.890991f,0.454022f,-5.3767e-016f},{-0.891007f,0.453989f,-5.37631e-016f}, -{-0.913531f,0.40677f,-4.81712e-016f},{-0.933581f,0.358367f,-4.24392e-016f},{-0.838655f,0.544663f,-6.45011e-016f}, -{-0.809001f,0.587808f,-6.38096e-016f},{-0.838665f,0.544647f,-6.44992e-016f},{-0.866009f,0.500028f,-5.92152e-016f}, -{-0.866024f,0.500002f,-6.41465e-016f},{-0.777125f,0.629346f,-7.45295e-016f},{-0.74312f,0.669158f,-7.92442e-016f}, -{-0.777137f,0.629331f,-7.45278e-016f},{-0.809009f,0.587797f,-6.96091e-016f},{-0.70708f,0.707134f,-8.37415e-016f}, -{-0.669102f,0.74317f,-8.80091e-016f},{-0.707099f,0.707115f,-9.76958e-016f},{-0.743137f,0.66914f,-9.24491e-016f}, -{-0.669122f,0.743152f,-8.80069e-016f},{-0.629291f,0.777169f,-9.20353e-016f},{-0.587756f,0.809038f,-9.58094e-016f}, -{-0.629312f,0.777153f,-7.66945e-016f},{-0.54461f,0.838689f,-1.15874e-015f},{-0.587776f,0.809023f,-9.58076e-016f}, -{-0.54463f,0.838677f,-9.93193e-016f},{-0.499972f,0.866041f,-8.54666e-016f},{-0.453965f,0.891019f,-1.05518e-015f}, -{-0.49999f,0.866031f,-1.02559e-015f},{-0.406714f,0.913555f,-1.08187e-015f},{-0.45398f,0.891012f,-1.23103e-015f}, -{-0.406729f,0.913549f,-1.26217e-015f},{-0.358347f,0.933588f,-1.10559e-015f},{-0.308997f,0.951063f,-1.12628e-015f}, -{-0.358363f,0.933582f,-1.10558e-015f},{-0.258801f,0.965931f,-1.14389e-015f},{-0.309013f,0.951058f,-1.12628e-015f}, -{-0.258815f,0.965927f,-1.14389e-015f},{-0.207899f,0.97815f,-1.15836e-015f},{-0.156426f,0.98769f,-1.3646e-015f}, -{-0.207911f,0.978148f,-1.15836e-015f},{-0.104524f,0.994522f,-1.17775e-015f},{-0.156436f,0.987688f,-1.16966e-015f}, -{-0.104542f,0.99452f,-9.81457e-016f},{-0.0520121f,0.998646f,-1.18263e-015f},{8.72318e-017f,1.0f,-1.18424e-015f}, -{-0.0519994f,0.998647f,-1.18264e-015f},{-1.19209e-007f,1.0f,-1.18424e-015f},{-0.951055f,-0.309021f,3.65954e-016f}, -{-0.866009f,-0.500028f,5.92152e-016f},{-0.777137f,-0.629331f,7.76331e-016f},{-0.629291f,-0.77717f,8.91592e-016f}, -{-0.49999f,-0.866031f,9.64159e-016f},{-0.308997f,-0.951063f,1.10649e-015f},{-0.0520121f,-0.998646f,1.20806e-015f}, -{0.0f,-1.17614e-015f,-1.0f},{-3.46945e-018f,-1.17614e-015f,-1.0f},{3.46945e-018f,-1.1692e-015f,-1.0f}, -{3.46945e-018f,-1.17267e-015f,-1.0f},{-8.67362e-019f,-1.17961e-015f,-1.0f},{-1.73472e-018f,-1.17267e-015f,-1.0f}, -{3.46945e-018f,-1.17614e-015f,-1.0f},{8.67362e-019f,-1.17267e-015f,-1.0f},{2.60209e-018f,-1.17267e-015f,-1.0f}, -{0.0f,-1.17267e-015f,-1.0f},{2.38524e-018f,-1.17267e-015f,-1.0f},{-3.25261e-018f,-1.16573e-015f,-1.0f}, -{0.0f,-1.1692e-015f,-1.0f},{-3.46945e-018f,-1.17267e-015f,-1.0f},{-1.73472e-018f,-1.17614e-015f,-1.0f}, -{-3.23556e-032f,-1.16573e-015f,-1.0f},{-3.36103e-018f,-1.17267e-015f,-1.0f},{-3.41524e-018f,-1.17267e-015f,-1.0f}, -{1.76183e-018f,-1.17961e-015f,-1.0f},{-1.62741e-032f,-1.17267e-015f,-1.0f},{0.0f,-1.17961e-015f,-1.0f}, -{-3.14419e-018f,-1.17961e-015f,-1.0f},{1.04354e-018f,-1.17961e-015f,-1.0f},{-3.03577e-018f,-1.17961e-015f,-1.0f}, -{-1.73472e-018f,-1.1692e-015f,-1.0f},{1.63223e-032f,-1.17614e-015f,-1.0f},{2.60209e-018f,-1.1692e-015f,-1.0f}, -{1.73472e-018f,-1.17961e-015f,-1.0f},{3.46945e-018f,-1.16573e-015f,-1.0f},{1.40946e-018f,-1.17267e-015f,-1.0f}, -{2.60209e-018f,-1.17961e-015f,-1.0f},{-3.46945e-018f,-1.16573e-015f,-1.0f},{-2.60209e-018f,-1.17267e-015f,-1.0f}, -{1.95156e-018f,-1.17961e-015f,-1.0f},{3.03577e-018f,-1.17267e-015f,-1.0f},{1.73472e-018f,-1.17267e-015f,-1.0f}, -{1.30104e-018f,-1.17267e-015f,-1.0f},{8.67362e-019f,-1.17614e-015f,-1.0f},{-2.1684e-018f,-1.17267e-015f,-1.0f}, -{1.30104e-018f,-1.17614e-015f,-1.0f},{-1.51788e-018f,-1.17961e-015f,-1.0f},{8.67362e-019f,-1.16573e-015f,-1.0f}, -{1.95156e-018f,-1.17267e-015f,-1.0f},{2.1684e-018f,-1.17961e-015f,-1.0f},{1.58565e-018f,-1.16573e-015f,-1.0f}, -{-8.13705e-033f,-1.17267e-015f,-1.0f},{3.06626e-018f,-1.17267e-015f,-1.0f},{-3.46945e-018f,-1.1692e-015f,-1.0f}, -{1.84314e-018f,-1.17267e-015f,-1.0f},{3.46945e-018f,-1.17961e-015f,-1.0f},{0.0f,-1.16573e-015f,-1.0f}, -{6.93889e-018f,-1.17614e-015f,-1.0f},{-6.5289e-032f,-1.17614e-015f,-1.0f},{6.93889e-018f,-1.17267e-015f,-1.0f}, -{-6.93889e-018f,-1.17267e-015f,-1.0f},{6.47112e-032f,-1.16573e-015f,-1.0f},{-6.54816e-032f,-1.17961e-015f,-1.0f}, -{-6.93889e-018f,-1.17961e-015f,-1.0f},{6.93889e-018f,-1.17961e-015f,-1.0f},{-6.50964e-032f,-1.17267e-015f,-1.0f}, -{-6.93889e-018f,-1.16573e-015f,-1.0f},{8.67362e-019f,-1.17961e-015f,-1.0f},{-2.1684e-018f,-1.17961e-015f,-1.0f}, -{-8.67362e-019f,-1.17267e-015f,-1.0f},{-1.30104e-018f,-1.17267e-015f,-1.0f},{-0.0581517f,-0.998308f,0.0f}, -{-3.49231e-012f,-1.0f,5.38529e-027f},{1.49639e-016f,-1.0f,0.0f},{-0.230535f,-0.973064f,3.60106e-016f}, -{-0.230613f,-0.973045f,3.60099e-016f},{-0.173651f,-0.984807f,1.82226e-016f},{-0.116108f,-0.993237f,1.83786e-016f}, -{-0.173275f,-0.984873f,3.64476e-016f},{-0.11595f,-0.993255f,1.83789e-016f},{-0.396094f,-0.91821f,3.39806e-016f}, -{-0.448811f,-0.893627f,0.0f},{-0.396067f,-0.918222f,3.3981e-016f},{-0.286837f,-0.957979f,3.54524e-016f}, -{-0.342035f,-0.939687f,3.47754e-016f},{-0.286798f,-0.957991f,3.54528e-016f},{-0.597145f,-0.802133f,5.93698e-016f}, -{-0.549498f,-0.835495f,6.18391e-016f},{-0.597158f,-0.802124f,5.93691e-016f},{-0.499989f,-0.866032f,0.0f}, -{-0.448787f,-0.893639f,6.61426e-016f},{-0.500008f,-0.866021f,6.40984e-016f},{-0.72737f,-0.686246f,5.07924e-016f}, -{-0.766042f,-0.642791f,4.75761e-016f},{-0.727358f,-0.686259f,5.07933e-016f},{-0.642785f,-0.766046f,5.66988e-016f}, -{-0.686238f,-0.727377f,5.38367e-016f},{-0.642773f,-0.766057f,5.66996e-016f},{-0.866013f,-0.500021f,7.40179e-016f}, -{-0.835473f,-0.549532f,4.06735e-016f},{-0.866023f,-0.500004f,3.70077e-016f},{-0.802106f,-0.597181f,4.42003e-016f}, -{-0.802121f,-0.597162f,4.41988e-016f},{-0.835486f,-0.549512f,4.0672e-016f},{-0.939696f,-0.342012f,2.5314e-016f}, -{-0.957994f,-0.28679f,2.12267e-016f},{-0.939685f,-0.342042f,2.53162e-016f},{-0.918216f,-0.396079f,2.93157e-016f}, -{-0.918208f,-0.396098f,2.93171e-016f},{-0.893624f,-0.448817f,3.32191e-016f},{-0.993236f,-0.116116f,8.5943e-017f}, -{-0.984803f,-0.173675f,1.28545e-016f},{-0.99324f,-0.11608f,8.59167e-017f},{-0.973038f,-0.230643f,1.7071e-016f}, -{-0.957982f,-0.286828f,2.12296e-016f},{-0.973049f,-0.2306f,1.70678e-016f},{-1.0f,-1.19209e-007f,8.82326e-023f}, -{-0.998307f,0.058159f,-4.30463e-017f},{-0.998309f,0.0581378f,-4.30306e-017f},{-0.998309f,-0.0581377f,4.30305e-017f}, -{-1.0f,-2.65488e-017f,1.96501e-032f},{-0.998307f,-0.0581591f,4.30464e-017f},{-0.984803f,0.173675f,-1.28545e-016f}, -{-0.973038f,0.230643f,-1.7071e-016f},{-0.984811f,0.173633f,-1.28514e-016f},{-0.99324f,0.11608f,-8.59168e-017f}, -{-0.993236f,0.116116f,0.0f},{-0.918208f,0.396098f,0.0f},{-0.939696f,0.342012f,-5.0628e-016f}, -{-0.939685f,0.342042f,0.0f},{-0.957993f,0.28679f,0.0f},{-0.973049f,0.2306f,-1.70678e-016f}, -{-0.957982f,0.286828f,0.0f},{-0.866013f,0.500021f,-7.40179e-016f},{-0.893631f,0.448803f,0.0f}, -{-0.893624f,0.448816f,-6.64382e-016f},{-0.918216f,0.396079f,-5.86315e-016f},{-0.802121f,0.597162f,0.0f}, -{-0.835486f,0.549512f,0.0f},{-0.802106f,0.597181f,0.0f},{-0.866023f,0.500004f,0.0f}, -{-0.835473f,0.549532f,0.0f},{-0.727369f,0.686246f,0.0f},{-0.766041f,0.642791f,0.0f}, -{-0.727358f,0.686258f,0.0f},{-0.766027f,0.642808f,-9.51547e-016f},{-0.642773f,0.766057f,0.0f}, -{-0.686238f,0.727377f,0.0f},{-0.686227f,0.727388f,-1.07675e-015f},{-0.597145f,0.802133f,0.0f}, -{-0.642785f,0.766046f,0.0f},{-0.597158f,0.802124f,0.0f},{-0.549498f,0.835495f,0.0f}, -{-0.499989f,0.866032f,0.0f},{-0.549511f,0.835486f,0.0f},{-0.448787f,0.893639f,0.0f}, -{-0.500008f,0.866021f,0.0f},{-0.448811f,0.893627f,0.0f},{-0.396067f,0.918221f,0.0f}, -{-0.342011f,0.939696f,0.0f},{-0.396094f,0.91821f,0.0f},{-0.286798f,0.957991f,0.0f}, -{-0.342035f,0.939687f,0.0f},{-0.286837f,0.957979f,0.0f},{-0.230613f,0.973045f,0.0f}, -{-0.173651f,0.984807f,0.0f},{-0.230535f,0.973064f,0.0f},{-0.173275f,0.984873f,0.0f}, -{-0.116108f,0.993237f,0.0f},{-0.11595f,0.993255f,0.0f},{-0.0581642f,0.998307f,0.0f}, -{-7.72329e-017f,1.0f,0.0f},{-0.0581517f,0.998308f,0.0f},{-0.984811f,-0.173632f,1.28514e-016f}, -{-0.893631f,-0.448803f,3.32181e-016f},{-0.766027f,-0.642808f,4.75773e-016f},{-0.686227f,-0.727388f,5.38375e-016f}, -{-0.549511f,-0.835486f,6.18384e-016f},{-0.342011f,-0.939696f,3.47757e-016f},{-0.0581641f,-0.998307f,9.2362e-017f}, -{0.0f,1.17441e-015f,1.0f},{0.0f,1.17094e-015f,1.0f},{0.0f,1.17614e-015f,1.0f}, -{0.0f,1.17267e-015f,1.0f},{0.0f,1.17874e-015f,1.0f},{-6.93889e-018f,1.17094e-015f,1.0f}, -{0.0f,1.17571e-015f,1.0f},{0.0f,1.17354e-015f,1.0f},{6.51446e-032f,1.17354e-015f,1.0f}, -{6.49038e-032f,1.1692e-015f,1.0f},{0.0f,1.17788e-015f,1.0f},{-6.93889e-018f,1.17614e-015f,1.0f}, -{0.0f,1.1692e-015f,1.0f},{0.0f,1.16747e-015f,1.0f},{0.0f,1.17701e-015f,1.0f}, -{0.0f,1.17007e-015f,1.0f},{-3.46945e-018f,1.17961e-015f,1.0f},{3.46945e-018f,1.17267e-015f,1.0f}, -{6.93889e-018f,1.17267e-015f,1.0f},{-3.46945e-018f,1.17267e-015f,1.0f},{0.0f,1.17181e-015f,1.0f}, -{3.46945e-018f,1.17614e-015f,1.0f},{-3.46945e-018f,1.17614e-015f,1.0f},{0.0f,1.17116e-015f,1.0f}, -{0.0f,1.17462e-015f,1.0f},{0.0f,1.17311e-015f,1.0f},{0.0f,1.17213e-015f,1.0f}, -{0.0f,1.17332e-015f,1.0f},{0.0f,1.16834e-015f,1.0f},{0.0f,1.16912e-015f,1.0f}, -{0.0f,1.17528e-015f,1.0f},{0.0f,1.17831e-015f,1.0f},{-3.46945e-018f,1.1692e-015f,1.0f}, -{0.0f,1.17353e-015f,1.0f},{6.93889e-018f,1.17311e-015f,1.0f},{3.46945e-018f,1.1692e-015f,1.0f}, -{-3.46945e-018f,1.17353e-015f,1.0f},{-1.62741e-032f,1.17267e-015f,1.0f},{3.46945e-018f,1.17332e-015f,1.0f}, -{3.46945e-018f,1.17213e-015f,1.0f},{-3.46945e-018f,1.17831e-015f,1.0f},{-3.46945e-018f,1.17462e-015f,1.0f}, -{3.46945e-018f,1.17788e-015f,1.0f},{-3.46945e-018f,1.16747e-015f,1.0f},{-3.25482e-032f,1.17267e-015f,1.0f}, -{-3.46945e-018f,1.17571e-015f,1.0f},{3.24519e-032f,1.1692e-015f,1.0f},{-3.46945e-018f,1.17788e-015f,1.0f}, -{-1.63223e-032f,1.17614e-015f,1.0f},{-3.25964e-032f,1.17441e-015f,1.0f},{-3.46945e-018f,1.17701e-015f,1.0f}, -{-3.46945e-018f,1.17094e-015f,1.0f},{-3.46945e-018f,1.17181e-015f,1.0f},{-1.6226e-032f,1.1692e-015f,1.0f}, -{3.25482e-032f,1.17267e-015f,1.0f},{-0.0407198f,0.623367f,-0.780869f},{4.8247e-017f,0.624695f,-0.780869f}, -{-0.0408655f,0.623357f,-0.780869f},{-0.0815543f,0.619349f,-0.780869f},{-0.121867f,0.612693f,-0.780869f}, -{-0.0815307f,0.619352f,-0.780869f},{-0.200788f,0.591547f,-0.780869f},{-0.200806f,0.591541f,-0.780869f}, -{-0.239048f,0.577148f,-0.780869f},{-0.161674f,0.603411f,-0.780869f},{-0.161672f,0.603412f,-0.780869f}, -{-0.121853f,0.612696f,-0.780869f},{-0.312348f,0.541002f,-0.780869f},{-0.347061f,0.519415f,-0.780869f}, -{-0.362343f,0.508873f,-0.780869f},{-0.276303f,0.560268f,-0.780869f},{-0.469671f,0.41189f,-0.780869f}, -{-0.49103f,0.386178f,-0.780869f},{-0.452096f,0.431107f,-0.780869f},{-0.441727f,0.441726f,-0.780869f}, -{-0.409076f,0.472124f,-0.780869f},{-0.411889f,0.469671f,-0.780869f},{-0.603411f,0.161675f,-0.780869f}, -{-0.613402f,0.118247f,-0.780869f},{-0.599383f,0.176024f,-0.780869f},{-0.577143f,0.239059f,-0.780869f}, -{-0.579937f,0.232201f,-0.780869f},{-0.560271f,0.276297f,-0.780869f},{-0.624695f,-7.81403e-016f,-0.780869f}, -{-0.621866f,0.0593872f,-0.780869f},{-0.623358f,0.0408508f,-0.780869f},{-0.612694f,0.121862f,-0.780869f}, -{-0.619352f,0.0815295f,-0.780869f},{-0.619352f,-0.0815289f,-0.780869f},{-0.623278f,-0.0420472f,-0.780869f}, -{-0.619032f,-0.0839247f,-0.780869f},{-0.624695f,-7.85004e-016f,-0.780869f},{-0.603409f,-0.161685f,-0.780869f}, -{-0.602152f,-0.166305f,-0.780869f},{-0.591542f,-0.200803f,-0.780869f},{-0.611979f,-0.125401f,-0.780869f}, -{-0.612693f,-0.121866f,-0.780869f},{-0.574359f,-0.245674f,-0.780869f},{-0.55652f,-0.283777f,-0.780869f}, -{-0.560272f,-0.276296f,-0.780869f},{-0.577143f,-0.23906f,-0.780869f},{-0.589592f,-0.206458f,-0.780869f}, -{-0.541001f,-0.312349f,-0.780869f},{-0.536156f,-0.320594f,-0.780869f},{-0.519411f,-0.347068f,-0.780869f}, -{-0.495597f,-0.3803f,-0.780869f},{-0.513359f,-0.355958f,-0.780869f},{-0.460896f,-0.421686f,-0.780869f}, -{-0.469665f,-0.411897f,-0.780869f},{-0.488234f,-0.389707f,-0.780869f},{-0.400085f,-0.479767f,-0.780869f}, -{-0.411883f,-0.469676f,-0.780869f},{-0.431469f,-0.45175f,-0.780869f},{-0.441721f,-0.441731f,-0.780869f}, -{-0.366885f,-0.505608f,-0.780869f},{-0.347057f,-0.519418f,-0.780869f},{-0.380283f,-0.49561f,-0.780869f}, -{-0.276286f,-0.560277f,-0.780869f},{-0.312341f,-0.541005f,-0.780869f},{-0.312348f,-0.541002f,-0.780869f}, -{-0.332022f,-0.529155f,-0.780869f},{-0.276253f,-0.560293f,-0.780869f},{-0.295655f,-0.550302f,-0.780869f}, -{-0.257945f,-0.568954f,-0.780869f},{-0.219062f,-0.585026f,-0.780869f},{-0.239077f,-0.577136f,-0.780869f}, -{-0.17919f,-0.598444f,-0.780869f},{-0.200818f,-0.591537f,-0.780869f},{-0.161695f,-0.603406f,-0.780869f}, -{-0.138507f,-0.609147f,-0.780869f},{-0.0968651f,-0.617139f,-0.780869f},{-0.12188f,-0.61269f,-0.780869f}, -{-0.0554646f,-0.622228f,-0.780869f},{-0.0815436f,-0.61935f,-0.780869f},{-0.0408587f,-0.623357f,-0.780869f}, -{-0.0134154f,-0.624551f,-0.780869f},{-1.44741e-016f,-0.624695f,-0.780869f},{-1.32341e-016f,-0.624695f,-0.780869f}, -{-0.121874f,-0.612691f,-0.780869f},{-0.161679f,-0.60341f,-0.780869f},{-0.121867f,-0.612693f,-0.780869f}, -{-0.276294f,-0.560273f,-0.780869f},{-0.161681f,-0.60341f,-0.780869f},{-0.239058f,-0.577144f,-0.780869f}, -{-0.081532f,-0.619352f,-0.780869f},{-0.0815751f,-0.619346f,-0.780869f},{-0.0408495f,-0.623358f,-0.780869f}, -{-0.0406682f,-0.62337f,-0.780869f},{-1.34995e-016f,-0.624695f,-0.780869f},{-1.67499e-016f,-0.624695f,-0.780869f}, -{-0.20067f,-0.591587f,-0.780869f},{-0.200802f,-0.591543f,-0.780869f},{-0.23903f,-0.577156f,-0.780869f}, -{-0.591544f,0.200798f,-0.780869f},{-0.623358f,-0.0408492f,-0.780869f},{-0.525513f,0.337758f,-0.780869f}, -{-0.541f,0.31235f,-0.780869f},{-0.555239f,0.286275f,-0.780869f},{-0.519413f,0.347065f,-0.780869f}, -{-0.495602f,0.380292f,-0.780869f},{-0.441709f,0.441743f,-0.780869f},{-0.411873f,0.469686f,-0.780869f}, -{-0.409092f,0.47211f,-0.780869f},{-0.347044f,0.519427f,-0.780869f},{-0.31233f,0.541012f,-0.780869f}, -{-0.380288f,0.495606f,-0.780869f},{-0.239067f,0.57714f,-0.780869f},{-0.276284f,0.560278f,-0.780869f}, -{-0.312352f,0.540999f,-0.780869f},{5.94472e-017f,0.624695f,-0.780869f},{-0.623357f,0.040871f,-0.780869f}, -{-0.624695f,-7.73092e-016f,-0.780869f},{-0.624695f,-7.89776e-016f,-0.780869f},{-0.621867f,0.0593711f,-0.780869f}, -{-0.613408f,0.118216f,-0.780869f},{-0.619348f,0.0815572f,-0.780869f},{-0.603406f,0.161693f,-0.780869f}, -{-0.612689f,0.121886f,-0.780869f},{-0.599395f,0.175983f,-0.780869f},{-0.579951f,0.232166f,-0.780869f}, -{-0.591537f,0.200819f,-0.780869f},{-0.560263f,0.276314f,-0.780869f},{-0.577134f,0.239082f,-0.780869f}, -{-0.555257f,0.286241f,-0.780869f},{-0.525532f,0.337728f,-0.780869f},{-0.540992f,0.312365f,-0.780869f}, -{-0.519405f,0.347077f,-0.780869f},{-0.491049f,0.386154f,-0.780869f},{-0.495593f,0.380304f,-0.780869f}, -{-0.452119f,0.431082f,-0.780869f},{-0.469657f,0.411906f,-0.780869f},{-0.362366f,0.508856f,-0.780869f}, -{-0.380275f,0.495616f,-0.780869f},{0.998775f,-0.049491f,0.0f},{1.0f,1.2919e-016f,0.0f}, -{1.0f,1.37264e-016f,0.0f},{0.977407f,-0.211368f,0.0f},{0.98727f,-0.159053f,0.0f}, -{0.977365f,-0.211559f,0.0f},{0.994856f,-0.101296f,0.0f},{0.994335f,-0.106287f,0.0f}, -{0.9986f,-0.0529056f,0.0f},{0.964773f,-0.263083f,0.0f},{0.962355f,-0.271796f,0.0f}, -{0.949405f,-0.314055f,0.0f},{0.866021f,-0.500008f,0.0f},{0.861571f,-0.507638f,0.0f}, -{0.887366f,-0.461066f,0.0f},{0.921279f,-0.388903f,0.0f},{0.910645f,-0.413189f,0.0f}, -{0.931345f,-0.364138f,0.0f},{0.734799f,-0.678285f,0.0f},{0.758453f,-0.651728f,0.0f}, -{0.716553f,-0.697532f,0.0f},{0.802733f,-0.596339f,0.0f},{0.833328f,-0.552779f,0.0f}, -{0.797427f,-0.603416f,0.0f},{0.541517f,-0.84069f,0.0f},{0.530443f,-0.847721f,0.0f}, -{0.574807f,-0.818289f,0.0f},{0.609678f,-0.792649f,0.0f},{0.658536f,-0.752549f,0.0f}, -{0.288713f,-0.957416f,0.0f},{0.339268f,-0.94069f,0.0f},{0.305468f,-0.952202f,0.0f}, -{0.437338f,-0.899297f,0.0f},{0.467738f,-0.883867f,0.0f},{0.388834f,-0.921308f,0.0f}, -{0.132754f,-0.991149f,0.0f},{0.10328f,-0.994652f,0.0f},{0.0798119f,-0.99681f,0.0f}, -{0.237346f,-0.971425f,0.0f},{0.239168f,-0.970978f,0.0f},{0.185314f,-0.982679f,0.0f}, -{-0.171605f,-0.985166f,0.0f},{-0.132709f,-0.991155f,0.0f},{-0.103293f,-0.994651f,0.0f}, -{-0.0266126f,-0.999646f,0.0f},{0.0266303f,-0.999645f,0.0f},{-0.0344868f,-0.999405f,0.0f}, -{-0.339241f,-0.940699f,0.0f},{-0.388834f,-0.921308f,0.0f},{-0.388825f,-0.921312f,0.0f}, -{-0.237326f,-0.97143f,0.0f},{-0.239133f,-0.970987f,0.0f},{-0.288698f,-0.95742f,0.0f}, -{-0.467738f,-0.883867f,0.0f},{-0.484556f,-0.87476f,0.0f},{-0.437309f,-0.899311f,0.0f}, -{-0.617538f,-0.786541f,0.0f},{-0.609678f,-0.792649f,0.0f},{-0.658522f,-0.752561f,0.0f}, -{-0.541517f,-0.84069f,0.0f},{-0.574801f,-0.818293f,0.0f},{-0.53043f,-0.847729f,0.0f}, -{-0.716559f,-0.697526f,0.0f},{-0.758457f,-0.651723f,0.0f},{-0.734782f,-0.678303f,0.0f}, -{-0.697641f,-0.716448f,0.0f},{-0.797431f,-0.60341f,0.0f},{-0.833335f,-0.552769f,0.0f}, -{-0.802718f,-0.596359f,0.0f},{-0.769841f,-0.638236f,0.0f},{-0.861559f,-0.507658f,0.0f}, -{-0.833319f,-0.552792f,0.0f},{-0.866023f,-0.500004f,0.0f},{-0.89538f,-0.445304f,0.0f}, -{-0.887356f,-0.461084f,0.0f},{-0.910637f,-0.413206f,0.0f},{-0.921283f,-0.388894f,0.0f}, -{-0.931337f,-0.364157f,0.0f},{-0.943659f,-0.330919f,0.0f},{-0.949398f,-0.314075f,0.0f}, -{-0.962422f,-0.27156f,0.0f},{-0.964768f,-0.263101f,0.0f},{-0.977403f,-0.211384f,0.0f}, -{-0.977365f,-0.211559f,0.0f},{-0.987859f,-0.155356f,0.0f},{-0.987268f,-0.159066f,0.0f}, -{-0.994333f,-0.106314f,0.0f},{-0.994856f,-0.101296f,0.0f},{-0.998775f,-0.049491f,0.0f}, -{-0.998601f,-0.0528865f,0.0f},{-0.305468f,-0.952202f,0.0f},{-0.185276f,-0.982686f,0.0f}, -{-0.079772f,-0.996813f,0.0f},{0.03448f,-0.999405f,0.0f},{0.171593f,-0.985168f,0.0f}, -{0.388857f,-0.921298f,0.0f},{0.484577f,-0.874749f,0.0f},{0.617547f,-0.786534f,0.0f}, -{0.697657f,-0.716432f,0.0f},{0.769857f,-0.638216f,0.0f},{0.833333f,-0.552771f,0.0f}, -{0.895373f,-0.445318f,0.0f},{0.943631f,-0.330998f,0.0f},{0.987859f,-0.155356f,0.0f}, -{-1.0f,-3.77476e-016f,0.0f},{-0.991435f,-0.130601f,-6.19104e-019f},{-0.99153f,-0.129881f,4.88629e-016f}, -{-0.865926f,-0.500171f,-8.92478e-019f},{-0.866063f,-0.499936f,-3.17394e-017f},{-0.923984f,-0.382431f,-5.0236e-018f}, -{-0.923897f,-0.38264f,-5.01887e-018f},{-0.966265f,-0.257551f,-6.30898e-018f},{-0.965902f,-0.258907f,4.70296e-016f}, -{-0.608898f,-0.793249f,2.51569e-017f},{-0.608701f,-0.7934f,2.51781e-017f},{-0.500177f,-0.865923f,3.67732e-017f}, -{-0.793302f,-0.608828f,-3.85657e-016f},{-0.70708f,-0.707134f,-3.34256e-016f},{-0.707182f,-0.707032f,1.01847e-016f}, -{-0.130461f,-0.991453f,-9.90614e-017f},{-0.130634f,-0.991431f,7.15089e-017f},{-0.258717f,-0.965953f,-5.85053e-017f}, -{-0.258991f,-0.96588f,-1.13773e-016f},{-0.382876f,-0.9238f,2.9328e-017f},{-0.382575f,-0.923924f,1.23656e-016f}, -{0.258717f,-0.965953f,1.33133e-016f},{0.130634f,-0.991431f,1.36399e-016f},{0.258991f,-0.96588f,-1.45574e-016f}, -{4.20972e-017f,-1.0f,-4.25225e-017f},{4.54604e-017f,-1.0f,-4.25225e-017f},{0.130461f,-0.991453f,1.40227e-017f}, -{0.499909f,-0.866078f,4.49026e-016f},{0.500177f,-0.865923f,1.55049e-016f},{0.608701f,-0.7934f,7.79706e-016f}, -{0.382876f,-0.9238f,7.50444e-017f},{0.382576f,-0.923924f,3.75533e-017f},{0.70708f,-0.707134f,2.56512e-016f}, -{0.707182f,-0.707032f,2.34744e-016f},{0.793302f,-0.608828f,4.26281e-016f},{0.608898f,-0.793249f,-1.21382e-016f}, -{0.865926f,-0.500171f,4.61524e-016f},{0.793414f,-0.608682f,-9.08045e-016f},{0.866063f,-0.499936f,-1.12653e-016f}, -{0.923984f,-0.382431f,1.71788e-016f},{0.923898f,-0.38264f,-9.65732e-017f},{0.965902f,-0.258907f,1.47384e-016f}, -{0.991435f,-0.130601f,3.73071e-016f},{0.966265f,-0.257551f,2.10001e-016f},{0.99153f,-0.129881f,1.22154e-016f}, -{1.0f,4.44089e-017f,0.0f},{-0.499909f,-0.866078f,-7.00363e-017f},{-0.793414f,-0.608682f,-3.85722e-016f}, -{-1.0f,-3.55271e-016f,0.0f},{1.38778e-017f,0.0f,-1.0f},{-2.77556e-017f,0.0f,-1.0f}, -{-1.38778e-017f,0.0f,-1.0f},{-0.209488f,-0.470509f,-0.857167f},{-0.302781f,-0.416639f,-0.857167f}, -{2.0793e-011f,0.515038f,-0.857167f},{-0.107041f,-0.503792f,-0.857167f},{-8.71204e-012f,-0.515038f,-0.857167f}, -{-0.382869f,-0.344494f,-0.857167f},{-0.446205f,-0.257227f,-0.857167f},{-0.489955f,-0.158772f,-0.857167f}, -{-0.512244f,-0.0535708f,-0.857167f},{-0.512182f,0.054163f,-0.857167f},{-0.445616f,0.258245f,-0.857167f}, -{-0.489568f,0.159959f,-0.857167f},{-0.302314f,0.416978f,-0.857167f},{-0.382299f,0.345125f,-0.857167f}, -{-0.106823f,0.503838f,-0.857167f},{-0.209119f,0.470674f,-0.857167f},{-5.23815e-016f,0.515038f,-0.857167f}, -{-4.16334e-016f,-1.0f,1.18424e-015f},{-0.20783f,-0.978165f,1.30318e-015f},{-0.207408f,-0.978254f,1.12778e-015f}, -{-0.86521f,-0.50141f,5.93789e-016f},{-0.742274f,-0.670096f,7.38614e-016f},{-0.743379f,-0.66887f,6.87574e-016f}, -{-0.586974f,-0.809606f,9.58766e-016f},{-0.406026f,-0.913862f,1.01459e-015f},{-0.406743f,-0.913543f,1.08185e-015f}, -{-0.994455f,-0.105163f,9.16276e-017f},{-0.994576f,-0.104013f,8.25206e-017f},{-0.994576f,0.104013f,-1.92941e-016f}, -{-0.866353f,-0.499433f,6.65378e-016f},{-0.951298f,-0.308272f,3.87884e-016f},{-0.950548f,-0.310578f,3.92178e-016f}, -{-0.950548f,0.310578f,-2.2169e-016f},{-0.86521f,0.50141f,-5.89149e-016f},{-0.866353f,0.499433f,-4.58297e-016f}, -{-0.951298f,0.308272f,-3.65067e-016f},{-0.994455f,0.105163f,3.82381e-017f},{-0.742274f,0.670096f,-7.82968e-016f}, -{-0.586974f,0.809606f,-1.0039e-015f},{-0.587881f,0.808947f,-1.05167e-015f},{-0.743379f,0.66887f,-8.52637e-016f}, -{-0.406743f,0.913543f,-9.8396e-016f},{-0.406026f,0.913862f,-1.10276e-015f},{-0.207408f,0.978254f,-1.31418e-015f}, -{-0.20783f,0.978165f,-1.07945e-015f},{1.11022e-016f,1.0f,-1.18424e-015f},{-0.587881f,-0.808947f,1.0015e-015f}, -{0.0f,0.515038f,-0.857167f},{-8.71183e-012f,-0.515038f,-0.857167f},{-3.77792e-017f,0.515038f,-0.857167f}, -{-8.88178e-016f,-1.0f,1.03621e-015f},{-0.20783f,-0.978165f,1.18915e-015f},{-0.207408f,-0.978254f,8.68864e-016f}, -{-0.86521f,-0.50141f,6.20715e-016f},{-0.742274f,-0.670096f,5.34884e-016f},{-0.743379f,-0.66887f,7.4811e-016f}, -{-0.586974f,-0.809606f,9.2581e-016f},{-0.406026f,-0.913862f,9.46951e-016f},{-0.406743f,-0.913543f,9.4662e-016f}, -{-0.994455f,-0.105163f,2.02034e-016f},{-0.994576f,-0.104013f,3.2862e-016f},{-0.994576f,0.104013f,-8.63697e-017f}, -{-0.951298f,-0.308272f,4.83071e-016f},{-0.950548f,-0.310578f,5.78862e-016f},{-0.950548f,0.310578f,-2.74108e-016f}, -{-0.86521f,0.50141f,-4.47156e-016f},{-0.866353f,0.499433f,-5.98803e-016f},{-0.951298f,0.308272f,-2.31911e-016f}, -{-0.994455f,0.105163f,-2.45591e-018f},{-0.742274f,0.670096f,-7.15151e-016f},{-0.586974f,0.809606f,-8.90323e-016f}, -{-0.587881f,0.808947f,-9.67842e-016f},{-0.743379f,0.66887f,-8.40245e-016f},{-0.406743f,0.913543f,-1.02153e-015f}, -{-0.406026f,0.913862f,-1.22443e-015f},{-0.207408f,0.978254f,-1.05802e-015f},{-0.20783f,0.978165f,-1.06498e-015f}, -{-0.587881f,-0.808947f,9.57986e-016f},{-8.7128e-012f,-0.515038f,-0.857167f},{-6.8535e-016f,0.515038f,-0.857167f}, -{8.88178e-016f,-1.0f,1.18424e-015f},{-0.20783f,-0.978165f,1.15838e-015f},{-0.207408f,-0.978254f,1.15849e-015f}, -{-0.86521f,-0.50141f,4.286e-016f},{-0.742274f,-0.670096f,8.87405e-016f},{-0.743379f,-0.66887f,6.32553e-016f}, -{-0.586974f,-0.809606f,9.15321e-016f},{-0.406026f,-0.913862f,1.08223e-015f},{-0.994455f,-0.105163f,1.16754e-016f}, -{-0.994576f,-0.104013f,1.59983e-016f},{-0.994576f,0.104013f,-3.80152e-017f},{-0.866353f,-0.499433f,5.27324e-016f}, -{-0.951298f,-0.308272f,4.12661e-016f},{-0.950548f,-0.310578f,2.74456e-016f},{-0.950548f,0.310578f,-2.33532e-016f}, -{-0.86521f,0.50141f,-5.96335e-016f},{-0.866353f,0.499433f,-5.68061e-016f},{-0.951298f,0.308272f,-2.59452e-016f}, -{-0.994455f,0.105163f,-4.315e-017f},{-0.742274f,0.670096f,-7.2774e-016f},{-0.586974f,0.809606f,-8.55024e-016f}, -{-0.587881f,0.808947f,-1.02665e-015f},{-0.743379f,0.66887f,-8.66361e-016f},{-0.406743f,0.913543f,-1.10059e-015f}, -{-0.406026f,0.913862f,-1.082e-015f},{-0.207408f,0.978254f,-1.12807e-015f},{-0.20783f,0.978165f,-1.036e-015f}, -{-0.587881f,-0.808947f,9.14474e-016f},{-2.0793e-011f,0.515038f,-0.857167f},{-8.7129e-012f,-0.515038f,-0.857167f}, -{-1.52141e-016f,0.515038f,-0.857167f},{9.4369e-016f,-1.0f,1.18424e-015f},{-0.207408f,-0.978254f,1.18919e-015f}, -{-0.86521f,-0.50141f,6.68012e-016f},{-0.742274f,-0.670096f,6.83675e-016f},{-0.743379f,-0.66887f,7.92101e-016f}, -{-0.406743f,-0.913543f,1.27729e-015f},{-0.994455f,-0.105163f,1.98142e-016f},{-0.994576f,0.104013f,8.65335e-018f}, -{-0.866353f,-0.499433f,6.5557e-016f},{-0.951298f,-0.308272f,5.03928e-016f},{-0.950548f,-0.310578f,2.50076e-016f}, -{-0.950548f,0.310578f,-3.08937e-016f},{-0.86521f,0.50141f,-5.85418e-016f},{-0.866353f,0.499433f,-7.08567e-016f}, -{-0.951298f,0.308272f,-3.94078e-016f},{-0.994455f,0.105163f,-1.73016e-016f},{-0.742274f,0.670096f,-8.05095e-016f}, -{-0.586974f,0.809606f,-9.35358e-016f},{-0.587881f,0.808947f,-1.05156e-015f},{-0.743379f,0.66887f,-9.1452e-016f}, -{-0.406743f,0.913543f,-9.91265e-016f},{-0.406026f,0.913862f,-1.16514e-015f},{-0.207408f,0.978254f,-1.06396e-015f}, -{-0.20783f,0.978165f,-1.24775e-015f},{-2.77556e-017f,1.0f,-1.18424e-015f},{-0.587881f,-0.808947f,8.70962e-016f}, -{0.130601f,-0.991435f,5.91127e-019f},{0.504792f,-0.863241f,-2.02127e-017f},{0.386527f,-0.922278f,-4.5688e-016f}, -{0.500171f,-0.865926f,3.75867e-016f},{0.260319f,-0.965523f,4.84382e-016f},{0.258907f,-0.965902f,2.3813e-017f}, -{0.382431f,-0.923984f,-2.11599e-018f},{0.7934f,-0.608701f,-1.21624e-016f},{0.866078f,-0.499909f,1.59434e-016f}, -{0.799182f,-0.60109f,3.0223e-017f},{0.707134f,-0.70708f,1.81955e-016f},{0.712942f,-0.701223f,8.71811e-018f}, -{0.61424f,-0.78912f,-8.47292e-018f},{0.993331f,-0.115297f,-1.28837e-016f},{0.969421f,-0.245402f,2.2597e-016f}, -{0.991453f,-0.130461f,-2.87378e-016f},{0.928562f,-0.371177f,-2.17091e-016f},{0.923924f,-0.382575f,5.85909e-017f}, -{0.965953f,-0.258717f,4.84292e-017f},{0.988912f,0.1485f,-2.16513e-016f},{0.96588f,0.258991f,-9.27243e-017f}, -{0.960687f,0.277634f,-5.52567e-018f},{1.0f,1.50355e-016f,2.5559e-017f},{0.991431f,0.130634f,-3.04207e-017f}, -{0.999859f,0.0167995f,-1.01552e-016f},{0.865923f,0.500177f,3.07191e-017f},{0.793249f,0.608898f,-1.58893e-016f}, -{0.854627f,0.519243f,-3.82786e-017f},{0.9238f,0.382876f,-4.32254e-016f},{0.915665f,0.401942f,3.20545e-017f}, -{0.707032f,0.707182f,1.84414e-016f},{0.608682f,0.793414f,-2.94158e-016f},{0.6891f,0.724667f,4.12928e-016f}, -{0.778651f,0.627457f,2.23169e-016f},{0.587492f,0.80923f,-2.92371e-016f},{0.499936f,0.866063f,-2.28218e-016f}, -{0.38264f,0.923898f,-1.88485e-016f},{0.475687f,0.879615f,-4.6342e-016f},{0.257551f,0.966265f,1.03607e-016f}, -{0.354917f,0.934898f,2.24615e-016f},{0.228996f,0.973427f,1.38774e-016f},{0.129881f,0.99153f,1.04307e-015f}, -{-4.21885e-016f,1.0f,0.0f},{0.0984243f,0.995145f,-1.69533e-016f},{-3.55271e-016f,1.0f,0.0f}, -{0.87148f,-0.490431f,1.62194e-016f},{0.608828f,-0.793302f,-4.00663e-016f},{0.131224f,-0.991353f,6.10153e-019f}, -{-0.99153f,-0.129881f,-4.91015e-016f},{-0.991435f,-0.130601f,-1.80136e-018f},{-0.865926f,-0.500171f,9.3755e-018f}, -{-0.923984f,-0.382431f,-7.91631e-019f},{-0.866063f,-0.499936f,-2.14221e-017f},{-0.923897f,-0.38264f,-2.44199e-017f}, -{-0.965902f,-0.258907f,-6.02945e-018f},{-0.966265f,-0.257551f,-4.82672e-016f},{-0.608898f,-0.793249f,1.18364e-016f}, -{-0.500177f,-0.865923f,-3.15104e-016f},{-0.608701f,-0.7934f,1.1825e-016f},{-0.793302f,-0.608828f,4.1567e-016f}, -{-0.707182f,-0.707032f,-3.42282e-019f},{-0.70708f,-0.707134f,-1.74822e-016f},{-0.130461f,-0.991453f,-1.03638e-016f}, -{-0.258717f,-0.965953f,-2.02191e-016f},{-0.130634f,-0.991431f,-2.74129e-016f},{-0.258991f,-0.96588f,-8.2881e-017f}, -{-0.382575f,-0.923924f,-2.01887e-016f},{-0.382876f,-0.9238f,-2.21359e-016f},{0.258717f,-0.965953f,-1.28219e-016f}, -{0.258991f,-0.96588f,1.82327e-016f},{0.130634f,-0.991431f,-7.95915e-017f},{6.27272e-017f,-1.0f,-9.36404e-017f}, -{0.130461f,-0.991453f,4.92989e-017f},{6.65124e-017f,-1.0f,-9.36404e-017f},{0.499909f,-0.866078f,-4.39633e-017f}, -{0.608701f,-0.7934f,3.80682e-016f},{0.500177f,-0.865923f,-2.43429e-016f},{0.382876f,-0.9238f,3.63034e-016f}, -{0.382576f,-0.923924f,1.36738e-016f},{0.70708f,-0.707134f,-2.86707e-016f},{0.793302f,-0.608828f,-4.30606e-016f}, -{0.707182f,-0.707032f,-2.64966e-016f},{0.608898f,-0.793249f,1.17848e-016f},{0.865926f,-0.500171f,-4.80949e-016f}, -{0.793414f,-0.608682f,8.84924e-016f},{0.866063f,-0.499936f,1.39452e-016f},{0.923984f,-0.382431f,-2.16909e-016f}, -{0.965902f,-0.258907f,-1.76024e-016f},{0.923898f,-0.38264f,7.5049e-017f},{0.991435f,-0.130601f,-3.76626e-016f}, -{0.966265f,-0.257551f,7.3088e-016f},{0.99153f,-0.129881f,-1.25711e-016f},{-0.499909f,-0.866078f,3.84467e-017f}, -{-0.793414f,-0.608682f,4.15754e-016f},{6.93889e-018f,0.0f,1.0f},{1.21431e-017f,0.0f,1.0f}, -{1.04083e-017f,0.0f,1.0f},{-1.38778e-017f,0.0f,1.0f},{-6.93889e-018f,0.0f,1.0f}, -{-1.04083e-017f,0.0f,1.0f},{1.73472e-018f,0.0f,1.0f},{-7.15573e-018f,0.0f,1.0f}, -{1.38778e-017f,0.0f,1.0f},{7.77156e-018f,0.0f,1.0f},{8.67362e-019f,0.0f,1.0f}, -{-8.67362e-018f,0.0f,1.0f},{9.97466e-018f,0.0f,1.0f},{3.46945e-018f,0.0f,1.0f}, -{-3.46945e-018f,0.0f,1.0f},{2.77556e-017f,0.0f,1.0f},{-0.130601f,0.991435f,1.77338e-018f}, -{-0.129881f,0.99153f,4.90961e-016f},{-0.500171f,0.865926f,3.08732e-017f},{-0.499936f,0.866063f,-5.81242e-020f}, -{-0.382431f,0.923984f,-6.34795e-018f},{-0.38264f,0.923897f,-6.29986e-018f},{-0.257551f,0.966265f,7.30839e-018f}, -{-0.258907f,0.965902f,4.8417e-016f},{-0.793249f,0.608898f,-1.1018e-016f},{-0.7934f,0.608701f,-1.10088e-016f}, -{-0.865923f,0.500177f,5.07923e-017f},{-0.608828f,0.793302f,-4.19108e-016f},{-0.707134f,0.70708f,-2.39145e-016f}, -{-0.707032f,0.707182f,2.2457e-017f},{-0.991453f,0.130461f,-2.76358e-016f},{-0.991431f,0.130634f,-1.05855e-016f}, -{-0.965953f,0.258717f,-1.6536e-016f},{-0.96588f,0.258991f,1.75599e-017f},{-0.9238f,0.382876f,-1.3075e-017f}, -{-0.923924f,0.382575f,8.1385e-017f},{-0.965953f,-0.258717f,2.15452e-016f},{-0.991431f,-0.130634f,1.78952e-016f}, -{-0.96588f,-0.258991f,-6.31777e-017f},{-1.0f,-2.40099e-017f,-4.66812e-017f},{-1.0f,-2.36302e-017f,-4.66812e-017f}, -{-0.991453f,-0.130461f,1.78822e-016f},{-0.866078f,-0.499909f,4.22895e-016f},{-0.865923f,-0.500177f,-8.46537e-017f}, -{-0.7934f,-0.608701f,8.26127e-016f},{-0.9238f,-0.382876f,1.31423e-016f},{-0.923924f,-0.382576f,9.38593e-017f}, -{-0.707134f,-0.70708f,2.26071e-016f},{-0.707032f,-0.707182f,2.04322e-016f},{-0.608828f,-0.793302f,3.53949e-016f}, -{-0.793249f,-0.608898f,-7.49318e-017f},{-0.500171f,-0.865926f,4.69837e-016f},{-0.608682f,-0.793414f,-8.86489e-016f}, -{-0.499936f,-0.866063f,-1.50588e-016f},{-0.382431f,-0.923984f,1.81164e-016f},{-0.38264f,-0.923898f,-8.71966e-017f}, -{-0.258907f,-0.965902f,1.58845e-016f},{-0.130601f,-0.991435f,3.72533e-016f},{-0.257551f,-0.966265f,2.2141e-016f}, -{-0.129881f,-0.99153f,1.21619e-016f},{4.44089e-017f,-1.0f,0.0f},{-0.866078f,0.499909f,1.57789e-016f}, -{-0.608682f,0.793414f,-4.19223e-016f},{-1.04083e-017f,0.0f,-1.0f},{6.93889e-018f,0.0f,-1.0f}, -{4.33681e-019f,0.0f,-1.0f},{1.07336e-017f,0.0f,-1.0f},{-6.93889e-018f,0.0f,-1.0f}, -{-6.50521e-018f,0.0f,-1.0f},{3.68629e-018f,0.0f,-1.0f},{4.07082e-018f,0.0f,-1.0f}, -{1.04083e-017f,0.0f,-1.0f},{0.444478f,-0.89579f,0.0f},{0.418355f,-0.908284f,0.0f}, -{0.133376f,-0.991066f,0.0f},{0.198953f,-0.980009f,0.0f},{0.145378f,-0.989376f,0.0f}, -{0.331391f,-0.943493f,0.0f},{0.263225f,-0.964735f,0.0f},{0.325799f,-0.945439f,0.0f}, -{-0.133376f,-0.991066f,0.0f},{-0.145378f,-0.989376f,0.0f},{-0.198953f,-0.980009f,0.0f}, -{0.0486891f,-0.998814f,0.0f},{-0.0486892f,-0.998814f,0.0f},{-6.76475e-016f,-1.0f,0.0f}, -{-0.325799f,-0.945439f,0.0f},{-0.331391f,-0.943493f,0.0f},{-0.386322f,-0.922364f,0.0f}, -{-0.263225f,-0.964735f,0.0f},{-0.24003f,-0.970766f,0.0f},{-0.444478f,-0.89579f,0.0f}, -{-0.418355f,-0.908283f,0.0f},{-0.0669122f,-0.997759f,0.0f},{0.0669122f,-0.997759f,0.0f}, -{0.24003f,-0.970766f,0.0f},{0.386322f,-0.922364f,0.0f},{-0.866025f,-0.5f,2.22045e-016f}, -{0.418355f,0.908283f,1.34453e-014f},{0.444478f,0.89579f,0.0f},{0.133376f,0.991066f,-3.66768e-015f}, -{0.198953f,0.980009f,-2.17606e-014f},{0.145378f,0.989376f,-1.12533e-014f},{0.263225f,0.964735f,-1.42809e-014f}, -{0.325799f,0.945439f,-9.40905e-015f},{0.331391f,0.943493f,6.98325e-015f},{-0.133376f,0.991066f,-5.62492e-015f}, -{-0.145378f,0.989376f,6.811e-015f},{-0.198953f,0.980009f,7.43077e-015f},{0.0486892f,0.998814f,-1.75808e-015f}, -{-0.0486891f,0.998814f,1.80313e-015f},{-3.75252e-016f,1.0f,-3.47178e-031f},{-0.325799f,0.945439f,-1.5311e-015f}, -{-0.331391f,0.943493f,-1.06169e-014f},{-0.386322f,0.922364f,-5.1396e-015f},{-0.263225f,0.964735f,1.93732e-015f}, -{-0.444478f,0.89579f,-3.54644e-016f},{-0.418355f,0.908284f,8.06481e-016f},{-0.24003f,0.970766f,-1.54398e-014f}, -{0.24003f,0.970766f,7.18511e-015f},{-0.0669122f,0.997759f,-3.81626e-015f},{0.0669122f,0.997759f,-2.47625e-016f}, -{0.386322f,0.922364f,-3.96751e-015f},{0.866025f,-0.5f,-2.29443e-016f},{0.0f,3.46945e-018f,-1.0f}, -{0.0f,-6.93889e-018f,-1.0f},{0.0f,6.93889e-018f,-1.0f},{0.0f,1.38778e-017f,-1.0f}, -{0.577419f,0.816448f,0.0f},{0.784136f,0.620589f,0.0f},{0.720693f,0.693254f,0.0f}, -{0.651394f,0.75874f,0.0f},{0.889343f,0.457241f,0.0f},{0.929514f,0.368787f,0.0f}, -{0.840654f,0.541573f,0.0f},{0.960722f,0.277511f,0.0f},{0.982785f,0.184754f,0.0f}, -{0.995774f,0.0918355f,0.0f},{1.0f,-6.52539e-016f,0.0f},{1.0f,-8.70052e-016f,0.0f}, -{-1.0f,6.03291e-016f,0.0f},{-0.995774f,-0.0918355f,1.81234e-017f},{-0.929514f,-0.368787f,-6.50222e-015f}, -{-0.960722f,-0.277511f,-1.39324e-014f},{-0.982785f,-0.184754f,2.2208e-017f},{-0.784136f,-0.620589f,4.14066e-015f}, -{-0.840654f,-0.541573f,4.26223e-015f},{-0.889343f,-0.457241f,7.28708e-015f},{-0.651394f,-0.75874f,8.81315e-015f}, -{-0.720693f,-0.693254f,-3.17985e-015f},{-0.577419f,-0.816448f,1.49179e-015f},{-1.0f,5.36259e-016f,0.0f}, -{1.83187e-015f,1.0f,0.0f},{1.83187e-015f,1.0f,8.62817e-032f},{0.0f,5.20417e-018f,-1.0f}, -{0.0f,-8.67362e-019f,-1.0f},{0.0f,-3.46945e-018f,-1.0f},{0.0f,-1.73472e-018f,-1.0f}, -{0.0f,-5.20417e-018f,-1.0f},{-0.995774f,0.0918355f,0.0f},{-1.0f,2.90017e-016f,0.0f}, -{-1.0f,3.99573e-013f,0.0f},{-0.929514f,0.368787f,0.0f},{-0.960722f,0.277511f,0.0f}, -{-0.982785f,0.184754f,0.0f},{-0.840654f,0.541573f,0.0f},{-0.784136f,0.620589f,0.0f}, -{-0.889343f,0.457241f,0.0f},{-0.720693f,0.693255f,0.0f},{-0.651394f,0.75874f,0.0f}, -{-0.577419f,0.816448f,0.0f},{1.33227e-015f,1.0f,-1.97215e-031f},{1.33227e-015f,1.0f,-1.04999e-032f}, -{0.577419f,-0.816448f,0.0f},{0.784136f,-0.620589f,2.05619e-015f},{0.720693f,-0.693255f,-2.6671e-015f}, -{0.651394f,-0.75874f,7.94521e-016f},{0.929514f,-0.368787f,3.27627e-015f},{0.889343f,-0.457241f,2.56146e-015f}, -{0.840654f,-0.541573f,8.97402e-016f},{0.982785f,-0.184754f,-5.16503e-015f},{0.960722f,-0.277511f,1.0602e-014f}, -{0.995774f,-0.0918355f,1.43378e-014f},{1.0f,-3.35162e-017f,0.0f},{0.0f,-1.38778e-017f,-1.0f}, -{-0.995188f,-0.0979889f,0.0f},{-1.0f,-3.99915e-013f,0.0f},{-0.923925f,-0.382573f,0.0f}, -{-0.956966f,-0.290201f,0.0f},{-0.923909f,-0.382613f,0.0f},{-0.956961f,-0.290216f,0.0f}, -{-0.980794f,-0.195045f,0.0f},{-0.980794f,-0.195048f,0.0f},{-0.773048f,-0.634347f,0.0f}, -{-0.707144f,-0.70707f,0.0f},{-0.773125f,-0.634253f,0.0f},{-0.831507f,-0.555514f,0.0f}, -{-0.83156f,-0.555435f,0.0f},{-0.881988f,-0.471271f,0.0f},{-0.471474f,-0.88188f,0.0f}, -{-0.555711f,-0.831376f,0.0f},{-0.471468f,-0.881883f,0.0f},{-0.634547f,-0.772884f,0.0f}, -{-0.634433f,-0.772978f,0.0f},{-0.555621f,-0.831435f,0.0f},{-0.194999f,-0.980803f,0.0f}, -{-0.0979559f,-0.995191f,0.0f},{-0.195278f,-0.980748f,0.0f},{-0.290209f,-0.956963f,0.0f}, -{-0.290455f,-0.956889f,0.0f},{-0.382806f,-0.923829f,0.0f},{0.195278f,-0.980748f,0.0f}, -{0.0979559f,-0.995191f,0.0f},{0.0981573f,-0.995171f,0.0f},{-5.55112e-017f,-1.0f,0.0f}, -{-0.0981573f,-0.995171f,0.0f},{-5.20417e-017f,-1.0f,0.0f},{0.382668f,-0.923886f,0.0f}, -{0.290209f,-0.956963f,0.0f},{0.382807f,-0.923829f,0.0f},{0.194999f,-0.980803f,0.0f}, -{0.290455f,-0.956889f,0.0f},{0.555621f,-0.831435f,0.0f},{0.555711f,-0.831376f,0.0f}, -{0.634547f,-0.772884f,0.0f},{0.471474f,-0.88188f,0.0f},{0.471468f,-0.881883f,0.0f}, -{0.707144f,-0.70707f,0.0f},{0.707246f,-0.706968f,0.0f},{0.773125f,-0.634253f,0.0f}, -{0.634433f,-0.772978f,0.0f},{0.83156f,-0.555435f,0.0f},{0.773048f,-0.634347f,0.0f}, -{0.881988f,-0.471271f,0.0f},{0.831507f,-0.555514f,0.0f},{0.881956f,-0.471332f,0.0f}, -{0.923925f,-0.382573f,0.0f},{0.956966f,-0.290201f,0.0f},{0.923909f,-0.382613f,0.0f}, -{0.980794f,-0.195045f,0.0f},{0.956961f,-0.290216f,0.0f},{0.980794f,-0.195048f,0.0f}, -{0.995188f,-0.0979878f,0.0f},{0.995188f,-0.0979889f,0.0f},{-0.382668f,-0.923886f,0.0f}, -{-0.707246f,-0.706968f,0.0f},{-0.881956f,-0.471332f,0.0f},{-0.995188f,-0.0979878f,0.0f}, -{-0.984809f,-0.173642f,0.0f},{-1.0f,1.57282e-016f,0.0f},{-0.765765f,-0.64312f,0.0f}, -{-0.766272f,-0.642516f,0.0f},{-0.865946f,-0.500137f,0.0f},{-0.939669f,-0.342084f,0.0f}, -{-0.866231f,-0.499643f,0.0f},{-0.939879f,-0.341507f,0.0f},{-0.341751f,-0.939791f,0.0f}, -{-0.173343f,-0.984861f,0.0f},{-0.342031f,-0.939689f,0.0f},{-0.642133f,-0.766593f,0.0f}, -{-0.499517f,-0.866304f,0.0f},{-0.50031f,-0.865846f,0.0f},{0.342031f,-0.939689f,0.0f}, -{0.173343f,-0.984861f,0.0f},{0.173688f,-0.984801f,0.0f},{-3.70074e-017f,-1.0f,0.0f}, -{-3.23815e-017f,-1.0f,0.0f},{0.64411f,-0.764933f,0.0f},{0.642133f,-0.766593f,0.0f}, -{0.50031f,-0.865846f,0.0f},{0.499517f,-0.866304f,0.0f},{0.766272f,-0.642516f,0.0f}, -{0.865946f,-0.500137f,0.0f},{0.765765f,-0.64312f,0.0f},{0.866231f,-0.499643f,0.0f}, -{0.939669f,-0.342084f,0.0f},{0.984809f,-0.173642f,0.0f},{0.939879f,-0.341507f,0.0f}, -{0.984871f,-0.173291f,0.0f},{0.341751f,-0.939791f,0.0f},{-0.173688f,-0.984801f,0.0f}, -{-0.64411f,-0.764933f,0.0f},{-0.984871f,-0.173291f,0.0f},{2.08167e-017f,0.0f,-1.0f}, -{2.34188e-017f,0.0f,-1.0f},{-2.08167e-017f,0.0f,-1.0f},{-8.67362e-018f,0.0f,-1.0f}, -{1.0842e-017f,0.0f,-1.0f},{2.77556e-017f,0.0f,-1.0f},{0.991152f,0.132731f,1.7726e-016f}, -{0.964765f,0.263112f,-1.21714e-017f},{0.964793f,0.263012f,1.90689e-016f},{0.99116f,0.132673f,1.95676e-016f}, -{1.0f,1.97655e-016f,1.82867e-032f},{0.921309f,0.388832f,-3.40953e-016f},{0.921362f,0.388705f,-1.79812e-017f}, -{0.861557f,0.507661f,-3.1884e-016f},{0.786578f,0.617491f,0.0f},{0.786661f,0.617385f,0.0f}, -{0.861635f,0.507528f,3.65825e-016f},{0.697798f,0.716295f,-2.58237e-016f},{0.697683f,0.716407f,0.0f}, -{0.596508f,0.802607f,0.0f},{0.596433f,0.802663f,2.92927e-016f},{0.484069f,0.87503f,-8.09565e-017f}, -{0.484772f,0.874641f,8.09205e-017f},{0.363152f,0.93173f,-2.68786e-016f},{0.364466f,0.931217f,0.0f}, -{0.237459f,0.971397f,-1.79745e-016f},{0.23745f,0.9714f,0.0f},{0.106383f,0.994325f,0.0f}, -{0.99116f,-0.132673f,-6.13738e-018f},{0.991152f,-0.132731f,0.0f},{0.964765f,-0.263112f,1.82571e-017f}, -{0.964793f,-0.263012f,-2.55617e-016f},{0.921309f,-0.388832f,3.31959e-016f},{0.921362f,-0.388705f,-4.08234e-016f}, -{0.861635f,-0.507528f,-2.55532e-016f},{0.861557f,-0.507661f,1.6992e-016f},{0.786578f,-0.617491f,1.74792e-016f}, -{0.786661f,-0.617385f,3.63904e-016f},{0.697683f,-0.716407f,-9.89883e-017f},{0.697798f,-0.716295f,-4.85478e-016f}, -{0.596508f,-0.802607f,1.06491e-016f},{0.596433f,-0.802663f,-1.43821e-016f},{0.484069f,-0.87503f,8.44299e-017f}, -{0.484771f,-0.874641f,2.17811e-016f},{0.363151f,-0.93173f,-1.71313e-016f},{0.364466f,-0.931217f,3.52312e-017f}, -{0.237459f,-0.971397f,2.12946e-016f},{0.23745f,-0.9714f,-2.36429e-016f},{0.106383f,-0.994325f,0.0f}, -{0.211559f,-0.977365f,0.0f},{0.211559f,0.977365f,0.0f},{0.0f,1.11022e-016f,1.0f}, -{1.0f,-3.60822e-016f,0.0f},{0.988818f,-0.149126f,-3.65936e-016f},{0.988846f,-0.148938f,0.0f}, -{0.826061f,-0.563581f,2.57135e-016f},{0.82663f,-0.562746f,1.52957e-016f},{0.900794f,-0.434246f,-2.47032e-016f}, -{0.901683f,-0.432397f,2.46854e-016f},{0.955572f,-0.294759f,-1.22275e-016f},{0.955502f,-0.294984f,5.4583e-017f}, -{0.499989f,-0.866031f,2.99023e-016f},{0.499834f,-0.866121f,1.94153e-016f},{0.365379f,-0.930859f,0.0f}, -{0.623256f,-0.782018f,-1.74079e-016f},{0.623488f,-0.781833f,-2.60037e-016f},{-0.074795f,-0.997199f,-8.53395e-017f}, -{-0.0746326f,-0.997211f,-1.24581e-016f},{0.0746326f,-0.997211f,1.77616e-016f},{0.074795f,-0.997199f,-2.90618e-016f}, -{0.222585f,-0.974913f,1.10791e-016f},{0.222381f,-0.97496f,-1.80404e-016f},{-0.499833f,-0.866122f,-3.08968e-016f}, -{-0.365177f,-0.930938f,2.3519e-016f},{-0.365379f,-0.930859f,-6.59594e-016f},{-0.222381f,-0.97496f,3.7743e-016f}, -{-0.222585f,-0.974913f,3.77471e-016f},{-0.732917f,-0.680318f,5.87241e-017f},{-0.623488f,-0.781833f,1.35626e-016f}, -{-0.733034f,-0.680192f,-1.83291e-016f},{-0.49999f,-0.866031f,7.951e-017f},{-0.623256f,-0.782018f,7.67051e-017f}, -{-0.82663f,-0.562746f,1.92502e-016f},{-0.826061f,-0.563581f,-1.66735e-016f},{-0.901683f,-0.432397f,-1.42043e-016f}, -{-0.900794f,-0.434246f,-2.48163e-016f},{-0.955502f,-0.294984f,9.93362e-017f},{-0.955572f,-0.294759f,2.96611e-017f}, -{-0.988846f,-0.148938f,-6.23501e-017f},{-0.988818f,-0.149126f,4.18655e-017f},{-1.0f,2.77556e-017f,0.0f}, -{0.365177f,-0.930938f,6.75713e-017f},{0.733034f,-0.680192f,1.35639e-016f},{1.11022e-016f,0.0f,1.0f}, -{2.22045e-016f,0.0f,1.0f},{-1.11022e-016f,0.0f,1.0f},{-2.22045e-016f,0.0f,1.0f}, -{0.978165f,-0.20783f,-8.09482e-019f},{0.978254f,-0.207408f,-8.06289e-019f},{0.50141f,-0.86521f,-7.86e-017f}, -{0.670096f,-0.742274f,1.47663e-017f},{0.66887f,-0.743379f,1.38533e-016f},{0.809606f,-0.586974f,2.23009e-019f}, -{0.913862f,-0.406026f,-1.6746e-016f},{0.913543f,-0.406743f,-1.67403e-016f},{0.105163f,-0.994455f,9.95328e-018f}, -{0.104013f,-0.994576f,6.55702e-017f},{-0.104013f,-0.994576f,3.02706e-017f},{0.499433f,-0.866353f,-3.2041e-017f}, -{0.308272f,-0.951298f,8.49254e-017f},{0.310578f,-0.950548f,-4.50449e-017f},{-0.310578f,-0.950548f,4.10929e-017f}, -{-0.50141f,-0.86521f,6.38835e-017f},{-0.499433f,-0.866353f,-5.80911e-017f},{-0.308272f,-0.951298f,1.12332e-016f}, -{-0.105163f,-0.994455f,-7.34256e-018f},{-0.670096f,-0.742274f,-2.88671e-017f},{-0.809606f,-0.586974f,1.0557e-016f}, -{-0.808947f,-0.587881f,-2.02787e-016f},{-0.66887f,-0.743379f,-8.46456e-017f},{-0.913543f,-0.406743f,-2.46108e-016f}, -{-0.913862f,-0.406026f,1.48066e-016f},{-0.978254f,-0.207408f,-1.1019e-016f},{-0.978165f,-0.20783f,2.68975e-016f}, -{-1.0f,-4.44089e-016f,0.0f},{0.808947f,-0.587881f,-3.12756e-016f},{0.0f,-2.22045e-016f,1.0f}, -{0.0f,4.44089e-016f,1.0f},{0.0f,-4.44089e-016f,1.0f},{0.0f,2.22045e-016f,1.0f}, -{0.0f,1.66533e-016f,1.0f},{0.0f,6.245e-017f,1.0f},{0.0f,-1.11022e-016f,1.0f}, -{0.0f,-3.1225e-017f,1.0f},{0.0f,-1.94289e-016f,1.0f},{0.0f,1.38778e-016f,1.0f}, -{0.0f,6.93889e-017f,1.0f},{0.380627f,0.924729f,-2.41539e-016f},{0.254521f,0.967067f,-1.78943e-016f}, -{0.254621f,0.967041f,-1.31824e-016f},{0.380681f,0.924706f,-3.4221e-016f},{0.5f,0.866025f,8.01234e-017f}, -{0.123916f,0.992293f,-4.58581e-017f},{0.124053f,0.992276f,2.06562e-016f},{-0.00886925f,0.999961f,0.0f}, -{-0.141474f,0.989942f,0.0f},{-0.141341f,0.989961f,3.66359e-016f},{-0.00871489f,0.999962f,1.61258e-018f}, -{-0.271431f,0.962458f,0.0f},{-0.271585f,0.962414f,0.0f},{-0.396824f,0.917895f,-3.39689e-016f}, -{-0.39691f,0.917858f,0.0f},{-0.515764f,0.856731f,-5.07925e-016f},{-0.515075f,0.857145f,3.17207e-016f}, -{-0.625326f,0.780364f,-2.88792e-016f},{-0.624225f,0.781245f,5.81092e-017f},{-0.722525f,0.691345f,-2.67388e-016f}, -{-0.722532f,0.691337f,5.11692e-016f},{-0.807919f,0.589293f,0.0f},{0.610478f,0.792033f,3.83186e-016f}, -{0.610525f,0.791997f,-2.59519e-016f},{0.710244f,0.703955f,7.17582e-016f},{0.710171f,0.704029f,-1.32545e-016f}, -{0.797393f,0.603461f,4.68602e-017f},{0.797309f,0.603571f,-1.40638e-016f},{0.87035f,0.492434f,-6.88718e-018f}, -{0.870426f,0.492299f,-2.01326e-016f},{0.928052f,0.372451f,4.36423e-017f},{0.928002f,0.372576f,-6.42341e-017f}, -{0.969268f,0.246008f,-7.27758e-017f},{0.969228f,0.246163f,-1.13338e-016f},{0.993332f,0.115288f,-1.39459e-017f}, -{0.993343f,0.115195f,7.5086e-017f},{0.999833f,-0.0182988f,-4.93539e-017f},{0.999847f,-0.017496f,-2.2592e-017f}, -{0.988478f,-0.151367f,6.80819e-017f},{0.98869f,-0.149972f,-2.29484e-016f},{0.959985f,-0.280053f,-4.92036e-018f}, -{0.959982f,-0.280063f,-1.73501e-017f},{0.914302f,-0.405032f,0.0f},{0.952202f,-0.305468f,0.0f}, -{-0.740644f,0.671898f,0.0f},{0.623556f,0.781778f,3.18161e-016f},{0.623408f,0.781897f,-5.76768e-017f}, -{0.901106f,0.4336f,1.21917e-016f},{0.900667f,0.43451f,1.19137e-016f},{0.826465f,0.562987f,3.82317e-017f}, -{0.825308f,0.564682f,0.0f},{0.733055f,0.68017f,3.39106e-017f},{0.733215f,0.679997f,-1.83813e-016f}, -{1.0f,-1.21766e-005f,-2.31274e-017f},{1.0f,-0.000192142f,6.946e-017f},{0.988837f,-0.149002f,1.05584e-016f}, -{0.955631f,0.294565f,9.87124e-017f},{0.988875f,0.148747f,-2.75237e-017f},{0.988831f,0.14904f,-7.33206e-017f}, -{0.826202f,-0.563374f,-1.79826e-016f},{0.826294f,-0.563239f,-7.55524e-017f},{0.900926f,-0.433972f,1.86017e-016f}, -{0.900997f,-0.433825f,-4.16795e-017f},{0.955592f,-0.294693f,-3.9043e-017f},{0.955531f,-0.294892f,-1.37788e-016f}, -{0.500166f,-0.865929f,2.67563e-018f},{0.623628f,-0.781722f,1.95335e-016f},{0.623458f,-0.781857f,-1.87816e-016f}, -{0.733149f,-0.680068f,-2.40741e-016f},{0.733007f,-0.680221f,1.4282e-016f},{0.222715f,-0.974884f,6.76696e-018f}, -{0.365343f,-0.930873f,-1.59166e-016f},{0.222546f,-0.974922f,8.82681e-017f},{0.50001f,-0.866019f,-4.87352e-017f}, -{0.365619f,-0.930764f,4.34431e-017f},{0.0740373f,-0.997256f,-5.34897e-016f},{0.0750446f,-0.99718f,1.55626e-017f}, -{-0.0763749f,-0.997079f,-2.39932e-016f},{-0.0743287f,-0.997234f,1.17298e-016f},{-0.222287f,-0.974981f,5.54047e-016f}, -{-0.222517f,-0.974929f,-4.69812e-016f},{-0.365439f,-0.930835f,2.29949e-016f},{-0.365262f,-0.930905f,-1.2259e-016f}, -{0.988805f,-0.149216f,0.0f},{0.95558f,0.294731f,0.0f},{-1.66533e-016f,0.0f,1.0f}, -{8.32667e-017f,0.0f,1.0f},{-1.38778e-016f,0.0f,1.0f},{-1.14492e-016f,0.0f,1.0f}, -{5.55112e-017f,0.0f,1.0f},{1.79544e-016f,0.0f,1.0f},{-6.50521e-017f,0.0f,1.0f}, -{-8.32667e-017f,0.0f,1.0f},{1.31839e-016f,0.0f,1.0f},{0.669069f,0.7432f,7.56184e-017f}, -{0.668748f,0.743489f,-1.99445e-016f},{0.999999f,0.00162868f,-1.50684e-019f},{0.977876f,0.209183f,0.0f}, -{0.97822f,0.207569f,1.9204e-017f},{0.913137f,0.407652f,-1.59913e-016f},{0.80856f,0.588414f,0.0f}, -{0.809021f,0.58778f,0.0f},{0.913805f,-0.406154f,3.28816e-017f},{0.913335f,-0.40721f,7.53489e-017f}, -{0.809321f,-0.587366f,2.10733e-016f},{1.0f,-0.000654662f,-4.60776e-017f},{0.978488f,-0.206306f,-7.63485e-017f}, -{0.66791f,-0.744242f,7.23873e-017f},{0.498589f,-0.866839f,-2.11766e-016f},{0.500567f,-0.865698f,2.02889e-016f}, -{0.669713f,-0.74262f,1.25295e-016f},{0.808642f,-0.588301f,5.44288e-017f},{0.30778f,-0.951458f,-1.03566e-016f}, -{0.103531f,-0.994626f,-3.39094e-016f},{0.104646f,-0.99451f,-1.43466e-016f},{0.30935f,-0.950948f,-2.09359e-017f}, -{-0.104522f,-0.994523f,6.2347e-017f},{-0.105302f,-0.99444f,-2.24253e-016f},{-0.309506f,-0.950897f,-2.31848e-016f}, -{-0.309096f,-0.951031f,1.16375e-016f},{0.0f,-2.08167e-016f,1.0f},{0.0f,-6.6116e-017f,1.0f}, -{0.0f,-2.15106e-016f,1.0f},{0.0f,-1.66533e-016f,1.0f},{0.0f,-1.00614e-016f,1.0f}, -{0.0f,4.33681e-017f,1.0f},{0.0f,7.56773e-017f,1.0f},{0.0f,1.30104e-018f,1.0f}, -{0.0f,4.16334e-017f,1.0f},{-0.610525f,0.791997f,-2.36613e-016f},{-0.710244f,0.703955f,3.90774e-016f}, -{-0.710171f,0.704029f,-1.1366e-018f},{-0.610478f,0.792033f,-3.15997e-016f},{-0.5f,0.866025f,5.73259e-016f}, -{-0.797393f,0.603461f,5.20424e-016f},{-0.797309f,0.603571f,-7.37659e-017f},{-0.870426f,0.492299f,2.11262e-017f}, -{-0.928052f,0.372451f,-3.61531e-016f},{-0.928002f,0.372576f,3.09595e-016f},{-0.87035f,0.492434f,1.01714e-016f}, -{-0.969228f,0.246163f,-1.79343e-016f},{-0.969268f,0.246008f,0.0f},{-0.993332f,0.115288f,-2.26469e-016f}, -{-0.993343f,0.115195f,-2.26436e-016f},{-0.999833f,-0.0182988f,0.0f},{-0.999847f,-0.017496f,0.0f}, -{-0.988478f,-0.151367f,0.0f},{-0.98869f,-0.149972f,-2.93946e-016f},{-0.959985f,-0.280053f,0.0f}, -{-0.959982f,-0.280063f,-2.07288e-016f},{-0.914302f,-0.405032f,0.0f},{-0.380681f,0.924706f,4.10153e-016f}, -{-0.380627f,0.924729f,1.00679e-016f},{-0.254521f,0.967067f,1.8483e-016f},{-0.254621f,0.967041f,7.06716e-017f}, -{-0.123916f,0.992293f,2.86613e-017f},{-0.124053f,0.992276f,1.20497e-016f},{0.00871499f,0.999962f,2.77948e-016f}, -{0.00886925f,0.999961f,-3.2052e-016f},{0.141474f,0.989942f,1.92975e-016f},{0.141341f,0.989961f,4.7266e-016f}, -{0.271585f,0.962414f,-2.20758e-016f},{0.271431f,0.962458f,1.54073e-017f},{0.396824f,0.917895f,2.78137e-017f}, -{0.39691f,0.917858f,1.25083e-016f},{0.515764f,0.856731f,1.21216e-016f},{0.515076f,0.857145f,-1.12882e-016f}, -{0.625326f,0.780363f,3.65282e-016f},{0.624225f,0.781245f,6.22071e-016f},{0.722525f,0.691345f,-8.52362e-016f}, -{0.722532f,0.691337f,-2.70972e-016f},{0.807919f,0.589293f,0.0f},{0.740644f,0.671898f,0.0f}, -{-0.952202f,-0.305468f,0.0f},{-0.365262f,0.930905f,0.0f},{0.0750445f,0.99718f,-9.22577e-017f}, -{-0.0763749f,0.997079f,-7.81162e-017f},{-0.222517f,0.974929f,-9.0199e-017f},{-0.222287f,0.974981f,0.0f}, -{0.500011f,0.866019f,-3.57684e-016f},{0.500166f,0.865929f,-5.24921e-017f},{0.623458f,0.781857f,-3.03062e-016f}, -{0.222715f,0.974884f,-8.2421e-017f},{0.365619f,0.930764f,-1.1071e-016f},{0.365343f,0.930873f,-4.30615e-017f}, -{0.900997f,0.433825f,1.76752e-016f},{0.900926f,0.433972f,1.30891e-017f},{0.826294f,0.563239f,0.0f}, -{0.826202f,0.563374f,5.21225e-017f},{0.733007f,0.680221f,9.92833e-017f},{0.733149f,0.680068f,-1.7203e-016f}, -{1.0f,0.000192253f,2.31296e-016f},{0.988805f,0.149217f,1.37224e-016f},{0.988837f,0.149001f,-7.84832e-017f}, -{0.955531f,0.294892f,2.07369e-016f},{0.955592f,0.294693f,-1.03241e-017f},{0.955631f,-0.294565f,-1.87008e-016f}, -{0.988831f,-0.14904f,-4.18312e-017f},{0.95558f,-0.294731f,-2.50979e-016f},{1.0f,1.20654e-005f,1.85036e-016f}, -{0.988875f,-0.148747f,4.43526e-016f},{0.900667f,-0.43451f,-2.40435e-016f},{0.901106f,-0.4336f,-3.36518e-017f}, -{0.825308f,-0.564682f,-5.29981e-017f},{0.826465f,-0.562987f,-2.07468e-016f},{0.733215f,-0.679997f,1.78805e-016f}, -{0.733055f,-0.68017f,5.50139e-018f},{0.623408f,-0.781897f,1.42876e-016f},{0.623556f,-0.781778f,7.87981e-017f}, -{0.623627f,0.781722f,1.15394e-016f},{0.222546f,0.974922f,4.11793e-017f},{-5.55112e-017f,0.0f,1.0f}, -{1.02349e-016f,0.0f,1.0f},{-4.85723e-017f,0.0f,1.0f},{4.85723e-017f,0.0f,1.0f}, -{-9.71445e-017f,0.0f,1.0f},{-7.22079e-017f,0.0f,1.0f},{-8.23994e-017f,0.0f,1.0f}, -{-6.93889e-017f,0.0f,1.0f},{-0.309096f,0.951031f,-2.85971e-017f},{-0.309506f,0.950897f,-2.86351e-017f}, -{0.498589f,0.866839f,2.17532e-016f},{0.30778f,0.951458f,0.0f},{0.30935f,0.950948f,-1.16601e-016f}, -{0.103531f,0.994626f,-9.57856e-018f},{-0.105302f,0.99444f,0.0f},{-0.104522f,0.994523f,9.6702e-018f}, -{0.808642f,0.588301f,1.46265e-016f},{0.809321f,0.587366f,-1.69037e-017f},{0.500567f,0.865698f,2.99122e-016f}, -{0.669713f,0.74262f,5.52155e-017f},{0.66791f,0.744242f,-2.06569e-016f},{0.978488f,0.206306f,-4.52641e-017f}, -{0.999999f,-0.00162857f,1.61907e-016f},{1.0f,0.000654662f,5.80361e-017f},{0.977984f,0.208678f,9.65329e-018f}, -{0.913805f,0.406154f,4.2272e-017f},{0.977876f,-0.209184f,5.66326e-017f},{0.913137f,-0.407652f,-9.05162e-018f}, -{0.913594f,-0.406629f,-7.7272e-017f},{0.97822f,-0.207569f,-1.86995e-016f},{0.809021f,-0.58778f,-8.44062e-017f}, -{0.80856f,-0.588414f,-1.30045e-016f},{0.668748f,-0.743489f,2.63395e-016f},{0.669069f,-0.7432f,3.8159e-017f}, -{0.104646f,0.99451f,0.0f},{0.0f,-6.245e-017f,1.0f},{0.0f,3.05311e-016f,1.0f}, -{0.0f,-2.498e-016f,1.0f},{0.0f,3.33067e-016f,1.0f},{0.0f,-5.89806e-017f,1.0f}, -{0.0f,8.32667e-017f,1.0f},{0.0f,-9.71445e-017f,1.0f},{0.0f,9.02056e-017f,1.0f}, -{0.0f,7.84962e-017f,1.0f},{0.0f,-7.98865e-017f,1.0f},{0.0f,-6.50521e-018f,1.0f}, -{0.0f,6.07153e-017f,1.0f},{0.0f,7.63278e-017f,1.0f},{0.0f,1.04083e-016f,1.0f}, -{0.0f,-8.32667e-017f,1.0f},{-0.991152f,-0.132731f,0.0f},{-0.964765f,-0.263112f,1.90689e-016f}, -{-0.964793f,-0.263012f,-3.44878e-016f},{-0.99116f,-0.132673f,-1.83401e-016f},{-1.0f,1.18593e-015f,-3.70074e-016f}, -{-1.0f,1.0871e-015f,-3.70074e-016f},{-0.921309f,-0.388832f,3.76927e-016f},{-0.921362f,-0.388705f,-6.81945e-016f}, -{-0.861557f,-0.507661f,-4.69681e-017f},{-0.786578f,-0.617491f,2.91092e-016f},{-0.786661f,-0.617385f,5.25126e-016f}, -{-0.861635f,-0.507528f,4.69558e-017f},{-0.697798f,-0.716295f,-1.91966e-016f},{-0.697683f,-0.716407f,-3.24475e-016f}, -{-0.596508f,-0.802607f,0.0f},{-0.596433f,-0.802663f,-7.42612e-017f},{-0.484069f,-0.87503f,-8.09565e-017f}, -{-0.484772f,-0.874641f,8.09205e-017f},{-0.363152f,-0.93173f,0.0f},{-0.364466f,-0.931217f,1.7231e-016f}, -{-0.237459f,-0.971397f,0.0f},{-0.23745f,-0.9714f,-3.99709e-018f},{-0.106383f,-0.994325f,0.0f}, -{-0.99116f,0.132673f,6.13738e-018f},{-0.991152f,0.132731f,7.336e-016f},{-0.964765f,0.263112f,-1.84603e-016f}, -{-0.964793f,0.263012f,-1.07511e-016f},{-0.921309f,0.388832f,3.22966e-016f},{-0.921362f,0.388705f,3.99244e-016f}, -{-0.861635f,0.507528f,-1.40598e-016f},{-0.861557f,0.507661f,-2.16888e-016f},{-0.786578f,0.617491f,-1.02699e-016f}, -{-0.786661f,0.617385f,-3.86014e-016f},{-0.697683f,0.716407f,1.92347e-016f},{-0.697798f,0.716295f,3.33219e-016f}, -{-0.596508f,0.802607f,1.9824e-016f},{-0.596433f,0.802663f,4.53374e-016f},{-0.484069f,0.87503f,-1.87889e-016f}, -{-0.484771f,0.874641f,3.75811e-016f},{-0.363151f,0.93173f,1.53169e-016f},{-0.364466f,0.931217f,3.45313e-016f}, -{-0.237459f,0.971397f,7.34234e-017f},{-0.23745f,0.9714f,-2.07432e-017f},{-0.106383f,0.994325f,0.0f}, -{-0.211559f,0.977365f,0.0f},{-0.211559f,-0.977365f,0.0f},{-0.988818f,0.149126f,-2.10562e-016f}, -{-0.988846f,0.148938f,-1.82973e-016f},{-0.826061f,0.563581f,-4.09987e-016f},{-0.82663f,0.562746f,9.76567e-017f}, -{-0.900794f,0.434246f,-1.6668e-016f},{-0.901683f,0.432397f,2.46854e-016f},{-0.955572f,0.294759f,-2.85899e-016f}, -{-0.955502f,0.294984f,1.76803e-016f},{-0.499989f,0.866031f,4.62583e-017f},{-0.499834f,0.866121f,-3.32885e-016f}, -{-0.365379f,0.930859f,-3.41265e-016f},{-0.732917f,0.680318f,-9.73263e-018f},{-0.623256f,0.782018f,7.23512e-017f}, -{-0.623488f,0.781833f,1.44668e-016f},{0.074795f,0.997199f,-3.92098e-017f},{0.0746326f,0.997211f,2.62972e-016f}, -{-0.0746326f,0.997211f,-3.29817e-016f},{-0.074795f,0.997199f,3.22899e-017f},{-0.222585f,0.974913f,-2.70593e-016f}, -{-0.222381f,0.97496f,-3.32329e-016f},{0.499833f,0.866122f,3.99162e-016f},{0.365177f,0.930938f,-1.96765e-016f}, -{0.365379f,0.930859f,1.22944e-016f},{0.222381f,0.97496f,1.00489e-016f},{0.222585f,0.974913f,-2.00988e-016f}, -{0.732917f,0.680318f,-2.14863e-016f},{0.623488f,0.781833f,-1.75456e-016f},{0.733034f,0.680192f,2.66388e-016f}, -{0.49999f,0.866031f,-2.0031e-017f},{0.623256f,0.782018f,9.73741e-017f},{0.82663f,0.562746f,-2.18645e-016f}, -{0.826061f,0.563581f,1.09908e-016f},{0.901683f,0.432397f,4.54617e-017f},{0.900794f,0.434246f,2.11672e-017f}, -{0.955502f,0.294984f,5.1766e-017f},{0.955572f,0.294759f,1.0035e-016f},{0.988846f,0.148938f,-1.13814e-016f}, -{0.988818f,0.149126f,4.48123e-017f},{1.0f,-1.41553e-015f,0.0f},{-0.365177f,0.930938f,1.01357e-016f}, -{-0.733034f,0.680192f,-1.35639e-016f},{-2.77556e-017f,0.0f,1.0f},{-1.04083e-016f,0.0f,1.0f}, -{6.41848e-017f,0.0f,1.0f},{5.09575e-017f,0.0f,1.0f},{4.16334e-017f,0.0f,1.0f}, -{6.93889e-017f,0.0f,1.0f},{-1.0f,5.27356e-016f,0.0f},{-0.978165f,0.20783f,-1.81712e-016f}, -{-0.978254f,0.207408f,-7.34724e-019f},{-0.50141f,0.86521f,5.85773e-017f},{-0.670096f,0.742274f,1.03122e-017f}, -{-0.66887f,0.743379f,1.68759e-016f},{-0.809606f,0.586974f,1.43405e-016f},{-0.913862f,0.406026f,-1.65029e-016f}, -{-0.913543f,0.406743f,4.15074e-018f},{-0.105163f,0.994455f,2.55483e-017f},{-0.104013f,0.994576f,2.55461e-017f}, -{0.104013f,0.994576f,1.39018e-017f},{-0.499433f,0.866353f,5.88395e-017f},{-0.308272f,0.951298f,8.42303e-017f}, -{-0.310578f,0.950548f,-2.26885e-018f},{0.310578f,0.950548f,8.17184e-017f},{0.50141f,0.86521f,3.88522e-017f}, -{0.499433f,0.866353f,-1.92414e-017f},{0.308272f,0.951298f,1.58688e-017f},{0.105163f,0.994455f,-2.22445e-017f}, -{0.670096f,0.742274f,1.34233e-016f},{0.809606f,0.586974f,2.91734e-016f},{0.808947f,0.587881f,-2.32496e-016f}, -{0.66887f,0.743379f,-2.76854e-016f},{0.913543f,0.406743f,-3.89617e-017f},{0.913862f,0.406026f,1.84203e-017f}, -{0.978254f,0.207408f,-4.74736e-018f},{0.978165f,0.20783f,5.52614e-017f},{-0.808947f,0.587881f,-1.55945e-016f}, -{-1.0f,6.66134e-016f,0.0f},{0.0f,4.64039e-017f,1.0f},{-0.380627f,-0.924729f,1.71109e-016f}, -{-0.254521f,-0.967067f,-5.83926e-016f},{-0.254621f,-0.967041f,-4.71144e-017f},{-0.380681f,-0.924706f,-3.02246e-017f}, -{-0.5f,-0.866025f,-4.62593e-017f},{-0.123916f,-0.992293f,2.0654e-016f},{-0.124053f,-0.992276f,-2.06562e-016f}, -{0.00886925f,-0.999961f,-3.28228e-018f},{0.141474f,-0.989942f,-5.23559e-017f},{0.141341f,-0.989961f,3.66359e-016f}, -{0.00871489f,-0.999962f,3.68448e-016f},{0.271431f,-0.962458f,-3.56181e-016f},{0.271585f,-0.962414f,3.56165e-016f}, -{0.396824f,-0.917895f,0.0f},{0.39691f,-0.917858f,1.46886e-016f},{0.515764f,-0.856731f,-3.17054e-016f}, -{0.515075f,-0.857145f,-3.17207e-016f},{0.625326f,-0.780364f,0.0f},{0.624225f,-0.781245f,5.81092e-017f}, -{0.722525f,-0.691345f,0.0f},{0.722532f,-0.691337f,5.11692e-016f},{0.807919f,-0.589293f,0.0f}, -{-0.610478f,-0.792033f,5.52628e-016f},{-0.610525f,-0.791997f,-1.67896e-017f},{-0.710244f,-0.703955f,1.32004e-016f}, -{-0.710171f,-0.704029f,6.45675e-017f},{-0.797393f,-0.603461f,-1.76465e-016f},{-0.797309f,-0.603571f,3.34015e-016f}, -{-0.87035f,-0.492434f,-1.7694e-016f},{-0.870426f,-0.492299f,-1.13867e-016f},{-0.928052f,-0.372451f,-7.32957e-017f}, -{-0.928002f,-0.372576f,1.63892e-016f},{-0.969268f,-0.246008f,3.96598e-017f},{-0.969228f,-0.246163f,-1.20102e-016f}, -{-0.993332f,-0.115288f,2.08517e-016f},{-0.993343f,-0.115195f,-6.69385e-017f},{-0.999833f,0.0182988f,-8.64086e-017f}, -{-0.999847f,0.017496f,-7.9525e-017f},{-0.988478f,0.151367f,1.19056e-016f},{-0.98869f,0.149972f,-1.73927e-016f}, -{-0.959985f,0.280053f,-5.6139e-017f},{-0.959982f,0.280063f,-6.67141e-017f},{-0.914302f,0.405032f,0.0f}, -{-0.952202f,0.305468f,2.11431e-016f},{-0.952202f,0.305468f,1.05716e-016f},{0.740644f,-0.671898f,0.0f}, -{-0.623556f,-0.781778f,2.89316e-016f},{-0.900667f,-0.43451f,2.05393e-016f},{-0.826465f,-0.562987f,0.0f}, -{-0.825308f,-0.564682f,-1.32618e-016f},{-0.733055f,-0.68017f,0.0f},{-1.0f,1.21766e-005f,-6.93822e-017f}, -{-1.0f,0.000192142f,1.15648e-016f},{-0.988837f,0.149002f,1.41928e-016f},{-0.988875f,-0.148747f,1.64758e-016f}, -{-0.988831f,-0.14904f,1.46641e-016f},{-0.826202f,0.563374f,-1.42465e-016f},{-0.826294f,0.563239f,-2.46664e-016f}, -{-0.900926f,0.433972f,-1.44341e-016f},{-0.900997f,0.433825f,-1.8293e-016f},{-0.955592f,0.294693f,2.21025e-017f}, -{-0.955531f,0.294892f,-8.84043e-017f},{-0.500166f,0.865929f,8.54658e-017f},{-0.623628f,0.781722f,1.15799e-016f}, -{-0.623458f,0.781857f,-9.38496e-017f},{-0.733149f,0.680068f,-2.82023e-016f},{-0.733007f,0.680221f,2.48139e-016f}, -{-0.222715f,0.974884f,2.24527e-016f},{-0.365343f,0.930873f,-4.86352e-016f},{-0.222546f,0.974922f,-2.35147e-016f}, -{-0.50001f,0.866019f,-4.57607e-016f},{-0.365619f,0.930764f,-7.09272e-017f},{-0.0740373f,0.997256f,-8.24722e-016f}, -{-0.0750446f,0.99718f,1.54166e-016f},{0.0763749f,0.997079f,-4.98902e-017f},{0.0743287f,0.997234f,5.83357e-016f}, -{0.222287f,0.974981f,9.80286e-017f},{0.222517f,0.974929f,1.42064e-016f},{0.365439f,0.930835f,5.09861e-016f}, -{0.365262f,0.930905f,1.5733e-016f},{-0.988805f,0.149216f,-1.19093e-016f},{1.66533e-016f,0.0f,1.0f}, -{-0.669069f,-0.7432f,-6.19013e-017f},{-0.668748f,-0.743489f,1.37573e-016f},{-0.999999f,-0.00162868f,4.62592e-017f}, -{-0.977876f,-0.209183f,-3.87067e-017f},{-0.97822f,-0.207569f,3.8408e-017f},{-0.913137f,-0.407652f,-8.44822e-017f}, -{-0.80856f,-0.588414f,-7.48068e-017f},{-0.809021f,-0.58778f,1.83611e-016f},{-0.913805f,0.406154f,1.1273e-016f}, -{-0.913335f,0.40721f,1.17599e-016f},{-0.809321f,0.587366f,9.17809e-017f},{-1.0f,0.000654662f,4.63199e-017f}, -{-0.977984f,0.208678f,-4.52409e-017f},{-0.978488f,0.206306f,0.0f},{-0.66791f,0.744242f,2.59976e-016f}, -{-0.498589f,0.866839f,3.03496e-016f},{-0.500567f,0.865698f,-2.80802e-016f},{-0.669713f,0.74262f,-4.64706e-017f}, -{-0.808642f,0.588301f,-6.29396e-017f},{-0.30778f,0.951458f,-1.52132e-017f},{-0.103531f,0.994626f,-7.81241e-017f}, -{-0.104646f,0.99451f,-2.59082e-016f},{-0.30935f,0.950948f,-3.73917e-016f},{0.104522f,0.994523f,1.24387e-016f}, -{0.105302f,0.99444f,-4.17065e-017f},{0.309506f,0.950897f,1.46431e-016f},{0.309096f,0.951031f,1.48399e-016f}, -{-0.913594f,-0.406629f,8.45244e-017f},{0.610525f,-0.791997f,-1.1297e-016f},{0.710244f,-0.703955f,2.60516e-016f}, -{0.710171f,-0.704029f,3.2511e-016f},{0.610478f,-0.792033f,4.06072e-016f},{0.5f,-0.866025f,2.29636e-016f}, -{0.797393f,-0.603461f,7.37737e-017f},{0.797309f,-0.603571f,7.37659e-017f},{0.870426f,-0.492299f,-2.62718e-016f}, -{0.928052f,-0.372451f,-5.19725e-017f},{0.928002f,-0.372576f,-8.58574e-017f},{0.87035f,-0.492434f,2.03427e-016f}, -{0.969228f,-0.246163f,2.70442e-016f},{0.969268f,-0.246008f,9.10412e-017f},{0.993332f,-0.115288f,-4.26652e-017f}, -{0.993343f,-0.115195f,0.0f},{0.999833f,0.0182988f,-1.35438e-017f},{0.999847f,0.017496f,1.97958e-016f}, -{0.988478f,0.151367f,0.0f},{0.98869f,0.149972f,-2.93946e-016f},{0.959985f,0.280053f,0.0f}, -{0.959982f,0.280063f,-2.07288e-016f},{0.914302f,0.405032f,0.0f},{0.380681f,-0.924706f,-1.76101e-017f}, -{0.380627f,-0.924729f,-1.38377e-016f},{0.254521f,-0.967067f,-1.76609e-017f},{0.254621f,-0.967041f,5.8393e-016f}, -{0.123916f,-0.992293f,1.06136e-016f},{0.124053f,-0.992276f,3.32784e-016f},{-0.00871499f,-0.999962f,-1.40587e-016f}, -{-0.00886925f,-0.999961f,-2.79596e-016f},{-0.141474f,-0.989942f,-3.33647e-016f},{-0.141341f,-0.989961f,2.25705e-016f}, -{-0.271585f,-0.962414f,-4.06693e-016f},{-0.271431f,-0.962458f,-1.92792e-016f},{-0.396824f,-0.917895f,2.45566e-016f}, -{-0.39691f,-0.917858f,3.42831e-016f},{-0.515764f,-0.856731f,3.68103e-016f},{-0.515076f,-0.857145f,-2.27015e-016f}, -{-0.625326f,-0.780363f,1.50692e-016f},{-0.624225f,-0.781245f,7.84799e-016f},{-0.722525f,-0.691345f,-6.59161e-016f}, -{-0.722532f,-0.691337f,-3.47879e-016f},{-0.807919f,-0.589293f,0.0f},{-0.740644f,-0.671898f,0.0f}, -{0.952202f,0.305468f,0.0f},{0.365262f,-0.930905f,0.0f},{-0.0750445f,-0.99718f,0.0f}, -{-0.0740373f,-0.997255f,-9.22647e-017f},{0.0743287f,-0.997234f,-1.37536e-017f},{0.0763749f,-0.997079f,9.22484e-017f}, -{0.222517f,-0.974929f,0.0f},{-0.500166f,-0.865929f,4.00573e-017f},{-0.623458f,-0.781857f,0.0f}, -{-0.222715f,-0.974884f,-4.12105e-017f},{-0.365619f,-0.930764f,-8.6113e-017f},{-0.365343f,-0.930873f,-2.45868e-016f}, -{-0.900997f,-0.433825f,1.89872e-016f},{-0.900926f,-0.433972f,-2.26931e-016f},{-0.826294f,-0.563239f,6.342e-017f}, -{-0.826202f,-0.563374f,-1.025e-016f},{-0.733007f,-0.680221f,2.34917e-016f},{-0.733149f,-0.680068f,4.38439e-016f}, -{-1.0f,-0.000192253f,-1.61925e-016f},{-0.988805f,-0.149217f,-6.57636e-016f},{-0.988837f,-0.149001f,-2.20099e-016f}, -{-0.955531f,-0.294892f,2.17468e-016f},{-0.955592f,-0.294693f,4.48866e-016f},{-0.955631f,0.294565f,-2.04833e-016f}, -{-0.988831f,0.14904f,5.69462e-017f},{-0.95558f,0.294731f,2.37133e-016f},{-1.0f,-1.20654e-005f,1.85036e-016f}, -{-0.988875f,0.148747f,-7.37777e-017f},{-0.900667f,0.43451f,9.83788e-017f},{-0.901106f,0.4336f,-8.21154e-017f}, -{-0.825308f,0.564682f,-4.24488e-017f},{-0.826465f,0.562987f,-1.95228e-016f},{-0.733215f,0.679997f,9.80932e-017f}, -{-0.733055f,0.68017f,-2.6778e-016f},{-0.623408f,0.781897f,7.95767e-017f},{-0.623556f,0.781778f,-2.53269e-016f}, -{-0.623627f,-0.781722f,2.30789e-016f},{-0.222546f,-0.974922f,9.01984e-017f},{0.309096f,-0.951031f,1.47379e-016f}, -{0.309506f,-0.950897f,1.75951e-016f},{-0.498589f,-0.866839f,5.71343e-017f},{-0.30778f,-0.951458f,5.69507e-017f}, -{-0.30935f,-0.950948f,0.0f},{-0.103531f,-0.994626f,1.74464e-016f},{0.105302f,-0.99444f,-1.84008e-016f}, -{0.104522f,-0.994523f,0.0f},{-0.808642f,-0.588301f,5.77928e-017f},{-0.809321f,-0.587366f,-2.0535e-017f}, -{-0.913335f,-0.40721f,-2.79887e-017f},{-0.500567f,-0.865698f,1.3703e-016f},{-0.669713f,-0.74262f,1.37412e-016f}, -{-0.66791f,-0.744242f,-9.97533e-017f},{-0.978488f,-0.206306f,8.45297e-017f},{-0.999999f,0.00162857f,6.92005e-017f}, -{-1.0f,-0.000654662f,-8.10446e-017f},{-0.977984f,-0.208678f,-1.83989e-016f},{-0.913805f,-0.406154f,1.59697e-016f}, -{-0.977876f,0.209184f,-1.85957e-017f},{-0.913137f,0.407652f,6.751e-017f},{-0.913594f,0.406629f,-1.81309e-016f}, -{-0.97822f,0.207569f,1.21186e-016f},{-0.809021f,0.58778f,4.45898e-017f},{-0.80856f,0.588414f,-1.89321e-016f}, -{-0.668748f,0.743489f,-2.18469e-016f},{-0.669069f,0.7432f,-4.4842e-017f},{-0.104646f,-0.99451f,-1.93703e-016f}, -{0.99153f,-0.129881f,0.0f},{1.0f,9.4369e-017f,0.0f},{0.991435f,-0.130601f,0.0f}, -{0.866063f,-0.499936f,0.0f},{0.923898f,-0.38264f,0.0f},{0.865926f,-0.500171f,0.0f}, -{0.965902f,-0.258907f,0.0f},{0.966265f,-0.257551f,0.0f},{0.608701f,-0.7934f,0.0f}, -{0.499909f,-0.866078f,0.0f},{0.608898f,-0.793249f,0.0f},{0.70708f,-0.707134f,0.0f}, -{0.707182f,-0.707032f,0.0f},{0.793414f,-0.608682f,0.0f},{0.130634f,-0.991431f,0.0f}, -{0.258991f,-0.96588f,0.0f},{0.130461f,-0.991453f,0.0f},{0.382876f,-0.9238f,0.0f}, -{0.382576f,-0.923924f,0.0f},{0.258717f,-0.965953f,0.0f},{-0.130461f,-0.991453f,0.0f}, -{-0.258991f,-0.96588f,0.0f},{-0.258717f,-0.965953f,0.0f},{-0.130634f,-0.991431f,0.0f}, -{-0.500177f,-0.865923f,0.0f},{-0.608898f,-0.793249f,0.0f},{-0.499909f,-0.866078f,0.0f}, -{-0.382576f,-0.923924f,0.0f},{-0.382876f,-0.9238f,0.0f},{-0.707182f,-0.707032f,0.0f}, -{-0.793414f,-0.608682f,0.0f},{-0.70708f,-0.707133f,0.0f},{-0.608701f,-0.7934f,0.0f}, -{-0.793302f,-0.608828f,0.0f},{-0.866063f,-0.499935f,0.0f},{-0.923898f,-0.38264f,0.0f}, -{-0.865926f,-0.500171f,0.0f},{-0.923984f,-0.382431f,0.0f},{-0.965902f,-0.258907f,0.0f}, -{-0.991435f,-0.130601f,0.0f},{-0.966265f,-0.257551f,0.0f},{-0.99153f,-0.129881f,0.0f}, -{0.500177f,-0.865923f,0.0f},{0.793302f,-0.608828f,0.0f},{0.923984f,-0.382431f,0.0f}, -{0.984809f,-0.173642f,0.0f},{1.0f,1.57282e-016f,0.0f},{0.765765f,-0.64312f,0.0f}, -{0.766272f,-0.642516f,0.0f},{0.865946f,-0.500137f,0.0f},{0.939669f,-0.342084f,0.0f}, -{0.866231f,-0.499643f,0.0f},{0.939879f,-0.341507f,0.0f},{0.341751f,-0.939791f,0.0f}, -{0.173343f,-0.984861f,0.0f},{0.342031f,-0.939689f,0.0f},{0.642133f,-0.766593f,0.0f}, -{0.499517f,-0.866304f,0.0f},{0.50031f,-0.865846f,0.0f},{-0.342031f,-0.939689f,0.0f}, -{-0.173343f,-0.984861f,0.0f},{-0.173688f,-0.984801f,0.0f},{3.70074e-017f,-1.0f,0.0f}, -{3.23815e-017f,-1.0f,0.0f},{-0.642133f,-0.766593f,0.0f},{-0.50031f,-0.865846f,0.0f}, -{-0.499517f,-0.866304f,0.0f},{-0.766272f,-0.642516f,0.0f},{-0.865946f,-0.500137f,0.0f}, -{-0.765765f,-0.64312f,0.0f},{-0.866231f,-0.499643f,0.0f},{-0.939669f,-0.342084f,0.0f}, -{-0.984809f,-0.173642f,0.0f},{-0.939879f,-0.341507f,0.0f},{-0.984871f,-0.173291f,0.0f}, -{-0.341751f,-0.939791f,0.0f},{0.173688f,-0.984801f,0.0f},{0.984871f,-0.173291f,0.0f}, -{0.152121f,0.988362f,0.0f},{1.20609e-016f,1.0f,0.0f},{-0.134181f,0.990957f,0.0f}, -{0.424076f,0.905627f,0.0f},{0.307814f,0.951446f,0.0f},{0.587751f,0.809042f,0.0f}, -{0.66247f,0.749088f,0.0f},{0.950842f,0.309676f,0.0f},{0.807656f,0.589654f,0.0f}, -{0.846384f,0.532573f,0.0f},{0.961226f,0.275761f,0.0f},{-0.309304f,0.950963f,0.0f}, -{-0.409073f,0.912502f,0.0f},{-0.588229f,0.808694f,0.0f},{-0.811958f,0.583716f,0.0f}, -{-0.6509f,0.759164f,0.0f},{-0.952103f,0.305779f,0.0f},{-0.84017f,0.542323f,0.0f}, -{-0.962625f,0.270837f,0.0f},{-1.0f,-1.18424e-015f,0.0f},{-1.0f,1.11022e-015f,0.0f}, -{0.317028f,0.948416f,0.0f},{0.594315f,0.804232f,0.0f},{0.812715f,0.582662f,0.0f}, -{0.952238f,0.305357f,0.0f},{0.00550409f,0.999985f,0.0f},{-5.5717e-017f,1.0f,0.0f}, -{-0.306183f,0.951973f,0.0f},{-0.584702f,0.811248f,0.0f},{-0.80785f,0.589388f,0.0f}, -{-0.954037f,0.299688f,0.0f},{-1.0f,-5.92119e-016f,0.0f},{-1.0f,-6.66134e-016f,0.0f}, -{3.70074e-017f,1.0f,3.42388e-034f},{-0.307814f,0.951446f,5.69571e-018f},{4.16334e-017f,1.0f,3.85186e-034f}, -{0.587751f,0.809042f,2.78932e-017f},{0.309304f,0.950963f,3.37619e-017f},{0.588229f,0.808694f,1.0203e-017f}, -{0.307814f,0.951446f,-2.84786e-018f},{0.807656f,0.589654f,7.32347e-018f},{0.952103f,0.305779f,-2.03109e-017f}, -{0.950842f,0.309676f,-7.83488e-018f},{0.811958f,0.583716f,-2.06583e-017f},{1.0f,-1.66533e-016f,0.0f}, -{-0.587751f,0.809042f,-1.49703e-017f},{-0.588229f,0.808694f,-1.08844e-017f},{-0.811958f,0.583716f,-3.00485e-017f}, -{-0.807656f,0.589654f,-1.09108e-017f},{-0.952103f,0.305779f,0.0f},{-0.950842f,0.309676f,0.0f}, -{-1.0f,-6.93889e-017f,0.0f},{0.568191f,0.822897f,0.0f},{0.353989f,0.935249f,0.0f}, -{0.354494f,0.935058f,0.0f},{0.120012f,0.992772f,0.0f},{0.567703f,0.823234f,0.0f}, -{0.120619f,0.992699f,0.0f},{0.748241f,0.663427f,0.0f},{0.748664f,0.662949f,0.0f}, -{0.885281f,0.465056f,0.0f},{-0.12025f,0.992744f,0.0f},{0.885683f,0.46429f,0.0f}, -{0.970894f,0.239511f,0.0f},{0.971f,0.239079f,0.0f},{-0.12127f,0.99262f,0.0f}, -{-0.35609f,0.934452f,0.0f},{-0.354397f,0.935095f,0.0f},{-0.567931f,0.823076f,0.0f}, -{-0.569129f,0.822248f,0.0f},{-0.74925f,0.662288f,0.0f},{-0.748191f,0.663484f,0.0f}, -{-0.885933f,0.463813f,0.0f},{-0.885106f,0.465389f,0.0f},{-0.970869f,0.23961f,0.0f}, -{-0.971139f,0.238516f,0.0f},{-1.0f,1.45407e-013f,0.0f},{-1.0f,2.2119e-011f,0.0f}, -{0.0806869f,-0.224573f,-0.971111f},{0.115976f,-0.167824f,-0.978971f},{0.0936942f,-0.206583f,-0.973933f}, -{0.212777f,0.00431306f,-0.977091f},{0.17217f,-0.0544436f,-0.983562f},{0.210353f,-0.0150728f,-0.977509f}, -{0.24749f,0.000588626f,-0.96889f},{0.200182f,-0.0534267f,-0.978301f},{0.239984f,-0.0200864f,-0.970569f}, -{0.0134776f,0.00860874f,-0.999872f},{0.0558224f,0.0575724f,-0.996779f},{0.0228466f,0.0251275f,-0.999423f}, -{0.131908f,-0.119876f,-0.983987f},{0.135331f,-0.114692f,-0.98414f},{0.106577f,-0.0967618f,-0.989585f}, -{0.127565f,-0.127645f,-0.983582f},{0.0434816f,0.0682479f,-0.99672f},{0.0416591f,0.0621953f,-0.997194f}, -{0.0678076f,0.102888f,-0.992379f},{-0.0134804f,-0.00861069f,-0.999872f},{-0.0558295f,-0.0575731f,-0.996779f}, -{-0.0228463f,-0.0251269f,-0.999423f},{0.042481f,0.0700992f,-0.996635f},{0.0389583f,0.0679419f,-0.996928f}, -{0.0312083f,0.0653011f,-0.997377f},{-0.0488646f,0.0236813f,-0.998525f},{-0.0123869f,0.00381403f,-0.999916f}, -{-0.122955f,0.136635f,-0.982961f},{-0.0744603f,0.15616f,-0.984921f},{-0.11848f,0.146051f,-0.982157f}, -{-0.20018f,0.0534268f,-0.978301f},{-0.239985f,0.0200864f,-0.970569f},{-0.247488f,-0.000588612f,-0.968891f}, -{-0.0911775f,-0.0374113f,-0.995132f},{-0.164561f,0.091503f,-0.982113f},{-0.132869f,0.129057f,-0.982695f}, -{-0.128065f,0.138732f,-0.982015f},{-0.253059f,-0.0201007f,-0.967242f},{-0.207008f,0.0338838f,-0.977752f}, -{-0.0937007f,0.206583f,-0.973932f},{-0.126712f,0.149271f,-0.980644f},{-0.113835f,0.164764f,-0.979742f}, -{-0.0806854f,0.224573f,-0.971111f},{-0.115975f,0.167824f,-0.978971f},{-0.0476595f,0.282538f,-0.958071f}, -{-0.0601369f,0.245617f,-0.9675f},{-0.099067f,0.189505f,-0.976869f},{-0.0257387f,0.300652f,-0.953386f}, -{-0.0999932f,0.189498f,-0.976776f},{-0.108516f,0.173184f,-0.978893f},{-0.107387f,0.17428f,-0.978823f}, -{-0.155908f,0.110576f,-0.981563f},{-0.107733f,0.172359f,-0.979125f},{-0.0781727f,0.233122f,-0.9693f}, -{0.00667651f,0.0246582f,-0.999674f},{0.0165896f,0.0396375f,-0.999076f},{-0.105383f,0.17193f,-0.979456f}, -{0.0619015f,0.0809495f,-0.994794f},{0.00832976f,-0.0847504f,-0.996367f},{-0.0744356f,-0.126144f,-0.989215f}, -{-0.0300614f,-0.145127f,-0.988956f},{-0.0434816f,-0.068248f,-0.99672f},{-0.0678076f,-0.102888f,-0.992379f}, -{-0.0424824f,-0.0700993f,-0.996635f},{0.0309353f,0.0400397f,-0.998719f},{0.105381f,-0.171931f,-0.979456f}, -{0.118496f,-0.146014f,-0.98216f},{0.0744765f,-0.156159f,-0.98492f},{0.00348893f,-0.00830625f,-0.999959f}, -{0.0123794f,-0.00381472f,-0.999916f},{0.139631f,-0.110247f,-0.984047f},{0.139617f,-0.112341f,-0.983812f}, -{0.168792f,-0.0732426f,-0.982927f},{0.135427f,-0.123518f,-0.983058f},{0.131599f,-0.131651f,-0.982522f}, -{0.255848f,0.0391961f,-0.965922f},{0.0990662f,-0.189505f,-0.976869f},{0.207001f,-0.033884f,-0.977754f}, -{0.0257381f,-0.300652f,-0.953386f},{0.0601361f,-0.245617f,-0.9675f},{0.0476609f,-0.282538f,-0.958071f}, -{0.108819f,-0.168871f,-0.979613f},{0.0781673f,-0.233124f,-0.9693f},{0.107726f,-0.172348f,-0.979128f}, -{0.071609f,-0.249664f,-0.965681f},{0.0999793f,-0.189499f,-0.976777f},{0.18367f,0.0228704f,-0.982722f}, -{0.143043f,-0.0368726f,-0.989029f},{-0.0165949f,-0.039638f,-0.999076f},{-0.031216f,-0.0653017f,-0.997377f}, -{0.138156f,-0.116935f,-0.983483f},{0.15591f,-0.110576f,-0.981563f},{0.189495f,-0.0760762f,-0.97893f}, -{0.253055f,0.0201006f,-0.967243f},{0.113819f,-0.164768f,-0.979743f},{0.110674f,-0.169985f,-0.979212f}, -{0.142319f,-0.13279f,-0.980873f},{0.0638565f,-0.265747f,-0.961926f},{0.111105f,-0.162971f,-0.980355f}, -{0.11444f,-0.155086f,-0.98125f},{0.0654512f,-0.217303f,-0.973907f},{0.122963f,-0.13662f,-0.982962f}, -{-0.0416577f,-0.0621948f,-0.997194f},{-0.0619016f,-0.0809495f,-0.994794f},{0.074428f,0.126144f,-0.989216f}, -{-0.10656f,0.0967627f,-0.989587f},{0.030073f,0.145128f,-0.988956f},{-0.132285f,0.119253f,-0.984012f}, -{-0.127537f,0.127694f,-0.98358f},{0.112261f,0.173544f,-0.978407f},{0.114801f,0.194823f,-0.974097f}, -{0.037314f,0.0525697f,-0.99792f},{0.107531f,0.153096f,-0.982343f},{0.102693f,0.132768f,-0.985813f}, -{0.0488762f,-0.0236802f,-0.998524f},{0.0911884f,0.0374122f,-0.995131f},{-0.0343818f,-0.207914f,-0.977543f}, -{-0.114804f,-0.194823f,-0.974097f},{-0.112265f,-0.173544f,-0.978406f},{-0.10753f,-0.153096f,-0.982344f}, -{-0.0373124f,-0.0525692f,-0.99792f},{-0.0309343f,-0.0400395f,-0.998719f},{-0.102696f,-0.132768f,-0.985812f}, -{-0.00349236f,0.00830612f,-0.999959f},{-0.143026f,0.0368738f,-0.989032f},{-0.172172f,0.0544429f,-0.983561f}, -{-0.108774f,0.16898f,-0.979599f},{-0.0716214f,0.249662f,-0.965681f},{-0.110692f,0.169978f,-0.979211f}, -{-0.183652f,-0.0228691f,-0.982725f},{-0.111114f,0.16297f,-0.980354f},{-0.114446f,0.155082f,-0.98125f}, -{-0.00831784f,0.0847515f,-0.996367f},{0.0256814f,0.0524475f,-0.998293f},{0.0332888f,0.0620644f,-0.997517f}, -{-0.212779f,-0.0043133f,-0.977091f},{-0.168808f,0.0732415f,-0.982924f},{-0.136682f,0.120661f,-0.983239f}, -{-0.139069f,0.114346f,-0.983659f},{-0.210368f,0.0150721f,-0.977506f},{-0.117902f,0.15764f,-0.980433f}, -{0.126705f,-0.149271f,-0.980645f},{0.164554f,-0.0915033f,-0.982115f},{0.117888f,-0.157641f,-0.980434f}, -{0.127125f,-0.140533f,-0.981881f},{0.122423f,-0.149416f,-0.981166f},{0.108474f,-0.173236f,-0.978889f}, -{0.257551f,0.0589452f,-0.964465f},{0.107335f,-0.174359f,-0.978815f},{0.239876f,0.0787303f,-0.967606f}, -{0.151587f,0.0943229f,-0.983933f},{0.138183f,-0.110958f,-0.984172f},{-0.00668129f,-0.0246587f,-0.999674f}, -{0.0971757f,0.111226f,-0.989033f},{-0.0256865f,-0.0524476f,-0.998293f},{-0.0389615f,-0.067942f,-0.996928f}, -{-0.033293f,-0.0620642f,-0.997517f},{0.0343964f,0.207915f,-0.977542f},{-0.135944f,0.113842f,-0.984154f}, -{-0.097181f,-0.111227f,-0.989032f},{-0.065439f,0.217303f,-0.973908f},{-0.139838f,0.110719f,-0.983965f}, -{-0.13881f,0.110345f,-0.984152f},{-0.239861f,-0.0787291f,-0.96761f},{-0.151574f,-0.0943219f,-0.983935f}, -{-0.257556f,-0.0589451f,-0.964464f},{-0.255863f,-0.0391964f,-0.965918f},{-0.0638606f,0.265747f,-0.961925f}, -{-0.122911f,0.148539f,-0.981239f},{-0.189496f,0.0760762f,-0.97893f},{-0.14232f,0.13279f,-0.980873f}, -{-0.410005f,-0.780986f,0.471123f},{-0.431924f,-0.756474f,0.491109f},{-0.406453f,-0.879699f,0.246832f}, -{-0.444614f,-0.738683f,0.506622f},{-0.428298f,-0.85525f,0.291734f},{-0.420701f,-0.718444f,0.553939f}, -{-0.415692f,-0.815118f,0.403464f},{-0.437394f,-0.721373f,0.536943f},{-0.430102f,-0.824692f,0.367282f}, -{-0.434004f,-0.838017f,0.330708f},{-0.44473f,-0.728083f,0.521641f},{-0.268829f,-0.797562f,0.540024f}, -{-0.258175f,-0.722769f,0.641055f},{-0.275537f,-0.774815f,0.568982f},{-0.352408f,-0.728926f,0.58692f}, -{-0.277529f,-0.733033f,0.620999f},{-0.28748f,-0.816277f,0.501046f},{-0.249748f,-0.689892f,0.679467f}, -{-0.215302f,-0.725361f,0.653833f},{-0.256534f,-0.738897f,0.623074f},{-0.261868f,-0.698996f,0.665454f}, -{-0.271108f,-0.755933f,0.595873f},{-0.264635f,-0.709599f,0.653021f},{0.0526752f,-0.683243f,0.728289f}, -{0.0541363f,-0.696338f,0.715669f},{0.0539424f,-0.667359f,0.74278f},{-0.0721475f,-0.716045f,0.694315f}, -{-0.211833f,-0.683867f,0.698178f},{-0.0718111f,-0.680519f,0.729203f},{0.052782f,-0.660486f,0.748981f}, -{0.0443778f,-0.671599f,0.739585f},{0.0438809f,-0.654656f,0.754652f},{0.0375909f,-0.660388f,0.749983f}, -{0.0241761f,-0.649023f,0.760385f},{0.0363458f,-0.648963f,0.759951f},{0.022026f,-0.643221f,0.765363f}, -{0.00631787f,-0.636811f,0.770994f},{0.0031649f,-0.636821f,0.771005f},{-0.355684f,-0.818732f,0.45074f}, -{-0.371045f,-0.909063f,0.18955f},{-0.405078f,-0.583044f,0.704253f},{-0.421979f,-0.580905f,0.696048f}, -{-0.431996f,-0.756391f,0.491175f},{-0.432024f,-0.581257f,0.689562f},{-0.444614f,-0.738684f,0.506621f}, -{-0.352294f,-0.728943f,0.586967f},{-0.420702f,-0.718445f,0.553937f},{-0.410108f,-0.59918f,0.687601f}, -{-0.437394f,-0.721374f,0.536941f},{-0.44473f,-0.728085f,0.521639f},{-0.431774f,-0.585021f,0.686528f}, -{-0.258155f,-0.722817f,0.641008f},{-0.239661f,-0.63406f,0.735208f},{-0.264648f,-0.709547f,0.653073f}, -{-0.336563f,-0.618695f,0.709888f},{-0.25777f,-0.632115f,0.730743f},{-0.27756f,-0.733036f,0.620982f}, -{-0.238256f,-0.634072f,0.735654f},{-0.211913f,-0.683867f,0.698154f},{-0.249749f,-0.689931f,0.679427f}, -{-0.246966f,-0.633237f,0.733498f},{-0.261827f,-0.698956f,0.665513f},{-0.24717f,-0.633257f,0.733412f}, -{0.0527819f,-0.660487f,0.74898f},{0.0540166f,-0.667343f,0.742789f},{0.0563396f,-0.634508f,0.77086f}, -{-0.0720207f,-0.680531f,0.729171f},{-0.204102f,-0.636975f,0.743375f},{-0.0680582f,-0.640402f,0.765018f}, -{0.055102f,-0.63474f,0.770759f},{0.0438808f,-0.654657f,0.754651f},{0.0454974f,-0.635485f,0.770772f}, -{0.0363458f,-0.648964f,0.759951f},{0.0219575f,-0.643198f,0.765385f},{0.0371135f,-0.63602f,0.77078f}, -{0.0218202f,-0.636578f,0.770903f},{0.0020686f,-0.636823f,0.771008f},{-0.425392f,-0.590849f,0.685521f}, -{-0.355736f,-0.325002f,0.876256f},{-0.376871f,-0.358337f,0.854144f},{-0.422036f,-0.5809f,0.696018f}, -{-0.390634f,-0.386348f,0.835548f},{-0.336442f,-0.618721f,0.709923f},{-0.410108f,-0.59918f,0.687601f}, -{-0.370105f,-0.46456f,0.804491f},{-0.394435f,-0.412203f,0.821285f},{-0.392371f,-0.437394f,0.809155f}, -{-0.239634f,-0.634063f,0.735214f},{-0.218199f,-0.539451f,0.813254f},{-0.24719f,-0.633254f,0.733407f}, -{-0.276989f,-0.497609f,0.821986f},{-0.210792f,-0.522063f,0.826449f},{-0.257804f,-0.632111f,0.730734f}, -{-0.110113f,-0.595637f,0.795671f},{-0.204172f,-0.63697f,0.743359f},{-0.223171f,-0.580852f,0.782819f}, -{-0.238249f,-0.634073f,0.735655f},{-0.246939f,-0.633239f,0.733505f},{-0.224079f,-0.567772f,0.792101f}, -{0.055102f,-0.63474f,0.770759f},{0.0564151f,-0.634503f,0.770859f},{0.0620428f,-0.606196f,0.792892f}, -{-0.0682671f,-0.640405f,0.764997f},{0.0414768f,-0.59941f,0.799366f},{0.0507293f,-0.614526f,0.787264f}, -{0.0454974f,-0.635485f,0.770772f},{0.0411515f,-0.622011f,0.781926f},{0.0217483f,-0.63658f,0.770904f}, -{0.024754f,-0.629429f,0.776664f},{0.0031651f,-0.636821f,0.771005f},{-0.226089f,-0.554028f,0.80121f}, -{-0.260709f,-0.018211f,0.965246f},{-0.29234f,-0.0905301f,0.95202f},{-0.376958f,-0.35848f,0.854046f}, -{-0.394436f,-0.412236f,0.821268f},{-0.39064f,-0.386367f,0.835537f},{-0.316442f,-0.150845f,0.936541f}, -{-0.27707f,-0.497587f,0.821973f},{-0.369949f,-0.464644f,0.804515f},{-0.326359f,-0.302136f,0.895658f}, -{-0.392367f,-0.43742f,0.809143f},{-0.331158f,-0.203847f,0.921293f},{-0.218211f,-0.539469f,0.813239f}, -{-0.186125f,-0.436519f,0.880232f},{-0.226126f,-0.554148f,0.801116f},{-0.234204f,-0.351848f,0.906284f}, -{-0.172939f,-0.39662f,0.901546f},{-0.210966f,-0.521912f,0.826499f},{-0.205901f,-0.526859f,0.824636f}, -{-0.110847f,-0.595587f,0.795606f},{-0.223412f,-0.580769f,0.782812f},{-0.202182f,-0.499197f,0.842571f}, -{-0.224072f,-0.567787f,0.792092f},{-0.198592f,-0.469626f,0.86024f},{0.0682852f,-0.579246f,0.812288f}, -{0.0620078f,-0.606222f,0.792874f},{0.0488013f,-0.564062f,0.824289f},{0.0416336f,-0.599414f,0.799355f}, -{-0.0985182f,-0.5515f,0.828337f},{0.056183f,-0.594988f,0.801768f},{0.0507196f,-0.614534f,0.787258f}, -{0.0411442f,-0.622016f,0.781923f},{0.0457027f,-0.609128f,0.791754f},{0.0285242f,-0.622938f,0.781751f}, -{0.0246587f,-0.629464f,0.776638f},{0.00635625f,-0.636811f,0.770994f},{-0.340146f,-0.25357f,0.90554f}, -{0.0457539f,-0.608772f,0.792025f},{0.055249f,-0.594765f,0.801999f},{0.0450032f,-0.608898f,0.791971f}, -{0.0284547f,-0.622817f,0.78185f},{0.0279898f,-0.622836f,0.781851f},{0.0688727f,-0.562516f,0.823913f}, -{0.0490876f,-0.563156f,0.824891f},{-0.0496963f,-0.550993f,0.833029f},{0.0683527f,-0.578569f,0.812765f}, -{0.0665103f,-0.579246f,0.812435f},{0.0562578f,-0.594461f,0.802154f},{-0.198149f,-0.468103f,0.861172f}, -{-0.198042f,-0.472958f,0.85854f},{-0.201746f,-0.497665f,0.84358f},{-0.205766f,-0.525395f,0.825603f}, -{-0.175094f,-0.529826f,0.829835f},{-0.0989846f,-0.550287f,0.829087f},{-0.181766f,-0.361545f,0.914465f}, -{-0.172451f,-0.394113f,0.902738f},{-0.233674f,-0.349592f,0.907294f},{-0.188934f,-0.441329f,0.87723f}, -{-0.185572f,-0.434558f,0.881319f},{-0.174204f,-0.40436f,0.897856f},{-0.331082f,-0.265363f,0.90552f}, -{-0.339571f,-0.251639f,0.906294f},{-0.33003f,-0.216776f,0.918743f},{-0.32564f,-0.30016f,0.896584f}, -{-0.257875f,-0.314928f,0.913412f},{-0.31893f,-0.16631f,0.933073f},{-0.33061f,-0.202144f,0.921865f}, -{-0.315979f,-0.149463f,0.936919f},{-0.302605f,-0.112599f,0.946442f},{-0.292181f,-0.0899699f,0.952122f}, -{-0.277704f,-0.0515423f,0.959283f},{-0.246428f,0.0205104f,0.968944f},{-0.199807f,-0.50237f,0.84125f}, -{0.00685645f,-0.636809f,0.770991f},{-0.170684f,0.109551f,0.979217f},{-0.206616f,0.0629021f,0.976398f}, -{-0.158053f,0.126478f,0.979297f},{-0.129887f,0.173613f,0.976211f},{-0.114756f,0.190018f,0.975051f}, -{-0.0931162f,0.239086f,0.966523f},{-0.0916011f,0.208979f,0.973621f},{-0.0745052f,0.25458f,0.964177f}, -{-0.13862f,0.146005f,0.979524f},{-0.0499282f,0.270988f,0.961287f},{-0.176521f,0.0935066f,0.979845f}, -{-0.180908f,0.0771143f,0.980472f},{-0.221759f,0.0289222f,0.974672f},{-0.258471f,0.00236958f,0.966016f}, -{-0.114433f,-0.0158869f,0.993304f},{-0.212524f,-0.00500348f,0.977143f},{-0.0688181f,0.0517682f,0.996285f}, -{-0.273986f,-0.0489217f,0.960489f},{-0.271537f,-0.0316006f,0.961909f},{-0.225011f,0.0119369f,0.974283f}, -{-0.0428923f,-0.0491747f,0.997869f},{-8.55582e-007f,-7.949e-008f,1.0f},{-0.0482005f,-0.0683324f,0.996498f}, -{-0.186842f,-0.0802466f,0.979107f},{-0.0392859f,-0.028666f,0.998817f},{-0.102404f,-0.0919448f,0.990485f}, -{-0.057155f,-0.107856f,0.992522f},{0.0265899f,-0.119144f,0.992521f},{-0.0835213f,-0.178742f,0.980345f}, -{-0.00540807f,-0.0192356f,0.9998f},{-0.0535629f,-0.0874508f,0.994728f},{0.158051f,-0.126478f,0.979297f}, -{0.114754f,-0.190018f,0.975051f},{0.129893f,-0.173613f,0.97621f},{0.130935f,-0.127075f,0.983213f}, -{0.168995f,-0.0610101f,0.983727f},{0.0931203f,-0.239086f,0.966523f},{0.0745033f,-0.25458f,0.964177f}, -{0.0916021f,-0.208979f,0.973621f},{0.0499291f,-0.270988f,0.961287f},{0.136947f,-0.158154f,0.977872f}, -{0.170691f,-0.10955f,0.979216f},{0.190497f,-0.0828562f,0.978185f},{0.206614f,-0.0629022f,0.976398f}, -{0.102078f,-0.224388f,0.969139f},{0.142513f,-0.142376f,0.979499f},{0.176539f,-0.0935053f,0.979842f}, -{0.109046f,-0.209369f,0.971737f},{0.0142462f,-0.186808f,0.982293f},{0.180916f,-0.0771131f,0.980471f}, -{0.107117f,-0.19432f,0.975072f},{-0.00908038f,-0.0397896f,0.999167f},{0.0687977f,-0.0517701f,0.996286f}, -{-0.0984282f,-0.14449f,0.984599f},{-0.0930399f,-0.127037f,0.987525f},{-0.103308f,-0.162383f,0.981305f}, -{-0.0885006f,-0.108876f,0.990108f},{0.0090855f,0.03979f,0.999167f},{0.00541255f,0.0192361f,0.9998f}, -{-0.269586f,-0.0667669f,0.960659f},{-0.169012f,0.0610092f,0.983724f},{-0.217019f,0.04552f,0.975106f}, -{-0.267327f,-0.0147946f,0.963492f},{-0.190496f,0.0828563f,0.978185f},{-0.102063f,0.22439f,0.96914f}, -{-0.13693f,0.158156f,0.977874f},{-0.109036f,0.209371f,0.971738f},{-0.142505f,0.142378f,0.9795f}, -{-0.107128f,0.194321f,0.975071f},{-0.130951f,0.127075f,0.983211f},{-0.0142661f,0.186807f,0.982293f}, -{-0.0266103f,0.119142f,0.992521f},{0.083517f,0.178742f,0.980345f},{0.05716f,0.107856f,0.992522f}, -{0.103317f,0.162383f,0.981304f},{0.258468f,-0.00236961f,0.966017f},{0.246429f,-0.0205104f,0.968944f}, -{0.0535675f,0.0874512f,0.994727f},{0.0984279f,0.14449f,0.984599f},{0.0930396f,0.127037f,0.987525f}, -{0.0481988f,0.0683322f,0.996498f},{0.0885078f,0.108876f,0.990107f},{0.0428965f,0.0491751f,0.997869f}, -{0.102401f,0.0919447f,0.990485f},{0.0392909f,0.0286666f,0.998817f},{0.186822f,0.080245f,0.979111f}, -{0.114413f,0.0158852f,0.993306f},{0.269573f,0.0667658f,0.960663f},{0.212507f,0.00500236f,0.977147f}, -{0.273996f,0.0489219f,0.960486f},{0.225019f,-0.0119362f,0.974281f},{0.271553f,0.031601f,0.961904f}, -{0.221777f,-0.0289212f,0.974668f},{0.26733f,0.0147946f,0.963491f},{0.217025f,-0.0455199f,0.975104f}, -{0.138621f,-0.146005f,0.979524f},{-0.00317738f,0.636821f,0.771005f},{-0.0246739f,0.629441f,0.776656f}, -{-0.0279566f,0.623058f,0.781676f},{-0.0551303f,0.595408f,0.80153f},{-0.0449278f,0.609331f,0.791642f}, -{-0.0411546f,0.621971f,0.781958f},{0.0499248f,0.552325f,0.832133f},{-0.0687359f,0.563612f,0.823175f}, -{-0.0416737f,0.599286f,0.79945f},{-0.0663718f,0.580108f,0.811831f},{-0.0507229f,0.614466f,0.787311f}, -{-0.0620227f,0.606128f,0.792945f},{0.223995f,0.567518f,0.792306f},{0.226021f,0.553812f,0.801378f}, -{0.198662f,0.475091f,0.857217f},{0.110786f,0.595421f,0.795739f},{0.223354f,0.58056f,0.782983f}, -{0.175481f,0.531382f,0.828758f},{0.276897f,0.496956f,0.822413f},{0.182559f,0.364365f,0.913187f}, -{0.210821f,0.521383f,0.82687f},{0.174949f,0.407013f,0.896511f},{0.18964f,0.443733f,0.875864f}, -{0.218089f,0.539048f,0.81355f},{0.330803f,0.219259f,0.917875f},{0.331812f,0.268014f,0.904472f}, -{0.392167f,0.436574f,0.809696f},{0.25864f,0.317724f,0.912226f},{0.369772f,0.46392f,0.805014f}, -{0.394193f,0.411246f,0.821881f},{0.319671f,0.168505f,0.932425f},{0.390338f,0.385206f,0.836213f}, -{0.303211f,0.114345f,0.946038f},{0.278069f,0.0525963f,0.95912f},{0.376599f,0.357097f,0.854784f}, -{0.355321f,0.323311f,0.87705f},{0.200313f,0.50421f,0.840028f},{-0.00685578f,0.636809f,0.770991f}, -{-0.002068f,0.636823f,0.771008f},{-0.0217543f,0.63654f,0.770937f},{-0.0247724f,0.629382f,0.776701f}, -{-0.0411683f,0.621921f,0.781997f},{-0.0371196f,0.635941f,0.770844f},{-0.0415314f,0.599172f,0.799542f}, -{-0.0620694f,0.606014f,0.793029f},{-0.056447f,0.634304f,0.77102f},{-0.0507421f,0.614392f,0.787367f}, -{-0.0454985f,0.63537f,0.770866f},{-0.0551123f,0.634587f,0.770884f},{0.223077f,0.580496f,0.78311f}, -{0.238176f,0.633724f,0.735979f},{0.223957f,0.56733f,0.792452f},{0.0682119f,0.64016f,0.765207f}, -{0.204107f,0.63668f,0.743626f},{0.110027f,0.595341f,0.795904f},{0.239503f,0.633497f,0.735744f}, -{0.210588f,0.521305f,0.826979f},{0.21802f,0.538815f,0.813723f},{0.247067f,0.632772f,0.733864f}, -{0.22593f,0.553496f,0.801622f},{0.246834f,0.632828f,0.733895f},{0.392125f,0.436343f,0.809842f}, -{0.369882f,0.463619f,0.805137f},{0.409993f,0.598406f,0.688343f},{0.27676f,0.496749f,0.822584f}, -{0.257657f,0.631462f,0.731347f},{0.336306f,0.618008f,0.710608f},{0.425267f,0.589992f,0.686336f}, -{0.394147f,0.411029f,0.822012f},{0.431633f,0.584074f,0.687423f},{0.390294f,0.385037f,0.836312f}, -{0.376488f,0.356858f,0.854932f},{0.431864f,0.580207f,0.690546f},{0.42187f,0.579716f,0.697105f}, -{0.404919f,0.581686f,0.705466f},{-0.00315153f,0.636821f,0.771006f},{-0.021951f,0.643165f,0.765413f}, -{-0.0218263f,0.636538f,0.770937f},{-0.0363394f,0.6489f,0.760005f},{0.068003f,0.640157f,0.765229f}, -{-0.0563715f,0.63431f,0.771021f},{-0.0540317f,0.667183f,0.742932f},{-0.0438692f,0.654564f,0.754732f}, -{0.238183f,0.633724f,0.735978f},{0.249708f,0.689649f,0.679728f},{0.246861f,0.632825f,0.733889f}, -{0.0719912f,0.680332f,0.72936f},{0.211878f,0.683631f,0.698395f},{0.204036f,0.636685f,0.743641f}, -{0.258076f,0.722371f,0.641543f},{0.257623f,0.631466f,0.731355f},{0.239529f,0.633495f,0.735738f}, -{0.264571f,0.709164f,0.65352f},{0.247047f,0.632774f,0.733869f},{0.261762f,0.698625f,0.665885f}, -{0.420681f,0.717841f,0.554735f},{0.336426f,0.617982f,0.710574f},{0.277479f,0.732529f,0.621616f}, -{0.35224f,0.728388f,0.587689f},{0.437381f,0.720712f,0.537841f},{0.444724f,0.72736f,0.522654f}, -{0.421813f,0.57972f,0.697136f},{0.44462f,0.737892f,0.507768f},{0.432036f,0.755513f,0.492489f}, -{0.4101f,0.780009f,0.472656f},{-0.0527785f,0.660363f,0.74909f},{-0.00629327f,0.636811f,0.770994f}, -{-0.0241581f,0.649001f,0.760404f},{-0.0220195f,0.643189f,0.765391f},{-0.0375725f,0.660345f,0.750022f}, -{-0.0363395f,0.648899f,0.760006f},{0.0717815f,0.680319f,0.729392f},{-0.0539575f,0.667198f,0.742923f}, -{-0.0541337f,0.696227f,0.715778f},{-0.0527786f,0.660362f,0.749091f},{-0.0438693f,0.654563f,0.754733f}, -{-0.0443535f,0.671536f,0.739643f},{0.249707f,0.68961f,0.679768f},{0.256526f,0.738688f,0.623325f}, -{0.261803f,0.698666f,0.665827f},{0.0721451f,0.715903f,0.694462f},{0.215298f,0.725187f,0.654026f}, -{0.211798f,0.683631f,0.69842f},{0.268798f,0.79723f,0.540529f},{0.277449f,0.732527f,0.621633f}, -{0.258096f,0.722323f,0.641589f},{0.275504f,0.774529f,0.569388f},{0.264558f,0.709216f,0.653469f}, -{0.271082f,0.755688f,0.596197f},{0.415759f,0.814669f,0.4043f},{0.420681f,0.717839f,0.554738f}, -{0.355703f,0.818321f,0.451472f},{0.352353f,0.728371f,0.587642f},{0.287459f,0.815902f,0.501668f}, -{0.430194f,0.824211f,0.368252f},{0.444724f,0.727359f,0.522656f},{0.437381f,0.72071f,0.537843f}, -{0.434129f,0.83751f,0.331828f},{0.44462f,0.73789f,0.50777f},{0.431964f,0.755597f,0.492423f}, -{0.428471f,0.854721f,0.293028f},{0.406702f,0.879159f,0.248341f},{0.371402f,0.908545f,0.19133f}, -{-0.0526576f,0.683158f,0.728369f},{-0.0263917f,0.652054f,0.757713f},{-0.00909888f,0.636797f,0.770977f}, -{-0.0536109f,0.695352f,0.716667f},{-0.0443236f,0.671834f,0.739374f},{-0.0456191f,0.680563f,0.731268f}, -{-0.0392338f,0.666389f,0.744571f},{-0.0375531f,0.660552f,0.749841f},{-0.0242147f,0.649157f,0.760269f}, -{0.0720186f,0.716437f,0.693924f},{0.215375f,0.747931f,0.627863f},{0.215321f,0.725786f,0.653354f}, -{-0.0526197f,0.683545f,0.728009f},{-0.055364f,0.711835f,0.700162f},{-0.0540181f,0.69673f,0.715297f}, -{0.279233f,0.809709f,0.516139f},{0.275645f,0.775365f,0.568181f},{0.271283f,0.756476f,0.595104f}, -{0.274244f,0.786708f,0.553065f},{0.256648f,0.739281f,0.622571f},{0.258544f,0.76548f,0.589233f}, -{0.351817f,0.864019f,0.360134f},{0.287541f,0.81663f,0.500435f},{0.289026f,0.85903f,0.42253f}, -{0.268949f,0.797912f,0.539447f},{0.271782f,0.836894f,0.475123f},{0.430114f,0.824737f,0.367166f}, -{0.415694f,0.815277f,0.40314f},{0.415649f,0.87405f,0.251538f},{0.355825f,0.818985f,0.450169f}, -{0.404724f,0.863226f,0.301729f},{0.415023f,0.887621f,0.199712f},{0.434041f,0.837936f,0.330866f}, -{0.403094f,0.903754f,0.144024f},{0.428382f,0.85503f,0.292254f},{0.406518f,0.879434f,0.247668f}, -{0.372382f,0.924662f,0.079571f},{0.325495f,0.945544f,0.0f},{0.0705335f,0.735204f,0.674167f}, -{0.286908f,0.957958f,-0.000297298f},{0.286152f,0.958184f,-0.00027813f},{0.278077f,0.951596f,-0.130911f}, -{0.266505f,0.956115f,-0.121731f},{0.270116f,0.962828f,-0.00025761f},{0.23607f,0.971736f,-0.000235456f}, -{0.258612f,0.959649f,-0.110422f},{0.111685f,0.993744f,-0.000218645f},{0.15671f,0.982441f,-0.101255f}, -{0.0244862f,0.995607f,-0.0903677f},{0.00228008f,0.999997f,-0.000195691f},{0.00864389f,0.999963f,-0.000166398f}, -{0.0121337f,0.996969f,-0.076847f},{0.0172244f,0.999852f,-0.000133472f},{0.0209404f,0.99785f,-0.0620961f}, -{0.0225323f,0.998704f,-0.0456418f},{0.0196045f,0.999808f,-9.71639e-005f},{0.0193212f,0.999813f,-5.4502e-005f}, -{0.0204337f,0.99946f,-0.0257239f},{0.0176994f,0.999843f,0.0f},{0.0173199f,0.99985f,0.0f}, -{0.267273f,0.953349f,-0.140321f},{0.257069f,0.95479f,-0.149306f},{0.271589f,0.962413f,-0.00031666f}, -{0.280293f,0.959914f,-0.000331412f},{0.282163f,0.946687f,-0.155461f},{0.308726f,0.937469f,-0.16075f}, -{0.318966f,0.947766f,-0.000342471f},{0.324966f,0.931085f,-0.165762f},{0.355068f,0.93484f,-0.000351538f}, -{0.370564f,0.928807f,-0.000361614f},{0.330965f,0.928046f,-0.17086f},{0.326564f,0.928594f,-0.176266f}, -{0.376575f,0.926386f,-0.000372148f},{0.30552f,0.934514f,-0.182597f},{0.373027f,0.92782f,-0.000383596f}, -{0.354145f,0.935191f,-0.000397484f},{0.272835f,0.943202f,-0.189554f},{0.325394f,0.945578f,-0.00041274f}, -{0.0211408f,0.997288f,-0.0705025f},{0.0173199f,0.99985f,-1.50134e-014f},{0.0149749f,0.999888f,1.04413e-015f}, -{0.0190992f,0.976903f,-0.212829f},{0.012063f,0.997001f,-0.0764401f},{0.0270514f,0.98481f,-0.171517f}, -{0.0267385f,0.991726f,-0.125559f},{0.0225092f,0.998719f,-0.0453197f},{0.258403f,0.959761f,-0.109939f}, -{0.185186f,0.942002f,-0.279891f},{0.235359f,0.921009f,-0.310401f},{0.0245818f,0.995645f,-0.0899239f}, -{0.060169f,0.966375f,-0.25f},{0.156085f,0.982591f,-0.100754f},{0.242529f,0.898699f,-0.365402f}, -{0.221008f,0.893124f,-0.391771f},{0.26728f,0.953393f,-0.140014f},{0.245706f,0.907932f,-0.33954f}, -{0.27811f,0.951625f,-0.130631f},{0.266559f,0.95615f,-0.121342f},{0.222884f,0.865841f,-0.447931f}, -{0.308832f,0.937463f,-0.160577f},{0.220933f,0.874336f,-0.432117f},{0.282182f,0.946719f,-0.155229f}, -{0.25702f,0.954855f,-0.148975f},{0.223806f,0.882967f,-0.412649f},{0.225231f,0.858059f,-0.461525f}, -{0.330999f,0.928053f,-0.170754f},{0.32502f,0.931092f,-0.165619f},{0.216849f,0.852796f,-0.475096f}, -{0.32658f,0.928602f,-0.176192f},{0.305399f,0.934555f,-0.182588f},{0.192096f,0.850459f,-0.489713f}, -{0.155604f,0.848968f,-0.505015f},{0.0209039f,0.997875f,-0.0617066f},{0.0204365f,0.999463f,-0.0256194f}, -{0.0198325f,0.993882f,-0.108651f},{0.0149749f,0.999888f,0.0f},{0.0107279f,0.999942f,0.0f}, -{0.027494f,0.940471f,-0.338759f},{0.0270456f,0.9848f,-0.171575f},{0.0323478f,0.961911f,-0.271441f}, -{0.0289941f,0.980028f,-0.196733f},{0.0267423f,0.99172f,-0.125606f},{0.0211768f,0.997263f,-0.0708398f}, -{0.184752f,0.942124f,-0.279767f},{0.198008f,0.842424f,-0.501114f},{0.235436f,0.92105f,-0.310221f}, -{0.0190528f,0.976871f,-0.212979f},{0.0630398f,0.914688f,-0.399213f},{0.0602812f,0.96636f,-0.250028f}, -{0.19314f,0.786761f,-0.586263f},{0.167212f,0.763159f,-0.624203f},{0.24247f,0.898676f,-0.365499f}, -{0.245744f,0.907886f,-0.339635f},{0.201874f,0.8124f,-0.547041f},{0.0929333f,0.700686f,-0.707392f}, -{0.220911f,0.874312f,-0.432176f},{0.113967f,0.718951f,-0.685653f},{0.2238f,0.88298f,-0.412625f}, -{0.221072f,0.893172f,-0.391626f},{0.154471f,0.739263f,-0.65546f},{0.0875221f,0.684218f,-0.724006f}, -{0.225226f,0.858048f,-0.461549f},{0.222895f,0.86583f,-0.447948f},{0.073847f,0.669461f,-0.739168f}, -{0.216833f,0.852792f,-0.475111f},{0.191924f,0.850452f,-0.489793f},{0.0484461f,0.655515f,-0.753627f}, -{0.0158475f,0.640906f,-0.767455f},{0.155604f,0.848968f,-0.505015f},{0.164174f,0.877789f,-0.450038f}, -{0.0167192f,0.990338f,-0.137663f},{0.0107279f,0.999942f,-5.79815e-010f},{0.00505961f,0.999987f,0.0f}, -{0.033892f,0.890883f,-0.452967f},{0.0323469f,0.961882f,-0.271545f},{0.0355093f,0.932581f,-0.35921f}, -{0.0291785f,0.966258f,-0.255917f},{0.0290016f,0.980011f,-0.196817f},{0.0198883f,0.993822f,-0.10919f}, -{0.163842f,0.877955f,-0.449834f},{0.13651f,0.780866f,-0.609602f},{0.148479f,0.718253f,-0.679755f}, -{0.0274608f,0.940382f,-0.339011f},{0.0636188f,0.841289f,-0.536829f},{0.0631371f,0.914656f,-0.399272f}, -{0.125965f,0.609067f,-0.783052f},{0.0957412f,0.559997f,-0.822944f},{0.193061f,0.786669f,-0.586412f}, -{0.201887f,0.812292f,-0.547197f},{0.142438f,0.660203f,-0.737458f},{-0.0540079f,0.439944f,-0.896399f}, -{0.113812f,0.718888f,-0.685746f},{-0.0113659f,0.472513f,-0.88125f},{0.154497f,0.739288f,-0.655427f}, -{0.167295f,0.763303f,-0.624004f},{0.06617f,0.514496f,-0.854936f},{-0.0658654f,0.414517f,-0.907655f}, -{0.0875037f,0.684189f,-0.724037f},{0.0929309f,0.700662f,-0.707415f},{-0.0816251f,0.391685f,-0.916472f}, -{0.0738257f,0.669444f,-0.739185f},{0.0482842f,0.65544f,-0.753702f},{-0.101927f,0.369884f,-0.92347f}, -{-0.123605f,0.347635f,-0.929447f},{0.0158475f,0.640907f,-0.767455f},{0.198107f,0.842564f,-0.500839f}, -{0.0111543f,0.989269f,-0.145677f},{0.00505961f,0.999987f,-2.85058e-010f},{-0.00138151f,0.999999f,1.91845e-016f}, -{0.0382111f,0.850391f,-0.524762f},{0.0355133f,0.932523f,-0.359361f},{0.0352909f,0.91244f,-0.407687f}, -{0.0256877f,0.959016f,-0.282185f},{0.0291895f,0.966226f,-0.256037f},{0.0167928f,0.990238f,-0.138374f}, -{0.136305f,0.781126f,-0.609314f},{0.0955151f,0.684245f,-0.72297f},{0.0993674f,0.584646f,-0.805181f}, -{0.0338728f,0.890704f,-0.453319f},{0.0484155f,0.77454f,-0.630669f},{0.0636976f,0.841226f,-0.536918f}, -{0.0560249f,0.401556f,-0.914119f},{0.0268241f,0.326384f,-0.944856f},{0.125862f,0.608874f,-0.783218f}, -{0.0741101f,0.485701f,-0.870978f},{0.142412f,0.659992f,-0.737652f},{0.14861f,0.71855f,-0.679412f}, -{-0.0637993f,0.196022f,-0.978522f},{-0.0116501f,0.472378f,-0.881319f},{0.0662311f,0.514541f,-0.854904f}, -{0.00189659f,0.257578f,-0.966256f},{0.0958443f,0.56027f,-0.822746f},{-0.197306f,0.110962f,-0.974042f}, -{-0.0658928f,0.414469f,-0.907675f},{-0.0540224f,0.439905f,-0.896418f},{-0.164717f,0.144236f,-0.975738f}, -{-0.210934f,0.08502f,-0.973796f},{-0.081646f,0.391658f,-0.916481f},{-0.223578f,0.0624871f,-0.972681f}, -{-0.233506f,0.0413979f,-0.971474f},{-0.102042f,0.369768f,-0.923504f},{0.102044f,-0.369767f,-0.923504f}, -{0.123604f,-0.347635f,-0.929447f},{0.0658736f,-0.414472f,-0.907675f},{0.1973f,-0.110963f,-0.974043f}, -{0.210917f,-0.0850214f,-0.973799f},{0.0816379f,-0.391659f,-0.916482f},{0.223573f,-0.0624874f,-0.972682f}, -{0.233508f,-0.0413979f,-0.971473f},{-0.00190271f,-0.257578f,-0.966256f},{-0.0662188f,-0.51454f,-0.854906f}, -{-0.0958526f,-0.560269f,-0.822746f},{0.164734f,-0.144235f,-0.975735f},{0.0116715f,-0.472379f,-0.881318f}, -{0.0638166f,-0.19602f,-0.978521f},{-0.142412f,-0.659992f,-0.737652f},{-0.148611f,-0.71855f,-0.679412f}, -{-0.0741122f,-0.485701f,-0.870978f},{-0.125862f,-0.608874f,-0.783218f},{-0.0560238f,-0.401556f,-0.914119f}, -{-0.0268274f,-0.326385f,-0.944856f},{-0.0338724f,-0.890704f,-0.453319f},{-0.0484116f,-0.77454f,-0.630669f}, -{-0.0636956f,-0.841226f,-0.536918f},{-0.0955126f,-0.684245f,-0.72297f},{-0.0993696f,-0.584646f,-0.80518f}, -{-0.136306f,-0.781126f,-0.609313f},{-0.0355125f,-0.932523f,-0.35936f},{-0.0352907f,-0.91244f,-0.407686f}, -{-0.0382116f,-0.850391f,-0.524763f},{-0.0291876f,-0.966226f,-0.256036f},{-0.025686f,-0.959016f,-0.282185f}, -{-0.0111537f,-0.989269f,-0.145677f},{-0.0167921f,-0.990238f,-0.138374f},{-0.0050596f,-0.999987f,0.0f}, -{0.00138152f,-0.999999f,-1.73582e-014f},{0.05402f,-0.439909f,-0.896416f},{-0.0482827f,-0.65544f,-0.753702f}, -{-0.0158483f,-0.640906f,-0.767455f},{-0.0929347f,-0.700666f,-0.707411f},{0.0658462f,-0.414519f,-0.907655f}, -{-0.0875227f,-0.68419f,-0.724033f},{-0.0738342f,-0.669444f,-0.739184f},{0.0816169f,-0.391685f,-0.916472f}, -{0.101929f,-0.369884f,-0.92347f},{-0.0661576f,-0.514494f,-0.854938f},{-0.154485f,-0.739288f,-0.65543f}, -{-0.167303f,-0.763301f,-0.624004f},{0.0540055f,-0.439948f,-0.896398f},{-0.113792f,-0.718891f,-0.685745f}, -{0.0113873f,-0.472514f,-0.88125f},{-0.198106f,-0.842564f,-0.500839f},{-0.14848f,-0.718253f,-0.679755f}, -{-0.142438f,-0.660203f,-0.737458f},{-0.201887f,-0.812292f,-0.547197f},{-0.125965f,-0.609068f,-0.783051f}, -{-0.193061f,-0.786669f,-0.586412f},{-0.0274602f,-0.940382f,-0.33901f},{-0.0636168f,-0.841289f,-0.536829f}, -{-0.0631375f,-0.914656f,-0.399271f},{-0.136511f,-0.780866f,-0.609601f},{-0.163845f,-0.877955f,-0.449833f}, -{-0.0323448f,-0.961882f,-0.271544f},{-0.0355085f,-0.932581f,-0.359209f},{-0.0338916f,-0.890883f,-0.452967f}, -{-0.0289993f,-0.980011f,-0.196816f},{-0.0291766f,-0.966258f,-0.255917f},{-0.0167184f,-0.990338f,-0.137663f}, -{-0.0198877f,-0.993822f,-0.109189f},{-0.0107279f,-0.999942f,-3.47115e-014f},{-0.0050596f,-0.999987f,-3.47131e-014f}, -{-0.0957495f,-0.559996f,-0.822944f},{-0.191923f,-0.850452f,-0.489793f},{-0.155604f,-0.848968f,-0.505015f}, -{-0.222898f,-0.865832f,-0.447942f},{-0.0875411f,-0.68422f,-0.724003f},{-0.225241f,-0.858046f,-0.461544f}, -{-0.21684f,-0.85279f,-0.47511f},{-0.0738554f,-0.669461f,-0.739167f},{-0.0484446f,-0.655515f,-0.753627f}, -{-0.154458f,-0.739263f,-0.655463f},{-0.221079f,-0.89317f,-0.391626f},{-0.16722f,-0.763157f,-0.624202f}, -{-0.092937f,-0.70069f,-0.707387f},{-0.220895f,-0.874317f,-0.432174f},{-0.113948f,-0.718955f,-0.685653f}, -{-0.235433f,-0.92105f,-0.310221f},{-0.198007f,-0.842424f,-0.501114f},{-0.201874f,-0.8124f,-0.547041f}, -{-0.245744f,-0.907886f,-0.339635f},{-0.19314f,-0.786761f,-0.586263f},{-0.24247f,-0.898676f,-0.365499f}, -{-0.0190519f,-0.976871f,-0.212977f},{-0.0630402f,-0.914689f,-0.399213f},{-0.060284f,-0.966361f,-0.250026f}, -{-0.164177f,-0.877788f,-0.450037f},{-0.184757f,-0.942123f,-0.279767f},{-0.0270421f,-0.9848f,-0.171573f}, -{-0.0323457f,-0.961912f,-0.27144f},{-0.0274934f,-0.940472f,-0.338758f},{-0.0267396f,-0.99172f,-0.125605f}, -{-0.0289918f,-0.980029f,-0.196732f},{-0.0198319f,-0.993882f,-0.108651f},{-0.0211762f,-0.997263f,-0.0708397f}, -{-0.0149749f,-0.999888f,1.73785e-014f},{-0.0107279f,-0.999942f,-1.37458e-007f},{-0.223789f,-0.882982f,-0.412628f}, -{-0.406267f,-0.879976f,0.24615f},{-0.325496f,-0.945544f,-4.37825e-014f},{-0.430021f,-0.825224f,0.366179f}, -{-0.415042f,-0.887589f,0.199814f},{-0.433914f,-0.838449f,0.32973f},{-0.428207f,-0.855563f,0.290948f}, -{-0.403111f,-0.903734f,0.144105f},{-0.372393f,-0.924654f,0.0796197f},{-0.351815f,-0.863964f,0.360266f}, -{-0.287563f,-0.817015f,0.499794f},{-0.289017f,-0.858968f,0.422662f},{-0.415666f,-0.874009f,0.251654f}, -{-0.415625f,-0.815734f,0.402286f},{-0.404737f,-0.863176f,0.301853f},{-0.271311f,-0.756732f,0.594766f}, -{-0.274232f,-0.786642f,0.553165f},{-0.279221f,-0.809642f,0.516252f},{-0.27568f,-0.775661f,0.567759f}, -{-0.271774f,-0.836827f,0.475247f},{-0.268981f,-0.798255f,0.538923f},{-0.0705437f,-0.73515f,0.674224f}, -{-0.215371f,-0.747875f,0.627932f},{-0.0720223f,-0.716587f,0.693769f},{-0.258526f,-0.76542f,0.589319f}, -{-0.256658f,-0.7395f,0.622308f},{-0.215327f,-0.725968f,0.65315f},{0.0536227f,-0.695311f,0.716706f}, -{0.0553596f,-0.711787f,0.700211f},{0.0526367f,-0.683635f,0.727924f},{0.05402f,-0.696847f,0.715182f}, -{0.0443476f,-0.671901f,0.739312f},{0.0456343f,-0.680533f,0.731295f},{0.0375712f,-0.660597f,0.7498f}, -{0.0392392f,-0.666369f,0.744589f},{0.0263913f,-0.652044f,0.757722f},{0.0242326f,-0.64918f,0.760249f}, -{0.00909943f,-0.636797f,0.770977f},{-0.355806f,-0.819405f,0.449419f},{-0.305399f,-0.934555f,-0.182588f}, -{-0.272835f,-0.943202f,-0.189554f},{-0.325025f,-0.931091f,-0.165614f},{-0.225246f,-0.858058f,-0.46152f}, -{-0.33101f,-0.92805f,-0.170751f},{-0.326585f,-0.928601f,-0.176191f},{-0.216857f,-0.852794f,-0.475095f}, -{-0.192095f,-0.850459f,-0.489713f},{-0.223794f,-0.882969f,-0.412652f},{-0.282168f,-0.946723f,-0.15523f}, -{-0.257023f,-0.954853f,-0.148976f},{-0.222888f,-0.865843f,-0.447925f},{-0.308825f,-0.937467f,-0.160573f}, -{-0.220917f,-0.874341f,-0.432116f},{-0.27811f,-0.951625f,-0.130631f},{-0.266557f,-0.95615f,-0.121342f}, -{-0.245706f,-0.907932f,-0.33954f},{-0.267282f,-0.953392f,-0.140014f},{-0.242529f,-0.8987f,-0.365402f}, -{-0.221015f,-0.893122f,-0.391771f},{-0.156094f,-0.98259f,-0.100754f},{-0.0601717f,-0.966375f,-0.249998f}, -{-0.185191f,-0.942001f,-0.279891f},{-0.235357f,-0.921009f,-0.310401f},{-0.258402f,-0.959761f,-0.10994f}, -{-0.0120606f,-0.997001f,-0.0764369f},{-0.0270479f,-0.98481f,-0.171515f},{-0.0190983f,-0.976903f,-0.212827f}, -{-0.0245852f,-0.995645f,-0.089921f},{-0.0208988f,-0.997876f,-0.0617047f},{-0.0267358f,-0.991726f,-0.125558f}, -{-0.0211402f,-0.997288f,-0.0705024f},{-0.0225064f,-0.998719f,-0.0453191f},{-0.0173199f,-0.99985f,0.0f}, -{-0.020436f,-0.999463f,-0.0256193f},{-0.0149749f,-0.999888f,0.0f},{-0.354145f,-0.93519f,-0.000397467f}, -{-0.325394f,-0.945578f,-0.00041274f},{-0.37057f,-0.928805f,-0.000358322f},{-0.330975f,-0.928043f,-0.170857f}, -{-0.376582f,-0.926383f,-0.00037055f},{-0.37303f,-0.927819f,-0.00038323f},{-0.326569f,-0.928592f,-0.176265f}, -{-0.30552f,-0.934514f,-0.182597f},{-0.282148f,-0.946691f,-0.155461f},{-0.318954f,-0.94777f,-0.000340813f}, -{-0.280289f,-0.959916f,-0.000332774f},{-0.324972f,-0.931084f,-0.165758f},{-0.355065f,-0.934841f,-0.000347719f}, -{-0.308718f,-0.937472f,-0.160746f},{-0.286908f,-0.957958f,-0.000297201f},{-0.286152f,-0.958184f,-0.000278036f}, -{-0.278077f,-0.951596f,-0.130911f},{-0.271594f,-0.962412f,-0.000317168f},{-0.267276f,-0.953349f,-0.140321f}, -{-0.257072f,-0.954789f,-0.149307f},{-0.111694f,-0.993743f,-0.00021707f},{-0.156718f,-0.982439f,-0.101254f}, -{-0.236074f,-0.971735f,-0.000236761f},{-0.25861f,-0.95965f,-0.110423f},{-0.266503f,-0.956116f,-0.121731f}, -{-0.270112f,-0.962829f,-0.000258194f},{-0.00863986f,-0.999963f,-0.000162909f},{-0.0121313f,-0.996969f,-0.0768439f}, -{-0.00228269f,-0.999997f,-0.000191989f},{-0.0244896f,-0.995608f,-0.0903648f},{-0.0172187f,-0.999852f,-0.000131616f}, -{-0.0209353f,-0.997851f,-0.0620942f},{-0.0225295f,-0.998704f,-0.0456412f},{-0.0196018f,-0.999808f,-9.66914e-005f}, -{-0.0193208f,-0.999813f,-5.44735e-005f},{-0.0204332f,-0.99946f,-0.0257239f},{-0.0176994f,-0.999843f,0.0f}, -{0.0f,0.271326f,0.962488f},{0.0f,0.253151f,0.967427f},{0.0f,0.26258f,0.96491f}, -{0.0f,0.147431f,0.989072f},{0.0f,0.162743f,0.986669f},{0.0f,0.209863f,0.977731f}, -{0.0f,0.243346f,0.96994f},{0.0f,0.20324f,0.979129f},{0.0f,0.0844041f,0.996432f}, -{0.0f,0.0211631f,0.999776f},{0.0f,0.0519304f,0.998651f},{0.0f,0.0826965f,0.996575f}, -{0.0f,0.113463f,0.993542f},{0.0f,0.11544f,0.993314f},{0.0f,0.119575f,0.992825f}, -{0.0f,0.125688f,0.99207f},{0.0f,0.133439f,0.991057f},{0.0f,0.142487f,0.989797f}, -{0.0f,0.1524f,0.988319f},{6.49463e-018f,-0.123071f,-0.992398f},{-1.11865e-017f,-0.13416f,-0.99096f}, -{-3.82822e-018f,-0.134575f,-0.990903f},{1.60303e-018f,-0.113491f,-0.993539f},{7.81879e-018f,-0.0902913f,-0.995915f}, -{9.91352e-018f,-0.0774828f,-0.996994f},{1.03021e-017f,-0.0670916f,-0.997747f},{-1.68674e-018f,-0.0438914f,-0.999036f}, -{3.8365e-018f,-0.147436f,-0.989072f},{8.0814e-018f,-0.0206911f,-0.999786f},{8.05703e-018f,-0.160907f,-0.98697f}, -{1.33567e-017f,-0.190446f,-0.981698f},{0.0f,-0.300752f,-0.953702f},{0.0f,-0.299196f,-0.954192f}, -{-9.04092e-018f,-0.266455f,-0.963847f},{3.88234e-018f,-0.25387f,-0.967238f},{-1.05499e-017f,-0.246065f,-0.969253f}, -{3.20684e-018f,-0.294624f,-0.955613f},{-3.12775e-018f,-0.287357f,-0.957824f},{1.04562e-017f,-0.277782f,-0.960644f}, -{1.18742e-017f,-0.240601f,-0.970624f},{-6.77626e-018f,1.0f,1.27676e-015f},{-6.77626e-018f,1.0f,1.27052e-015f}, -{0.0f,1.0f,1.27676e-015f},{-3.2255e-018f,1.0f,1.2844e-015f},{-2.22261e-018f,1.0f,1.27052e-015f}, -{-2.05998e-018f,1.0f,1.27052e-015f},{2.92735e-018f,1.0f,1.2844e-015f},{0.0f,1.0f,1.27052e-015f}, -{1.0f,-2.22045e-016f,0.0f},{1.0f,4.44089e-016f,0.0f},{1.0f,8.88178e-016f,0.0f}, -{0.44501f,-0.895526f,0.0f},{0.287138f,-0.957889f,0.0f},{0.264225f,-0.964461f,0.0f}, -{0.0777153f,-0.996976f,0.0f},{0.484196f,-0.87496f,0.0f},{0.615293f,-0.788298f,0.0f}, -{0.658728f,-0.752381f,0.0f},{0.777371f,-0.629043f,0.0f},{0.803054f,-0.595906f,0.0f}, -{0.899416f,-0.437093f,0.0f},{0.910992f,-0.412424f,0.0f},{0.974657f,-0.223703f,0.0f}, -{0.977683f,-0.210088f,0.0f},{1.0f,1.04131e-014f,0.0f},{1.0f,5.20654e-015f,0.0f}, -{0.62939f,0.77709f,1.00199e-015f},{0.608066f,0.793886f,8.62015e-016f},{0.773996f,0.63319f,7.65657e-016f}, -{1.0f,-6.28037e-016f,-6.81933e-031f},{1.0f,2.51215e-015f,2.72773e-030f},{0.975403f,0.22043f,2.71985e-016f}, -{0.902955f,0.429735f,5.30243e-016f},{0.974096f,0.226136f,2.90187e-016f},{0.89737f,0.44128f,5.88046e-016f}, -{0.786233f,0.61793f,7.01456e-016f},{0.439791f,0.8981f,9.6132e-016f},{0.22612f,0.974099f,1.13394e-015f}, -{0.422231f,0.906488f,1.14646e-015f},{0.216293f,0.976328f,1.13616e-015f},{3.14018e-016f,1.0f,1.18453e-015f}, -{0.0f,0.636824f,0.771009f},{4.41885e-018f,0.636824f,0.771009f},{0.0764224f,-0.976094f,0.203472f}, -{0.0777152f,-0.996976f,2.3946e-009f},{0.0777152f,-0.996976f,1.82309e-009f},{5.69588e-006f,0.0519161f,0.998651f}, -{0.0391237f,-0.456027f,0.889106f},{1.35909e-005f,0.0825944f,0.996583f},{0.0691877f,-0.861638f,0.502785f}, -{0.0509221f,-0.636981f,0.769196f},{0.0777152f,-0.996976f,6.33733e-010f},{0.0777152f,-0.996976f,-2.35021e-015f}, -{0.0749912f,-0.917412f,0.390808f},{0.0700812f,-0.856741f,0.510962f},{0.0305668f,-0.282672f,0.95873f}, -{0.0398436f,-0.436736f,0.898707f},{0.0583498f,-0.663385f,0.746f},{0.0286465f,-0.347654f,0.937185f}, -{0.0674458f,-0.854338f,0.515323f},{1.67095e-011f,0.113462f,0.993542f},{3.90358e-007f,0.0211583f,0.999776f}, -{0.0777152f,-0.996976f,1.22379e-009f},{0.707107f,0.115053f,0.697684f},{0.702691f,-0.041302f,0.710295f}, -{0.918265f,-0.13998f,0.3704f},{0.664219f,-0.196116f,0.721354f},{0.76718f,-0.515388f,0.381851f}, -{0.863385f,-0.335631f,0.376721f},{0.490492f,-0.464798f,0.737143f},{0.467108f,-0.794304f,0.388447f}, -{0.632878f,-0.671315f,0.385748f},{0.0777152f,-0.996976f,8.89301e-008f},{0.289241f,-0.957256f,8.65022e-007f}, -{0.278854f,-0.87754f,0.390082f},{0.256675f,-0.171643f,0.951135f},{0.309894f,-0.101729f,0.945313f}, -{-4.90387e-007f,0.133372f,0.991066f},{0.113588f,-0.26464f,0.957634f},{0.216859f,-0.631152f,0.744728f}, -{0.189962f,-0.227046f,0.955178f},{0.368095f,0.151307f,0.917394f},{0.366433f,0.0644563f,0.928209f}, -{-1.36278e-016f,0.162743f,0.986669f},{-4.77403e-007f,0.152368f,0.988324f},{0.929788f,0.0598835f,0.363191f}, -{0.977729f,-0.20987f,1.07918e-005f},{1.0f,1.37117e-008f,8.31709e-008f},{0.34688f,-0.0217202f,0.937658f}, -{-1.01854e-006f,0.142402f,0.989809f},{0.362795f,-0.563926f,0.741867f},{0.592707f,-0.339591f,0.730326f}, -{-7.18981e-007f,0.115426f,0.993316f},{0.0305691f,-0.282671f,0.95873f},{1.58673e-014f,0.113463f,0.993542f}, -{0.0583523f,-0.663385f,0.746f},{0.911397f,-0.411528f,6.3595e-006f},{0.0749922f,-0.917412f,0.390808f}, -{0.804305f,-0.594217f,4.18309e-006f},{-1.78317e-007f,0.125613f,0.992079f},{0.660117f,-0.751163f,2.58675e-006f}, -{1.33025e-007f,0.11953f,0.992831f},{0.485516f,-0.874228f,4.30103e-007f},{0.929788f,0.0599047f,0.363187f}, -{1.0f,-6.95989e-015f,-4.64483e-014f},{0.87226f,0.0993814f,0.478837f},{2.41719e-015f,0.203217f,0.979134f}, -{0.489042f,0.177258f,0.85406f},{0.87226f,0.119006f,0.474341f},{0.489042f,0.212261f,0.84604f}, -{0.368095f,0.151316f,0.917393f},{0.0f,0.162743f,0.986669f},{0.707107f,0.115076f,0.69768f}, -{0.640795f,0.750862f,0.159966f},{0.633896f,0.690083f,0.34923f},{0.773588f,0.633689f,4.47054e-006f}, -{0.87226f,0.119072f,0.474324f},{0.974072f,0.226237f,4.35889e-005f},{0.89728f,0.441461f,1.9127e-005f}, -{0.831026f,0.314908f,0.458507f},{0.608053f,0.793896f,1.75823e-008f},{0.56074f,0.604452f,0.56587f}, -{0.362672f,0.475573f,0.801436f},{0.412157f,0.425828f,0.805479f},{0.748579f,0.4929f,0.443484f}, -{0.489042f,0.2123f,0.84603f},{0.461687f,0.325164f,0.825296f},{2.66133e-006f,0.271328f,0.962487f}, -{3.42352e-007f,0.262654f,0.96489f},{-1.24911e-015f,0.243346f,0.96994f},{2.24678e-006f,0.253185f,0.967418f}, -{0.0486817f,-0.640323f,-0.766562f},{0.0370848f,-0.513173f,-0.857483f},{0.0666236f,-0.875571f,-0.478474f}, -{0.0775964f,-0.996904f,-0.0127208f},{0.0776561f,-0.996948f,-0.00805679f},{0.0653022f,-0.880476f,-0.469572f}, -{0.0659754f,-0.878213f,-0.473698f},{0.0660304f,-0.857586f,-0.510084f},{0.0777085f,-0.996974f,-0.00192217f}, -{0.0777145f,-0.996976f,-0.00043536f},{0.0758877f,-0.977579f,-0.196417f},{5.59703e-006f,-0.043964f,-0.999033f}, -{0.0257948f,-0.350245f,-0.936303f},{0.0365804f,-0.52637f,-0.849468f},{1.00329e-005f,-0.0672212f,-0.997738f}, -{0.0410888f,-0.616326f,-0.786418f},{0.0665963f,-0.902304f,-0.425926f},{0.036057f,-0.539132f,-0.841449f}, -{4.01696e-007f,-0.0206959f,-0.999786f},{3.419e-007f,-0.113495f,-0.993538f},{0.0776912f,-0.996967f,-0.00445871f}, -{1.17965e-005f,-0.0904433f,-0.995902f},{-6.16506e-018f,0.123071f,-0.992398f},{1.30823e-017f,0.13416f,-0.99096f}, -{4.86852e-018f,0.134575f,-0.990903f},{-8.07206e-018f,0.113491f,-0.993539f},{1.48949e-020f,0.0902913f,-0.995915f}, -{-3.75189e-018f,0.0774828f,-0.996994f},{5.48641e-018f,0.0670916f,-0.997747f},{-2.91677e-017f,0.0438914f,-0.999036f}, -{3.19289e-018f,0.147436f,-0.989072f},{-5.39916e-018f,0.0206911f,-0.999786f},{-1.04945e-017f,0.160907f,-0.98697f}, -{-2.1531e-018f,0.190446f,-0.981698f},{0.0f,0.300752f,-0.953702f},{-1.03859e-017f,0.299196f,-0.954192f}, -{-1.0491e-017f,0.266455f,-0.963847f},{-5.26397e-018f,0.25387f,-0.967238f},{1.44857e-017f,0.246065f,-0.969253f}, -{0.0f,0.294624f,-0.955613f},{1.04255e-017f,0.287357f,-0.957824f},{0.0f,0.277782f,-0.960644f}, -{5.2824e-018f,0.240601f,-0.970624f},{0.0f,-0.271326f,0.962488f},{0.0f,-0.253151f,0.967427f}, -{0.0f,-0.26258f,0.96491f},{0.0f,-0.147431f,0.989072f},{0.0f,-0.162743f,0.986669f}, -{0.0f,-0.209863f,0.977731f},{0.0f,-0.243346f,0.96994f},{0.0f,-0.20324f,0.979129f}, -{0.0f,-0.0844041f,0.996432f},{0.0f,-0.0211631f,0.999776f},{0.0f,-0.0519304f,0.998651f}, -{0.0f,-0.0826965f,0.996575f},{0.0f,-0.113463f,0.993542f},{0.0f,-0.115523f,0.993305f}, -{0.0f,-0.119556f,0.992828f},{0.0f,-0.125642f,0.992076f},{0.0f,-0.133401f,0.991062f}, -{0.0f,-0.142437f,0.989804f},{0.0f,-0.152342f,0.988328f},{0.0f,-1.0f,-1.26288e-015f}, -{0.0f,-1.0f,-1.26775e-015f},{-1.0f,-1.77636e-015f,0.0f},{-0.44501f,0.895526f,0.0f}, -{-0.287142f,0.957888f,0.0f},{-0.264225f,0.964461f,0.0f},{-0.0777153f,0.996976f,0.0f}, -{-0.484193f,0.874961f,0.0f},{-0.615293f,0.788298f,0.0f},{-0.658731f,0.752379f,0.0f}, -{-0.777371f,0.629043f,0.0f},{-0.803054f,0.595907f,0.0f},{-0.899416f,0.437093f,0.0f}, -{-0.910997f,0.412414f,0.0f},{-0.974657f,0.223703f,0.0f},{-0.977682f,0.210092f,0.0f}, -{-1.0f,-1.04131e-014f,0.0f},{-1.0f,-5.20654e-015f,0.0f},{-0.608066f,-0.793886f,-1.01875e-015f}, -{-0.773996f,-0.63319f,-7.50031e-016f},{-0.62939f,-0.77709f,-9.20484e-016f},{-0.89737f,-0.44128f,-5.60822e-016f}, -{-0.786233f,-0.61793f,-7.31954e-016f},{-0.975403f,-0.22043f,-2.72665e-016f},{-0.902955f,-0.429735f,-5.0373e-016f}, -{-0.974096f,-0.226136f,-2.80072e-016f},{-0.439791f,-0.8981f,-1.24113e-015f},{-0.22612f,-0.974099f,-1.15385e-015f}, -{-0.422231f,-0.906488f,-1.07376e-015f},{-0.216293f,-0.976328f,-1.15649e-015f},{-3.14018e-016f,-1.0f,-1.18453e-015f}, -{-4.24524e-018f,-0.636824f,0.771009f},{9.31099e-019f,-0.636824f,0.771009f},{-5.78592e-018f,-0.636824f,0.771009f}, -{-5.00079e-018f,-0.636824f,0.771009f},{0.0f,-0.636824f,0.771009f},{1.67186e-018f,-0.636824f,0.771009f}, -{4.01246e-018f,-0.636824f,0.771009f},{2.67498e-018f,-0.636824f,0.771009f},{5.34995e-018f,-0.636824f,0.771009f}, -{-2.00623e-018f,-0.636824f,0.771009f},{-3.77969e-018f,-0.636824f,0.771009f},{-2.75858e-018f,-0.636824f,0.771009f}, -{2.26987e-019f,-0.636824f,0.771009f},{-5.34995e-018f,-0.636824f,0.771009f},{2.20943e-018f,-0.636824f,0.771009f}, -{-0.076394f,0.975689f,0.205416f},{-0.0777152f,0.996976f,2.40026e-009f},{-0.0777152f,0.996976f,1.82763e-009f}, -{-5.69588e-006f,-0.0519161f,0.998651f},{-0.0391237f,0.456027f,0.889106f},{-1.3591e-005f,-0.0825944f,0.996583f}, -{-0.0691877f,0.861638f,0.502785f},{-0.050805f,0.635452f,0.770467f},{-0.0777152f,0.996976f,6.35071e-010f}, -{-0.0777152f,0.996976f,1.31007e-017f},{-0.0749912f,0.917412f,0.390808f},{-0.0700812f,0.856741f,0.510962f}, -{-0.0305668f,0.282672f,0.95873f},{-0.0398436f,0.436736f,0.898707f},{-0.0583498f,0.663385f,0.746f}, -{-0.0285025f,0.345792f,0.937878f},{-0.0673689f,0.853315f,0.517025f},{-1.67093e-011f,-0.113462f,0.993542f}, -{-3.90359e-007f,-0.0211583f,0.999776f},{-0.0777152f,0.996976f,1.22684e-009f},{-0.362409f,0.564161f,0.741878f}, -{-0.112973f,0.264855f,0.957648f},{-0.215685f,0.631536f,0.744744f},{-0.659094f,0.75206f,-1.94181e-007f}, -{-0.631911f,0.672214f,0.385768f},{-0.466608f,0.794595f,0.388454f},{-0.803414f,0.595421f,4.71637e-006f}, -{-0.0749922f,0.917412f,0.390808f},{-0.28767f,0.95773f,5.42362e-007f},{-0.277342f,0.878015f,0.390091f}, -{-0.346813f,0.0219211f,0.937678f},{1.10489e-006f,-0.133312f,0.991074f},{-0.309574f,0.102261f,0.94536f}, -{-0.0777152f,0.996976f,-3.03639e-015f},{-0.702528f,0.0424957f,0.710387f},{-0.929788f,-0.0598835f,0.363191f}, -{-0.707107f,-0.115053f,0.697684f},{-0.911187f,0.411994f,8.1719e-006f},{-0.863203f,0.336083f,0.376735f}, -{-0.766361f,0.516581f,0.381883f},{-0.918012f,0.141492f,0.37045f},{-0.664088f,0.196474f,0.721378f}, -{4.30608e-007f,-0.152291f,0.988336f},{7.6959e-007f,-0.142379f,0.989812f},{-0.366351f,-0.0637951f,0.928287f}, -{-0.48975f,0.465521f,0.73718f},{-0.18976f,0.227177f,0.955187f},{-0.368095f,-0.151307f,0.917394f}, -{1.2436e-015f,-0.162743f,0.986669f},{-0.484991f,0.874519f,1.45876e-006f},{-0.0583523f,0.663385f,0.746f}, -{-0.0305691f,0.282671f,0.95873f},{5.79189e-014f,-0.113463f,0.993542f},{9.38329e-007f,-0.115403f,0.993319f}, -{-0.256288f,0.172046f,0.951166f},{3.02192e-008f,-0.119516f,0.992832f},{-3.80451e-007f,-0.125569f,0.992085f}, -{-0.59209f,0.340547f,0.730382f},{-0.977393f,0.21143f,5.28771e-006f},{-0.929788f,-0.0599047f,0.363187f}, -{-1.0f,6.95989e-015f,-4.64483e-014f},{-0.87226f,-0.0993814f,0.478837f},{-1.63982e-015f,-0.203217f,0.979134f}, -{-0.489042f,-0.177258f,0.85406f},{-0.87226f,-0.119006f,0.474341f},{-0.489042f,-0.212261f,0.84604f}, -{-0.368095f,-0.151316f,0.917393f},{-3.30488e-015f,-0.162743f,0.986669f},{-0.707107f,-0.115076f,0.69768f}, -{-0.640795f,-0.750862f,0.159966f},{-0.633896f,-0.690083f,0.34923f},{-0.773588f,-0.633689f,4.47054e-006f}, -{-0.87226f,-0.119072f,0.474324f},{-0.974072f,-0.226237f,4.35889e-005f},{-0.89728f,-0.441461f,1.9127e-005f}, -{-0.831026f,-0.314908f,0.458507f},{-0.608053f,-0.793896f,1.75822e-008f},{-0.56074f,-0.604452f,0.56587f}, -{-0.362672f,-0.475573f,0.801436f},{-0.412157f,-0.425828f,0.805479f},{-0.748579f,-0.4929f,0.443484f}, -{-0.489042f,-0.2123f,0.84603f},{-0.461687f,-0.325164f,0.825296f},{-2.66133e-006f,-0.271328f,0.962487f}, -{-3.42352e-007f,-0.262654f,0.96489f},{-1.05425e-016f,-0.243346f,0.96994f},{-2.24678e-006f,-0.253185f,0.967418f}, -{-0.0666236f,0.875571f,-0.478474f},{-0.0486817f,0.640323f,-0.766562f},{-0.0370848f,0.513173f,-0.857483f}, -{-0.0257948f,0.350245f,-0.936303f},{-4.01482e-007f,0.0206959f,-0.999786f},{-5.59705e-006f,0.0439641f,-0.999033f}, -{-0.0410888f,0.616326f,-0.786418f},{-0.036057f,0.539132f,-0.841449f},{-3.41892e-007f,0.113495f,-0.993538f}, -{-0.0653022f,0.880476f,-0.469573f},{-0.0776561f,0.996948f,-0.00805682f},{-0.0659754f,0.878213f,-0.473698f}, -{-0.0665963f,0.902304f,-0.425926f},{-0.0775964f,0.996904f,-0.0127207f},{-0.0776912f,0.996967f,-0.00445868f}, -{-0.0660304f,0.857586f,-0.510084f},{-0.0365804f,0.52637f,-0.849468f},{-0.0777085f,0.996974f,-0.00192216f}, -{-0.0777145f,0.996976f,-0.000435368f},{-0.0758877f,0.977579f,-0.196417f},{-1.00329e-005f,0.0672213f,-0.997738f}, -{-1.17964e-005f,0.0904433f,-0.995902f},{0.970979f,-0.239165f,0.0f},{1.0f,-2.21189e-011f,0.0f}, -{0.35609f,-0.934452f,0.0f},{0.569129f,-0.822248f,0.0f},{0.568041f,-0.823f,0.0f}, -{0.885313f,-0.464996f,0.0f},{0.74925f,-0.662288f,0.0f},{0.885933f,-0.463813f,0.0f}, -{-0.119912f,-0.992785f,0.0f},{-0.354158f,-0.935185f,0.0f},{-0.120012f,-0.992772f,0.0f}, -{0.355204f,-0.934789f,0.0f},{0.120803f,-0.992676f,0.0f},{0.12127f,-0.99262f,0.0f}, -{-0.567216f,-0.823569f,0.0f},{-0.7483f,-0.663361f,0.0f},{-0.567703f,-0.823234f,0.0f}, -{-0.353989f,-0.935249f,0.0f},{-0.748241f,-0.663427f,0.0f},{-0.885185f,-0.465239f,0.0f}, -{-0.885281f,-0.465056f,0.0f},{-0.970894f,-0.239511f,0.0f},{-0.970844f,-0.239712f,0.0f}, -{0.748446f,-0.663196f,0.0f},{0.971139f,-0.238516f,0.0f},{0.0f,1.11022e-016f,-1.0f}, -{0.0f,-1.11022e-016f,-1.0f},{0.0f,-5.55112e-017f,-1.0f},{0.0f,5.55112e-017f,-1.0f}, -{1.0f,-1.38778e-017f,0.0f},{0.959454f,-0.281866f,3.5075e-017f},{0.959948f,-0.28018f,-4.21701e-019f}, -{0.142833f,-0.989747f,2.49501e-017f},{0.415948f,-0.909389f,-1.25209e-017f},{0.413963f,-0.910294f,-4.85725e-018f}, -{0.655247f,-0.755415f,1.3143e-017f},{0.844985f,-0.53479f,1.81431e-018f},{0.840053f,-0.542504f,1.76327e-018f}, -{-0.413963f,-0.910294f,-1.17305e-017f},{-0.142833f,-0.989747f,2.30199e-017f},{-0.415948f,-0.909389f,2.57792e-017f}, -{0.141528f,-0.989934f,-9.05295e-018f},{-0.141527f,-0.989934f,2.56689e-017f},{-0.840053f,-0.542504f,-5.88236e-019f}, -{-0.655247f,-0.755415f,2.43207e-017f},{-0.844985f,-0.53479f,-3.19936e-017f},{-0.655503f,-0.755193f,8.23455e-018f}, -{-0.959948f,-0.28018f,3.039e-017f},{-0.959454f,-0.281866f,-5.9836e-018f},{0.655503f,-0.755193f,1.3143e-017f}, -{0.962605f,-0.270909f,0.0f},{1.0f,-4.07586e-012f,0.0f},{0.309304f,-0.950963f,0.0f}, -{0.588229f,-0.808694f,0.0f},{0.409074f,-0.912501f,0.0f},{0.650924f,-0.759143f,0.0f}, -{0.811958f,-0.583716f,0.0f},{0.840179f,-0.542309f,0.0f},{-0.307814f,-0.951446f,0.0f}, -{-0.424076f,-0.905627f,0.0f},{-0.587751f,-0.809042f,0.0f},{0.134185f,-0.990956f,0.0f}, -{-0.152115f,-0.988363f,0.0f},{2.72147e-017f,-1.0f,0.0f},{-0.807656f,-0.589654f,0.0f}, -{-0.662432f,-0.749122f,0.0f},{-0.846367f,-0.5326f,0.0f},{-0.961254f,-0.275665f,0.0f}, -{-0.950842f,-0.309676f,0.0f},{0.952103f,-0.305779f,0.0f},{0.962289f,-0.272029f,0.0f}, -{1.0f,5.92119e-016f,0.0f},{1.0f,-1.60011e-012f,0.0f},{0.410952f,-0.911657f,0.0f}, -{0.650115f,-0.759835f,0.0f},{0.84148f,-0.540288f,0.0f},{-0.149984f,-0.988688f,0.0f}, -{-0.424076f,-0.905627f,0.0f},{0.137383f,-0.990518f,0.0f},{-0.661313f,-0.75011f,0.0f}, -{-0.844868f,-0.534974f,0.0f},{-0.960674f,-0.277678f,0.0f},{-1.0f,-1.19209e-007f,0.0f}, -{-0.988362f,0.152121f,0.0f},{-1.0f,1.20609e-016f,0.0f},{-0.990957f,-0.134181f,0.0f}, -{-0.905627f,0.424076f,0.0f},{-0.951446f,0.307814f,0.0f},{-0.809042f,0.587751f,0.0f}, -{-0.749088f,0.66247f,0.0f},{-0.309676f,0.950842f,0.0f},{-0.589654f,0.807656f,0.0f}, -{-0.532573f,0.846384f,0.0f},{-0.275761f,0.961226f,0.0f},{6.66134e-016f,1.0f,0.0f}, -{-0.950963f,-0.309304f,0.0f},{-0.912502f,-0.409073f,0.0f},{-0.808694f,-0.588229f,0.0f}, -{-0.583716f,-0.811958f,0.0f},{-0.759164f,-0.6509f,0.0f},{-0.305779f,-0.952103f,0.0f}, -{-0.542323f,-0.84017f,0.0f},{-0.270837f,-0.962625f,0.0f},{1.18424e-015f,-1.0f,0.0f}, -{-1.11022e-015f,-1.0f,0.0f},{-0.948416f,0.317028f,0.0f},{-0.804232f,0.594315f,0.0f}, -{-0.582662f,0.812715f,0.0f},{-0.305357f,0.952238f,0.0f},{-0.999985f,0.00550409f,0.0f}, -{-1.4803e-016f,1.0f,0.0f},{-1.19209e-007f,1.0f,0.0f},{-1.0f,-5.5717e-017f,0.0f}, -{-0.951973f,-0.306183f,0.0f},{-0.811248f,-0.584702f,0.0f},{-0.589388f,-0.80785f,0.0f}, -{-0.299688f,-0.954037f,0.0f},{5.92119e-016f,-1.0f,0.0f},{6.66134e-016f,-1.0f,0.0f}, -{-1.0f,3.70074e-017f,3.42388e-034f},{-0.951446f,-0.307814f,5.69571e-018f},{-1.0f,4.16334e-017f,3.85186e-034f}, -{-0.809042f,0.587751f,2.78932e-017f},{-0.950963f,0.309304f,3.37619e-017f},{-0.808694f,0.588229f,1.0203e-017f}, -{-0.951446f,0.307814f,-2.84786e-018f},{-0.589654f,0.807656f,7.32347e-018f},{-0.305779f,0.952103f,-2.03109e-017f}, -{1.4803e-016f,1.0f,0.0f},{-0.309676f,0.950842f,-7.83488e-018f},{-0.583716f,0.811958f,-2.06583e-017f}, -{1.66533e-016f,1.0f,0.0f},{-0.809042f,-0.587751f,-1.49703e-017f},{-0.808694f,-0.588229f,-1.08844e-017f}, -{-0.583716f,-0.811958f,-3.00485e-017f},{-0.589654f,-0.807656f,-1.09108e-017f},{-0.305779f,-0.952103f,0.0f}, -{-0.309676f,-0.950842f,0.0f},{6.93889e-017f,-1.0f,0.0f},{-0.822897f,0.568191f,0.0f}, -{-0.935249f,0.353989f,0.0f},{-0.935058f,0.354494f,0.0f},{-0.992772f,0.120012f,0.0f}, -{-0.823234f,0.567703f,0.0f},{-0.992699f,0.120619f,0.0f},{-0.663427f,0.748241f,0.0f}, -{-0.662949f,0.748664f,0.0f},{-0.465056f,0.885281f,0.0f},{-0.992744f,-0.12025f,0.0f}, -{-0.46429f,0.885683f,0.0f},{-0.239511f,0.970894f,0.0f},{-8.88178e-017f,1.0f,0.0f}, -{-0.239079f,0.971f,0.0f},{-0.99262f,-0.12127f,0.0f},{-0.934452f,-0.35609f,0.0f}, -{-0.935095f,-0.354397f,0.0f},{-0.823076f,-0.567931f,0.0f},{-0.822248f,-0.569129f,0.0f}, -{-0.662288f,-0.74925f,0.0f},{-0.663484f,-0.748191f,0.0f},{-0.463813f,-0.885933f,0.0f}, -{-0.465389f,-0.885106f,0.0f},{-0.23961f,-0.970869f,0.0f},{-0.238516f,-0.971139f,0.0f}, -{-1.45407e-013f,-1.0f,0.0f},{-2.2119e-011f,-1.0f,0.0f},{0.224573f,0.0806869f,-0.971111f}, -{0.167824f,0.115976f,-0.978971f},{0.206583f,0.0936942f,-0.973933f},{-0.00431306f,0.212777f,-0.977091f}, -{0.0544436f,0.17217f,-0.983562f},{0.0150728f,0.210353f,-0.977509f},{-0.000588626f,0.24749f,-0.96889f}, -{0.0534267f,0.200182f,-0.978301f},{0.0200864f,0.239984f,-0.970569f},{-0.00860874f,0.0134776f,-0.999872f}, -{-0.0575724f,0.0558224f,-0.996779f},{-0.0251275f,0.0228466f,-0.999423f},{0.119876f,0.131908f,-0.983987f}, -{0.114692f,0.135331f,-0.98414f},{0.0967618f,0.106577f,-0.989585f},{0.127645f,0.127565f,-0.983582f}, -{-0.0682479f,0.0434816f,-0.99672f},{-0.0621953f,0.0416591f,-0.997194f},{-0.102888f,0.0678076f,-0.992379f}, -{0.00861069f,-0.0134804f,-0.999872f},{0.0575731f,-0.0558295f,-0.996779f},{0.0251269f,-0.0228463f,-0.999423f}, -{-0.0700992f,0.042481f,-0.996635f},{-0.0679419f,0.0389583f,-0.996928f},{-0.0653011f,0.0312083f,-0.997377f}, -{-0.0236813f,-0.0488646f,-0.998525f},{-0.00381403f,-0.0123869f,-0.999916f},{-0.136635f,-0.122955f,-0.982961f}, -{-0.15616f,-0.0744603f,-0.984921f},{-0.146051f,-0.11848f,-0.982157f},{-0.0534268f,-0.20018f,-0.978301f}, -{-0.0200864f,-0.239985f,-0.970569f},{0.000588612f,-0.247488f,-0.968891f},{0.0374113f,-0.0911775f,-0.995132f}, -{-0.091503f,-0.164561f,-0.982113f},{-0.129057f,-0.132869f,-0.982695f},{-0.138732f,-0.128065f,-0.982015f}, -{0.0201007f,-0.253059f,-0.967242f},{-0.0338838f,-0.207008f,-0.977752f},{-0.206583f,-0.0937007f,-0.973932f}, -{-0.149271f,-0.126712f,-0.980644f},{-0.164764f,-0.113835f,-0.979742f},{-0.224573f,-0.0806854f,-0.971111f}, -{-0.167824f,-0.115975f,-0.978971f},{-0.282538f,-0.0476595f,-0.958071f},{-0.245617f,-0.0601369f,-0.9675f}, -{-0.189505f,-0.099067f,-0.976869f},{-0.300652f,-0.0257387f,-0.953386f},{-0.189498f,-0.0999932f,-0.976776f}, -{-0.173184f,-0.108516f,-0.978893f},{-0.17428f,-0.107387f,-0.978823f},{-0.110576f,-0.155908f,-0.981563f}, -{-0.172359f,-0.107733f,-0.979125f},{-0.233122f,-0.0781727f,-0.9693f},{-0.0246582f,0.00667651f,-0.999674f}, -{-0.0396375f,0.0165896f,-0.999076f},{-0.17193f,-0.105383f,-0.979456f},{-0.0809495f,0.0619015f,-0.994794f}, -{0.0847504f,0.00832976f,-0.996367f},{0.126144f,-0.0744356f,-0.989215f},{0.145127f,-0.0300614f,-0.988956f}, -{0.068248f,-0.0434816f,-0.99672f},{0.102888f,-0.0678076f,-0.992379f},{0.0700993f,-0.0424824f,-0.996635f}, -{-0.0400397f,0.0309353f,-0.998719f},{0.171931f,0.105381f,-0.979456f},{0.146014f,0.118496f,-0.98216f}, -{0.156159f,0.0744765f,-0.98492f},{0.00830625f,0.00348893f,-0.999959f},{0.00381472f,0.0123794f,-0.999916f}, -{0.110247f,0.139631f,-0.984047f},{0.112341f,0.139617f,-0.983812f},{0.0732426f,0.168792f,-0.982927f}, -{0.123518f,0.135427f,-0.983058f},{0.131651f,0.131599f,-0.982522f},{-0.0391961f,0.255848f,-0.965922f}, -{0.189505f,0.0990662f,-0.976869f},{0.033884f,0.207001f,-0.977754f},{0.300652f,0.0257381f,-0.953386f}, -{0.245617f,0.0601361f,-0.9675f},{0.282538f,0.0476609f,-0.958071f},{0.168871f,0.108819f,-0.979613f}, -{0.233124f,0.0781673f,-0.9693f},{0.172348f,0.107726f,-0.979128f},{0.249664f,0.071609f,-0.965681f}, -{0.189499f,0.0999793f,-0.976777f},{-0.0228704f,0.18367f,-0.982722f},{0.0368726f,0.143043f,-0.989029f}, -{0.039638f,-0.0165949f,-0.999076f},{0.0653017f,-0.031216f,-0.997377f},{0.116935f,0.138156f,-0.983483f}, -{0.110576f,0.15591f,-0.981563f},{0.0760762f,0.189495f,-0.97893f},{-0.0201006f,0.253055f,-0.967243f}, -{0.164768f,0.113819f,-0.979743f},{0.169985f,0.110674f,-0.979212f},{0.13279f,0.142319f,-0.980873f}, -{0.265747f,0.0638565f,-0.961926f},{0.162971f,0.111105f,-0.980355f},{0.155086f,0.11444f,-0.98125f}, -{0.217303f,0.0654512f,-0.973907f},{0.13662f,0.122963f,-0.982962f},{0.0621948f,-0.0416577f,-0.997194f}, -{0.0809495f,-0.0619016f,-0.994794f},{-0.126144f,0.074428f,-0.989216f},{-0.0967627f,-0.10656f,-0.989587f}, -{-0.145128f,0.030073f,-0.988956f},{-0.119253f,-0.132285f,-0.984012f},{-0.127694f,-0.127537f,-0.98358f}, -{-0.173544f,0.112261f,-0.978407f},{-0.194823f,0.114801f,-0.974097f},{-0.0525697f,0.037314f,-0.99792f}, -{-0.153096f,0.107531f,-0.982343f},{-0.132768f,0.102693f,-0.985813f},{0.0236802f,0.0488762f,-0.998524f}, -{-0.0374122f,0.0911884f,-0.995131f},{0.207914f,-0.0343818f,-0.977543f},{0.194823f,-0.114804f,-0.974097f}, -{0.173544f,-0.112265f,-0.978406f},{0.153096f,-0.10753f,-0.982344f},{0.0525692f,-0.0373124f,-0.99792f}, -{0.0400395f,-0.0309343f,-0.998719f},{0.132768f,-0.102696f,-0.985812f},{-0.00830612f,-0.00349236f,-0.999959f}, -{-0.0368738f,-0.143026f,-0.989032f},{-0.0544429f,-0.172172f,-0.983561f},{-0.16898f,-0.108774f,-0.979599f}, -{-0.249662f,-0.0716214f,-0.965681f},{-0.169978f,-0.110692f,-0.979211f},{0.0228691f,-0.183652f,-0.982725f}, -{-0.16297f,-0.111114f,-0.980354f},{-0.155082f,-0.114446f,-0.98125f},{-0.0847515f,-0.00831784f,-0.996367f}, -{-0.0524475f,0.0256814f,-0.998293f},{-0.0620644f,0.0332888f,-0.997517f},{0.0043133f,-0.212779f,-0.977091f}, -{-0.0732415f,-0.168808f,-0.982924f},{-0.120661f,-0.136682f,-0.983239f},{-0.114346f,-0.139069f,-0.983659f}, -{-0.0150721f,-0.210368f,-0.977506f},{-0.15764f,-0.117902f,-0.980433f},{0.149271f,0.126705f,-0.980645f}, -{0.0915033f,0.164554f,-0.982115f},{0.157641f,0.117888f,-0.980434f},{0.140533f,0.127125f,-0.981881f}, -{0.149416f,0.122423f,-0.981166f},{0.173236f,0.108474f,-0.978889f},{-0.0589452f,0.257551f,-0.964465f}, -{0.174359f,0.107335f,-0.978815f},{-0.0787303f,0.239876f,-0.967606f},{-0.0943229f,0.151587f,-0.983933f}, -{0.110958f,0.138183f,-0.984172f},{0.0246587f,-0.00668129f,-0.999674f},{-0.111226f,0.0971757f,-0.989033f}, -{0.0524476f,-0.0256865f,-0.998293f},{0.067942f,-0.0389615f,-0.996928f},{0.0620642f,-0.033293f,-0.997517f}, -{-0.207915f,0.0343964f,-0.977542f},{-0.113842f,-0.135944f,-0.984154f},{0.111227f,-0.097181f,-0.989032f}, -{-0.217303f,-0.065439f,-0.973908f},{-0.110719f,-0.139838f,-0.983965f},{-0.110345f,-0.13881f,-0.984152f}, -{0.0787291f,-0.239861f,-0.96761f},{0.0943219f,-0.151574f,-0.983935f},{0.0589451f,-0.257556f,-0.964464f}, -{0.0391964f,-0.255863f,-0.965918f},{-0.265747f,-0.0638606f,-0.961925f},{-0.148539f,-0.122911f,-0.981239f}, -{-0.0760762f,-0.189496f,-0.97893f},{-0.13279f,-0.14232f,-0.980873f},{0.780986f,-0.410005f,0.471123f}, -{0.756474f,-0.431924f,0.491109f},{0.879699f,-0.406453f,0.246832f},{0.738683f,-0.444614f,0.506622f}, -{0.85525f,-0.428298f,0.291734f},{0.718444f,-0.420701f,0.553939f},{0.815118f,-0.415692f,0.403464f}, -{0.721373f,-0.437394f,0.536943f},{0.824692f,-0.430102f,0.367282f},{0.838017f,-0.434004f,0.330708f}, -{0.728083f,-0.44473f,0.521641f},{0.797562f,-0.268829f,0.540024f},{0.722769f,-0.258175f,0.641055f}, -{0.774815f,-0.275537f,0.568982f},{0.728926f,-0.352408f,0.58692f},{0.733033f,-0.277529f,0.620999f}, -{0.816277f,-0.28748f,0.501046f},{0.689892f,-0.249748f,0.679467f},{0.725361f,-0.215302f,0.653833f}, -{0.738897f,-0.256534f,0.623074f},{0.698996f,-0.261868f,0.665454f},{0.755933f,-0.271108f,0.595873f}, -{0.709599f,-0.264635f,0.653021f},{0.683243f,0.0526752f,0.728289f},{0.696338f,0.0541363f,0.715669f}, -{0.667359f,0.0539424f,0.74278f},{0.716045f,-0.0721475f,0.694315f},{0.683867f,-0.211833f,0.698178f}, -{0.680519f,-0.0718111f,0.729203f},{0.660486f,0.052782f,0.748981f},{0.671599f,0.0443778f,0.739585f}, -{0.654656f,0.0438809f,0.754652f},{0.660388f,0.0375909f,0.749983f},{0.649023f,0.0241761f,0.760385f}, -{0.648963f,0.0363458f,0.759951f},{0.643221f,0.022026f,0.765363f},{0.636811f,0.00631787f,0.770994f}, -{0.636821f,0.0031649f,0.771005f},{0.818732f,-0.355684f,0.45074f},{0.909063f,-0.371045f,0.18955f}, -{0.583044f,-0.405078f,0.704253f},{0.580905f,-0.421979f,0.696048f},{0.756391f,-0.431996f,0.491175f}, -{0.581257f,-0.432024f,0.689562f},{0.738684f,-0.444614f,0.506621f},{0.728943f,-0.352294f,0.586967f}, -{0.718445f,-0.420702f,0.553937f},{0.59918f,-0.410108f,0.687601f},{0.721374f,-0.437394f,0.536941f}, -{0.728085f,-0.44473f,0.521639f},{0.585021f,-0.431774f,0.686528f},{0.722817f,-0.258155f,0.641008f}, -{0.63406f,-0.239661f,0.735208f},{0.709547f,-0.264648f,0.653073f},{0.618695f,-0.336563f,0.709888f}, -{0.632115f,-0.25777f,0.730743f},{0.733036f,-0.27756f,0.620982f},{0.634072f,-0.238256f,0.735654f}, -{0.683867f,-0.211913f,0.698154f},{0.689931f,-0.249749f,0.679427f},{0.633237f,-0.246966f,0.733498f}, -{0.698956f,-0.261827f,0.665513f},{0.633257f,-0.24717f,0.733412f},{0.660487f,0.0527819f,0.74898f}, -{0.667343f,0.0540166f,0.742789f},{0.634508f,0.0563396f,0.77086f},{0.680531f,-0.0720207f,0.729171f}, -{0.636975f,-0.204102f,0.743375f},{0.640402f,-0.0680582f,0.765018f},{0.63474f,0.055102f,0.770759f}, -{0.654657f,0.0438808f,0.754651f},{0.635485f,0.0454974f,0.770772f},{0.648964f,0.0363458f,0.759951f}, -{0.643198f,0.0219575f,0.765385f},{0.63602f,0.0371135f,0.77078f},{0.636578f,0.0218202f,0.770903f}, -{0.636823f,0.0020686f,0.771008f},{0.590849f,-0.425392f,0.685521f},{0.325002f,-0.355736f,0.876256f}, -{0.358337f,-0.376871f,0.854144f},{0.5809f,-0.422036f,0.696018f},{0.386348f,-0.390634f,0.835548f}, -{0.618721f,-0.336442f,0.709923f},{0.59918f,-0.410108f,0.687601f},{0.46456f,-0.370105f,0.804491f}, -{0.412203f,-0.394435f,0.821285f},{0.437394f,-0.392371f,0.809155f},{0.634063f,-0.239634f,0.735214f}, -{0.539451f,-0.218199f,0.813254f},{0.633254f,-0.24719f,0.733407f},{0.497609f,-0.276989f,0.821986f}, -{0.522063f,-0.210792f,0.826449f},{0.632111f,-0.257804f,0.730734f},{0.595637f,-0.110113f,0.795671f}, -{0.63697f,-0.204172f,0.743359f},{0.580852f,-0.223171f,0.782819f},{0.634073f,-0.238249f,0.735655f}, -{0.633239f,-0.246939f,0.733505f},{0.567772f,-0.224079f,0.792101f},{0.63474f,0.055102f,0.770759f}, -{0.634503f,0.0564151f,0.770859f},{0.606196f,0.0620428f,0.792892f},{0.640405f,-0.0682671f,0.764997f}, -{0.59941f,0.0414768f,0.799366f},{0.614526f,0.0507293f,0.787264f},{0.635485f,0.0454974f,0.770772f}, -{0.622011f,0.0411515f,0.781926f},{0.63658f,0.0217483f,0.770904f},{0.629429f,0.024754f,0.776664f}, -{0.636821f,0.0031651f,0.771005f},{0.554028f,-0.226089f,0.80121f},{0.018211f,-0.260709f,0.965246f}, -{0.0905301f,-0.29234f,0.95202f},{0.35848f,-0.376958f,0.854046f},{0.412236f,-0.394436f,0.821268f}, -{0.386367f,-0.39064f,0.835537f},{0.150845f,-0.316442f,0.936541f},{0.497587f,-0.27707f,0.821973f}, -{0.464644f,-0.369949f,0.804515f},{0.302136f,-0.326359f,0.895658f},{0.43742f,-0.392367f,0.809143f}, -{0.203847f,-0.331158f,0.921293f},{0.539469f,-0.218211f,0.813239f},{0.436519f,-0.186125f,0.880232f}, -{0.554148f,-0.226126f,0.801116f},{0.351848f,-0.234204f,0.906284f},{0.39662f,-0.172939f,0.901546f}, -{0.521912f,-0.210966f,0.826499f},{0.526859f,-0.205901f,0.824636f},{0.595587f,-0.110847f,0.795606f}, -{0.580769f,-0.223412f,0.782812f},{0.499197f,-0.202182f,0.842571f},{0.567787f,-0.224072f,0.792092f}, -{0.469626f,-0.198592f,0.86024f},{0.579246f,0.0682852f,0.812288f},{0.606222f,0.0620078f,0.792874f}, -{0.564062f,0.0488013f,0.824289f},{0.599414f,0.0416336f,0.799355f},{0.5515f,-0.0985182f,0.828337f}, -{0.594988f,0.056183f,0.801768f},{0.614534f,0.0507196f,0.787258f},{0.622016f,0.0411442f,0.781923f}, -{0.609128f,0.0457027f,0.791754f},{0.622938f,0.0285242f,0.781751f},{0.629464f,0.0246587f,0.776638f}, -{0.636811f,0.00635625f,0.770994f},{0.25357f,-0.340146f,0.90554f},{0.608772f,0.0457539f,0.792025f}, -{0.594765f,0.055249f,0.801999f},{0.608898f,0.0450032f,0.791971f},{0.622817f,0.0284547f,0.78185f}, -{0.622836f,0.0279898f,0.781851f},{0.562516f,0.0688727f,0.823913f},{0.563156f,0.0490876f,0.824891f}, -{0.550993f,-0.0496963f,0.833029f},{0.578569f,0.0683527f,0.812765f},{0.579246f,0.0665103f,0.812435f}, -{0.594461f,0.0562578f,0.802154f},{0.468103f,-0.198149f,0.861172f},{0.472958f,-0.198042f,0.85854f}, -{0.497665f,-0.201746f,0.84358f},{0.525395f,-0.205766f,0.825603f},{0.529826f,-0.175094f,0.829835f}, -{0.550287f,-0.0989846f,0.829087f},{0.361545f,-0.181766f,0.914465f},{0.394113f,-0.172451f,0.902738f}, -{0.349592f,-0.233674f,0.907294f},{0.441329f,-0.188934f,0.87723f},{0.434558f,-0.185572f,0.881319f}, -{0.40436f,-0.174204f,0.897856f},{0.265363f,-0.331082f,0.90552f},{0.251639f,-0.339571f,0.906294f}, -{0.216776f,-0.33003f,0.918743f},{0.30016f,-0.32564f,0.896584f},{0.314928f,-0.257875f,0.913412f}, -{0.16631f,-0.31893f,0.933073f},{0.202144f,-0.33061f,0.921865f},{0.149463f,-0.315979f,0.936919f}, -{0.112599f,-0.302605f,0.946442f},{0.0899699f,-0.292181f,0.952122f},{0.0515423f,-0.277704f,0.959283f}, -{-0.0205104f,-0.246428f,0.968944f},{0.50237f,-0.199807f,0.84125f},{0.636809f,0.00685645f,0.770991f}, -{-0.109551f,-0.170684f,0.979217f},{-0.0629021f,-0.206616f,0.976398f},{-0.126478f,-0.158053f,0.979297f}, -{-0.173613f,-0.129887f,0.976211f},{-0.190018f,-0.114756f,0.975051f},{-0.239086f,-0.0931162f,0.966523f}, -{-0.208979f,-0.0916011f,0.973621f},{-0.25458f,-0.0745052f,0.964177f},{-0.146005f,-0.13862f,0.979524f}, -{-0.270988f,-0.0499282f,0.961287f},{-0.0935066f,-0.176521f,0.979845f},{-0.0771143f,-0.180908f,0.980472f}, -{-0.0289222f,-0.221759f,0.974672f},{-0.00236958f,-0.258471f,0.966016f},{0.0158869f,-0.114433f,0.993304f}, -{0.00500348f,-0.212524f,0.977143f},{-0.0517682f,-0.0688181f,0.996285f},{0.0489217f,-0.273986f,0.960489f}, -{0.0316006f,-0.271537f,0.961909f},{-0.0119369f,-0.225011f,0.974283f},{0.0491747f,-0.0428923f,0.997869f}, -{7.949e-008f,-8.55582e-007f,1.0f},{0.0683324f,-0.0482005f,0.996498f},{0.0802466f,-0.186842f,0.979107f}, -{0.028666f,-0.0392859f,0.998817f},{0.0919448f,-0.102404f,0.990485f},{0.107856f,-0.057155f,0.992522f}, -{0.119144f,0.0265899f,0.992521f},{0.178742f,-0.0835213f,0.980345f},{0.0192356f,-0.00540807f,0.9998f}, -{0.0874508f,-0.0535629f,0.994728f},{0.126478f,0.158051f,0.979297f},{0.190018f,0.114754f,0.975051f}, -{0.173613f,0.129893f,0.97621f},{0.127075f,0.130935f,0.983213f},{0.0610101f,0.168995f,0.983727f}, -{0.239086f,0.0931203f,0.966523f},{0.25458f,0.0745033f,0.964177f},{0.208979f,0.0916021f,0.973621f}, -{0.270988f,0.0499291f,0.961287f},{0.158154f,0.136947f,0.977872f},{0.10955f,0.170691f,0.979216f}, -{0.0828562f,0.190497f,0.978185f},{0.0629022f,0.206614f,0.976398f},{0.224388f,0.102078f,0.969139f}, -{0.142376f,0.142513f,0.979499f},{0.0935053f,0.176539f,0.979842f},{0.209369f,0.109046f,0.971737f}, -{0.186808f,0.0142462f,0.982293f},{0.0771131f,0.180916f,0.980471f},{0.19432f,0.107117f,0.975072f}, -{0.0397896f,-0.00908038f,0.999167f},{0.0517701f,0.0687977f,0.996286f},{0.14449f,-0.0984282f,0.984599f}, -{0.127037f,-0.0930399f,0.987525f},{0.162383f,-0.103308f,0.981305f},{0.108876f,-0.0885006f,0.990108f}, -{-0.03979f,0.0090855f,0.999167f},{-0.0192361f,0.00541255f,0.9998f},{0.0667669f,-0.269586f,0.960659f}, -{-0.0610092f,-0.169012f,0.983724f},{-0.04552f,-0.217019f,0.975106f},{0.0147946f,-0.267327f,0.963492f}, -{-0.0828563f,-0.190496f,0.978185f},{-0.22439f,-0.102063f,0.96914f},{-0.158156f,-0.13693f,0.977874f}, -{-0.209371f,-0.109036f,0.971738f},{-0.142378f,-0.142505f,0.9795f},{-0.194321f,-0.107128f,0.975071f}, -{-0.127075f,-0.130951f,0.983211f},{-0.186807f,-0.0142661f,0.982293f},{-0.119142f,-0.0266103f,0.992521f}, -{-0.178742f,0.083517f,0.980345f},{-0.107856f,0.05716f,0.992522f},{-0.162383f,0.103317f,0.981304f}, -{0.00236961f,0.258468f,0.966017f},{0.0205104f,0.246429f,0.968944f},{-0.0874512f,0.0535675f,0.994727f}, -{-0.14449f,0.0984279f,0.984599f},{-0.127037f,0.0930396f,0.987525f},{-0.0683322f,0.0481988f,0.996498f}, -{-0.108876f,0.0885078f,0.990107f},{-0.0491751f,0.0428965f,0.997869f},{-0.0919447f,0.102401f,0.990485f}, -{-0.0286666f,0.0392909f,0.998817f},{-0.080245f,0.186822f,0.979111f},{-0.0158852f,0.114413f,0.993306f}, -{-0.0667658f,0.269573f,0.960663f},{-0.00500236f,0.212507f,0.977147f},{-0.0489219f,0.273996f,0.960486f}, -{0.0119362f,0.225019f,0.974281f},{-0.031601f,0.271553f,0.961904f},{0.0289212f,0.221777f,0.974668f}, -{-0.0147946f,0.26733f,0.963491f},{0.0455199f,0.217025f,0.975104f},{0.146005f,0.138621f,0.979524f}, -{-0.636821f,-0.00317738f,0.771005f},{-0.629441f,-0.0246739f,0.776656f},{-0.623058f,-0.0279566f,0.781676f}, -{-0.595408f,-0.0551303f,0.80153f},{-0.609331f,-0.0449278f,0.791642f},{-0.621971f,-0.0411546f,0.781958f}, -{-0.552325f,0.0499248f,0.832133f},{-0.563612f,-0.0687359f,0.823175f},{-0.599286f,-0.0416737f,0.79945f}, -{-0.580108f,-0.0663718f,0.811831f},{-0.614466f,-0.0507229f,0.787311f},{-0.606128f,-0.0620227f,0.792945f}, -{-0.567518f,0.223995f,0.792306f},{-0.553812f,0.226021f,0.801378f},{-0.475091f,0.198662f,0.857217f}, -{-0.595421f,0.110786f,0.795739f},{-0.58056f,0.223354f,0.782983f},{-0.531382f,0.175481f,0.828758f}, -{-0.496956f,0.276897f,0.822413f},{-0.364365f,0.182559f,0.913187f},{-0.521383f,0.210821f,0.82687f}, -{-0.407013f,0.174949f,0.896511f},{-0.443733f,0.18964f,0.875864f},{-0.539048f,0.218089f,0.81355f}, -{-0.219259f,0.330803f,0.917875f},{-0.268014f,0.331812f,0.904472f},{-0.436574f,0.392167f,0.809696f}, -{-0.317724f,0.25864f,0.912226f},{-0.46392f,0.369772f,0.805014f},{-0.411246f,0.394193f,0.821881f}, -{-0.168505f,0.319671f,0.932425f},{-0.385206f,0.390338f,0.836213f},{-0.114345f,0.303211f,0.946038f}, -{-0.0525963f,0.278069f,0.95912f},{-0.357097f,0.376599f,0.854784f},{-0.323311f,0.355321f,0.87705f}, -{-0.50421f,0.200313f,0.840028f},{-0.636809f,-0.00685578f,0.770991f},{-0.636823f,-0.002068f,0.771008f}, -{-0.63654f,-0.0217543f,0.770937f},{-0.629382f,-0.0247724f,0.776701f},{-0.621921f,-0.0411683f,0.781997f}, -{-0.635941f,-0.0371196f,0.770844f},{-0.599172f,-0.0415314f,0.799542f},{-0.606014f,-0.0620694f,0.793029f}, -{-0.634304f,-0.056447f,0.77102f},{-0.614392f,-0.0507421f,0.787367f},{-0.63537f,-0.0454985f,0.770866f}, -{-0.634587f,-0.0551123f,0.770884f},{-0.580496f,0.223077f,0.78311f},{-0.633724f,0.238176f,0.735979f}, -{-0.56733f,0.223957f,0.792452f},{-0.64016f,0.0682119f,0.765207f},{-0.63668f,0.204107f,0.743626f}, -{-0.595341f,0.110027f,0.795904f},{-0.633497f,0.239503f,0.735744f},{-0.521305f,0.210588f,0.826979f}, -{-0.538815f,0.21802f,0.813723f},{-0.632772f,0.247067f,0.733864f},{-0.553496f,0.22593f,0.801622f}, -{-0.632828f,0.246834f,0.733895f},{-0.436343f,0.392125f,0.809842f},{-0.463619f,0.369882f,0.805137f}, -{-0.598406f,0.409993f,0.688343f},{-0.496749f,0.27676f,0.822584f},{-0.631462f,0.257657f,0.731347f}, -{-0.618008f,0.336306f,0.710608f},{-0.589992f,0.425267f,0.686336f},{-0.411029f,0.394147f,0.822012f}, -{-0.584074f,0.431633f,0.687423f},{-0.385037f,0.390294f,0.836312f},{-0.356858f,0.376488f,0.854932f}, -{-0.580207f,0.431864f,0.690546f},{-0.579716f,0.42187f,0.697105f},{-0.581686f,0.404919f,0.705466f}, -{-0.636821f,-0.00315153f,0.771006f},{-0.643165f,-0.021951f,0.765413f},{-0.636538f,-0.0218263f,0.770937f}, -{-0.6489f,-0.0363394f,0.760005f},{-0.640157f,0.068003f,0.765229f},{-0.63431f,-0.0563715f,0.771021f}, -{-0.667183f,-0.0540317f,0.742932f},{-0.654564f,-0.0438692f,0.754732f},{-0.633724f,0.238183f,0.735978f}, -{-0.689649f,0.249708f,0.679728f},{-0.632825f,0.246861f,0.733889f},{-0.680332f,0.0719912f,0.72936f}, -{-0.683631f,0.211878f,0.698395f},{-0.636685f,0.204036f,0.743641f},{-0.722371f,0.258076f,0.641543f}, -{-0.631466f,0.257623f,0.731355f},{-0.633495f,0.239529f,0.735738f},{-0.709164f,0.264571f,0.65352f}, -{-0.632774f,0.247047f,0.733869f},{-0.698625f,0.261762f,0.665885f},{-0.717841f,0.420681f,0.554735f}, -{-0.617982f,0.336426f,0.710574f},{-0.732529f,0.277479f,0.621616f},{-0.728388f,0.35224f,0.587689f}, -{-0.720712f,0.437381f,0.537841f},{-0.72736f,0.444724f,0.522654f},{-0.57972f,0.421813f,0.697136f}, -{-0.737892f,0.44462f,0.507768f},{-0.755513f,0.432036f,0.492489f},{-0.780009f,0.4101f,0.472656f}, -{-0.660363f,-0.0527785f,0.74909f},{-0.636811f,-0.00629327f,0.770994f},{-0.649001f,-0.0241581f,0.760404f}, -{-0.643189f,-0.0220195f,0.765391f},{-0.660345f,-0.0375725f,0.750022f},{-0.648899f,-0.0363395f,0.760006f}, -{-0.680319f,0.0717815f,0.729392f},{-0.667198f,-0.0539575f,0.742923f},{-0.696227f,-0.0541337f,0.715778f}, -{-0.660362f,-0.0527786f,0.749091f},{-0.654563f,-0.0438693f,0.754733f},{-0.671536f,-0.0443535f,0.739643f}, -{-0.68961f,0.249707f,0.679768f},{-0.738688f,0.256526f,0.623325f},{-0.698666f,0.261803f,0.665827f}, -{-0.715903f,0.0721451f,0.694462f},{-0.725187f,0.215298f,0.654026f},{-0.683631f,0.211798f,0.69842f}, -{-0.79723f,0.268798f,0.540529f},{-0.732527f,0.277449f,0.621633f},{-0.722323f,0.258096f,0.641589f}, -{-0.774529f,0.275504f,0.569388f},{-0.709216f,0.264558f,0.653469f},{-0.755688f,0.271082f,0.596197f}, -{-0.814669f,0.415759f,0.4043f},{-0.717839f,0.420681f,0.554738f},{-0.818321f,0.355703f,0.451472f}, -{-0.728371f,0.352353f,0.587642f},{-0.815902f,0.287459f,0.501668f},{-0.824211f,0.430194f,0.368252f}, -{-0.727359f,0.444724f,0.522656f},{-0.72071f,0.437381f,0.537843f},{-0.83751f,0.434129f,0.331828f}, -{-0.73789f,0.44462f,0.50777f},{-0.755597f,0.431964f,0.492423f},{-0.854721f,0.428471f,0.293028f}, -{-0.879159f,0.406702f,0.248341f},{-0.908545f,0.371402f,0.19133f},{-0.683158f,-0.0526576f,0.728369f}, -{-0.652054f,-0.0263917f,0.757713f},{-0.636797f,-0.00909888f,0.770977f},{-0.695352f,-0.0536109f,0.716667f}, -{-0.671834f,-0.0443236f,0.739374f},{-0.680563f,-0.0456191f,0.731268f},{-0.666389f,-0.0392338f,0.744571f}, -{-0.660552f,-0.0375531f,0.749841f},{-0.649157f,-0.0242147f,0.760269f},{-0.716437f,0.0720186f,0.693924f}, -{-0.747931f,0.215375f,0.627863f},{-0.725786f,0.215321f,0.653354f},{-0.683545f,-0.0526197f,0.728009f}, -{-0.711835f,-0.055364f,0.700162f},{-0.69673f,-0.0540181f,0.715297f},{-0.809709f,0.279233f,0.516139f}, -{-0.775365f,0.275645f,0.568181f},{-0.756476f,0.271283f,0.595104f},{-0.786708f,0.274244f,0.553065f}, -{-0.739281f,0.256648f,0.622571f},{-0.76548f,0.258544f,0.589233f},{-0.864019f,0.351817f,0.360134f}, -{-0.81663f,0.287541f,0.500435f},{-0.85903f,0.289026f,0.42253f},{-0.797912f,0.268949f,0.539447f}, -{-0.836894f,0.271782f,0.475123f},{-0.824737f,0.430114f,0.367166f},{-0.815277f,0.415694f,0.40314f}, -{-0.87405f,0.415649f,0.251538f},{-0.818985f,0.355825f,0.450169f},{-0.863226f,0.404724f,0.301729f}, -{-0.887621f,0.415023f,0.199712f},{-0.837936f,0.434041f,0.330866f},{-0.903754f,0.403094f,0.144024f}, -{-0.85503f,0.428382f,0.292254f},{-0.879434f,0.406518f,0.247668f},{-0.924662f,0.372382f,0.079571f}, -{-0.945544f,0.325495f,0.0f},{-0.735204f,0.0705335f,0.674167f},{-0.957958f,0.286908f,-0.000297298f}, -{-0.958184f,0.286152f,-0.00027813f},{-0.951596f,0.278077f,-0.130911f},{-0.956115f,0.266505f,-0.121731f}, -{-0.962828f,0.270116f,-0.00025761f},{-0.971736f,0.23607f,-0.000235456f},{-0.959649f,0.258612f,-0.110422f}, -{-0.993744f,0.111685f,-0.000218645f},{-0.982441f,0.15671f,-0.101255f},{-0.995607f,0.0244862f,-0.0903677f}, -{-0.999997f,0.00228008f,-0.000195691f},{-0.999963f,0.00864389f,-0.000166398f},{-0.996969f,0.0121337f,-0.076847f}, -{-0.999852f,0.0172244f,-0.000133472f},{-0.99785f,0.0209404f,-0.0620961f},{-0.998704f,0.0225323f,-0.0456418f}, -{-0.999808f,0.0196045f,-9.71639e-005f},{-0.999813f,0.0193212f,-5.4502e-005f},{-0.99946f,0.0204337f,-0.0257239f}, -{-0.999843f,0.0176994f,0.0f},{-0.99985f,0.0173199f,0.0f},{-0.953349f,0.267273f,-0.140321f}, -{-0.95479f,0.257069f,-0.149306f},{-0.962413f,0.271589f,-0.00031666f},{-0.959914f,0.280293f,-0.000331412f}, -{-0.946687f,0.282163f,-0.155461f},{-0.937469f,0.308726f,-0.16075f},{-0.947766f,0.318966f,-0.000342471f}, -{-0.931085f,0.324966f,-0.165762f},{-0.93484f,0.355068f,-0.000351538f},{-0.928807f,0.370564f,-0.000361614f}, -{-0.928046f,0.330965f,-0.17086f},{-0.928594f,0.326564f,-0.176266f},{-0.926386f,0.376575f,-0.000372148f}, -{-0.934514f,0.30552f,-0.182597f},{-0.92782f,0.373027f,-0.000383596f},{-0.935191f,0.354145f,-0.000397484f}, -{-0.943202f,0.272835f,-0.189554f},{-0.945578f,0.325394f,-0.00041274f},{-0.997288f,0.0211408f,-0.0705025f}, -{-0.99985f,0.0173199f,-1.50134e-014f},{-0.999888f,0.0149749f,1.04413e-015f},{-0.976903f,0.0190992f,-0.212829f}, -{-0.997001f,0.012063f,-0.0764401f},{-0.98481f,0.0270514f,-0.171517f},{-0.991726f,0.0267385f,-0.125559f}, -{-0.998719f,0.0225092f,-0.0453197f},{-0.959761f,0.258403f,-0.109939f},{-0.942002f,0.185186f,-0.279891f}, -{-0.921009f,0.235359f,-0.310401f},{-0.995645f,0.0245818f,-0.0899239f},{-0.966375f,0.060169f,-0.25f}, -{-0.982591f,0.156085f,-0.100754f},{-0.898699f,0.242529f,-0.365402f},{-0.893124f,0.221008f,-0.391771f}, -{-0.953393f,0.26728f,-0.140014f},{-0.907932f,0.245706f,-0.33954f},{-0.951625f,0.27811f,-0.130631f}, -{-0.95615f,0.266559f,-0.121342f},{-0.865841f,0.222884f,-0.447931f},{-0.937463f,0.308832f,-0.160577f}, -{-0.874336f,0.220933f,-0.432117f},{-0.946719f,0.282182f,-0.155229f},{-0.954855f,0.25702f,-0.148975f}, -{-0.882967f,0.223806f,-0.412649f},{-0.858059f,0.225231f,-0.461525f},{-0.928053f,0.330999f,-0.170754f}, -{-0.931092f,0.32502f,-0.165619f},{-0.852796f,0.216849f,-0.475096f},{-0.928602f,0.32658f,-0.176192f}, -{-0.934555f,0.305399f,-0.182588f},{-0.850459f,0.192096f,-0.489713f},{-0.848968f,0.155604f,-0.505015f}, -{-0.997875f,0.0209039f,-0.0617066f},{-0.999463f,0.0204365f,-0.0256194f},{-0.993882f,0.0198325f,-0.108651f}, -{-0.999888f,0.0149749f,0.0f},{-0.999942f,0.0107279f,0.0f},{-0.940471f,0.027494f,-0.338759f}, -{-0.9848f,0.0270456f,-0.171575f},{-0.961911f,0.0323478f,-0.271441f},{-0.980028f,0.0289941f,-0.196733f}, -{-0.99172f,0.0267423f,-0.125606f},{-0.997263f,0.0211768f,-0.0708398f},{-0.942124f,0.184752f,-0.279767f}, -{-0.842424f,0.198008f,-0.501114f},{-0.92105f,0.235436f,-0.310221f},{-0.976871f,0.0190528f,-0.212979f}, -{-0.914688f,0.0630398f,-0.399213f},{-0.96636f,0.0602812f,-0.250028f},{-0.786761f,0.19314f,-0.586263f}, -{-0.763159f,0.167212f,-0.624203f},{-0.898676f,0.24247f,-0.365499f},{-0.907886f,0.245744f,-0.339635f}, -{-0.8124f,0.201874f,-0.547041f},{-0.700686f,0.0929333f,-0.707392f},{-0.874312f,0.220911f,-0.432176f}, -{-0.718951f,0.113967f,-0.685653f},{-0.88298f,0.2238f,-0.412625f},{-0.893172f,0.221072f,-0.391626f}, -{-0.739263f,0.154471f,-0.65546f},{-0.684218f,0.0875221f,-0.724006f},{-0.858048f,0.225226f,-0.461549f}, -{-0.86583f,0.222895f,-0.447948f},{-0.669461f,0.073847f,-0.739168f},{-0.852792f,0.216833f,-0.475111f}, -{-0.850452f,0.191924f,-0.489793f},{-0.655515f,0.0484461f,-0.753627f},{-0.640906f,0.0158475f,-0.767455f}, -{-0.848968f,0.155604f,-0.505015f},{-0.877789f,0.164174f,-0.450038f},{-0.990338f,0.0167192f,-0.137663f}, -{-0.999942f,0.0107279f,-5.79815e-010f},{-0.999987f,0.00505961f,0.0f},{-0.890883f,0.033892f,-0.452967f}, -{-0.961882f,0.0323469f,-0.271545f},{-0.932581f,0.0355093f,-0.35921f},{-0.966258f,0.0291785f,-0.255917f}, -{-0.980011f,0.0290016f,-0.196817f},{-0.993822f,0.0198883f,-0.10919f},{-0.877955f,0.163842f,-0.449834f}, -{-0.780866f,0.13651f,-0.609602f},{-0.718253f,0.148479f,-0.679755f},{-0.940382f,0.0274608f,-0.339011f}, -{-0.841289f,0.0636188f,-0.536829f},{-0.914656f,0.0631371f,-0.399272f},{-0.609067f,0.125965f,-0.783052f}, -{-0.559997f,0.0957412f,-0.822944f},{-0.786669f,0.193061f,-0.586412f},{-0.812292f,0.201887f,-0.547197f}, -{-0.660203f,0.142438f,-0.737458f},{-0.439944f,-0.0540079f,-0.896399f},{-0.718888f,0.113812f,-0.685746f}, -{-0.472513f,-0.0113659f,-0.88125f},{-0.739288f,0.154497f,-0.655427f},{-0.763303f,0.167295f,-0.624004f}, -{-0.514496f,0.06617f,-0.854936f},{-0.414517f,-0.0658654f,-0.907655f},{-0.684189f,0.0875037f,-0.724037f}, -{-0.700662f,0.0929309f,-0.707415f},{-0.391685f,-0.0816251f,-0.916472f},{-0.669444f,0.0738257f,-0.739185f}, -{-0.65544f,0.0482842f,-0.753702f},{-0.369884f,-0.101927f,-0.92347f},{-0.347635f,-0.123605f,-0.929447f}, -{-0.640907f,0.0158475f,-0.767455f},{-0.842564f,0.198107f,-0.500839f},{-0.989269f,0.0111543f,-0.145677f}, -{-0.999987f,0.00505961f,-2.85058e-010f},{-0.999999f,-0.00138151f,1.91845e-016f},{-0.850391f,0.0382111f,-0.524762f}, -{-0.932523f,0.0355133f,-0.359361f},{-0.91244f,0.0352909f,-0.407687f},{-0.959016f,0.0256877f,-0.282185f}, -{-0.966226f,0.0291895f,-0.256037f},{-0.990238f,0.0167928f,-0.138374f},{-0.781126f,0.136305f,-0.609314f}, -{-0.684245f,0.0955151f,-0.72297f},{-0.584646f,0.0993674f,-0.805181f},{-0.890704f,0.0338728f,-0.453319f}, -{-0.77454f,0.0484155f,-0.630669f},{-0.841226f,0.0636976f,-0.536918f},{-0.401556f,0.0560249f,-0.914119f}, -{-0.326384f,0.0268241f,-0.944856f},{-0.608874f,0.125862f,-0.783218f},{-0.485701f,0.0741101f,-0.870978f}, -{-0.659992f,0.142412f,-0.737652f},{-0.71855f,0.14861f,-0.679412f},{-0.196022f,-0.0637993f,-0.978522f}, -{-0.472378f,-0.0116501f,-0.881319f},{-0.514541f,0.0662311f,-0.854904f},{-0.257578f,0.00189659f,-0.966256f}, -{-0.56027f,0.0958443f,-0.822746f},{-0.110962f,-0.197306f,-0.974042f},{-0.414469f,-0.0658928f,-0.907675f}, -{-0.439905f,-0.0540224f,-0.896418f},{-0.144236f,-0.164717f,-0.975738f},{-0.08502f,-0.210934f,-0.973796f}, -{-0.391658f,-0.081646f,-0.916481f},{-0.0624871f,-0.223578f,-0.972681f},{-0.0413979f,-0.233506f,-0.971474f}, -{-0.369768f,-0.102042f,-0.923504f},{0.369767f,0.102044f,-0.923504f},{0.347635f,0.123604f,-0.929447f}, -{0.414472f,0.0658736f,-0.907675f},{0.110963f,0.1973f,-0.974043f},{0.0850214f,0.210917f,-0.973799f}, -{0.391659f,0.0816379f,-0.916482f},{0.0624874f,0.223573f,-0.972682f},{0.0413979f,0.233508f,-0.971473f}, -{0.257578f,-0.00190271f,-0.966256f},{0.51454f,-0.0662188f,-0.854906f},{0.560269f,-0.0958526f,-0.822746f}, -{0.144235f,0.164734f,-0.975735f},{0.472379f,0.0116715f,-0.881318f},{0.19602f,0.0638166f,-0.978521f}, -{0.659992f,-0.142412f,-0.737652f},{0.71855f,-0.148611f,-0.679412f},{0.485701f,-0.0741122f,-0.870978f}, -{0.608874f,-0.125862f,-0.783218f},{0.401556f,-0.0560238f,-0.914119f},{0.326385f,-0.0268274f,-0.944856f}, -{0.890704f,-0.0338724f,-0.453319f},{0.77454f,-0.0484116f,-0.630669f},{0.841226f,-0.0636956f,-0.536918f}, -{0.684245f,-0.0955126f,-0.72297f},{0.584646f,-0.0993696f,-0.80518f},{0.781126f,-0.136306f,-0.609313f}, -{0.932523f,-0.0355125f,-0.35936f},{0.91244f,-0.0352907f,-0.407686f},{0.850391f,-0.0382116f,-0.524763f}, -{0.966226f,-0.0291876f,-0.256036f},{0.959016f,-0.025686f,-0.282185f},{0.989269f,-0.0111537f,-0.145677f}, -{0.990238f,-0.0167921f,-0.138374f},{0.999987f,-0.0050596f,0.0f},{0.999999f,0.00138152f,-1.73582e-014f}, -{0.439909f,0.05402f,-0.896416f},{0.65544f,-0.0482827f,-0.753702f},{0.640906f,-0.0158483f,-0.767455f}, -{0.700666f,-0.0929347f,-0.707411f},{0.414519f,0.0658462f,-0.907655f},{0.68419f,-0.0875227f,-0.724033f}, -{0.669444f,-0.0738342f,-0.739184f},{0.391685f,0.0816169f,-0.916472f},{0.369884f,0.101929f,-0.92347f}, -{0.514494f,-0.0661576f,-0.854938f},{0.739288f,-0.154485f,-0.65543f},{0.763301f,-0.167303f,-0.624004f}, -{0.439948f,0.0540055f,-0.896398f},{0.718891f,-0.113792f,-0.685745f},{0.472514f,0.0113873f,-0.88125f}, -{0.842564f,-0.198106f,-0.500839f},{0.718253f,-0.14848f,-0.679755f},{0.660203f,-0.142438f,-0.737458f}, -{0.812292f,-0.201887f,-0.547197f},{0.609068f,-0.125965f,-0.783051f},{0.786669f,-0.193061f,-0.586412f}, -{0.940382f,-0.0274602f,-0.33901f},{0.841289f,-0.0636168f,-0.536829f},{0.914656f,-0.0631375f,-0.399271f}, -{0.780866f,-0.136511f,-0.609601f},{0.877955f,-0.163845f,-0.449833f},{0.961882f,-0.0323448f,-0.271544f}, -{0.932581f,-0.0355085f,-0.359209f},{0.890883f,-0.0338916f,-0.452967f},{0.980011f,-0.0289993f,-0.196816f}, -{0.966258f,-0.0291766f,-0.255917f},{0.990338f,-0.0167184f,-0.137663f},{0.993822f,-0.0198877f,-0.109189f}, -{0.999942f,-0.0107279f,-3.47115e-014f},{0.999987f,-0.0050596f,-3.47131e-014f},{0.559996f,-0.0957495f,-0.822944f}, -{0.850452f,-0.191923f,-0.489793f},{0.848968f,-0.155604f,-0.505015f},{0.865832f,-0.222898f,-0.447942f}, -{0.68422f,-0.0875411f,-0.724003f},{0.858046f,-0.225241f,-0.461544f},{0.85279f,-0.21684f,-0.47511f}, -{0.669461f,-0.0738554f,-0.739167f},{0.655515f,-0.0484446f,-0.753627f},{0.739263f,-0.154458f,-0.655463f}, -{0.89317f,-0.221079f,-0.391626f},{0.763157f,-0.16722f,-0.624202f},{0.70069f,-0.092937f,-0.707387f}, -{0.874317f,-0.220895f,-0.432174f},{0.718955f,-0.113948f,-0.685653f},{0.92105f,-0.235433f,-0.310221f}, -{0.842424f,-0.198007f,-0.501114f},{0.8124f,-0.201874f,-0.547041f},{0.907886f,-0.245744f,-0.339635f}, -{0.786761f,-0.19314f,-0.586263f},{0.898676f,-0.24247f,-0.365499f},{0.976871f,-0.0190519f,-0.212977f}, -{0.914689f,-0.0630402f,-0.399213f},{0.966361f,-0.060284f,-0.250026f},{0.877788f,-0.164177f,-0.450037f}, -{0.942123f,-0.184757f,-0.279767f},{0.9848f,-0.0270421f,-0.171573f},{0.961912f,-0.0323457f,-0.27144f}, -{0.940472f,-0.0274934f,-0.338758f},{0.99172f,-0.0267396f,-0.125605f},{0.980029f,-0.0289918f,-0.196732f}, -{0.993882f,-0.0198319f,-0.108651f},{0.997263f,-0.0211762f,-0.0708397f},{0.999888f,-0.0149749f,1.73785e-014f}, -{0.999942f,-0.0107279f,-1.37458e-007f},{0.882982f,-0.223789f,-0.412628f},{0.879976f,-0.406267f,0.24615f}, -{0.945544f,-0.325496f,-4.37825e-014f},{0.825224f,-0.430021f,0.366179f},{0.887589f,-0.415042f,0.199814f}, -{0.838449f,-0.433914f,0.32973f},{0.855563f,-0.428207f,0.290948f},{0.903734f,-0.403111f,0.144105f}, -{0.924654f,-0.372393f,0.0796197f},{0.863964f,-0.351815f,0.360266f},{0.817015f,-0.287563f,0.499794f}, -{0.858968f,-0.289017f,0.422662f},{0.874009f,-0.415666f,0.251654f},{0.815734f,-0.415625f,0.402286f}, -{0.863176f,-0.404737f,0.301853f},{0.756732f,-0.271311f,0.594766f},{0.786642f,-0.274232f,0.553165f}, -{0.809642f,-0.279221f,0.516252f},{0.775661f,-0.27568f,0.567759f},{0.836827f,-0.271774f,0.475247f}, -{0.798255f,-0.268981f,0.538923f},{0.73515f,-0.0705437f,0.674224f},{0.747875f,-0.215371f,0.627932f}, -{0.716587f,-0.0720223f,0.693769f},{0.76542f,-0.258526f,0.589319f},{0.7395f,-0.256658f,0.622308f}, -{0.725968f,-0.215327f,0.65315f},{0.695311f,0.0536227f,0.716706f},{0.711787f,0.0553596f,0.700211f}, -{0.683635f,0.0526367f,0.727924f},{0.696847f,0.05402f,0.715182f},{0.671901f,0.0443476f,0.739312f}, -{0.680533f,0.0456343f,0.731295f},{0.660597f,0.0375712f,0.7498f},{0.666369f,0.0392392f,0.744589f}, -{0.652044f,0.0263913f,0.757722f},{0.64918f,0.0242326f,0.760249f},{0.636797f,0.00909943f,0.770977f}, -{0.819405f,-0.355806f,0.449419f},{0.934555f,-0.305399f,-0.182588f},{0.943202f,-0.272835f,-0.189554f}, -{0.931091f,-0.325025f,-0.165614f},{0.858058f,-0.225246f,-0.46152f},{0.92805f,-0.33101f,-0.170751f}, -{0.928601f,-0.326585f,-0.176191f},{0.852794f,-0.216857f,-0.475095f},{0.850459f,-0.192095f,-0.489713f}, -{0.882969f,-0.223794f,-0.412652f},{0.946723f,-0.282168f,-0.15523f},{0.954853f,-0.257023f,-0.148976f}, -{0.865843f,-0.222888f,-0.447925f},{0.937467f,-0.308825f,-0.160573f},{0.874341f,-0.220917f,-0.432116f}, -{0.951625f,-0.27811f,-0.130631f},{0.95615f,-0.266557f,-0.121342f},{0.907932f,-0.245706f,-0.33954f}, -{0.953392f,-0.267282f,-0.140014f},{0.8987f,-0.242529f,-0.365402f},{0.893122f,-0.221015f,-0.391771f}, -{0.98259f,-0.156094f,-0.100754f},{0.966375f,-0.0601717f,-0.249998f},{0.942001f,-0.185191f,-0.279891f}, -{0.921009f,-0.235357f,-0.310401f},{0.959761f,-0.258402f,-0.10994f},{0.997001f,-0.0120606f,-0.0764369f}, -{0.98481f,-0.0270479f,-0.171515f},{0.976903f,-0.0190983f,-0.212827f},{0.995645f,-0.0245852f,-0.089921f}, -{0.997876f,-0.0208988f,-0.0617047f},{0.991726f,-0.0267358f,-0.125558f},{0.997288f,-0.0211402f,-0.0705024f}, -{0.998719f,-0.0225064f,-0.0453191f},{0.99985f,-0.0173199f,0.0f},{0.999463f,-0.020436f,-0.0256193f}, -{0.999888f,-0.0149749f,0.0f},{0.93519f,-0.354145f,-0.000397467f},{0.945578f,-0.325394f,-0.00041274f}, -{0.928805f,-0.37057f,-0.000358322f},{0.928043f,-0.330975f,-0.170857f},{0.926383f,-0.376582f,-0.00037055f}, -{0.927819f,-0.37303f,-0.00038323f},{0.928592f,-0.326569f,-0.176265f},{0.934514f,-0.30552f,-0.182597f}, -{0.946691f,-0.282148f,-0.155461f},{0.94777f,-0.318954f,-0.000340813f},{0.959916f,-0.280289f,-0.000332774f}, -{0.931084f,-0.324972f,-0.165758f},{0.934841f,-0.355065f,-0.000347719f},{0.937472f,-0.308718f,-0.160746f}, -{0.957958f,-0.286908f,-0.000297201f},{0.958184f,-0.286152f,-0.000278036f},{0.951596f,-0.278077f,-0.130911f}, -{0.962412f,-0.271594f,-0.000317168f},{0.953349f,-0.267276f,-0.140321f},{0.954789f,-0.257072f,-0.149307f}, -{0.993743f,-0.111694f,-0.00021707f},{0.982439f,-0.156718f,-0.101254f},{0.971735f,-0.236074f,-0.000236761f}, -{0.95965f,-0.25861f,-0.110423f},{0.956116f,-0.266503f,-0.121731f},{0.962829f,-0.270112f,-0.000258194f}, -{0.999963f,-0.00863986f,-0.000162909f},{0.996969f,-0.0121313f,-0.0768439f},{0.999997f,-0.00228269f,-0.000191989f}, -{0.995608f,-0.0244896f,-0.0903648f},{0.999852f,-0.0172187f,-0.000131616f},{0.997851f,-0.0209353f,-0.0620942f}, -{0.998704f,-0.0225295f,-0.0456412f},{0.999808f,-0.0196018f,-9.66914e-005f},{0.999813f,-0.0193208f,-5.44735e-005f}, -{0.99946f,-0.0204332f,-0.0257239f},{0.999843f,-0.0176994f,0.0f},{-0.271326f,0.0f,0.962488f}, -{-0.253151f,0.0f,0.967427f},{-0.26258f,0.0f,0.96491f},{-0.147431f,0.0f,0.989072f}, -{-0.162743f,0.0f,0.986669f},{-0.209863f,0.0f,0.977731f},{-0.243346f,0.0f,0.96994f}, -{-0.20324f,0.0f,0.979129f},{-0.0844041f,0.0f,0.996432f},{-0.0211631f,0.0f,0.999776f}, -{-0.0519304f,0.0f,0.998651f},{-0.0826965f,0.0f,0.996575f},{-0.113463f,0.0f,0.993542f}, -{-0.11544f,0.0f,0.993314f},{-0.119575f,0.0f,0.992825f},{-0.125688f,0.0f,0.99207f}, -{-0.133439f,0.0f,0.991057f},{-0.142487f,0.0f,0.989797f},{-0.1524f,0.0f,0.988319f}, -{0.123071f,6.49463e-018f,-0.992398f},{0.13416f,-1.11865e-017f,-0.99096f},{0.134575f,-3.82822e-018f,-0.990903f}, -{0.113491f,1.60303e-018f,-0.993539f},{0.0902913f,7.81879e-018f,-0.995915f},{0.0774828f,9.91352e-018f,-0.996994f}, -{0.0670916f,1.03021e-017f,-0.997747f},{0.0438914f,-1.68674e-018f,-0.999036f},{0.147436f,3.8365e-018f,-0.989072f}, -{0.0206911f,8.0814e-018f,-0.999786f},{0.160907f,8.05703e-018f,-0.98697f},{0.190446f,1.33567e-017f,-0.981698f}, -{0.300752f,0.0f,-0.953702f},{0.299196f,0.0f,-0.954192f},{0.266455f,-9.04092e-018f,-0.963847f}, -{0.25387f,3.88234e-018f,-0.967238f},{0.246065f,-1.05499e-017f,-0.969253f},{0.294624f,3.20684e-018f,-0.955613f}, -{0.287357f,-3.12775e-018f,-0.957824f},{0.277782f,1.04562e-017f,-0.960644f},{0.240601f,1.18742e-017f,-0.970624f}, -{-1.0f,-6.77626e-018f,1.27676e-015f},{-1.0f,-6.77626e-018f,1.27052e-015f},{-1.0f,0.0f,1.27676e-015f}, -{-1.0f,-3.2255e-018f,1.2844e-015f},{-1.0f,-2.22261e-018f,1.27052e-015f},{-1.0f,-2.05998e-018f,1.27052e-015f}, -{-1.0f,2.92735e-018f,1.2844e-015f},{-1.0f,0.0f,1.27052e-015f},{2.22045e-016f,1.0f,0.0f}, -{-4.44089e-016f,1.0f,0.0f},{4.44089e-016f,1.0f,0.0f},{-8.88178e-016f,1.0f,0.0f}, -{0.895526f,0.44501f,0.0f},{0.957889f,0.287138f,0.0f},{0.964461f,0.264225f,0.0f}, -{0.996976f,0.0777153f,0.0f},{0.87496f,0.484196f,0.0f},{0.788298f,0.615293f,0.0f}, -{0.752381f,0.658728f,0.0f},{0.629043f,0.777371f,0.0f},{0.595906f,0.803054f,0.0f}, -{0.437093f,0.899416f,0.0f},{0.412424f,0.910992f,0.0f},{0.223703f,0.974657f,0.0f}, -{0.210088f,0.977683f,0.0f},{-1.04131e-014f,1.0f,0.0f},{-5.20654e-015f,1.0f,0.0f}, -{-0.77709f,0.62939f,1.00199e-015f},{-0.793886f,0.608066f,8.62015e-016f},{-0.63319f,0.773996f,7.65657e-016f}, -{6.28037e-016f,1.0f,-6.81933e-031f},{-2.51215e-015f,1.0f,2.72773e-030f},{-0.22043f,0.975403f,2.71985e-016f}, -{-0.429735f,0.902955f,5.30243e-016f},{-0.226136f,0.974096f,2.90187e-016f},{-0.44128f,0.89737f,5.88046e-016f}, -{-0.61793f,0.786233f,7.01456e-016f},{-0.8981f,0.439791f,9.6132e-016f},{-0.974099f,0.22612f,1.13394e-015f}, -{-0.906488f,0.422231f,1.14646e-015f},{-0.976328f,0.216293f,1.13616e-015f},{-1.0f,3.14018e-016f,1.18453e-015f}, -{-0.636824f,0.0f,0.771009f},{-0.636824f,4.41885e-018f,0.771009f},{0.976094f,0.0764224f,0.203472f}, -{0.996976f,0.0777152f,2.3946e-009f},{0.996976f,0.0777152f,1.82309e-009f},{-0.0519161f,5.69588e-006f,0.998651f}, -{0.456027f,0.0391237f,0.889106f},{-0.0825944f,1.35909e-005f,0.996583f},{0.861638f,0.0691877f,0.502785f}, -{0.636981f,0.0509221f,0.769196f},{0.996976f,0.0777152f,6.33733e-010f},{0.996976f,0.0777152f,-2.35021e-015f}, -{0.917412f,0.0749912f,0.390808f},{0.856741f,0.0700812f,0.510962f},{0.282672f,0.0305668f,0.95873f}, -{0.436736f,0.0398436f,0.898707f},{0.663385f,0.0583498f,0.746f},{0.347654f,0.0286465f,0.937185f}, -{0.854338f,0.0674458f,0.515323f},{-0.113462f,1.67095e-011f,0.993542f},{-0.0211583f,3.90358e-007f,0.999776f}, -{0.996976f,0.0777152f,1.22379e-009f},{-0.115053f,0.707107f,0.697684f},{0.041302f,0.702691f,0.710295f}, -{0.13998f,0.918265f,0.3704f},{0.196116f,0.664219f,0.721354f},{0.515388f,0.76718f,0.381851f}, -{0.335631f,0.863385f,0.376721f},{0.464798f,0.490492f,0.737143f},{0.794304f,0.467108f,0.388447f}, -{0.671315f,0.632878f,0.385748f},{0.996976f,0.0777152f,8.89301e-008f},{0.957256f,0.289241f,8.65022e-007f}, -{0.87754f,0.278854f,0.390082f},{0.171643f,0.256675f,0.951135f},{0.101729f,0.309894f,0.945313f}, -{-0.133372f,-4.90387e-007f,0.991066f},{0.26464f,0.113588f,0.957634f},{0.631152f,0.216859f,0.744728f}, -{0.227046f,0.189962f,0.955178f},{-0.151307f,0.368095f,0.917394f},{-0.0644563f,0.366433f,0.928209f}, -{-0.162743f,-1.36278e-016f,0.986669f},{-0.152368f,-4.77403e-007f,0.988324f},{-0.0598835f,0.929788f,0.363191f}, -{0.20987f,0.977729f,1.07918e-005f},{-1.37117e-008f,1.0f,8.31709e-008f},{0.0217202f,0.34688f,0.937658f}, -{-0.142402f,-1.01854e-006f,0.989809f},{0.563926f,0.362795f,0.741867f},{0.339591f,0.592707f,0.730326f}, -{-0.115426f,-7.18981e-007f,0.993316f},{0.282671f,0.0305691f,0.95873f},{-0.113463f,1.58673e-014f,0.993542f}, -{0.663385f,0.0583523f,0.746f},{0.411528f,0.911397f,6.3595e-006f},{0.917412f,0.0749922f,0.390808f}, -{0.594217f,0.804305f,4.18309e-006f},{-0.125613f,-1.78317e-007f,0.992079f},{0.751163f,0.660117f,2.58675e-006f}, -{-0.11953f,1.33025e-007f,0.992831f},{0.874228f,0.485516f,4.30103e-007f},{-0.0599047f,0.929788f,0.363187f}, -{6.95989e-015f,1.0f,-4.64483e-014f},{-0.0993814f,0.87226f,0.478837f},{-0.203217f,2.41719e-015f,0.979134f}, -{-0.177258f,0.489042f,0.85406f},{-0.119006f,0.87226f,0.474341f},{-0.212261f,0.489042f,0.84604f}, -{-0.151316f,0.368095f,0.917393f},{-0.162743f,0.0f,0.986669f},{-0.115076f,0.707107f,0.69768f}, -{-0.750862f,0.640795f,0.159966f},{-0.690083f,0.633896f,0.34923f},{-0.633689f,0.773588f,4.47054e-006f}, -{-0.119072f,0.87226f,0.474324f},{-0.226237f,0.974072f,4.35889e-005f},{-0.441461f,0.89728f,1.9127e-005f}, -{-0.314908f,0.831026f,0.458507f},{-0.793896f,0.608053f,1.75823e-008f},{-0.604452f,0.56074f,0.56587f}, -{-0.475573f,0.362672f,0.801436f},{-0.425828f,0.412157f,0.805479f},{-0.4929f,0.748579f,0.443484f}, -{-0.2123f,0.489042f,0.84603f},{-0.325164f,0.461687f,0.825296f},{-0.271328f,2.66133e-006f,0.962487f}, -{-0.262654f,3.42352e-007f,0.96489f},{-0.243346f,-1.24911e-015f,0.96994f},{-0.253185f,2.24678e-006f,0.967418f}, -{0.640323f,0.0486817f,-0.766562f},{0.513173f,0.0370848f,-0.857483f},{0.875571f,0.0666236f,-0.478474f}, -{0.996904f,0.0775964f,-0.0127208f},{0.996948f,0.0776561f,-0.00805679f},{0.880476f,0.0653022f,-0.469572f}, -{0.878213f,0.0659754f,-0.473698f},{0.857586f,0.0660304f,-0.510084f},{0.996974f,0.0777085f,-0.00192217f}, -{0.996976f,0.0777145f,-0.00043536f},{0.977579f,0.0758877f,-0.196417f},{0.043964f,5.59703e-006f,-0.999033f}, -{0.350245f,0.0257948f,-0.936303f},{0.52637f,0.0365804f,-0.849468f},{0.0672212f,1.00329e-005f,-0.997738f}, -{0.616326f,0.0410888f,-0.786418f},{0.902304f,0.0665963f,-0.425926f},{0.539132f,0.036057f,-0.841449f}, -{0.0206959f,4.01696e-007f,-0.999786f},{0.113495f,3.419e-007f,-0.993538f},{0.996967f,0.0776912f,-0.00445871f}, -{0.0904433f,1.17965e-005f,-0.995902f},{-0.123071f,-6.16506e-018f,-0.992398f},{-0.13416f,1.30823e-017f,-0.99096f}, -{-0.134575f,4.86852e-018f,-0.990903f},{-0.113491f,-8.07206e-018f,-0.993539f},{-0.0902913f,1.48949e-020f,-0.995915f}, -{-0.0774828f,-3.75189e-018f,-0.996994f},{-0.0670916f,5.48641e-018f,-0.997747f},{-0.0438914f,-2.91677e-017f,-0.999036f}, -{-0.147436f,3.19289e-018f,-0.989072f},{-0.0206911f,-5.39916e-018f,-0.999786f},{-0.160907f,-1.04945e-017f,-0.98697f}, -{-0.190446f,-2.1531e-018f,-0.981698f},{-0.300752f,0.0f,-0.953702f},{-0.299196f,-1.03859e-017f,-0.954192f}, -{-0.266455f,-1.0491e-017f,-0.963847f},{-0.25387f,-5.26397e-018f,-0.967238f},{-0.246065f,1.44857e-017f,-0.969253f}, -{-0.294624f,0.0f,-0.955613f},{-0.287357f,1.04255e-017f,-0.957824f},{-0.277782f,0.0f,-0.960644f}, -{-0.240601f,5.2824e-018f,-0.970624f},{0.271326f,0.0f,0.962488f},{0.253151f,0.0f,0.967427f}, -{0.26258f,0.0f,0.96491f},{0.147431f,0.0f,0.989072f},{0.162743f,0.0f,0.986669f}, -{0.209863f,0.0f,0.977731f},{0.243346f,0.0f,0.96994f},{0.20324f,0.0f,0.979129f}, -{0.0844041f,0.0f,0.996432f},{0.0211631f,0.0f,0.999776f},{0.0519304f,0.0f,0.998651f}, -{0.0826965f,0.0f,0.996575f},{0.113463f,0.0f,0.993542f},{0.115523f,0.0f,0.993305f}, -{0.119556f,0.0f,0.992828f},{0.125642f,0.0f,0.992076f},{0.133401f,0.0f,0.991062f}, -{0.142437f,0.0f,0.989804f},{0.152342f,0.0f,0.988328f},{1.0f,0.0f,-1.26288e-015f}, -{1.0f,0.0f,-1.26775e-015f},{1.77636e-015f,-1.0f,0.0f},{-0.895526f,-0.44501f,0.0f}, -{-0.957888f,-0.287142f,0.0f},{-0.964461f,-0.264225f,0.0f},{-0.996976f,-0.0777153f,0.0f}, -{-0.874961f,-0.484193f,0.0f},{-0.788298f,-0.615293f,0.0f},{-0.752379f,-0.658731f,0.0f}, -{-0.629043f,-0.777371f,0.0f},{-0.595907f,-0.803054f,0.0f},{-0.437093f,-0.899416f,0.0f}, -{-0.412414f,-0.910997f,0.0f},{-0.223703f,-0.974657f,0.0f},{-0.210092f,-0.977682f,0.0f}, -{1.04131e-014f,-1.0f,0.0f},{5.20654e-015f,-1.0f,0.0f},{0.793886f,-0.608066f,-1.01875e-015f}, -{0.63319f,-0.773996f,-7.50031e-016f},{0.77709f,-0.62939f,-9.20484e-016f},{0.44128f,-0.89737f,-5.60822e-016f}, -{0.61793f,-0.786233f,-7.31954e-016f},{0.22043f,-0.975403f,-2.72665e-016f},{0.429735f,-0.902955f,-5.0373e-016f}, -{0.226136f,-0.974096f,-2.80072e-016f},{0.8981f,-0.439791f,-1.24113e-015f},{0.974099f,-0.22612f,-1.15385e-015f}, -{0.906488f,-0.422231f,-1.07376e-015f},{0.976328f,-0.216293f,-1.15649e-015f},{1.0f,-3.14018e-016f,-1.18453e-015f}, -{0.636824f,-4.24524e-018f,0.771009f},{0.636824f,9.31099e-019f,0.771009f},{0.636824f,-5.78592e-018f,0.771009f}, -{0.636824f,-5.00079e-018f,0.771009f},{0.636824f,0.0f,0.771009f},{0.636824f,1.67186e-018f,0.771009f}, -{0.636824f,4.01246e-018f,0.771009f},{0.636824f,2.67498e-018f,0.771009f},{0.636824f,5.34995e-018f,0.771009f}, -{0.636824f,-2.00623e-018f,0.771009f},{0.636824f,-3.77969e-018f,0.771009f},{0.636824f,-2.75858e-018f,0.771009f}, -{0.636824f,2.26987e-019f,0.771009f},{0.636824f,-5.34995e-018f,0.771009f},{0.636824f,2.20943e-018f,0.771009f}, -{-0.975689f,-0.076394f,0.205416f},{-0.996976f,-0.0777152f,2.40026e-009f},{-0.996976f,-0.0777152f,1.82763e-009f}, -{0.0519161f,-5.69588e-006f,0.998651f},{-0.456027f,-0.0391237f,0.889106f},{0.0825944f,-1.3591e-005f,0.996583f}, -{-0.861638f,-0.0691877f,0.502785f},{-0.635452f,-0.050805f,0.770467f},{-0.996976f,-0.0777152f,6.35071e-010f}, -{-0.996976f,-0.0777152f,1.31007e-017f},{-0.917412f,-0.0749912f,0.390808f},{-0.856741f,-0.0700812f,0.510962f}, -{-0.282672f,-0.0305668f,0.95873f},{-0.436736f,-0.0398436f,0.898707f},{-0.663385f,-0.0583498f,0.746f}, -{-0.345792f,-0.0285025f,0.937878f},{-0.853315f,-0.0673689f,0.517025f},{0.113462f,-1.67093e-011f,0.993542f}, -{0.0211583f,-3.90359e-007f,0.999776f},{-0.996976f,-0.0777152f,1.22684e-009f},{-0.564161f,-0.362409f,0.741878f}, -{-0.264855f,-0.112973f,0.957648f},{-0.631536f,-0.215685f,0.744744f},{-0.75206f,-0.659094f,-1.94181e-007f}, -{-0.672214f,-0.631911f,0.385768f},{-0.794595f,-0.466608f,0.388454f},{-0.595421f,-0.803414f,4.71637e-006f}, -{-0.917412f,-0.0749922f,0.390808f},{-0.95773f,-0.28767f,5.42362e-007f},{-0.878015f,-0.277342f,0.390091f}, -{-0.0219211f,-0.346813f,0.937678f},{0.133312f,1.10489e-006f,0.991074f},{-0.102261f,-0.309574f,0.94536f}, -{-0.996976f,-0.0777152f,-3.03639e-015f},{-0.0424957f,-0.702528f,0.710387f},{0.0598835f,-0.929788f,0.363191f}, -{0.115053f,-0.707107f,0.697684f},{-0.411994f,-0.911187f,8.1719e-006f},{-0.336083f,-0.863203f,0.376735f}, -{-0.516581f,-0.766361f,0.381883f},{-0.141492f,-0.918012f,0.37045f},{-0.196474f,-0.664088f,0.721378f}, -{0.152291f,4.30608e-007f,0.988336f},{0.142379f,7.6959e-007f,0.989812f},{0.0637951f,-0.366351f,0.928287f}, -{-0.465521f,-0.48975f,0.73718f},{-0.227177f,-0.18976f,0.955187f},{0.151307f,-0.368095f,0.917394f}, -{0.162743f,1.2436e-015f,0.986669f},{-0.874519f,-0.484991f,1.45876e-006f},{-0.663385f,-0.0583523f,0.746f}, -{-0.282671f,-0.0305691f,0.95873f},{0.113463f,5.79189e-014f,0.993542f},{0.115403f,9.38329e-007f,0.993319f}, -{-0.172046f,-0.256288f,0.951166f},{0.119516f,3.02192e-008f,0.992832f},{0.125569f,-3.80451e-007f,0.992085f}, -{-0.340547f,-0.59209f,0.730382f},{-0.21143f,-0.977393f,5.28771e-006f},{0.0599047f,-0.929788f,0.363187f}, -{-6.95989e-015f,-1.0f,-4.64483e-014f},{0.0993814f,-0.87226f,0.478837f},{0.203217f,-1.63982e-015f,0.979134f}, -{0.177258f,-0.489042f,0.85406f},{0.119006f,-0.87226f,0.474341f},{0.212261f,-0.489042f,0.84604f}, -{0.151316f,-0.368095f,0.917393f},{0.162743f,-3.30488e-015f,0.986669f},{0.115076f,-0.707107f,0.69768f}, -{0.750862f,-0.640795f,0.159966f},{0.690083f,-0.633896f,0.34923f},{0.633689f,-0.773588f,4.47054e-006f}, -{0.119072f,-0.87226f,0.474324f},{0.226237f,-0.974072f,4.35889e-005f},{0.441461f,-0.89728f,1.9127e-005f}, -{0.314908f,-0.831026f,0.458507f},{0.793896f,-0.608053f,1.75822e-008f},{0.604452f,-0.56074f,0.56587f}, -{0.475573f,-0.362672f,0.801436f},{0.425828f,-0.412157f,0.805479f},{0.4929f,-0.748579f,0.443484f}, -{0.2123f,-0.489042f,0.84603f},{0.325164f,-0.461687f,0.825296f},{0.271328f,-2.66133e-006f,0.962487f}, -{0.262654f,-3.42352e-007f,0.96489f},{0.243346f,-1.05425e-016f,0.96994f},{0.253185f,-2.24678e-006f,0.967418f}, -{-0.875571f,-0.0666236f,-0.478474f},{-0.640323f,-0.0486817f,-0.766562f},{-0.513173f,-0.0370848f,-0.857483f}, -{-0.350245f,-0.0257948f,-0.936303f},{-0.0206959f,-4.01482e-007f,-0.999786f},{-0.0439641f,-5.59705e-006f,-0.999033f}, -{-0.616326f,-0.0410888f,-0.786418f},{-0.539132f,-0.036057f,-0.841449f},{-0.113495f,-3.41892e-007f,-0.993538f}, -{-0.880476f,-0.0653022f,-0.469573f},{-0.996948f,-0.0776561f,-0.00805682f},{-0.878213f,-0.0659754f,-0.473698f}, -{-0.902304f,-0.0665963f,-0.425926f},{-0.996904f,-0.0775964f,-0.0127207f},{-0.996967f,-0.0776912f,-0.00445868f}, -{-0.857586f,-0.0660304f,-0.510084f},{-0.52637f,-0.0365804f,-0.849468f},{-0.996974f,-0.0777085f,-0.00192216f}, -{-0.996976f,-0.0777145f,-0.000435368f},{-0.977579f,-0.0758877f,-0.196417f},{-0.0672213f,-1.00329e-005f,-0.997738f}, -{-0.0904433f,-1.17964e-005f,-0.995902f},{0.239165f,0.970979f,0.0f},{2.21189e-011f,1.0f,0.0f}, -{-9.4369e-017f,1.0f,0.0f},{0.934452f,0.35609f,0.0f},{0.822248f,0.569129f,0.0f}, -{0.823f,0.568041f,0.0f},{0.464996f,0.885313f,0.0f},{0.662288f,0.74925f,0.0f}, -{0.463813f,0.885933f,0.0f},{0.992785f,-0.119912f,0.0f},{0.935185f,-0.354158f,0.0f}, -{0.992772f,-0.120012f,0.0f},{0.934789f,0.355204f,0.0f},{0.992676f,0.120803f,0.0f}, -{0.99262f,0.12127f,0.0f},{0.823569f,-0.567216f,0.0f},{0.663361f,-0.7483f,0.0f}, -{0.823234f,-0.567703f,0.0f},{0.935249f,-0.353989f,0.0f},{0.663427f,-0.748241f,0.0f}, -{0.465239f,-0.885185f,0.0f},{0.465056f,-0.885281f,0.0f},{0.239511f,-0.970894f,0.0f}, -{0.239712f,-0.970844f,0.0f},{0.663196f,0.748446f,0.0f},{0.238516f,0.971139f,0.0f}, -{-1.11022e-016f,0.0f,-1.0f},{1.11022e-016f,0.0f,-1.0f},{5.55112e-017f,0.0f,-1.0f}, -{-5.55112e-017f,0.0f,-1.0f},{1.38778e-017f,1.0f,0.0f},{0.281866f,0.959454f,3.5075e-017f}, -{0.28018f,0.959948f,-4.21701e-019f},{0.989747f,0.142833f,2.49501e-017f},{0.909389f,0.415948f,-1.25209e-017f}, -{0.910294f,0.413963f,-4.85725e-018f},{0.755415f,0.655247f,1.3143e-017f},{0.53479f,0.844985f,1.81431e-018f}, -{0.542504f,0.840053f,1.76327e-018f},{0.910294f,-0.413963f,-1.17305e-017f},{0.989747f,-0.142833f,2.30199e-017f}, -{0.909389f,-0.415948f,2.57792e-017f},{0.989934f,0.141528f,-9.05295e-018f},{0.989934f,-0.141527f,2.56689e-017f}, -{0.542504f,-0.840053f,-5.88236e-019f},{0.755415f,-0.655247f,2.43207e-017f},{0.53479f,-0.844985f,-3.19936e-017f}, -{0.755193f,-0.655503f,8.23455e-018f},{0.28018f,-0.959948f,3.039e-017f},{0.281866f,-0.959454f,-5.9836e-018f}, -{7.40149e-017f,-1.0f,0.0f},{0.755193f,0.655503f,1.3143e-017f},{7.40149e-017f,1.0f,0.0f}, -{0.270909f,0.962605f,0.0f},{4.07586e-012f,1.0f,0.0f},{0.950963f,0.309304f,0.0f}, -{0.808694f,0.588229f,0.0f},{0.912501f,0.409074f,0.0f},{0.759143f,0.650924f,0.0f}, -{0.583716f,0.811958f,0.0f},{0.542309f,0.840179f,0.0f},{0.951446f,-0.307814f,0.0f}, -{0.905627f,-0.424076f,0.0f},{0.809042f,-0.587751f,0.0f},{0.990956f,0.134185f,0.0f}, -{0.988363f,-0.152115f,0.0f},{1.0f,2.72147e-017f,0.0f},{0.589654f,-0.807656f,0.0f}, -{0.749122f,-0.662432f,0.0f},{0.5326f,-0.846367f,0.0f},{0.275665f,-0.961254f,0.0f}, -{0.309676f,-0.950842f,0.0f},{0.305779f,0.952103f,0.0f},{0.272029f,0.962289f,0.0f}, -{-5.92119e-016f,1.0f,0.0f},{1.60011e-012f,1.0f,0.0f},{0.911657f,0.410952f,0.0f}, -{0.759835f,0.650115f,0.0f},{0.540288f,0.84148f,0.0f},{0.988688f,-0.149984f,0.0f}, -{0.905627f,-0.424076f,0.0f},{0.990518f,0.137383f,0.0f},{1.0f,3.70074e-017f,0.0f}, -{0.75011f,-0.661313f,0.0f},{0.534974f,-0.844868f,0.0f},{0.277678f,-0.960674f,0.0f}, -{1.19209e-007f,-1.0f,0.0f},{-0.133225f,0.157091f,0.978557f},{-0.301804f,-0.0247052f,0.95305f}, -{-0.321243f,-0.00178462f,0.946995f},{-0.418489f,0.112883f,0.901179f},{-0.243083f,0.286628f,0.92669f}, -{-0.225214f,0.265559f,0.93742f},{-0.452261f,-0.283519f,0.845622f},{-0.645f,-0.47632f,0.597573f}, -{-0.656839f,-0.462361f,0.595638f},{-0.282442f,-0.0475355f,0.958106f},{-0.114411f,0.134906f,0.984231f}, -{-0.765511f,-0.605729f,0.216993f},{-0.76115f,-0.610871f,0.217916f},{-0.244062f,-0.0927915f,0.96531f}, -{-0.469014f,-0.263765f,0.842884f},{-0.263186f,-0.0702416f,0.962185f},{-0.739853f,-0.635983f,-0.219416f}, -{-0.748269f,-0.62606f,0.219416f},{-0.757174f,-0.642143f,0.119748f},{-0.756818f,-0.615978f,0.218624f}, -{-0.504783f,-0.428095f,-0.749619f},{-0.38664f,-0.360895f,-0.848684f},{-0.598628f,-0.530999f,-0.599736f}, -{-0.712963f,-0.604648f,-0.355084f},{0.038317f,-0.0451812f,-0.998244f},{-0.150369f,-0.203268f,-0.967508f}, -{-0.169153f,-0.181119f,-0.968805f},{0.0191669f,-0.0226006f,-0.999561f},{-0.18253f,-0.1548f,-0.970938f}, -{4.02562e-016f,-4.74676e-016f,-1.0f},{-0.170486f,0.201027f,0.964636f},{-0.340727f,0.0211908f,0.939923f}, -{-0.360228f,0.0441843f,0.931817f},{-0.151922f,0.179137f,0.972023f},{-0.379711f,0.0671573f,0.922665f}, -{-0.1889f,0.222739f,0.956402f},{-0.588114f,-0.123331f,0.79932f},{-0.399143f,0.0900703f,0.912454f}, -{-0.207148f,0.244256f,0.947327f},{-0.437715f,0.135553f,0.888837f},{-0.260738f,0.307446f,0.915146f}, -{-0.475662f,0.180297f,0.860952f},{-0.49431f,0.202286f,0.845422f},{-0.312267f,0.368206f,0.875736f}, -{-0.456785f,0.158038f,0.875426f},{-0.36133f,0.426058f,0.829407f},{-0.345274f,0.407126f,0.845597f}, -{-0.530776f,0.245284f,0.811242f},{-0.328915f,0.387836f,0.861045f},{-0.392475f,0.462782f,0.794856f}, -{-0.565895f,0.286694f,0.773026f},{-0.582863f,0.306702f,0.752465f},{-0.548521f,0.266208f,0.792627f}, -{-0.436576f,0.514784f,0.737834f},{-0.615454f,0.345131f,0.708591f},{-0.450527f,0.531233f,0.717508f}, -{-0.599393f,0.326194f,0.730976f},{-0.489956f,0.577725f,0.652822f},{-0.477228f,0.562717f,0.674983f}, -{-0.660525f,0.398276f,0.636461f},{-0.464081f,0.547216f,0.696551f},{-0.646047f,0.381204f,0.661292f}, -{-0.525514f,0.619653f,0.58298f},{-0.687723f,0.430346f,0.58467f},{-0.700401f,0.445295f,0.557808f}, -{-0.674425f,0.414666f,0.610904f},{-0.723827f,0.472918f,0.502416f},{-0.55692f,0.656685f,0.508532f}, -{-0.546929f,0.644904f,0.533824f},{-0.536457f,0.632556f,0.558647f},{-0.583927f,0.68853f,0.430066f}, -{-0.575427f,0.678508f,0.45663f},{-0.753955f,0.508443f,0.415977f},{-0.734548f,0.48556f,0.473994f}, -{-0.762629f,0.518671f,0.386494f},{-0.59938f,0.706751f,0.375828f},{-0.591913f,0.697947f,0.403124f}, -{-0.784509f,0.54447f,0.296814f},{-0.612728f,0.72249f,0.32027f},{-0.777905f,0.536683f,0.326857f}, -{-0.60632f,0.714934f,0.348202f},{-0.770612f,0.528084f,0.356769f},{-0.623923f,0.735691f,0.263588f}, -{-0.795672f,0.557633f,0.236543f},{-0.628701f,0.741325f,0.234887f},{-0.790429f,0.551451f,0.266692f}, -{-0.618597f,0.729411f,0.292057f},{-0.632927f,0.746308f,0.205979f},{-0.804162f,0.567644f,0.176364f}, -{-0.636597f,0.750636f,0.176891f},{-0.800246f,0.563026f,0.206418f},{-0.814352f,0.57966f,0.0287253f}, -{-0.646797f,0.762662f,3.14853e-016f},{-0.646513f,0.762327f,0.0296338f},{-0.639708f,0.754304f,0.147647f}, -{-0.807432f,0.5715f,0.146429f},{-0.812092f,0.576994f,0.0870897f},{-0.949862f,0.30322f,0.0762915f}, -{-0.951107f,0.304688f,0.0506043f},{-0.645661f,0.761323f,0.0592414f},{-0.642257f,0.757309f,0.118274f}, -{-0.644242f,0.75965f,0.0887967f},{-0.813513f,0.57867f,0.0577667f},{-0.81007f,0.574611f,0.116657f}, -{-0.997518f,-0.0606536f,0.0357603f},{-0.885978f,-0.463681f,0.00650573f},{-0.998038f,-0.0600411f,0.0177823f}, -{-0.942915f,0.295029f,0.154497f},{-0.939484f,0.290984f,0.180824f},{-0.996638f,-0.061691f,0.0539127f}, -{-0.948091f,0.301132f,0.102193f},{-0.995387f,-0.0631666f,0.0722163f},{-0.991729f,-0.0674795f,0.109178f}, -{-0.602655f,-0.797758f,-0.0197241f},{-0.603113f,-0.797218f,-0.0264206f},{-0.223622f,-0.973184f,-0.0539127f}, -{-0.885009f,-0.464825f,0.0264206f},{-0.885466f,-0.464285f,0.0197241f},{0.14403f,-0.986628f,-0.0762915f}, -{0.145275f,-0.988096f,-0.0506043f},{-0.0805097f,-0.996754f,-1.10368e-016f},{-0.222222f,-0.974834f,-0.0177823f}, -{0.14601f,-0.988963f,-0.0251637f},{0.438888f,-0.898083f,-0.0287253f},{0.427652f,-0.903943f,-3.00521e-016f}, -{0.17704f,-0.984204f,-5.39175e-016f},{0.646797f,-0.762662f,-6.22394e-016f},{-0.930885f,0.280844f,0.233625f}, -{-0.712441f,0.459492f,0.530373f},{-0.566422f,0.66789f,0.482793f},{-0.744593f,0.497404f,0.445162f}, -{-0.872541f,0.212049f,0.440122f},{-0.514109f,0.606205f,0.606801f},{-0.502253f,0.592225f,0.630089f}, -{-0.631014f,0.363479f,0.68535f},{-0.422243f,0.497882f,0.757512f},{-0.804404f,0.131706f,0.579299f}, -{-0.893848f,-0.182894f,0.409371f},{-0.902811f,-0.172326f,0.394f},{-0.407538f,0.480543f,0.776525f}, -{-0.377068f,0.444615f,0.812488f},{-0.295345f,0.348252f,0.889658f},{-0.278164f,0.327993f,0.902799f}, -{-0.512693f,0.223962f,0.828846f},{-0.844231f,-0.241401f,0.47854f},{-0.718971f,0.030968f,0.69435f}, -{-0.833475f,-0.254083f,0.490674f},{-0.0954963f,0.112603f,0.98904f},{-0.0764977f,0.0902013f,0.992981f}, -{-0.0574318f,0.06772f,0.99605f},{-0.621631f,-0.503876f,0.599736f},{-0.71354f,-0.605138f,0.353084f}, -{-0.225096f,-0.115155f,0.967508f},{-0.0383156f,0.0451794f,0.998244f},{-0.206312f,-0.137304f,0.968805f}, -{-0.019166f,0.0225994f,0.999561f},{-0.757056f,-0.642042f,-0.121027f},{-0.182011f,-0.154359f,0.971105f}, -{-2.03646e-016f,2.40127e-016f,1.0f},{-0.355998f,-0.301914f,0.884372f},{-0.506241f,-0.429332f,0.747926f}, -{-0.419192f,-0.322513f,0.848684f},{-0.627779f,-0.532405f,0.567836f},{-0.435647f,-0.30311f,0.847547f}, -{-0.485883f,-0.243875f,0.839311f},{-0.502844f,-0.223875f,0.834882f},{-0.519872f,-0.203796f,0.829578f}, -{-0.536941f,-0.18367f,0.823383f},{-0.554024f,-0.163527f,0.816282f},{-0.571091f,-0.143403f,0.808264f}, -{-0.752979f,-0.348998f,0.557873f},{-0.764881f,-0.334964f,0.550232f},{-0.605061f,-0.103347f,0.789443f}, -{-0.621904f,-0.0834874f,0.778631f},{-0.638609f,-0.0637896f,0.766883f},{-0.655145f,-0.0442908f,0.754203f}, -{-0.671482f,-0.0250283f,0.740598f},{-0.687585f,-0.0060395f,0.726078f},{-0.703426f,0.0126381f,0.710657f}, -{-0.73419f,0.0489141f,0.677179f},{-0.749055f,0.0664415f,0.659168f},{-0.763535f,0.0835161f,0.640343f}, -{-0.777605f,0.100105f,0.620734f},{-0.791236f,0.116178f,0.600374f},{-0.817087f,0.146661f,0.557547f}, -{-0.829264f,0.161019f,0.535159f},{-0.840913f,0.174755f,0.512177f},{-0.852019f,0.187851f,0.488646f}, -{-0.862566f,0.200287f,0.464612f},{-0.8723f,-0.47981f,0.0942108f},{-0.954853f,-0.110961f,0.275577f}, -{-0.870179f,-0.48231f,0.100821f},{-0.881933f,0.223123f,0.415224f},{-0.890732f,0.233499f,0.389967f}, -{-0.898933f,0.243169f,0.3644f},{-0.906532f,0.252128f,0.338573f},{-0.913525f,0.260374f,0.312533f}, -{-0.919913f,0.267907f,0.286331f},{-0.925699f,0.274729f,0.260012f},{-0.935477f,0.286259f,0.207214f}, -{-0.989305f,-0.070338f,0.127782f},{-0.94578f,0.298407f,0.128274f},{-0.951842f,0.305555f,0.0251637f}, -{-0.938627f,0.344933f,7.30221e-017f},{-0.822203f,0.569194f,2.30577e-016f},{-0.627461f,-0.532136f,-0.56844f}, -{-0.63326f,-0.490164f,0.598933f},{-0.66876f,-0.448305f,0.593113f},{-0.680746f,-0.434172f,0.589983f}, -{-0.692779f,-0.419983f,0.586235f},{-0.704841f,-0.40576f,0.581857f},{-0.716913f,-0.391526f,0.576839f}, -{-0.728974f,-0.377304f,0.571173f},{-0.741003f,-0.36312f,0.564853f},{-0.776686f,-0.321045f,0.541931f}, -{-0.804996f,-0.55917f,0.198267f},{-0.809271f,-0.554129f,0.194989f},{-0.788372f,-0.307265f,0.53297f}, -{-0.799916f,-0.293653f,0.523356f},{-0.811296f,-0.280235f,0.513095f},{-0.82249f,-0.267036f,0.502197f}, -{-0.837294f,-0.521086f,0.165552f},{-0.650828f,-0.740956f,-0.165552f},{-0.64719f,-0.745245f,-0.160482f}, -{-0.854735f,-0.229015f,0.465812f},{-0.864968f,-0.216949f,0.452509f},{-0.87491f,-0.205226f,0.438652f}, -{-0.884543f,-0.193867f,0.424264f},{-0.857299f,-0.497498f,0.132416f},{-0.630822f,-0.764545f,-0.132417f}, -{-0.627951f,-0.767931f,-0.126333f},{-0.911416f,-0.16218f,0.378179f},{-0.919648f,-0.152473f,0.361938f}, -{-0.927496f,-0.143219f,0.34531f},{-0.93495f,-0.134431f,0.328326f},{-0.941998f,-0.126119f,0.31102f}, -{-0.948635f,-0.118293f,0.293425f},{-0.960649f,-0.104127f,0.25751f},{-0.966018f,-0.097796f,0.239258f}, -{-0.97096f,-0.0919688f,0.220857f},{-0.975475f,-0.0866457f,0.20234f},{-0.979563f,-0.0818252f,0.183742f}, -{-0.983228f,-0.0775037f,0.165095f},{-0.986473f,-0.0736768f,0.146431f},{-0.993754f,-0.0650924f,0.0906466f}, -{-0.602333f,-0.798137f,-0.0130831f},{-0.996651f,0.0817741f,3.49386e-017f},{-0.370185f,-0.380298f,-0.847547f}, -{-0.752523f,-0.621043f,0.219122f},{-0.769896f,-0.600558f,0.215848f},{-0.718226f,-0.661484f,-0.215848f}, -{-0.713823f,-0.666676f,-0.214476f},{-0.774298f,-0.595367f,0.214476f},{-0.778711f,-0.590164f,0.212875f}, -{-0.783128f,-0.584956f,0.211039f},{-0.78754f,-0.579753f,0.208966f},{-0.791941f,-0.574564f,0.206653f}, -{-0.796323f,-0.569397f,0.2041f},{-0.800677f,-0.564263f,0.201304f},{-0.813495f,-0.549149f,0.191472f}, -{-0.674627f,-0.712894f,-0.191472f},{-0.670463f,-0.717803f,-0.187718f},{-0.817658f,-0.54424f,0.187718f}, -{-0.821754f,-0.539411f,0.183731f},{-0.825773f,-0.534672f,0.179515f},{-0.829707f,-0.530032f,0.175076f}, -{-0.83355f,-0.525501f,0.170419f},{-0.840932f,-0.516797f,0.160482f},{-0.844456f,-0.512642f,0.155219f}, -{-0.84786f,-0.508628f,0.14977f},{-0.851139f,-0.504761f,0.144146f},{-0.854287f,-0.501049f,0.138358f}, -{-0.860171f,-0.494112f,0.126333f},{-0.862897f,-0.490897f,0.120119f},{-0.865476f,-0.487856f,0.113788f}, -{-0.867904f,-0.484993f,0.107351f},{-0.874264f,-0.477494f,0.0875334f},{-0.613858f,-0.784549f,-0.0875334f}, -{-0.61205f,-0.786681f,-0.0808013f},{-0.876072f,-0.475362f,0.0808013f},{-0.877724f,-0.473415f,0.0740269f}, -{-0.879219f,-0.471651f,0.0672227f},{-0.88056f,-0.47007f,0.0604006f},{-0.881747f,-0.46867f,0.0535724f}, -{-0.882783f,-0.467448f,0.0467496f},{-0.88367f,-0.466403f,0.0399431f},{-0.884411f,-0.465529f,0.0331634f}, -{-0.885788f,-0.463905f,0.0130831f},{-0.983879f,-0.178833f,5.93908e-017f},{-0.731303f,-0.646064f,-0.218624f}, -{-0.726972f,-0.651171f,-0.217917f},{-0.735599f,-0.640999f,-0.219122f},{-0.722611f,-0.656314f,-0.216992f}, -{-0.70941f,-0.671879f,-0.212875f},{-0.704994f,-0.677087f,-0.211039f},{-0.700581f,-0.682289f,-0.208966f}, -{-0.491286f,-0.657571f,-0.571173f},{-0.479257f,-0.671755f,-0.564852f},{-0.69618f,-0.687479f,-0.206653f}, -{-0.691799f,-0.692645f,-0.2041f},{-0.687444f,-0.69778f,-0.201305f},{-0.683125f,-0.702872f,-0.198267f}, -{-0.67885f,-0.707913f,-0.194989f},{-0.666368f,-0.722632f,-0.183731f},{-0.39777f,-0.767839f,-0.502197f}, -{-0.386784f,-0.780792f,-0.490674f},{-0.662349f,-0.727371f,-0.179515f},{-0.658414f,-0.73201f,-0.175076f}, -{-0.654571f,-0.736542f,-0.170419f},{-0.643666f,-0.749401f,-0.155219f},{-0.335717f,-0.841008f,-0.424264f}, -{-0.326411f,-0.851981f,-0.409371f},{-0.640261f,-0.753415f,-0.14977f},{-0.636982f,-0.757282f,-0.144146f}, -{-0.633834f,-0.760993f,-0.138358f},{-0.625224f,-0.771146f,-0.120119f},{-0.28531f,-0.900444f,-0.328326f}, -{-0.278262f,-0.908756f,-0.311019f},{-0.622645f,-0.774187f,-0.113788f},{-0.620218f,-0.77705f,-0.107351f}, -{-0.617942f,-0.779732f,-0.100821f},{-0.615822f,-0.782232f,-0.0942108f},{-0.610398f,-0.788628f,-0.0740269f}, -{-0.608902f,-0.790392f,-0.0672227f},{-0.240697f,-0.95305f,-0.183742f},{-0.237032f,-0.957371f,-0.165095f}, -{-0.607562f,-0.791973f,-0.0604006f},{-0.606374f,-0.793373f,-0.0535724f},{-0.605338f,-0.794594f,-0.0467497f}, -{-0.604451f,-0.79564f,-0.0399431f},{-0.603711f,-0.796513f,-0.0331634f},{-0.602143f,-0.798361f,-0.00650573f}, -{-0.762662f,-0.646797f,-1.07812e-032f},{-0.904079f,-0.427366f,5.07106e-017f},{-0.575259f,-0.558555f,-0.597573f}, -{-0.563421f,-0.572514f,-0.595638f},{-0.587f,-0.544711f,-0.598933f},{-0.5515f,-0.58657f,-0.593113f}, -{-0.539514f,-0.600703f,-0.589983f},{-0.527481f,-0.614892f,-0.586235f},{-0.515419f,-0.629115f,-0.581857f}, -{-0.503347f,-0.643349f,-0.576839f},{-0.46728f,-0.685877f,-0.557873f},{-0.183928f,-0.599921f,-0.778631f}, -{-0.455379f,-0.699911f,-0.550232f},{-0.443573f,-0.71383f,-0.541931f},{-0.431888f,-0.727609f,-0.53297f}, -{-0.420344f,-0.741222f,-0.523356f},{-0.408963f,-0.75464f,-0.513095f},{-0.0716416f,-0.732322f,-0.677179f}, -{-0.376029f,-0.793474f,-0.47854f},{-0.365525f,-0.80586f,-0.465812f},{-0.355292f,-0.817926f,-0.452509f}, -{-0.34535f,-0.829649f,-0.438652f},{0.0112556f,-0.830069f,-0.557547f},{-0.317449f,-0.862549f,-0.394f}, -{-0.308844f,-0.872695f,-0.378179f},{-0.300612f,-0.882402f,-0.361938f},{-0.292763f,-0.891656f,-0.34531f}, -{0.0761008f,-0.90653f,-0.415224f},{-0.271625f,-0.916582f,-0.293425f},{-0.265406f,-0.923914f,-0.275577f}, -{-0.259611f,-0.930748f,-0.25751f},{-0.254241f,-0.937079f,-0.239258f},{-0.249299f,-0.942906f,-0.220857f}, -{-0.244785f,-0.948229f,-0.20234f},{-0.233786f,-0.961198f,-0.146431f},{0.133653f,-0.974392f,-0.180824f}, -{-0.230955f,-0.964537f,-0.127782f},{-0.228531f,-0.967395f,-0.109178f},{-0.226506f,-0.969782f,-0.0906466f}, -{-0.224873f,-0.971708f,-0.0722163f},{-0.222742f,-0.974221f,-0.0357604f},{-0.337862f,-0.941196f,-1.55829e-016f}, -{-0.569614f,-0.821913f,-4.03832e-017f},{-0.348737f,-0.295756f,-0.889332f},{-0.353571f,-0.399889f,-0.845622f}, -{-0.336818f,-0.419643f,-0.842884f},{-0.319949f,-0.439533f,-0.839311f},{-0.302988f,-0.459533f,-0.834882f}, -{-0.28596f,-0.479612f,-0.829578f},{-0.26889f,-0.499738f,-0.823383f},{-0.251808f,-0.519881f,-0.816282f}, -{-0.234741f,-0.540006f,-0.808264f},{-0.217718f,-0.560077f,-0.79932f},{-0.20077f,-0.580061f,-0.789443f}, -{0.0813202f,-0.476462f,-0.875426f},{0.295347f,-0.348255f,-0.889657f},{0.100197f,-0.49872f,-0.860952f}, -{-0.167223f,-0.619618f,-0.766883f},{-0.150686f,-0.639117f,-0.754203f},{-0.13435f,-0.65838f,-0.740598f}, -{-0.118247f,-0.677368f,-0.726078f},{-0.102406f,-0.696046f,-0.710657f},{-0.0868611f,-0.714376f,-0.69435f}, -{-0.0567769f,-0.749849f,-0.659168f},{0.207399f,-0.625125f,-0.752465f},{-0.0422963f,-0.766924f,-0.640343f}, -{-0.0282275f,-0.783513f,-0.620733f},{-0.0145961f,-0.799586f,-0.600374f},{-0.00142744f,-0.815114f,-0.579299f}, -{0.29896f,-0.733089f,-0.610904f},{0.51411f,-0.606206f,-0.606799f},{0.312259f,-0.74877f,-0.58467f}, -{0.0234316f,-0.844427f,-0.535159f},{0.0350815f,-0.858163f,-0.512177f},{0.0461876f,-0.871259f,-0.488646f}, -{0.0567343f,-0.883695f,-0.464612f},{0.0667093f,-0.895457f,-0.440122f},{0.0849003f,-0.916907f,-0.389967f}, -{0.378491f,-0.826866f,-0.415977f},{0.0931016f,-0.926577f,-0.3644f},{0.1007f,-0.935536f,-0.338573f}, -{0.107693f,-0.943782f,-0.312533f},{0.114081f,-0.951315f,-0.286331f},{0.119867f,-0.958137f,-0.260012f}, -{0.125053f,-0.964252f,-0.233625f},{0.129645f,-0.969667f,-0.207214f},{0.137083f,-0.978437f,-0.154497f}, -{0.139948f,-0.981815f,-0.128274f},{0.142259f,-0.98454f,-0.102193f},{-0.131403f,-0.225632f,-0.96531f}, -{-0.112279f,-0.248182f,-0.962185f},{-0.0930223f,-0.270888f,-0.958106f},{-0.0736605f,-0.293718f,-0.95305f}, -{-0.054222f,-0.316638f,-0.946995f},{-0.034737f,-0.339614f,-0.939923f},{-0.0152368f,-0.362607f,-0.931817f}, -{0.00424604f,-0.38558f,-0.922665f},{0.0236779f,-0.408493f,-0.912454f},{0.0430246f,-0.431306f,-0.901179f}, -{0.0622506f,-0.453976f,-0.888837f},{0.118846f,-0.520709f,-0.845422f},{0.137229f,-0.542385f,-0.828846f}, -{0.155311f,-0.563707f,-0.811242f},{0.173056f,-0.584631f,-0.792627f},{0.19043f,-0.605117f,-0.773026f}, -{0.392477f,-0.462784f,-0.794854f},{0.223929f,-0.644617f,-0.730976f},{0.239989f,-0.663554f,-0.708591f}, -{0.25555f,-0.681902f,-0.68535f},{0.270582f,-0.699627f,-0.661292f},{0.28506f,-0.716699f,-0.636461f}, -{0.324937f,-0.763719f,-0.557808f},{0.336976f,-0.777915f,-0.530373f},{0.348363f,-0.791341f,-0.502416f}, -{0.359084f,-0.803983f,-0.473994f},{0.369129f,-0.815827f,-0.445162f},{0.575428f,-0.678509f,-0.456627f}, -{0.387165f,-0.837094f,-0.386494f},{0.395148f,-0.846507f,-0.356769f},{0.40244f,-0.855106f,-0.326857f}, -{0.409044f,-0.862893f,-0.296814f},{0.414964f,-0.869874f,-0.266692f},{0.420207f,-0.876056f,-0.236543f}, -{0.424781f,-0.881449f,-0.206418f},{0.428697f,-0.886067f,-0.176364f},{0.431968f,-0.889923f,-0.146429f}, -{0.434606f,-0.893034f,-0.116657f},{0.436627f,-0.895417f,-0.0870897f},{0.438049f,-0.897093f,-0.0577667f}, -{0.0574334f,-0.067722f,-0.99605f},{0.0764992f,-0.090203f,-0.992981f},{0.0954975f,-0.112605f,-0.98904f}, -{0.114412f,-0.134908f,-0.98423f},{0.133227f,-0.157093f,-0.978556f},{0.151924f,-0.179139f,-0.972023f}, -{0.170488f,-0.201028f,-0.964635f},{0.188902f,-0.222741f,-0.956401f},{0.20715f,-0.244258f,-0.947326f}, -{0.225216f,-0.265561f,-0.937419f},{0.243085f,-0.28663f,-0.926689f},{0.260739f,-0.307448f,-0.915145f}, -{0.278165f,-0.327995f,-0.902798f},{0.312269f,-0.368208f,-0.875734f},{0.328917f,-0.387838f,-0.861043f}, -{0.345276f,-0.407127f,-0.845596f},{0.361331f,-0.426059f,-0.829405f},{0.37707f,-0.444617f,-0.812486f}, -{0.407539f,-0.480545f,-0.776523f},{0.422244f,-0.497883f,-0.757511f},{0.436577f,-0.514784f,-0.737833f}, -{0.450527f,-0.531233f,-0.717507f},{0.464082f,-0.547216f,-0.696551f},{0.477229f,-0.562718f,-0.674982f}, -{0.489956f,-0.577726f,-0.652821f},{0.502254f,-0.592226f,-0.630087f},{0.525515f,-0.619654f,-0.582978f}, -{0.536458f,-0.632557f,-0.558645f},{0.546929f,-0.644905f,-0.533822f},{0.556921f,-0.656686f,-0.508529f}, -{0.566423f,-0.667891f,-0.48279f},{0.583927f,-0.688531f,-0.430063f},{0.591914f,-0.697948f,-0.403122f}, -{0.59938f,-0.706752f,-0.375826f},{0.606321f,-0.714935f,-0.3482f},{0.612728f,-0.722491f,-0.320268f}, -{0.618598f,-0.729411f,-0.292055f},{0.623924f,-0.735692f,-0.263585f},{0.628702f,-0.741326f,-0.234884f}, -{0.632928f,-0.746309f,-0.205977f},{0.636597f,-0.750636f,-0.176888f},{0.639708f,-0.754304f,-0.147645f}, -{0.642257f,-0.757309f,-0.118272f},{0.644242f,-0.75965f,-0.0887941f},{0.645661f,-0.761323f,-0.0592391f}, -{0.646513f,-0.762327f,-0.0296323f},{0.632928f,-0.746309f,0.205977f},{0.428697f,-0.886067f,0.176364f}, -{0.424781f,-0.881449f,0.206418f},{0.395148f,-0.846507f,0.356769f},{0.59938f,-0.706752f,0.375826f}, -{0.606321f,-0.714935f,0.3482f},{0.434606f,-0.893034f,0.116657f},{0.436627f,-0.895417f,0.0870897f}, -{0.142259f,-0.98454f,0.102193f},{0.639708f,-0.754304f,0.147645f},{0.642257f,-0.757309f,0.118272f}, -{-0.222222f,-0.974834f,0.0177823f},{-0.337862f,-0.941196f,3.41808e-016f},{-0.602143f,-0.798361f,0.00650572f}, -{-0.223622f,-0.973184f,0.0539127f},{-0.224873f,-0.971708f,0.0722163f},{0.14403f,-0.986628f,0.0762915f}, -{-0.885978f,-0.463681f,-0.00650572f},{-0.983879f,-0.178833f,-4.69192e-016f},{-0.998038f,-0.0600412f,-0.0177823f}, -{-0.602655f,-0.797758f,0.0197241f},{-0.603113f,-0.797218f,0.0264206f},{-0.814352f,0.579659f,-0.0287252f}, -{-0.813513f,0.57867f,-0.0577667f},{-0.951842f,0.305555f,-0.0251636f},{-0.996651f,0.0817739f,-5.50975e-016f}, -{-0.646797f,0.762662f,-9.3359e-016f},{-0.822203f,0.569194f,-3.00566e-016f},{-0.645661f,0.761323f,-0.0592414f}, -{0.431968f,-0.889923f,0.146429f},{0.636597f,-0.750636f,0.176888f},{-0.646513f,0.762327f,-0.0296337f}, -{0.623924f,-0.735692f,0.263585f},{0.420207f,-0.876056f,0.236543f},{0.414964f,-0.869874f,0.266692f}, -{0.628702f,-0.741326f,0.234884f},{0.409044f,-0.862893f,0.296814f},{0.618598f,-0.729411f,0.292055f}, -{0.40244f,-0.855106f,0.326857f},{0.612728f,-0.722491f,0.320268f},{0.387165f,-0.837094f,0.386494f}, -{0.591914f,-0.697948f,0.403122f},{0.369129f,-0.815827f,0.445162f},{0.359084f,-0.803983f,0.473994f}, -{0.566423f,-0.667891f,0.48279f},{0.378491f,-0.826866f,0.415977f},{0.536458f,-0.632557f,0.558645f}, -{0.546929f,-0.644905f,0.533822f},{0.336976f,-0.777915f,0.530373f},{0.556921f,-0.656686f,0.508529f}, -{0.51411f,-0.606206f,0.606799f},{0.312259f,-0.74877f,0.58467f},{0.29896f,-0.733089f,0.610904f}, -{0.324937f,-0.763719f,0.557808f},{0.477229f,-0.562718f,0.674982f},{0.270582f,-0.699627f,0.661292f}, -{0.464082f,-0.547216f,0.696551f},{0.28506f,-0.716699f,0.636461f},{0.422243f,-0.497883f,0.757511f}, -{0.436577f,-0.514784f,0.737833f},{0.223929f,-0.644617f,0.730976f},{0.450527f,-0.531233f,0.717507f}, -{0.239989f,-0.663554f,0.708591f},{0.37707f,-0.444617f,0.812486f},{0.19043f,-0.605117f,0.773026f}, -{0.173056f,-0.584631f,0.792627f},{0.207399f,-0.625125f,0.752465f},{0.137229f,-0.542385f,0.828846f}, -{0.328917f,-0.387838f,0.861043f},{0.345276f,-0.407127f,0.845596f},{0.361331f,-0.426059f,0.829405f}, -{0.278165f,-0.327995f,0.902798f},{0.295347f,-0.348255f,0.889657f},{0.0813203f,-0.476461f,0.875426f}, -{0.118846f,-0.520709f,0.845422f},{0.0622506f,-0.453976f,0.888837f},{0.243085f,-0.28663f,0.926689f}, -{0.260739f,-0.307447f,0.915145f},{0.00424601f,-0.38558f,0.922665f},{0.20715f,-0.244258f,0.947326f}, -{0.023678f,-0.408493f,0.912454f},{0.225216f,-0.265561f,0.937419f},{0.0430246f,-0.431306f,0.901179f}, -{0.170488f,-0.201028f,0.964635f},{-0.0152368f,-0.362607f,0.931817f},{-0.034737f,-0.339614f,0.939923f}, -{0.188902f,-0.222741f,0.956401f},{0.133227f,-0.157093f,0.978556f},{-0.054222f,-0.316638f,0.946995f}, -{-0.0736605f,-0.293718f,0.95305f},{0.151924f,-0.179139f,0.972023f},{0.0954975f,-0.112605f,0.98904f}, -{0.114412f,-0.134908f,0.98423f},{-0.0930223f,-0.270888f,0.958106f},{-0.731303f,-0.646064f,0.218624f}, -{-0.575259f,-0.558555f,0.597573f},{-0.563421f,-0.572514f,0.595638f},{-0.169153f,-0.181119f,0.968805f}, -{0.0383171f,-0.0451812f,0.998244f},{-0.150369f,-0.203268f,0.967508f},{0.019167f,-0.0226006f,0.999561f}, -{-0.131403f,-0.225632f,0.96531f},{-0.112279f,-0.248181f,0.962185f},{-0.353571f,-0.399889f,0.845622f}, -{0.0574335f,-0.0677219f,0.99605f},{0.0764992f,-0.090203f,0.992981f},{-0.28596f,-0.479612f,0.829578f}, -{-0.539514f,-0.600703f,0.589983f},{-0.302988f,-0.459533f,0.834882f},{-0.726972f,-0.651171f,0.217917f}, -{-0.336818f,-0.419643f,0.842884f},{-0.756818f,-0.615978f,-0.218624f},{-0.752523f,-0.621043f,-0.219122f}, -{-0.735599f,-0.640999f,0.219122f},{-0.452261f,-0.283519f,-0.845622f},{-0.435647f,-0.30311f,-0.847547f}, -{-0.645f,-0.47632f,-0.597573f},{-0.506241f,-0.429332f,-0.747926f},{-0.621631f,-0.503876f,-0.599737f}, -{-0.419192f,-0.322513f,-0.848684f},{-0.206312f,-0.137304f,-0.968805f},{-0.355998f,-0.301914f,-0.884372f}, -{-0.182011f,-0.154359f,-0.971105f},{-0.0191661f,0.0225993f,-0.999561f},{-2.93527e-009f,-2.48934e-009f,1.0f}, -{-0.18253f,-0.1548f,0.970938f},{-0.251808f,-0.519881f,0.816282f},{0.155311f,-0.563707f,0.811242f}, -{0.312269f,-0.368208f,0.875734f},{0.100197f,-0.49872f,0.860952f},{-0.118246f,-0.677368f,0.726078f}, -{0.392477f,-0.462784f,0.794854f},{0.407539f,-0.480545f,0.776523f},{0.25555f,-0.681902f,0.68535f}, -{0.489956f,-0.577726f,0.652821f},{-0.0282274f,-0.783513f,0.620733f},{-0.34535f,-0.829649f,0.438652f}, -{-0.355292f,-0.817926f,0.452509f},{0.502254f,-0.592226f,0.630087f},{0.525515f,-0.619654f,0.582978f}, -{0.575428f,-0.678509f,0.456627f},{0.583927f,-0.688531f,0.430063f},{0.348363f,-0.791341f,0.502416f}, -{-0.300612f,-0.882402f,0.361938f},{0.0461875f,-0.871259f,0.488646f},{-0.292763f,-0.891656f,0.34531f}, -{0.114081f,-0.951315f,0.286331f},{0.644242f,-0.75965f,0.0887942f},{-0.762662f,-0.646797f,1.22271e-018f}, -{0.645661f,-0.761323f,0.059239f},{0.438049f,-0.897093f,0.0577667f},{0.14601f,-0.988963f,0.0251636f}, -{-0.0805097f,-0.996754f,5.00783e-016f},{0.646513f,-0.762327f,0.0296322f},{0.438888f,-0.898083f,0.0287252f}, -{0.427652f,-0.903943f,6.47993e-016f},{0.17704f,-0.984204f,6.55067e-016f},{0.646797f,-0.762662f,9.4456e-016f}, -{-0.569614f,-0.821913f,2.60919e-016f},{-0.904079f,-0.427366f,-2.0282e-016f},{0.145275f,-0.988096f,0.0506042f}, -{0.139948f,-0.981815f,0.128274f},{0.137083f,-0.978437f,0.154497f},{0.133653f,-0.974392f,0.180824f}, -{0.129646f,-0.969667f,0.207214f},{0.125053f,-0.964252f,0.233625f},{0.119867f,-0.958137f,0.260012f}, -{-0.249299f,-0.942906f,0.220857f},{-0.254241f,-0.937079f,0.239258f},{0.107693f,-0.943782f,0.312533f}, -{0.1007f,-0.935536f,0.338573f},{0.0931016f,-0.926577f,0.3644f},{0.0849004f,-0.916907f,0.389967f}, -{0.0761008f,-0.906531f,0.415224f},{0.0667093f,-0.895457f,0.440122f},{0.0567345f,-0.883695f,0.464612f}, -{0.0350815f,-0.858163f,0.512177f},{0.0234317f,-0.844426f,0.535159f},{0.0112556f,-0.830069f,0.557547f}, -{-0.00142745f,-0.815114f,0.579299f},{-0.0145962f,-0.799586f,0.600374f},{-0.0422964f,-0.766924f,0.640343f}, -{-0.0567769f,-0.749849f,0.659168f},{-0.0716415f,-0.732322f,0.677179f},{-0.0868612f,-0.714376f,0.69435f}, -{-0.102406f,-0.696046f,0.710657f},{-0.683125f,-0.702872f,0.198267f},{-0.431888f,-0.72761f,0.53297f}, -{-0.67885f,-0.707914f,0.194989f},{-0.13435f,-0.65838f,0.740598f},{-0.150686f,-0.639117f,0.754203f}, -{-0.167223f,-0.619618f,0.766883f},{-0.183928f,-0.599921f,0.778631f},{-0.20077f,-0.580061f,0.789443f}, -{-0.217718f,-0.560078f,0.79932f},{-0.234741f,-0.540005f,0.808264f},{-0.26889f,-0.499738f,0.823383f}, -{-0.527481f,-0.614892f,0.586235f},{-0.319949f,-0.439533f,0.839311f},{-0.370185f,-0.380298f,0.847547f}, -{-0.38664f,-0.360895f,0.848684f},{-0.348737f,-0.295756f,0.889332f},{-0.951107f,0.304688f,-0.0506042f}, -{-0.222742f,-0.974221f,0.0357603f},{-0.226506f,-0.969783f,0.0906467f},{-0.228531f,-0.967395f,0.109178f}, -{-0.230955f,-0.964537f,0.127782f},{-0.233786f,-0.961198f,0.146431f},{-0.237032f,-0.957371f,0.165095f}, -{-0.240697f,-0.95305f,0.183742f},{-0.244785f,-0.948229f,0.20234f},{-0.259611f,-0.930748f,0.25751f}, -{-0.615822f,-0.782232f,0.0942108f},{-0.617942f,-0.779732f,0.100821f},{-0.265406f,-0.923914f,0.275577f}, -{-0.271625f,-0.916582f,0.293425f},{-0.278261f,-0.908756f,0.31102f},{-0.28531f,-0.900444f,0.328326f}, -{-0.636982f,-0.757282f,0.144146f},{-0.851139f,-0.504761f,-0.144146f},{-0.84786f,-0.508627f,-0.14977f}, -{-0.308844f,-0.872695f,0.378179f},{-0.317449f,-0.862549f,0.394f},{-0.326411f,-0.851981f,0.409371f}, -{-0.335717f,-0.841008f,0.424264f},{-0.658414f,-0.73201f,0.175076f},{-0.829707f,-0.530032f,-0.175076f}, -{-0.825773f,-0.534672f,-0.179515f},{-0.365525f,-0.80586f,0.465812f},{-0.376029f,-0.793474f,0.47854f}, -{-0.386784f,-0.780792f,0.490674f},{-0.39777f,-0.767839f,0.502197f},{-0.408963f,-0.75464f,0.513095f}, -{-0.420343f,-0.741222f,0.523356f},{-0.443573f,-0.71383f,0.541931f},{-0.455379f,-0.699911f,0.550232f}, -{-0.46728f,-0.685877f,0.557873f},{-0.479257f,-0.671755f,0.564853f},{-0.491286f,-0.657571f,0.571173f}, -{-0.503347f,-0.643349f,0.576839f},{-0.515418f,-0.629115f,0.581857f},{-0.5515f,-0.58657f,0.593113f}, -{-0.748269f,-0.62606f,-0.219416f},{-0.587f,-0.544711f,0.598933f},{-0.598628f,-0.530999f,0.599736f}, -{-0.504783f,-0.428095f,0.749619f},{-0.603711f,-0.796513f,0.0331634f},{-0.602333f,-0.798137f,0.0130831f}, -{-0.604451f,-0.79564f,0.0399431f},{-0.88367f,-0.466402f,-0.0399431f},{-0.882783f,-0.467448f,-0.0467496f}, -{-0.605338f,-0.794594f,0.0467496f},{-0.606374f,-0.793373f,0.0535724f},{-0.607562f,-0.791973f,0.0604006f}, -{-0.608902f,-0.790392f,0.0672227f},{-0.610398f,-0.788628f,0.0740269f},{-0.61205f,-0.786681f,0.0808012f}, -{-0.613858f,-0.784549f,0.0875334f},{-0.620218f,-0.77705f,0.107351f},{-0.867904f,-0.484993f,-0.107351f}, -{-0.865476f,-0.487856f,-0.113788f},{-0.622646f,-0.774187f,0.113788f},{-0.625224f,-0.771146f,0.120119f}, -{-0.627951f,-0.767931f,0.126333f},{-0.630822f,-0.764545f,0.132417f},{-0.633834f,-0.760993f,0.138358f}, -{-0.640261f,-0.753415f,0.14977f},{-0.643666f,-0.749401f,0.155219f},{-0.64719f,-0.745245f,0.160482f}, -{-0.650827f,-0.740956f,0.165552f},{-0.654571f,-0.736542f,0.170419f},{-0.662349f,-0.727371f,0.179515f}, -{-0.666368f,-0.722632f,0.183731f},{-0.670463f,-0.717803f,0.187718f},{-0.674627f,-0.712894f,0.191472f}, -{-0.687445f,-0.69778f,0.201304f},{-0.800677f,-0.564263f,-0.201304f},{-0.796323f,-0.569397f,-0.2041f}, -{-0.691799f,-0.692645f,0.2041f},{-0.69618f,-0.687479f,0.206653f},{-0.700581f,-0.68229f,0.208966f}, -{-0.704994f,-0.677087f,0.211039f},{-0.70941f,-0.671879f,0.212875f},{-0.713823f,-0.666676f,0.214476f}, -{-0.718226f,-0.661484f,0.215848f},{-0.722611f,-0.656314f,0.216993f},{-0.739853f,-0.635983f,0.219416f}, -{-0.757174f,-0.642143f,-0.119748f},{-0.757056f,-0.642042f,0.121027f},{-0.712963f,-0.604648f,0.355084f}, -{-0.627461f,-0.532136f,0.56844f},{-0.885466f,-0.464285f,-0.0197242f},{-0.885009f,-0.464825f,-0.0264206f}, -{-0.885788f,-0.463905f,-0.013083f},{-0.884411f,-0.465529f,-0.0331634f},{-0.881747f,-0.46867f,-0.0535725f}, -{-0.88056f,-0.47007f,-0.0604006f},{-0.879219f,-0.471651f,-0.0672226f},{-0.979563f,-0.0818251f,-0.183742f}, -{-0.975475f,-0.0866458f,-0.20234f},{-0.877724f,-0.473414f,-0.074027f},{-0.876072f,-0.475362f,-0.0808012f}, -{-0.874264f,-0.477494f,-0.0875334f},{-0.8723f,-0.47981f,-0.0942108f},{-0.870179f,-0.482311f,-0.100821f}, -{-0.862897f,-0.490897f,-0.120119f},{-0.93495f,-0.134431f,-0.328326f},{-0.927496f,-0.143219f,-0.34531f}, -{-0.860171f,-0.494112f,-0.126333f},{-0.857299f,-0.497498f,-0.132416f},{-0.854287f,-0.501049f,-0.138358f}, -{-0.844456f,-0.512642f,-0.155219f},{-0.884543f,-0.193867f,-0.424264f},{-0.87491f,-0.205225f,-0.438652f}, -{-0.840931f,-0.516798f,-0.160482f},{-0.837294f,-0.521086f,-0.165552f},{-0.83355f,-0.525501f,-0.170419f}, -{-0.821754f,-0.539411f,-0.183731f},{-0.82249f,-0.267036f,-0.502197f},{-0.811296f,-0.280235f,-0.513095f}, -{-0.817658f,-0.54424f,-0.187718f},{-0.813495f,-0.549149f,-0.191472f},{-0.809271f,-0.554129f,-0.194989f}, -{-0.804996f,-0.55917f,-0.198267f},{-0.791941f,-0.574564f,-0.206653f},{-0.78754f,-0.579753f,-0.208966f}, -{-0.728974f,-0.377304f,-0.571173f},{-0.716913f,-0.391526f,-0.576839f},{-0.783128f,-0.584956f,-0.211039f}, -{-0.778711f,-0.590164f,-0.212874f},{-0.774298f,-0.595367f,-0.214476f},{-0.769896f,-0.600558f,-0.215847f}, -{-0.765511f,-0.605729f,-0.216993f},{-0.76115f,-0.610871f,-0.217917f},{-0.996638f,-0.061691f,-0.0539127f}, -{-0.995387f,-0.0631666f,-0.0722163f},{-0.997518f,-0.0606535f,-0.0357603f},{-0.993754f,-0.0650924f,-0.0906467f}, -{-0.991729f,-0.0674796f,-0.109178f},{-0.989305f,-0.0703379f,-0.127782f},{-0.986473f,-0.0736768f,-0.146431f}, -{-0.983228f,-0.0775037f,-0.165095f},{-0.97096f,-0.0919687f,-0.220857f},{-0.906532f,0.252128f,-0.338573f}, -{-0.966018f,-0.0977961f,-0.239258f},{-0.960649f,-0.104127f,-0.25751f},{-0.954853f,-0.110961f,-0.275577f}, -{-0.948635f,-0.118294f,-0.293425f},{-0.941998f,-0.126119f,-0.31102f},{-0.840913f,0.174755f,-0.512177f}, -{-0.919648f,-0.152473f,-0.361938f},{-0.911416f,-0.16218f,-0.378179f},{-0.902811f,-0.172326f,-0.394f}, -{-0.893848f,-0.182894f,-0.409371f},{-0.763536f,0.0835161f,-0.640343f},{-0.864968f,-0.216949f,-0.452509f}, -{-0.854735f,-0.229015f,-0.465812f},{-0.844231f,-0.241401f,-0.47854f},{-0.833475f,-0.254083f,-0.490674f}, -{-0.671482f,-0.0250282f,-0.740598f},{-0.799916f,-0.293653f,-0.523356f},{-0.788372f,-0.307266f,-0.53297f}, -{-0.776686f,-0.321045f,-0.541931f},{-0.764881f,-0.334964f,-0.550232f},{-0.752979f,-0.348998f,-0.557873f}, -{-0.741003f,-0.36312f,-0.564853f},{-0.704841f,-0.40576f,-0.581857f},{-0.519872f,-0.203796f,-0.829578f}, -{-0.692779f,-0.419983f,-0.586235f},{-0.680746f,-0.434172f,-0.589983f},{-0.66876f,-0.448305f,-0.593113f}, -{-0.656839f,-0.462361f,-0.595638f},{-0.63326f,-0.490164f,-0.598933f},{-0.71354f,-0.605138f,-0.353084f}, -{-0.938627f,0.344933f,-6.77795e-016f},{-0.949862f,0.30322f,-0.0762915f},{-0.948091f,0.301132f,-0.102193f}, -{-0.94578f,0.298407f,-0.128274f},{-0.942915f,0.295029f,-0.154497f},{-0.939484f,0.290984f,-0.180824f}, -{-0.935477f,0.286259f,-0.207214f},{-0.930885f,0.280844f,-0.233625f},{-0.925699f,0.274728f,-0.260012f}, -{-0.919913f,0.267907f,-0.286331f},{-0.913525f,0.260374f,-0.312533f},{-0.753955f,0.508443f,-0.415977f}, -{-0.575427f,0.678508f,-0.45663f},{-0.744593f,0.497404f,-0.445162f},{-0.898933f,0.243169f,-0.3644f}, -{-0.890732f,0.233499f,-0.389967f},{-0.881933f,0.223123f,-0.415224f},{-0.872541f,0.212048f,-0.440122f}, -{-0.862566f,0.200287f,-0.464612f},{-0.852019f,0.187851f,-0.488646f},{-0.829264f,0.161019f,-0.535159f}, -{-0.674425f,0.414665f,-0.610904f},{-0.817087f,0.146661f,-0.557547f},{-0.804404f,0.131706f,-0.579299f}, -{-0.791236f,0.116178f,-0.600374f},{-0.777605f,0.100105f,-0.620733f},{-0.582863f,0.306702f,-0.752465f}, -{-0.392475f,0.462782f,-0.794856f},{-0.565895f,0.286694f,-0.773026f},{-0.749055f,0.0664413f,-0.659168f}, -{-0.73419f,0.0489142f,-0.677179f},{-0.718971f,0.0309681f,-0.69435f},{-0.703426f,0.012638f,-0.710657f}, -{-0.687585f,-0.00603948f,-0.726078f},{-0.655146f,-0.0442909f,-0.754203f},{-0.456785f,0.158039f,-0.875426f}, -{-0.638609f,-0.0637896f,-0.766883f},{-0.621904f,-0.0834874f,-0.778631f},{-0.605061f,-0.103347f,-0.789443f}, -{-0.588114f,-0.123331f,-0.79932f},{-0.571091f,-0.143402f,-0.808264f},{-0.554024f,-0.163527f,-0.816282f}, -{-0.536942f,-0.18367f,-0.823383f},{-0.502844f,-0.223875f,-0.834882f},{-0.485883f,-0.243875f,-0.839311f}, -{-0.469014f,-0.263765f,-0.842884f},{-0.627779f,-0.532405f,-0.567836f},{-0.812092f,0.576994f,-0.0870897f}, -{-0.81007f,0.57461f,-0.116657f},{-0.807432f,0.5715f,-0.146429f},{-0.804162f,0.567644f,-0.176364f}, -{-0.800246f,0.563026f,-0.206418f},{-0.795672f,0.557633f,-0.236543f},{-0.790429f,0.551451f,-0.266692f}, -{-0.784509f,0.54447f,-0.296814f},{-0.777905f,0.536683f,-0.326857f},{-0.770612f,0.528084f,-0.356769f}, -{-0.762629f,0.518671f,-0.386494f},{-0.734548f,0.48556f,-0.473994f},{-0.723827f,0.472918f,-0.502416f}, -{-0.712441f,0.459492f,-0.530373f},{-0.700401f,0.445295f,-0.557808f},{-0.687723f,0.430346f,-0.58467f}, -{-0.514109f,0.606205f,-0.606801f},{-0.660525f,0.398276f,-0.636461f},{-0.646047f,0.381204f,-0.661292f}, -{-0.631014f,0.363479f,-0.68535f},{-0.615454f,0.345131f,-0.708591f},{-0.599393f,0.326194f,-0.730976f}, -{-0.548521f,0.266208f,-0.792627f},{-0.530776f,0.245284f,-0.811242f},{-0.512694f,0.223962f,-0.828846f}, -{-0.49431f,0.202286f,-0.845422f},{-0.475662f,0.180297f,-0.860952f},{-0.295345f,0.348252f,-0.889658f}, -{-0.437715f,0.135553f,-0.888837f},{-0.418489f,0.112883f,-0.901179f},{-0.399143f,0.0900703f,-0.912454f}, -{-0.379711f,0.0671571f,-0.922664f},{-0.360228f,0.0441843f,-0.931817f},{-0.340728f,0.0211909f,-0.939923f}, -{-0.321243f,-0.00178467f,-0.946995f},{-0.301804f,-0.0247052f,-0.95305f},{-0.282442f,-0.0475355f,-0.958106f}, -{-0.263186f,-0.0702415f,-0.962185f},{-0.244062f,-0.0927915f,-0.96531f},{-0.225096f,-0.115155f,-0.967508f}, -{-0.644242f,0.75965f,-0.0887968f},{-0.642257f,0.757309f,-0.118274f},{-0.639708f,0.754304f,-0.147647f}, -{-0.636597f,0.750636f,-0.176891f},{-0.632927f,0.746308f,-0.205979f},{-0.628701f,0.741325f,-0.234887f}, -{-0.623923f,0.735691f,-0.263588f},{-0.618597f,0.729411f,-0.292057f},{-0.612728f,0.72249f,-0.320271f}, -{-0.60632f,0.714934f,-0.348202f},{-0.59938f,0.706751f,-0.375828f},{-0.591913f,0.697947f,-0.403124f}, -{-0.583927f,0.68853f,-0.430066f},{-0.566422f,0.66789f,-0.482793f},{-0.55692f,0.656685f,-0.508532f}, -{-0.546929f,0.644904f,-0.533824f},{-0.536457f,0.632556f,-0.558647f},{-0.525514f,0.619653f,-0.58298f}, -{-0.502253f,0.592225f,-0.630088f},{-0.489956f,0.577725f,-0.652822f},{-0.477228f,0.562717f,-0.674983f}, -{-0.464081f,0.547216f,-0.696551f},{-0.450527f,0.531233f,-0.717508f},{-0.436576f,0.514783f,-0.737834f}, -{-0.422243f,0.497882f,-0.757512f},{-0.407538f,0.480543f,-0.776525f},{-0.377068f,0.444615f,-0.812488f}, -{-0.36133f,0.426058f,-0.829407f},{-0.345274f,0.407126f,-0.845597f},{-0.328915f,0.387836f,-0.861045f}, -{-0.312267f,0.368206f,-0.875736f},{-0.278164f,0.327993f,-0.902799f},{-0.260738f,0.307446f,-0.915146f}, -{-0.243083f,0.286628f,-0.92669f},{-0.225214f,0.265559f,-0.93742f},{-0.207148f,0.244256f,-0.947327f}, -{-0.1889f,0.222739f,-0.956402f},{-0.170486f,0.201027f,-0.964636f},{-0.151922f,0.179137f,-0.972023f}, -{-0.133225f,0.157091f,-0.978557f},{-0.114411f,0.134906f,-0.984231f},{-0.0954964f,0.112603f,-0.98904f}, -{-0.0764977f,0.0902013f,-0.992981f},{-0.0574318f,0.0677199f,-0.99605f},{-0.0383156f,0.0451794f,-0.998244f}, -{-0.336976f,0.777915f,-0.530373f},{-0.324937f,0.763719f,-0.557808f},{-0.536458f,0.632557f,-0.558645f}, -{-0.546929f,0.644905f,-0.533822f},{0.633834f,0.760993f,-0.138358f},{0.317449f,0.862549f,-0.394f}, -{0.308844f,0.872695f,-0.378179f},{-0.359084f,0.803983f,-0.473994f},{-0.556921f,0.656686f,-0.508529f}, -{-0.566423f,0.667891f,-0.48279f},{-0.348363f,0.791341f,-0.502416f},{-0.575428f,0.678509f,-0.456627f}, -{-0.583927f,0.688531f,-0.430063f},{-0.378491f,0.826866f,-0.415977f},{-0.369129f,0.815827f,-0.445162f}, -{-0.591914f,0.697948f,-0.403122f},{-0.387165f,0.837094f,-0.386494f},{-0.395148f,0.846507f,-0.356769f}, -{-0.59938f,0.706752f,-0.375826f},{-0.606321f,0.714935f,-0.3482f},{-0.40244f,0.855106f,-0.326857f}, -{0.259611f,0.930748f,-0.25751f},{-0.0931016f,0.926577f,-0.3644f},{0.254241f,0.937079f,-0.239258f}, -{-0.409044f,0.862893f,-0.296814f},{-0.612728f,0.722491f,-0.320268f},{-0.618598f,0.729411f,-0.292055f}, -{-0.414964f,0.869874f,-0.266692f},{-0.623924f,0.735692f,-0.263585f},{-0.420207f,0.876056f,-0.236543f}, -{-0.424781f,0.881449f,-0.206418f},{-0.632928f,0.746309f,-0.205977f},{-0.428697f,0.886067f,-0.176364f}, -{-0.628702f,0.741326f,-0.234884f},{-0.636597f,0.750636f,-0.176888f},{-0.431968f,0.889923f,-0.146429f}, -{-0.639708f,0.754304f,-0.147645f},{-0.434606f,0.893034f,-0.116657f},{-0.642257f,0.757309f,-0.118272f}, -{-0.436627f,0.895417f,-0.0870897f},{-0.14403f,0.986628f,-0.0762915f},{-0.142259f,0.98454f,-0.102193f}, -{0.646513f,-0.762327f,0.0296337f},{0.814352f,-0.57966f,0.0287252f},{0.951842f,-0.305555f,0.0251636f}, -{0.998038f,0.0600412f,0.0177823f},{0.996651f,-0.0817739f,4.44435e-016f},{0.822203f,-0.569194f,3.04136e-016f}, -{0.813513f,-0.57867f,0.0577667f},{0.812092f,-0.576994f,0.0870897f},{0.949862f,-0.30322f,0.0762915f}, -{-0.644242f,0.75965f,-0.0887942f},{0.223622f,0.973184f,-0.0539127f},{0.224873f,0.971708f,-0.0722163f}, -{0.603113f,0.797218f,-0.0264206f},{0.226506f,0.969783f,-0.0906467f},{0.602655f,0.797758f,-0.0197242f}, -{-0.645661f,0.761323f,-0.059239f},{-0.438049f,0.897093f,-0.0577667f},{0.0805097f,0.996754f,-4.48371e-016f}, -{0.222222f,0.974834f,-0.0177823f},{-0.14601f,0.988963f,-0.0251636f},{0.337862f,0.941196f,-4.29587e-016f}, -{0.602143f,0.798361f,-0.00650572f},{0.569614f,0.821913f,-3.05233e-016f},{-0.17704f,0.984204f,-6.14496e-016f}, -{-0.438888f,0.898083f,-0.0287252f},{-0.427652f,0.903943f,-9.46059e-016f},{-0.646513f,0.762327f,-0.0296322f}, -{0.885978f,0.463681f,0.00650572f},{0.983879f,0.178833f,5.48296e-016f},{-0.525515f,0.619654f,-0.582978f}, -{-0.51411f,0.606206f,-0.606799f},{-0.312259f,0.74877f,-0.58467f},{-0.29896f,0.733089f,-0.610904f}, -{-0.502254f,0.592226f,-0.630087f},{-0.489956f,0.577726f,-0.652821f},{-0.28506f,0.716699f,-0.636461f}, -{-0.270582f,0.699627f,-0.661292f},{-0.477229f,0.562718f,-0.674982f},{-0.464082f,0.547216f,-0.696551f}, -{-0.25555f,0.681902f,-0.68535f},{-0.450527f,0.531233f,-0.717507f},{-0.239989f,0.663554f,-0.708591f}, -{0.0567769f,0.749849f,-0.659168f},{0.355292f,0.817926f,-0.452509f},{0.365525f,0.80586f,-0.465812f}, -{-0.223929f,0.644617f,-0.730976f},{-0.436577f,0.514784f,-0.737833f},{-0.207399f,0.625125f,-0.752465f}, -{-0.422244f,0.497883f,-0.757511f},{-0.392477f,0.462784f,-0.794854f},{-0.407539f,0.480545f,-0.776523f}, -{-0.19043f,0.605117f,-0.773026f},{-0.37707f,0.444617f,-0.812486f},{-0.173056f,0.584631f,-0.792627f}, -{-0.361331f,0.426059f,-0.829405f},{-0.345276f,0.407127f,-0.845596f},{-0.155311f,0.563707f,-0.811242f}, -{-0.137229f,0.542385f,-0.828846f},{-0.328917f,0.387838f,-0.861043f},{-0.118846f,0.520709f,-0.845422f}, -{0.443573f,0.71383f,-0.541931f},{0.683126f,0.702872f,-0.198267f},{0.455379f,0.699911f,-0.550232f}, -{-0.312269f,0.368208f,-0.875734f},{-0.100197f,0.49872f,-0.860952f},{-0.0813203f,0.476461f,-0.875426f}, -{-0.295347f,0.348255f,-0.889657f},{-0.278165f,0.327995f,-0.902798f},{-0.260739f,0.307447f,-0.915145f}, -{-0.243085f,0.28663f,-0.926689f},{-0.0622506f,0.453976f,-0.888837f},{-0.0430246f,0.431306f,-0.901179f}, -{-0.225216f,0.265561f,-0.937419f},{-0.023678f,0.408493f,-0.912454f},{-0.20715f,0.244258f,-0.947326f}, -{-0.188902f,0.222741f,-0.956401f},{-0.00424602f,0.38558f,-0.922665f},{0.0152368f,0.362607f,-0.931817f}, -{-0.170488f,0.201028f,-0.964635f},{0.034737f,0.339614f,-0.939923f},{0.28596f,0.479612f,-0.829578f}, -{0.054222f,0.316638f,-0.946995f},{0.26889f,0.499738f,-0.823383f},{-0.151924f,0.179139f,-0.972023f}, -{0.0736605f,0.293718f,-0.95305f},{-0.133227f,0.157093f,-0.978556f},{0.112279f,0.248181f,-0.962185f}, -{0.319949f,0.439533f,-0.839311f},{0.336818f,0.419643f,-0.842884f},{-0.114412f,0.134908f,-0.98423f}, -{0.731303f,0.646064f,-0.218624f},{0.756818f,0.615978f,0.218624f},{0.735599f,0.640999f,-0.219122f}, -{0.718226f,0.661484f,-0.215848f},{0.722611f,0.656314f,-0.216993f},{0.5515f,0.58657f,-0.593113f}, -{0.452261f,0.283519f,0.845622f},{0.645f,0.47632f,0.597573f},{0.469014f,0.263765f,0.842884f}, -{0.419192f,0.322513f,0.848684f},{0.506241f,0.429332f,0.747926f},{0.621631f,0.503876f,0.599737f}, -{0.587f,0.544711f,-0.598933f},{0.575259f,0.558555f,-0.597573f},{0.355998f,0.301914f,0.884372f}, -{0.206312f,0.137304f,0.968805f},{0.182011f,0.154359f,0.971105f},{0.563421f,0.572514f,-0.595638f}, -{0.726972f,0.651171f,-0.217916f},{0.370185f,0.380298f,-0.847547f},{0.353571f,0.399889f,-0.845622f}, -{0.0191661f,-0.0225994f,0.999561f},{0.0930223f,0.270888f,-0.958106f},{-0.0954975f,0.112605f,-0.98904f}, -{-0.0764992f,0.090203f,-0.992981f},{0.131403f,0.225632f,-0.96531f},{0.150369f,0.203268f,-0.967508f}, -{-0.0574334f,0.0677219f,-0.99605f},{0.169153f,0.181119f,-0.968805f},{-0.019167f,0.0226006f,-0.999561f}, -{-0.0383172f,0.0451812f,-0.998244f},{0.18253f,0.1548f,-0.970938f},{0.904079f,0.427366f,1.81967e-016f}, -{-0.145275f,0.988096f,-0.0506042f},{-0.139948f,0.981815f,-0.128274f},{-0.137083f,0.978437f,-0.154497f}, -{-0.133653f,0.974392f,-0.180824f},{-0.129646f,0.969667f,-0.207214f},{-0.125053f,0.964252f,-0.233625f}, -{-0.119867f,0.958137f,-0.260012f},{-0.114081f,0.951315f,-0.286331f},{-0.107693f,0.943782f,-0.312533f}, -{-0.1007f,0.935536f,-0.338573f},{-0.0849004f,0.916907f,-0.389967f},{-0.0761008f,0.906531f,-0.415224f}, -{-0.0667092f,0.895457f,-0.440122f},{-0.0567345f,0.883695f,-0.464612f},{-0.0461876f,0.871259f,-0.488646f}, -{-0.0350814f,0.858163f,-0.512177f},{-0.0234317f,0.844426f,-0.535159f},{-0.0112556f,0.830069f,-0.557547f}, -{0.00142745f,0.815114f,-0.579299f},{0.0145961f,0.799586f,-0.600374f},{0.0282274f,0.783513f,-0.620733f}, -{0.0422964f,0.766924f,-0.640343f},{0.0716415f,0.732322f,-0.677179f},{0.0868611f,0.714376f,-0.69435f}, -{0.102406f,0.696046f,-0.710657f},{0.118246f,0.677368f,-0.726078f},{0.13435f,0.65838f,-0.740598f}, -{0.150686f,0.639117f,-0.754203f},{0.167223f,0.619618f,-0.766883f},{0.183928f,0.599921f,-0.778631f}, -{0.20077f,0.580061f,-0.789443f},{0.217718f,0.560078f,-0.79932f},{0.234741f,0.540005f,-0.808264f}, -{0.251808f,0.519881f,-0.816282f},{0.302988f,0.459533f,-0.834882f},{0.539514f,0.600703f,-0.589983f}, -{0.38664f,0.360895f,-0.848684f},{0.348737f,0.295756f,-0.889332f},{0.645661f,-0.761323f,0.0592414f}, -{0.222742f,0.974221f,-0.0357603f},{0.228531f,0.967395f,-0.109178f},{0.230955f,0.964537f,-0.127782f}, -{0.233786f,0.961198f,-0.146431f},{0.237032f,0.957371f,-0.165095f},{0.240697f,0.95305f,-0.183742f}, -{0.244785f,0.948229f,-0.20234f},{0.249299f,0.942906f,-0.220857f},{0.271625f,0.916582f,-0.293425f}, -{0.265406f,0.923914f,-0.275577f},{0.617942f,0.779732f,-0.100821f},{0.278261f,0.908756f,-0.31102f}, -{0.28531f,0.900444f,-0.328326f},{0.292763f,0.891656f,-0.34531f},{0.300612f,0.882402f,-0.361938f}, -{0.326411f,0.851981f,-0.409371f},{0.335717f,0.841008f,-0.424264f},{0.34535f,0.829649f,-0.438652f}, -{0.662349f,0.727371f,-0.179515f},{0.825773f,0.534672f,0.179515f},{0.666368f,0.722632f,-0.183731f}, -{0.376029f,0.793474f,-0.47854f},{0.386784f,0.780792f,-0.490674f},{0.39777f,0.767839f,-0.502197f}, -{0.408963f,0.75464f,-0.513095f},{0.420343f,0.741222f,-0.523356f},{0.431888f,0.72761f,-0.53297f}, -{0.46728f,0.685877f,-0.557873f},{0.479257f,0.671755f,-0.564853f},{0.491286f,0.657571f,-0.571173f}, -{0.503347f,0.643349f,-0.576839f},{0.515419f,0.629115f,-0.581857f},{0.527481f,0.614892f,-0.586235f}, -{0.757056f,0.642042f,-0.121027f},{0.739853f,0.635983f,-0.219416f},{0.748269f,0.62606f,0.219416f}, -{0.598628f,0.530999f,-0.599736f},{0.504783f,0.428095f,-0.749619f},{0.762662f,0.646797f,1.22271e-018f}, -{0.602333f,0.798137f,-0.013083f},{0.603711f,0.796513f,-0.0331634f},{0.604451f,0.79564f,-0.0399431f}, -{0.881747f,0.46867f,0.0535724f},{0.607562f,0.791973f,-0.0604006f},{0.606374f,0.793373f,-0.0535725f}, -{0.605338f,0.794594f,-0.0467496f},{0.608902f,0.790392f,-0.0672227f},{0.610398f,0.788628f,-0.0740269f}, -{0.61205f,0.786681f,-0.0808013f},{0.613858f,0.784549f,-0.0875334f},{0.615822f,0.782232f,-0.0942108f}, -{0.865476f,0.487856f,0.113788f},{0.625224f,0.771146f,-0.120119f},{0.622646f,0.774187f,-0.113788f}, -{0.620218f,0.77705f,-0.107351f},{0.627951f,0.767931f,-0.126333f},{0.630822f,0.764545f,-0.132417f}, -{0.84786f,0.508627f,0.14977f},{0.643666f,0.749401f,-0.155219f},{0.640261f,0.753415f,-0.14977f}, -{0.636982f,0.757282f,-0.144146f},{0.64719f,0.745245f,-0.160482f},{0.650827f,0.740956f,-0.165552f}, -{0.654571f,0.736542f,-0.170419f},{0.658414f,0.73201f,-0.175076f},{0.670463f,0.717803f,-0.187718f}, -{0.674627f,0.712894f,-0.191472f},{0.67885f,0.707914f,-0.194989f},{0.796323f,0.569397f,0.2041f}, -{0.69618f,0.687479f,-0.206653f},{0.691799f,0.692645f,-0.2041f},{0.687445f,0.69778f,-0.201304f}, -{0.700581f,0.682289f,-0.208966f},{0.704994f,0.677087f,-0.211039f},{0.70941f,0.671879f,-0.212874f}, -{0.713823f,0.666676f,-0.214476f},{0.63326f,0.490164f,0.598933f},{0.76115f,0.610871f,0.217917f}, -{0.712963f,0.604648f,-0.355084f},{0.627461f,0.532136f,-0.56844f},{0.885466f,0.464285f,0.0197241f}, -{0.885788f,0.463905f,0.0130831f},{0.885009f,0.464825f,0.0264206f},{0.884411f,0.465529f,0.0331634f}, -{0.88367f,0.466402f,0.0399431f},{0.882783f,0.467448f,0.0467496f},{0.88056f,0.47007f,0.0604006f}, -{0.876072f,0.475362f,0.0808012f},{0.877724f,0.473414f,0.074027f},{0.975475f,0.0866458f,0.20234f}, -{0.879219f,0.471651f,0.0672226f},{0.874264f,0.477494f,0.0875334f},{0.8723f,0.47981f,0.0942108f}, -{0.870179f,0.482311f,0.100821f},{0.867904f,0.484993f,0.107351f},{0.840913f,-0.174755f,0.512177f}, -{0.919648f,0.152473f,0.361938f},{0.852019f,-0.187851f,0.488646f},{0.862897f,0.490897f,0.120119f}, -{0.860171f,0.494112f,0.126333f},{0.857299f,0.497498f,0.132416f},{0.854287f,0.501049f,0.138358f}, -{0.851139f,0.504761f,0.144146f},{0.763536f,-0.0835161f,0.640343f},{0.864968f,0.216949f,0.452509f}, -{0.777605f,-0.100105f,0.620733f},{0.844456f,0.512642f,0.155219f},{0.840931f,0.516798f,0.160482f}, -{0.837294f,0.521086f,0.165552f},{0.83355f,0.525501f,0.170419f},{0.829707f,0.530032f,0.175076f}, -{0.813495f,0.549149f,0.191472f},{0.817658f,0.54424f,0.187718f},{0.811296f,0.280235f,0.513095f}, -{0.821754f,0.539411f,0.183731f},{0.809271f,0.554129f,0.194989f},{0.804996f,0.55917f,0.198267f}, -{0.800677f,0.564263f,0.201304f},{0.791941f,0.574564f,0.206653f},{0.778711f,0.590164f,0.212874f}, -{0.783128f,0.584956f,0.211039f},{0.716913f,0.391526f,0.576839f},{0.78754f,0.579753f,0.208966f}, -{0.774298f,0.595367f,0.214476f},{0.769896f,0.600558f,0.215847f},{0.765511f,0.605729f,0.216993f}, -{0.656839f,0.462361f,0.595638f},{0.752523f,0.621043f,0.219122f},{0.996638f,0.061691f,0.0539127f}, -{0.997518f,0.0606535f,0.0357603f},{0.995387f,0.0631668f,0.0722163f},{0.993754f,0.0650926f,0.0906467f}, -{0.991729f,0.0674794f,0.109178f},{0.989305f,0.0703379f,0.127782f},{0.986473f,0.073677f,0.146431f}, -{0.983228f,0.0775037f,0.165095f},{0.979563f,0.0818251f,0.183742f},{0.913525f,-0.260374f,0.312533f}, -{0.906532f,-0.252128f,0.338573f},{0.966018f,0.0977959f,0.239258f},{0.97096f,0.0919687f,0.220857f}, -{0.960649f,0.104127f,0.257509f},{0.954853f,0.110961f,0.275577f},{0.948635f,0.118293f,0.293425f}, -{0.941998f,0.126119f,0.31102f},{0.93495f,0.134431f,0.328326f},{0.927496f,0.143219f,0.34531f}, -{0.911416f,0.16218f,0.378179f},{0.902811f,0.172326f,0.394f},{0.893848f,0.182894f,0.409371f}, -{0.884543f,0.193867f,0.424264f},{0.87491f,0.205226f,0.438652f},{0.854735f,0.229015f,0.465812f}, -{0.844231f,0.241401f,0.47854f},{0.833475f,0.254083f,0.490674f},{0.82249f,0.267036f,0.502197f}, -{0.671482f,0.0250282f,0.740598f},{0.655145f,0.0442907f,0.754203f},{0.788372f,0.307265f,0.53297f}, -{0.799916f,0.293653f,0.523356f},{0.776686f,0.321045f,0.541931f},{0.764881f,0.334965f,0.550232f}, -{0.752979f,0.348998f,0.557873f},{0.741003f,0.36312f,0.564853f},{0.728974f,0.377304f,0.571173f}, -{0.704841f,0.40576f,0.581857f},{0.519872f,0.203796f,0.829578f},{0.502844f,0.223875f,0.834882f}, -{0.680746f,0.434172f,0.589983f},{0.692779f,0.419983f,0.586235f},{0.66876f,0.448305f,0.593113f}, -{0.71354f,0.605138f,0.353084f},{0.757174f,0.642143f,0.119748f},{0.938627f,-0.344933f,5.47231e-016f}, -{0.951107f,-0.304688f,0.0506042f},{0.948091f,-0.301132f,0.102193f},{0.94578f,-0.298407f,0.128274f}, -{0.81007f,-0.574611f,0.116657f},{0.942915f,-0.295029f,0.154497f},{0.939484f,-0.290984f,0.180824f}, -{0.935477f,-0.286259f,0.207214f},{0.930885f,-0.280844f,0.233625f},{0.925699f,-0.274728f,0.260012f}, -{0.919913f,-0.267907f,0.286331f},{0.575427f,-0.678508f,0.45663f},{0.744593f,-0.497404f,0.445162f}, -{0.753955f,-0.508443f,0.415977f},{0.898933f,-0.243169f,0.3644f},{0.890732f,-0.233499f,0.389967f}, -{0.881933f,-0.223123f,0.415224f},{0.872541f,-0.212048f,0.440122f},{0.862566f,-0.200287f,0.464612f}, -{0.674425f,-0.414666f,0.610904f},{0.829264f,-0.161019f,0.535159f},{0.687723f,-0.430346f,0.58467f}, -{0.817087f,-0.146661f,0.557547f},{0.804404f,-0.131706f,0.579299f},{0.791236f,-0.116178f,0.600374f}, -{0.582863f,-0.306702f,0.752465f},{0.392475f,-0.462782f,0.794856f},{0.565895f,-0.286694f,0.773026f}, -{0.749055f,-0.0664413f,0.659168f},{0.73419f,-0.0489142f,0.677179f},{0.718971f,-0.0309681f,0.69435f}, -{0.703426f,-0.012638f,0.710657f},{0.687585f,0.00603948f,0.726078f},{0.456785f,-0.158038f,0.875426f}, -{0.638609f,0.0637897f,0.766883f},{0.475662f,-0.180297f,0.860952f},{0.621904f,0.0834874f,0.778631f}, -{0.605061f,0.103347f,0.789443f},{0.588114f,0.123331f,0.79932f},{0.571091f,0.143402f,0.808264f}, -{0.554024f,0.163527f,0.816282f},{0.536942f,0.18367f,0.823383f},{0.485883f,0.243875f,0.839311f}, -{0.225096f,0.115155f,0.967508f},{0.244062f,0.0927915f,0.96531f},{0.435647f,0.30311f,0.847547f}, -{0.627779f,0.532405f,0.567837f},{0.807432f,-0.5715f,0.146429f},{0.804162f,-0.567644f,0.176364f}, -{0.800246f,-0.563026f,0.206418f},{0.795672f,-0.557633f,0.236543f},{0.790429f,-0.55145f,0.266692f}, -{0.784509f,-0.54447f,0.296814f},{0.777905f,-0.536683f,0.326857f},{0.770612f,-0.528084f,0.356769f}, -{0.762629f,-0.518671f,0.386494f},{0.734548f,-0.48556f,0.473994f},{0.723827f,-0.472918f,0.502416f}, -{0.712441f,-0.459492f,0.530373f},{0.700401f,-0.445295f,0.557808f},{0.514109f,-0.606205f,0.606801f}, -{0.660525f,-0.398276f,0.636461f},{0.646047f,-0.381204f,0.661292f},{0.631014f,-0.363479f,0.68535f}, -{0.615454f,-0.345131f,0.708591f},{0.599393f,-0.326193f,0.730976f},{0.548521f,-0.266208f,0.792627f}, -{0.530776f,-0.245284f,0.811242f},{0.512693f,-0.223962f,0.828846f},{0.49431f,-0.202286f,0.845422f}, -{0.295345f,-0.348252f,0.889658f},{0.437715f,-0.135553f,0.888837f},{0.418489f,-0.112882f,0.901179f}, -{0.399143f,-0.0900703f,0.912454f},{0.379711f,-0.0671572f,0.922665f},{0.360228f,-0.0441842f,0.931817f}, -{0.340728f,-0.0211909f,0.939923f},{0.321243f,0.00178458f,0.946995f},{0.301804f,0.0247052f,0.95305f}, -{0.282442f,0.0475356f,0.958106f},{0.263186f,0.0702416f,0.962185f},{0.644242f,-0.75965f,0.0887968f}, -{0.642257f,-0.757309f,0.118274f},{0.639708f,-0.754304f,0.147647f},{0.636597f,-0.750636f,0.176891f}, -{0.632927f,-0.746308f,0.205979f},{0.628701f,-0.741325f,0.234887f},{0.623923f,-0.735691f,0.263588f}, -{0.618597f,-0.729411f,0.292057f},{0.612728f,-0.72249f,0.320271f},{0.60632f,-0.714934f,0.348202f}, -{0.59938f,-0.706751f,0.375828f},{0.591913f,-0.697947f,0.403124f},{0.583927f,-0.68853f,0.430066f}, -{0.566422f,-0.66789f,0.482793f},{0.55692f,-0.656685f,0.508532f},{0.546929f,-0.644904f,0.533824f}, -{0.536457f,-0.632556f,0.558647f},{0.525514f,-0.619653f,0.58298f},{0.502253f,-0.592225f,0.630088f}, -{0.489956f,-0.577725f,0.652822f},{0.477228f,-0.562717f,0.674983f},{0.464081f,-0.547216f,0.696551f}, -{0.450527f,-0.531233f,0.717508f},{0.436576f,-0.514784f,0.737834f},{0.422243f,-0.497882f,0.757512f}, -{0.407538f,-0.480543f,0.776525f},{0.377068f,-0.444615f,0.812488f},{0.36133f,-0.426058f,0.829407f}, -{0.345274f,-0.407126f,0.845597f},{0.328915f,-0.387836f,0.861045f},{0.312267f,-0.368206f,0.875736f}, -{0.278164f,-0.327993f,0.902799f},{0.260738f,-0.307446f,0.915146f},{0.243083f,-0.286628f,0.92669f}, -{0.225214f,-0.265559f,0.93742f},{0.207148f,-0.244256f,0.947327f},{0.1889f,-0.222739f,0.956402f}, -{0.170486f,-0.201027f,0.964636f},{0.151922f,-0.179137f,0.972023f},{0.133225f,-0.157091f,0.978557f}, -{0.114411f,-0.134906f,0.984231f},{0.0954964f,-0.112603f,0.98904f},{0.0764977f,-0.0902013f,0.992981f}, -{0.0574318f,-0.0677199f,0.99605f},{0.0383156f,-0.0451794f,0.998244f},{0.864968f,0.216949f,-0.452509f}, -{0.854735f,0.229015f,-0.465812f},{0.83355f,0.525501f,-0.170419f},{0.512693f,-0.223962f,-0.828846f}, -{0.345274f,-0.407126f,-0.845597f},{0.328915f,-0.387836f,-0.861045f},{0.530776f,-0.245284f,-0.811242f}, -{0.49431f,-0.202286f,-0.845422f},{0.312267f,-0.368206f,-0.875736f},{0.475662f,-0.180297f,-0.860952f}, -{0.260738f,-0.307446f,-0.915146f},{0.456785f,-0.158038f,-0.875426f},{0.278164f,-0.327993f,-0.902799f}, -{0.295345f,-0.348252f,-0.889658f},{0.243083f,-0.286628f,-0.92669f},{0.437715f,-0.135553f,-0.888837f}, -{0.36133f,-0.426058f,-0.829407f},{0.418489f,-0.112883f,-0.901179f},{0.225214f,-0.265559f,-0.93742f}, -{0.399143f,-0.0900702f,-0.912454f},{0.638609f,0.0637896f,-0.766883f},{0.764881f,0.334964f,-0.550232f}, -{0.776686f,0.321045f,-0.541931f},{0.379711f,-0.0671572f,-0.922665f},{0.207148f,-0.244256f,-0.947327f}, -{0.360228f,-0.0441843f,-0.931817f},{0.1889f,-0.222739f,-0.956402f},{0.170486f,-0.201027f,-0.964636f}, -{0.340727f,-0.0211908f,-0.939923f},{0.151922f,-0.179137f,-0.972023f},{0.133225f,-0.157091f,-0.978557f}, -{0.114411f,-0.134906f,-0.984231f},{0.301804f,0.0247052f,-0.95305f},{0.321242f,0.00178461f,-0.946995f}, -{0.0954963f,-0.112603f,-0.98904f},{0.282442f,0.0475355f,-0.958106f},{0.0764977f,-0.0902013f,-0.992981f}, -{0.263186f,0.0702416f,-0.962185f},{0.18253f,0.1548f,0.970938f},{-0.019167f,0.0226005f,0.999561f}, -{0.244062f,0.0927915f,-0.96531f},{0.169153f,0.181119f,0.968805f},{0.452261f,0.283519f,-0.845622f}, -{0.469014f,0.263765f,-0.842884f},{0.131403f,0.225632f,0.96531f},{0.353571f,0.399889f,0.845622f}, -{0.150369f,0.203268f,0.967508f},{0.76115f,0.610871f,-0.217916f},{0.66876f,0.448305f,-0.593113f}, -{0.656839f,0.462361f,-0.595638f},{0.598628f,0.530999f,0.599736f},{0.739853f,0.635983f,0.219416f}, -{0.712963f,0.604648f,0.355084f},{0.504783f,0.428095f,0.749619f},{0.38664f,0.360895f,0.848684f}, -{0.0574318f,-0.06772f,-0.99605f},{0.645f,0.47632f,-0.597573f},{0.757056f,0.642042f,0.121027f}, -{0.748269f,0.62606f,-0.219416f},{0.206312f,0.137304f,-0.968805f},{0.355998f,0.301914f,-0.884372f}, -{0.419192f,0.322513f,-0.848684f},{0.0383156f,-0.0451794f,-0.998244f},{0.225096f,0.115155f,-0.967508f}, -{0.621631f,0.503876f,-0.599736f},{0.71354f,0.605138f,-0.353084f},{0.627779f,0.532405f,-0.567836f}, -{0.757174f,0.642143f,-0.119748f},{0.182011f,0.154359f,-0.971105f},{0.019166f,-0.0225994f,-0.999561f}, -{0.756818f,0.615978f,-0.218624f},{0.548521f,-0.266208f,-0.792627f},{0.377068f,-0.444615f,-0.812488f}, -{0.565895f,-0.286694f,-0.773026f},{0.582863f,-0.306702f,-0.752465f},{0.392475f,-0.462782f,-0.794856f}, -{0.407538f,-0.480543f,-0.776525f},{0.422243f,-0.497882f,-0.757512f},{0.436576f,-0.514784f,-0.737834f}, -{0.599393f,-0.326194f,-0.730976f},{0.615454f,-0.345131f,-0.708591f},{0.450527f,-0.531233f,-0.717508f}, -{0.631014f,-0.363479f,-0.68535f},{0.464081f,-0.547216f,-0.696551f},{0.646047f,-0.381204f,-0.661292f}, -{0.829264f,-0.161018f,-0.535159f},{0.902811f,0.172326f,-0.394f},{0.911416f,0.16218f,-0.378179f}, -{0.660525f,-0.398276f,-0.636461f},{0.477228f,-0.562717f,-0.674983f},{0.674424f,-0.414665f,-0.610904f}, -{0.489956f,-0.577725f,-0.652822f},{0.514109f,-0.606205f,-0.606801f},{0.502253f,-0.592225f,-0.630089f}, -{0.687723f,-0.430346f,-0.58467f},{0.525514f,-0.619653f,-0.58298f},{0.700401f,-0.445295f,-0.557808f}, -{0.536457f,-0.632556f,-0.558647f},{0.546929f,-0.644904f,-0.533824f},{0.712441f,-0.459492f,-0.530373f}, -{0.723827f,-0.472918f,-0.502416f},{0.55692f,-0.656685f,-0.508532f},{0.734548f,-0.48556f,-0.473994f}, -{0.960649f,0.104127f,-0.25751f},{0.872299f,0.47981f,-0.0942108f},{0.966018f,0.097796f,-0.239258f}, -{0.566422f,-0.66789f,-0.482793f},{0.744593f,-0.497404f,-0.445162f},{0.753955f,-0.508443f,-0.415977f}, -{0.575427f,-0.678508f,-0.45663f},{0.583927f,-0.68853f,-0.430066f},{0.591913f,-0.697947f,-0.403124f}, -{0.59938f,-0.706751f,-0.375828f},{0.762629f,-0.518671f,-0.386494f},{0.770612f,-0.528084f,-0.356769f}, -{0.60632f,-0.714934f,-0.348202f},{0.777905f,-0.536683f,-0.326857f},{0.612728f,-0.72249f,-0.32027f}, -{0.618597f,-0.729411f,-0.292057f},{0.784509f,-0.54447f,-0.296814f},{0.790429f,-0.551451f,-0.266692f}, -{0.623923f,-0.735691f,-0.263588f},{0.795672f,-0.557633f,-0.236543f},{0.939484f,-0.290984f,-0.180824f}, -{0.800246f,-0.563026f,-0.206418f},{0.935477f,-0.286259f,-0.207214f},{0.628701f,-0.741325f,-0.234887f}, -{0.804162f,-0.567644f,-0.176364f},{0.632927f,-0.746308f,-0.205979f},{0.998038f,0.0600411f,-0.0177823f}, -{0.885788f,0.463905f,-0.0130831f},{0.885978f,0.463681f,-0.00650573f},{0.636597f,-0.750636f,-0.176891f}, -{0.223622f,0.973184f,0.0539127f},{0.602655f,0.797758f,0.0197241f},{0.224873f,0.971708f,0.0722163f}, -{0.94578f,-0.298407f,-0.128274f},{0.948091f,-0.301132f,-0.102193f},{0.81007f,-0.574611f,-0.116657f}, -{-0.14403f,0.986628f,0.0762915f},{-0.142259f,0.98454f,0.102193f},{-0.14601f,0.988963f,0.0251637f}, -{0.0805097f,0.996754f,1.11285e-016f},{0.222222f,0.974834f,0.0177823f},{0.885008f,0.464825f,-0.0264206f}, -{0.996638f,0.0616911f,-0.0539127f},{0.995387f,0.0631666f,-0.0722163f},{-0.438888f,0.898083f,0.0287253f}, -{-0.17704f,0.984204f,4.07949e-016f},{0.884411f,0.465529f,-0.0331634f},{0.993754f,0.0650924f,-0.0906466f}, -{0.88367f,0.466403f,-0.0399431f},{-0.427653f,0.903943f,3.52919e-035f},{0.639708f,-0.754304f,-0.147647f}, -{0.807432f,-0.5715f,-0.146429f},{0.813513f,-0.57867f,-0.0577667f},{0.812092f,-0.576994f,-0.0870897f}, -{0.949862f,-0.30322f,-0.0762915f},{0.642257f,-0.757309f,-0.118274f},{0.644242f,-0.75965f,-0.0887967f}, -{0.645661f,-0.761323f,-0.0592414f},{0.646513f,-0.762327f,-0.0296338f},{0.814352f,-0.57966f,-0.0287253f}, -{0.506241f,0.429332f,-0.747926f},{0.435647f,0.30311f,-0.847547f},{0.485883f,0.243875f,-0.839311f}, -{0.502844f,0.223875f,-0.834882f},{0.519872f,0.203796f,-0.829578f},{0.536941f,0.18367f,-0.823383f}, -{0.554024f,0.163527f,-0.816282f},{0.571091f,0.143403f,-0.808264f},{0.588114f,0.12333f,-0.79932f}, -{0.605061f,0.103347f,-0.789443f},{0.621904f,0.0834874f,-0.778631f},{0.655145f,0.0442908f,-0.754203f}, -{0.671482f,0.0250283f,-0.740598f},{0.687585f,0.00603957f,-0.726078f},{0.703426f,-0.0126381f,-0.710657f}, -{0.718971f,-0.0309681f,-0.69435f},{0.73419f,-0.0489141f,-0.677179f},{0.749055f,-0.0664415f,-0.659168f}, -{0.763536f,-0.083516f,-0.640343f},{0.777605f,-0.100105f,-0.620734f},{0.791236f,-0.116178f,-0.600374f}, -{0.804404f,-0.131706f,-0.579299f},{0.817087f,-0.146661f,-0.557547f},{0.840913f,-0.174755f,-0.512177f}, -{0.852019f,-0.187851f,-0.488646f},{0.862566f,-0.200287f,-0.464612f},{0.872541f,-0.212049f,-0.440122f}, -{0.881933f,-0.223123f,-0.415224f},{0.890732f,-0.233499f,-0.389967f},{0.898933f,-0.243169f,-0.3644f}, -{0.906532f,-0.252128f,-0.338573f},{0.913525f,-0.260374f,-0.312533f},{0.919913f,-0.267907f,-0.286331f}, -{0.925699f,-0.274729f,-0.260012f},{0.930885f,-0.280844f,-0.233625f},{0.942915f,-0.295029f,-0.154497f}, -{0.991729f,0.0674795f,-0.109178f},{0.951842f,-0.305555f,-0.0251637f},{0.951107f,-0.304688f,-0.0506043f}, -{0.938627f,-0.344933f,-2.28355e-016f},{0.822203f,-0.569194f,-3.01839e-016f},{0.627461f,0.532136f,0.56844f}, -{0.633259f,0.490164f,-0.598933f},{0.680746f,0.434172f,-0.589983f},{0.692779f,0.419983f,-0.586235f}, -{0.704841f,0.40576f,-0.581857f},{0.716913f,0.391526f,-0.576839f},{0.728974f,0.377304f,-0.571173f}, -{0.741003f,0.36312f,-0.564853f},{0.752979f,0.348998f,-0.557873f},{0.799916f,0.293653f,-0.523356f}, -{0.788372f,0.307265f,-0.53297f},{0.809271f,0.554129f,-0.194989f},{0.811296f,0.280235f,-0.513095f}, -{0.82249f,0.267036f,-0.502197f},{0.833475f,0.254083f,-0.490674f},{0.844231f,0.241401f,-0.47854f}, -{0.87491f,0.205226f,-0.438652f},{0.884543f,0.193867f,-0.424264f},{0.893848f,0.182894f,-0.409371f}, -{0.86017f,0.494112f,-0.126333f},{0.627951f,0.767931f,0.126333f},{0.862897f,0.490897f,-0.120119f}, -{0.919648f,0.152473f,-0.361938f},{0.927496f,0.143219f,-0.34531f},{0.93495f,0.134431f,-0.328326f}, -{0.941998f,0.126119f,-0.31102f},{0.948635f,0.118293f,-0.293425f},{0.954853f,0.110961f,-0.275577f}, -{0.97096f,0.0919687f,-0.220857f},{0.975475f,0.0866457f,-0.20234f},{0.979563f,0.0818252f,-0.183742f}, -{0.983228f,0.0775037f,-0.165095f},{0.986473f,0.0736769f,-0.146431f},{0.989305f,0.0703379f,-0.127782f}, -{0.997518f,0.0606535f,-0.0357604f},{0.885466f,0.464285f,-0.0197241f},{0.996651f,-0.0817741f,-2.89047e-016f}, -{-0.0383171f,0.0451812f,0.998244f},{0.752523f,0.621043f,-0.219122f},{0.765511f,0.605729f,-0.216993f}, -{0.769896f,0.600558f,-0.215848f},{0.70941f,0.671879f,0.212874f},{0.783128f,0.584956f,-0.211039f}, -{0.778711f,0.590164f,-0.212875f},{0.774298f,0.595367f,-0.214476f},{0.78754f,0.579753f,-0.208966f}, -{0.791941f,0.574564f,-0.206653f},{0.796323f,0.569397f,-0.2041f},{0.800677f,0.564263f,-0.201305f}, -{0.804996f,0.55917f,-0.198267f},{0.670463f,0.717803f,0.187718f},{0.821754f,0.539411f,-0.183731f}, -{0.817658f,0.54424f,-0.187718f},{0.813495f,0.549149f,-0.191472f},{0.825773f,0.534672f,-0.179515f}, -{0.829707f,0.530032f,-0.175076f},{0.64719f,0.745245f,0.160482f},{0.844456f,0.512642f,-0.155219f}, -{0.840932f,0.516797f,-0.160482f},{0.837294f,0.521086f,-0.165552f},{0.84786f,0.508628f,-0.14977f}, -{0.851139f,0.504761f,-0.144146f},{0.854287f,0.501049f,-0.138358f},{0.857299f,0.497498f,-0.132417f}, -{0.865476f,0.487856f,-0.113788f},{0.867904f,0.484993f,-0.107351f},{0.870179f,0.48231f,-0.100821f}, -{0.61205f,0.786681f,0.0808013f},{0.877724f,0.473415f,-0.0740269f},{0.876072f,0.475362f,-0.0808013f}, -{0.874264f,0.477494f,-0.0875334f},{0.879219f,0.471651f,-0.0672227f},{0.88056f,0.47007f,-0.0604006f}, -{0.881747f,0.46867f,-0.0535724f},{0.882783f,0.467448f,-0.0467496f},{0.603113f,0.797218f,0.0264206f}, -{0.983879f,0.178833f,-2.6491e-016f},{0.731303f,0.646064f,0.218624f},{0.735599f,0.640999f,0.219122f}, -{0.726972f,0.651171f,0.217917f},{0.722611f,0.656314f,0.216992f},{0.718226f,0.661484f,0.215848f}, -{0.713823f,0.666676f,0.214476f},{0.704994f,0.677087f,0.211039f},{0.691799f,0.692645f,0.2041f}, -{0.69618f,0.687479f,0.206653f},{0.479257f,0.671755f,0.564852f},{0.700581f,0.682289f,0.208966f}, -{0.687444f,0.69778f,0.201305f},{0.683125f,0.702872f,0.198267f},{0.67885f,0.707913f,0.194989f}, -{0.674627f,0.712894f,0.191472f},{0.0716416f,0.732322f,0.677179f},{0.376029f,0.793474f,0.47854f}, -{0.0868611f,0.714376f,0.69435f},{0.666368f,0.722632f,0.183731f},{0.662349f,0.727371f,0.179515f}, -{0.658414f,0.73201f,0.175076f},{0.654571f,0.736542f,0.170419f},{0.650828f,0.740956f,0.165552f}, -{-0.0112556f,0.830069f,0.557547f},{0.317449f,0.862549f,0.394f},{0.00142744f,0.815114f,0.579299f}, -{0.643666f,0.749401f,0.155219f},{0.640261f,0.753415f,0.14977f},{0.636982f,0.757282f,0.144146f}, -{0.633834f,0.760993f,0.138358f},{0.630822f,0.764545f,0.132417f},{0.620218f,0.77705f,0.107351f}, -{0.622645f,0.774187f,0.113788f},{0.278262f,0.908756f,0.311019f},{0.625224f,0.771146f,0.120119f}, -{0.617942f,0.779732f,0.100821f},{0.615822f,0.782232f,0.0942108f},{0.613858f,0.784549f,0.0875334f}, -{0.610398f,0.788628f,0.0740269f},{0.606374f,0.793373f,0.0535724f},{0.607562f,0.791973f,0.0604006f}, -{0.237032f,0.957371f,0.165095f},{0.608902f,0.790392f,0.0672227f},{0.605338f,0.794594f,0.0467497f}, -{0.604451f,0.79564f,0.0399431f},{0.603711f,0.796513f,0.0331634f},{0.602333f,0.798137f,0.0130831f}, -{0.602143f,0.798361f,0.00650573f},{0.762662f,0.646797f,-2.05938e-033f},{0.904079f,0.427366f,-1.54031e-016f}, -{0.575259f,0.558555f,0.597573f},{0.587f,0.544711f,0.598933f},{0.563421f,0.572514f,0.595638f}, -{0.5515f,0.58657f,0.593113f},{0.539514f,0.600703f,0.589983f},{0.527481f,0.614892f,0.586235f}, -{0.515419f,0.629115f,0.581857f},{0.503347f,0.643349f,0.576839f},{0.491286f,0.657571f,0.571173f}, -{0.20077f,0.580061f,0.789443f},{0.183928f,0.599921f,0.778631f},{0.455379f,0.699911f,0.550232f}, -{0.46728f,0.685877f,0.557873f},{0.443574f,0.71383f,0.541931f},{0.431888f,0.72761f,0.53297f}, -{0.420343f,0.741222f,0.523356f},{0.408963f,0.75464f,0.513095f},{0.39777f,0.767839f,0.502197f}, -{0.386784f,0.780792f,0.490674f},{0.365525f,0.80586f,0.465812f},{0.355292f,0.817926f,0.452509f}, -{0.34535f,0.829649f,0.438652f},{0.335717f,0.841008f,0.424264f},{0.326411f,0.851981f,0.409371f}, -{0.308844f,0.872695f,0.378179f},{0.300612f,0.882402f,0.361938f},{0.292763f,0.891656f,0.34531f}, -{0.28531f,0.900444f,0.328326f},{-0.0761008f,0.90653f,0.415224f},{-0.0849005f,0.916907f,0.389967f}, -{0.265406f,0.923914f,0.275577f},{0.271625f,0.916582f,0.293425f},{0.259611f,0.930748f,0.257509f}, -{0.254241f,0.937079f,0.239258f},{0.249299f,0.942906f,0.220857f},{0.244785f,0.948229f,0.20234f}, -{0.240697f,0.95305f,0.183742f},{0.233786f,0.961198f,0.146431f},{-0.133653f,0.974392f,0.180824f}, -{-0.137083f,0.978437f,0.154497f},{0.228531f,0.967395f,0.109178f},{0.230955f,0.964537f,0.127782f}, -{0.226506f,0.969783f,0.0906467f},{0.222742f,0.974221f,0.0357604f},{0.337862f,0.941196f,1.5621e-016f}, -{0.569614f,0.821913f,6.56678e-035f},{0.348737f,0.295756f,0.889332f},{0.370185f,0.380298f,0.847547f}, -{0.336818f,0.419643f,0.842884f},{0.319949f,0.439533f,0.839311f},{0.112279f,0.248181f,0.962185f}, -{0.302988f,0.459533f,0.834882f},{0.28596f,0.479612f,0.829578f},{0.26889f,0.499738f,0.823383f}, -{0.251808f,0.519881f,0.816282f},{0.234741f,0.540006f,0.808264f},{0.217718f,0.560077f,0.79932f}, -{-0.295347f,0.348255f,0.889657f},{-0.100197f,0.49872f,0.860952f},{-0.0813203f,0.476461f,0.875426f}, -{0.167223f,0.619618f,0.766883f},{0.150686f,0.639117f,0.754203f},{0.13435f,0.65838f,0.740598f}, -{0.118247f,0.677368f,0.726078f},{0.102406f,0.696046f,0.710657f},{-0.207399f,0.625125f,0.752465f}, -{0.0567769f,0.749849f,0.659168f},{-0.19043f,0.605117f,0.773026f},{0.0422963f,0.766924f,0.640343f}, -{0.0282273f,0.783513f,0.620734f},{0.0145963f,0.799586f,0.600374f},{-0.29896f,0.733089f,0.610904f}, -{-0.51411f,0.606207f,0.606799f},{-0.312259f,0.74877f,0.58467f},{-0.0234316f,0.844427f,0.535159f}, -{-0.0350815f,0.858163f,0.512177f},{-0.0461876f,0.871259f,0.488646f},{-0.0567343f,0.883695f,0.464612f}, -{-0.0667093f,0.895457f,0.440122f},{-0.378491f,0.826866f,0.415977f},{-0.0931014f,0.926577f,0.3644f}, -{-0.369129f,0.815827f,0.445162f},{-0.1007f,0.935536f,0.338573f},{-0.107693f,0.943782f,0.312533f}, -{-0.114081f,0.951315f,0.286331f},{-0.119867f,0.958137f,0.260012f},{-0.125053f,0.964252f,0.233625f}, -{-0.129645f,0.969667f,0.207214f},{-0.139948f,0.981815f,0.128274f},{-0.438049f,0.897093f,0.0577667f}, -{-0.436627f,0.895417f,0.0870897f},{-0.145275f,0.988096f,0.0506043f},{0.0930223f,0.270888f,0.958106f}, -{0.0736606f,0.293718f,0.95305f},{0.054222f,0.316638f,0.946995f},{0.034737f,0.339614f,0.939923f}, -{0.015237f,0.362607f,0.931817f},{-0.00424604f,0.38558f,0.922665f},{-0.023678f,0.408493f,0.912454f}, -{-0.0430246f,0.431306f,0.901179f},{-0.0622507f,0.453976f,0.888837f},{-0.118846f,0.520709f,0.845422f}, -{-0.137229f,0.542385f,0.828846f},{-0.155311f,0.563707f,0.811242f},{-0.173056f,0.584631f,0.792627f}, -{-0.392477f,0.462784f,0.794854f},{-0.223929f,0.644617f,0.730976f},{-0.239989f,0.663554f,0.708591f}, -{-0.25555f,0.681902f,0.68535f},{-0.270582f,0.699627f,0.661292f},{-0.28506f,0.716699f,0.636461f}, -{-0.324936f,0.763719f,0.557808f},{-0.336976f,0.777915f,0.530373f},{-0.348363f,0.791341f,0.502416f}, -{-0.359084f,0.803983f,0.473994f},{-0.575428f,0.678509f,0.456627f},{-0.387165f,0.837094f,0.386494f}, -{-0.395148f,0.846507f,0.356769f},{-0.40244f,0.855106f,0.326857f},{-0.409044f,0.862893f,0.296814f}, -{-0.414964f,0.869874f,0.266692f},{-0.420207f,0.876056f,0.236543f},{-0.424781f,0.881449f,0.206418f}, -{-0.428697f,0.886067f,0.176364f},{-0.431967f,0.889923f,0.146429f},{-0.434606f,0.893034f,0.116657f}, -{-0.0574335f,0.0677219f,0.99605f},{-0.0764992f,0.090203f,0.992981f},{-0.0954975f,0.112605f,0.98904f}, -{-0.114412f,0.134908f,0.98423f},{-0.133227f,0.157093f,0.978556f},{-0.151924f,0.179139f,0.972023f}, -{-0.170488f,0.201028f,0.964635f},{-0.188902f,0.222741f,0.956401f},{-0.20715f,0.244258f,0.947326f}, -{-0.225216f,0.265561f,0.937419f},{-0.243085f,0.28663f,0.926689f},{-0.260739f,0.307448f,0.915145f}, -{-0.278165f,0.327995f,0.902798f},{-0.312269f,0.368208f,0.875734f},{-0.328917f,0.387838f,0.861043f}, -{-0.345276f,0.407127f,0.845596f},{-0.361331f,0.426059f,0.829405f},{-0.37707f,0.444617f,0.812486f}, -{-0.407539f,0.480545f,0.776523f},{-0.422244f,0.497883f,0.757511f},{-0.436577f,0.514784f,0.737833f}, -{-0.450527f,0.531233f,0.717507f},{-0.464082f,0.547216f,0.696551f},{-0.477229f,0.562718f,0.674982f}, -{-0.489956f,0.577726f,0.652821f},{-0.502254f,0.592226f,0.630087f},{-0.525515f,0.619654f,0.582978f}, -{-0.536458f,0.632557f,0.558645f},{-0.546929f,0.644905f,0.533822f},{-0.556921f,0.656686f,0.508529f}, -{-0.566423f,0.667891f,0.48279f},{-0.583927f,0.688531f,0.430063f},{-0.591914f,0.697948f,0.403122f}, -{-0.59938f,0.706752f,0.375826f},{-0.606321f,0.714935f,0.3482f},{-0.612728f,0.722491f,0.320268f}, -{-0.618598f,0.729411f,0.292055f},{-0.623923f,0.735692f,0.263585f},{-0.628702f,0.741326f,0.234884f}, -{-0.632928f,0.746309f,0.205977f},{-0.636597f,0.750636f,0.176888f},{-0.639708f,0.754304f,0.147645f}, -{-0.642257f,0.757309f,0.118272f},{-0.644242f,0.75965f,0.0887941f},{-0.645661f,0.761323f,0.0592391f}, -{-0.646513f,0.762327f,0.0296323f},{-5.74474e-016f,6.77383e-016f,1.0f},{7.92072e-017f,-9.33961e-017f,1.0f}, -{0.156255f,0.134204f,0.978557f},{-0.0265911f,0.301644f,0.95305f},{-0.00379251f,0.321225f,0.946995f}, -{0.110265f,0.419187f,0.901179f},{0.285103f,0.24487f,0.92669f},{0.264146f,0.22687f,0.93742f}, -{-0.286341f,0.45048f,0.845622f},{-0.480343f,0.642011f,0.597573f},{-0.466457f,0.653936f,0.595638f}, -{-0.0492999f,0.28214f,0.958106f},{0.134188f,0.115252f,0.984231f},{-0.610502f,0.76171f,0.216993f}, -{-0.615617f,0.757316f,0.217916f},{-0.0943152f,0.243477f,0.96531f},{-0.266692f,0.467356f,0.842884f}, -{-0.0718852f,0.262742f,0.962185f},{-0.640595f,0.735863f,-0.219416f},{-0.630724f,0.744341f,0.219416f}, -{-0.646863f,0.753146f,0.119748f},{-0.620697f,0.752953f,0.218624f},{-0.431242f,0.502097f,-0.749619f}, -{-0.363305f,0.384377f,-0.848684f},{-0.534731f,0.595298f,-0.599736f},{-0.609092f,0.70917f,-0.355084f}, -{-0.0449409f,-0.0385987f,-0.998244f},{-0.204204f,0.149095f,-0.967508f},{-0.182173f,0.168018f,-0.968805f}, -{-0.0224804f,-0.0193078f,-0.999561f},{-0.155937f,0.181559f,-0.970938f},{-4.72151e-016f,-4.05521e-016f,-1.0f}, -{0.199957f,0.171739f,0.964636f},{0.0190607f,0.340853f,0.939923f},{0.0419318f,0.360497f,0.931817f}, -{0.178184f,0.153039f,0.972023f},{0.0647826f,0.380123f,0.922665f},{0.221554f,0.190289f,0.956402f}, -{-0.127004f,0.587331f,0.79932f},{0.0875737f,0.399698f,0.912454f},{0.242957f,0.208671f,0.947327f}, -{0.132814f,0.438554f,0.888837f},{0.30581f,0.262654f,0.915146f},{0.17732f,0.47678f,0.860952f}, -{0.199192f,0.495565f,0.845422f},{0.366247f,0.314563f,0.875736f},{0.15518f,0.457764f,0.875426f}, -{0.423791f,0.363986f,0.829407f},{0.40496f,0.347812f,0.845597f},{0.241961f,0.532298f,0.811242f}, -{0.385773f,0.331333f,0.861045f},{0.46032f,0.39536f,0.794856f},{0.283151f,0.567676f,0.773026f}, -{0.303053f,0.584769f,0.752465f},{0.262774f,0.550174f,0.792627f},{0.512045f,0.439786f,0.737834f}, -{0.341277f,0.617599f,0.708591f},{0.528407f,0.453838f,0.717508f},{0.322441f,0.601421f,0.730976f}, -{0.574651f,0.493557f,0.652822f},{0.559724f,0.480736f,0.674983f},{0.39414f,0.663002f,0.636461f}, -{0.544304f,0.467493f,0.696551f},{0.377159f,0.648417f,0.661292f},{0.616356f,0.529376f,0.58298f}, -{0.426039f,0.6904f,0.58467f},{0.440909f,0.703171f,0.557808f},{0.410442f,0.677003f,0.610904f}, -{0.468385f,0.726769f,0.502416f},{0.653191f,0.561014f,0.508532f},{0.641473f,0.550949f,0.533824f}, -{0.629191f,0.5404f,0.558647f},{0.684866f,0.588219f,0.430066f},{0.674898f,0.579657f,0.45663f}, -{0.503721f,0.757119f,0.415977f},{0.480959f,0.737569f,0.473994f},{0.513894f,0.765856f,0.386494f}, -{0.702991f,0.603786f,0.375828f},{0.694233f,0.596264f,0.403124f},{0.539556f,0.787897f,0.296814f}, -{0.718646f,0.617231f,0.32027f},{0.53181f,0.781244f,0.326857f},{0.711131f,0.610777f,0.348202f}, -{0.523257f,0.773898f,0.356769f},{0.731777f,0.628509f,0.263588f},{0.552648f,0.799142f,0.236543f}, -{0.737381f,0.633323f,0.234887f},{0.546499f,0.79386f,0.266692f},{0.72553f,0.623144f,0.292057f}, -{0.742337f,0.63758f,0.205979f},{0.562606f,0.807694f,0.176364f},{0.746642f,0.641277f,0.176891f}, -{0.558013f,0.803749f,0.206418f},{0.574558f,0.81796f,0.0287253f},{0.758605f,0.651551f,3.14853e-016f}, -{0.758272f,0.651265f,0.0296338f},{0.75029f,0.64441f,0.147647f},{0.566442f,0.810988f,0.146429f}, -{0.571907f,0.815682f,0.0870897f},{0.297277f,0.951738f,0.0762915f},{0.298738f,0.952993f,0.0506043f}, -{0.757272f,0.650407f,0.0592414f},{0.75328f,0.646978f,0.118274f},{0.755608f,0.648977f,0.0887967f}, -{0.573574f,0.817114f,0.0577667f},{0.569536f,0.813646f,0.116657f},{-0.0668874f,0.997119f,0.0357603f}, -{-0.46921f,0.883063f,0.00650573f},{-0.0662782f,0.997643f,0.0177823f},{0.28913f,0.944741f,0.154497f}, -{0.285106f,0.941285f,0.180824f},{-0.0679193f,0.996233f,0.0539127f},{0.2952f,0.949955f,0.102193f}, -{-0.069387f,0.994972f,0.0722163f},{-0.073677f,0.991288f,0.109178f},{-0.801509f,0.597657f,-0.0197241f}, -{-0.800972f,0.598118f,-0.0264206f},{-0.974563f,0.217534f,-0.0539127f},{-0.470347f,0.882086f,0.0264206f}, -{-0.46981f,0.882547f,0.0197241f},{-0.985709f,-0.150194f,-0.0762915f},{-0.987169f,-0.151448f,-0.0506043f}, -{-0.997238f,0.0742779f,-1.10368e-016f},{-0.976204f,0.216125f,-0.0177823f},{-0.988031f,-0.152188f,-0.0251637f}, -{-0.895322f,-0.444493f,-0.0287253f},{-0.901253f,-0.433294f,-3.00521e-016f},{-0.983078f,-0.183188f,-5.39175e-016f}, -{-0.758605f,-0.651551f,-6.22394e-016f},{0.27502f,0.932622f,0.233625f},{0.45503f,0.715299f,0.530373f}, -{0.664336f,0.570586f,0.482793f},{0.49274f,0.747688f,0.445162f},{0.206591f,0.87385f,0.440122f}, -{0.60298f,0.517888f,0.606801f},{0.589074f,0.505945f,0.630089f},{0.359528f,0.633274f,0.68535f}, -{0.495233f,0.425347f,0.757512f},{0.126676f,0.805212f,0.579299f},{-0.188478f,0.892688f,0.409371f}, -{-0.177966f,0.901716f,0.394f},{0.477987f,0.410534f,0.776525f},{0.44225f,0.37984f,0.812488f}, -{0.346399f,0.297516f,0.889658f},{0.326248f,0.280208f,0.902799f},{0.220753f,0.514083f,0.828846f}, -{-0.246673f,0.842705f,0.47854f},{0.0264735f,0.71915f,0.69435f},{-0.259287f,0.831871f,0.490674f}, -{0.112004f,0.0961983f,0.98904f},{0.0897214f,0.07706f,0.992981f},{0.0673597f,0.0578539f,0.99605f}, -{-0.507751f,0.61847f,0.599736f},{-0.609586f,0.709744f,0.353084f},{-0.11656f,0.224371f,0.967508f}, -{0.044939f,0.0385972f,0.998244f},{-0.138591f,0.205449f,0.968805f},{0.0224791f,0.0193069f,0.999561f}, -{-0.646762f,0.753028f,-0.121027f},{-0.155494f,0.181042f,0.971105f},{2.38849e-016f,2.05143e-016f,1.0f}, -{-0.304133f,0.354104f,0.884372f},{-0.432488f,0.503548f,0.747926f},{-0.325126f,0.417168f,0.848684f}, -{-0.536319f,0.624439f,0.567836f},{-0.305827f,0.433744f,0.847547f},{-0.246907f,0.484349f,0.839311f}, -{-0.227014f,0.501435f,0.834882f},{-0.207042f,0.518588f,0.829578f},{-0.187022f,0.535783f,0.823383f}, -{-0.166987f,0.552991f,0.816282f},{-0.146969f,0.570184f,0.808264f},{-0.353698f,0.750783f,0.557873f}, -{-0.339739f,0.762773f,0.550232f},{-0.107127f,0.604404f,0.789443f},{-0.087373f,0.62137f,0.778631f}, -{-0.06778f,0.638198f,0.766883f},{-0.0483849f,0.654856f,0.754203f},{-0.0292249f,0.671312f,0.740598f}, -{-0.0103371f,0.687534f,0.726078f},{0.00824112f,0.703491f,0.710657f},{0.0443241f,0.734482f,0.677179f}, -{0.0617582f,0.749456f,0.659168f},{0.078742f,0.764043f,0.640343f},{0.0952429f,0.778215f,0.620734f}, -{0.111231f,0.791946f,0.600374f},{0.141551f,0.817988f,0.557547f},{0.155832f,0.830254f,0.535159f}, -{0.169496f,0.841989f,0.512177f},{0.182521f,0.853177f,0.488646f},{0.194892f,0.863801f,0.464612f}, -{-0.485253f,0.869283f,0.0942108f},{-0.116927f,0.954141f,0.275577f},{-0.48774f,0.867148f,0.100821f}, -{0.217606f,0.88331f,0.415224f},{0.227926f,0.892174f,0.389967f},{0.237545f,0.900436f,0.3644f}, -{0.246457f,0.90809f,0.338573f},{0.254659f,0.915135f,0.312533f},{0.262152f,0.92157f,0.286331f}, -{0.268937f,0.927398f,0.260012f},{0.280406f,0.937248f,0.207214f},{-0.0765203f,0.988846f,0.127782f}, -{0.292489f,0.947626f,0.128274f},{0.2996f,0.953733f,0.0251637f},{0.339059f,0.940765f,7.30221e-017f}, -{0.564043f,0.825745f,2.30577e-016f},{-0.536047f,0.624123f,-0.56844f},{-0.494113f,0.630183f,0.598933f}, -{-0.452476f,0.665945f,0.593113f},{-0.438418f,0.678019f,0.589983f},{-0.424305f,0.69014f,0.586235f}, -{-0.410157f,0.702291f,0.581857f},{-0.395999f,0.714451f,0.576839f},{-0.381854f,0.726601f,0.571173f}, -{-0.367745f,0.738719f,0.564853f},{-0.325893f,0.774664f,0.541931f},{-0.564191f,0.801485f,0.198267f}, -{-0.559177f,0.805792f,0.194989f},{-0.312187f,0.786436f,0.53297f},{-0.298647f,0.798065f,0.523356f}, -{-0.2853f,0.809529f,0.513095f},{-0.272171f,0.820805f,0.502197f},{-0.52631f,0.834021f,0.165552f}, -{-0.74501f,0.646183f,-0.165552f},{-0.749276f,0.642519f,-0.160482f},{-0.234353f,0.853287f,0.465812f}, -{-0.222351f,0.863595f,0.452509f},{-0.21069f,0.87361f,0.438652f},{-0.199392f,0.883313f,0.424264f}, -{-0.502847f,0.854173f,0.132416f},{-0.768473f,0.626031f,-0.132417f},{-0.771841f,0.623139f,-0.126333f}, -{-0.167874f,0.910384f,0.378179f},{-0.158218f,0.918677f,0.361938f},{-0.149013f,0.926583f,0.34531f}, -{-0.140272f,0.934091f,0.328326f},{-0.132004f,0.941192f,0.31102f},{-0.124221f,0.947877f,0.293425f}, -{-0.11013f,0.959979f,0.25751f},{-0.103832f,0.965388f,0.239258f},{-0.098036f,0.970367f,0.220857f}, -{-0.0927412f,0.974914f,0.20234f},{-0.0879463f,0.979032f,0.183742f},{-0.0836479f,0.982724f,0.165095f}, -{-0.0798413f,0.985994f,0.146431f},{-0.0713026f,0.993327f,0.0906466f},{-0.801887f,0.597333f,-0.0130831f}, -{0.0755429f,0.997143f,3.49386e-017f},{-0.382604f,0.367801f,-0.847547f},{-0.625735f,0.748626f,0.219122f}, -{-0.605359f,0.766127f,0.215847f},{-0.665961f,0.714077f,-0.215848f},{-0.671124f,0.709642f,-0.214476f}, -{-0.600195f,0.770562f,0.214476f},{-0.595019f,0.775007f,0.212875f},{-0.58984f,0.779456f,0.211039f}, -{-0.584664f,0.783901f,0.208966f},{-0.579503f,0.788334f,0.206653f},{-0.574364f,0.792748f,0.2041f}, -{-0.569256f,0.797135f,0.201304f},{-0.554223f,0.810046f,0.191472f},{-0.717096f,0.670158f,-0.191472f}, -{-0.721979f,0.665964f,-0.187718f},{-0.54934f,0.814241f,0.187718f},{-0.544537f,0.818366f,0.183731f}, -{-0.539823f,0.822414f,0.179515f},{-0.535208f,0.826378f,0.175076f},{-0.530701f,0.830249f,0.170419f}, -{-0.522044f,0.837685f,0.160482f},{-0.51791f,0.841235f,0.155219f},{-0.513917f,0.844665f,0.14977f}, -{-0.510071f,0.847968f,0.144146f},{-0.506379f,0.851139f,0.138358f},{-0.499479f,0.857065f,0.126333f}, -{-0.496281f,0.859812f,0.120119f},{-0.493256f,0.86241f,0.113788f},{-0.490408f,0.864856f,0.107351f}, -{-0.482949f,0.871262f,0.0875334f},{-0.78837f,0.608942f,-0.0875334f},{-0.790491f,0.60712f,-0.0808013f}, -{-0.480829f,0.873084f,0.0808013f},{-0.478892f,0.874747f,0.0740269f},{-0.477137f,0.876254f,0.0672227f}, -{-0.475565f,0.877605f,0.0604006f},{-0.474172f,0.878801f,0.0535724f},{-0.472957f,0.879844f,0.0467496f}, -{-0.471917f,0.880738f,0.0399431f},{-0.471048f,0.881484f,0.0331634f},{-0.469433f,0.882871f,0.0130831f}, -{-0.18498f,0.982742f,5.93908e-017f},{-0.650623f,0.727251f,-0.218624f},{-0.655703f,0.722888f,-0.217917f}, -{-0.645585f,0.731578f,-0.219122f},{-0.660818f,0.718494f,-0.216992f},{-0.6763f,0.705197f,-0.212875f}, -{-0.68148f,0.700748f,-0.211039f},{-0.686655f,0.696303f,-0.208966f},{-0.660628f,0.487166f,-0.571173f}, -{-0.674737f,0.475049f,-0.564852f},{-0.691817f,0.69187f,-0.206653f},{-0.696956f,0.687456f,-0.2041f}, -{-0.702063f,0.68307f,-0.201305f},{-0.707128f,0.678719f,-0.198267f},{-0.712143f,0.674412f,-0.194989f}, -{-0.726783f,0.661838f,-0.183731f},{-0.770311f,0.392963f,-0.502197f},{-0.783195f,0.381897f,-0.490674f}, -{-0.731497f,0.65779f,-0.179515f},{-0.736111f,0.653826f,-0.175076f},{-0.740619f,0.649955f,-0.170419f}, -{-0.753409f,0.638969f,-0.155219f},{-0.84309f,0.330454f,-0.424264f},{-0.854004f,0.32108f,-0.409371f}, -{-0.757402f,0.63554f,-0.14977f},{-0.761248f,0.632236f,-0.144146f},{-0.76494f,0.629065f,-0.138358f}, -{-0.775039f,0.620392f,-0.120119f},{-0.90221f,0.279676f,-0.328326f},{-0.910477f,0.272576f,-0.311019f}, -{-0.778063f,0.617794f,-0.113788f},{-0.780911f,0.615349f,-0.107351f},{-0.783579f,0.613057f,-0.100821f}, -{-0.786066f,0.610921f,-0.0942108f},{-0.792428f,0.605457f,-0.0740269f},{-0.794182f,0.60395f,-0.0672227f}, -{-0.954536f,0.234735f,-0.183742f},{-0.958834f,0.231043f,-0.165095f},{-0.795755f,0.602599f,-0.0604006f}, -{-0.797147f,0.601403f,-0.0535724f},{-0.798362f,0.60036f,-0.0467497f},{-0.799403f,0.599467f,-0.0399431f}, -{-0.800271f,0.59872f,-0.0331634f},{-0.802109f,0.597142f,-0.00650573f},{-0.651551f,0.758605f,-1.07812e-032f}, -{-0.433008f,0.90139f,5.07106e-017f},{-0.562139f,0.571757f,-0.597573f},{-0.576025f,0.559831f,-0.595638f}, -{-0.548369f,0.583584f,-0.598933f},{-0.590006f,0.547823f,-0.593113f},{-0.604064f,0.535749f,-0.589983f}, -{-0.618177f,0.523627f,-0.586235f},{-0.632324f,0.511476f,-0.581857f},{-0.646483f,0.499316f,-0.576839f}, -{-0.688784f,0.462984f,-0.557873f},{-0.601059f,0.180175f,-0.778631f},{-0.702743f,0.450995f,-0.550232f}, -{-0.716589f,0.439103f,-0.541931f},{-0.730295f,0.427331f,-0.53297f},{-0.743835f,0.415702f,-0.523356f}, -{-0.757182f,0.404239f,-0.513095f},{-0.732756f,0.0670628f,-0.677179f},{-0.795809f,0.371062f,-0.47854f}, -{-0.808129f,0.360481f,-0.465812f},{-0.820131f,0.350173f,-0.452509f},{-0.831792f,0.340158f,-0.438652f}, -{-0.829983f,-0.0164437f,-0.557547f},{-0.864516f,0.312051f,-0.394f},{-0.874608f,0.303383f,-0.378179f}, -{-0.884264f,0.29509f,-0.361938f},{-0.893469f,0.287184f,-0.34531f},{-0.906037f,-0.0817656f,-0.415224f}, -{-0.918261f,0.26589f,-0.293425f},{-0.925555f,0.259626f,-0.275577f},{-0.932352f,0.253788f,-0.25751f}, -{-0.93865f,0.248379f,-0.239258f},{-0.944446f,0.243401f,-0.220857f},{-0.949741f,0.238853f,-0.20234f}, -{-0.962641f,0.227774f,-0.146431f},{-0.973538f,-0.13974f,-0.180824f},{-0.965962f,0.224921f,-0.127782f}, -{-0.968805f,0.222479f,-0.109178f},{-0.971179f,0.22044f,-0.0906466f},{-0.973095f,0.218795f,-0.0722163f}, -{-0.975595f,0.216648f,-0.0357604f},{-0.943289f,0.331972f,-1.55829e-016f},{-0.825457f,0.564465f,-4.03832e-017f}, -{-0.29793f,0.346881f,-0.889332f},{-0.402091f,0.351065f,-0.845622f},{-0.42174f,0.334188f,-0.842884f}, -{-0.441525f,0.317195f,-0.839311f},{-0.461418f,0.30011f,-0.834882f},{-0.48139f,0.282956f,-0.829578f}, -{-0.501409f,0.265762f,-0.823383f},{-0.521445f,0.248554f,-0.816282f},{-0.541462f,0.231361f,-0.808264f}, -{-0.561427f,0.214213f,-0.79932f},{-0.581305f,0.197141f,-0.789443f},{-0.475944f,-0.0842967f,-0.875426f}, -{-0.346402f,-0.297518f,-0.889657f},{-0.498084f,-0.103313f,-0.860952f},{-0.620651f,0.163347f,-0.766883f}, -{-0.640047f,0.146689f,-0.754203f},{-0.659207f,0.130232f,-0.740598f},{-0.678094f,0.11401f,-0.726078f}, -{-0.696673f,0.0980537f,-0.710657f},{-0.714905f,0.0823942f,-0.69435f},{-0.75019f,0.0520888f,-0.659168f}, -{-0.623817f,-0.211302f,-0.752465f},{-0.767173f,0.0375018f,-0.640343f},{-0.783674f,0.0233296f,-0.620733f}, -{-0.799662f,0.00959801f,-0.600374f},{-0.815107f,-0.00366745f,-0.579299f},{-0.731206f,-0.303536f,-0.610904f}, -{-0.602981f,-0.517889f,-0.606799f},{-0.746803f,-0.316933f,-0.58467f},{-0.844264f,-0.0287092f,-0.535159f}, -{-0.857927f,-0.0404448f,-0.512177f},{-0.870953f,-0.0516324f,-0.488646f},{-0.883323f,-0.0622568f,-0.464612f}, -{-0.895022f,-0.072305f,-0.440122f},{-0.916358f,-0.0906297f,-0.389967f},{-0.824484f,-0.383652f,-0.415977f}, -{-0.925977f,-0.0988914f,-0.3644f},{-0.934889f,-0.106546f,-0.338573f},{-0.943091f,-0.11359f,-0.312533f}, -{-0.950583f,-0.120025f,-0.286331f},{-0.957369f,-0.125853f,-0.260012f},{-0.963451f,-0.131077f,-0.233625f}, -{-0.968838f,-0.135704f,-0.207214f},{-0.977561f,-0.143196f,-0.154497f},{-0.980921f,-0.146082f,-0.128274f}, -{-0.983632f,-0.14841f,-0.102193f},{-0.226448f,0.12999f,-0.96531f},{-0.248879f,0.110725f,-0.962185f}, -{-0.271464f,0.0913273f,-0.958106f},{-0.294173f,0.0718231f,-0.95305f},{-0.316971f,0.0522418f,-0.946995f}, -{-0.339824f,0.0326136f,-0.939923f},{-0.362695f,0.0129701f,-0.931817f},{-0.385546f,-0.00665603f,-0.922665f}, -{-0.408337f,-0.0262307f,-0.912454f},{-0.431028f,-0.0457197f,-0.901179f},{-0.453578f,-0.065087f,-0.888837f}, -{-0.519956f,-0.122098f,-0.845422f},{-0.541517f,-0.140616f,-0.828846f},{-0.562725f,-0.158831f,-0.811242f}, -{-0.583538f,-0.176707f,-0.792627f},{-0.603915f,-0.194209f,-0.773026f},{-0.460322f,-0.395362f,-0.794854f}, -{-0.643204f,-0.227954f,-0.730976f},{-0.662041f,-0.244132f,-0.708591f},{-0.680291f,-0.259807f,-0.68535f}, -{-0.697922f,-0.27495f,-0.661292f},{-0.714903f,-0.289535f,-0.636461f},{-0.761673f,-0.329704f,-0.557808f}, -{-0.775794f,-0.341832f,-0.530373f},{-0.789149f,-0.353302f,-0.502416f},{-0.801723f,-0.364102f,-0.473994f}, -{-0.813504f,-0.374221f,-0.445162f},{-0.674899f,-0.579658f,-0.456627f},{-0.834658f,-0.392389f,-0.386494f}, -{-0.844021f,-0.400431f,-0.356769f},{-0.852574f,-0.407777f,-0.326857f},{-0.860319f,-0.41443f,-0.296814f}, -{-0.867263f,-0.420393f,-0.266692f},{-0.873412f,-0.425675f,-0.236543f},{-0.878777f,-0.430282f,-0.206418f}, -{-0.88337f,-0.434227f,-0.176364f},{-0.887205f,-0.437522f,-0.146429f},{-0.8903f,-0.440179f,-0.116657f}, -{-0.892671f,-0.442216f,-0.0870897f},{-0.894338f,-0.443647f,-0.0577667f},{-0.0673617f,-0.0578556f,-0.99605f}, -{-0.0897231f,-0.0770615f,-0.992981f},{-0.112006f,-0.0961995f,-0.98904f},{-0.13419f,-0.115254f,-0.98423f}, -{-0.156257f,-0.134206f,-0.978556f},{-0.178186f,-0.153041f,-0.972023f},{-0.199959f,-0.171741f,-0.964635f}, -{-0.221556f,-0.19029f,-0.956401f},{-0.242959f,-0.208673f,-0.947326f},{-0.264148f,-0.226872f,-0.937419f}, -{-0.285105f,-0.244871f,-0.926689f},{-0.305812f,-0.262656f,-0.915145f},{-0.32625f,-0.28021f,-0.902798f}, -{-0.366249f,-0.314564f,-0.875734f},{-0.385775f,-0.331335f,-0.861043f},{-0.404961f,-0.347814f,-0.845596f}, -{-0.423793f,-0.363987f,-0.829405f},{-0.442252f,-0.379842f,-0.812486f},{-0.477988f,-0.410535f,-0.776523f}, -{-0.495234f,-0.425347f,-0.757511f},{-0.512046f,-0.439786f,-0.737833f},{-0.528407f,-0.453839f,-0.717507f}, -{-0.544305f,-0.467493f,-0.696551f},{-0.559724f,-0.480737f,-0.674982f},{-0.574652f,-0.493558f,-0.652821f}, -{-0.589075f,-0.505946f,-0.630087f},{-0.616357f,-0.529378f,-0.582978f},{-0.629192f,-0.540401f,-0.558645f}, -{-0.641474f,-0.55095f,-0.533822f},{-0.653193f,-0.561015f,-0.508529f},{-0.664337f,-0.570587f,-0.48279f}, -{-0.684867f,-0.58822f,-0.430063f},{-0.694234f,-0.596265f,-0.403122f},{-0.702992f,-0.603786f,-0.375826f}, -{-0.711132f,-0.610777f,-0.3482f},{-0.718647f,-0.617232f,-0.320268f},{-0.725531f,-0.623145f,-0.292055f}, -{-0.731777f,-0.62851f,-0.263585f},{-0.737381f,-0.633323f,-0.234884f},{-0.742338f,-0.63758f,-0.205977f}, -{-0.746642f,-0.641277f,-0.176888f},{-0.750291f,-0.64441f,-0.147645f},{-0.75328f,-0.646978f,-0.118272f}, -{-0.755608f,-0.648978f,-0.0887941f},{-0.757272f,-0.650407f,-0.0592391f},{-0.758272f,-0.651265f,-0.0296323f}, -{-0.742338f,-0.63758f,0.205977f},{-0.88337f,-0.434227f,0.176364f},{-0.878777f,-0.430282f,0.206418f}, -{-0.844021f,-0.400431f,0.356769f},{-0.702992f,-0.603786f,0.375826f},{-0.711132f,-0.610777f,0.3482f}, -{-0.8903f,-0.440179f,0.116657f},{-0.892671f,-0.442216f,0.0870897f},{-0.983632f,-0.14841f,0.102193f}, -{-0.750291f,-0.64441f,0.147645f},{-0.75328f,-0.646978f,0.118272f},{-0.976204f,0.216125f,0.0177823f}, -{-0.943289f,0.331972f,3.41808e-016f},{-0.80211f,0.597142f,0.00650572f},{-0.974563f,0.217534f,0.0539127f}, -{-0.973095f,0.218795f,0.0722163f},{-0.985709f,-0.150194f,0.0762915f},{-0.46921f,0.883063f,-0.00650572f}, -{-0.184979f,0.982742f,-4.69192e-016f},{-0.0662783f,0.997643f,-0.0177823f},{-0.801509f,0.597657f,0.0197241f}, -{-0.800972f,0.598118f,0.0264206f},{0.574558f,0.81796f,-0.0287252f},{0.573574f,0.817114f,-0.0577667f}, -{0.2996f,0.953733f,-0.0251636f},{0.0755427f,0.997143f,-5.50975e-016f},{0.758605f,0.651551f,-9.3359e-016f}, -{0.564043f,0.825745f,-3.00566e-016f},{0.757272f,0.650407f,-0.0592414f},{-0.887205f,-0.437522f,0.146429f}, -{-0.746642f,-0.641277f,0.176888f},{0.758271f,0.651265f,-0.0296337f},{-0.731777f,-0.62851f,0.263585f}, -{-0.873412f,-0.425675f,0.236543f},{-0.867263f,-0.420393f,0.266692f},{-0.737381f,-0.633323f,0.234884f}, -{-0.860319f,-0.41443f,0.296814f},{-0.725531f,-0.623145f,0.292055f},{-0.852574f,-0.407777f,0.326857f}, -{-0.718647f,-0.617232f,0.320268f},{-0.834658f,-0.392389f,0.386494f},{-0.694234f,-0.596265f,0.403122f}, -{-0.813504f,-0.374221f,0.445162f},{-0.801723f,-0.364102f,0.473994f},{-0.664337f,-0.570587f,0.48279f}, -{-0.824484f,-0.383652f,0.415977f},{-0.629192f,-0.540401f,0.558645f},{-0.641474f,-0.55095f,0.533822f}, -{-0.775794f,-0.341832f,0.530373f},{-0.653193f,-0.561015f,0.508529f},{-0.602981f,-0.517889f,0.606799f}, -{-0.746803f,-0.316933f,0.58467f},{-0.731206f,-0.303536f,0.610904f},{-0.761673f,-0.329704f,0.557808f}, -{-0.559724f,-0.480737f,0.674982f},{-0.697922f,-0.27495f,0.661292f},{-0.544305f,-0.467493f,0.696551f}, -{-0.714903f,-0.289535f,0.636461f},{-0.495234f,-0.425347f,0.757511f},{-0.512046f,-0.439786f,0.737833f}, -{-0.643204f,-0.227954f,0.730976f},{-0.528407f,-0.453839f,0.717507f},{-0.662041f,-0.244132f,0.708591f}, -{-0.442252f,-0.379842f,0.812486f},{-0.603915f,-0.194209f,0.773026f},{-0.583538f,-0.176707f,0.792627f}, -{-0.623817f,-0.211302f,0.752465f},{-0.541517f,-0.140616f,0.828846f},{-0.385775f,-0.331335f,0.861043f}, -{-0.404961f,-0.347814f,0.845596f},{-0.423793f,-0.363987f,0.829405f},{-0.32625f,-0.28021f,0.902798f}, -{-0.346402f,-0.297518f,0.889657f},{-0.475944f,-0.0842968f,0.875426f},{-0.519956f,-0.122098f,0.845422f}, -{-0.453578f,-0.065087f,0.888837f},{-0.285105f,-0.244871f,0.926689f},{-0.305812f,-0.262656f,0.915145f}, -{-0.385546f,-0.00665599f,0.922665f},{-0.242959f,-0.208673f,0.947326f},{-0.408337f,-0.0262308f,0.912454f}, -{-0.264148f,-0.226872f,0.937419f},{-0.431028f,-0.0457197f,0.901179f},{-0.199959f,-0.171741f,0.964635f}, -{-0.362695f,0.0129701f,0.931817f},{-0.339824f,0.0326136f,0.939923f},{-0.221556f,-0.19029f,0.956401f}, -{-0.156257f,-0.134206f,0.978556f},{-0.316971f,0.0522418f,0.946995f},{-0.294173f,0.0718231f,0.95305f}, -{-0.178186f,-0.153041f,0.972023f},{-0.112006f,-0.0961995f,0.98904f},{-0.13419f,-0.115254f,0.98423f}, -{-0.271464f,0.0913273f,0.958106f},{-0.650623f,0.727251f,0.218624f},{-0.562139f,0.571757f,0.597573f}, -{-0.576025f,0.559831f,0.595638f},{-0.182173f,0.168017f,0.968805f},{-0.0449408f,-0.0385988f,0.998244f}, -{-0.204204f,0.149095f,0.967508f},{-0.0224803f,-0.0193079f,0.999561f},{-0.226448f,0.12999f,0.96531f}, -{-0.248878f,0.110725f,0.962185f},{-0.402091f,0.351064f,0.845622f},{-0.0673616f,-0.0578556f,0.99605f}, -{-0.0897231f,-0.0770615f,0.992981f},{-0.48139f,0.282956f,0.829578f},{-0.604064f,0.535749f,0.589983f}, -{-0.461418f,0.30011f,0.834882f},{-0.655702f,0.722888f,0.217917f},{-0.42174f,0.334188f,0.842884f}, -{-0.620697f,0.752953f,-0.218624f},{-0.625735f,0.748626f,-0.219122f},{-0.645585f,0.731578f,0.219122f}, -{-0.286341f,0.45048f,-0.845622f},{-0.305827f,0.433744f,-0.847547f},{-0.480343f,0.642011f,-0.597573f}, -{-0.432488f,0.503548f,-0.747926f},{-0.507751f,0.61847f,-0.599737f},{-0.325127f,0.417168f,-0.848684f}, -{-0.138591f,0.205449f,-0.968805f},{-0.304133f,0.354104f,-0.884372f},{-0.155494f,0.181042f,-0.971105f}, -{0.0224791f,0.019307f,-0.999561f},{-2.50764e-009f,2.91966e-009f,1.0f},{-0.155937f,0.181559f,0.970938f}, -{-0.521445f,0.248554f,0.816282f},{-0.562725f,-0.158831f,0.811242f},{-0.366249f,-0.314564f,0.875734f}, -{-0.498084f,-0.103313f,0.860952f},{-0.678094f,0.11401f,0.726078f},{-0.460322f,-0.395362f,0.794854f}, -{-0.477988f,-0.410535f,0.776523f},{-0.680291f,-0.259807f,0.68535f},{-0.574652f,-0.493558f,0.652821f}, -{-0.783674f,0.0233295f,0.620733f},{-0.831792f,0.340158f,0.438652f},{-0.820131f,0.350173f,0.452509f}, -{-0.589075f,-0.505946f,0.630087f},{-0.616357f,-0.529378f,0.582978f},{-0.674899f,-0.579658f,0.456627f}, -{-0.684867f,-0.58822f,0.430063f},{-0.789149f,-0.353302f,0.502416f},{-0.884264f,0.29509f,0.361938f}, -{-0.870953f,-0.0516324f,0.488646f},{-0.893469f,0.287184f,0.34531f},{-0.950583f,-0.120025f,0.286331f}, -{-0.755608f,-0.648978f,0.0887942f},{-0.651551f,0.758605f,1.22271e-018f},{-0.757272f,-0.650407f,0.059239f}, -{-0.894338f,-0.443647f,0.0577667f},{-0.988031f,-0.152189f,0.0251636f},{-0.997238f,0.0742779f,5.00783e-016f}, -{-0.758272f,-0.651265f,0.0296322f},{-0.895322f,-0.444493f,0.0287252f},{-0.901253f,-0.433294f,6.47993e-016f}, -{-0.983078f,-0.183188f,6.55067e-016f},{-0.758605f,-0.651551f,9.4456e-016f},{-0.825457f,0.564465f,2.60919e-016f}, -{-0.433008f,0.90139f,-2.0282e-016f},{-0.987169f,-0.151448f,0.0506042f},{-0.980921f,-0.146082f,0.128274f}, -{-0.977561f,-0.143196f,0.154497f},{-0.973538f,-0.13974f,0.180824f},{-0.968838f,-0.135704f,0.207214f}, -{-0.963451f,-0.131077f,0.233625f},{-0.957369f,-0.125853f,0.260012f},{-0.944446f,0.243401f,0.220857f}, -{-0.93865f,0.248379f,0.239258f},{-0.943091f,-0.11359f,0.312533f},{-0.934889f,-0.106546f,0.338573f}, -{-0.925977f,-0.0988913f,0.3644f},{-0.916358f,-0.0906299f,0.389967f},{-0.906037f,-0.0817656f,0.415224f}, -{-0.895022f,-0.072305f,0.440122f},{-0.883323f,-0.0622569f,0.464612f},{-0.857927f,-0.0404447f,0.512177f}, -{-0.844263f,-0.0287093f,0.535159f},{-0.829983f,-0.0164437f,0.557547f},{-0.815107f,-0.00366744f,0.579299f}, -{-0.799662f,0.00959806f,0.600374f},{-0.767173f,0.0375019f,0.640343f},{-0.75019f,0.0520888f,0.659168f}, -{-0.732756f,0.0670627f,0.677179f},{-0.714905f,0.0823943f,0.69435f},{-0.696673f,0.0980537f,0.710657f}, -{-0.707128f,0.678719f,0.198267f},{-0.730295f,0.427331f,0.53297f},{-0.712143f,0.674412f,0.194989f}, -{-0.659207f,0.130232f,0.740598f},{-0.640047f,0.146689f,0.754203f},{-0.620651f,0.163347f,0.766883f}, -{-0.601058f,0.180175f,0.778631f},{-0.581305f,0.197141f,0.789443f},{-0.561427f,0.214213f,0.79932f}, -{-0.541462f,0.231361f,0.808264f},{-0.501409f,0.265762f,0.823383f},{-0.618177f,0.523627f,0.586235f}, -{-0.441525f,0.317195f,0.839311f},{-0.382604f,0.367801f,0.847547f},{-0.363305f,0.384377f,0.848684f}, -{-0.29793f,0.346881f,0.889332f},{0.298738f,0.952993f,-0.0506042f},{-0.975595f,0.216648f,0.0357603f}, -{-0.971179f,0.22044f,0.0906467f},{-0.968805f,0.222479f,0.109178f},{-0.965962f,0.224921f,0.127782f}, -{-0.962641f,0.227774f,0.146431f},{-0.958834f,0.231043f,0.165095f},{-0.954536f,0.234735f,0.183742f}, -{-0.949741f,0.238853f,0.20234f},{-0.932352f,0.253788f,0.25751f},{-0.786066f,0.610921f,0.0942108f}, -{-0.783579f,0.613057f,0.100821f},{-0.925555f,0.259626f,0.275577f},{-0.918261f,0.26589f,0.293425f}, -{-0.910478f,0.272576f,0.31102f},{-0.90221f,0.279676f,0.328326f},{-0.761248f,0.632237f,0.144146f}, -{-0.510071f,0.847968f,-0.144146f},{-0.513917f,0.844665f,-0.14977f},{-0.874608f,0.303383f,0.378179f}, -{-0.864516f,0.312051f,0.394f},{-0.854004f,0.32108f,0.409371f},{-0.84309f,0.330454f,0.424264f}, -{-0.736111f,0.653826f,0.175076f},{-0.535208f,0.826378f,-0.175076f},{-0.539823f,0.822414f,-0.179515f}, -{-0.808129f,0.360481f,0.465812f},{-0.795809f,0.371062f,0.47854f},{-0.783195f,0.381897f,0.490674f}, -{-0.770311f,0.392963f,0.502197f},{-0.757182f,0.404239f,0.513095f},{-0.743835f,0.415702f,0.523356f}, -{-0.716589f,0.439103f,0.541931f},{-0.702743f,0.450995f,0.550232f},{-0.688784f,0.462984f,0.557873f}, -{-0.674737f,0.475049f,0.564853f},{-0.660628f,0.487166f,0.571173f},{-0.646483f,0.499316f,0.576839f}, -{-0.632324f,0.511476f,0.581857f},{-0.590006f,0.547823f,0.593113f},{-0.630724f,0.744341f,-0.219416f}, -{-0.548369f,0.583584f,0.598933f},{-0.534731f,0.595298f,0.599736f},{-0.431242f,0.502097f,0.749619f}, -{-0.800271f,0.59872f,0.0331634f},{-0.801887f,0.597333f,0.0130831f},{-0.799403f,0.599466f,0.0399431f}, -{-0.471917f,0.880738f,-0.0399431f},{-0.472957f,0.879844f,-0.0467496f},{-0.798362f,0.60036f,0.0467496f}, -{-0.797147f,0.601403f,0.0535724f},{-0.795755f,0.602599f,0.0604006f},{-0.794182f,0.60395f,0.0672227f}, -{-0.792428f,0.605457f,0.0740269f},{-0.790491f,0.607121f,0.0808012f},{-0.78837f,0.608942f,0.0875334f}, -{-0.780911f,0.615348f,0.107351f},{-0.490408f,0.864856f,-0.107351f},{-0.493256f,0.86241f,-0.113788f}, -{-0.778063f,0.617794f,0.113788f},{-0.775039f,0.620392f,0.120119f},{-0.771841f,0.623139f,0.126333f}, -{-0.768473f,0.626031f,0.132417f},{-0.76494f,0.629065f,0.138358f},{-0.757402f,0.63554f,0.14977f}, -{-0.753409f,0.638969f,0.155219f},{-0.749276f,0.642519f,0.160482f},{-0.74501f,0.646183f,0.165552f}, -{-0.740619f,0.649955f,0.170419f},{-0.731497f,0.65779f,0.179515f},{-0.726783f,0.661838f,0.183731f}, -{-0.72198f,0.665964f,0.187718f},{-0.717096f,0.670158f,0.191472f},{-0.702063f,0.68307f,0.201304f}, -{-0.569257f,0.797135f,-0.201304f},{-0.574363f,0.792748f,-0.2041f},{-0.696956f,0.687456f,0.2041f}, -{-0.691817f,0.69187f,0.206653f},{-0.686655f,0.696303f,0.208966f},{-0.68148f,0.700748f,0.211039f}, -{-0.6763f,0.705197f,0.212875f},{-0.671124f,0.709642f,0.214476f},{-0.665961f,0.714077f,0.215848f}, -{-0.660818f,0.718494f,0.216993f},{-0.640595f,0.735863f,0.219416f},{-0.646863f,0.753146f,-0.119748f}, -{-0.646762f,0.753028f,0.121027f},{-0.609092f,0.70917f,0.355084f},{-0.536047f,0.624123f,0.56844f}, -{-0.46981f,0.882547f,-0.0197242f},{-0.470347f,0.882086f,-0.0264206f},{-0.469433f,0.882871f,-0.013083f}, -{-0.471048f,0.881484f,-0.0331634f},{-0.474172f,0.878801f,-0.0535725f},{-0.475565f,0.877605f,-0.0604006f}, -{-0.477137f,0.876254f,-0.0672226f},{-0.0879462f,0.979032f,-0.183742f},{-0.0927413f,0.974914f,-0.20234f}, -{-0.478891f,0.874747f,-0.074027f},{-0.480829f,0.873084f,-0.0808012f},{-0.482949f,0.871262f,-0.0875334f}, -{-0.485253f,0.869283f,-0.0942108f},{-0.48774f,0.867147f,-0.100821f},{-0.496281f,0.859812f,-0.120119f}, -{-0.140272f,0.934091f,-0.328326f},{-0.149013f,0.926583f,-0.34531f},{-0.499479f,0.857065f,-0.126333f}, -{-0.502847f,0.854173f,-0.132416f},{-0.506379f,0.851139f,-0.138358f},{-0.51791f,0.841235f,-0.155219f}, -{-0.199392f,0.883313f,-0.424264f},{-0.21069f,0.87361f,-0.438652f},{-0.522044f,0.837685f,-0.160482f}, -{-0.52631f,0.834021f,-0.165552f},{-0.530701f,0.830249f,-0.170419f},{-0.544537f,0.818366f,-0.183731f}, -{-0.272171f,0.820805f,-0.502197f},{-0.2853f,0.809529f,-0.513095f},{-0.54934f,0.814241f,-0.187718f}, -{-0.554223f,0.810046f,-0.191472f},{-0.559177f,0.805792f,-0.194989f},{-0.564191f,0.801485f,-0.198267f}, -{-0.579503f,0.788334f,-0.206653f},{-0.584664f,0.783901f,-0.208966f},{-0.381854f,0.726601f,-0.571173f}, -{-0.395999f,0.714451f,-0.576839f},{-0.58984f,0.779456f,-0.211039f},{-0.595019f,0.775007f,-0.212874f}, -{-0.600195f,0.770562f,-0.214476f},{-0.605359f,0.766127f,-0.215847f},{-0.610502f,0.76171f,-0.216993f}, -{-0.615617f,0.757316f,-0.217917f},{-0.0679193f,0.996233f,-0.0539127f},{-0.069387f,0.994972f,-0.0722163f}, -{-0.0668873f,0.997119f,-0.0357603f},{-0.0713025f,0.993327f,-0.0906467f},{-0.0736771f,0.991288f,-0.109178f}, -{-0.0765202f,0.988846f,-0.127782f},{-0.0798413f,0.985994f,-0.146431f},{-0.0836479f,0.982724f,-0.165095f}, -{-0.0980359f,0.970367f,-0.220857f},{0.246457f,0.90809f,-0.338573f},{-0.103832f,0.965388f,-0.239258f}, -{-0.11013f,0.959979f,-0.25751f},{-0.116927f,0.954141f,-0.275577f},{-0.124221f,0.947877f,-0.293425f}, -{-0.132004f,0.941192f,-0.31102f},{0.169495f,0.841989f,-0.512177f},{-0.158218f,0.918677f,-0.361938f}, -{-0.167874f,0.910384f,-0.378179f},{-0.177966f,0.901716f,-0.394f},{-0.188478f,0.892688f,-0.409371f}, -{0.078742f,0.764043f,-0.640343f},{-0.222351f,0.863595f,-0.452509f},{-0.234353f,0.853287f,-0.465812f}, -{-0.246673f,0.842705f,-0.47854f},{-0.259287f,0.831871f,-0.490674f},{-0.0292248f,0.671312f,-0.740598f}, -{-0.298647f,0.798065f,-0.523356f},{-0.312187f,0.786436f,-0.53297f},{-0.325893f,0.774664f,-0.541931f}, -{-0.339739f,0.762773f,-0.550232f},{-0.353698f,0.750783f,-0.557873f},{-0.367745f,0.738719f,-0.564853f}, -{-0.410157f,0.702291f,-0.581857f},{-0.207042f,0.518588f,-0.829578f},{-0.424305f,0.69014f,-0.586235f}, -{-0.438418f,0.678019f,-0.589983f},{-0.452476f,0.665945f,-0.593113f},{-0.466457f,0.653936f,-0.595638f}, -{-0.494113f,0.630183f,-0.598933f},{-0.609586f,0.709744f,-0.353084f},{0.339059f,0.940765f,-6.77795e-016f}, -{0.297277f,0.951738f,-0.0762915f},{0.2952f,0.949954f,-0.102193f},{0.29249f,0.947626f,-0.128274f}, -{0.28913f,0.944741f,-0.154497f},{0.285106f,0.941285f,-0.180824f},{0.280406f,0.937248f,-0.207214f}, -{0.27502f,0.932622f,-0.233625f},{0.268937f,0.927398f,-0.260012f},{0.262152f,0.92157f,-0.286331f}, -{0.254659f,0.915135f,-0.312533f},{0.503721f,0.757119f,-0.415977f},{0.674898f,0.579657f,-0.45663f}, -{0.492741f,0.747688f,-0.445162f},{0.237545f,0.900436f,-0.3644f},{0.227927f,0.892174f,-0.389967f}, -{0.217606f,0.88331f,-0.415224f},{0.206591f,0.87385f,-0.440122f},{0.194892f,0.863801f,-0.464612f}, -{0.182522f,0.853177f,-0.488646f},{0.155832f,0.830254f,-0.535159f},{0.410442f,0.677003f,-0.610904f}, -{0.141551f,0.817988f,-0.557547f},{0.126675f,0.805212f,-0.579299f},{0.111231f,0.791946f,-0.600374f}, -{0.095243f,0.778215f,-0.620733f},{0.303053f,0.584769f,-0.752465f},{0.46032f,0.39536f,-0.794856f}, -{0.283151f,0.567676f,-0.773026f},{0.0617581f,0.749456f,-0.659168f},{0.0443242f,0.734482f,-0.677179f}, -{0.0264735f,0.71915f,-0.69435f},{0.008241f,0.703491f,-0.710657f},{-0.0103371f,0.687534f,-0.726078f}, -{-0.048385f,0.654856f,-0.754203f},{0.15518f,0.457764f,-0.875426f},{-0.06778f,0.638198f,-0.766883f}, -{-0.0873729f,0.62137f,-0.778631f},{-0.107127f,0.604404f,-0.789443f},{-0.127004f,0.587331f,-0.79932f}, -{-0.146969f,0.570183f,-0.808264f},{-0.166987f,0.552991f,-0.816282f},{-0.187022f,0.535783f,-0.823383f}, -{-0.227014f,0.501435f,-0.834882f},{-0.246907f,0.484349f,-0.839311f},{-0.266692f,0.467356f,-0.842884f}, -{-0.536319f,0.624439f,-0.567836f},{0.571907f,0.815682f,-0.0870897f},{0.569536f,0.813646f,-0.116657f}, -{0.566442f,0.810988f,-0.146429f},{0.562606f,0.807694f,-0.176364f},{0.558013f,0.803749f,-0.206418f}, -{0.552648f,0.799142f,-0.236543f},{0.546499f,0.79386f,-0.266692f},{0.539556f,0.787897f,-0.296814f}, -{0.53181f,0.781244f,-0.326857f},{0.523257f,0.773898f,-0.356769f},{0.513894f,0.765856f,-0.386494f}, -{0.480959f,0.737569f,-0.473994f},{0.468385f,0.726769f,-0.502416f},{0.45503f,0.715299f,-0.530373f}, -{0.440909f,0.703171f,-0.557808f},{0.426039f,0.6904f,-0.58467f},{0.60298f,0.517888f,-0.606801f}, -{0.39414f,0.663001f,-0.636461f},{0.377159f,0.648417f,-0.661292f},{0.359528f,0.633274f,-0.68535f}, -{0.341277f,0.617599f,-0.708591f},{0.322441f,0.601421f,-0.730976f},{0.262774f,0.550174f,-0.792627f}, -{0.241961f,0.532298f,-0.811242f},{0.220753f,0.514083f,-0.828846f},{0.199192f,0.495565f,-0.845422f}, -{0.17732f,0.47678f,-0.860952f},{0.346399f,0.297516f,-0.889658f},{0.132814f,0.438554f,-0.888837f}, -{0.110265f,0.419187f,-0.901179f},{0.0875737f,0.399698f,-0.912454f},{0.0647825f,0.380123f,-0.922664f}, -{0.0419318f,0.360497f,-0.931817f},{0.0190608f,0.340853f,-0.939923f},{-0.00379256f,0.321225f,-0.946995f}, -{-0.0265911f,0.301644f,-0.95305f},{-0.0493f,0.28214f,-0.958106f},{-0.0718851f,0.262741f,-0.962185f}, -{-0.0943152f,0.243477f,-0.96531f},{-0.11656f,0.224371f,-0.967508f},{0.755608f,0.648978f,-0.0887968f}, -{0.75328f,0.646978f,-0.118274f},{0.75029f,0.64441f,-0.147647f},{0.746642f,0.641277f,-0.176891f}, -{0.742337f,0.63758f,-0.205979f},{0.737381f,0.633323f,-0.234887f},{0.731777f,0.628509f,-0.263588f}, -{0.72553f,0.623144f,-0.292057f},{0.718646f,0.617231f,-0.320271f},{0.711131f,0.610777f,-0.348202f}, -{0.702991f,0.603786f,-0.375828f},{0.694233f,0.596264f,-0.403124f},{0.684866f,0.588219f,-0.430066f}, -{0.664336f,0.570586f,-0.482793f},{0.653191f,0.561014f,-0.508532f},{0.641473f,0.550949f,-0.533824f}, -{0.629191f,0.5404f,-0.558647f},{0.616356f,0.529376f,-0.58298f},{0.589074f,0.505945f,-0.630088f}, -{0.574651f,0.493557f,-0.652822f},{0.559724f,0.480736f,-0.674983f},{0.544304f,0.467493f,-0.696551f}, -{0.528407f,0.453838f,-0.717508f},{0.512045f,0.439786f,-0.737834f},{0.495233f,0.425347f,-0.757512f}, -{0.477987f,0.410534f,-0.776525f},{0.44225f,0.37984f,-0.812488f},{0.423791f,0.363986f,-0.829407f}, -{0.40496f,0.347812f,-0.845597f},{0.385773f,0.331333f,-0.861045f},{0.366247f,0.314563f,-0.875736f}, -{0.326248f,0.280208f,-0.902799f},{0.30581f,0.262654f,-0.915146f},{0.285103f,0.24487f,-0.92669f}, -{0.264146f,0.22687f,-0.93742f},{0.242957f,0.208671f,-0.947327f},{0.221554f,0.190289f,-0.956402f}, -{0.199957f,0.171739f,-0.964636f},{0.178184f,0.153039f,-0.972023f},{0.156255f,0.134204f,-0.978557f}, -{0.134188f,0.115252f,-0.984231f},{0.112004f,0.0961983f,-0.98904f},{0.0897214f,0.07706f,-0.992981f}, -{0.0673596f,0.0578539f,-0.99605f},{0.044939f,0.0385973f,-0.998244f},{0.775794f,0.341832f,-0.530373f}, -{0.761673f,0.329704f,-0.557808f},{0.629192f,0.540401f,-0.558645f},{0.641474f,0.55095f,-0.533822f}, -{0.76494f,-0.629065f,-0.138358f},{0.864516f,-0.312051f,-0.394f},{0.874608f,-0.303383f,-0.378179f}, -{0.801723f,0.364102f,-0.473994f},{0.653193f,0.561015f,-0.508529f},{0.664337f,0.570587f,-0.48279f}, -{0.789149f,0.353302f,-0.502416f},{0.674899f,0.579658f,-0.456627f},{0.684867f,0.58822f,-0.430063f}, -{0.824484f,0.383652f,-0.415977f},{0.813504f,0.374221f,-0.445162f},{0.694234f,0.596265f,-0.403122f}, -{0.834658f,0.392389f,-0.386494f},{0.844021f,0.400431f,-0.356769f},{0.702992f,0.603786f,-0.375826f}, -{0.711132f,0.610777f,-0.3482f},{0.852574f,0.407777f,-0.326857f},{0.932352f,-0.253788f,-0.25751f}, -{0.925977f,0.0988914f,-0.3644f},{0.93865f,-0.248379f,-0.239258f},{0.860319f,0.41443f,-0.296814f}, -{0.718647f,0.617232f,-0.320268f},{0.725531f,0.623145f,-0.292055f},{0.867263f,0.420393f,-0.266692f}, -{0.731777f,0.62851f,-0.263585f},{0.873412f,0.425675f,-0.236543f},{0.878777f,0.430282f,-0.206418f}, -{0.742338f,0.63758f,-0.205977f},{0.88337f,0.434227f,-0.176364f},{0.737381f,0.633323f,-0.234884f}, -{0.746642f,0.641277f,-0.176888f},{0.887205f,0.437522f,-0.146429f},{0.750291f,0.64441f,-0.147645f}, -{0.8903f,0.440179f,-0.116657f},{0.75328f,0.646978f,-0.118272f},{0.892671f,0.442216f,-0.0870897f}, -{0.985709f,0.150194f,-0.0762915f},{0.983632f,0.14841f,-0.102193f},{-0.758272f,-0.651265f,0.0296337f}, -{-0.574558f,-0.81796f,0.0287252f},{-0.2996f,-0.953733f,0.0251636f},{0.0662783f,-0.997643f,0.0177823f}, -{-0.0755427f,-0.997143f,4.44435e-016f},{-0.564043f,-0.825745f,3.04136e-016f},{-0.573574f,-0.817114f,0.0577667f}, -{-0.571907f,-0.815682f,0.0870897f},{-0.297277f,-0.951738f,0.0762915f},{0.755608f,0.648978f,-0.0887942f}, -{0.974563f,-0.217534f,-0.0539127f},{0.973095f,-0.218795f,-0.0722163f},{0.800972f,-0.598118f,-0.0264206f}, -{0.971179f,-0.22044f,-0.0906467f},{0.801509f,-0.597657f,-0.0197242f},{0.757272f,0.650407f,-0.059239f}, -{0.894338f,0.443647f,-0.0577667f},{0.997238f,-0.0742779f,-4.48371e-016f},{0.976204f,-0.216125f,-0.0177823f}, -{0.988031f,0.152189f,-0.0251636f},{0.943289f,-0.331972f,-4.29587e-016f},{0.80211f,-0.597142f,-0.00650572f}, -{0.825457f,-0.564465f,-3.05233e-016f},{0.983078f,0.183188f,-6.14496e-016f},{0.895322f,0.444493f,-0.0287252f}, -{0.901253f,0.433294f,-9.46059e-016f},{0.758272f,0.651265f,-0.0296322f},{0.46921f,-0.883063f,0.00650572f}, -{0.184979f,-0.982742f,5.48296e-016f},{0.616357f,0.529378f,-0.582978f},{0.602981f,0.517889f,-0.606799f}, -{0.746803f,0.316933f,-0.58467f},{0.731206f,0.303536f,-0.610904f},{0.589075f,0.505946f,-0.630087f}, -{0.574652f,0.493558f,-0.652821f},{0.714903f,0.289535f,-0.636461f},{0.697922f,0.27495f,-0.661292f}, -{0.559724f,0.480737f,-0.674982f},{0.544305f,0.467493f,-0.696551f},{0.680291f,0.259807f,-0.68535f}, -{0.528407f,0.453839f,-0.717507f},{0.662041f,0.244132f,-0.708591f},{0.75019f,-0.0520889f,-0.659168f}, -{0.820131f,-0.350173f,-0.452509f},{0.808129f,-0.360481f,-0.465812f},{0.643204f,0.227954f,-0.730976f}, -{0.512046f,0.439786f,-0.737833f},{0.623817f,0.211302f,-0.752465f},{0.495234f,0.425347f,-0.757511f}, -{0.460322f,0.395362f,-0.794854f},{0.477988f,0.410535f,-0.776523f},{0.603915f,0.194209f,-0.773026f}, -{0.442252f,0.379842f,-0.812486f},{0.583538f,0.176707f,-0.792627f},{0.423793f,0.363987f,-0.829405f}, -{0.404961f,0.347814f,-0.845596f},{0.562725f,0.158831f,-0.811242f},{0.541517f,0.140616f,-0.828846f}, -{0.385775f,0.331335f,-0.861043f},{0.519956f,0.122098f,-0.845422f},{0.716589f,-0.439103f,-0.541931f}, -{0.707128f,-0.678719f,-0.198267f},{0.702743f,-0.450995f,-0.550232f},{0.366249f,0.314564f,-0.875734f}, -{0.498084f,0.103313f,-0.860952f},{0.475944f,0.0842968f,-0.875426f},{0.346402f,0.297518f,-0.889657f}, -{0.32625f,0.28021f,-0.902798f},{0.305812f,0.262656f,-0.915145f},{0.285105f,0.244871f,-0.926689f}, -{0.453578f,0.065087f,-0.888837f},{0.431028f,0.0457196f,-0.901179f},{0.264148f,0.226872f,-0.937419f}, -{0.408337f,0.0262308f,-0.912454f},{0.242959f,0.208673f,-0.947326f},{0.221556f,0.19029f,-0.956401f}, -{0.385546f,0.00665601f,-0.922665f},{0.362695f,-0.0129701f,-0.931817f},{0.199959f,0.171741f,-0.964635f}, -{0.339824f,-0.0326136f,-0.939923f},{0.48139f,-0.282956f,-0.829578f},{0.316971f,-0.0522418f,-0.946995f}, -{0.501409f,-0.265762f,-0.823383f},{0.178186f,0.153041f,-0.972023f},{0.294173f,-0.0718231f,-0.95305f}, -{0.156257f,0.134206f,-0.978556f},{0.248878f,-0.110725f,-0.962185f},{0.441525f,-0.317195f,-0.839311f}, -{0.42174f,-0.334188f,-0.842884f},{0.13419f,0.115253f,-0.98423f},{0.650623f,-0.727251f,-0.218624f}, -{0.620697f,-0.752953f,0.218624f},{0.645585f,-0.731578f,-0.219122f},{0.665961f,-0.714077f,-0.215848f}, -{0.660818f,-0.718494f,-0.216993f},{0.590006f,-0.547823f,-0.593113f},{0.286341f,-0.45048f,0.845622f}, -{0.480343f,-0.642011f,0.597573f},{0.266692f,-0.467356f,0.842884f},{0.325127f,-0.417168f,0.848684f}, -{0.432488f,-0.503548f,0.747926f},{0.507751f,-0.61847f,0.599737f},{0.548369f,-0.583584f,-0.598933f}, -{0.562139f,-0.571757f,-0.597573f},{0.304133f,-0.354104f,0.884372f},{0.138591f,-0.205449f,0.968805f}, -{0.155494f,-0.181043f,0.971105f},{0.576025f,-0.559831f,-0.595638f},{0.655703f,-0.722888f,-0.217916f}, -{0.382604f,-0.367801f,-0.847547f},{0.402091f,-0.351064f,-0.845622f},{-0.0224792f,-0.0193069f,0.999561f}, -{0.271464f,-0.0913273f,-0.958106f},{0.112006f,0.0961995f,-0.98904f},{0.0897231f,0.0770615f,-0.992981f}, -{0.226448f,-0.12999f,-0.96531f},{0.204204f,-0.149095f,-0.967508f},{0.0673616f,0.0578556f,-0.99605f}, -{0.182173f,-0.168017f,-0.968805f},{0.0224803f,0.0193079f,-0.999561f},{0.0449408f,0.0385988f,-0.998244f}, -{0.155937f,-0.181559f,-0.970938f},{0.433008f,-0.90139f,1.81967e-016f},{0.987169f,0.151448f,-0.0506042f}, -{0.980921f,0.146082f,-0.128274f},{0.977561f,0.143196f,-0.154497f},{0.973538f,0.13974f,-0.180824f}, -{0.968838f,0.135704f,-0.207214f},{0.963451f,0.131077f,-0.233625f},{0.957369f,0.125853f,-0.260012f}, -{0.950583f,0.120025f,-0.286331f},{0.943091f,0.11359f,-0.312533f},{0.934889f,0.106546f,-0.338573f}, -{0.916358f,0.0906299f,-0.389967f},{0.906037f,0.0817656f,-0.415224f},{0.895022f,0.072305f,-0.440122f}, -{0.883323f,0.0622569f,-0.464612f},{0.870953f,0.0516324f,-0.488646f},{0.857927f,0.0404447f,-0.512177f}, -{0.844263f,0.0287093f,-0.535159f},{0.829983f,0.0164437f,-0.557547f},{0.815107f,0.00366744f,-0.579299f}, -{0.799662f,-0.00959801f,-0.600374f},{0.783674f,-0.0233295f,-0.620733f},{0.767173f,-0.0375019f,-0.640343f}, -{0.732756f,-0.0670627f,-0.677179f},{0.714905f,-0.0823942f,-0.69435f},{0.696673f,-0.0980537f,-0.710657f}, -{0.678094f,-0.11401f,-0.726078f},{0.659207f,-0.130232f,-0.740598f},{0.640047f,-0.146689f,-0.754203f}, -{0.620651f,-0.163347f,-0.766883f},{0.601058f,-0.180175f,-0.778631f},{0.581305f,-0.197141f,-0.789443f}, -{0.561427f,-0.214213f,-0.79932f},{0.541462f,-0.231361f,-0.808264f},{0.521445f,-0.248554f,-0.816282f}, -{0.461418f,-0.30011f,-0.834882f},{0.604064f,-0.535749f,-0.589983f},{0.363305f,-0.384377f,-0.848684f}, -{0.29793f,-0.346881f,-0.889332f},{-0.757272f,-0.650407f,0.0592414f},{0.975595f,-0.216648f,-0.0357603f}, -{0.968805f,-0.222479f,-0.109178f},{0.965962f,-0.224921f,-0.127782f},{0.962641f,-0.227774f,-0.146431f}, -{0.958834f,-0.231043f,-0.165095f},{0.954536f,-0.234735f,-0.183742f},{0.949741f,-0.238853f,-0.20234f}, -{0.944446f,-0.243401f,-0.220857f},{0.918261f,-0.26589f,-0.293425f},{0.925555f,-0.259626f,-0.275577f}, -{0.783579f,-0.613057f,-0.100821f},{0.910478f,-0.272576f,-0.31102f},{0.90221f,-0.279676f,-0.328326f}, -{0.893469f,-0.287184f,-0.34531f},{0.884264f,-0.29509f,-0.361938f},{0.854004f,-0.32108f,-0.409371f}, -{0.84309f,-0.330454f,-0.424264f},{0.831792f,-0.340158f,-0.438652f},{0.731496f,-0.65779f,-0.179515f}, -{0.539823f,-0.822414f,0.179515f},{0.726783f,-0.661838f,-0.183731f},{0.795809f,-0.371062f,-0.47854f}, -{0.783195f,-0.381897f,-0.490674f},{0.770311f,-0.392963f,-0.502197f},{0.757182f,-0.404239f,-0.513095f}, -{0.743835f,-0.415702f,-0.523356f},{0.730295f,-0.427331f,-0.53297f},{0.688784f,-0.462984f,-0.557873f}, -{0.674737f,-0.475049f,-0.564853f},{0.660628f,-0.487166f,-0.571173f},{0.646483f,-0.499316f,-0.576839f}, -{0.632324f,-0.511476f,-0.581857f},{0.618177f,-0.523627f,-0.586235f},{0.646762f,-0.753028f,-0.121027f}, -{0.640595f,-0.735863f,-0.219416f},{0.630724f,-0.744341f,0.219416f},{0.534731f,-0.595298f,-0.599736f}, -{0.431242f,-0.502097f,-0.749619f},{0.651551f,-0.758605f,1.22271e-018f},{0.801887f,-0.597333f,-0.013083f}, -{0.800271f,-0.59872f,-0.0331634f},{0.799403f,-0.599466f,-0.0399431f},{0.474172f,-0.878801f,0.0535724f}, -{0.795755f,-0.6026f,-0.0604006f},{0.797147f,-0.601403f,-0.0535725f},{0.798362f,-0.60036f,-0.0467496f}, -{0.794182f,-0.60395f,-0.0672227f},{0.792428f,-0.605457f,-0.0740269f},{0.790491f,-0.607121f,-0.0808013f}, -{0.78837f,-0.608942f,-0.0875334f},{0.786066f,-0.610921f,-0.0942108f},{0.493256f,-0.86241f,0.113788f}, -{0.775039f,-0.620392f,-0.120119f},{0.778063f,-0.617794f,-0.113788f},{0.780911f,-0.615348f,-0.107351f}, -{0.771841f,-0.623139f,-0.126333f},{0.768473f,-0.626031f,-0.132417f},{0.513917f,-0.844665f,0.14977f}, -{0.753409f,-0.638969f,-0.155219f},{0.757402f,-0.63554f,-0.14977f},{0.761248f,-0.632237f,-0.144146f}, -{0.749276f,-0.642519f,-0.160482f},{0.74501f,-0.646183f,-0.165552f},{0.740619f,-0.649955f,-0.170419f}, -{0.736112f,-0.653826f,-0.175076f},{0.72198f,-0.665964f,-0.187718f},{0.717096f,-0.670158f,-0.191472f}, -{0.712143f,-0.674412f,-0.194989f},{0.574363f,-0.792748f,0.2041f},{0.691817f,-0.69187f,-0.206653f}, -{0.696956f,-0.687456f,-0.2041f},{0.702063f,-0.68307f,-0.201304f},{0.686655f,-0.696303f,-0.208966f}, -{0.68148f,-0.700748f,-0.211039f},{0.6763f,-0.705197f,-0.212874f},{0.671124f,-0.709642f,-0.214476f}, -{0.494113f,-0.630183f,0.598933f},{0.615617f,-0.757316f,0.217917f},{0.609092f,-0.70917f,-0.355084f}, -{0.536047f,-0.624123f,-0.56844f},{0.46981f,-0.882547f,0.0197241f},{0.469433f,-0.882871f,0.0130831f}, -{0.470347f,-0.882086f,0.0264206f},{0.471048f,-0.881484f,0.0331634f},{0.471917f,-0.880738f,0.0399431f}, -{0.472957f,-0.879844f,0.0467496f},{0.475565f,-0.877605f,0.0604006f},{0.480829f,-0.873084f,0.0808012f}, -{0.478891f,-0.874747f,0.074027f},{0.0927413f,-0.974914f,0.20234f},{0.477137f,-0.876254f,0.0672226f}, -{0.482949f,-0.871262f,0.0875334f},{0.485253f,-0.869283f,0.0942108f},{0.48774f,-0.867147f,0.100821f}, -{0.490408f,-0.864856f,0.107351f},{-0.169495f,-0.841989f,0.512177f},{0.158218f,-0.918677f,0.361938f}, -{-0.182522f,-0.853177f,0.488646f},{0.496281f,-0.859812f,0.120119f},{0.499479f,-0.857065f,0.126333f}, -{0.502847f,-0.854173f,0.132416f},{0.506379f,-0.851139f,0.138358f},{0.510071f,-0.847968f,0.144146f}, -{-0.078742f,-0.764043f,0.640343f},{0.222351f,-0.863595f,0.452509f},{-0.095243f,-0.778215f,0.620733f}, -{0.51791f,-0.841235f,0.155219f},{0.522044f,-0.837685f,0.160482f},{0.52631f,-0.834021f,0.165552f}, -{0.530701f,-0.830249f,0.170419f},{0.535208f,-0.826378f,0.175076f},{0.554223f,-0.810046f,0.191472f}, -{0.54934f,-0.814241f,0.187718f},{0.2853f,-0.809529f,0.513095f},{0.544537f,-0.818366f,0.183731f}, -{0.559177f,-0.805792f,0.194989f},{0.564191f,-0.801485f,0.198267f},{0.569257f,-0.797135f,0.201304f}, -{0.579503f,-0.788334f,0.206653f},{0.595019f,-0.775007f,0.212874f},{0.58984f,-0.779456f,0.211039f}, -{0.395999f,-0.714451f,0.576839f},{0.584664f,-0.783901f,0.208966f},{0.600195f,-0.770562f,0.214476f}, -{0.605359f,-0.766127f,0.215847f},{0.610502f,-0.76171f,0.216993f},{0.466457f,-0.653936f,0.595638f}, -{0.625735f,-0.748626f,0.219122f},{0.0679193f,-0.996233f,0.0539127f},{0.0668873f,-0.997119f,0.0357603f}, -{0.0693872f,-0.994972f,0.0722163f},{0.0713027f,-0.993327f,0.0906467f},{0.0736769f,-0.991288f,0.109178f}, -{0.0765202f,-0.988846f,0.127782f},{0.0798415f,-0.985994f,0.146431f},{0.0836479f,-0.982724f,0.165095f}, -{0.0879462f,-0.979032f,0.183742f},{-0.254659f,-0.915135f,0.312533f},{-0.246457f,-0.90809f,0.338573f}, -{0.103832f,-0.965388f,0.239258f},{0.0980359f,-0.970367f,0.220857f},{0.11013f,-0.959979f,0.257509f}, -{0.116927f,-0.954141f,0.275577f},{0.12422f,-0.947877f,0.293425f},{0.132004f,-0.941192f,0.31102f}, -{0.140272f,-0.934091f,0.328326f},{0.149013f,-0.926583f,0.34531f},{0.167874f,-0.910384f,0.378179f}, -{0.177966f,-0.901716f,0.394f},{0.188478f,-0.892688f,0.409371f},{0.199392f,-0.883313f,0.424264f}, -{0.21069f,-0.87361f,0.438652f},{0.234353f,-0.853287f,0.465812f},{0.246673f,-0.842705f,0.47854f}, -{0.259287f,-0.831871f,0.490674f},{0.272171f,-0.820805f,0.502197f},{0.0292248f,-0.671312f,0.740598f}, -{0.0483848f,-0.654856f,0.754203f},{0.312187f,-0.786436f,0.53297f},{0.298647f,-0.798065f,0.523356f}, -{0.325893f,-0.774664f,0.541931f},{0.339739f,-0.762773f,0.550232f},{0.353698f,-0.750783f,0.557873f}, -{0.367745f,-0.738719f,0.564853f},{0.381854f,-0.726601f,0.571173f},{0.410157f,-0.702291f,0.581857f}, -{0.207042f,-0.518588f,0.829578f},{0.227014f,-0.501435f,0.834882f},{0.438418f,-0.678019f,0.589983f}, -{0.424305f,-0.69014f,0.586235f},{0.452476f,-0.665945f,0.593113f},{0.609586f,-0.709744f,0.353084f}, -{0.646863f,-0.753146f,0.119748f},{-0.339059f,-0.940765f,5.47231e-016f},{-0.298738f,-0.952993f,0.0506042f}, -{-0.2952f,-0.949954f,0.102193f},{-0.29249f,-0.947626f,0.128274f},{-0.569536f,-0.813646f,0.116657f}, -{-0.28913f,-0.944741f,0.154497f},{-0.285106f,-0.941285f,0.180824f},{-0.280406f,-0.937248f,0.207214f}, -{-0.27502f,-0.932622f,0.233625f},{-0.268937f,-0.927398f,0.260012f},{-0.262152f,-0.92157f,0.286331f}, -{-0.674898f,-0.579657f,0.45663f},{-0.492741f,-0.747688f,0.445162f},{-0.503721f,-0.757119f,0.415977f}, -{-0.237545f,-0.900436f,0.3644f},{-0.227927f,-0.892174f,0.389967f},{-0.217606f,-0.88331f,0.415224f}, -{-0.206591f,-0.87385f,0.440122f},{-0.194892f,-0.863801f,0.464612f},{-0.410442f,-0.677003f,0.610904f}, -{-0.155832f,-0.830254f,0.535159f},{-0.426039f,-0.6904f,0.58467f},{-0.141551f,-0.817988f,0.557547f}, -{-0.126676f,-0.805212f,0.579299f},{-0.11123f,-0.791947f,0.600374f},{-0.303053f,-0.584769f,0.752465f}, -{-0.46032f,-0.39536f,0.794856f},{-0.283151f,-0.567676f,0.773026f},{-0.0617581f,-0.749456f,0.659168f}, -{-0.0443242f,-0.734482f,0.677179f},{-0.0264735f,-0.71915f,0.69435f},{-0.008241f,-0.703491f,0.710657f}, -{0.0103371f,-0.687534f,0.726078f},{-0.15518f,-0.457764f,0.875426f},{0.0677801f,-0.638198f,0.766883f}, -{-0.177321f,-0.476779f,0.860952f},{0.0873729f,-0.62137f,0.778631f},{0.107127f,-0.604404f,0.789443f}, -{0.127004f,-0.587331f,0.79932f},{0.146969f,-0.570183f,0.808264f},{0.166987f,-0.552991f,0.816282f}, -{0.187022f,-0.535783f,0.823383f},{0.246907f,-0.484349f,0.839311f},{0.11656f,-0.224372f,0.967508f}, -{0.0943152f,-0.243477f,0.96531f},{0.305827f,-0.433744f,0.847547f},{0.536319f,-0.624439f,0.567837f}, -{-0.566442f,-0.810988f,0.146429f},{-0.562606f,-0.807694f,0.176364f},{-0.558013f,-0.803749f,0.206418f}, -{-0.552648f,-0.799142f,0.236543f},{-0.546499f,-0.79386f,0.266692f},{-0.539556f,-0.787897f,0.296814f}, -{-0.53181f,-0.781244f,0.326857f},{-0.523257f,-0.773898f,0.356769f},{-0.513894f,-0.765856f,0.386494f}, -{-0.480959f,-0.737569f,0.473994f},{-0.468385f,-0.726769f,0.502416f},{-0.45503f,-0.715299f,0.530373f}, -{-0.440909f,-0.703171f,0.557808f},{-0.60298f,-0.517888f,0.606801f},{-0.39414f,-0.663001f,0.636461f}, -{-0.377159f,-0.648417f,0.661292f},{-0.359528f,-0.633274f,0.68535f},{-0.341277f,-0.617599f,0.708591f}, -{-0.322441f,-0.601421f,0.730976f},{-0.262774f,-0.550174f,0.792627f},{-0.241961f,-0.532298f,0.811242f}, -{-0.220753f,-0.514083f,0.828846f},{-0.199192f,-0.495565f,0.845422f},{-0.346399f,-0.297516f,0.889658f}, -{-0.132814f,-0.438554f,0.888837f},{-0.110264f,-0.419187f,0.901179f},{-0.0875737f,-0.399698f,0.912454f}, -{-0.0647826f,-0.380123f,0.922665f},{-0.0419317f,-0.360497f,0.931817f},{-0.0190608f,-0.340853f,0.939923f}, -{0.00379247f,-0.321225f,0.946995f},{0.0265911f,-0.301644f,0.95305f},{0.0493001f,-0.28214f,0.958106f}, -{0.0718852f,-0.262742f,0.962185f},{-0.755608f,-0.648977f,0.0887968f},{-0.75328f,-0.646978f,0.118274f}, -{-0.75029f,-0.64441f,0.147647f},{-0.746642f,-0.641277f,0.176891f},{-0.742337f,-0.63758f,0.205979f}, -{-0.737381f,-0.633323f,0.234887f},{-0.731777f,-0.628509f,0.263588f},{-0.72553f,-0.623144f,0.292057f}, -{-0.718646f,-0.617231f,0.320271f},{-0.711131f,-0.610777f,0.348202f},{-0.702991f,-0.603786f,0.375828f}, -{-0.694233f,-0.596264f,0.403124f},{-0.684866f,-0.588219f,0.430066f},{-0.664336f,-0.570586f,0.482793f}, -{-0.653191f,-0.561014f,0.508532f},{-0.641473f,-0.550949f,0.533824f},{-0.629191f,-0.5404f,0.558647f}, -{-0.616356f,-0.529376f,0.58298f},{-0.589074f,-0.505945f,0.630088f},{-0.574651f,-0.493557f,0.652822f}, -{-0.559723f,-0.480736f,0.674983f},{-0.544304f,-0.467493f,0.696551f},{-0.528406f,-0.453838f,0.717508f}, -{-0.512045f,-0.439786f,0.737834f},{-0.495233f,-0.425347f,0.757512f},{-0.477987f,-0.410534f,0.776525f}, -{-0.44225f,-0.37984f,0.812488f},{-0.423791f,-0.363986f,0.829407f},{-0.40496f,-0.347812f,0.845597f}, -{-0.385773f,-0.331333f,0.861045f},{-0.366247f,-0.314563f,0.875736f},{-0.326248f,-0.280208f,0.902799f}, -{-0.30581f,-0.262654f,0.915146f},{-0.285103f,-0.24487f,0.92669f},{-0.264146f,-0.22687f,0.93742f}, -{-0.242957f,-0.208671f,0.947327f},{-0.221554f,-0.190289f,0.956402f},{-0.199957f,-0.171739f,0.964636f}, -{-0.178184f,-0.153039f,0.972023f},{-0.156255f,-0.134204f,0.978557f},{-0.134188f,-0.115252f,0.984231f}, -{-0.112004f,-0.0961983f,0.98904f},{-0.0897214f,-0.07706f,0.992981f},{-0.0673596f,-0.0578539f,0.99605f}, -{-0.044939f,-0.0385973f,0.998244f},{0.222351f,-0.863595f,-0.452509f},{0.234353f,-0.853287f,-0.465812f}, -{0.530701f,-0.830249f,-0.170419f},{-0.220753f,-0.514083f,-0.828846f},{-0.40496f,-0.347812f,-0.845597f}, -{-0.385773f,-0.331333f,-0.861045f},{-0.241961f,-0.532298f,-0.811242f},{-0.199192f,-0.495565f,-0.845422f}, -{-0.366247f,-0.314563f,-0.875736f},{-0.17732f,-0.47678f,-0.860952f},{-0.30581f,-0.262654f,-0.915146f}, -{-0.15518f,-0.457764f,-0.875426f},{-0.326248f,-0.280208f,-0.902799f},{-0.346399f,-0.297516f,-0.889658f}, -{-0.285103f,-0.24487f,-0.92669f},{-0.132814f,-0.438554f,-0.888837f},{-0.423791f,-0.363986f,-0.829407f}, -{-0.110265f,-0.419187f,-0.901179f},{-0.264146f,-0.22687f,-0.93742f},{-0.0875736f,-0.399698f,-0.912454f}, -{0.06778f,-0.638198f,-0.766883f},{0.339739f,-0.762773f,-0.550232f},{0.325893f,-0.774664f,-0.541931f}, -{-0.0647826f,-0.380123f,-0.922665f},{-0.242957f,-0.208671f,-0.947327f},{-0.0419318f,-0.360497f,-0.931817f}, -{-0.221554f,-0.190289f,-0.956402f},{-0.199957f,-0.171739f,-0.964636f},{-0.0190607f,-0.340853f,-0.939923f}, -{-0.178184f,-0.153039f,-0.972023f},{-0.156255f,-0.134204f,-0.978557f},{-0.134188f,-0.115252f,-0.984231f}, -{0.0265912f,-0.301644f,-0.95305f},{0.0037925f,-0.321225f,-0.946995f},{-0.112004f,-0.0961983f,-0.98904f}, -{0.0492999f,-0.28214f,-0.958106f},{-0.0897213f,-0.07706f,-0.992981f},{0.0718852f,-0.262742f,-0.962185f}, -{0.155937f,-0.181559f,0.970938f},{0.0224803f,0.0193079f,0.999561f},{0.0943152f,-0.243477f,-0.96531f}, -{0.182173f,-0.168017f,0.968805f},{0.286341f,-0.45048f,-0.845622f},{0.266692f,-0.467356f,-0.842884f}, -{0.226448f,-0.12999f,0.96531f},{0.402091f,-0.351065f,0.845622f},{0.204204f,-0.149095f,0.967508f}, -{0.615617f,-0.757316f,-0.217916f},{0.452476f,-0.665945f,-0.593113f},{0.466457f,-0.653936f,-0.595638f}, -{0.534731f,-0.595298f,0.599736f},{0.640595f,-0.735863f,0.219416f},{0.609092f,-0.70917f,0.355084f}, -{0.431242f,-0.502097f,0.749619f},{0.363305f,-0.384377f,0.848684f},{-0.0673597f,-0.0578539f,-0.99605f}, -{0.480343f,-0.642011f,-0.597573f},{0.646762f,-0.753028f,0.121027f},{0.630724f,-0.744341f,-0.219416f}, -{0.138591f,-0.205449f,-0.968805f},{0.304133f,-0.354104f,-0.884372f},{0.325126f,-0.417168f,-0.848684f}, -{-0.044939f,-0.0385972f,-0.998244f},{0.11656f,-0.224371f,-0.967508f},{0.507751f,-0.61847f,-0.599736f}, -{0.609586f,-0.709744f,-0.353084f},{0.536319f,-0.624439f,-0.567836f},{0.646863f,-0.753146f,-0.119748f}, -{0.155494f,-0.181042f,-0.971105f},{-0.0224791f,-0.0193069f,-0.999561f},{0.620697f,-0.752953f,-0.218624f}, -{-0.262774f,-0.550174f,-0.792627f},{-0.44225f,-0.37984f,-0.812488f},{-0.283151f,-0.567676f,-0.773026f}, -{-0.303053f,-0.584769f,-0.752465f},{-0.46032f,-0.39536f,-0.794856f},{-0.477987f,-0.410534f,-0.776525f}, -{-0.495233f,-0.425347f,-0.757512f},{-0.512045f,-0.439786f,-0.737834f},{-0.322441f,-0.601421f,-0.730976f}, -{-0.341277f,-0.617599f,-0.708591f},{-0.528407f,-0.453838f,-0.717508f},{-0.359528f,-0.633274f,-0.68535f}, -{-0.544304f,-0.467493f,-0.696551f},{-0.377159f,-0.648417f,-0.661292f},{-0.155832f,-0.830254f,-0.535159f}, -{0.177966f,-0.901716f,-0.394f},{0.167874f,-0.910384f,-0.378179f},{-0.39414f,-0.663002f,-0.636461f}, -{-0.559724f,-0.480736f,-0.674983f},{-0.410442f,-0.677003f,-0.610904f},{-0.574651f,-0.493557f,-0.652822f}, -{-0.60298f,-0.517888f,-0.606801f},{-0.589074f,-0.505945f,-0.630089f},{-0.426039f,-0.6904f,-0.58467f}, -{-0.616356f,-0.529376f,-0.58298f},{-0.440909f,-0.703171f,-0.557808f},{-0.629191f,-0.5404f,-0.558647f}, -{-0.641473f,-0.550949f,-0.533824f},{-0.45503f,-0.715299f,-0.530373f},{-0.468385f,-0.726769f,-0.502416f}, -{-0.653191f,-0.561014f,-0.508532f},{-0.480959f,-0.737569f,-0.473994f},{0.11013f,-0.959979f,-0.25751f}, -{0.485253f,-0.869283f,-0.0942108f},{0.103832f,-0.965388f,-0.239258f},{-0.664336f,-0.570586f,-0.482793f}, -{-0.492741f,-0.747688f,-0.445162f},{-0.503721f,-0.757119f,-0.415977f},{-0.674898f,-0.579657f,-0.45663f}, -{-0.684866f,-0.588219f,-0.430066f},{-0.694233f,-0.596264f,-0.403124f},{-0.702991f,-0.603786f,-0.375828f}, -{-0.513894f,-0.765856f,-0.386494f},{-0.523257f,-0.773898f,-0.356769f},{-0.711131f,-0.610777f,-0.348202f}, -{-0.53181f,-0.781244f,-0.326857f},{-0.718646f,-0.617231f,-0.32027f},{-0.72553f,-0.623144f,-0.292057f}, -{-0.539556f,-0.787897f,-0.296814f},{-0.546499f,-0.79386f,-0.266692f},{-0.731777f,-0.628509f,-0.263588f}, -{-0.552648f,-0.799142f,-0.236543f},{-0.285106f,-0.941285f,-0.180824f},{-0.558013f,-0.803749f,-0.206418f}, -{-0.280406f,-0.937248f,-0.207214f},{-0.737381f,-0.633323f,-0.234887f},{-0.562606f,-0.807694f,-0.176364f}, -{-0.742337f,-0.63758f,-0.205979f},{0.0662782f,-0.997643f,-0.0177823f},{0.469433f,-0.882871f,-0.0130831f}, -{0.46921f,-0.883063f,-0.00650573f},{-0.746642f,-0.641277f,-0.176891f},{0.974563f,-0.217534f,0.0539127f}, -{0.801509f,-0.597657f,0.0197241f},{0.973095f,-0.218795f,0.0722163f},{-0.292489f,-0.947626f,-0.128274f}, -{-0.2952f,-0.949955f,-0.102193f},{-0.569536f,-0.813646f,-0.116657f},{0.985709f,0.150194f,0.0762915f}, -{0.983632f,0.14841f,0.102193f},{0.988031f,0.152188f,0.0251637f},{0.997238f,-0.0742779f,1.11285e-016f}, -{0.976204f,-0.216125f,0.0177823f},{0.470347f,-0.882086f,-0.0264206f},{0.0679194f,-0.996233f,-0.0539127f}, -{0.069387f,-0.994972f,-0.0722163f},{0.895322f,0.444493f,0.0287253f},{0.983078f,0.183188f,4.07949e-016f}, -{0.471048f,-0.881484f,-0.0331634f},{0.0713026f,-0.993327f,-0.0906466f},{0.471917f,-0.880738f,-0.0399431f}, -{0.901253f,0.433294f,3.52919e-035f},{-0.75029f,-0.64441f,-0.147647f},{-0.566442f,-0.810988f,-0.146429f}, -{-0.573574f,-0.817114f,-0.0577667f},{-0.571907f,-0.815682f,-0.0870897f},{-0.297277f,-0.951738f,-0.0762915f}, -{-0.75328f,-0.646978f,-0.118274f},{-0.755608f,-0.648977f,-0.0887967f},{-0.757272f,-0.650407f,-0.0592414f}, -{-0.758271f,-0.651265f,-0.0296338f},{-0.574558f,-0.81796f,-0.0287253f},{0.432488f,-0.503548f,-0.747926f}, -{0.305827f,-0.433744f,-0.847547f},{0.246907f,-0.484349f,-0.839311f},{0.227014f,-0.501435f,-0.834882f}, -{0.207042f,-0.518588f,-0.829578f},{0.187022f,-0.535783f,-0.823383f},{0.166987f,-0.552991f,-0.816282f}, -{0.146969f,-0.570184f,-0.808264f},{0.127004f,-0.587331f,-0.79932f},{0.107127f,-0.604404f,-0.789443f}, -{0.087373f,-0.62137f,-0.778631f},{0.0483849f,-0.654856f,-0.754203f},{0.0292249f,-0.671312f,-0.740598f}, -{0.0103372f,-0.687534f,-0.726078f},{-0.00824112f,-0.703491f,-0.710657f},{-0.0264736f,-0.71915f,-0.69435f}, -{-0.0443241f,-0.734482f,-0.677179f},{-0.0617582f,-0.749456f,-0.659168f},{-0.0787419f,-0.764043f,-0.640343f}, -{-0.0952429f,-0.778215f,-0.620734f},{-0.111231f,-0.791946f,-0.600374f},{-0.126676f,-0.805212f,-0.579299f}, -{-0.141551f,-0.817988f,-0.557547f},{-0.169496f,-0.841989f,-0.512177f},{-0.182522f,-0.853177f,-0.488646f}, -{-0.194892f,-0.863801f,-0.464612f},{-0.206591f,-0.87385f,-0.440122f},{-0.217606f,-0.88331f,-0.415224f}, -{-0.227926f,-0.892174f,-0.389967f},{-0.237545f,-0.900436f,-0.3644f},{-0.246457f,-0.90809f,-0.338573f}, -{-0.254659f,-0.915135f,-0.312533f},{-0.262152f,-0.92157f,-0.286331f},{-0.268937f,-0.927398f,-0.260012f}, -{-0.27502f,-0.932622f,-0.233625f},{-0.28913f,-0.944741f,-0.154497f},{0.073677f,-0.991288f,-0.109178f}, -{-0.2996f,-0.953733f,-0.0251637f},{-0.298737f,-0.952993f,-0.0506043f},{-0.339059f,-0.940765f,-2.28355e-016f}, -{-0.564043f,-0.825745f,-3.01839e-016f},{0.536047f,-0.624123f,0.56844f},{0.494113f,-0.630183f,-0.598933f}, -{0.438418f,-0.678019f,-0.589983f},{0.424305f,-0.69014f,-0.586235f},{0.410158f,-0.702291f,-0.581857f}, -{0.395999f,-0.714451f,-0.576839f},{0.381854f,-0.726601f,-0.571173f},{0.367745f,-0.738719f,-0.564853f}, -{0.353698f,-0.750783f,-0.557873f},{0.298647f,-0.798065f,-0.523356f},{0.312187f,-0.786436f,-0.53297f}, -{0.559177f,-0.805792f,-0.194989f},{0.2853f,-0.809529f,-0.513095f},{0.272171f,-0.820805f,-0.502197f}, -{0.259287f,-0.831871f,-0.490674f},{0.246673f,-0.842705f,-0.47854f},{0.21069f,-0.87361f,-0.438652f}, -{0.199392f,-0.883313f,-0.424264f},{0.188478f,-0.892688f,-0.409371f},{0.499479f,-0.857065f,-0.126333f}, -{0.771841f,-0.623139f,0.126333f},{0.496281f,-0.859812f,-0.120119f},{0.158218f,-0.918677f,-0.361938f}, -{0.149013f,-0.926583f,-0.34531f},{0.140272f,-0.934091f,-0.328326f},{0.132004f,-0.941192f,-0.31102f}, -{0.124221f,-0.947877f,-0.293425f},{0.116927f,-0.954141f,-0.275577f},{0.0980359f,-0.970367f,-0.220857f}, -{0.0927412f,-0.974914f,-0.20234f},{0.0879463f,-0.979032f,-0.183742f},{0.0836479f,-0.982724f,-0.165095f}, -{0.0798414f,-0.985994f,-0.146431f},{0.0765202f,-0.988846f,-0.127782f},{0.0668873f,-0.997119f,-0.0357604f}, -{0.46981f,-0.882547f,-0.0197241f},{-0.0755429f,-0.997143f,-2.89047e-016f},{0.0449408f,0.0385988f,0.998244f}, -{0.625735f,-0.748626f,-0.219122f},{0.610502f,-0.76171f,-0.216993f},{0.605359f,-0.766127f,-0.215847f}, -{0.6763f,-0.705197f,0.212874f},{0.58984f,-0.779456f,-0.211039f},{0.595019f,-0.775007f,-0.212875f}, -{0.600195f,-0.770562f,-0.214476f},{0.584664f,-0.783901f,-0.208966f},{0.579503f,-0.788334f,-0.206653f}, -{0.574364f,-0.792748f,-0.2041f},{0.569256f,-0.797135f,-0.201305f},{0.564191f,-0.801485f,-0.198267f}, -{0.721979f,-0.665964f,0.187718f},{0.544537f,-0.818366f,-0.183731f},{0.54934f,-0.814241f,-0.187718f}, -{0.554223f,-0.810046f,-0.191472f},{0.539823f,-0.822414f,-0.179515f},{0.535208f,-0.826378f,-0.175076f}, -{0.749276f,-0.642519f,0.160482f},{0.51791f,-0.841235f,-0.155219f},{0.522044f,-0.837685f,-0.160482f}, -{0.52631f,-0.834021f,-0.165552f},{0.513917f,-0.844665f,-0.14977f},{0.510071f,-0.847968f,-0.144146f}, -{0.506379f,-0.851139f,-0.138358f},{0.502846f,-0.854173f,-0.132417f},{0.493256f,-0.86241f,-0.113788f}, -{0.490408f,-0.864856f,-0.107351f},{0.48774f,-0.867148f,-0.100821f},{0.790491f,-0.60712f,0.0808013f}, -{0.478892f,-0.874747f,-0.0740269f},{0.480829f,-0.873084f,-0.0808013f},{0.482949f,-0.871262f,-0.0875334f}, -{0.477137f,-0.876254f,-0.0672227f},{0.475565f,-0.877605f,-0.0604006f},{0.474172f,-0.878801f,-0.0535724f}, -{0.472957f,-0.879844f,-0.0467496f},{0.800972f,-0.598118f,0.0264206f},{0.184979f,-0.982742f,-2.6491e-016f}, -{0.650623f,-0.727251f,0.218624f},{0.645585f,-0.731578f,0.219122f},{0.655703f,-0.722888f,0.217917f}, -{0.660818f,-0.718494f,0.216992f},{0.665961f,-0.714077f,0.215848f},{0.671124f,-0.709642f,0.214476f}, -{0.68148f,-0.700748f,0.211039f},{0.696956f,-0.687456f,0.2041f},{0.691817f,-0.69187f,0.206653f}, -{0.674737f,-0.475049f,0.564852f},{0.686655f,-0.696303f,0.208966f},{0.702063f,-0.68307f,0.201305f}, -{0.707128f,-0.678719f,0.198267f},{0.712143f,-0.674412f,0.194989f},{0.717096f,-0.670158f,0.191472f}, -{0.732756f,-0.0670628f,0.677179f},{0.795809f,-0.371062f,0.47854f},{0.714905f,-0.0823942f,0.69435f}, -{0.726783f,-0.661838f,0.183731f},{0.731497f,-0.65779f,0.179515f},{0.736111f,-0.653826f,0.175076f}, -{0.740619f,-0.649955f,0.170419f},{0.74501f,-0.646183f,0.165552f},{0.829983f,0.0164437f,0.557547f}, -{0.864516f,-0.312051f,0.394f},{0.815107f,0.00366745f,0.579299f},{0.753409f,-0.638969f,0.155219f}, -{0.757402f,-0.63554f,0.14977f},{0.761248f,-0.632236f,0.144146f},{0.76494f,-0.629065f,0.138358f}, -{0.768473f,-0.626031f,0.132417f},{0.780911f,-0.615349f,0.107351f},{0.778063f,-0.617794f,0.113788f}, -{0.910477f,-0.272576f,0.311019f},{0.775039f,-0.620392f,0.120119f},{0.783579f,-0.613057f,0.100821f}, -{0.786066f,-0.610921f,0.0942108f},{0.78837f,-0.608942f,0.0875334f},{0.792428f,-0.605457f,0.0740269f}, -{0.797147f,-0.601403f,0.0535724f},{0.795755f,-0.602599f,0.0604006f},{0.958834f,-0.231043f,0.165095f}, -{0.794182f,-0.60395f,0.0672227f},{0.798362f,-0.60036f,0.0467497f},{0.799403f,-0.599467f,0.0399431f}, -{0.800271f,-0.59872f,0.0331634f},{0.801887f,-0.597333f,0.0130831f},{0.802109f,-0.597142f,0.00650573f}, -{0.651551f,-0.758605f,-2.05938e-033f},{0.433008f,-0.90139f,-1.54031e-016f},{0.562139f,-0.571757f,0.597573f}, -{0.548369f,-0.583584f,0.598933f},{0.576025f,-0.559831f,0.595638f},{0.590006f,-0.547823f,0.593113f}, -{0.604064f,-0.535749f,0.589983f},{0.618177f,-0.523627f,0.586235f},{0.632325f,-0.511476f,0.581857f}, -{0.646483f,-0.499316f,0.576839f},{0.660628f,-0.487166f,0.571173f},{0.581305f,-0.197141f,0.789443f}, -{0.601058f,-0.180175f,0.778631f},{0.702743f,-0.450995f,0.550232f},{0.688784f,-0.462984f,0.557873f}, -{0.716589f,-0.439103f,0.541931f},{0.730295f,-0.427331f,0.53297f},{0.743835f,-0.415702f,0.523356f}, -{0.757182f,-0.404239f,0.513095f},{0.770311f,-0.392963f,0.502197f},{0.783195f,-0.381897f,0.490674f}, -{0.808129f,-0.360481f,0.465812f},{0.820131f,-0.350173f,0.452509f},{0.831792f,-0.340157f,0.438652f}, -{0.84309f,-0.330454f,0.424264f},{0.854004f,-0.32108f,0.409371f},{0.874608f,-0.303383f,0.378179f}, -{0.884264f,-0.29509f,0.361938f},{0.893469f,-0.287184f,0.34531f},{0.90221f,-0.279676f,0.328326f}, -{0.906037f,0.0817656f,0.415224f},{0.916358f,0.09063f,0.389967f},{0.925555f,-0.259626f,0.275577f}, -{0.918261f,-0.26589f,0.293425f},{0.932352f,-0.253788f,0.257509f},{0.93865f,-0.248379f,0.239258f}, -{0.944446f,-0.243401f,0.220857f},{0.949741f,-0.238853f,0.20234f},{0.954536f,-0.234735f,0.183742f}, -{0.962641f,-0.227774f,0.146431f},{0.973538f,0.13974f,0.180824f},{0.977561f,0.143196f,0.154497f}, -{0.968805f,-0.222479f,0.109178f},{0.965962f,-0.224922f,0.127782f},{0.971179f,-0.22044f,0.0906467f}, -{0.975595f,-0.216648f,0.0357604f},{0.943289f,-0.331972f,1.5621e-016f},{0.825457f,-0.564465f,6.56678e-035f}, -{0.29793f,-0.346881f,0.889332f},{0.382604f,-0.367801f,0.847547f},{0.42174f,-0.334188f,0.842884f}, -{0.441525f,-0.317195f,0.839311f},{0.248878f,-0.110725f,0.962185f},{0.461418f,-0.30011f,0.834882f}, -{0.48139f,-0.282956f,0.829578f},{0.501409f,-0.265762f,0.823383f},{0.521445f,-0.248554f,0.816282f}, -{0.541462f,-0.231361f,0.808264f},{0.561427f,-0.214213f,0.79932f},{0.346402f,0.297518f,0.889657f}, -{0.498084f,0.103313f,0.860952f},{0.475944f,0.0842968f,0.875426f},{0.620651f,-0.163347f,0.766883f}, -{0.640047f,-0.146689f,0.754203f},{0.659207f,-0.130232f,0.740598f},{0.678094f,-0.11401f,0.726078f}, -{0.696673f,-0.0980537f,0.710657f},{0.623817f,0.211302f,0.752465f},{0.75019f,-0.0520888f,0.659168f}, -{0.603915f,0.194209f,0.773026f},{0.767173f,-0.0375018f,0.640343f},{0.783674f,-0.0233294f,0.620734f}, -{0.799662f,-0.00959819f,0.600374f},{0.731206f,0.303536f,0.610904f},{0.602981f,0.517889f,0.606799f}, -{0.746803f,0.316933f,0.58467f},{0.844264f,0.0287092f,0.535159f},{0.857927f,0.0404448f,0.512177f}, -{0.870953f,0.0516324f,0.488646f},{0.883323f,0.0622568f,0.464612f},{0.895022f,0.072305f,0.440122f}, -{0.824484f,0.383652f,0.415977f},{0.925977f,0.0988912f,0.3644f},{0.813504f,0.374221f,0.445163f}, -{0.934889f,0.106546f,0.338573f},{0.943091f,0.11359f,0.312533f},{0.950583f,0.120025f,0.286331f}, -{0.957369f,0.125853f,0.260012f},{0.963451f,0.131077f,0.233625f},{0.968838f,0.135704f,0.207214f}, -{0.980921f,0.146082f,0.128274f},{0.894338f,0.443647f,0.0577667f},{0.892671f,0.442216f,0.0870897f}, -{0.987169f,0.151448f,0.0506043f},{0.271464f,-0.0913273f,0.958106f},{0.294173f,-0.0718233f,0.95305f}, -{0.316971f,-0.0522418f,0.946995f},{0.339824f,-0.0326136f,0.939923f},{0.362696f,-0.0129702f,0.931817f}, -{0.385546f,0.00665603f,0.922665f},{0.408337f,0.0262309f,0.912454f},{0.431028f,0.0457197f,0.901179f}, -{0.453578f,0.0650871f,0.888837f},{0.519956f,0.122098f,0.845422f},{0.541517f,0.140616f,0.828846f}, -{0.562725f,0.158831f,0.811242f},{0.583538f,0.176707f,0.792627f},{0.460322f,0.395362f,0.794854f}, -{0.643204f,0.227954f,0.730976f},{0.662041f,0.244132f,0.708591f},{0.680291f,0.259807f,0.68535f}, -{0.697922f,0.27495f,0.661292f},{0.714903f,0.289534f,0.636461f},{0.761673f,0.329704f,0.557808f}, -{0.775794f,0.341832f,0.530373f},{0.789149f,0.353302f,0.502416f},{0.801723f,0.364102f,0.473994f}, -{0.674899f,0.579658f,0.456627f},{0.834658f,0.392389f,0.386494f},{0.844021f,0.400431f,0.356769f}, -{0.852574f,0.407777f,0.326857f},{0.860319f,0.41443f,0.296814f},{0.867263f,0.420393f,0.266692f}, -{0.873412f,0.425675f,0.236543f},{0.878777f,0.430282f,0.206418f},{0.88337f,0.434227f,0.176364f}, -{0.887205f,0.437521f,0.146429f},{0.8903f,0.440179f,0.116657f},{0.0673616f,0.0578556f,0.99605f}, -{0.0897231f,0.0770615f,0.992981f},{0.112006f,0.0961995f,0.98904f},{0.13419f,0.115254f,0.98423f}, -{0.156257f,0.134206f,0.978556f},{0.178186f,0.153041f,0.972023f},{0.199959f,0.171741f,0.964635f}, -{0.221556f,0.19029f,0.956401f},{0.242959f,0.208673f,0.947326f},{0.264148f,0.226872f,0.937419f}, -{0.285105f,0.244871f,0.926689f},{0.305812f,0.262656f,0.915145f},{0.32625f,0.28021f,0.902798f}, -{0.366249f,0.314564f,0.875734f},{0.385775f,0.331335f,0.861043f},{0.404961f,0.347814f,0.845596f}, -{0.423793f,0.363987f,0.829405f},{0.442252f,0.379842f,0.812486f},{0.477988f,0.410535f,0.776523f}, -{0.495234f,0.425347f,0.757511f},{0.512046f,0.439786f,0.737833f},{0.528407f,0.453839f,0.717507f}, -{0.544305f,0.467493f,0.696551f},{0.559724f,0.480737f,0.674982f},{0.574652f,0.493558f,0.652821f}, -{0.589075f,0.505946f,0.630087f},{0.616357f,0.529378f,0.582978f},{0.629192f,0.540401f,0.558645f}, -{0.641474f,0.55095f,0.533822f},{0.653193f,0.561015f,0.508529f},{0.664337f,0.570587f,0.48279f}, -{0.684867f,0.58822f,0.430063f},{0.694234f,0.596265f,0.403122f},{0.702992f,0.603786f,0.375826f}, -{0.711132f,0.610777f,0.3482f},{0.718647f,0.617232f,0.320268f},{0.725531f,0.623145f,0.292055f}, -{0.731777f,0.62851f,0.263585f},{0.737381f,0.633323f,0.234884f},{0.742338f,0.63758f,0.205977f}, -{0.746642f,0.641277f,0.176888f},{0.750291f,0.64441f,0.147645f},{0.75328f,0.646978f,0.118272f}, -{0.755608f,0.648978f,0.0887941f},{0.757272f,0.650407f,0.0592391f},{0.758272f,0.651265f,0.0296323f}, -{6.73779e-016f,5.78696e-016f,1.0f},{-9.28992e-017f,-7.97894e-017f,1.0f},{0.00379251f,-0.321225f,0.946995f}, -{-0.110265f,-0.419187f,0.901179f},{0.286341f,-0.45048f,0.845622f},{0.480343f,-0.642011f,0.597573f}, -{0.466457f,-0.653936f,0.595638f},{0.0492999f,-0.28214f,0.958106f},{-0.134188f,-0.115252f,0.984231f}, -{0.610502f,-0.76171f,0.216993f},{0.615617f,-0.757316f,0.217916f},{0.0943152f,-0.243477f,0.96531f}, -{0.266692f,-0.467356f,0.842884f},{0.640595f,-0.735863f,-0.219416f},{0.630724f,-0.744341f,0.219416f}, -{0.620697f,-0.752953f,0.218624f},{0.431242f,-0.502097f,-0.749619f},{0.363305f,-0.384377f,-0.848684f}, -{0.534731f,-0.595298f,-0.599736f},{0.609092f,-0.70917f,-0.355084f},{0.0449409f,0.0385987f,-0.998244f}, -{0.204204f,-0.149095f,-0.967508f},{0.182173f,-0.168018f,-0.968805f},{0.0224804f,0.0193078f,-0.999561f}, -{0.155937f,-0.181559f,-0.970938f},{4.72151e-016f,4.05521e-016f,-1.0f},{-0.199957f,-0.171739f,0.964636f}, -{-0.0190607f,-0.340853f,0.939923f},{-0.0419318f,-0.360497f,0.931817f},{-0.178184f,-0.153039f,0.972023f}, -{-0.0647826f,-0.380123f,0.922665f},{-0.221554f,-0.190289f,0.956402f},{0.127004f,-0.587331f,0.79932f}, -{-0.0875737f,-0.399698f,0.912454f},{-0.242957f,-0.208671f,0.947327f},{-0.132814f,-0.438554f,0.888837f}, -{-0.30581f,-0.262654f,0.915146f},{-0.17732f,-0.47678f,0.860952f},{-0.199192f,-0.495565f,0.845422f}, -{-0.366247f,-0.314563f,0.875736f},{-0.15518f,-0.457764f,0.875426f},{-0.241961f,-0.532298f,0.811242f}, -{-0.385773f,-0.331333f,0.861045f},{-0.46032f,-0.39536f,0.794856f},{-0.262774f,-0.550174f,0.792627f}, -{-0.341277f,-0.617599f,0.708591f},{-0.528407f,-0.453838f,0.717508f},{-0.322441f,-0.601421f,0.730976f}, -{-0.559724f,-0.480736f,0.674983f},{-0.39414f,-0.663002f,0.636461f},{-0.544304f,-0.467493f,0.696551f}, -{-0.377159f,-0.648417f,0.661292f},{-0.440909f,-0.703171f,0.557808f},{-0.468385f,-0.726769f,0.502416f}, -{-0.684866f,-0.588219f,0.430066f},{-0.674898f,-0.579657f,0.45663f},{-0.480959f,-0.737569f,0.473994f}, -{-0.513894f,-0.765856f,0.386494f},{-0.702991f,-0.603786f,0.375828f},{-0.539556f,-0.787897f,0.296814f}, -{-0.718646f,-0.617231f,0.32027f},{-0.731777f,-0.628509f,0.263588f},{-0.552648f,-0.799142f,0.236543f}, -{-0.737381f,-0.633323f,0.234887f},{-0.546499f,-0.79386f,0.266692f},{-0.72553f,-0.623144f,0.292057f}, -{-0.742337f,-0.63758f,0.205979f},{-0.562606f,-0.807694f,0.176364f},{-0.558013f,-0.803749f,0.206418f}, -{-0.574558f,-0.81796f,0.0287253f},{-0.758605f,-0.651551f,3.14853e-016f},{-0.758272f,-0.651265f,0.0296338f}, -{-0.566442f,-0.810988f,0.146429f},{-0.297277f,-0.951738f,0.0762915f},{-0.298738f,-0.952993f,0.0506043f}, -{-0.757272f,-0.650407f,0.0592414f},{-0.755608f,-0.648977f,0.0887967f},{-0.573574f,-0.817114f,0.0577667f}, -{-0.569536f,-0.813646f,0.116657f},{0.0668874f,-0.997119f,0.0357603f},{0.46921f,-0.883063f,0.00650573f}, -{0.0662782f,-0.997643f,0.0177823f},{-0.28913f,-0.944741f,0.154497f},{-0.285106f,-0.941285f,0.180824f}, -{-0.2952f,-0.949955f,0.102193f},{0.069387f,-0.994972f,0.0722163f},{0.073677f,-0.991288f,0.109178f}, -{0.801509f,-0.597657f,-0.0197241f},{0.800972f,-0.598118f,-0.0264206f},{0.974563f,-0.217534f,-0.0539127f}, -{0.470347f,-0.882086f,0.0264206f},{0.46981f,-0.882547f,0.0197241f},{0.985709f,0.150194f,-0.0762915f}, -{0.987169f,0.151448f,-0.0506043f},{0.997238f,-0.0742779f,-1.10368e-016f},{0.976204f,-0.216125f,-0.0177823f}, -{0.988031f,0.152188f,-0.0251637f},{0.895322f,0.444493f,-0.0287253f},{0.901253f,0.433294f,-3.00521e-016f}, -{0.983078f,0.183188f,-5.39175e-016f},{0.758605f,0.651551f,-6.22394e-016f},{-0.27502f,-0.932622f,0.233625f}, -{-0.45503f,-0.715299f,0.530373f},{-0.664336f,-0.570586f,0.482793f},{-0.49274f,-0.747688f,0.445162f}, -{-0.206591f,-0.87385f,0.440122f},{-0.589074f,-0.505945f,0.630089f},{-0.126676f,-0.805212f,0.579299f}, -{0.188478f,-0.892688f,0.409371f},{0.177966f,-0.901716f,0.394f},{-0.477987f,-0.410534f,0.776525f}, -{-0.44225f,-0.37984f,0.812488f},{-0.326248f,-0.280208f,0.902799f},{-0.220753f,-0.514083f,0.828846f}, -{0.246673f,-0.842705f,0.47854f},{-0.0264735f,-0.71915f,0.69435f},{0.259287f,-0.831871f,0.490674f}, -{-0.112004f,-0.0961983f,0.98904f},{-0.0897214f,-0.07706f,0.992981f},{-0.0673597f,-0.0578539f,0.99605f}, -{0.507751f,-0.61847f,0.599736f},{0.609586f,-0.709744f,0.353084f},{0.11656f,-0.224371f,0.967508f}, -{-0.044939f,-0.0385972f,0.998244f},{0.138591f,-0.205449f,0.968805f},{-0.0224791f,-0.0193069f,0.999561f}, -{0.155494f,-0.181042f,0.971105f},{-2.38849e-016f,-2.05143e-016f,1.0f},{0.304133f,-0.354104f,0.884372f}, -{0.432488f,-0.503548f,0.747926f},{0.325126f,-0.417168f,0.848684f},{0.536319f,-0.624439f,0.567836f}, -{0.305827f,-0.433744f,0.847547f},{0.246907f,-0.484349f,0.839311f},{0.227014f,-0.501435f,0.834882f}, -{0.207042f,-0.518588f,0.829578f},{0.187022f,-0.535783f,0.823383f},{0.166987f,-0.552991f,0.816282f}, -{0.146969f,-0.570184f,0.808264f},{0.353698f,-0.750783f,0.557873f},{0.339739f,-0.762773f,0.550232f}, -{0.087373f,-0.62137f,0.778631f},{0.06778f,-0.638198f,0.766883f},{0.0483849f,-0.654856f,0.754203f}, -{0.0292249f,-0.671312f,0.740598f},{0.0103371f,-0.687534f,0.726078f},{-0.00824112f,-0.703491f,0.710657f}, -{-0.0443241f,-0.734482f,0.677179f},{-0.0617582f,-0.749456f,0.659168f},{-0.078742f,-0.764043f,0.640343f}, -{-0.0952429f,-0.778215f,0.620734f},{-0.111231f,-0.791946f,0.600374f},{-0.141551f,-0.817988f,0.557547f}, -{-0.169496f,-0.841989f,0.512177f},{-0.182521f,-0.853177f,0.488646f},{-0.194892f,-0.863801f,0.464612f}, -{0.116927f,-0.954141f,0.275577f},{0.48774f,-0.867148f,0.100821f},{-0.217606f,-0.88331f,0.415224f}, -{-0.227926f,-0.892174f,0.389967f},{-0.237545f,-0.900436f,0.3644f},{-0.246457f,-0.90809f,0.338573f}, -{-0.254659f,-0.915135f,0.312533f},{-0.262152f,-0.92157f,0.286331f},{-0.268937f,-0.927398f,0.260012f}, -{-0.280406f,-0.937248f,0.207214f},{0.0765203f,-0.988846f,0.127782f},{-0.292489f,-0.947626f,0.128274f}, -{-0.2996f,-0.953733f,0.0251637f},{-0.339059f,-0.940765f,7.30221e-017f},{-0.564043f,-0.825745f,2.30577e-016f}, -{0.536047f,-0.624123f,-0.56844f},{0.494113f,-0.630183f,0.598933f},{0.452476f,-0.665945f,0.593113f}, -{0.438418f,-0.678019f,0.589983f},{0.424305f,-0.69014f,0.586235f},{0.381854f,-0.726601f,0.571173f}, -{0.367745f,-0.738719f,0.564853f},{0.325893f,-0.774664f,0.541931f},{0.559177f,-0.805792f,0.194989f}, -{0.312187f,-0.786436f,0.53297f},{0.298647f,-0.798065f,0.523356f},{0.2853f,-0.809529f,0.513095f}, -{0.272171f,-0.820805f,0.502197f},{0.52631f,-0.834021f,0.165552f},{0.74501f,-0.646183f,-0.165552f}, -{0.749276f,-0.642519f,-0.160482f},{0.234353f,-0.853287f,0.465812f},{0.222351f,-0.863595f,0.452509f}, -{0.21069f,-0.87361f,0.438652f},{0.199392f,-0.883313f,0.424264f},{0.502847f,-0.854173f,0.132416f}, -{0.768473f,-0.626031f,-0.132417f},{0.771841f,-0.623139f,-0.126333f},{0.167874f,-0.910384f,0.378179f}, -{0.158218f,-0.918677f,0.361938f},{0.149013f,-0.926583f,0.34531f},{0.140272f,-0.934091f,0.328326f}, -{0.132004f,-0.941192f,0.31102f},{0.124221f,-0.947877f,0.293425f},{0.11013f,-0.959979f,0.25751f}, -{0.103832f,-0.965388f,0.239258f},{0.098036f,-0.970367f,0.220857f},{0.0927412f,-0.974914f,0.20234f}, -{0.0879463f,-0.979032f,0.183742f},{0.0798413f,-0.985994f,0.146431f},{0.0713026f,-0.993327f,0.0906466f}, -{0.801887f,-0.597333f,-0.0130831f},{-0.0755429f,-0.997143f,3.49386e-017f},{0.382604f,-0.367801f,-0.847547f}, -{0.605359f,-0.766127f,0.215847f},{0.665961f,-0.714077f,-0.215848f},{0.671124f,-0.709642f,-0.214476f}, -{0.595019f,-0.775007f,0.212875f},{0.584664f,-0.783901f,0.208966f},{0.579503f,-0.788334f,0.206653f}, -{0.574364f,-0.792748f,0.2041f},{0.569256f,-0.797135f,0.201304f},{0.554223f,-0.810046f,0.191472f}, -{0.717096f,-0.670158f,-0.191472f},{0.721979f,-0.665964f,-0.187718f},{0.54934f,-0.814241f,0.187718f}, -{0.544537f,-0.818366f,0.183731f},{0.535208f,-0.826378f,0.175076f},{0.530701f,-0.830249f,0.170419f}, -{0.522044f,-0.837685f,0.160482f},{0.513917f,-0.844665f,0.14977f},{0.510071f,-0.847968f,0.144146f}, -{0.506379f,-0.851139f,0.138358f},{0.499479f,-0.857065f,0.126333f},{0.496281f,-0.859812f,0.120119f}, -{0.493256f,-0.86241f,0.113788f},{0.490408f,-0.864856f,0.107351f},{0.482949f,-0.871262f,0.0875334f}, -{0.78837f,-0.608942f,-0.0875334f},{0.790491f,-0.60712f,-0.0808013f},{0.480829f,-0.873084f,0.0808013f}, -{0.478892f,-0.874747f,0.0740269f},{0.477137f,-0.876254f,0.0672227f},{0.474172f,-0.878801f,0.0535724f}, -{0.472957f,-0.879844f,0.0467496f},{0.471917f,-0.880738f,0.0399431f},{0.471048f,-0.881484f,0.0331634f}, -{0.469433f,-0.882871f,0.0130831f},{0.18498f,-0.982742f,5.93908e-017f},{0.650623f,-0.727251f,-0.218624f}, -{0.655703f,-0.722888f,-0.217917f},{0.645585f,-0.731578f,-0.219122f},{0.660818f,-0.718494f,-0.216992f}, -{0.6763f,-0.705197f,-0.212875f},{0.68148f,-0.700748f,-0.211039f},{0.686655f,-0.696303f,-0.208966f}, -{0.660628f,-0.487166f,-0.571173f},{0.674737f,-0.475049f,-0.564852f},{0.691817f,-0.69187f,-0.206653f}, -{0.696956f,-0.687456f,-0.2041f},{0.702063f,-0.68307f,-0.201305f},{0.707128f,-0.678719f,-0.198267f}, -{0.712143f,-0.674412f,-0.194989f},{0.726783f,-0.661838f,-0.183731f},{0.770311f,-0.392963f,-0.502197f}, -{0.783195f,-0.381897f,-0.490674f},{0.731497f,-0.65779f,-0.179515f},{0.736111f,-0.653826f,-0.175076f}, -{0.740619f,-0.649955f,-0.170419f},{0.753409f,-0.638969f,-0.155219f},{0.854004f,-0.32108f,-0.409371f}, -{0.757402f,-0.63554f,-0.14977f},{0.761248f,-0.632236f,-0.144146f},{0.76494f,-0.629065f,-0.138358f}, -{0.775039f,-0.620392f,-0.120119f},{0.90221f,-0.279676f,-0.328326f},{0.910477f,-0.272576f,-0.311019f}, -{0.778063f,-0.617794f,-0.113788f},{0.780911f,-0.615349f,-0.107351f},{0.783579f,-0.613057f,-0.100821f}, -{0.786066f,-0.610921f,-0.0942108f},{0.792428f,-0.605457f,-0.0740269f},{0.794182f,-0.60395f,-0.0672227f}, -{0.954536f,-0.234735f,-0.183742f},{0.795755f,-0.602599f,-0.0604006f},{0.797147f,-0.601403f,-0.0535724f}, -{0.798362f,-0.60036f,-0.0467497f},{0.799403f,-0.599467f,-0.0399431f},{0.800271f,-0.59872f,-0.0331634f}, -{0.802109f,-0.597142f,-0.00650573f},{0.651551f,-0.758605f,-1.07812e-032f},{0.433008f,-0.90139f,5.07106e-017f}, -{0.562139f,-0.571757f,-0.597573f},{0.576025f,-0.559831f,-0.595638f},{0.548369f,-0.583584f,-0.598933f}, -{0.590006f,-0.547823f,-0.593113f},{0.604064f,-0.535749f,-0.589983f},{0.632324f,-0.511476f,-0.581857f}, -{0.601059f,-0.180175f,-0.778631f},{0.702743f,-0.450995f,-0.550232f},{0.730295f,-0.427331f,-0.53297f}, -{0.743835f,-0.415702f,-0.523356f},{0.757182f,-0.404239f,-0.513095f},{0.732756f,-0.0670628f,-0.677179f}, -{0.795809f,-0.371062f,-0.47854f},{0.808129f,-0.360481f,-0.465812f},{0.820131f,-0.350173f,-0.452509f}, -{0.831792f,-0.340158f,-0.438652f},{0.829983f,0.0164437f,-0.557547f},{0.864516f,-0.312051f,-0.394f}, -{0.874608f,-0.303383f,-0.378179f},{0.884264f,-0.29509f,-0.361938f},{0.893469f,-0.287184f,-0.34531f}, -{0.906037f,0.0817656f,-0.415224f},{0.918261f,-0.26589f,-0.293425f},{0.925555f,-0.259626f,-0.275577f}, -{0.93865f,-0.248379f,-0.239258f},{0.949741f,-0.238853f,-0.20234f},{0.962641f,-0.227774f,-0.146431f}, -{0.973538f,0.13974f,-0.180824f},{0.965962f,-0.224921f,-0.127782f},{0.968805f,-0.222479f,-0.109178f}, -{0.971179f,-0.22044f,-0.0906466f},{0.973095f,-0.218795f,-0.0722163f},{0.975595f,-0.216648f,-0.0357604f}, -{0.943289f,-0.331972f,-1.55829e-016f},{0.825457f,-0.564465f,-4.03832e-017f},{0.402091f,-0.351065f,-0.845622f}, -{0.42174f,-0.334188f,-0.842884f},{0.441525f,-0.317195f,-0.839311f},{0.461418f,-0.30011f,-0.834882f}, -{0.48139f,-0.282956f,-0.829578f},{0.501409f,-0.265762f,-0.823383f},{0.521445f,-0.248554f,-0.816282f}, -{0.541462f,-0.231361f,-0.808264f},{0.561427f,-0.214213f,-0.79932f},{0.581305f,-0.197141f,-0.789443f}, -{0.475944f,0.0842967f,-0.875426f},{0.346402f,0.297518f,-0.889657f},{0.620651f,-0.163347f,-0.766883f}, -{0.640047f,-0.146689f,-0.754203f},{0.659207f,-0.130232f,-0.740598f},{0.678094f,-0.11401f,-0.726078f}, -{0.714905f,-0.0823942f,-0.69435f},{0.75019f,-0.0520888f,-0.659168f},{0.623817f,0.211302f,-0.752465f}, -{0.767173f,-0.0375018f,-0.640343f},{0.783674f,-0.0233296f,-0.620733f},{0.815107f,0.00366745f,-0.579299f}, -{0.731206f,0.303536f,-0.610904f},{0.746803f,0.316933f,-0.58467f},{0.844264f,0.0287092f,-0.535159f}, -{0.857927f,0.0404448f,-0.512177f},{0.870953f,0.0516324f,-0.488646f},{0.883323f,0.0622568f,-0.464612f}, -{0.895022f,0.072305f,-0.440122f},{0.916358f,0.0906297f,-0.389967f},{0.824484f,0.383652f,-0.415977f}, -{0.934889f,0.106546f,-0.338573f},{0.943091f,0.11359f,-0.312533f},{0.950583f,0.120025f,-0.286331f}, -{0.957369f,0.125853f,-0.260012f},{0.968838f,0.135704f,-0.207214f},{0.977561f,0.143196f,-0.154497f}, -{0.980921f,0.146082f,-0.128274f},{0.983632f,0.14841f,-0.102193f},{0.226448f,-0.12999f,-0.96531f}, -{0.248879f,-0.110725f,-0.962185f},{0.271464f,-0.0913273f,-0.958106f},{0.294173f,-0.0718231f,-0.95305f}, -{0.316971f,-0.0522418f,-0.946995f},{0.339824f,-0.0326136f,-0.939923f},{0.362695f,-0.0129701f,-0.931817f}, -{0.385546f,0.00665603f,-0.922665f},{0.408337f,0.0262307f,-0.912454f},{0.431028f,0.0457197f,-0.901179f}, -{0.453578f,0.065087f,-0.888837f},{0.519956f,0.122098f,-0.845422f},{0.541517f,0.140616f,-0.828846f}, -{0.562725f,0.158831f,-0.811242f},{0.583538f,0.176707f,-0.792627f},{0.643204f,0.227954f,-0.730976f}, -{0.662041f,0.244132f,-0.708591f},{0.680291f,0.259807f,-0.68535f},{0.697922f,0.27495f,-0.661292f}, -{0.761673f,0.329704f,-0.557808f},{0.775794f,0.341832f,-0.530373f},{0.789149f,0.353302f,-0.502416f}, -{0.801723f,0.364102f,-0.473994f},{0.852574f,0.407777f,-0.326857f},{0.860319f,0.41443f,-0.296814f}, -{0.873412f,0.425675f,-0.236543f},{0.878777f,0.430282f,-0.206418f},{0.887205f,0.437522f,-0.146429f}, -{0.8903f,0.440179f,-0.116657f},{0.892671f,0.442216f,-0.0870897f},{0.894338f,0.443647f,-0.0577667f}, -{0.0673617f,0.0578556f,-0.99605f},{0.13419f,0.115254f,-0.98423f},{0.156257f,0.134206f,-0.978556f}, -{0.178186f,0.153041f,-0.972023f},{0.199959f,0.171741f,-0.964635f},{0.221556f,0.19029f,-0.956401f}, -{0.242959f,0.208673f,-0.947326f},{0.264148f,0.226872f,-0.937419f},{0.285105f,0.244871f,-0.926689f}, -{0.305812f,0.262656f,-0.915145f},{0.32625f,0.28021f,-0.902798f},{0.423793f,0.363987f,-0.829405f}, -{0.477988f,0.410535f,-0.776523f},{0.528407f,0.453839f,-0.717507f},{0.559724f,0.480737f,-0.674982f}, -{0.589075f,0.505946f,-0.630087f},{0.616357f,0.529378f,-0.582978f},{0.653193f,0.561015f,-0.508529f}, -{0.684867f,0.58822f,-0.430063f},{0.694234f,0.596265f,-0.403122f},{0.725531f,0.623145f,-0.292055f}, -{0.731777f,0.62851f,-0.263585f},{0.737381f,0.633323f,-0.234884f},{0.746642f,0.641277f,-0.176888f}, -{0.750291f,0.64441f,-0.147645f},{0.75328f,0.646978f,-0.118272f},{0.755608f,0.648978f,-0.0887941f}, -{0.757272f,0.650407f,-0.0592391f},{0.758272f,0.651265f,-0.0296323f},{0.878777f,0.430282f,0.206418f}, -{0.844021f,0.400431f,0.356769f},{0.8903f,0.440179f,0.116657f},{0.892671f,0.442216f,0.0870897f}, -{0.983632f,0.14841f,0.102193f},{0.750291f,0.64441f,0.147645f},{0.75328f,0.646978f,0.118272f}, -{0.976204f,-0.216125f,0.0177823f},{0.943289f,-0.331972f,3.41808e-016f},{0.80211f,-0.597142f,0.00650572f}, -{0.974563f,-0.217534f,0.0539127f},{0.973095f,-0.218795f,0.0722163f},{0.985709f,0.150194f,0.0762915f}, -{0.46921f,-0.883063f,-0.00650572f},{0.184979f,-0.982742f,-4.69192e-016f},{0.0662783f,-0.997643f,-0.0177823f}, -{0.801509f,-0.597657f,0.0197241f},{0.800972f,-0.598118f,0.0264206f},{-0.574558f,-0.81796f,-0.0287252f}, -{-0.573574f,-0.817114f,-0.0577667f},{-0.2996f,-0.953733f,-0.0251636f},{-0.0755427f,-0.997143f,-5.50975e-016f}, -{-0.758605f,-0.651551f,-9.3359e-016f},{-0.564043f,-0.825745f,-3.00566e-016f},{-0.757272f,-0.650407f,-0.0592414f}, -{0.887205f,0.437522f,0.146429f},{0.746642f,0.641277f,0.176888f},{-0.758271f,-0.651265f,-0.0296337f}, -{0.731777f,0.62851f,0.263585f},{0.873412f,0.425675f,0.236543f},{0.867263f,0.420393f,0.266692f}, -{0.737381f,0.633323f,0.234884f},{0.860319f,0.41443f,0.296814f},{0.725531f,0.623145f,0.292055f}, -{0.852574f,0.407777f,0.326857f},{0.718647f,0.617232f,0.320268f},{0.694234f,0.596265f,0.403122f}, -{0.813504f,0.374221f,0.445162f},{0.801723f,0.364102f,0.473994f},{0.824484f,0.383652f,0.415977f}, -{0.775794f,0.341832f,0.530373f},{0.653193f,0.561015f,0.508529f},{0.602981f,0.517889f,0.606799f}, -{0.731206f,0.303536f,0.610904f},{0.761673f,0.329704f,0.557808f},{0.697922f,0.27495f,0.661292f}, -{0.544305f,0.467493f,0.696551f},{0.714903f,0.289535f,0.636461f},{0.512046f,0.439786f,0.737833f}, -{0.643204f,0.227954f,0.730976f},{0.528407f,0.453839f,0.717507f},{0.662041f,0.244132f,0.708591f}, -{0.583538f,0.176707f,0.792627f},{0.541517f,0.140616f,0.828846f},{0.32625f,0.28021f,0.902798f}, -{0.346402f,0.297518f,0.889657f},{0.475944f,0.0842968f,0.875426f},{0.519956f,0.122098f,0.845422f}, -{0.453578f,0.065087f,0.888837f},{0.285105f,0.244871f,0.926689f},{0.305812f,0.262656f,0.915145f}, -{0.385546f,0.00665599f,0.922665f},{0.242959f,0.208673f,0.947326f},{0.408337f,0.0262308f,0.912454f}, -{0.199959f,0.171741f,0.964635f},{0.362695f,-0.0129701f,0.931817f},{0.339824f,-0.0326136f,0.939923f}, -{0.221556f,0.19029f,0.956401f},{0.156257f,0.134206f,0.978556f},{0.316971f,-0.0522418f,0.946995f}, -{0.294173f,-0.0718231f,0.95305f},{0.178186f,0.153041f,0.972023f},{0.271464f,-0.0913273f,0.958106f}, -{0.650623f,-0.727251f,0.218624f},{0.576025f,-0.559831f,0.595638f},{0.182173f,-0.168017f,0.968805f}, -{0.0449408f,0.0385988f,0.998244f},{0.204204f,-0.149095f,0.967508f},{0.0224803f,0.0193079f,0.999561f}, -{0.226448f,-0.12999f,0.96531f},{0.248878f,-0.110725f,0.962185f},{0.402091f,-0.351064f,0.845622f}, -{0.0673616f,0.0578556f,0.99605f},{0.0897231f,0.0770615f,0.992981f},{0.48139f,-0.282956f,0.829578f}, -{0.604064f,-0.535749f,0.589983f},{0.461418f,-0.30011f,0.834882f},{0.655702f,-0.722888f,0.217917f}, -{0.42174f,-0.334188f,0.842884f},{0.620697f,-0.752953f,-0.218624f},{0.625735f,-0.748626f,-0.219122f}, -{0.645585f,-0.731578f,0.219122f},{0.286341f,-0.45048f,-0.845622f},{0.305827f,-0.433744f,-0.847547f}, -{0.480343f,-0.642011f,-0.597573f},{0.432488f,-0.503548f,-0.747926f},{0.507751f,-0.61847f,-0.599737f}, -{0.325127f,-0.417168f,-0.848684f},{0.138591f,-0.205449f,-0.968805f},{0.304133f,-0.354104f,-0.884372f}, -{0.155494f,-0.181042f,-0.971105f},{-0.0f,0.0f,-1.0f},{-0.0224791f,-0.019307f,-0.999561f}, -{2.50764e-009f,-2.91966e-009f,1.0f},{0.155937f,-0.181559f,0.970938f},{0.521445f,-0.248554f,0.816282f}, -{0.562725f,0.158831f,0.811242f},{0.498084f,0.103313f,0.860952f},{0.678094f,-0.11401f,0.726078f}, -{0.477988f,0.410535f,0.776523f},{0.783674f,-0.0233295f,0.620733f},{0.831792f,-0.340158f,0.438652f}, -{0.820131f,-0.350173f,0.452509f},{0.589075f,0.505946f,0.630087f},{0.616357f,0.529378f,0.582978f}, -{0.684867f,0.58822f,0.430063f},{0.789149f,0.353302f,0.502416f},{0.884264f,-0.29509f,0.361938f}, -{0.870953f,0.0516324f,0.488646f},{0.893469f,-0.287184f,0.34531f},{0.950583f,0.120025f,0.286331f}, -{0.755608f,0.648978f,0.0887942f},{0.757272f,0.650407f,0.059239f},{0.894338f,0.443647f,0.0577667f}, -{0.988031f,0.152189f,0.0251636f},{0.997238f,-0.0742779f,5.00783e-016f},{0.758272f,0.651265f,0.0296322f}, -{0.895322f,0.444493f,0.0287252f},{0.901253f,0.433294f,6.47993e-016f},{0.983078f,0.183188f,6.55067e-016f}, -{0.758605f,0.651551f,9.4456e-016f},{0.825457f,-0.564465f,2.60919e-016f},{0.433008f,-0.90139f,-2.0282e-016f}, -{0.987169f,0.151448f,0.0506042f},{0.980921f,0.146082f,0.128274f},{0.977561f,0.143196f,0.154497f}, -{0.973538f,0.13974f,0.180824f},{0.968838f,0.135704f,0.207214f},{0.963451f,0.131077f,0.233625f}, -{0.957369f,0.125853f,0.260012f},{0.944446f,-0.243401f,0.220857f},{0.93865f,-0.248379f,0.239258f}, -{0.934889f,0.106546f,0.338573f},{0.925977f,0.0988913f,0.3644f},{0.916358f,0.0906299f,0.389967f}, -{0.906037f,0.0817656f,0.415224f},{0.895022f,0.072305f,0.440122f},{0.883323f,0.0622569f,0.464612f}, -{0.857927f,0.0404447f,0.512177f},{0.844263f,0.0287093f,0.535159f},{0.829983f,0.0164437f,0.557547f}, -{0.815107f,0.00366744f,0.579299f},{0.799662f,-0.00959806f,0.600374f},{0.767173f,-0.0375019f,0.640343f}, -{0.732756f,-0.0670627f,0.677179f},{0.714905f,-0.0823943f,0.69435f},{0.696673f,-0.0980537f,0.710657f}, -{0.730295f,-0.427331f,0.53297f},{0.712143f,-0.674412f,0.194989f},{0.659207f,-0.130232f,0.740598f}, -{0.640047f,-0.146689f,0.754203f},{0.620651f,-0.163347f,0.766883f},{0.601058f,-0.180175f,0.778631f}, -{0.581305f,-0.197141f,0.789443f},{0.561427f,-0.214213f,0.79932f},{0.541462f,-0.231361f,0.808264f}, -{0.501409f,-0.265762f,0.823383f},{0.618177f,-0.523627f,0.586235f},{0.441525f,-0.317195f,0.839311f}, -{0.382604f,-0.367801f,0.847547f},{0.363305f,-0.384377f,0.848684f},{0.29793f,-0.346881f,0.889332f}, -{-0.298738f,-0.952993f,-0.0506042f},{0.975595f,-0.216648f,0.0357603f},{0.971179f,-0.22044f,0.0906467f}, -{0.968805f,-0.222479f,0.109178f},{0.965962f,-0.224921f,0.127782f},{0.962641f,-0.227774f,0.146431f}, -{0.954536f,-0.234735f,0.183742f},{0.949741f,-0.238853f,0.20234f},{0.932352f,-0.253788f,0.25751f}, -{0.783579f,-0.613057f,0.100821f},{0.925555f,-0.259626f,0.275577f},{0.918261f,-0.26589f,0.293425f}, -{0.910478f,-0.272576f,0.31102f},{0.90221f,-0.279676f,0.328326f},{0.761248f,-0.632237f,0.144146f}, -{0.510071f,-0.847968f,-0.144146f},{0.513917f,-0.844665f,-0.14977f},{0.874608f,-0.303383f,0.378179f}, -{0.864516f,-0.312051f,0.394f},{0.854004f,-0.32108f,0.409371f},{0.84309f,-0.330454f,0.424264f}, -{0.736111f,-0.653826f,0.175076f},{0.535208f,-0.826378f,-0.175076f},{0.539823f,-0.822414f,-0.179515f}, -{0.808129f,-0.360481f,0.465812f},{0.795809f,-0.371062f,0.47854f},{0.783195f,-0.381897f,0.490674f}, -{0.770311f,-0.392963f,0.502197f},{0.757182f,-0.404239f,0.513095f},{0.743835f,-0.415702f,0.523356f}, -{0.716589f,-0.439103f,0.541931f},{0.702743f,-0.450995f,0.550232f},{0.688784f,-0.462984f,0.557873f}, -{0.674737f,-0.475049f,0.564853f},{0.660628f,-0.487166f,0.571173f},{0.632324f,-0.511476f,0.581857f}, -{0.590006f,-0.547823f,0.593113f},{0.630724f,-0.744341f,-0.219416f},{0.548369f,-0.583584f,0.598933f}, -{0.534731f,-0.595298f,0.599736f},{0.431242f,-0.502097f,0.749619f},{0.800271f,-0.59872f,0.0331634f}, -{0.801887f,-0.597333f,0.0130831f},{0.799403f,-0.599466f,0.0399431f},{0.471917f,-0.880738f,-0.0399431f}, -{0.472957f,-0.879844f,-0.0467496f},{0.798362f,-0.60036f,0.0467496f},{0.797147f,-0.601403f,0.0535724f}, -{0.794182f,-0.60395f,0.0672227f},{0.792428f,-0.605457f,0.0740269f},{0.790491f,-0.607121f,0.0808012f}, -{0.78837f,-0.608942f,0.0875334f},{0.780911f,-0.615348f,0.107351f},{0.490408f,-0.864856f,-0.107351f}, -{0.493256f,-0.86241f,-0.113788f},{0.778063f,-0.617794f,0.113788f},{0.775039f,-0.620392f,0.120119f}, -{0.771841f,-0.623139f,0.126333f},{0.768473f,-0.626031f,0.132417f},{0.76494f,-0.629065f,0.138358f}, -{0.757402f,-0.63554f,0.14977f},{0.749276f,-0.642519f,0.160482f},{0.74501f,-0.646183f,0.165552f}, -{0.740619f,-0.649955f,0.170419f},{0.731497f,-0.65779f,0.179515f},{0.726783f,-0.661838f,0.183731f}, -{0.72198f,-0.665964f,0.187718f},{0.717096f,-0.670158f,0.191472f},{0.702063f,-0.68307f,0.201304f}, -{0.569257f,-0.797135f,-0.201304f},{0.574363f,-0.792748f,-0.2041f},{0.696956f,-0.687456f,0.2041f}, -{0.691817f,-0.69187f,0.206653f},{0.686655f,-0.696303f,0.208966f},{0.6763f,-0.705197f,0.212875f}, -{0.671124f,-0.709642f,0.214476f},{0.665961f,-0.714077f,0.215848f},{0.660818f,-0.718494f,0.216993f}, -{0.640595f,-0.735863f,0.219416f},{0.46981f,-0.882547f,-0.0197242f},{0.470347f,-0.882086f,-0.0264206f}, -{0.469433f,-0.882871f,-0.013083f},{0.471048f,-0.881484f,-0.0331634f},{0.474172f,-0.878801f,-0.0535725f}, -{0.475565f,-0.877605f,-0.0604006f},{0.477137f,-0.876254f,-0.0672226f},{0.0879462f,-0.979032f,-0.183742f}, -{0.0927413f,-0.974914f,-0.20234f},{0.478891f,-0.874747f,-0.074027f},{0.480829f,-0.873084f,-0.0808012f}, -{0.482949f,-0.871262f,-0.0875334f},{0.485253f,-0.869283f,-0.0942108f},{0.48774f,-0.867147f,-0.100821f}, -{0.496281f,-0.859812f,-0.120119f},{0.140272f,-0.934091f,-0.328326f},{0.149013f,-0.926583f,-0.34531f}, -{0.499479f,-0.857065f,-0.126333f},{0.502847f,-0.854173f,-0.132416f},{0.506379f,-0.851139f,-0.138358f}, -{0.51791f,-0.841235f,-0.155219f},{0.21069f,-0.87361f,-0.438652f},{0.522044f,-0.837685f,-0.160482f}, -{0.52631f,-0.834021f,-0.165552f},{0.530701f,-0.830249f,-0.170419f},{0.544537f,-0.818366f,-0.183731f}, -{0.272171f,-0.820805f,-0.502197f},{0.2853f,-0.809529f,-0.513095f},{0.54934f,-0.814241f,-0.187718f}, -{0.554223f,-0.810046f,-0.191472f},{0.559177f,-0.805792f,-0.194989f},{0.564191f,-0.801485f,-0.198267f}, -{0.579503f,-0.788334f,-0.206653f},{0.584664f,-0.783901f,-0.208966f},{0.381854f,-0.726601f,-0.571173f}, -{0.58984f,-0.779456f,-0.211039f},{0.595019f,-0.775007f,-0.212874f},{0.600195f,-0.770562f,-0.214476f}, -{0.605359f,-0.766127f,-0.215847f},{0.610502f,-0.76171f,-0.216993f},{0.615617f,-0.757316f,-0.217917f}, -{0.0679193f,-0.996233f,-0.0539127f},{0.069387f,-0.994972f,-0.0722163f},{0.0668873f,-0.997119f,-0.0357603f}, -{0.0713025f,-0.993327f,-0.0906467f},{0.0736771f,-0.991288f,-0.109178f},{0.0765202f,-0.988846f,-0.127782f}, -{0.0798413f,-0.985994f,-0.146431f},{-0.246457f,-0.90809f,-0.338573f},{0.103832f,-0.965388f,-0.239258f}, -{0.116927f,-0.954141f,-0.275577f},{0.124221f,-0.947877f,-0.293425f},{0.132004f,-0.941192f,-0.31102f}, -{-0.169495f,-0.841989f,-0.512177f},{0.158218f,-0.918677f,-0.361938f},{0.167874f,-0.910384f,-0.378179f}, -{0.177966f,-0.901716f,-0.394f},{0.188478f,-0.892688f,-0.409371f},{-0.078742f,-0.764043f,-0.640343f}, -{0.222351f,-0.863595f,-0.452509f},{0.234353f,-0.853287f,-0.465812f},{0.246673f,-0.842705f,-0.47854f}, -{0.259287f,-0.831871f,-0.490674f},{0.0292248f,-0.671312f,-0.740598f},{0.298647f,-0.798065f,-0.523356f}, -{0.312187f,-0.786436f,-0.53297f},{0.339739f,-0.762773f,-0.550232f},{0.367745f,-0.738719f,-0.564853f}, -{0.410157f,-0.702291f,-0.581857f},{0.207042f,-0.518588f,-0.829578f},{0.424305f,-0.69014f,-0.586235f}, -{0.438418f,-0.678019f,-0.589983f},{0.452476f,-0.665945f,-0.593113f},{0.494113f,-0.630183f,-0.598933f}, -{0.609586f,-0.709744f,-0.353084f},{-0.339059f,-0.940765f,-6.77795e-016f},{-0.297277f,-0.951738f,-0.0762915f}, -{-0.2952f,-0.949954f,-0.102193f},{-0.29249f,-0.947626f,-0.128274f},{-0.28913f,-0.944741f,-0.154497f}, -{-0.285106f,-0.941285f,-0.180824f},{-0.280406f,-0.937248f,-0.207214f},{-0.27502f,-0.932622f,-0.233625f}, -{-0.268937f,-0.927398f,-0.260012f},{-0.262152f,-0.92157f,-0.286331f},{-0.254659f,-0.915135f,-0.312533f}, -{-0.503721f,-0.757119f,-0.415977f},{-0.674898f,-0.579657f,-0.45663f},{-0.237545f,-0.900436f,-0.3644f}, -{-0.227927f,-0.892174f,-0.389967f},{-0.217606f,-0.88331f,-0.415224f},{-0.206591f,-0.87385f,-0.440122f}, -{-0.182522f,-0.853177f,-0.488646f},{-0.155832f,-0.830254f,-0.535159f},{-0.410442f,-0.677003f,-0.610904f}, -{-0.141551f,-0.817988f,-0.557547f},{-0.126675f,-0.805212f,-0.579299f},{-0.095243f,-0.778215f,-0.620733f}, -{-0.283151f,-0.567676f,-0.773026f},{-0.0617581f,-0.749456f,-0.659168f},{-0.0443242f,-0.734482f,-0.677179f}, -{-0.0264735f,-0.71915f,-0.69435f},{-0.008241f,-0.703491f,-0.710657f},{0.0103371f,-0.687534f,-0.726078f}, -{0.048385f,-0.654856f,-0.754203f},{-0.15518f,-0.457764f,-0.875426f},{0.0873729f,-0.62137f,-0.778631f}, -{0.107127f,-0.604404f,-0.789443f},{0.127004f,-0.587331f,-0.79932f},{0.146969f,-0.570183f,-0.808264f}, -{0.187022f,-0.535783f,-0.823383f},{0.227014f,-0.501435f,-0.834882f},{0.246907f,-0.484349f,-0.839311f}, -{0.266692f,-0.467356f,-0.842884f},{0.536319f,-0.624439f,-0.567836f},{-0.569536f,-0.813646f,-0.116657f}, -{-0.566442f,-0.810988f,-0.146429f},{-0.558013f,-0.803749f,-0.206418f},{-0.552648f,-0.799142f,-0.236543f}, -{-0.546499f,-0.79386f,-0.266692f},{-0.539556f,-0.787897f,-0.296814f},{-0.53181f,-0.781244f,-0.326857f}, -{-0.513894f,-0.765856f,-0.386494f},{-0.480959f,-0.737569f,-0.473994f},{-0.468385f,-0.726769f,-0.502416f}, -{-0.45503f,-0.715299f,-0.530373f},{-0.440909f,-0.703171f,-0.557808f},{-0.39414f,-0.663001f,-0.636461f}, -{-0.377159f,-0.648417f,-0.661292f},{-0.359528f,-0.633274f,-0.68535f},{-0.341277f,-0.617599f,-0.708591f}, -{-0.322441f,-0.601421f,-0.730976f},{-0.262774f,-0.550174f,-0.792627f},{-0.241961f,-0.532298f,-0.811242f}, -{-0.220753f,-0.514083f,-0.828846f},{-0.199192f,-0.495565f,-0.845422f},{-0.132814f,-0.438554f,-0.888837f}, -{-0.0875737f,-0.399698f,-0.912454f},{-0.0647825f,-0.380123f,-0.922664f},{-0.0419318f,-0.360497f,-0.931817f}, -{-0.0190608f,-0.340853f,-0.939923f},{0.00379256f,-0.321225f,-0.946995f},{0.0265911f,-0.301644f,-0.95305f}, -{0.0493f,-0.28214f,-0.958106f},{0.0718851f,-0.262741f,-0.962185f},{0.0943152f,-0.243477f,-0.96531f}, -{0.11656f,-0.224371f,-0.967508f},{-0.755608f,-0.648978f,-0.0887968f},{-0.742337f,-0.63758f,-0.205979f}, -{-0.737381f,-0.633323f,-0.234887f},{-0.731777f,-0.628509f,-0.263588f},{-0.72553f,-0.623144f,-0.292057f}, -{-0.718646f,-0.617231f,-0.320271f},{-0.711131f,-0.610777f,-0.348202f},{-0.702991f,-0.603786f,-0.375828f}, -{-0.684866f,-0.588219f,-0.430066f},{-0.629191f,-0.5404f,-0.558647f},{-0.589074f,-0.505945f,-0.630088f}, -{-0.544304f,-0.467493f,-0.696551f},{-0.512045f,-0.439786f,-0.737834f},{-0.477987f,-0.410534f,-0.776525f}, -{-0.44225f,-0.37984f,-0.812488f},{-0.385773f,-0.331333f,-0.861045f},{-0.366247f,-0.314563f,-0.875736f}, -{-0.326248f,-0.280208f,-0.902799f},{-0.30581f,-0.262654f,-0.915146f},{-0.221554f,-0.190289f,-0.956402f}, -{-0.199957f,-0.171739f,-0.964636f},{-0.178184f,-0.153039f,-0.972023f},{-0.134188f,-0.115252f,-0.984231f}, -{-0.112004f,-0.0961983f,-0.98904f},{-0.0897214f,-0.07706f,-0.992981f},{-0.0673596f,-0.0578539f,-0.99605f}, -{-0.044939f,-0.0385973f,-0.998244f},{-0.775794f,-0.341832f,-0.530373f},{-0.761673f,-0.329704f,-0.557808f}, -{-0.76494f,0.629065f,-0.138358f},{-0.864516f,0.312051f,-0.394f},{-0.874608f,0.303383f,-0.378179f}, -{-0.801723f,-0.364102f,-0.473994f},{-0.653193f,-0.561015f,-0.508529f},{-0.789149f,-0.353302f,-0.502416f}, -{-0.684867f,-0.58822f,-0.430063f},{-0.824484f,-0.383652f,-0.415977f},{-0.694234f,-0.596265f,-0.403122f}, -{-0.852574f,-0.407777f,-0.326857f},{-0.93865f,0.248379f,-0.239258f},{-0.860319f,-0.41443f,-0.296814f}, -{-0.725531f,-0.623145f,-0.292055f},{-0.731777f,-0.62851f,-0.263585f},{-0.873412f,-0.425675f,-0.236543f}, -{-0.878777f,-0.430282f,-0.206418f},{-0.737381f,-0.633323f,-0.234884f},{-0.746642f,-0.641277f,-0.176888f}, -{-0.887205f,-0.437522f,-0.146429f},{-0.750291f,-0.64441f,-0.147645f},{-0.8903f,-0.440179f,-0.116657f}, -{-0.75328f,-0.646978f,-0.118272f},{-0.892671f,-0.442216f,-0.0870897f},{-0.985709f,-0.150194f,-0.0762915f}, -{-0.983632f,-0.14841f,-0.102193f},{0.758272f,0.651265f,0.0296337f},{0.574558f,0.81796f,0.0287252f}, -{0.2996f,0.953733f,0.0251636f},{-0.0662783f,0.997643f,0.0177823f},{0.0755427f,0.997143f,4.44435e-016f}, -{0.564043f,0.825745f,3.04136e-016f},{0.573574f,0.817114f,0.0577667f},{0.297277f,0.951738f,0.0762915f}, -{-0.755608f,-0.648978f,-0.0887942f},{-0.974563f,0.217534f,-0.0539127f},{-0.973095f,0.218795f,-0.0722163f}, -{-0.800972f,0.598118f,-0.0264206f},{-0.971179f,0.22044f,-0.0906467f},{-0.801509f,0.597657f,-0.0197242f}, -{-0.757272f,-0.650407f,-0.059239f},{-0.894338f,-0.443647f,-0.0577667f},{-0.997238f,0.0742779f,-4.48371e-016f}, -{-0.976204f,0.216125f,-0.0177823f},{-0.988031f,-0.152189f,-0.0251636f},{-0.943289f,0.331972f,-4.29587e-016f}, -{-0.80211f,0.597142f,-0.00650572f},{-0.825457f,0.564465f,-3.05233e-016f},{-0.983078f,-0.183188f,-6.14496e-016f}, -{-0.895322f,-0.444493f,-0.0287252f},{-0.901253f,-0.433294f,-9.46059e-016f},{-0.758272f,-0.651265f,-0.0296322f}, -{-0.46921f,0.883063f,0.00650572f},{-0.184979f,0.982742f,5.48296e-016f},{-0.616357f,-0.529378f,-0.582978f}, -{-0.746803f,-0.316933f,-0.58467f},{-0.731206f,-0.303536f,-0.610904f},{-0.589075f,-0.505946f,-0.630087f}, -{-0.697922f,-0.27495f,-0.661292f},{-0.559724f,-0.480737f,-0.674982f},{-0.680291f,-0.259807f,-0.68535f}, -{-0.528407f,-0.453839f,-0.717507f},{-0.662041f,-0.244132f,-0.708591f},{-0.75019f,0.0520889f,-0.659168f}, -{-0.820131f,0.350173f,-0.452509f},{-0.808129f,0.360481f,-0.465812f},{-0.643204f,-0.227954f,-0.730976f}, -{-0.623817f,-0.211302f,-0.752465f},{-0.477988f,-0.410535f,-0.776523f},{-0.583538f,-0.176707f,-0.792627f}, -{-0.423793f,-0.363987f,-0.829405f},{-0.562725f,-0.158831f,-0.811242f},{-0.541517f,-0.140616f,-0.828846f}, -{-0.519956f,-0.122098f,-0.845422f},{-0.707128f,0.678719f,-0.198267f},{-0.702743f,0.450995f,-0.550232f}, -{-0.475944f,-0.0842968f,-0.875426f},{-0.346402f,-0.297518f,-0.889657f},{-0.32625f,-0.28021f,-0.902798f}, -{-0.305812f,-0.262656f,-0.915145f},{-0.285105f,-0.244871f,-0.926689f},{-0.453578f,-0.065087f,-0.888837f}, -{-0.431028f,-0.0457196f,-0.901179f},{-0.264148f,-0.226872f,-0.937419f},{-0.408337f,-0.0262308f,-0.912454f}, -{-0.242959f,-0.208673f,-0.947326f},{-0.221556f,-0.19029f,-0.956401f},{-0.385546f,-0.00665601f,-0.922665f}, -{-0.362695f,0.0129701f,-0.931817f},{-0.199959f,-0.171741f,-0.964635f},{-0.339824f,0.0326136f,-0.939923f}, -{-0.48139f,0.282956f,-0.829578f},{-0.316971f,0.0522418f,-0.946995f},{-0.501409f,0.265762f,-0.823383f}, -{-0.178186f,-0.153041f,-0.972023f},{-0.294173f,0.0718231f,-0.95305f},{-0.156257f,-0.134206f,-0.978556f}, -{-0.248878f,0.110725f,-0.962185f},{-0.441525f,0.317195f,-0.839311f},{-0.42174f,0.334188f,-0.842884f}, -{-0.13419f,-0.115253f,-0.98423f},{-0.650623f,0.727251f,-0.218624f},{-0.620697f,0.752953f,0.218624f}, -{-0.645585f,0.731578f,-0.219122f},{-0.665961f,0.714077f,-0.215848f},{-0.660818f,0.718494f,-0.216993f}, -{-0.590006f,0.547823f,-0.593113f},{-0.286341f,0.45048f,0.845622f},{-0.480343f,0.642011f,0.597573f}, -{-0.266692f,0.467356f,0.842884f},{-0.325127f,0.417168f,0.848684f},{-0.432488f,0.503548f,0.747926f}, -{-0.507751f,0.61847f,0.599737f},{-0.548369f,0.583584f,-0.598933f},{-0.562139f,0.571757f,-0.597573f}, -{-0.304133f,0.354104f,0.884372f},{-0.138591f,0.205449f,0.968805f},{-0.155494f,0.181043f,0.971105f}, -{-0.576025f,0.559831f,-0.595638f},{-0.655703f,0.722888f,-0.217916f},{-0.382604f,0.367801f,-0.847547f}, -{-0.402091f,0.351064f,-0.845622f},{0.0224792f,0.0193069f,0.999561f},{-0.271464f,0.0913273f,-0.958106f}, -{-0.226448f,0.12999f,-0.96531f},{-0.204204f,0.149095f,-0.967508f},{-0.0673616f,-0.0578556f,-0.99605f}, -{-0.182173f,0.168017f,-0.968805f},{-0.0224803f,-0.0193079f,-0.999561f},{-0.0449408f,-0.0385988f,-0.998244f}, -{-0.155937f,0.181559f,-0.970938f},{-0.433008f,0.90139f,1.81967e-016f},{-0.987169f,-0.151448f,-0.0506042f}, -{-0.980921f,-0.146082f,-0.128274f},{-0.977561f,-0.143196f,-0.154497f},{-0.973538f,-0.13974f,-0.180824f}, -{-0.968838f,-0.135704f,-0.207214f},{-0.957369f,-0.125853f,-0.260012f},{-0.950583f,-0.120025f,-0.286331f}, -{-0.943091f,-0.11359f,-0.312533f},{-0.934889f,-0.106546f,-0.338573f},{-0.916358f,-0.0906299f,-0.389967f}, -{-0.906037f,-0.0817656f,-0.415224f},{-0.895022f,-0.072305f,-0.440122f},{-0.883323f,-0.0622569f,-0.464612f}, -{-0.870953f,-0.0516324f,-0.488646f},{-0.857927f,-0.0404447f,-0.512177f},{-0.844263f,-0.0287093f,-0.535159f}, -{-0.829983f,-0.0164437f,-0.557547f},{-0.815107f,-0.00366744f,-0.579299f},{-0.783674f,0.0233295f,-0.620733f}, -{-0.767173f,0.0375019f,-0.640343f},{-0.732756f,0.0670627f,-0.677179f},{-0.714905f,0.0823942f,-0.69435f}, -{-0.678094f,0.11401f,-0.726078f},{-0.659207f,0.130232f,-0.740598f},{-0.640047f,0.146689f,-0.754203f}, -{-0.620651f,0.163347f,-0.766883f},{-0.601058f,0.180175f,-0.778631f},{-0.581305f,0.197141f,-0.789443f}, -{-0.561427f,0.214213f,-0.79932f},{-0.541462f,0.231361f,-0.808264f},{-0.521445f,0.248554f,-0.816282f}, -{-0.461418f,0.30011f,-0.834882f},{-0.604064f,0.535749f,-0.589983f},{-0.363305f,0.384377f,-0.848684f}, -{0.757272f,0.650407f,0.0592414f},{-0.975595f,0.216648f,-0.0357603f},{-0.968805f,0.222479f,-0.109178f}, -{-0.965962f,0.224921f,-0.127782f},{-0.962641f,0.227774f,-0.146431f},{-0.954536f,0.234735f,-0.183742f}, -{-0.949741f,0.238853f,-0.20234f},{-0.918261f,0.26589f,-0.293425f},{-0.925555f,0.259626f,-0.275577f}, -{-0.783579f,0.613057f,-0.100821f},{-0.910478f,0.272576f,-0.31102f},{-0.90221f,0.279676f,-0.328326f}, -{-0.893469f,0.287184f,-0.34531f},{-0.884264f,0.29509f,-0.361938f},{-0.854004f,0.32108f,-0.409371f}, -{-0.831792f,0.340158f,-0.438652f},{-0.731496f,0.65779f,-0.179515f},{-0.726783f,0.661838f,-0.183731f}, -{-0.795809f,0.371062f,-0.47854f},{-0.783195f,0.381897f,-0.490674f},{-0.770311f,0.392963f,-0.502197f}, -{-0.757182f,0.404239f,-0.513095f},{-0.743835f,0.415702f,-0.523356f},{-0.730295f,0.427331f,-0.53297f}, -{-0.674737f,0.475049f,-0.564853f},{-0.660628f,0.487166f,-0.571173f},{-0.632324f,0.511476f,-0.581857f}, -{-0.640595f,0.735863f,-0.219416f},{-0.630724f,0.744341f,0.219416f},{-0.534731f,0.595298f,-0.599736f}, -{-0.431242f,0.502097f,-0.749619f},{-0.801887f,0.597333f,-0.013083f},{-0.800271f,0.59872f,-0.0331634f}, -{-0.799403f,0.599466f,-0.0399431f},{-0.474172f,0.878801f,0.0535724f},{-0.795755f,0.6026f,-0.0604006f}, -{-0.797147f,0.601403f,-0.0535725f},{-0.798362f,0.60036f,-0.0467496f},{-0.794182f,0.60395f,-0.0672227f}, -{-0.792428f,0.605457f,-0.0740269f},{-0.790491f,0.607121f,-0.0808013f},{-0.78837f,0.608942f,-0.0875334f}, -{-0.786066f,0.610921f,-0.0942108f},{-0.493256f,0.86241f,0.113788f},{-0.775039f,0.620392f,-0.120119f}, -{-0.778063f,0.617794f,-0.113788f},{-0.780911f,0.615348f,-0.107351f},{-0.771841f,0.623139f,-0.126333f}, -{-0.768473f,0.626031f,-0.132417f},{-0.513917f,0.844665f,0.14977f},{-0.753409f,0.638969f,-0.155219f}, -{-0.757402f,0.63554f,-0.14977f},{-0.761248f,0.632237f,-0.144146f},{-0.749276f,0.642519f,-0.160482f}, -{-0.74501f,0.646183f,-0.165552f},{-0.740619f,0.649955f,-0.170419f},{-0.736112f,0.653826f,-0.175076f}, -{-0.72198f,0.665964f,-0.187718f},{-0.717096f,0.670158f,-0.191472f},{-0.712143f,0.674412f,-0.194989f}, -{-0.574363f,0.792748f,0.2041f},{-0.691817f,0.69187f,-0.206653f},{-0.696956f,0.687456f,-0.2041f}, -{-0.702063f,0.68307f,-0.201304f},{-0.686655f,0.696303f,-0.208966f},{-0.68148f,0.700748f,-0.211039f}, -{-0.6763f,0.705197f,-0.212874f},{-0.671124f,0.709642f,-0.214476f},{-0.494113f,0.630183f,0.598933f}, -{-0.615617f,0.757316f,0.217917f},{-0.609092f,0.70917f,-0.355084f},{-0.536047f,0.624123f,-0.56844f}, -{-0.46981f,0.882547f,0.0197241f},{-0.469433f,0.882871f,0.0130831f},{-0.470347f,0.882086f,0.0264206f}, -{-0.471048f,0.881484f,0.0331634f},{-0.471917f,0.880738f,0.0399431f},{-0.472957f,0.879844f,0.0467496f}, -{-0.480829f,0.873084f,0.0808012f},{-0.478891f,0.874747f,0.074027f},{-0.0927413f,0.974914f,0.20234f}, -{-0.477137f,0.876254f,0.0672226f},{-0.482949f,0.871262f,0.0875334f},{-0.48774f,0.867147f,0.100821f}, -{-0.490408f,0.864856f,0.107351f},{0.169495f,0.841989f,0.512177f},{-0.158218f,0.918677f,0.361938f}, -{0.182522f,0.853177f,0.488646f},{-0.496281f,0.859812f,0.120119f},{-0.499479f,0.857065f,0.126333f}, -{-0.502847f,0.854173f,0.132416f},{-0.506379f,0.851139f,0.138358f},{-0.510071f,0.847968f,0.144146f}, -{0.078742f,0.764043f,0.640343f},{-0.222351f,0.863595f,0.452509f},{0.095243f,0.778215f,0.620733f}, -{-0.522044f,0.837685f,0.160482f},{-0.52631f,0.834021f,0.165552f},{-0.530701f,0.830249f,0.170419f}, -{-0.535208f,0.826378f,0.175076f},{-0.554223f,0.810046f,0.191472f},{-0.54934f,0.814241f,0.187718f}, -{-0.2853f,0.809529f,0.513095f},{-0.544537f,0.818366f,0.183731f},{-0.559177f,0.805792f,0.194989f}, -{-0.569257f,0.797135f,0.201304f},{-0.579503f,0.788334f,0.206653f},{-0.595019f,0.775007f,0.212874f}, -{-0.584664f,0.783901f,0.208966f},{-0.605359f,0.766127f,0.215847f},{-0.610502f,0.76171f,0.216993f}, -{-0.466457f,0.653936f,0.595638f},{-0.0668873f,0.997119f,0.0357603f},{-0.0693872f,0.994972f,0.0722163f}, -{-0.0713027f,0.993327f,0.0906467f},{-0.0736769f,0.991288f,0.109178f},{-0.0765202f,0.988846f,0.127782f}, -{-0.0798415f,0.985994f,0.146431f},{-0.0879462f,0.979032f,0.183742f},{0.254659f,0.915135f,0.312533f}, -{0.246457f,0.90809f,0.338573f},{-0.103832f,0.965388f,0.239258f},{-0.0980359f,0.970367f,0.220857f}, -{-0.11013f,0.959979f,0.257509f},{-0.116927f,0.954141f,0.275577f},{-0.12422f,0.947877f,0.293425f}, -{-0.132004f,0.941192f,0.31102f},{-0.140272f,0.934091f,0.328326f},{-0.149013f,0.926583f,0.34531f}, -{-0.167874f,0.910384f,0.378179f},{-0.177966f,0.901716f,0.394f},{-0.188478f,0.892688f,0.409371f}, -{-0.199392f,0.883313f,0.424264f},{-0.21069f,0.87361f,0.438652f},{-0.234353f,0.853287f,0.465812f}, -{-0.246673f,0.842705f,0.47854f},{-0.259287f,0.831871f,0.490674f},{-0.272171f,0.820805f,0.502197f}, -{-0.0292248f,0.671312f,0.740598f},{-0.0483848f,0.654856f,0.754203f},{-0.312187f,0.786436f,0.53297f}, -{-0.298647f,0.798065f,0.523356f},{-0.325893f,0.774664f,0.541931f},{-0.339739f,0.762773f,0.550232f}, -{-0.353698f,0.750783f,0.557873f},{-0.367745f,0.738719f,0.564853f},{-0.381854f,0.726601f,0.571173f}, -{-0.207042f,0.518588f,0.829578f},{-0.227014f,0.501435f,0.834882f},{-0.438418f,0.678019f,0.589983f}, -{-0.424305f,0.69014f,0.586235f},{-0.452476f,0.665945f,0.593113f},{-0.609586f,0.709744f,0.353084f}, -{0.339059f,0.940765f,5.47231e-016f},{0.298738f,0.952993f,0.0506042f},{0.2952f,0.949954f,0.102193f}, -{0.29249f,0.947626f,0.128274f},{0.569536f,0.813646f,0.116657f},{0.28913f,0.944741f,0.154497f}, -{0.285106f,0.941285f,0.180824f},{0.280406f,0.937248f,0.207214f},{0.27502f,0.932622f,0.233625f}, -{0.268937f,0.927398f,0.260012f},{0.262152f,0.92157f,0.286331f},{0.674898f,0.579657f,0.45663f}, -{0.492741f,0.747688f,0.445162f},{0.237545f,0.900436f,0.3644f},{0.227927f,0.892174f,0.389967f}, -{0.217606f,0.88331f,0.415224f},{0.206591f,0.87385f,0.440122f},{0.194892f,0.863801f,0.464612f}, -{0.141551f,0.817988f,0.557547f},{0.126676f,0.805212f,0.579299f},{0.11123f,0.791947f,0.600374f}, -{0.46032f,0.39536f,0.794856f},{0.0617581f,0.749456f,0.659168f},{0.0443242f,0.734482f,0.677179f}, -{0.0264735f,0.71915f,0.69435f},{0.008241f,0.703491f,0.710657f},{-0.0103371f,0.687534f,0.726078f}, -{0.15518f,0.457764f,0.875426f},{-0.0677801f,0.638198f,0.766883f},{0.177321f,0.476779f,0.860952f}, -{-0.0873729f,0.62137f,0.778631f},{-0.127004f,0.587331f,0.79932f},{-0.146969f,0.570183f,0.808264f}, -{-0.166987f,0.552991f,0.816282f},{-0.187022f,0.535783f,0.823383f},{-0.246907f,0.484349f,0.839311f}, -{-0.11656f,0.224372f,0.967508f},{-0.0943152f,0.243477f,0.96531f},{-0.305827f,0.433744f,0.847547f}, -{-0.536319f,0.624439f,0.567837f},{0.566442f,0.810988f,0.146429f},{0.562606f,0.807694f,0.176364f}, -{0.558013f,0.803749f,0.206418f},{0.552648f,0.799142f,0.236543f},{0.546499f,0.79386f,0.266692f}, -{0.539556f,0.787897f,0.296814f},{0.513894f,0.765856f,0.386494f},{0.480959f,0.737569f,0.473994f}, -{0.468385f,0.726769f,0.502416f},{0.45503f,0.715299f,0.530373f},{0.440909f,0.703171f,0.557808f}, -{0.39414f,0.663001f,0.636461f},{0.377159f,0.648417f,0.661292f},{0.341277f,0.617599f,0.708591f}, -{0.322441f,0.601421f,0.730976f},{0.262774f,0.550174f,0.792627f},{0.241961f,0.532298f,0.811242f}, -{0.220753f,0.514083f,0.828846f},{0.199192f,0.495565f,0.845422f},{0.132814f,0.438554f,0.888837f}, -{0.110264f,0.419187f,0.901179f},{0.0875737f,0.399698f,0.912454f},{0.0647826f,0.380123f,0.922665f}, -{0.0419317f,0.360497f,0.931817f},{0.0190608f,0.340853f,0.939923f},{-0.00379247f,0.321225f,0.946995f}, -{-0.0493001f,0.28214f,0.958106f},{0.755608f,0.648977f,0.0887968f},{0.742337f,0.63758f,0.205979f}, -{0.737381f,0.633323f,0.234887f},{0.731777f,0.628509f,0.263588f},{0.72553f,0.623144f,0.292057f}, -{0.718646f,0.617231f,0.320271f},{0.702991f,0.603786f,0.375828f},{0.684866f,0.588219f,0.430066f}, -{0.664336f,0.570586f,0.482793f},{0.589074f,0.505945f,0.630088f},{0.559723f,0.480736f,0.674983f}, -{0.544304f,0.467493f,0.696551f},{0.528406f,0.453838f,0.717508f},{0.477987f,0.410534f,0.776525f}, -{0.44225f,0.37984f,0.812488f},{0.385773f,0.331333f,0.861045f},{0.366247f,0.314563f,0.875736f}, -{0.326248f,0.280208f,0.902799f},{0.30581f,0.262654f,0.915146f},{0.242957f,0.208671f,0.947327f}, -{0.221554f,0.190289f,0.956402f},{0.199957f,0.171739f,0.964636f},{0.178184f,0.153039f,0.972023f}, -{0.134188f,0.115252f,0.984231f},{0.112004f,0.0961983f,0.98904f},{0.0897214f,0.07706f,0.992981f}, -{0.0673596f,0.0578539f,0.99605f},{0.044939f,0.0385973f,0.998244f},{-0.222351f,0.863595f,-0.452509f}, -{-0.234353f,0.853287f,-0.465812f},{-0.530701f,0.830249f,-0.170419f},{0.220753f,0.514083f,-0.828846f}, -{0.385773f,0.331333f,-0.861045f},{0.241961f,0.532298f,-0.811242f},{0.199192f,0.495565f,-0.845422f}, -{0.366247f,0.314563f,-0.875736f},{0.30581f,0.262654f,-0.915146f},{0.15518f,0.457764f,-0.875426f}, -{0.326248f,0.280208f,-0.902799f},{0.132814f,0.438554f,-0.888837f},{0.0875736f,0.399698f,-0.912454f}, -{-0.339739f,0.762773f,-0.550232f},{0.0647826f,0.380123f,-0.922665f},{0.0419318f,0.360497f,-0.931817f}, -{0.221554f,0.190289f,-0.956402f},{0.199957f,0.171739f,-0.964636f},{0.0190607f,0.340853f,-0.939923f}, -{0.178184f,0.153039f,-0.972023f},{0.134188f,0.115252f,-0.984231f},{-0.0265912f,0.301644f,-0.95305f}, -{-0.0037925f,0.321225f,-0.946995f},{0.112004f,0.0961983f,-0.98904f},{-0.0492999f,0.28214f,-0.958106f}, -{0.0897213f,0.07706f,-0.992981f},{-0.0718852f,0.262742f,-0.962185f},{-0.155937f,0.181559f,0.970938f}, -{-0.0224803f,-0.0193079f,0.999561f},{-0.0943152f,0.243477f,-0.96531f},{-0.182173f,0.168017f,0.968805f}, -{-0.286341f,0.45048f,-0.845622f},{-0.266692f,0.467356f,-0.842884f},{-0.226448f,0.12999f,0.96531f}, -{-0.402091f,0.351065f,0.845622f},{-0.204204f,0.149095f,0.967508f},{-0.615617f,0.757316f,-0.217916f}, -{-0.452476f,0.665945f,-0.593113f},{-0.534731f,0.595298f,0.599736f},{-0.640595f,0.735863f,0.219416f}, -{-0.431242f,0.502097f,0.749619f},{-0.363305f,0.384377f,0.848684f},{0.0673597f,0.0578539f,-0.99605f}, -{-0.480343f,0.642011f,-0.597573f},{-0.630724f,0.744341f,-0.219416f},{-0.138591f,0.205449f,-0.968805f}, -{-0.304133f,0.354104f,-0.884372f},{-0.325126f,0.417168f,-0.848684f},{0.044939f,0.0385972f,-0.998244f}, -{-0.11656f,0.224371f,-0.967508f},{-0.507751f,0.61847f,-0.599736f},{-0.609586f,0.709744f,-0.353084f}, -{-0.536319f,0.624439f,-0.567836f},{-0.155494f,0.181042f,-0.971105f},{0.0224791f,0.0193069f,-0.999561f}, -{-0.620697f,0.752953f,-0.218624f},{0.262774f,0.550174f,-0.792627f},{0.44225f,0.37984f,-0.812488f}, -{0.283151f,0.567676f,-0.773026f},{0.477987f,0.410534f,-0.776525f},{0.512045f,0.439786f,-0.737834f}, -{0.322441f,0.601421f,-0.730976f},{0.341277f,0.617599f,-0.708591f},{0.359528f,0.633274f,-0.68535f}, -{0.544304f,0.467493f,-0.696551f},{0.377159f,0.648417f,-0.661292f},{0.155832f,0.830254f,-0.535159f}, -{-0.177966f,0.901716f,-0.394f},{-0.167874f,0.910384f,-0.378179f},{0.39414f,0.663002f,-0.636461f}, -{0.410442f,0.677003f,-0.610904f},{0.589074f,0.505945f,-0.630089f},{0.440909f,0.703171f,-0.557808f}, -{0.629191f,0.5404f,-0.558647f},{0.45503f,0.715299f,-0.530373f},{0.468385f,0.726769f,-0.502416f}, -{0.480959f,0.737569f,-0.473994f},{-0.485253f,0.869283f,-0.0942108f},{-0.103832f,0.965388f,-0.239258f}, -{0.503721f,0.757119f,-0.415977f},{0.674898f,0.579657f,-0.45663f},{0.684866f,0.588219f,-0.430066f}, -{0.702991f,0.603786f,-0.375828f},{0.513894f,0.765856f,-0.386494f},{0.711131f,0.610777f,-0.348202f}, -{0.53181f,0.781244f,-0.326857f},{0.718646f,0.617231f,-0.32027f},{0.72553f,0.623144f,-0.292057f}, -{0.539556f,0.787897f,-0.296814f},{0.546499f,0.79386f,-0.266692f},{0.731777f,0.628509f,-0.263588f}, -{0.552648f,0.799142f,-0.236543f},{0.285106f,0.941285f,-0.180824f},{0.558013f,0.803749f,-0.206418f}, -{0.280406f,0.937248f,-0.207214f},{0.737381f,0.633323f,-0.234887f},{0.742337f,0.63758f,-0.205979f}, -{-0.0662782f,0.997643f,-0.0177823f},{-0.469433f,0.882871f,-0.0130831f},{-0.46921f,0.883063f,-0.00650573f}, -{-0.974563f,0.217534f,0.0539127f},{-0.801509f,0.597657f,0.0197241f},{-0.973095f,0.218795f,0.0722163f}, -{0.292489f,0.947626f,-0.128274f},{0.2952f,0.949955f,-0.102193f},{0.569536f,0.813646f,-0.116657f}, -{-0.985709f,-0.150194f,0.0762915f},{-0.983632f,-0.14841f,0.102193f},{-0.988031f,-0.152188f,0.0251637f}, -{-0.997238f,0.0742779f,1.11285e-016f},{-0.976204f,0.216125f,0.0177823f},{-0.470347f,0.882086f,-0.0264206f}, -{-0.0679194f,0.996233f,-0.0539127f},{-0.069387f,0.994972f,-0.0722163f},{-0.895322f,-0.444493f,0.0287253f}, -{-0.983078f,-0.183188f,4.07949e-016f},{-0.471048f,0.881484f,-0.0331634f},{-0.0713026f,0.993327f,-0.0906466f}, -{-0.471917f,0.880738f,-0.0399431f},{-0.901253f,-0.433294f,3.52919e-035f},{0.566442f,0.810988f,-0.146429f}, -{0.573574f,0.817114f,-0.0577667f},{0.297277f,0.951738f,-0.0762915f},{0.755608f,0.648977f,-0.0887967f}, -{0.757272f,0.650407f,-0.0592414f},{0.758271f,0.651265f,-0.0296338f},{0.574558f,0.81796f,-0.0287253f}, -{-0.432488f,0.503548f,-0.747926f},{-0.305827f,0.433744f,-0.847547f},{-0.246907f,0.484349f,-0.839311f}, -{-0.227014f,0.501435f,-0.834882f},{-0.207042f,0.518588f,-0.829578f},{-0.187022f,0.535783f,-0.823383f}, -{-0.146969f,0.570184f,-0.808264f},{-0.127004f,0.587331f,-0.79932f},{-0.107127f,0.604404f,-0.789443f}, -{-0.087373f,0.62137f,-0.778631f},{-0.0483849f,0.654856f,-0.754203f},{-0.0292249f,0.671312f,-0.740598f}, -{-0.0103372f,0.687534f,-0.726078f},{0.00824112f,0.703491f,-0.710657f},{0.0264736f,0.71915f,-0.69435f}, -{0.0443241f,0.734482f,-0.677179f},{0.0617582f,0.749456f,-0.659168f},{0.0787419f,0.764043f,-0.640343f}, -{0.0952429f,0.778215f,-0.620734f},{0.126676f,0.805212f,-0.579299f},{0.141551f,0.817988f,-0.557547f}, -{0.169496f,0.841989f,-0.512177f},{0.182522f,0.853177f,-0.488646f},{0.206591f,0.87385f,-0.440122f}, -{0.217606f,0.88331f,-0.415224f},{0.227926f,0.892174f,-0.389967f},{0.237545f,0.900436f,-0.3644f}, -{0.246457f,0.90809f,-0.338573f},{0.254659f,0.915135f,-0.312533f},{0.262152f,0.92157f,-0.286331f}, -{0.268937f,0.927398f,-0.260012f},{0.27502f,0.932622f,-0.233625f},{0.28913f,0.944741f,-0.154497f}, -{-0.073677f,0.991288f,-0.109178f},{0.2996f,0.953733f,-0.0251637f},{0.298737f,0.952993f,-0.0506043f}, -{0.339059f,0.940765f,-2.28355e-016f},{0.564043f,0.825745f,-3.01839e-016f},{-0.494113f,0.630183f,-0.598933f}, -{-0.438418f,0.678019f,-0.589983f},{-0.424305f,0.69014f,-0.586235f},{-0.410158f,0.702291f,-0.581857f}, -{-0.381854f,0.726601f,-0.571173f},{-0.367745f,0.738719f,-0.564853f},{-0.298647f,0.798065f,-0.523356f}, -{-0.312187f,0.786436f,-0.53297f},{-0.559177f,0.805792f,-0.194989f},{-0.2853f,0.809529f,-0.513095f}, -{-0.272171f,0.820805f,-0.502197f},{-0.259287f,0.831871f,-0.490674f},{-0.246673f,0.842705f,-0.47854f}, -{-0.21069f,0.87361f,-0.438652f},{-0.188478f,0.892688f,-0.409371f},{-0.499479f,0.857065f,-0.126333f}, -{-0.771841f,0.623139f,0.126333f},{-0.496281f,0.859812f,-0.120119f},{-0.158218f,0.918677f,-0.361938f}, -{-0.149013f,0.926583f,-0.34531f},{-0.140272f,0.934091f,-0.328326f},{-0.132004f,0.941192f,-0.31102f}, -{-0.124221f,0.947877f,-0.293425f},{-0.116927f,0.954141f,-0.275577f},{-0.0927412f,0.974914f,-0.20234f}, -{-0.0879463f,0.979032f,-0.183742f},{-0.0798414f,0.985994f,-0.146431f},{-0.0765202f,0.988846f,-0.127782f}, -{-0.0668873f,0.997119f,-0.0357604f},{-0.46981f,0.882547f,-0.0197241f},{0.0755429f,0.997143f,-2.89047e-016f}, -{-0.0449408f,-0.0385988f,0.998244f},{-0.625735f,0.748626f,-0.219122f},{-0.610502f,0.76171f,-0.216993f}, -{-0.605359f,0.766127f,-0.215847f},{-0.6763f,0.705197f,0.212874f},{-0.58984f,0.779456f,-0.211039f}, -{-0.595019f,0.775007f,-0.212875f},{-0.600195f,0.770562f,-0.214476f},{-0.584664f,0.783901f,-0.208966f}, -{-0.579503f,0.788334f,-0.206653f},{-0.574364f,0.792748f,-0.2041f},{-0.569256f,0.797135f,-0.201305f}, -{-0.564191f,0.801485f,-0.198267f},{-0.721979f,0.665964f,0.187718f},{-0.544537f,0.818366f,-0.183731f}, -{-0.54934f,0.814241f,-0.187718f},{-0.554223f,0.810046f,-0.191472f},{-0.539823f,0.822414f,-0.179515f}, -{-0.535208f,0.826378f,-0.175076f},{-0.749276f,0.642519f,0.160482f},{-0.51791f,0.841235f,-0.155219f}, -{-0.522044f,0.837685f,-0.160482f},{-0.52631f,0.834021f,-0.165552f},{-0.513917f,0.844665f,-0.14977f}, -{-0.510071f,0.847968f,-0.144146f},{-0.506379f,0.851139f,-0.138358f},{-0.502846f,0.854173f,-0.132417f}, -{-0.493256f,0.86241f,-0.113788f},{-0.490408f,0.864856f,-0.107351f},{-0.48774f,0.867148f,-0.100821f}, -{-0.790491f,0.60712f,0.0808013f},{-0.478892f,0.874747f,-0.0740269f},{-0.480829f,0.873084f,-0.0808013f}, -{-0.482949f,0.871262f,-0.0875334f},{-0.477137f,0.876254f,-0.0672227f},{-0.475565f,0.877605f,-0.0604006f}, -{-0.474172f,0.878801f,-0.0535724f},{-0.472957f,0.879844f,-0.0467496f},{-0.800972f,0.598118f,0.0264206f}, -{-0.184979f,0.982742f,-2.6491e-016f},{-0.650623f,0.727251f,0.218624f},{-0.645585f,0.731578f,0.219122f}, -{-0.655703f,0.722888f,0.217917f},{-0.660818f,0.718494f,0.216992f},{-0.665961f,0.714077f,0.215848f}, -{-0.671124f,0.709642f,0.214476f},{-0.696956f,0.687456f,0.2041f},{-0.691817f,0.69187f,0.206653f}, -{-0.674737f,0.475049f,0.564852f},{-0.686655f,0.696303f,0.208966f},{-0.702063f,0.68307f,0.201305f}, -{-0.712143f,0.674412f,0.194989f},{-0.717096f,0.670158f,0.191472f},{-0.732756f,0.0670628f,0.677179f}, -{-0.795809f,0.371062f,0.47854f},{-0.714905f,0.0823942f,0.69435f},{-0.726783f,0.661838f,0.183731f}, -{-0.731497f,0.65779f,0.179515f},{-0.736111f,0.653826f,0.175076f},{-0.740619f,0.649955f,0.170419f}, -{-0.74501f,0.646183f,0.165552f},{-0.829983f,-0.0164437f,0.557547f},{-0.864516f,0.312051f,0.394f}, -{-0.815107f,-0.00366745f,0.579299f},{-0.757402f,0.63554f,0.14977f},{-0.761248f,0.632236f,0.144146f}, -{-0.76494f,0.629065f,0.138358f},{-0.768473f,0.626031f,0.132417f},{-0.780911f,0.615349f,0.107351f}, -{-0.778063f,0.617794f,0.113788f},{-0.910477f,0.272576f,0.311019f},{-0.775039f,0.620392f,0.120119f}, -{-0.783579f,0.613057f,0.100821f},{-0.78837f,0.608942f,0.0875334f},{-0.792428f,0.605457f,0.0740269f}, -{-0.797147f,0.601403f,0.0535724f},{-0.794182f,0.60395f,0.0672227f},{-0.798362f,0.60036f,0.0467497f}, -{-0.799403f,0.599467f,0.0399431f},{-0.800271f,0.59872f,0.0331634f},{-0.801887f,0.597333f,0.0130831f}, -{-0.802109f,0.597142f,0.00650573f},{-0.651551f,0.758605f,-2.05938e-033f},{-0.433008f,0.90139f,-1.54031e-016f}, -{-0.548369f,0.583584f,0.598933f},{-0.576025f,0.559831f,0.595638f},{-0.590006f,0.547823f,0.593113f}, -{-0.604064f,0.535749f,0.589983f},{-0.618177f,0.523627f,0.586235f},{-0.632325f,0.511476f,0.581857f}, -{-0.660628f,0.487166f,0.571173f},{-0.581305f,0.197141f,0.789443f},{-0.601058f,0.180175f,0.778631f}, -{-0.702743f,0.450995f,0.550232f},{-0.688784f,0.462984f,0.557873f},{-0.716589f,0.439103f,0.541931f}, -{-0.730295f,0.427331f,0.53297f},{-0.743835f,0.415702f,0.523356f},{-0.757182f,0.404239f,0.513095f}, -{-0.770311f,0.392963f,0.502197f},{-0.783195f,0.381897f,0.490674f},{-0.808129f,0.360481f,0.465812f}, -{-0.820131f,0.350173f,0.452509f},{-0.831792f,0.340157f,0.438652f},{-0.84309f,0.330454f,0.424264f}, -{-0.854004f,0.32108f,0.409371f},{-0.874608f,0.303383f,0.378179f},{-0.884264f,0.29509f,0.361938f}, -{-0.893469f,0.287184f,0.34531f},{-0.90221f,0.279676f,0.328326f},{-0.906037f,-0.0817656f,0.415224f}, -{-0.916358f,-0.09063f,0.389967f},{-0.925555f,0.259626f,0.275577f},{-0.918261f,0.26589f,0.293425f}, -{-0.932352f,0.253788f,0.257509f},{-0.93865f,0.248379f,0.239258f},{-0.944446f,0.243401f,0.220857f}, -{-0.949741f,0.238853f,0.20234f},{-0.954536f,0.234735f,0.183742f},{-0.962641f,0.227774f,0.146431f}, -{-0.973538f,-0.13974f,0.180824f},{-0.977561f,-0.143196f,0.154497f},{-0.968805f,0.222479f,0.109178f}, -{-0.965962f,0.224922f,0.127782f},{-0.971179f,0.22044f,0.0906467f},{-0.975595f,0.216648f,0.0357604f}, -{-0.943289f,0.331972f,1.5621e-016f},{-0.825457f,0.564465f,6.56678e-035f},{-0.29793f,0.346881f,0.889332f}, -{-0.382604f,0.367801f,0.847547f},{-0.42174f,0.334188f,0.842884f},{-0.441525f,0.317195f,0.839311f}, -{-0.248878f,0.110725f,0.962185f},{-0.461418f,0.30011f,0.834882f},{-0.48139f,0.282956f,0.829578f}, -{-0.501409f,0.265762f,0.823383f},{-0.521445f,0.248554f,0.816282f},{-0.541462f,0.231361f,0.808264f}, -{-0.561427f,0.214213f,0.79932f},{-0.346402f,-0.297518f,0.889657f},{-0.498084f,-0.103313f,0.860952f}, -{-0.475944f,-0.0842968f,0.875426f},{-0.620651f,0.163347f,0.766883f},{-0.640047f,0.146689f,0.754203f}, -{-0.659207f,0.130232f,0.740598f},{-0.678094f,0.11401f,0.726078f},{-0.696673f,0.0980537f,0.710657f}, -{-0.767173f,0.0375018f,0.640343f},{-0.783674f,0.0233294f,0.620734f},{-0.799662f,0.00959819f,0.600374f}, -{-0.731206f,-0.303536f,0.610904f},{-0.602981f,-0.517889f,0.606799f},{-0.844264f,-0.0287092f,0.535159f}, -{-0.857927f,-0.0404448f,0.512177f},{-0.870953f,-0.0516324f,0.488646f},{-0.883323f,-0.0622568f,0.464612f}, -{-0.895022f,-0.072305f,0.440122f},{-0.824484f,-0.383652f,0.415977f},{-0.925977f,-0.0988912f,0.3644f}, -{-0.813504f,-0.374221f,0.445163f},{-0.934889f,-0.106546f,0.338573f},{-0.950583f,-0.120025f,0.286331f}, -{-0.957369f,-0.125853f,0.260012f},{-0.963451f,-0.131077f,0.233625f},{-0.968838f,-0.135704f,0.207214f}, -{-0.980921f,-0.146082f,0.128274f},{-0.894338f,-0.443647f,0.0577667f},{-0.892671f,-0.442216f,0.0870897f}, -{-0.987169f,-0.151448f,0.0506043f},{-0.271464f,0.0913273f,0.958106f},{-0.294173f,0.0718233f,0.95305f}, -{-0.316971f,0.0522418f,0.946995f},{-0.339824f,0.0326136f,0.939923f},{-0.362696f,0.0129702f,0.931817f}, -{-0.385546f,-0.00665603f,0.922665f},{-0.408337f,-0.0262309f,0.912454f},{-0.453578f,-0.0650871f,0.888837f}, -{-0.519956f,-0.122098f,0.845422f},{-0.541517f,-0.140616f,0.828846f},{-0.562725f,-0.158831f,0.811242f}, -{-0.583538f,-0.176707f,0.792627f},{-0.643204f,-0.227954f,0.730976f},{-0.662041f,-0.244132f,0.708591f}, -{-0.697922f,-0.27495f,0.661292f},{-0.714903f,-0.289534f,0.636461f},{-0.761673f,-0.329704f,0.557808f}, -{-0.775794f,-0.341832f,0.530373f},{-0.789149f,-0.353302f,0.502416f},{-0.801723f,-0.364102f,0.473994f}, -{-0.844021f,-0.400431f,0.356769f},{-0.852574f,-0.407777f,0.326857f},{-0.860319f,-0.41443f,0.296814f}, -{-0.867263f,-0.420393f,0.266692f},{-0.873412f,-0.425675f,0.236543f},{-0.878777f,-0.430282f,0.206418f}, -{-0.887205f,-0.437521f,0.146429f},{-0.8903f,-0.440179f,0.116657f},{-0.0673616f,-0.0578556f,0.99605f}, -{-0.0897231f,-0.0770615f,0.992981f},{-0.156257f,-0.134206f,0.978556f},{-0.178186f,-0.153041f,0.972023f}, -{-0.199959f,-0.171741f,0.964635f},{-0.221556f,-0.19029f,0.956401f},{-0.242959f,-0.208673f,0.947326f}, -{-0.285105f,-0.244871f,0.926689f},{-0.305812f,-0.262656f,0.915145f},{-0.32625f,-0.28021f,0.902798f}, -{-0.477988f,-0.410535f,0.776523f},{-0.512046f,-0.439786f,0.737833f},{-0.528407f,-0.453839f,0.717507f}, -{-0.544305f,-0.467493f,0.696551f},{-0.589075f,-0.505946f,0.630087f},{-0.616357f,-0.529378f,0.582978f}, -{-0.653193f,-0.561015f,0.508529f},{-0.684867f,-0.58822f,0.430063f},{-0.694234f,-0.596265f,0.403122f}, -{-0.718647f,-0.617232f,0.320268f},{-0.725531f,-0.623145f,0.292055f},{-0.731777f,-0.62851f,0.263585f}, -{-0.737381f,-0.633323f,0.234884f},{-0.746642f,-0.641277f,0.176888f},{-0.750291f,-0.64441f,0.147645f}, -{-0.75328f,-0.646978f,0.118272f},{-0.755608f,-0.648978f,0.0887941f},{-0.757272f,-0.650407f,0.0592391f}, -{-0.758272f,-0.651265f,0.0296323f},{-6.73779e-016f,-5.78696e-016f,1.0f},{9.28992e-017f,7.97894e-017f,1.0f}, -{7.40149e-017f,1.0f,1.85037e-017f},{-0.104013f,0.994576f,-2.52608e-018f},{0.105163f,0.994455f,-1.75194e-017f}, -{0.310578f,0.950548f,3.401e-017f},{0.194653f,0.980872f,4.88637e-017f},{0.382179f,0.924088f,2.46819e-017f}, -{0.670096f,0.742274f,5.21559e-017f},{0.555293f,0.831655f,1.71547e-017f},{0.50141f,0.86521f,-5.09311e-017f}, -{0.809606f,0.586974f,3.41454e-017f},{0.707075f,0.707139f,-4.75018e-018f},{0.831545f,0.555458f,1.51199e-017f}, -{0.913862f,0.406026f,-1.53953e-017f},{0.978254f,0.207408f,-1.49117e-017f},{0.923954f,0.382504f,8.43939e-018f}, -{1.0f,-1.57282e-016f,0.0f},{0.980825f,0.19489f,8.3164e-018f},{-0.196168f,0.98057f,-3.53809e-017f}, -{-0.308272f,0.951298f,-2.33067e-017f},{-0.384009f,0.923329f,6.85621e-017f},{-0.556611f,0.830773f,-3.33196e-017f}, -{-0.499433f,0.866353f,3.37942e-017f},{-0.707766f,0.706447f,2.28697e-017f},{-0.66887f,0.743379f,5.57946e-017f}, -{-0.808947f,0.587881f,2.83047e-017f},{-0.831851f,0.554999f,-3.91541e-017f},{-0.924075f,0.382212f,2.82894e-017f}, -{-0.913543f,0.406743f,-1.3996e-017f},{-0.98085f,0.194766f,1.44155e-017f},{-0.978165f,0.20783f,1.53825e-017f}, -{-1.0f,1.21431e-016f,0.0f},{-1.0f,1.22587e-016f,0.0f},{-0.475871f,0.197004f,-0.857167f}, -{-0.428277f,0.286082f,-0.857167f},{0.515038f,2.65357e-011f,-0.857167f},{-0.505162f,0.100376f,-0.857167f}, -{-0.515038f,8.7125e-012f,-0.857167f},{-0.36417f,0.364203f,-0.857167f},{-0.285997f,0.428334f,-0.857167f}, -{-0.196837f,0.475941f,-0.857167f},{-0.100254f,0.505186f,-0.857167f},{3.87126e-016f,0.515038f,-0.857167f}, -{0.19778f,0.47555f,-0.857167f},{0.101034f,0.505031f,-0.857167f},{0.364526f,0.363847f,-0.857167f}, -{0.286676f,0.42788f,-0.857167f},{0.475934f,0.196854f,-0.857167f},{0.428435f,0.285846f,-0.857167f}, -{0.515038f,5.63228e-016f,-0.857167f},{0.505175f,0.100312f,-0.857167f},{0.743195f,0.669075f,0.0f}, -{0.866128f,0.499822f,0.0f},{0.808688f,0.588238f,0.0f},{-4.44089e-017f,1.0f,0.0f}, -{-0.156467f,0.987683f,0.0f},{0.89086f,0.454278f,0.0f},{0.940023f,0.341112f,0.0f}, -{0.951024f,0.309116f,0.0f},{0.984831f,0.173514f,0.0f},{0.987686f,0.156452f,0.0f}, -{1.0f,5.55112e-018f,0.0f},{0.706727f,0.707486f,0.0f},{0.587512f,0.809215f,0.0f}, -{0.587575f,0.80917f,0.0f},{0.453641f,0.891185f,0.0f},{0.40683f,0.913504f,0.0f}, -{0.308716f,0.951154f,0.0f},{0.208031f,0.978122f,0.0f},{0.156246f,0.987718f,0.0f}, -{-0.40677f,0.91353f,0.0f},{-0.208006f,0.978127f,0.0f},{-0.309067f,0.95104f,0.0f}, -{-0.707621f,0.706592f,0.0f},{-0.587567f,0.809176f,0.0f},{-0.587746f,0.809045f,0.0f}, -{-0.454023f,0.89099f,0.0f},{-0.939985f,0.341216f,0.0f},{-0.866205f,0.499689f,0.0f}, -{-0.891077f,0.453852f,0.0f},{-0.743115f,0.669164f,0.0f},{-0.809929f,0.586527f,0.0f}, -{-0.987719f,0.156239f,0.0f},{-0.984781f,0.173802f,0.0f},{-0.951116f,0.308833f,0.0f}, -{-1.0f,-2.22045e-016f,0.0f},{-0.104013f,-0.994576f,-1.75012e-017f},{0.105163f,-0.994455f,-1.77626e-017f}, -{0.310578f,-0.950548f,4.93869e-018f},{0.194653f,-0.980872f,8.23072e-018f},{0.382179f,-0.924088f,-3.16302e-018f}, -{0.670096f,-0.742274f,-6.30166e-018f},{0.555293f,-0.831655f,-1.21778e-017f},{0.50141f,-0.86521f,-1.26379e-018f}, -{0.809606f,-0.586974f,-3.60649e-017f},{0.707075f,-0.707139f,4.52306e-017f},{0.831545f,-0.555458f,-2.40794e-017f}, -{0.913862f,-0.406026f,1.43248e-017f},{0.978254f,-0.207408f,2.12095e-017f},{0.923954f,-0.382504f,-2.4773e-017f}, -{0.980825f,-0.19489f,2.03008e-018f},{-0.196168f,-0.98057f,3.17611e-018f},{-0.308272f,-0.951298f,-1.70678e-017f}, -{-0.384009f,-0.923329f,2.2205e-019f},{-0.556611f,-0.830773f,-7.08082e-018f},{-0.499433f,-0.866353f,-8.66378e-019f}, -{-0.707766f,-0.706447f,5.72963e-018f},{-0.66887f,-0.743379f,-1.08295e-017f},{-0.808947f,-0.587881f,-2.8066e-018f}, -{-0.831851f,-0.554999f,-9.62021e-019f},{-0.924075f,-0.382212f,-1.06868e-018f},{-0.913543f,-0.406743f,-2.11299e-018f}, -{-0.98085f,-0.194766f,1.44155e-017f},{-0.978165f,-0.20783f,0.0f},{-1.0f,-2.31296e-018f,0.0f}, -{-0.475871f,-0.197004f,0.857167f},{-0.428277f,-0.286082f,0.857167f},{0.515038f,8.88154e-011f,0.857167f}, -{-0.505162f,-0.100376f,0.857167f},{-0.515038f,-8.71138e-012f,0.857167f},{-0.36417f,-0.364203f,0.857167f}, -{-0.285997f,-0.428334f,0.857167f},{-0.196837f,-0.475941f,0.857167f},{-0.100254f,-0.505186f,0.857167f}, -{-4.12517e-017f,-0.515038f,0.857167f},{0.19778f,-0.47555f,0.857167f},{0.101034f,-0.505031f,0.857167f}, -{0.364526f,-0.363847f,0.857167f},{0.286676f,-0.42788f,0.857167f},{0.475934f,-0.196854f,0.857167f}, -{0.428435f,-0.285846f,0.857167f},{0.515038f,4.59894e-016f,0.857167f},{0.505175f,-0.100312f,0.857167f}, -{0.743195f,-0.669075f,0.0f},{0.866128f,-0.499822f,0.0f},{0.808688f,-0.588238f,0.0f}, -{-0.156467f,-0.987683f,0.0f},{0.89086f,-0.454278f,0.0f},{0.940023f,-0.341112f,0.0f}, -{0.951024f,-0.309116f,0.0f},{0.984831f,-0.173514f,0.0f},{0.987686f,-0.156452f,0.0f}, -{1.0f,-1.30451e-016f,0.0f},{1.0f,-1.33227e-016f,0.0f},{0.706727f,-0.707486f,0.0f}, -{0.587512f,-0.809215f,0.0f},{0.587575f,-0.80917f,0.0f},{0.453641f,-0.891185f,0.0f}, -{0.40683f,-0.913504f,0.0f},{0.308716f,-0.951154f,0.0f},{0.208031f,-0.978122f,0.0f}, -{0.156246f,-0.987718f,0.0f},{-0.40677f,-0.91353f,0.0f},{-0.208006f,-0.978127f,0.0f}, -{-0.309067f,-0.95104f,0.0f},{-0.707621f,-0.706592f,0.0f},{-0.587567f,-0.809176f,0.0f}, -{-0.587746f,-0.809045f,0.0f},{-0.454023f,-0.89099f,0.0f},{-0.939985f,-0.341216f,0.0f}, -{-0.866205f,-0.499689f,0.0f},{-0.891077f,-0.453852f,0.0f},{-0.743115f,-0.669164f,0.0f}, -{-0.809929f,-0.586527f,0.0f},{-0.987719f,-0.156239f,0.0f},{-0.984781f,-0.173802f,0.0f}, -{-0.951116f,-0.308833f,0.0f},{-1.0f,2.22045e-017f,0.0f},{0.866025f,0.5f,1.20185e-017f}, -{-0.866025f,-0.5f,-1.20185e-017f},{-0.866025f,-0.5f,-1.29482e-017f},{0.866025f,-0.5f,-6.93889e-018f}, -{2.77556e-016f,-1.0f,-1.73472e-017f},{3.33067e-016f,-1.0f,-1.73472e-017f},{3.33067e-016f,-1.0f,2.08167e-017f}, -{2.77556e-016f,-1.0f,-6.85322e-019f},{-3.84593e-017f,1.0f,-6.16298e-033f},{-3.84593e-017f,1.0f,0.0f}, -{-1.45717e-016f,0.0f,1.0f},{8.88178e-017f,0.0f,1.0f},{-1.52656e-016f,0.0f,1.0f}, -{-1.59595e-016f,0.0f,1.0f},{1.38778e-016f,0.0f,1.0f},{-0.866025f,0.5f,-2.75508e-017f}, -{-0.866025f,0.5f,-2.61136e-017f},{-0.866025f,0.5f,-1.89555e-018f},{0.987719f,0.156239f,0.0f}, -{1.0f,-1.41553e-016f,0.0f},{0.984848f,0.173419f,0.0f},{0.707621f,0.706592f,0.0f}, -{0.809929f,0.586527f,0.0f},{0.74297f,0.669325f,0.0f},{0.940139f,0.34079f,0.0f}, -{0.891077f,0.453852f,0.0f},{0.951116f,0.308833f,0.0f},{0.207738f,0.978184f,0.0f}, -{-0.000204802f,1.0f,0.0f},{0.156467f,0.987683f,0.0f},{0.587839f,0.808978f,0.0f}, -{0.406907f,0.91347f,0.0f},{0.454023f,0.89099f,0.0f},{-0.588053f,0.808823f,0.0f}, -{-0.453641f,0.891185f,0.0f},{-0.407167f,0.913354f,0.0f},{-0.308716f,0.951154f,0.0f}, -{-0.156246f,0.987718f,0.0f},{-0.208137f,0.9781f,0.0f},{-0.706727f,0.707486f,0.0f}, -{-0.743046f,0.669241f,0.0f},{-0.866091f,0.499886f,0.0f},{-0.89086f,0.454278f,0.0f}, -{-0.808688f,0.588238f,0.0f},{-0.9402f,0.340622f,0.0f},{-0.951024f,0.309116f,0.0f}, -{-0.9849f,0.173126f,0.0f},{-0.987686f,0.156452f,0.0f},{-0.587512f,0.809215f,0.0f}, -{4.44089e-017f,1.0f,0.0f},{0.309067f,0.95104f,0.0f},{0.587746f,0.809045f,0.0f}, -{0.866141f,0.499799f,0.0f},{-4.44089e-016f,0.0f,1.0f},{4.44089e-016f,0.0f,1.0f}, -{8.88178e-016f,0.0f,1.0f},{0.0f,-8.88178e-016f,1.0f},{0.0f,6.66134e-016f,1.0f}, -{0.470509f,0.209488f,0.857167f},{0.416639f,0.302781f,0.857167f},{-0.515038f,-9.57464e-011f,0.857167f}, -{0.503792f,0.107041f,0.857167f},{0.515038f,8.71144e-012f,0.857167f},{0.344494f,0.382869f,0.857167f}, -{0.257227f,0.446205f,0.857167f},{0.158772f,0.489955f,0.857167f},{0.0535708f,0.512244f,0.857167f}, -{-0.054163f,0.512182f,0.857167f},{-0.258245f,0.445616f,0.857167f},{-0.159959f,0.489568f,0.857167f}, -{-0.416978f,0.302314f,0.857167f},{-0.345125f,0.382299f,0.857167f},{-0.503838f,0.106823f,0.857167f}, -{-0.470674f,0.209119f,0.857167f},{-0.515038f,-3.74123e-016f,0.857167f},{1.0f,-1.29526e-016f,0.0f}, -{0.978165f,0.20783f,-8.77813e-017f},{0.978254f,0.207408f,1.53513e-017f},{0.50141f,0.86521f,6.40384e-017f}, -{0.670096f,0.742274f,7.43956e-017f},{0.66887f,0.743379f,-5.51477e-018f},{0.809606f,0.586974f,-5.99229e-017f}, -{0.913862f,0.406026f,3.0052e-017f},{0.913543f,0.406743f,1.50525e-017f},{0.105163f,0.994455f,-2.0347e-017f}, -{0.104013f,0.994576f,1.92463e-018f},{-0.104013f,0.994576f,-5.52101e-017f},{0.499433f,0.866353f,-3.20615e-017f}, -{0.308272f,0.951298f,1.76026e-017f},{0.310578f,0.950548f,5.2766e-017f},{-0.310578f,0.950548f,-2.94305e-017f}, -{-0.50141f,0.86521f,1.66462e-017f},{-0.499433f,0.866353f,2.40461e-017f},{-0.308272f,0.951298f,5.70418e-018f}, -{-0.105163f,0.994455f,1.64552e-017f},{-0.670096f,0.742274f,-3.4671e-017f},{-0.809606f,0.586974f,3.04307e-018f}, -{-0.808947f,0.587881f,1.56371e-017f},{-0.66887f,0.743379f,-5.77706e-017f},{-0.913543f,0.406743f,8.0545e-018f}, -{-0.913862f,0.406026f,1.26789e-017f},{-0.978254f,0.207408f,-9.04189e-018f},{-0.978165f,0.20783f,-1.02592e-017f}, -{-1.0f,-2.89121e-019f,0.0f},{-1.0f,2.31296e-018f,0.0f},{0.808947f,0.587881f,-2.1756e-017f}, -{0.987719f,-0.156239f,0.0f},{0.984848f,-0.173419f,0.0f},{0.707621f,-0.706592f,0.0f}, -{0.809929f,-0.586527f,0.0f},{0.743022f,-0.669267f,0.0f},{0.940139f,-0.34079f,0.0f}, -{0.891077f,-0.453852f,0.0f},{0.951116f,-0.308833f,0.0f},{0.208043f,-0.97812f,0.0f}, -{0.000184774f,-1.0f,0.0f},{0.156467f,-0.987683f,0.0f},{0.587964f,-0.808887f,0.0f}, -{0.40712f,-0.913375f,0.0f},{0.454023f,-0.89099f,0.0f},{-0.587927f,-0.808914f,0.0f}, -{-0.453641f,-0.891185f,0.0f},{-0.406953f,-0.913449f,0.0f},{-0.308716f,-0.951154f,0.0f}, -{-0.156246f,-0.987718f,0.0f},{-0.207832f,-0.978164f,0.0f},{-0.706727f,-0.707486f,0.0f}, -{-0.742993f,-0.669299f,0.0f},{-0.866091f,-0.499886f,0.0f},{-0.89086f,-0.454278f,0.0f}, -{-0.808688f,-0.588238f,0.0f},{-0.9402f,-0.340622f,0.0f},{-0.951024f,-0.309116f,0.0f}, -{-0.9849f,-0.173126f,0.0f},{-1.0f,-2.88658e-016f,0.0f},{-0.987686f,-0.156452f,0.0f}, -{-1.0f,-2.66454e-016f,0.0f},{-0.587512f,-0.809215f,0.0f},{8.88178e-017f,-1.0f,0.0f}, -{0.309067f,-0.95104f,0.0f},{0.587746f,-0.809045f,0.0f},{0.866141f,-0.499799f,0.0f}, -{-0.0f,2.77556e-017f,-1.0f},{-0.0f,1.38778e-017f,-1.0f},{0.0f,-2.77556e-017f,-1.0f}, -{2.77556e-017f,-0.0f,-1.0f},{-2.43605e-017f,0.0f,-1.0f},{-0.0f,2.08167e-017f,-1.0f}, -{-0.0f,5.55112e-017f,-1.0f},{-0.0f,2.07242e-017f,-1.0f},{0.470509f,-0.209488f,-0.857167f}, -{0.416639f,-0.302781f,-0.857167f},{-0.515038f,-1.96047e-011f,-0.857167f},{0.503792f,-0.107041f,-0.857167f}, -{0.515038f,-8.71228e-012f,-0.857167f},{0.344494f,-0.382869f,-0.857167f},{0.257227f,-0.446205f,-0.857167f}, -{0.158772f,-0.489955f,-0.857167f},{0.0535708f,-0.512244f,-0.857167f},{-0.054163f,-0.512182f,-0.857167f}, -{-0.258245f,-0.445616f,-0.857167f},{-0.159959f,-0.489568f,-0.857167f},{-0.416978f,-0.302314f,-0.857167f}, -{-0.345125f,-0.382299f,-0.857167f},{-0.503838f,-0.106823f,-0.857167f},{-0.470674f,-0.209119f,-0.857167f}, -{-0.515038f,-5.77524e-016f,-0.857167f},{0.978165f,-0.20783f,7.23987e-017f},{0.978254f,-0.207408f,0.0f}, -{0.50141f,-0.86521f,1.85559e-017f},{0.670096f,-0.742274f,-2.21274e-017f},{0.66887f,-0.743379f,-2.47532e-017f}, -{0.809606f,-0.586974f,5.99229e-017f},{0.913862f,-0.406026f,0.0f},{0.913543f,-0.406743f,0.0f}, -{0.105163f,-0.994455f,2.22929e-017f},{0.104013f,-0.994576f,1.84034e-017f},{-0.104013f,-0.994576f,-1.64787e-017f}, -{0.499433f,-0.866353f,0.0f},{0.308272f,-0.951298f,1.76026e-017f},{0.310578f,-0.950548f,1.75887e-017f}, -{-0.310578f,-0.950548f,0.0f},{-0.50141f,-0.86521f,8.0048e-018f},{-0.499433f,-0.866353f,-3.39469e-018f}, -{-0.308272f,-0.951298f,8.80128e-018f},{-0.105163f,-0.994455f,2.22929e-017f},{-0.670096f,-0.742274f,-3.33889e-019f}, -{-0.809606f,-0.586974f,-1.35765e-018f},{-0.808947f,-0.587881f,-1.01698e-018f},{-0.66887f,-0.743379f,1.65048e-017f}, -{-0.913543f,-0.406743f,-2.8802e-018f},{-0.913862f,-0.406026f,-7.51299e-018f},{-0.978254f,-0.207408f,3.91078e-018f}, -{-0.978165f,-0.20783f,2.24517e-019f},{-1.0f,1.24033e-016f,0.0f},{-1.0f,1.249e-016f,0.0f}, -{0.808947f,-0.587881f,0.0f},{0.0580986f,-0.998311f,1.85037e-017f},{0.161621f,-0.986853f,-2.52608e-018f}, -{-0.047209f,-0.998885f,-1.75194e-017f},{-0.254828f,-0.966986f,3.401e-017f},{-0.137337f,-0.990524f,4.88637e-017f}, -{-0.327845f,-0.944731f,2.46819e-017f},{-0.625839f,-0.779952f,5.21559e-017f},{-0.506037f,-0.862512f,1.71547e-017f}, -{-0.450295f,-0.89288f,-5.09311e-017f},{-0.774136f,-0.633019f,3.41454e-017f},{-0.664797f,-0.747024f,-4.75018e-018f}, -{-0.797869f,-0.602831f,1.51199e-017f},{-0.888728f,-0.458434f,-1.53953e-017f},{-0.964552f,-0.263893f,-1.49117e-017f}, -{-0.90017f,-0.435538f,8.43939e-018f},{-0.998311f,-0.0580986f,0.0f},{-0.967845f,-0.251545f,8.3164e-018f}, -{0.252807f,-0.967517f,-3.53809e-017f},{0.36302f,-0.931781f,-2.33067e-017f},{0.437005f,-0.899459f,6.85621e-017f}, -{0.603937f,-0.797032f,-3.33196e-017f},{0.548923f,-0.835873f,3.37942e-017f},{0.747614f,-0.664134f,2.28697e-017f}, -{0.71093f,-0.703263f,5.57946e-017f},{0.841736f,-0.539889f,2.83047e-017f},{0.862691f,-0.505732f,-3.91541e-017f}, -{0.94472f,-0.327879f,2.82894e-017f},{0.935631f,-0.35298f,-1.3996e-017f},{0.990509f,-0.137451f,1.44155e-017f}, -{0.988587f,-0.150649f,1.53825e-017f},{0.998311f,0.0580986f,0.0f},{0.486513f,-0.169024f,-0.857167f}, -{0.444175f,-0.260716f,-0.857167f},{-0.514168f,-0.029923f,-0.857167f},{0.510141f,-0.070857f,-0.857167f}, -{0.514168f,0.029923f,-0.857167f},{0.384715f,-0.34243f,-0.857167f},{0.310399f,-0.410994f,-0.857167f}, -{0.224156f,-0.463701f,-0.857167f},{0.129435f,-0.498508f,-0.857167f},{0.029923f,-0.514168f,-0.857167f}, -{-0.169817f,-0.486237f,-0.857167f},{-0.071522f,-0.510048f,-0.857167f},{-0.342771f,-0.384411f,-0.857167f}, -{-0.261332f,-0.443813f,-0.857167f},{-0.463693f,-0.224172f,-0.857167f},{-0.411104f,-0.310254f,-0.857167f}, -{-0.498494f,-0.129492f,-0.857167f},{-0.703068f,-0.711123f,0.0f},{-0.835626f,-0.549298f,0.0f}, -{-0.773146f,-0.634228f,0.0f},{0.0580986f,-0.998311f,0.0f},{0.213586f,-0.976924f,0.0f}, -{-0.862963f,-0.505268f,0.0f},{-0.918617f,-0.39515f,0.0f},{-0.931459f,-0.363847f,0.0f}, -{-0.973087f,-0.230439f,0.0f},{-0.976928f,-0.213571f,0.0f},{-0.66443f,-0.747351f,0.0f}, -{-0.539506f,-0.841982f,0.0f},{-0.539571f,-0.84194f,0.0f},{-0.401098f,-0.916035f,0.0f}, -{-0.353069f,-0.935597f,0.0f},{-0.252934f,-0.967484f,0.0f},{-0.150852f,-0.988556f,0.0f}, -{-0.0985972f,-0.995127f,0.0f},{0.459158f,-0.888355f,0.0f},{0.264483f,-0.96439f,0.0f}, -{0.363799f,-0.931478f,0.0f},{0.747478f,-0.664287f,0.0f},{0.633586f,-0.773672f,0.0f}, -{0.633758f,-0.773531f,0.0f},{0.505021f,-0.863107f,0.0f},{0.958221f,-0.286028f,0.0f}, -{0.893773f,-0.44852f,0.0f},{0.91594f,-0.401315f,0.0f},{0.780737f,-0.62486f,0.0f}, -{0.842638f,-0.538481f,0.0f},{0.995128f,-0.0985905f,0.0f},{0.993215f,-0.116295f,0.0f}, -{0.967452f,-0.253053f,0.0f},{-0.0580986f,0.998311f,0.0f},{0.0460542f,0.998939f,-1.75012e-017f}, -{-0.162762f,0.986665f,-1.77626e-017f},{-0.365279f,0.930898f,4.93869e-018f},{-0.251312f,0.967906f,8.23072e-018f}, -{-0.435222f,0.900323f,-3.16302e-018f},{-0.71209f,0.702089f,-6.30166e-018f},{-0.602673f,0.797988f,-1.21778e-017f}, -{-0.55083f,0.834617f,-1.26379e-018f},{-0.842341f,0.538945f,-3.60649e-017f},{-0.746964f,0.664864f,4.52306e-017f}, -{-0.862411f,0.506208f,-2.40794e-017f},{-0.935907f,0.352246f,1.43248e-017f},{-0.988652f,0.150223f,2.12095e-017f}, -{-0.944616f,0.328178f,-2.4773e-017f},{-0.990491f,0.137576f,2.03008e-018f},{0.138867f,0.990311f,3.17611e-018f}, -{0.252482f,0.967602f,-1.70678e-017f},{0.329717f,0.94408f,2.2205e-019f},{0.507404f,0.861708f,-7.08082e-018f}, -{0.448255f,0.893906f,-8.66378e-019f},{0.665526f,0.746374f,5.72963e-018f},{0.624551f,0.780984f,-1.08295e-017f}, -{0.773426f,0.633887f,-2.8066e-018f},{0.798201f,0.602391f,-9.62021e-019f},{0.900308f,0.435254f,-1.06868e-018f}, -{0.888368f,0.459131f,-2.11299e-018f},{0.967877f,0.251423f,1.44155e-017f},{0.964438f,0.264309f,0.0f}, -{0.463622f,0.224319f,0.857167f},{0.410933f,0.310481f,0.857167f},{-0.514168f,-0.029923f,0.857167f}, -{0.498477f,0.129555f,0.857167f},{0.514168f,0.029923f,0.857167f},{0.342396f,0.384746f,0.857167f}, -{0.260628f,0.444227f,0.857167f},{0.168853f,0.486573f,0.857167f},{0.070734f,0.510158f,0.857167f}, -{-0.029923f,0.514168f,0.857167f},{-0.225074f,0.463256f,0.857167f},{-0.130205f,0.498308f,0.857167f}, -{-0.385049f,0.342054f,0.857167f},{-0.311051f,0.410502f,0.857167f},{-0.486567f,0.16887f,0.857167f}, -{-0.444319f,0.260471f,0.857167f},{-0.51015f,0.0707922f,0.857167f},{-0.780812f,0.624766f,0.0f}, -{-0.893704f,0.448657f,0.0f},{-0.841497f,0.540261f,0.0f},{0.0988201f,0.995105f,0.0f}, -{-0.915748f,0.401752f,0.0f},{-0.958253f,0.285922f,0.0f},{-0.967377f,0.253341f,0.0f}, -{-0.993249f,0.116004f,0.0f},{-0.995107f,0.0988045f,0.0f},{-0.746637f,0.665231f,0.0f}, -{-0.633534f,0.773715f,0.0f},{-0.633594f,0.773666f,0.0f},{-0.504651f,0.863323f,0.0f}, -{-0.459216f,0.888325f,0.0f},{-0.363455f,0.931612f,0.0f},{-0.264507f,0.964384f,0.0f}, -{-0.213367f,0.976972f,0.0f},{0.353009f,0.93562f,0.0f},{0.150827f,0.98856f,0.0f}, -{0.25329f,0.96739f,0.0f},{0.665374f,0.74651f,0.0f},{0.539562f,0.841946f,0.0f}, -{0.539749f,0.841826f,0.0f},{0.401491f,0.915863f,0.0f},{0.918573f,0.395251f,0.0f}, -{0.83571f,0.54917f,0.0f},{0.863204f,0.504856f,0.0f},{0.702982f,0.711208f,0.0f}, -{0.774485f,0.632592f,0.0f},{0.976973f,0.213361f,0.0f},{0.973019f,0.230723f,0.0f}, -{0.931567f,0.36357f,0.0f},{-0.835513f,-0.54947f,1.20185e-017f},{0.835513f,0.54947f,-1.20185e-017f}, -{0.835513f,0.54947f,-1.29482e-017f},{0.835513f,0.54947f,0.0f},{-0.893612f,0.448841f,0.0f}, -{-0.893612f,0.448841f,-6.93889e-018f},{-0.0580986f,0.998311f,-1.73472e-017f},{-0.0580986f,0.998311f,2.08167e-017f}, -{-0.0580986f,0.998311f,-6.85322e-019f},{0.0580986f,-0.998311f,-6.16298e-033f},{-2.2167e-016f,-1.29005e-017f,1.0f}, -{1.66252e-016f,9.67536e-018f,1.0f},{1.10835e-016f,6.45024e-018f,1.0f},{-1.10835e-016f,-6.45024e-018f,1.0f}, -{-8.31261e-017f,-4.83768e-018f,1.0f},{1.45471e-016f,8.46594e-018f,1.0f},{-6.92717e-018f,-4.0314e-019f,1.0f}, -{-8.86678e-017f,-5.16019e-018f,1.0f},{-2.77087e-017f,-1.61256e-018f,1.0f},{1.52398e-016f,8.86908e-018f,1.0f}, -{1.59325e-016f,9.27222e-018f,1.0f},{-1.38543e-016f,-8.0628e-018f,1.0f},{-5.54174e-017f,-3.22512e-018f,1.0f}, -{2.2167e-016f,1.29005e-017f,1.0f},{-1.66252e-016f,-9.67536e-018f,1.0f},{0.893612f,-0.448841f,-2.75508e-017f}, -{0.893612f,-0.448841f,-2.61136e-017f},{0.893612f,-0.448841f,-1.89555e-018f},{-0.976973f,-0.213361f,0.0f}, -{-0.973109f,-0.230345f,0.0f},{-0.665374f,-0.74651f,0.0f},{-0.774485f,-0.632592f,0.0f}, -{-0.702828f,-0.71136f,0.0f},{-0.918752f,-0.394835f,0.0f},{-0.863204f,-0.504856f,0.0f}, -{-0.931567f,-0.36357f,0.0f},{-0.150556f,-0.988601f,0.0f},{0.058303f,-0.998299f,0.0f}, -{-0.0988201f,-0.995105f,0.0f},{-0.539845f,-0.841764f,0.0f},{-0.353148f,-0.935567f,0.0f}, -{-0.401491f,-0.915863f,0.0f},{0.634051f,-0.773291f,0.0f},{0.504651f,-0.863323f,0.0f}, -{0.459544f,-0.888155f,0.0f},{0.363455f,-0.931612f,0.0f},{0.213367f,-0.976972f,0.0f}, -{0.264611f,-0.964355f,0.0f},{0.746637f,-0.665231f,0.0f},{0.780673f,-0.62494f,0.0f}, -{0.893671f,-0.448723f,0.0f},{0.915748f,-0.401752f,0.0f},{0.841497f,-0.540261f,0.0f}, -{0.958402f,-0.285423f,0.0f},{0.967377f,-0.253341f,0.0f},{0.993294f,-0.115612f,0.0f}, -{0.995107f,-0.0988045f,0.0f},{0.633534f,-0.773715f,0.0f},{-0.25329f,-0.96739f,0.0f}, -{-0.539749f,-0.841826f,0.0f},{-0.835641f,-0.549276f,0.0f},{-1.29005e-017f,2.2167e-016f,1.0f}, -{1.93507e-017f,-3.32504e-016f,1.0f},{1.29005e-017f,-2.2167e-016f,1.0f},{4.43339e-016f,2.5801e-017f,1.0f}, -{-4.43339e-016f,-2.5801e-017f,1.0f},{-8.86678e-016f,-5.16019e-017f,1.0f},{-2.5801e-017f,4.43339e-016f,1.0f}, -{-5.16019e-017f,8.86678e-016f,1.0f},{3.87014e-017f,-6.65009e-016f,1.0f},{2.5801e-017f,-4.43339e-016f,1.0f}, -{-0.457544f,-0.23647f,0.857167f},{-0.398344f,-0.326476f,0.857167f},{-0.496722f,-0.136129f,0.857167f}, -{-0.321668f,-0.402236f,0.857167f},{-0.230869f,-0.460395f,0.857167f},{-0.130038f,-0.498352f,0.857167f}, -{-0.0237196f,-0.514492f,0.857167f},{0.0838285f,-0.50817f,0.857167f},{0.283699f,-0.42986f,0.857167f}, -{0.188132f,-0.479448f,0.857167f},{0.433838f,-0.277577f,0.857167f},{0.366753f,-0.361602f,0.857167f}, -{0.509194f,-0.0773705f,0.857167f},{0.482028f,-0.18142f,0.857167f},{-0.964438f,-0.264309f,-8.77813e-017f}, -{-0.964552f,-0.263893f,1.53513e-017f},{-0.450295f,-0.89288f,6.40384e-017f},{-0.625839f,-0.779952f,7.43956e-017f}, -{-0.624551f,-0.780984f,-5.51477e-018f},{-0.774136f,-0.633019f,-5.99229e-017f},{-0.888728f,-0.458434f,3.0052e-017f}, -{-0.888368f,-0.459131f,1.50525e-017f},{-0.047209f,-0.998885f,-2.0347e-017f},{-0.0460542f,-0.998939f,1.92463e-018f}, -{0.161621f,-0.986853f,-5.52101e-017f},{-0.448255f,-0.893906f,-3.20615e-017f},{-0.252482f,-0.967602f,1.76026e-017f}, -{-0.254827f,-0.966987f,5.2766e-017f},{0.365279f,-0.930898f,-2.94305e-017f},{0.55083f,-0.834617f,1.66462e-017f}, -{0.548923f,-0.835873f,2.40461e-017f},{0.36302f,-0.931781f,5.70418e-018f},{0.162762f,-0.986665f,1.64552e-017f}, -{0.71209f,-0.702089f,-3.4671e-017f},{0.842341f,-0.538945f,3.04307e-018f},{0.841736f,-0.539889f,1.56371e-017f}, -{0.71093f,-0.703263f,-5.77706e-017f},{0.935631f,-0.35298f,8.0545e-018f},{0.935907f,-0.352246f,1.26789e-017f}, -{0.988652f,-0.150223f,-9.04189e-018f},{0.988587f,-0.150649f,-1.02592e-017f},{-0.773426f,-0.633887f,-2.1756e-017f}, -{-0.995128f,0.0985905f,0.0f},{-0.99326f,0.115908f,0.0f},{-0.747478f,0.664287f,0.0f}, -{-0.842638f,0.538481f,0.0f},{-0.78065f,0.624968f,0.0f},{-0.958351f,0.285594f,0.0f}, -{-0.91594f,0.401315f,0.0f},{-0.967452f,0.253053f,0.0f},{-0.264519f,0.964381f,0.0f}, -{-0.058283f,0.9983f,0.0f},{-0.213586f,0.976924f,0.0f},{-0.633966f,0.773361f,0.0f}, -{-0.459498f,0.888179f,0.0f},{-0.505021f,0.863107f,0.0f},{0.539937f,0.841705f,0.0f}, -{0.401098f,0.916035f,0.0f},{0.353196f,0.935549f,0.0f},{0.252934f,0.967484f,0.0f}, -{0.0985972f,0.995127f,0.0f},{0.150651f,0.988587f,0.0f},{0.66443f,0.747351f,0.0f}, -{0.702853f,0.711335f,0.0f},{0.835585f,0.54936f,0.0f},{0.862963f,0.505268f,0.0f}, -{0.773146f,0.634228f,0.0f},{0.918822f,0.394671f,0.0f},{0.931459f,0.363847f,0.0f}, -{0.973178f,0.230054f,0.0f},{0.976928f,0.213571f,0.0f},{0.539506f,0.841982f,0.0f}, -{-0.363799f,0.931478f,0.0f},{-0.633758f,0.773531f,0.0f},{-0.893716f,0.448633f,0.0f}, -{1.61256e-018f,-2.77087e-017f,-1.0f},{8.0628e-019f,-1.38543e-017f,-1.0f},{-8.0628e-019f,1.38543e-017f,-1.0f}, -{-1.61256e-018f,2.77087e-017f,-1.0f},{1.38543e-017f,8.0628e-019f,-1.0f},{5.54174e-017f,3.22512e-018f,-1.0f}, -{2.07815e-017f,1.20942e-018f,-1.0f},{-2.77087e-017f,-1.61256e-018f,-1.0f},{2.43194e-017f,1.41531e-018f,-1.0f}, -{1.20942e-018f,-2.07815e-017f,-1.0f},{3.22512e-018f,-5.54174e-017f,-1.0f},{1.20404e-018f,-2.06892e-017f,-1.0f}, -{-0.481885f,0.181798f,-0.857167f},{-0.433526f,0.278063f,-0.857167f},{-0.50916f,0.0775901f,-0.857167f}, -{-0.366156f,0.362207f,-0.857167f},{-0.282716f,0.430506f,-0.857167f},{-0.186969f,0.479903f,-0.857167f}, -{-0.083241f,0.508267f,-0.857167f},{0.0243144f,0.514464f,-0.857167f},{0.231919f,0.459867f,-0.857167f}, -{0.131246f,0.498035f,-0.857167f},{0.39871f,0.326029f,-0.857167f},{0.322331f,0.401705f,-0.857167f}, -{0.496781f,0.135915f,-0.857167f},{0.457729f,0.236111f,-0.857167f},{-0.988587f,0.150649f,7.23987e-017f}, -{-0.988652f,0.150223f,0.0f},{-0.55083f,0.834617f,1.85559e-017f},{-0.71209f,0.702089f,-2.21274e-017f}, -{-0.71093f,0.703263f,-2.47532e-017f},{-0.842341f,0.538945f,5.99229e-017f},{-0.935907f,0.352246f,0.0f}, -{-0.935631f,0.35298f,0.0f},{-0.162762f,0.986665f,2.22929e-017f},{-0.161621f,0.986853f,1.84034e-017f}, -{0.0460541f,0.998939f,-1.64787e-017f},{-0.548923f,0.835873f,0.0f},{-0.36302f,0.931781f,1.76026e-017f}, -{-0.365278f,0.930898f,1.75887e-017f},{0.254828f,0.966986f,0.0f},{0.450295f,0.89288f,8.0048e-018f}, -{0.448255f,0.893906f,-3.39469e-018f},{0.252482f,0.967602f,8.80128e-018f},{0.047209f,0.998885f,2.22929e-017f}, -{0.625839f,0.779952f,-3.33889e-019f},{0.774136f,0.633019f,-1.35765e-018f},{0.773426f,0.633887f,-1.01698e-018f}, -{0.624551f,0.780984f,1.65048e-017f},{0.888368f,0.459131f,-2.8802e-018f},{0.888728f,0.458434f,-7.51299e-018f}, -{0.964552f,0.263893f,3.91078e-018f},{0.964438f,0.264309f,2.24517e-019f},{-0.841736f,0.539889f,0.0f}, -{-7.40149e-017f,-1.0f,1.85037e-017f},{0.104013f,-0.994576f,-2.52608e-018f},{-0.105163f,-0.994455f,-1.75194e-017f}, -{-0.310578f,-0.950548f,3.401e-017f},{-0.194653f,-0.980872f,4.88637e-017f},{-0.382179f,-0.924088f,2.46819e-017f}, -{-0.670096f,-0.742274f,5.21559e-017f},{-0.555293f,-0.831655f,1.71547e-017f},{-0.50141f,-0.86521f,-5.09311e-017f}, -{-0.809606f,-0.586974f,3.41454e-017f},{-0.707075f,-0.707139f,-4.75018e-018f},{-0.831545f,-0.555458f,1.51199e-017f}, -{-0.913862f,-0.406026f,-1.53953e-017f},{-0.978254f,-0.207408f,-1.49117e-017f},{-0.923954f,-0.382504f,8.43939e-018f}, -{-0.980825f,-0.19489f,8.3164e-018f},{0.196168f,-0.98057f,-3.53809e-017f},{0.308272f,-0.951298f,-2.33067e-017f}, -{0.384009f,-0.923329f,6.85621e-017f},{0.556611f,-0.830773f,-3.33196e-017f},{0.499433f,-0.866353f,3.37942e-017f}, -{0.707766f,-0.706447f,2.28697e-017f},{0.66887f,-0.743379f,5.57946e-017f},{0.808947f,-0.587881f,2.83047e-017f}, -{0.831851f,-0.554999f,-3.91541e-017f},{0.924075f,-0.382212f,2.82894e-017f},{0.913543f,-0.406743f,-1.3996e-017f}, -{0.98085f,-0.194766f,1.44155e-017f},{0.978165f,-0.20783f,1.53825e-017f},{1.0f,-1.21431e-016f,0.0f}, -{1.0f,-1.22587e-016f,0.0f},{0.475871f,-0.197004f,-0.857167f},{0.428277f,-0.286082f,-0.857167f}, -{-0.515038f,-2.65357e-011f,-0.857167f},{0.505162f,-0.100376f,-0.857167f},{0.515038f,-8.7125e-012f,-0.857167f}, -{0.36417f,-0.364203f,-0.857167f},{0.285997f,-0.428334f,-0.857167f},{0.196837f,-0.475941f,-0.857167f}, -{0.100254f,-0.505186f,-0.857167f},{-3.87126e-016f,-0.515038f,-0.857167f},{-0.19778f,-0.47555f,-0.857167f}, -{-0.101034f,-0.505031f,-0.857167f},{-0.364526f,-0.363847f,-0.857167f},{-0.286676f,-0.42788f,-0.857167f}, -{-0.475934f,-0.196854f,-0.857167f},{-0.428435f,-0.285846f,-0.857167f},{-0.515038f,-5.63228e-016f,-0.857167f}, -{-0.505175f,-0.100312f,-0.857167f},{-0.743195f,-0.669075f,0.0f},{-0.866128f,-0.499822f,0.0f}, -{-0.940023f,-0.341112f,0.0f},{-0.984831f,-0.173514f,0.0f},{-1.0f,-5.55112e-018f,0.0f}, -{-0.587575f,-0.80917f,0.0f},{-0.40683f,-0.913504f,0.0f},{-0.208031f,-0.978122f,0.0f}, -{0.40677f,-0.91353f,0.0f},{0.208006f,-0.978127f,0.0f},{0.587567f,-0.809176f,0.0f}, -{0.939985f,-0.341216f,0.0f},{0.866205f,-0.499689f,0.0f},{0.743115f,-0.669164f,0.0f}, -{0.984781f,-0.173802f,0.0f},{1.0f,1.77636e-016f,0.0f},{1.0f,2.22045e-016f,0.0f}, -{0.104013f,0.994576f,-1.75012e-017f},{-0.105163f,0.994455f,-1.77626e-017f},{-0.310578f,0.950548f,4.93869e-018f}, -{-0.194653f,0.980872f,8.23072e-018f},{-0.382179f,0.924088f,-3.16302e-018f},{-0.670096f,0.742274f,-6.30166e-018f}, -{-0.555293f,0.831655f,-1.21778e-017f},{-0.50141f,0.86521f,-1.26379e-018f},{-0.809606f,0.586974f,-3.60649e-017f}, -{-0.707075f,0.707139f,4.52306e-017f},{-0.831545f,0.555458f,-2.40794e-017f},{-0.913862f,0.406026f,1.43248e-017f}, -{-0.978254f,0.207408f,2.12095e-017f},{-0.923954f,0.382504f,-2.4773e-017f},{-1.0f,-1.57282e-016f,0.0f}, -{-0.980825f,0.19489f,2.03008e-018f},{0.196168f,0.98057f,3.17611e-018f},{0.308272f,0.951298f,-1.70678e-017f}, -{0.384009f,0.923329f,2.2205e-019f},{0.556611f,0.830773f,-7.08082e-018f},{0.499433f,0.866353f,-8.66378e-019f}, -{0.707766f,0.706447f,5.72963e-018f},{0.66887f,0.743379f,-1.08295e-017f},{0.808947f,0.587881f,-2.8066e-018f}, -{0.831851f,0.554999f,-9.62021e-019f},{0.924075f,0.382212f,-1.06868e-018f},{0.913543f,0.406743f,-2.11299e-018f}, -{0.98085f,0.194766f,1.44155e-017f},{0.978165f,0.20783f,0.0f},{1.0f,2.31296e-018f,0.0f}, -{0.475871f,0.197004f,0.857167f},{0.428277f,0.286082f,0.857167f},{-0.515038f,-8.88154e-011f,0.857167f}, -{0.505162f,0.100376f,0.857167f},{0.515038f,8.71138e-012f,0.857167f},{0.36417f,0.364203f,0.857167f}, -{0.285997f,0.428334f,0.857167f},{0.196837f,0.475941f,0.857167f},{0.100254f,0.505186f,0.857167f}, -{4.12517e-017f,0.515038f,0.857167f},{-0.19778f,0.47555f,0.857167f},{-0.101034f,0.505031f,0.857167f}, -{-0.364526f,0.363847f,0.857167f},{-0.286676f,0.42788f,0.857167f},{-0.475934f,0.196854f,0.857167f}, -{-0.428435f,0.285846f,0.857167f},{-0.515038f,-4.59894e-016f,0.857167f},{-0.505175f,0.100312f,0.857167f}, -{-0.743195f,0.669075f,0.0f},{-0.866128f,0.499822f,0.0f},{-0.940023f,0.341112f,0.0f}, -{-0.984831f,0.173514f,0.0f},{-1.0f,1.30451e-016f,0.0f},{-1.0f,1.33227e-016f,0.0f}, -{-0.587575f,0.80917f,0.0f},{-0.40683f,0.913504f,0.0f},{-0.208031f,0.978122f,0.0f}, -{0.40677f,0.91353f,0.0f},{0.208006f,0.978127f,0.0f},{0.587567f,0.809176f,0.0f}, -{0.939985f,0.341216f,0.0f},{0.866205f,0.499689f,0.0f},{0.743115f,0.669164f,0.0f}, -{0.984781f,0.173802f,0.0f},{1.0f,-2.22045e-017f,0.0f},{-0.866025f,-0.5f,1.20185e-017f}, -{0.866025f,0.5f,-1.20185e-017f},{0.866025f,0.5f,-1.29482e-017f},{-0.866025f,0.5f,-6.93889e-018f}, -{-2.77556e-016f,1.0f,-1.73472e-017f},{-3.33067e-016f,1.0f,-1.73472e-017f},{-3.33067e-016f,1.0f,2.08167e-017f}, -{-2.77556e-016f,1.0f,-6.85322e-019f},{3.84593e-017f,-1.0f,-6.16298e-033f},{3.84593e-017f,-1.0f,0.0f}, -{1.45717e-016f,0.0f,1.0f},{-8.88178e-017f,0.0f,1.0f},{1.52656e-016f,0.0f,1.0f}, -{1.59595e-016f,0.0f,1.0f},{0.866025f,-0.5f,-2.75508e-017f},{0.866025f,-0.5f,-2.61136e-017f}, -{0.866025f,-0.5f,-1.89555e-018f},{-1.0f,1.41553e-016f,0.0f},{-0.984848f,-0.173419f,0.0f}, -{-0.74297f,-0.669325f,0.0f},{-0.940139f,-0.34079f,0.0f},{-0.207738f,-0.978184f,0.0f}, -{0.000204802f,-1.0f,0.0f},{-0.587839f,-0.808978f,0.0f},{-0.406907f,-0.91347f,0.0f}, -{0.588053f,-0.808823f,0.0f},{0.407167f,-0.913354f,0.0f},{0.208137f,-0.9781f,0.0f}, -{0.743046f,-0.669241f,0.0f},{0.866091f,-0.499886f,0.0f},{0.9402f,-0.340622f,0.0f}, -{0.9849f,-0.173126f,0.0f},{-4.44089e-017f,-1.0f,0.0f},{-0.866141f,-0.499799f,0.0f}, -{0.0f,-3.33067e-016f,1.0f},{-8.88178e-016f,0.0f,1.0f},{0.0f,8.88178e-016f,1.0f}, -{0.0f,-6.66134e-016f,1.0f},{-0.470509f,-0.209488f,0.857167f},{-0.416639f,-0.302781f,0.857167f}, -{0.515038f,9.57464e-011f,0.857167f},{-0.503792f,-0.107041f,0.857167f},{-0.515038f,-8.71144e-012f,0.857167f}, -{-0.344494f,-0.382869f,0.857167f},{-0.257227f,-0.446205f,0.857167f},{-0.158772f,-0.489955f,0.857167f}, -{-0.0535708f,-0.512244f,0.857167f},{0.054163f,-0.512182f,0.857167f},{0.258245f,-0.445616f,0.857167f}, -{0.159959f,-0.489568f,0.857167f},{0.416978f,-0.302314f,0.857167f},{0.345125f,-0.382299f,0.857167f}, -{0.503838f,-0.106823f,0.857167f},{0.470674f,-0.209119f,0.857167f},{0.515038f,3.74123e-016f,0.857167f}, -{-1.0f,1.29526e-016f,0.0f},{-0.978165f,-0.20783f,-8.77813e-017f},{-0.978254f,-0.207408f,1.53513e-017f}, -{-0.50141f,-0.86521f,6.40384e-017f},{-0.670096f,-0.742274f,7.43956e-017f},{-0.66887f,-0.743379f,-5.51477e-018f}, -{-0.809606f,-0.586974f,-5.99229e-017f},{-0.913862f,-0.406026f,3.0052e-017f},{-0.913543f,-0.406743f,1.50525e-017f}, -{-0.105163f,-0.994455f,-2.0347e-017f},{-0.104013f,-0.994576f,1.92463e-018f},{0.104013f,-0.994576f,-5.52101e-017f}, -{-0.499433f,-0.866353f,-3.20615e-017f},{-0.308272f,-0.951298f,1.76026e-017f},{-0.310578f,-0.950548f,5.2766e-017f}, -{0.310578f,-0.950548f,-2.94305e-017f},{0.50141f,-0.86521f,1.66462e-017f},{0.499433f,-0.866353f,2.40461e-017f}, -{0.308272f,-0.951298f,5.70418e-018f},{0.105163f,-0.994455f,1.64552e-017f},{0.670096f,-0.742274f,-3.4671e-017f}, -{0.809606f,-0.586974f,3.04307e-018f},{0.808947f,-0.587881f,1.56371e-017f},{0.66887f,-0.743379f,-5.77706e-017f}, -{0.913543f,-0.406743f,8.0545e-018f},{0.913862f,-0.406026f,1.26789e-017f},{0.978254f,-0.207408f,-9.04189e-018f}, -{0.978165f,-0.20783f,-1.02592e-017f},{1.0f,2.89121e-019f,0.0f},{1.0f,-2.31296e-018f,0.0f}, -{-0.808947f,-0.587881f,-2.1756e-017f},{-0.984848f,0.173419f,0.0f},{-0.743022f,0.669267f,0.0f}, -{-0.940139f,0.34079f,0.0f},{-0.208043f,0.97812f,0.0f},{-0.000184774f,1.0f,0.0f}, -{-0.587964f,0.808887f,0.0f},{-0.40712f,0.913375f,0.0f},{0.587927f,0.808914f,0.0f}, -{0.406953f,0.913449f,0.0f},{0.207832f,0.978164f,0.0f},{0.742993f,0.669299f,0.0f}, -{0.866091f,0.499886f,0.0f},{0.9402f,0.340622f,0.0f},{0.9849f,0.173126f,0.0f}, -{1.0f,2.88658e-016f,0.0f},{1.0f,2.66454e-016f,0.0f},{-0.866141f,0.499799f,0.0f}, -{0.0f,2.77556e-017f,-1.0f},{2.43605e-017f,0.0f,-1.0f},{0.0f,-2.08167e-017f,-1.0f}, -{0.0f,-2.07242e-017f,-1.0f},{-0.470509f,0.209488f,-0.857167f},{-0.416639f,0.302781f,-0.857167f}, -{0.515038f,1.96047e-011f,-0.857167f},{-0.503792f,0.107041f,-0.857167f},{-0.515038f,8.71228e-012f,-0.857167f}, -{-0.344494f,0.382869f,-0.857167f},{-0.257227f,0.446205f,-0.857167f},{-0.158772f,0.489955f,-0.857167f}, -{-0.0535708f,0.512244f,-0.857167f},{0.054163f,0.512182f,-0.857167f},{0.258245f,0.445616f,-0.857167f}, -{0.159959f,0.489568f,-0.857167f},{0.416978f,0.302314f,-0.857167f},{0.345125f,0.382299f,-0.857167f}, -{0.503838f,0.106823f,-0.857167f},{0.470674f,0.209119f,-0.857167f},{0.515038f,5.77524e-016f,-0.857167f}, -{-0.978165f,0.20783f,7.23987e-017f},{-0.978254f,0.207408f,0.0f},{-0.50141f,0.86521f,1.85559e-017f}, -{-0.670096f,0.742274f,-2.21274e-017f},{-0.66887f,0.743379f,-2.47532e-017f},{-0.809606f,0.586974f,5.99229e-017f}, -{-0.913862f,0.406026f,0.0f},{-0.913543f,0.406743f,0.0f},{-0.105163f,0.994455f,2.22929e-017f}, -{-0.104013f,0.994576f,1.84034e-017f},{0.104013f,0.994576f,-1.64787e-017f},{-0.499433f,0.866353f,0.0f}, -{-0.308272f,0.951298f,1.76026e-017f},{-0.310578f,0.950548f,1.75887e-017f},{0.310578f,0.950548f,0.0f}, -{0.50141f,0.86521f,8.0048e-018f},{0.499433f,0.866353f,-3.39469e-018f},{0.308272f,0.951298f,8.80128e-018f}, -{0.105163f,0.994455f,2.22929e-017f},{0.670096f,0.742274f,-3.33889e-019f},{0.809606f,0.586974f,-1.35765e-018f}, -{0.808947f,0.587881f,-1.01698e-018f},{0.66887f,0.743379f,1.65048e-017f},{0.913543f,0.406743f,-2.8802e-018f}, -{0.913862f,0.406026f,-7.51299e-018f},{0.978254f,0.207408f,3.91078e-018f},{0.978165f,0.20783f,2.24517e-019f}, -{1.0f,-1.24033e-016f,0.0f},{1.0f,-1.249e-016f,0.0f},{-0.808947f,0.587881f,0.0f}, -{0.173171f,-0.984892f,2.40319e-017f},{-9.25186e-018f,-1.0f,2.31296e-017f},{-7.40149e-017f,-1.0f,2.31296e-017f}, -{-0.174653f,-0.98463f,9.17788e-018f},{-0.341361f,-0.939932f,-5.87441e-017f},{-0.173171f,-0.984892f,7.35351e-017f}, -{-0.343547f,-0.939135f,2.8923e-017f},{-0.499433f,-0.866353f,-2.69892e-017f},{-0.50141f,-0.86521f,-6.36638e-017f}, -{-0.642401f,-0.766369f,-5.10181e-017f},{-0.766786f,-0.641903f,3.93107e-017f},{-0.765783f,-0.643099f,-1.29623e-017f}, -{-0.643858f,-0.765145f,-1.31306e-016f},{-0.866509f,-0.499162f,-1.50895e-017f},{-0.865824f,-0.500349f,-1.69498e-017f}, -{-0.93996f,-0.341285f,-1.43832e-017f},{-0.939558f,-0.34239f,-3.55344e-017f},{-0.984877f,-0.173254f,-3.11529e-017f}, -{-0.984896f,-0.173146f,1.83632e-017f},{-1.0f,9.25186e-018f,0.0f},{0.174653f,-0.98463f,-9.02129e-017f}, -{0.343547f,-0.939135f,-6.09442e-017f},{0.341361f,-0.939932f,5.80656e-017f},{0.499433f,-0.866353f,4.22428e-017f}, -{0.50141f,-0.86521f,-6.73633e-017f},{0.643858f,-0.765145f,-3.72305e-018f},{0.642401f,-0.766369f,-4.75242e-017f}, -{0.766786f,-0.641903f,4.43387e-018f},{0.765783f,-0.643099f,-3.19634e-017f},{0.865824f,-0.500349f,-2.50327e-018f}, -{0.866509f,-0.499162f,2.18382e-017f},{0.93996f,-0.341285f,0.0f},{0.939558f,-0.34239f,0.0f}, -{0.984896f,-0.173146f,0.0f},{0.984877f,-0.173254f,-1.60292e-017f},{1.0f,-1.23454e-016f,0.0f}, -{-0.865936f,-0.500155f,0.0f},{-0.854507f,-0.51944f,0.0f},{-0.775519f,-0.631325f,0.0f}, -{0.0683073f,-0.997664f,0.0f},{-0.0681817f,-0.997673f,0.0f},{-0.917149f,-0.398545f,0.0f}, -{-0.923845f,-0.382766f,0.0f},{-0.962855f,-0.270019f,0.0f},{-0.966227f,-0.257693f,0.0f}, -{-0.990676f,-0.13624f,0.0f},{-0.991539f,-0.129812f,0.0f},{-0.743005f,-0.669286f,0.0f}, -{-0.587506f,-0.80922f,0.0f},{-0.682437f,-0.730944f,0.0f},{-0.460028f,-0.887904f,0.0f}, -{-0.576624f,-0.81701f,0.0f},{-0.334824f,-0.942281f,0.0f},{-0.406692f,-0.913565f,0.0f}, -{-0.207937f,-0.978142f,0.0f},{-0.203392f,-0.979097f,0.0f},{0.334953f,-0.942235f,0.0f}, -{0.406678f,-0.913572f,0.0f},{0.207869f,-0.978157f,0.0f},{0.203541f,-0.979066f,0.0f}, -{0.682558f,-0.730831f,0.0f},{0.587343f,-0.809338f,0.0f},{0.576674f,-0.816974f,0.0f}, -{0.460094f,-0.88787f,0.0f},{0.865951f,-0.500129f,0.0f},{0.854435f,-0.519558f,0.0f}, -{0.917715f,-0.397241f,0.0f},{0.74294f,-0.669358f,0.0f},{0.775729f,-0.631066f,0.0f}, -{0.966174f,-0.257891f,0.0f},{0.96322f,-0.268715f,0.0f},{0.990678f,-0.136227f,0.0f}, -{0.92384f,-0.38278f,0.0f},{0.991509f,-0.130039f,0.0f},{-3.33067e-016f,1.0f,-4.16334e-017f}, -{-3.33067e-016f,1.0f,-2.77556e-017f},{-3.33067e-016f,1.0f,-5.55111e-017f},{0.173171f,0.984892f,1.78986e-017f}, -{-9.25186e-018f,1.0f,-1.67181e-035f},{-0.174653f,0.98463f,-2.90351e-018f},{-0.341361f,0.939932f,-2.3159e-017f}, -{-0.173171f,0.984892f,-2.19044e-018f},{-0.343547f,0.939135f,8.62609e-018f},{-0.499433f,0.866353f,1.29071e-017f}, -{-0.50141f,0.86521f,-1.57974e-018f},{-0.642401f,0.766369f,2.86405e-017f},{-0.766786f,0.641903f,-2.87549e-017f}, -{-0.765783f,0.643099f,-1.1667e-017f},{-0.643858f,0.765145f,5.31763e-017f},{-0.866509f,0.499162f,-3.48634e-017f}, -{-0.865824f,0.500349f,-7.01556e-018f},{-0.93996f,0.341285f,1.42356e-017f},{-0.939558f,0.34239f,-6.37547e-017f}, -{-0.984877f,0.173254f,1.97007e-017f},{-0.984896f,0.173146f,-1.94221e-019f},{-1.0f,-9.25186e-018f,0.0f}, -{0.174653f,0.98463f,-4.41838e-018f},{0.343547f,0.939135f,1.79971e-017f},{0.341361f,0.939932f,-2.17403e-017f}, -{0.499433f,0.866353f,-1.08297e-018f},{0.50141f,0.86521f,-1.19599e-017f},{0.643858f,0.765145f,4.09797e-017f}, -{0.642401f,0.766369f,-9.28657e-019f},{0.766786f,0.641903f,-1.10847e-018f},{0.765783f,0.643099f,-3.30704e-017f}, -{0.865824f,0.500349f,2.31458e-017f},{0.866509f,0.499162f,-2.05856e-017f},{0.93996f,0.341285f,1.35881e-018f}, -{0.939558f,0.34239f,0.0f},{0.984896f,0.173146f,0.0f},{0.984877f,0.173254f,-1.60292e-017f}, -{1.0f,2.02384e-018f,0.0f},{-0.865936f,0.500155f,0.0f},{-0.854507f,0.51944f,0.0f}, -{-0.775519f,0.631325f,0.0f},{0.0683073f,0.997664f,0.0f},{-0.0681817f,0.997673f,0.0f}, -{-0.917149f,0.398545f,0.0f},{-0.923845f,0.382766f,0.0f},{-0.962855f,0.270019f,0.0f}, -{-0.966227f,0.257693f,0.0f},{-0.990676f,0.13624f,0.0f},{-0.991539f,0.129812f,0.0f}, -{-1.0f,1.19209e-007f,0.0f},{-0.743005f,0.669286f,0.0f},{-0.587506f,0.80922f,0.0f}, -{-0.682437f,0.730944f,0.0f},{-0.460028f,0.887904f,0.0f},{-0.576624f,0.81701f,0.0f}, -{-0.334824f,0.942281f,0.0f},{-0.406692f,0.913565f,0.0f},{-0.207937f,0.978142f,0.0f}, -{-0.203392f,0.979097f,0.0f},{0.334953f,0.942235f,0.0f},{0.406678f,0.913572f,0.0f}, -{0.207869f,0.978157f,0.0f},{0.203541f,0.979066f,0.0f},{0.682558f,0.730831f,0.0f}, -{0.587343f,0.809338f,0.0f},{0.576674f,0.816974f,0.0f},{0.460094f,0.88787f,0.0f}, -{0.865951f,0.500129f,0.0f},{0.854435f,0.519558f,0.0f},{0.917715f,0.397241f,0.0f}, -{0.74294f,0.669358f,0.0f},{0.775729f,0.631066f,0.0f},{0.966174f,0.257891f,0.0f}, -{0.96322f,0.268715f,0.0f},{0.990678f,0.136227f,0.0f},{0.92384f,0.38278f,0.0f}, -{0.991509f,0.130039f,0.0f},{0.866025f,0.5f,1.70981e-017f},{0.866025f,0.5f,1.85927e-018f}, -{-0.866025f,0.5f,1.38778e-017f},{-0.984877f,0.173254f,1.60292e-017f},{-0.984896f,0.173146f,0.0f}, -{-0.765783f,0.643099f,2.97493e-017f},{-0.766786f,0.641903f,-3.5471e-017f},{-0.865824f,0.500349f,-2.31458e-017f}, -{-0.866509f,0.499162f,2.30909e-017f},{-0.93996f,0.341285f,0.0f},{-0.939558f,0.34239f,0.0f}, -{-0.343547f,0.939135f,-2.17219e-017f},{-0.341361f,0.939932f,2.17403e-017f},{-0.174653f,0.98463f,4.03966e-018f}, -{-0.642401f,0.766369f,0.0f},{-0.50141f,0.86521f,2.31949e-017f},{0.174653f,0.98463f,4.03966e-018f}, -{0.341361f,0.939932f,1.77925e-017f},{0.173171f,0.984892f,4.00538e-018f},{9.25186e-018f,1.0f,0.0f}, -{0.643858f,0.765145f,-1.25718e-017f},{0.642401f,0.766369f,-3.47348e-017f},{0.50141f,0.86521f,1.0006e-017f}, -{0.499433f,0.866353f,-4.24336e-018f},{0.343547f,0.939135f,-2.91481e-018f},{0.766786f,0.641903f,-9.27937e-018f}, -{0.865824f,0.500349f,1.55228e-017f},{0.765783f,0.643099f,-1.85933e-018f},{0.866509f,0.499162f,-1.44318e-018f}, -{0.939558f,0.34239f,1.07308e-017f},{0.984877f,0.173254f,9.86413e-018f},{0.93996f,0.341285f,3.39702e-018f}, -{0.984896f,0.173146f,-1.1702e-017f},{-0.173171f,0.984892f,-1.87748e-017f},{-0.643858f,0.765145f,-3.53951e-017f}, -{3.84593e-017f,-1.0f,2.46519e-032f},{9.71445e-017f,0.0f,1.0f},{9.28077e-017f,0.0f,1.0f}, -{6.245e-017f,0.0f,1.0f},{-9.02056e-017f,0.0f,1.0f},{9.36751e-017f,0.0f,1.0f}, -{-8.08815e-017f,0.0f,1.0f},{-4.16334e-017f,0.0f,1.0f},{0.866025f,-0.5f,4.83767e-017f}, -{0.866025f,-0.5f,-3.32262e-017f},{-0.991509f,-0.130039f,0.0f},{-0.854435f,-0.519558f,0.0f}, -{-0.917715f,-0.397241f,0.0f},{-0.865951f,-0.500129f,0.0f},{-0.92384f,-0.38278f,0.0f}, -{-0.96322f,-0.268715f,0.0f},{-0.966174f,-0.257891f,0.0f},{-0.775729f,-0.631066f,0.0f}, -{-0.74294f,-0.669358f,0.0f},{-0.682558f,-0.730831f,0.0f},{-0.207869f,-0.978157f,0.0f}, -{-0.0683073f,-0.997664f,0.0f},{-0.406678f,-0.913572f,0.0f},{-0.334953f,-0.942235f,0.0f}, -{-0.460094f,-0.88787f,0.0f},{0.576624f,-0.81701f,0.0f},{0.460028f,-0.887904f,0.0f}, -{0.587506f,-0.80922f,0.0f},{0.334824f,-0.942281f,0.0f},{0.203392f,-0.979097f,0.0f}, -{0.207937f,-0.978142f,0.0f},{0.682437f,-0.730944f,0.0f},{0.743005f,-0.669286f,0.0f}, -{0.775519f,-0.631325f,0.0f},{0.865936f,-0.500155f,0.0f},{0.917149f,-0.398545f,0.0f}, -{0.854507f,-0.51944f,0.0f},{0.923845f,-0.382766f,0.0f},{0.962855f,-0.270019f,0.0f}, -{0.966227f,-0.257693f,0.0f},{0.991539f,-0.129812f,0.0f},{0.990676f,-0.13624f,0.0f}, -{1.0f,-1.19209e-007f,0.0f},{0.406692f,-0.913565f,0.0f},{0.0681817f,-0.997673f,0.0f}, -{-0.203541f,-0.979066f,0.0f},{-0.576674f,-0.816974f,0.0f},{-0.587343f,-0.809338f,0.0f}, -{-0.990678f,-0.136227f,0.0f},{-0.984877f,-0.173254f,1.60292e-017f},{-0.984896f,-0.173146f,0.0f}, -{-0.765783f,-0.643099f,6.51739e-017f},{-0.766786f,-0.641903f,3.5471e-017f},{-0.865824f,-0.500349f,0.0f}, -{-0.866509f,-0.499162f,-2.30909e-017f},{-0.93996f,-0.341285f,0.0f},{-0.939558f,-0.34239f,0.0f}, -{-0.343547f,-0.939135f,6.51656e-017f},{-0.341361f,-0.939932f,-6.52209e-017f},{-0.174653f,-0.98463f,9.10966e-017f}, -{-0.642401f,-0.766369f,6.51687e-017f},{-0.499433f,-0.866353f,-4.00769e-017f},{-0.50141f,-0.86521f,8.0048e-017f}, -{0.174653f,-0.98463f,-1.13871e-017f},{0.341361f,-0.939932f,6.91687e-017f},{0.173171f,-0.984892f,-7.63514e-017f}, -{7.40149e-017f,-1.0f,-2.31296e-017f},{9.25186e-018f,-1.0f,-2.31296e-017f},{0.643858f,-0.765145f,8.9189e-017f}, -{0.642401f,-0.766369f,-3.71463e-018f},{0.50141f,-0.86521f,2.08077e-017f},{0.499433f,-0.866353f,3.00576e-017f}, -{0.343547f,-0.939135f,-2.9668e-017f},{0.766786f,-0.641903f,3.71175e-018f},{0.865824f,-0.500349f,1.19628e-017f}, -{0.765783f,-0.643099f,4.04648e-017f},{0.866509f,-0.499162f,4.98303e-017f},{0.939558f,-0.34239f,3.49929e-018f}, -{0.984877f,-0.173254f,1.39894e-018f},{0.93996f,-0.341285f,1.29405e-018f},{0.984896f,-0.173146f,-5.94412e-018f}, -{-0.173171f,-0.984892f,-3.0791e-017f},{-0.643858f,-0.765145f,2.97844e-017f},{-0.991509f,0.130039f,0.0f}, -{-0.854435f,0.519558f,0.0f},{-0.917715f,0.397241f,0.0f},{-0.865951f,0.500129f,0.0f}, -{-0.92384f,0.38278f,0.0f},{-0.96322f,0.268715f,0.0f},{-0.966174f,0.257891f,0.0f}, -{-0.775729f,0.631066f,0.0f},{-0.74294f,0.669358f,0.0f},{-0.682558f,0.730831f,0.0f}, -{-0.207869f,0.978157f,0.0f},{-0.0683073f,0.997664f,0.0f},{-0.406678f,0.913572f,0.0f}, -{-0.334953f,0.942235f,0.0f},{-0.460094f,0.88787f,0.0f},{0.576624f,0.81701f,0.0f}, -{0.460028f,0.887904f,0.0f},{0.587506f,0.80922f,0.0f},{0.334824f,0.942281f,0.0f}, -{0.203392f,0.979097f,0.0f},{0.207937f,0.978142f,0.0f},{0.682437f,0.730944f,0.0f}, -{0.743005f,0.669286f,0.0f},{0.775519f,0.631325f,0.0f},{0.865936f,0.500155f,0.0f}, -{0.917149f,0.398545f,0.0f},{0.854507f,0.51944f,0.0f},{0.923845f,0.382766f,0.0f}, -{0.962855f,0.270019f,0.0f},{0.966227f,0.257693f,0.0f},{0.991539f,0.129812f,0.0f}, -{0.990676f,0.13624f,0.0f},{0.406692f,0.913565f,0.0f},{0.0681817f,0.997673f,0.0f}, -{-0.203541f,0.979066f,0.0f},{-0.576674f,0.816974f,0.0f},{-0.587343f,0.809338f,0.0f}, -{-0.990678f,0.136227f,0.0f},{-1.56125e-017f,0.0f,-1.0f},{2.24376e-017f,0.0f,-1.0f}, -{0.0f,6.66133e-018f,-1.0f},{-0.826318f,0.563203f,8.5792e-016f},{-0.642788f,0.766044f,2.41345e-015f}, -{-0.411158f,0.911564f,4.62954e-015f},{-0.158603f,0.987342f,-9.23504e-017f},{-0.411158f,0.911564f,2.06582e-015f}, -{0.0871557f,0.996195f,0.0f},{-0.944801f,0.327644f,-1.14754e-015f},{-0.996195f,0.0871557f,0.0f}, -{0.911564f,-0.411158f,6.02585e-016f},{0.766044f,-0.642788f,2.94214e-015f},{0.563203f,-0.826318f,9.64676e-016f}, -{0.327644f,-0.944801f,-9.8684e-016f},{0.563203f,-0.826318f,5.93271e-017f},{0.0871557f,-0.996195f,0.0f}, -{0.987342f,-0.158603f,0.0f},{0.996195f,0.0871557f,0.0f},{0.563203f,0.826318f,-8.5792e-016f}, -{0.766044f,0.642788f,3.08747e-015f},{0.911564f,0.411158f,3.8213e-016f},{0.987342f,0.158603f,-1.87973e-016f}, -{0.996195f,-0.0871557f,0.0f},{0.327644f,0.944801f,6.91476e-016f},{-0.411158f,-0.911564f,-9.85162e-016f}, -{-0.642788f,-0.766044f,2.97296e-015f},{-0.826318f,-0.563203f,-3.47088e-015f},{-0.944801f,-0.327644f,3.94878e-016f}, -{-0.996195f,-0.0871557f,0.0f},{-0.158603f,-0.987342f,4.08313e-016f},{0.826318f,-0.563203f,0.0f}, -{0.642788f,-0.766044f,-2.49102e-015f},{0.411158f,-0.911564f,1.48326e-015f},{0.158603f,-0.987342f,4.46669e-015f}, -{0.411158f,-0.911564f,1.36553e-015f},{-0.0871557f,-0.996195f,0.0f},{0.944801f,-0.327644f,3.04041e-016f}, -{-0.911564f,0.411158f,-6.75921e-016f},{-0.766044f,0.642788f,-3.67481e-016f},{-0.766044f,0.642788f,1.28733e-015f}, -{-0.563203f,0.826318f,6.30798e-016f},{-0.327644f,0.944801f,4.06883e-015f},{-0.563203f,0.826318f,-1.38054e-015f}, -{-0.0871557f,0.996195f,0.0f},{-0.987342f,0.158603f,8.16626e-016f},{0.563203f,0.826318f,-4.26026e-015f}, -{0.766044f,0.642788f,4.25258e-016f},{0.911564f,0.411158f,1.0983e-015f},{0.987342f,0.158603f,1.5422e-016f}, -{0.327644f,0.944801f,-6.58982e-018f},{-0.411158f,-0.911564f,2.34676e-015f},{-0.642788f,-0.766044f,1.45647e-015f}, -{-0.826318f,-0.563203f,1.2984e-017f},{-0.944801f,-0.327644f,-2.78891e-016f},{-0.158603f,-0.987342f,-4.78492e-018f}, -{0.826318f,-0.563203f,-4.23761e-015f},{0.642788f,-0.766044f,4.40666e-016f},{0.411158f,-0.911564f,1.12007e-015f}, -{0.158603f,-0.987342f,2.37841e-016f},{0.944801f,-0.327644f,-1.31796e-017f},{-0.911564f,0.411158f,2.35503e-015f}, -{-0.766044f,0.642788f,1.50818e-015f},{-0.563203f,0.826318f,-2.90842e-017f},{-0.327644f,0.944801f,-4.12948e-016f}, -{-0.987342f,0.158603f,4.78492e-018f},{-0.563203f,-0.826318f,-4.27159e-015f},{-0.766044f,-0.642788f,4.67628e-016f}, -{-0.911564f,-0.411158f,1.14986e-015f},{-0.987342f,-0.158603f,2.73989e-016f},{-0.327644f,-0.944801f,0.0f}, -{0.411158f,0.911564f,2.32608e-015f},{0.642788f,0.766044f,1.46294e-015f},{0.826318f,0.563203f,-3.1681e-017f}, -{0.944801f,0.327644f,-2.83939e-016f},{0.158603f,0.987342f,-1.59497e-018f},{0.826318f,-0.563203f,1.44993e-015f}, -{0.642788f,-0.766044f,2.4393e-015f},{0.411158f,-0.911564f,-4.18125e-015f},{0.158603f,-0.987342f,8.31771e-016f}, -{0.411158f,-0.911564f,-1.65888e-015f},{0.944801f,-0.327644f,0.0f},{-0.911564f,0.411158f,-2.19033e-015f}, -{-0.766044f,0.642788f,-3.6771e-015f},{-0.766044f,0.642788f,-1.19489e-015f},{-0.563203f,0.826318f,-7.29772e-016f}, -{-0.327644f,0.944801f,-3.40246e-015f},{-0.563203f,0.826318f,1.11462e-015f},{-0.987342f,0.158603f,4.08313e-016f}, -{-0.563203f,-0.826318f,-2.65912e-016f},{-0.766044f,-0.642788f,2.72372e-015f},{-0.911564f,-0.411158f,-8.55226e-016f}, -{-0.987342f,-0.158603f,2.40746e-015f},{-0.911564f,-0.411158f,-5.99094e-016f},{-0.327644f,-0.944801f,-6.91476e-016f}, -{0.411158f,0.911564f,4.55913e-016f},{0.642788f,0.766044f,3.70792e-015f},{0.826318f,0.563203f,6.53453e-016f}, -{0.944801f,0.327644f,-4.49072e-015f},{0.158603f,0.987342f,5.67178e-016f},{-0.826318f,0.563203f,-5.92007e-016f}, -{-0.642788f,0.766044f,-1.03426e-016f},{-0.411158f,0.911564f,-6.48711e-016f},{-0.158603f,0.987342f,-2.75969e-015f}, -{-0.944801f,0.327644f,1.68699e-015f},{0.911564f,-0.411158f,7.33362e-017f},{0.766044f,-0.642788f,9.35257e-016f}, -{0.563203f,-0.826318f,2.43257e-016f},{0.327644f,-0.944801f,-1.38084e-015f},{-0.563203f,-0.826318f,2.11031e-015f}, -{-0.766044f,-0.642788f,-8.23554e-016f},{-0.911564f,-0.411158f,-1.36865e-015f},{-0.987342f,-0.158603f,-1.67467e-016f}, -{-0.327644f,-0.944801f,-1.31796e-017f},{0.411158f,0.911564f,2.33642e-015f},{0.642788f,0.766044f,4.84808e-018f}, -{0.826318f,0.563203f,-6.03969e-016f},{0.944801f,0.327644f,-2.44862e-016f},{0.158603f,0.987342f,2.54184e-015f}, -{-0.826318f,0.563203f,2.11031e-015f},{-0.642788f,0.766044f,-8.5822e-016f},{-0.411158f,0.911564f,-1.4099e-015f}, -{-0.158603f,0.987342f,-1.68553e-016f},{-0.944801f,0.327644f,-6.58982e-018f},{0.911564f,-0.411158f,2.34056e-015f}, -{0.766044f,-0.642788f,-1.93923e-017f},{0.563203f,-0.826318f,-5.38529e-016f},{0.327644f,-0.944801f,-2.89548e-016f}, -{0.987342f,-0.158603f,2.53865e-015f},{0.563203f,0.826318f,2.15562e-015f},{0.766044f,0.642788f,-8.11999e-016f}, -{0.911564f,0.411158f,-1.3824e-015f},{0.987342f,0.158603f,-1.10685e-016f},{-0.411158f,-0.911564f,2.34883e-015f}, -{-0.642788f,-0.766044f,2.74725e-017f},{-0.826318f,-0.563203f,-5.36452e-016f},{-0.944801f,-0.327644f,-3.24435e-016f}, -{-0.158603f,-0.987342f,2.54503e-015f},{-0.563203f,-0.826318f,3.03281e-015f},{-0.766044f,-0.642788f,-3.0099e-015f}, -{-0.911564f,-0.411158f,-9.44011e-016f},{-0.987342f,-0.158603f,2.45238e-016f},{-0.911564f,-0.411158f,1.24043e-017f}, -{-0.327644f,-0.944801f,5.39456e-016f},{0.411158f,0.911564f,3.82577e-016f},{0.642788f,0.766044f,4.75332e-016f}, -{0.826318f,0.563203f,-1.81339e-015f},{0.944801f,0.327644f,3.44751e-015f},{0.158603f,0.987342f,0.0f}, -{-0.826318f,0.563203f,-4.28292e-015f},{-0.642788f,0.766044f,4.67628e-016f},{-0.411158f,0.911564f,1.0983e-015f}, -{-0.158603f,0.987342f,2.69956e-016f},{-0.944801f,0.327644f,6.58982e-018f},{0.911564f,-0.411158f,2.34469e-015f}, -{0.766044f,-0.642788f,1.47748e-015f},{0.563203f,-0.826318f,-1.45421e-017f},{0.327644f,-0.944801f,-3.87636e-016f}, -{0.987342f,-0.158603f,-3.18994e-018f},{0.563203f,0.826318f,-5.92007e-016f},{0.766044f,0.642788f,-1.03426e-016f}, -{0.911564f,0.411158f,-6.48711e-016f},{0.987342f,0.158603f,-2.75969e-015f},{0.327644f,0.944801f,1.68699e-015f}, -{-0.411158f,-0.911564f,-1.97032e-015f},{-0.642788f,-0.766044f,-3.61548e-015f},{-0.642788f,-0.766044f,-1.25652e-015f}, -{-0.826318f,-0.563203f,-7.52427e-016f},{-0.944801f,-0.327644f,-3.40576e-015f},{-0.826318f,-0.563203f,1.09197e-015f}, -{-0.104013f,0.994576f,-6.6149e-017f},{0.105163f,0.994455f,3.5074e-016f},{0.104013f,0.994576f,-2.77314e-017f}, -{-0.105163f,0.994455f,6.61477e-016f},{-0.308272f,0.951298f,-6.26411e-016f},{-0.310578f,0.950548f,-2.09449e-015f}, -{-0.50141f,0.86521f,-1.84452e-015f},{-0.66887f,0.743379f,-1.74439e-015f},{-0.499433f,0.866353f,-2.26521e-016f}, -{-0.670096f,0.742274f,-5.94667e-016f},{-0.808947f,0.587881f,-3.87528e-016f},{-0.809606f,0.586974f,-1.45655e-015f}, -{-0.913543f,0.406743f,-1.77092e-016f},{-0.913862f,0.406026f,3.24871e-015f},{-0.978165f,0.20783f,4.08599e-015f}, -{-0.978254f,0.207408f,-1.59112e-015f},{-1.0f,1.18424e-015f,0.0f},{0.308272f,0.951298f,9.4669e-016f}, -{0.499433f,0.866353f,1.42515e-015f},{0.310578f,0.950548f,1.52945e-016f},{0.50141f,0.86521f,6.9607e-017f}, -{0.66887f,0.743379f,0.0f},{0.670096f,0.742274f,1.78483e-015f},{0.808947f,0.587881f,-2.08258e-015f}, -{0.913543f,0.406743f,6.54457e-017f},{0.809606f,0.586974f,-1.98983e-015f},{0.913862f,0.406026f,0.0f}, -{0.978254f,0.207408f,-5.0369e-015f},{1.0f,-9.4739e-015f,0.0f},{-0.104013f,0.994576f,9.38801e-017f}, -{0.105163f,0.994455f,4.30745e-016f},{0.104013f,0.994576f,-2.27768e-016f},{-0.105163f,0.994455f,5.01467e-016f}, -{-0.308272f,0.951298f,-4.73345e-016f},{-0.310578f,0.950548f,-2.03714e-015f},{-0.50141f,0.86521f,-1.7053e-015f}, -{-0.66887f,0.743379f,-1.60982e-015f},{-0.670096f,0.742274f,-6.24525e-016f},{-0.808947f,0.587881f,-3.81616e-016f}, -{-0.809606f,0.586974f,-1.44179e-015f},{-0.913543f,0.406743f,-2.19018e-016f},{-0.913862f,0.406026f,3.22523e-015f}, -{-0.978165f,0.20783f,4.08922e-015f},{-0.978254f,0.207408f,-1.62446e-015f},{0.308272f,0.951298f,7.93624e-016f}, -{0.499433f,0.866353f,1.28576e-015f},{0.310578f,0.950548f,7.64725e-017f},{0.50141f,0.86521f,-6.9607e-017f}, -{0.670096f,0.742274f,1.6654e-015f},{0.913543f,0.406743f,0.0f},{0.809606f,0.586974f,-2.08427e-015f}, -{0.978165f,0.20783f,3.34403e-017f},{0.978254f,0.207408f,-5.07027e-015f},{-0.104013f,0.994576f,-1.73895e-016f}, -{0.105163f,0.994455f,1.6001e-016f},{0.104013f,0.994576f,1.73895e-016f},{-0.105163f,0.994455f,-4.00024e-017f}, -{-0.308272f,0.951298f,-6.71751e-016f},{-0.310578f,0.950548f,1.61654e-016f},{-0.50141f,0.86521f,-1.38259e-015f}, -{-0.66887f,0.743379f,-6.41222e-016f},{-0.499433f,0.866353f,1.60719e-016f},{-0.670096f,0.742274f,-1.27144e-015f}, -{-0.808947f,0.587881f,4.64432e-016f},{-0.809606f,0.586974f,1.42408e-015f},{-0.913543f,0.406743f,-2.92513e-016f}, -{-0.913862f,0.406026f,1.97537e-015f},{-0.978165f,0.20783f,1.58084e-015f},{-0.978254f,0.207408f,-1.89991e-015f}, -{-1.0f,1.0066e-014f,0.0f},{0.308272f,0.951298f,0.0f},{0.499433f,0.866353f,-1.28576e-015f}, -{0.50141f,0.86521f,-1.36045e-015f},{0.66887f,0.743379f,1.72196e-015f},{0.670096f,0.742274f,-5.97167e-017f}, -{0.913543f,0.406743f,2.35185e-015f},{0.809606f,0.586974f,0.0f},{0.913862f,0.406026f,2.35267e-015f}, -{0.978165f,0.20783f,-5.00299e-015f},{0.978254f,0.207408f,-3.33724e-017f},{-0.104013f,0.994576f,-3.33924e-016f}, -{0.105163f,0.994455f,8.00048e-017f},{0.104013f,0.994576f,3.73931e-016f},{-0.105163f,0.994455f,1.20007e-016f}, -{-0.308272f,0.951298f,-8.24817e-016f},{-0.310578f,0.950548f,1.043e-016f},{-0.50141f,0.86521f,-1.52181e-015f}, -{-0.66887f,0.743379f,-7.75785e-016f},{-0.499433f,0.866353f,-6.5802e-017f},{-0.670096f,0.742274f,-1.24159e-015f}, -{-0.808947f,0.587881f,4.5852e-016f},{-0.809606f,0.586974f,1.40933e-015f},{-0.913543f,0.406743f,-2.50587e-016f}, -{-0.913862f,0.406026f,1.99885e-015f},{-0.978165f,0.20783f,1.57761e-015f},{-0.978254f,0.207408f,-1.86657e-015f}, -{0.308272f,0.951298f,1.53066e-016f},{0.499433f,0.866353f,-1.14636e-015f},{0.50141f,0.86521f,-1.22124e-015f}, -{0.670096f,0.742274f,5.97167e-017f},{0.913543f,0.406743f,2.4173e-015f},{0.809606f,0.586974f,9.44452e-017f}, -{0.978165f,0.20783f,-5.03643e-015f},{0.978254f,0.207408f,0.0f},{-0.104013f,0.994576f,2.55628e-015f}, -{0.105163f,0.994455f,3.84446e-015f},{0.104013f,0.994576f,-8.36797e-018f},{-0.105163f,0.994455f,2.54746e-015f}, -{-0.308272f,0.951298f,-1.84919e-015f},{-0.310578f,0.950548f,6.24273e-016f},{-0.50141f,0.86521f,-2.49577e-015f}, -{-0.66887f,0.743379f,-1.86669e-015f},{-0.499433f,0.866353f,4.20202e-015f},{-0.670096f,0.742274f,-6.0878e-016f}, -{-0.808947f,0.587881f,-5.61965e-016f},{-0.809606f,0.586974f,-5.29626e-016f},{-0.913543f,0.406743f,-4.68477e-016f}, -{-0.913862f,0.406026f,1.88599e-016f},{-0.978165f,0.20783f,-8.08443e-016f},{-0.978254f,0.207408f,3.31428e-016f}, -{0.308272f,0.951298f,-1.21213e-015f},{0.499433f,0.866353f,-2.23036e-015f},{0.310578f,0.950548f,3.68317e-015f}, -{0.50141f,0.86521f,-2.3081e-015f},{0.66887f,0.743379f,1.96759e-015f},{0.670096f,0.742274f,1.0782e-016f}, -{0.808947f,0.587881f,-1.95242e-016f},{0.809606f,0.586974f,6.51336e-017f},{0.913862f,0.406026f,-2.23761e-015f}, -{0.978165f,0.20783f,1.07009e-015f},{0.978254f,0.207408f,-1.06792e-015f},{-0.104013f,0.994576f,2.54791e-015f}, -{0.105163f,0.994455f,2.56439e-015f},{0.104013f,0.994576f,8.36797e-018f},{-0.105163f,0.994455f,-1.27162e-015f}, -{-0.308272f,0.951298f,-1.82439e-015f},{-0.310578f,0.950548f,-1.79786e-015f},{-0.50141f,0.86521f,-1.67057e-015f}, -{-0.66887f,0.743379f,-8.96351e-016f},{-0.499433f,0.866353f,-3.97345e-015f},{-0.670096f,0.742274f,2.57549e-015f}, -{-0.808947f,0.587881f,1.24903e-015f},{-0.809606f,0.586974f,6.51412e-018f},{-0.913543f,0.406743f,-4.18802e-016f}, -{-0.913862f,0.406026f,4.82137e-016f},{-0.978165f,0.20783f,5.39336e-016f},{-0.978254f,0.207408f,3.75279e-016f}, -{-1.0f,3.70074e-017f,0.0f},{0.308272f,0.951298f,-2.53585e-015f},{0.499433f,0.866353f,2.23036e-015f}, -{0.310578f,0.950548f,4.89424e-015f},{0.50141f,0.86521f,8.06778e-017f},{0.66887f,0.743379f,-3.93518e-015f}, -{0.670096f,0.742274f,-5.7328e-015f},{0.808947f,0.587881f,-1.51346e-015f},{0.913862f,0.406026f,-1.47042e-016f}, -{0.978254f,0.207408f,-9.10514e-016f},{0.105163f,0.994455f,3.84869e-015f},{0.104013f,0.994576f,2.51039e-017f}, -{-0.310578f,0.950548f,5.86794e-016f},{-0.50141f,0.86521f,-2.45543e-015f},{-0.66887f,0.743379f,-1.85997e-015f}, -{-0.499433f,0.866353f,4.16184e-015f},{-0.670096f,0.742274f,-7.23339e-016f},{-0.808947f,0.587881f,-7.32801e-016f}, -{-0.809606f,0.586974f,-5.96795e-016f},{-0.913543f,0.406743f,-3.41009e-016f},{-0.913862f,0.406026f,2.10425e-016f}, -{-0.978165f,0.20783f,-9.90731e-016f},{-0.978254f,0.207408f,1.24376e-016f},{0.308272f,0.951298f,-1.19972e-015f}, -{0.499433f,0.866353f,-2.27054e-015f},{0.310578f,0.950548f,3.67068e-015f},{0.50141f,0.86521f,-2.22742e-015f}, -{0.66887f,0.743379f,1.91378e-015f},{0.670096f,0.742274f,-1.0782e-016f},{0.808947f,0.587881f,-1.30161e-016f}, -{0.809606f,0.586974f,1.30267e-016f},{0.913862f,0.406026f,-2.09057e-015f},{0.978165f,0.20783f,1.22748e-015f}, -{0.105163f,0.994455f,2.56015e-015f},{0.104013f,0.994576f,1.67359e-017f},{-0.105163f,0.994455f,-1.29277e-015f}, -{-0.310578f,0.950548f,-1.78537e-015f},{-0.50141f,0.86521f,-1.66048e-015f},{-0.66887f,0.743379f,-9.97247e-016f}, -{-0.499433f,0.866353f,-3.84287e-015f},{-0.670096f,0.742274f,2.54179e-015f},{-0.808947f,0.587881f,1.41783e-015f}, -{-0.809606f,0.586974f,2.30411e-016f},{-0.913543f,0.406743f,-4.4866e-016f},{-0.913862f,0.406026f,6.14245e-016f}, -{-0.978165f,0.20783f,6.54611e-016f},{-0.978254f,0.207408f,1.60695e-016f},{-1.0f,3.14563e-016f,0.0f}, -{0.308272f,0.951298f,-2.44905e-015f},{0.499433f,0.866353f,2.15e-015f},{0.310578f,0.950548f,4.91923e-015f}, -{0.50141f,0.86521f,4.03389e-017f},{0.66887f,0.743379f,-3.82756e-015f},{0.670096f,0.742274f,-5.62498e-015f}, -{0.808947f,0.587881f,-1.64362e-015f},{0.913543f,0.406743f,-1.46991e-016f},{0.978165f,0.20783f,1.57389e-016f}, -{-0.104013f,0.994576f,-3.07782e-016f},{0.104013f,0.994576f,-3.61655e-016f},{-0.105163f,0.994455f,-4.46105e-016f}, -{-0.308272f,0.951298f,-7.65328e-017f},{-0.310578f,0.950548f,3.61544e-016f},{-0.50141f,0.86521f,2.00587e-015f}, -{-0.66887f,0.743379f,5.42625e-016f},{-0.499433f,0.866353f,-2.73223e-015f},{-0.808947f,0.587881f,2.6919e-016f}, -{-0.809606f,0.586974f,1.35895e-015f},{-0.913543f,0.406743f,2.90454e-015f},{-0.913862f,0.406026f,-3.57547e-015f}, -{-0.978165f,0.20783f,6.07001e-016f},{-0.978254f,0.207408f,-2.30818e-015f},{0.308272f,0.951298f,-3.96812e-016f}, -{0.499433f,0.866353f,0.0f},{0.310578f,0.950548f,8.76033e-016f},{0.50141f,0.86521f,1.22124e-015f}, -{0.66887f,0.743379f,-1.72196e-015f},{0.670096f,0.742274f,-1.78483e-015f},{0.808947f,0.587881f,0.0f}, -{0.913862f,0.406026f,4.70535e-015f},{1.0f,9.4739e-015f,0.0f},{-0.104013f,0.994576f,-5.75557e-016f}, -{-0.308272f,0.951298f,1.21873e-016f},{-0.50141f,0.86521f,-2.53104e-016f},{-0.66887f,0.743379f,-3.18355e-016f}, -{-0.670096f,0.742274f,-7.32345e-016f},{-0.808947f,0.587881f,-3.37532e-015f},{-0.809606f,0.586974f,-2.35366e-015f}, -{-0.913543f,0.406743f,6.26179e-016f},{-0.913862f,0.406026f,1.68129e-015f},{-0.978165f,0.20783f,3.11538e-015f}, -{-0.978254f,0.207408f,-2.35245e-015f},{-1.0f,-1.0066e-014f,0.0f},{0.310578f,0.950548f,1.27581e-015f}, -{0.808947f,0.587881f,6.24774e-015f},{0.913543f,0.406743f,4.7037e-015f},{-0.104013f,0.994576f,-7.35586e-016f}, -{0.104013f,0.994576f,-1.61619e-016f},{-0.308272f,0.951298f,-3.11924e-017f},{-0.310578f,0.950548f,3.0419e-016f}, -{-0.50141f,0.86521f,-3.92318e-016f},{-0.66887f,0.743379f,-4.52917e-016f},{-0.670096f,0.742274f,-7.02486e-016f}, -{-0.808947f,0.587881f,-3.38123e-015f},{-0.809606f,0.586974f,-2.36842e-015f},{-0.913543f,0.406743f,6.68105e-016f}, -{-0.913862f,0.406026f,1.70476e-015f},{-0.978165f,0.20783f,3.11215e-015f},{-0.978254f,0.207408f,-2.31911e-015f}, -{0.499433f,0.866353f,1.39398e-016f},{0.310578f,0.950548f,1.35229e-015f},{0.50141f,0.86521f,1.36045e-015f}, -{0.670096f,0.742274f,-1.6654e-015f},{0.913543f,0.406743f,4.76915e-015f},{-0.104013f,0.994576f,-4.67811e-016f}, -{-0.105163f,0.994455f,-2.86095e-016f},{-0.308272f,0.951298f,-2.29599e-016f},{-0.50141f,0.86521f,1.86666e-015f}, -{-0.66887f,0.743379f,4.08063e-016f},{-0.499433f,0.866353f,-2.95875e-015f},{-0.808947f,0.587881f,2.63278e-016f}, -{-0.809606f,0.586974f,1.34419e-015f},{-0.913543f,0.406743f,2.94646e-015f},{-0.913862f,0.406026f,-3.55199e-015f}, -{-0.978165f,0.20783f,6.03768e-016f},{-0.978254f,0.207408f,-2.27484e-015f},{0.308272f,0.951298f,-2.43746e-016f}, -{0.310578f,0.950548f,9.52505e-016f},{-0.104013f,0.994576f,-1.28023e-015f},{0.105163f,0.994455f,-6.40039e-015f}, -{0.104013f,0.994576f,-1.2635e-015f},{-0.105163f,0.994455f,-3.84023e-015f},{-0.308272f,0.951298f,-3.07371e-015f}, -{-0.50141f,0.86521f,8.55453e-016f},{-0.66887f,0.743379f,4.91897e-016f},{-0.499433f,0.866353f,-2.5192e-015f}, -{-0.670096f,0.742274f,2.12958e-015f},{-0.808947f,0.587881f,4.21337e-015f},{-0.809606f,0.586974f,-3.09392e-017f}, -{-0.913543f,0.406743f,-1.09766e-015f},{-0.913862f,0.406026f,-7.15687e-016f},{-0.978165f,0.20783f,4.50713e-016f}, -{-0.978254f,0.207408f,2.11367e-017f},{0.308272f,0.951298f,3.69838e-015f},{0.499433f,0.866353f,-2.15e-015f}, -{0.310578f,0.950548f,2.44712e-015f},{0.50141f,0.86521f,2.26776e-015f},{0.808947f,0.587881f,1.30161e-016f}, -{0.809606f,0.586974f,-1.51112e-015f},{0.913862f,0.406026f,1.47042e-016f},{0.978254f,0.207408f,1.57403e-016f}, -{-0.104013f,0.994576f,-1.2886e-015f},{0.105163f,0.994455f,-2.54323e-015f},{0.104013f,0.994576f,-1.29697e-015f}, -{-0.105163f,0.994455f,-2.56439e-015f},{-0.308272f,0.951298f,2.43665e-015f},{-0.310578f,0.950548f,-1.77287e-015f}, -{-0.50141f,0.86521f,-2.01694e-017f},{-0.66887f,0.743379f,-4.04454e-016f},{-0.499433f,0.866353f,2.22032e-015f}, -{-0.670096f,0.742274f,-1.08838e-015f},{-0.808947f,0.587881f,-7.85202e-016f},{-0.809606f,0.586974f,2.0208e-015f}, -{-0.913543f,0.406743f,-1.10599e-015f},{-0.913862f,0.406026f,9.7451e-016f},{-0.978165f,0.20783f,-1.11392e-015f}, -{-0.978254f,0.207408f,1.58514e-016f},{0.308272f,0.951298f,-2.42425e-015f},{0.499433f,0.866353f,-4.46073e-015f}, -{0.310578f,0.950548f,2.47211e-015f},{0.50141f,0.86521f,-1.21017e-016f},{0.66887f,0.743379f,3.71993e-015f}, -{0.670096f,0.742274f,1.91093e-015f},{0.808947f,0.587881f,1.51346e-015f},{0.913543f,0.406743f,-1.19412e-015f}, -{0.913862f,0.406026f,-1.04529e-015f},{0.978254f,0.207408f,3.14806e-016f},{-0.104013f,0.994576f,-1.27605e-015f}, -{0.105163f,0.994455f,-2.56015e-015f},{0.104013f,0.994576f,-1.27187e-015f},{-0.105163f,0.994455f,-2.55169e-015f}, -{-0.308272f,0.951298f,2.44285e-015f},{-0.310578f,0.950548f,-1.89781e-015f},{-0.50141f,0.86521f,1.51271e-017f}, -{-0.66887f,0.743379f,-4.24633e-016f},{-0.499433f,0.866353f,2.28059e-015f},{-0.670096f,0.742274f,-1.03447e-015f}, -{-0.808947f,0.587881f,-8.25877e-016f},{-0.809606f,0.586974f,1.78876e-015f},{-0.913543f,0.406743f,-1.13241e-015f}, -{-0.913862f,0.406026f,9.48088e-016f},{-0.978165f,0.20783f,-1.26731e-015f},{-0.978254f,0.207408f,1.76191e-016f}, -{0.308272f,0.951298f,-2.48625e-015f},{0.499433f,0.866353f,-4.54109e-015f},{0.310578f,0.950548f,2.45961e-015f}, -{0.66887f,0.743379f,3.77374e-015f},{0.670096f,0.742274f,2.01875e-015f},{0.808947f,0.587881f,1.64362e-015f}, -{0.913543f,0.406743f,-1.04713e-015f},{0.913862f,0.406026f,-1.19233e-015f},{0.105163f,0.994455f,-6.40462e-015f}, -{0.104013f,0.994576f,-1.27605e-015f},{-0.105163f,0.994455f,-3.83177e-015f},{-0.308272f,0.951298f,-3.06751e-015f}, -{-0.310578f,0.950548f,6.18026e-016f},{-0.50141f,0.86521f,8.60495e-016f},{-0.66887f,0.743379f,3.50643e-016f}, -{-0.499433f,0.866353f,-2.39364e-015f},{-0.670096f,0.742274f,2.21045e-015f},{-0.808947f,0.587881f,4.28049e-015f}, -{-0.809606f,0.586974f,3.82652e-017f},{-0.913543f,0.406743f,-1.05976e-015f},{-0.913862f,0.406026f,-7.14539e-016f}, -{-0.978165f,0.20783f,6.42838e-016f},{-0.978254f,0.207408f,2.38181e-016f},{0.308272f,0.951298f,3.71078e-015f}, -{0.310578f,0.950548f,2.39715e-015f},{0.50141f,0.86521f,2.18708e-015f},{0.66887f,0.743379f,5.38112e-017f}, -{0.670096f,0.742274f,5.39099e-017f},{0.808947f,0.587881f,-6.50806e-017f},{0.809606f,0.586974f,-1.31572e-015f}, -{0.978165f,0.20783f,9.12701e-016f},{0.978254f,0.207408f,-1.57403e-016f},{-2.9992e-017f,1.0f,4.35009e-018f}, -{0.307814f,0.951446f,8.09361e-016f},{-3.30053e-017f,1.0f,4.35009e-018f},{-0.587751f,0.809042f,-3.83595e-016f}, -{-0.309304f,0.950963f,-1.80891e-016f},{-0.588229f,0.808694f,-7.54388e-016f},{-0.307814f,0.951446f,1.83345e-017f}, -{-0.807656f,0.589654f,2.20949e-015f},{-0.952103f,0.305779f,4.58604e-015f},{-0.950842f,0.309676f,1.56814e-015f}, -{-0.811958f,0.583716f,-1.76798e-015f},{0.309304f,0.950963f,4.15271e-016f},{0.587751f,0.809042f,-2.12505e-018f}, -{0.588229f,0.808694f,1.51231e-015f},{0.811958f,0.583716f,6.63961e-019f},{0.807656f,0.589654f,-2.07933e-015f}, -{0.952103f,0.305779f,2.44947e-015f},{0.950842f,0.309676f,-2.44821e-015f},{-7.14668e-017f,1.0f,1.76219e-017f}, -{0.307814f,0.951446f,4.05503e-016f},{-7.63065e-017f,1.0f,1.76219e-017f},{-0.587751f,0.809042f,1.91069e-015f}, -{-0.309304f,0.950963f,-8.01418e-016f},{-0.588229f,0.808694f,2.00475e-016f},{-0.307814f,0.951446f,1.92778e-016f}, -{-0.807656f,0.589654f,1.55906e-015f},{-0.952103f,0.305779f,3.26471e-015f},{-0.950842f,0.309676f,7.07118e-016f}, -{-0.811958f,0.583716f,-1.04241e-015f},{0.309304f,0.950963f,8.97608e-018f},{0.587751f,0.809042f,7.59323e-016f}, -{0.588229f,0.808694f,-7.62656e-016f},{0.811958f,0.583716f,-2.08933e-015f},{0.807656f,0.589654f,2.08126e-015f}, -{0.952103f,0.305779f,1.03838e-019f},{0.950842f,0.309676f,2.44827e-015f},{1.0f,1.89478e-014f,0.0f}, -{0.0f,1.0f,1.28722e-015f},{0.307814f,0.951446f,-3.67724e-015f},{1.18424e-015f,1.0f,1.28722e-015f}, -{-0.587751f,0.809042f,2.57397e-016f},{-0.309304f,0.950963f,6.12825e-016f},{-0.588229f,0.808694f,-1.47886e-018f}, -{-0.307814f,0.951446f,2.45098e-015f},{-0.807656f,0.589654f,2.89271e-015f},{-0.952103f,0.305779f,-6.10308e-016f}, -{-0.950842f,0.309676f,-1.03589e-015f},{-0.811958f,0.583716f,9.97398e-016f},{0.309304f,0.950963f,0.0f}, -{0.587751f,0.809042f,4.16564e-015f},{0.588229f,0.808694f,5.91545e-018f},{0.811958f,0.583716f,1.63307e-017f}, -{0.807656f,0.589654f,-1.51802e-015f},{0.952103f,0.305779f,0.0f},{0.950842f,0.309676f,7.97239e-016f}, -{1.0f,-6.93889e-017f,0.0f},{0.0f,1.0f,-6.43608e-016f},{0.307814f,0.951446f,1.22162e-015f}, -{1.48864e-033f,1.0f,-6.43608e-016f},{-0.587751f,0.809042f,-5.23661e-016f},{-0.309304f,0.950963f,-1.22332e-015f}, -{-0.588229f,0.808694f,1.03948e-015f},{-0.307814f,0.951446f,-1.83553e-015f},{-0.807656f,0.589654f,5.20805e-016f}, -{-0.952103f,0.305779f,2.13798e-016f},{-0.950842f,0.309676f,8.91809e-016f},{-0.811958f,0.583716f,6.21714e-016f}, -{0.587751f,0.809042f,1.04141e-015f},{0.588229f,0.808694f,-1.03505e-015f},{0.811958f,0.583716f,1.51907e-015f}, -{0.807656f,0.589654f,1.51802e-015f},{0.950842f,0.309676f,-7.97239e-016f},{0.307814f,0.951446f,-3.79309e-016f}, -{-0.587751f,0.809042f,7.51249e-016f},{-0.309304f,0.950963f,-7.78103e-016f},{-0.588229f,0.808694f,2.7896e-018f}, -{-0.807656f,0.589654f,4.02884e-015f},{-0.952103f,0.305779f,-5.00781e-015f},{-1.0f,1.89478e-014f,0.0f}, -{-0.950842f,0.309676f,5.45e-016f},{-0.811958f,0.583716f,-7.88142e-016f},{-1.0f,1.06581e-014f,0.0f}, -{0.309304f,0.950963f,1.71297e-017f},{0.587751f,0.809042f,1.511e-015f},{0.588229f,0.808694f,-2.04514e-018f}, -{0.807656f,0.589654f,2.07918e-015f},{0.952103f,0.305779f,-2.45277e-015f},{0.950842f,0.309676f,2.44755e-015f}, -{0.0f,1.0f,-1.28722e-015f},{0.307814f,0.951446f,-3.09549e-018f},{-1.18424e-015f,1.0f,-1.28722e-015f}, -{-0.587751f,0.809042f,7.78103e-016f},{-0.309304f,0.950963f,-1.83536e-015f},{-0.588229f,0.808694f,1.55997e-015f}, -{-0.307814f,0.951446f,-1.22317e-015f},{-0.807656f,0.589654f,-2.70499e-015f},{-0.952103f,0.305779f,5.82801e-016f}, -{-0.950842f,0.309676f,6.707e-016f},{-0.811958f,0.583716f,-2.47768e-015f},{0.309304f,0.950963f,-2.44819e-015f}, -{0.587751f,0.809042f,0.0f},{0.588229f,0.808694f,-2.07601e-015f},{0.0f,1.0f,6.43608e-016f}, -{0.307814f,0.951446f,-4.90196e-015f},{-1.48864e-033f,1.0f,6.43608e-016f},{-0.588229f,0.808694f,-5.21961e-016f}, -{-0.307814f,0.951446f,3.06334e-015f},{-0.807656f,0.589654f,-5.22835e-016f},{-0.952103f,0.305779f,-1.18305e-016f}, -{-0.950842f,0.309676f,-6.59069e-016f},{-0.811958f,0.583716f,7.15635e-016f},{0.309304f,0.950963f,1.22409e-015f}, -{0.588229f,0.808694f,1.04688e-015f},{0.307814f,0.951446f,8.01726e-016f},{-0.587751f,0.809042f,-1.69861e-016f}, -{-0.309304f,0.950963f,1.93934e-016f},{-0.588229f,0.808694f,-1.31388e-015f},{-0.307814f,0.951446f,5.89001e-016f}, -{-0.807656f,0.589654f,-1.94968e-015f},{-0.952103f,0.305779f,3.28386e-015f},{-0.950842f,0.309676f,-1.06186e-015f}, -{-0.811958f,0.583716f,5.25337e-016f},{0.309304f,0.950963f,-3.89165e-016f},{0.587751f,0.809042f,-7.53802e-016f}, -{0.588229f,0.808694f,7.51699e-016f},{0.811958f,0.583716f,1.00283e-018f},{0.807656f,0.589654f,-2.07725e-015f}, -{0.950842f,0.309676f,3.9552e-019f},{1.0f,-1.89478e-014f,0.0f},{-0.761438f,0.648238f,2.94694e-016f}, -{-0.718339f,0.695693f,3.39459e-016f},{-0.718357f,0.695675f,-3.39456e-016f},{0.0960133f,0.99538f,-2.46936e-016f}, -{0.0320605f,0.999486f,-9.42991e-016f},{0.0960396f,0.995378f,3.20316e-016f},{-0.032044f,0.999486f,-4.9277e-016f}, -{0.032044f,0.999486f,6.25231e-016f},{0.159589f,0.987184f,8.58394e-016f},{0.15962f,0.987179f,1.45997e-016f}, -{0.22251f,0.974931f,-4.52703e-016f},{0.222542f,0.974923f,-7.64298e-016f},{0.284517f,0.958671f,-4.25434e-016f}, -{0.284548f,0.958662f,-2.51271e-016f},{0.345353f,0.938473f,-6.8736e-016f},{0.518376f,0.855153f,5.08747e-016f}, -{0.462522f,0.886608f,-1.07923e-015f},{0.462558f,0.886589f,2.04673e-016f},{0.345385f,0.938461f,-1.21586e-015f}, -{0.404803f,0.914404f,-3.09674e-016f},{0.404769f,0.914419f,1.8029e-016f},{0.572101f,0.820183f,6.61372e-016f}, -{0.518412f,0.855131f,-5.92076e-016f},{0.572134f,0.82016f,-4.37334e-016f},{0.623475f,0.781843f,1.31467e-016f}, -{0.672313f,0.740267f,1.23799e-015f},{0.672288f,0.740289f,-8.27861e-016f},{0.623505f,0.781819f,8.6137e-016f}, -{0.718339f,0.695693f,-8.99733e-016f},{0.718357f,0.695675f,-5.67888e-016f},{0.761438f,0.648238f,-1.33697e-016f}, -{0.761447f,0.648227f,2.16584e-016f},{0.801409f,0.598117f,-3.98106e-016f},{0.801406f,0.598121f,2.48774e-016f}, -{0.981554f,0.191184f,4.00667e-016f},{0.967317f,0.25357f,-1.85681e-016f},{0.981559f,0.191157f,-7.78912e-016f}, -{0.871315f,0.490723f,-1.02521e-015f},{0.90096f,0.433902f,2.05671e-017f},{0.871302f,0.490747f,-7.5201e-016f}, -{0.838075f,0.545555f,3.05312e-016f},{0.838084f,0.545542f,1.28783e-015f},{0.900965f,0.433892f,-3.31874e-016f}, -{0.926902f,0.375304f,-2.89443e-016f},{0.926953f,0.375176f,3.48902e-016f},{0.949042f,0.315149f,7.91723e-016f}, -{0.94917f,0.314763f,1.83311e-017f},{0.967287f,0.253683f,-1.2494e-015f},{0.991791f,0.12787f,1.80602e-016f}, -{0.997946f,0.0640673f,-2.96278e-017f},{0.997945f,0.0640792f,-1.66986e-016f},{0.991787f,0.127897f,-1.01412e-015f}, -{1.0f,-1.4803e-017f,0.0f},{-0.0320605f,0.999486f,-2.5793e-018f},{-0.0960397f,0.995377f,3.1259e-016f}, -{-0.0960134f,0.99538f,7.93068e-016f},{-0.159589f,0.987184f,3.0484e-016f},{-0.15962f,0.987179f,1.05577e-015f}, -{-0.222542f,0.974923f,-1.16968e-015f},{-0.22251f,0.97493f,-9.5911e-016f},{-0.284548f,0.958662f,-3.77177e-016f}, -{-0.284517f,0.958671f,3.77173e-016f},{-0.345353f,0.938473f,3.02004e-016f},{-0.345385f,0.938461f,-7.97082e-017f}, -{-0.404803f,0.914404f,0.0f},{-0.404769f,0.914419f,6.53655e-016f},{-0.462558f,0.886589f,2.10881e-016f}, -{-0.462522f,0.886608f,-5.70627e-016f},{-0.518376f,0.855153f,-2.33487e-016f},{-0.518412f,0.855131f,3.58598e-016f}, -{-0.572134f,0.82016f,2.17902e-016f},{-0.572101f,0.820183f,-1.38078e-016f},{-0.623505f,0.781819f,-3.02538e-016f}, -{-0.623476f,0.781843f,-2.516e-016f},{-0.672288f,0.740289f,1.06108e-015f},{-0.672313f,0.740267f,-5.84618e-016f}, -{-0.761447f,0.648227f,2.94685e-016f},{-0.801409f,0.598117f,-6.42849e-016f},{-0.801406f,0.598121f,6.353e-017f}, -{-0.838075f,0.545555f,2.16275e-016f},{-0.838084f,0.545542f,-4.07081e-017f},{-0.871315f,0.490723f,1.40196e-016f}, -{-0.871302f,0.490747f,4.56042e-016f},{-0.900965f,0.433892f,1.44967e-016f},{-0.90096f,0.433902f,1.44966e-016f}, -{-0.926902f,0.375304f,9.24079e-017f},{-0.926953f,0.375176f,0.0f},{-0.94917f,0.314763f,2.02584e-016f}, -{-0.949042f,0.315149f,2.02832e-016f},{-0.967317f,0.25357f,0.0f},{-0.967287f,0.253683f,-1.63272e-016f}, -{-0.981554f,0.191184f,0.0f},{-0.981559f,0.191157f,0.0f},{-0.991791f,0.12787f,0.0f}, -{-0.991787f,0.127897f,0.0f},{-0.997946f,0.0640673f,0.0f},{-0.997945f,0.0640791f,-2.01813e-016f}, -{-1.0f,5.92119e-017f,0.0f},{-0.761438f,0.648238f,-1.22517e-016f},{-0.718339f,0.695693f,1.08295e-016f}, -{-0.718357f,0.695675f,2.3117e-016f},{0.0960133f,0.99538f,5.02084e-017f},{0.0320605f,0.999486f,-7.73789e-018f}, -{0.0960396f,0.995378f,6.56751e-017f},{-0.032044f,0.999486f,0.0f},{0.032044f,0.999486f,-7.73392e-018f}, -{0.159589f,0.987184f,1.97357e-016f},{0.15962f,0.987179f,1.28416e-017f},{0.22251f,0.974931f,1.50038e-016f}, -{0.222542f,0.974923f,-1.56867e-016f},{0.284517f,0.958671f,1.54252e-016f},{0.284548f,0.958662f,-7.46707e-017f}, -{0.345353f,0.938473f,2.7603e-016f},{0.518376f,0.855153f,-1.14686e-016f},{0.462522f,0.886608f,-2.41867e-016f}, -{0.462558f,0.886589f,-1.76763e-016f},{0.345385f,0.938461f,2.28326e-016f},{0.404803f,0.914404f,-2.28546e-016f}, -{0.404769f,0.914419f,5.6987e-017f},{0.572101f,0.820183f,-2.07117e-016f},{0.518412f,0.855131f,2.98183e-016f}, -{0.572134f,0.82016f,2.07129e-016f},{0.623475f,0.781843f,3.69924e-016f},{0.672313f,0.740267f,2.31169e-016f}, -{0.672288f,0.740289f,5.2187e-016f},{0.623505f,0.781819f,6.95605e-017f},{0.718339f,0.695693f,-4.01349e-016f}, -{0.718357f,0.695675f,3.64397e-016f},{0.761438f,0.648238f,1.44968e-016f},{0.761447f,0.648227f,4.58818e-016f}, -{0.801409f,0.598117f,-2.05097e-016f},{0.801406f,0.598121f,-6.80769e-016f},{0.981554f,0.191184f,1.41704e-015f}, -{0.967317f,0.25357f,3.82454e-016f},{0.981559f,0.191157f,-1.05674e-015f},{0.871315f,0.490723f,-9.36431e-016f}, -{0.90096f,0.433902f,4.48018e-017f},{0.871302f,0.490747f,-3.7096e-016f},{0.838075f,0.545555f,3.69875e-016f}, -{0.838084f,0.545542f,1.37433e-015f},{0.900965f,0.433892f,-3.75604e-016f},{0.926902f,0.375304f,-3.03308e-017f}, -{0.926953f,0.375176f,3.109e-016f},{0.949042f,0.315149f,-4.05339e-016f},{0.94917f,0.314763f,-5.01206e-016f}, -{0.967287f,0.253683f,-2.42347e-016f},{0.991791f,0.12787f,-1.89542e-017f},{0.997946f,0.0640673f,-1.23846e-016f}, -{0.997945f,0.0640792f,-2.32866e-016f},{0.991787f,0.127897f,-1.33263e-017f},{-0.0320605f,0.999486f,-1.28965e-018f}, -{-0.0960397f,0.995377f,5.40854e-017f},{-0.0960134f,0.99538f,0.0f},{-0.159589f,0.987184f,-2.56782e-017f}, -{-0.15962f,0.987179f,2.56832e-017f},{-0.222542f,0.974923f,-1.56867e-016f},{-0.22251f,0.97493f,-1.38967e-016f}, -{-0.284548f,0.958662f,-6.86764e-017f},{-0.284517f,0.958671f,2.28896e-017f},{-0.345353f,0.938473f,3.57572e-016f}, -{-0.345385f,0.938461f,-5.5573e-017f},{-0.404803f,0.914404f,6.51336e-017f},{-0.404769f,0.914419f,1.6282e-016f}, -{-0.462558f,0.886589f,3.72132e-017f},{-0.462522f,0.886608f,7.44207e-017f},{-0.518376f,0.855153f,2.33487e-016f}, -{-0.518412f,0.855131f,1.08358e-016f},{-0.572134f,0.82016f,-1.38086e-016f},{-0.572101f,0.820183f,2.63938e-016f}, -{-0.623505f,0.781819f,-2.00646e-016f},{-0.623476f,0.781843f,0.0f},{-0.672288f,0.740289f,0.0f}, -{-0.672313f,0.740267f,1.08176e-016f},{-0.761447f,0.648227f,0.0f},{-0.801409f,0.598117f,0.0f}, -{-0.801406f,0.598121f,-1.28948e-016f},{-0.838075f,0.545555f,-1.34848e-016f},{-0.838084f,0.545542f,0.0f}, -{-0.871315f,0.490723f,0.0f},{-0.900965f,0.433892f,0.0f},{-0.90096f,0.433902f,-1.34297e-016f}, -{-0.926902f,0.375304f,-1.4914e-016f},{-0.926953f,0.375176f,2.98297e-016f},{-0.94917f,0.314763f,0.0f}, -{-0.949042f,0.315149f,0.0f},{-0.967317f,0.25357f,-1.55643e-016f},{-0.967287f,0.253683f,7.63412e-018f}, -{-0.981554f,0.191184f,1.57934e-016f},{-0.981559f,0.191157f,1.2303e-016f},{-0.991787f,0.127897f,2.41896e-016f}, -{-0.997945f,0.0640791f,-1.60571e-016f},{-0.761438f,0.648238f,0.0f},{-0.718339f,0.695693f,2.23877e-016f}, -{-0.718357f,0.695675f,-4.47741e-016f},{0.0960133f,0.99538f,3.51215e-016f},{0.0320605f,0.999486f,3.42273e-016f}, -{-0.032044f,0.999486f,-4.72146e-016f},{0.032044f,0.999486f,1.27624e-015f},{0.159589f,0.987184f,7.94198e-016f}, -{0.15962f,0.987179f,-5.022e-016f},{0.22251f,0.974931f,-3.78511e-016f},{0.222542f,0.974923f,5.9166e-016f}, -{0.284517f,0.958671f,3.08504e-016f},{0.284548f,0.958662f,8.02594e-016f},{0.345353f,0.938473f,-7.5501e-016f}, -{0.518376f,0.855153f,-8.32879e-016f},{0.462522f,0.886608f,-5.02391e-016f},{0.462558f,0.886589f,6.82274e-017f}, -{0.345385f,0.938461f,-1.39465e-015f},{0.404803f,0.914404f,2.03832e-016f},{0.404769f,0.914419f,-8.20038e-017f}, -{0.572101f,0.820183f,-1.06879e-015f},{0.518412f,0.855131f,6.78507e-016f},{0.572134f,0.82016f,6.60622e-016f}, -{0.623475f,0.781843f,9.80918e-016f},{0.672313f,0.740267f,2.57355e-016f},{0.672288f,0.740289f,-2.9505e-016f}, -{0.623505f,0.781819f,4.08838e-016f},{0.718339f,0.695693f,-1.96803e-016f},{0.718357f,0.695675f,2.10791e-016f}, -{0.761438f,0.648238f,-4.65431e-016f},{0.761447f,0.648227f,-3.46836e-016f},{0.801409f,0.598117f,3.19296e-016f}, -{0.801406f,0.598121f,2.0836e-016f},{0.981554f,0.191184f,-1.63198e-016f},{0.967317f,0.25357f,1.39352e-016f}, -{0.981559f,0.191157f,1.09203e-016f},{0.871315f,0.490723f,2.84009e-016f},{0.90096f,0.433902f,9.59966e-017f}, -{0.871302f,0.490747f,0.0f},{0.838075f,0.545555f,-2.20643e-016f},{0.838084f,0.545542f,3.61373e-016f}, -{0.900965f,0.433892f,-1.38293e-016f},{0.926902f,0.375304f,-1.28524e-016f},{0.926953f,0.375176f,1.80871e-017f}, -{0.949042f,0.315149f,6.82655e-017f},{0.94917f,0.314763f,1.30547e-016f},{0.967287f,0.253683f,1.42883e-016f}, -{0.991791f,0.12787f,4.92136e-017f},{0.997946f,0.0640673f,-3.34814e-017f},{0.997945f,0.0640792f,-3.21075e-017f}, -{0.991787f,0.127897f,-4.36713e-017f},{1.0f,-1.18424e-016f,0.0f},{1.0f,-1.22125e-016f,0.0f}, -{-0.0320605f,0.999486f,6.63911e-016f},{-0.0960397f,0.995377f,-2.58504e-016f},{-0.0960134f,0.99538f,8.3169e-016f}, -{-0.159589f,0.987184f,9.53038e-016f},{-0.15962f,0.987179f,3.17678e-016f},{-0.222542f,0.974923f,-8.69587e-016f}, -{-0.22251f,0.97493f,3.99e-016f},{-0.284548f,0.958662f,-7.08571e-016f},{-0.284517f,0.958671f,1.83117e-016f}, -{-0.345353f,0.938473f,4.92873e-016f},{-0.345385f,0.938461f,-4.13146e-016f},{-0.404803f,0.914404f,1.30267e-016f}, -{-0.404769f,0.914419f,-2.60512e-016f},{-0.462558f,0.886589f,-1.23983e-017f},{-0.462522f,0.886608f,2.72945e-016f}, -{-0.518376f,0.855153f,5.50383e-016f},{-0.518412f,0.855131f,0.0f},{-0.572134f,0.82016f,-5.27861e-016f}, -{-0.572101f,0.820183f,-3.68209e-016f},{-0.623505f,0.781819f,-1.15607e-015f},{-0.623476f,0.781843f,9.04474e-016f}, -{-0.672288f,0.740289f,4.3269e-016f},{-0.672313f,0.740267f,-1.38559e-015f},{-0.761447f,0.648227f,4.90073e-016f}, -{-0.801409f,0.598117f,-7.08269e-016f},{-0.801406f,0.598121f,5.15791e-016f},{-0.838075f,0.545555f,1.42991e-015f}, -{-0.838084f,0.545542f,5.39397e-016f},{-0.871315f,0.490723f,1.4374e-015f},{-0.871302f,0.490747f,8.05705e-016f}, -{-0.900965f,0.433892f,2.79256e-016f},{-0.90096f,0.433902f,-2.79263e-016f},{-0.926902f,0.375304f,-1.19312e-015f}, -{-0.94917f,0.314763f,-6.10893e-016f},{-0.949042f,0.315149f,6.10811e-016f},{-0.981559f,0.191157f,1.26348e-015f}, -{-0.991791f,0.12787f,-1.27665e-015f},{-0.997946f,0.0640673f,-4.12342e-017f},{-0.997945f,0.0640791f,0.0f}, -{-1.0f,2.96059e-017f,0.0f},{-0.761438f,0.648238f,6.98673e-016f},{-0.718339f,0.695693f,2.38452e-016f}, -{-0.718357f,0.695675f,2.23871e-016f},{0.0960133f,0.99538f,9.26924e-017f},{0.0320605f,0.999486f,0.0f}, -{0.0960396f,0.995378f,-1.60158e-016f},{-0.032044f,0.999486f,1.81443e-016f},{0.032044f,0.999486f,1.03119e-017f}, -{0.159589f,0.987184f,-1.02713e-016f},{0.15962f,0.987179f,5.13664e-017f},{0.22251f,0.974931f,-3.58022e-017f}, -{0.222542f,0.974923f,-1.14241e-016f},{0.284517f,0.958671f,7.7126e-017f},{0.284548f,0.958662f,-2.31376e-016f}, -{0.345353f,0.938473f,-1.99332e-017f},{0.518376f,0.855153f,1.59511e-016f},{0.462522f,0.886608f,-7.44207e-017f}, -{0.462558f,0.886589f,7.44265e-017f},{0.345385f,0.938461f,1.31073e-016f},{0.404803f,0.914404f,-2.03832e-016f}, -{0.404769f,0.914419f,3.42516e-016f},{0.572101f,0.820183f,0.0f},{0.518412f,0.855131f,1.37592e-016f}, -{0.572134f,0.82016f,-9.20575e-017f},{0.623475f,0.781843f,2.70309e-016f},{0.672313f,0.740267f,1.21844e-016f}, -{0.672288f,0.740289f,4.072e-017f},{0.623505f,0.781819f,-2.46886e-017f},{0.718339f,0.695693f,5.59692e-017f}, -{0.718357f,0.695675f,-1.58167e-017f},{0.761438f,0.648238f,9.58184e-017f},{0.761447f,0.648227f,0.0f}, -{0.801409f,0.598117f,-1.73215e-016f},{0.801406f,0.598121f,-4.04141e-017f},{0.981554f,0.191184f,-1.63905e-016f}, -{0.967317f,0.25357f,-7.6878e-017f},{0.981559f,0.191157f,5.28888e-017f},{0.871315f,0.490723f,1.89545e-016f}, -{0.90096f,0.433902f,2.2772e-016f},{0.871302f,0.490747f,-3.40821e-016f},{0.838075f,0.545555f,-1.33657e-016f}, -{0.838084f,0.545542f,-1.67369e-016f},{0.900965f,0.433892f,2.95425e-017f},{0.926902f,0.375304f,4.04643e-016f}, -{0.926953f,0.375176f,-1.73096e-017f},{0.949042f,0.315149f,7.36158e-017f},{0.94917f,0.314763f,-7.22027e-018f}, -{0.967287f,0.253683f,-1.19283e-019f},{0.991791f,0.12787f,8.57703e-019f},{0.997946f,0.0640673f,-5.42011e-017f}, -{0.997945f,0.0640792f,-2.44892e-017f},{0.991787f,0.127897f,-1.77286e-016f},{1.0f,-1.59132e-016f,0.0f}, -{-0.0320605f,0.999486f,0.0f},{-0.0960397f,0.995377f,0.0f},{-0.159589f,0.987184f,-1.02713e-016f}, -{-0.15962f,0.987179f,2.10205e-016f},{-0.222542f,0.974923f,-7.16149e-017f},{-0.22251f,0.97493f,7.16044e-017f}, -{-0.284548f,0.958662f,-3.08501e-016f},{-0.284517f,0.958671f,-9.15586e-017f},{-0.345353f,0.938473f,0.0f}, -{-0.345385f,0.938461f,0.0f},{-0.404769f,0.914419f,0.0f},{-0.462522f,0.886608f,0.0f}, -{-0.518376f,0.855153f,-5.84395e-017f},{-0.518412f,0.855131f,-3.33654e-016f},{-0.572134f,0.82016f,0.0f}, -{-0.623505f,0.781819f,-6.52885e-016f},{-0.672288f,0.740289f,8.6538e-016f},{-0.672313f,0.740267f,-2.38221e-016f}, -{-0.761447f,0.648227f,1.18875e-015f},{-0.801409f,0.598117f,-1.54738e-015f},{-0.801406f,0.598121f,-5.15791e-016f}, -{-0.838075f,0.545555f,3.6383e-016f},{-0.871315f,0.490723f,1.12157e-015f},{-0.871302f,0.490747f,1.12155e-015f}, -{-0.900965f,0.433892f,5.79868e-016f},{-0.90096f,0.433902f,-5.79865e-016f},{-0.926902f,0.375304f,0.0f}, -{-0.926953f,0.375176f,-5.96594e-016f},{-0.94917f,0.314763f,6.10893e-016f},{-0.967317f,0.25357f,-1.40834e-015f}, -{-0.967287f,0.253683f,1.63272e-016f},{-0.981559f,0.191157f,1.38651e-015f},{-0.991791f,0.12787f,-1.19435e-015f}, -{-0.991787f,0.127897f,8.23157e-017f},{-1.0f,1.4803e-017f,0.0f},{-0.104013f,0.994576f,3.5353e-016f}, -{0.105163f,0.994455f,-6.06197e-016f},{0.104013f,0.994576f,-5.89909e-016f},{-0.105163f,0.994455f,9.60058e-016f}, -{-0.308272f,0.951298f,4.26112e-018f},{-0.310578f,0.950548f,-4.99725e-017f},{-0.50141f,0.86521f,-3.27865e-016f}, -{-0.66887f,0.743379f,-5.14273e-016f},{-0.499433f,0.866353f,9.45034e-016f},{-0.670096f,0.742274f,-6.85702e-016f}, -{-0.808947f,0.587881f,-3.17829e-016f},{-0.809606f,0.586974f,-1.49813e-016f},{-0.913543f,0.406743f,4.89574e-016f}, -{-0.913862f,0.406026f,-3.27139e-016f},{-0.978165f,0.20783f,4.59595e-016f},{-0.978254f,0.207408f,2.95231e-016f}, -{-1.0f,-1.33227e-015f,0.0f},{0.499433f,0.866353f,-5.57591e-016f},{0.310578f,0.950548f,0.0f}, -{0.50141f,0.86521f,-1.61356e-016f},{0.66887f,0.743379f,-9.56889e-016f},{0.670096f,0.742274f,-6.93373e-016f}, -{0.808947f,0.587881f,-1.18042e-016f},{0.913543f,0.406743f,5.23566e-016f},{0.809606f,0.586974f,4.03822e-016f}, -{0.913862f,0.406026f,2.94084e-016f},{1.0f,1.18424e-015f,0.0f},{-0.104013f,0.994576f,3.36794e-016f}, -{0.105163f,0.994455f,-6.5696e-016f},{0.104013f,0.994576f,-6.56853e-016f},{-0.105163f,0.994455f,8.92374e-016f}, -{-0.308272f,0.951298f,2.27468e-016f},{-0.310578f,0.950548f,2.49863e-017f},{-0.50141f,0.86521f,-4.69051e-016f}, -{-0.499433f,0.866353f,9.65124e-016f},{-0.670096f,0.742274f,-7.26134e-016f},{-0.808947f,0.587881f,-9.00466e-017f}, -{-0.809606f,0.586974f,-5.2113e-017f},{-0.913543f,0.406743f,4.25266e-016f},{-0.913862f,0.406026f,-5.24727e-016f}, -{-0.978165f,0.20783f,6.42805e-016f},{-0.978254f,0.207408f,9.93815e-018f},{-1.0f,1.25825e-015f,0.0f}, -{0.308272f,0.951298f,-9.9203e-017f},{0.310578f,0.950548f,-9.99451e-017f},{0.809606f,0.586974f,-3.77781e-016f}, -{0.913862f,0.406026f,5.88168e-016f},{0.978254f,0.207408f,-6.29612e-016f},{1.0f,-1.18424e-015f,0.0f}, -{-0.104013f,0.994576f,9.93647e-016f},{0.105163f,0.994455f,1.31392e-015f},{0.104013f,0.994576f,5.02078e-017f}, -{-0.105163f,0.994455f,3.20019e-016f},{-0.308272f,0.951298f,-6.08002e-016f},{-0.50141f,0.86521f,5.07418e-016f}, -{-0.66887f,0.743379f,-6.33884e-016f},{-0.499433f,0.866353f,-4.48944e-016f},{-0.670096f,0.742274f,-8.85355e-017f}, -{-0.808947f,0.587881f,3.44309e-016f},{-0.809606f,0.586974f,7.94639e-016f},{-0.913543f,0.406743f,3.42322e-016f}, -{-0.913862f,0.406026f,3.83328e-016f},{-0.978165f,0.20783f,5.54168e-016f},{-0.978254f,0.207408f,1.60699e-016f}, -{0.308272f,0.951298f,1.22453e-015f},{0.499433f,0.866353f,5.57591e-016f},{0.310578f,0.950548f,-1.22356e-015f}, -{0.66887f,0.743379f,4.78444e-016f},{0.670096f,0.742274f,-2.1564e-016f},{0.913543f,0.406743f,-5.23566e-016f}, -{0.809606f,0.586974f,1.15938e-015f},{-0.104013f,0.994576f,9.76911e-016f},{0.105163f,0.994455f,1.26316e-015f}, -{0.104013f,0.994576f,-1.67359e-017f},{-0.105163f,0.994455f,2.52336e-016f},{-0.308272f,0.951298f,-3.84795e-016f}, -{-0.50141f,0.86521f,3.66232e-016f},{-0.499433f,0.866353f,-4.28854e-016f},{-0.670096f,0.742274f,-1.28968e-016f}, -{-0.808947f,0.587881f,5.72092e-016f},{-0.809606f,0.586974f,8.92339e-016f},{-0.913543f,0.406743f,2.78013e-016f}, -{-0.913862f,0.406026f,1.85741e-016f},{-0.978165f,0.20783f,7.37379e-016f},{-0.978254f,0.207408f,-1.24594e-016f}, -{0.308272f,0.951298f,1.12532e-015f},{0.310578f,0.950548f,-1.3235e-015f},{0.809606f,0.586974f,3.77781e-016f}, -{-0.104013f,0.994576f,9.26703e-016f},{0.105163f,0.994455f,1.17855e-015f},{0.104013f,0.994576f,-3.34719e-017f}, -{-0.105163f,0.994455f,3.87703e-016f},{-0.308272f,0.951298f,-3.10392e-016f},{-0.310578f,0.950548f,2.49863e-016f}, -{-0.50141f,0.86521f,7.29282e-016f},{-0.66887f,0.743379f,1.18511e-017f},{-0.499433f,0.866353f,-3.48494e-016f}, -{-0.670096f,0.742274f,-1.02013e-016f},{-0.808947f,0.587881f,1.97878e-016f},{-0.809606f,0.586974f,1.21801e-015f}, -{-0.913543f,0.406743f,2.04518e-016f},{-0.913862f,0.406026f,5.70787e-017f},{-0.978165f,0.20783f,8.92923e-016f}, -{-0.978254f,0.207408f,-6.1033e-016f},{-1.0f,2.51651e-015f,0.0f},{0.308272f,0.951298f,1.02612e-015f}, -{0.50141f,0.86521f,3.22711e-016f},{0.670096f,0.742274f,-4.31279e-016f},{0.808947f,0.587881f,-8.99009e-016f}, -{0.978254f,0.207408f,-1.25922e-015f},{0.104013f,0.994576f,1.33888e-016f},{-0.308272f,0.951298f,-7.56806e-016f}, -{-0.310578f,0.950548f,4.99725e-017f},{-0.50141f,0.86521f,5.27588e-016f},{-0.66887f,0.743379f,-1.11819e-015f}, -{-0.499433f,0.866353f,-3.88674e-016f},{-0.670096f,0.742274f,-6.41112e-016f},{-0.808947f,0.587881f,-7.94601e-016f}, -{-0.809606f,0.586974f,1.00632e-015f},{-0.913543f,0.406743f,7.28172e-016f},{-0.913862f,0.406026f,8.29049e-016f}, -{-0.978165f,0.20783f,2.91649e-016f},{-0.978254f,0.207408f,-5.20414e-017f},{-1.0f,-2.66454e-015f,0.0f}, -{0.499433f,0.866353f,8.7903e-016f},{0.310578f,0.950548f,-1.12361e-015f},{0.50141f,0.86521f,0.0f}, -{0.670096f,0.742274f,0.0f},{0.809606f,0.586974f,1.41992e-015f},{0.104013f,0.994576f,-5.06229e-016f}, -{-0.105163f,0.994455f,1.02774e-015f},{-0.308272f,0.951298f,-1.44543e-016f},{-0.50141f,0.86521f,-3.07696e-016f}, -{-0.66887f,0.743379f,-9.98574e-016f},{-0.499433f,0.866353f,1.0053e-015f},{-0.670096f,0.742274f,-1.23828e-015f}, -{-0.808947f,0.587881f,-1.45674e-015f},{-0.809606f,0.586974f,6.18708e-017f},{-0.913543f,0.406743f,8.75425e-016f}, -{-0.913862f,0.406026f,1.18582e-016f},{-0.978165f,0.20783f,1.97076e-016f},{-0.978254f,0.207408f,8.24911e-017f}, -{0.499433f,0.866353f,-2.36152e-016f},{0.310578f,0.950548f,9.99451e-017f},{0.670096f,0.742274f,-4.77733e-016f}, -{0.809606f,0.586974f,6.64356e-016f},{0.105163f,0.994455f,-7.07722e-016f},{0.104013f,0.994576f,-7.40532e-016f}, -{-0.308272f,0.951298f,3.0187e-016f},{-0.310578f,0.950548f,9.99451e-017f},{-0.50141f,0.86521f,-1.4634e-016f}, -{-0.66887f,0.743379f,-2.72122e-016f},{-0.499433f,0.866353f,1.16602e-015f},{-0.670096f,0.742274f,-6.4527e-016f}, -{-0.808947f,0.587881f,-4.8053e-016f},{-0.809606f,0.586974f,-2.8008e-016f},{-0.913543f,0.406743f,6.18191e-016f}, -{-0.913862f,0.406026f,-5.15537e-016f},{-0.978165f,0.20783f,-3.56243e-016f},{-0.978254f,0.207408f,9.60179e-017f}, -{-1.0f,2.66454e-015f,0.0f},{0.308272f,0.951298f,9.9203e-017f},{0.310578f,0.950548f,-2.99835e-016f}, -{0.66887f,0.743379f,-1.38738e-015f},{0.670096f,0.742274f,-4.64542e-017f},{0.808947f,0.587881f,6.62925e-016f}, -{0.913543f,0.406743f,-6.43974e-017f},{0.809606f,0.586974f,-8.98849e-016f},{0.978165f,0.20783f,1.25911e-015f}, -{0.826318f,-0.563203f,2.17827e-015f},{0.642788f,-0.766044f,-8.27406e-016f},{0.411158f,-0.911564f,-1.4099e-015f}, -{0.158603f,-0.987342f,-1.62037e-016f},{0.944801f,-0.327644f,1.31796e-017f},{-0.911564f,0.411158f,2.34469e-015f}, -{-0.766044f,0.642788f,-2.74725e-017f},{-0.563203f,0.826318f,-5.49955e-016f},{-0.327644f,0.944801f,-2.4991e-016f}, -{-0.987342f,0.158603f,2.54184e-015f},{0.0746326f,0.997211f,-2.34456e-017f},{-0.074795f,0.997199f,-5.19989e-016f}, -{-0.0746326f,0.997211f,2.89595e-016f},{0.222381f,0.97496f,-5.69819e-016f},{0.074795f,0.997199f,1.28888e-016f}, -{0.222585f,0.974913f,-9.61018e-016f},{0.365177f,0.930938f,7.43247e-016f},{0.365379f,0.930859f,1.64673e-015f}, -{0.49999f,0.866031f,-6.16426e-016f},{0.499833f,0.866122f,1.18802e-015f},{0.623256f,0.782018f,-4.36855e-016f}, -{0.82663f,0.562746f,-2.05696e-015f},{0.900794f,0.434246f,-2.67821e-015f},{0.826061f,0.563581f,3.78148e-015f}, -{0.623488f,0.781833f,2.4348e-015f},{0.732917f,0.680318f,-3.91184e-015f},{0.733034f,0.680192f,-2.46978e-015f}, -{0.901683f,0.432397f,-1.33326e-016f},{0.955502f,0.294984f,9.24071e-016f},{0.955572f,0.294759f,-1.22029e-015f}, -{0.988846f,0.148938f,2.44716e-015f},{0.988818f,0.149126f,-1.41507e-015f},{-0.222381f,0.97496f,-5.76348e-016f}, -{-0.365177f,0.930938f,3.67387e-017f},{-0.222585f,0.974913f,-4.28956e-017f},{-0.365379f,0.930859f,7.43524e-017f}, -{-0.499834f,0.866121f,1.2601e-015f},{-0.499989f,0.866031f,-1.2789e-015f},{-0.623256f,0.782018f,-1.648e-015f}, -{-0.732917f,0.680318f,3.01013e-017f},{-0.623488f,0.781833f,-3.28495e-015f},{-0.733034f,0.680192f,-1.85694e-015f}, -{-0.826061f,0.563581f,-2.135e-015f},{-0.82663f,0.562746f,-4.26401e-015f},{-0.900794f,0.434246f,2.32224e-015f}, -{-0.955502f,0.294984f,2.79226e-018f},{-0.901683f,0.432397f,-1.33512e-017f},{-0.955572f,0.294759f,-3.07218e-018f}, -{-0.988818f,0.149126f,8.60722e-020f},{-0.988846f,0.148938f,1.12747e-019f},{0.0746326f,0.997211f,2.56725e-015f}, -{-0.074795f,0.997199f,-1.28361e-015f},{-0.0746326f,0.997211f,3.84937e-015f},{0.222381f,0.97496f,-6.27044e-015f}, -{0.074795f,0.997199f,-1.28211e-015f},{0.222585f,0.974913f,-1.87791e-015f},{0.365177f,0.930938f,-1.10171e-017f}, -{0.365379f,0.930859f,-2.40011e-015f},{0.49999f,0.866031f,-3.0455e-015f},{0.499833f,0.866122f,2.50346e-015f}, -{0.623256f,0.782018f,-7.54969e-016f},{0.82663f,0.562746f,1.35373e-016f},{0.900794f,0.434246f,8.30693e-016f}, -{0.826061f,0.563581f,-3.70334e-017f},{0.623488f,0.781833f,7.8614e-016f},{0.732917f,0.680318f,0.0f}, -{0.733034f,0.680192f,-9.83866e-017f},{0.901683f,0.432397f,-2.82436e-016f},{0.955502f,0.294984f,-5.75977e-016f}, -{0.955572f,0.294759f,6.52881e-016f},{0.988846f,0.148938f,8.2274e-016f},{0.988818f,0.149126f,1.39061e-016f}, -{-0.222381f,0.97496f,-2.50997e-015f},{-0.365177f,0.930938f,4.80796e-015f},{-0.222585f,0.974913f,3.76477e-015f}, -{-0.365379f,0.930859f,2.39643e-015f},{-0.499834f,0.866121f,-2.22977e-015f},{-0.623256f,0.782018f,0.0f}, -{-0.732917f,0.680318f,-2.94819e-017f},{-0.623488f,0.781833f,-6.0634e-015f},{-0.733034f,0.680192f,-2.94867e-017f}, -{-0.826061f,0.563581f,2.9018e-015f},{-0.82663f,0.562746f,2.831e-015f},{-0.900794f,0.434246f,7.24697e-017f}, -{-0.955502f,0.294984f,-7.68711e-017f},{-0.901683f,0.432397f,-1.11318e-015f},{-0.955572f,0.294759f,0.0f}, -{-0.988818f,0.149126f,-7.67832e-016f},{-0.988846f,0.148938f,-7.95536e-017f},{0.0746326f,0.997211f,7.26226e-017f}, -{-0.074795f,0.997199f,-3.86026e-017f},{-0.0746326f,0.997211f,1.39011e-018f},{0.222381f,0.97496f,-2.83567e-016f}, -{0.074795f,0.997199f,-1.59944e-016f},{0.222585f,0.974913f,4.17819e-017f},{0.365177f,0.930938f,-1.96876e-016f}, -{0.365379f,0.930859f,-1.1752e-015f},{0.49999f,0.866031f,1.15346e-015f},{0.499833f,0.866122f,-2.59619e-016f}, -{0.623256f,0.782018f,-2.04138e-015f},{0.82663f,0.562746f,6.03166e-016f},{0.900794f,0.434246f,5.46692e-016f}, -{0.826061f,0.563581f,-1.66803e-015f},{0.623488f,0.781833f,1.23095e-015f},{0.732917f,0.680318f,9.23191e-016f}, -{0.733034f,0.680192f,-2.70567e-015f},{0.901683f,0.432397f,-2.81735e-015f},{0.955502f,0.294984f,3.82595e-015f}, -{0.955572f,0.294759f,5.47878e-016f},{0.988846f,0.148938f,-6.9894e-016f},{0.988818f,0.149126f,-2.60585e-015f}, -{-0.222381f,0.97496f,-2.90095e-016f},{-0.222585f,0.974913f,2.43619e-016f},{-0.499989f,0.866031f,1.29548e-015f}, -{-0.623256f,0.782018f,-3.25253e-015f},{-0.732917f,0.680318f,-1.85674e-015f},{-0.623488f,0.781833f,-1.67982e-015f}, -{-0.733034f,0.680192f,3.02069e-017f},{-0.826061f,0.563581f,4.24491e-015f},{-0.82663f,0.562746f,-7.8038e-018f}, -{-0.955502f,0.294984f,-4.91695e-015f},{-0.955572f,0.294759f,4.91703e-015f},{0.0746326f,0.997211f,-2.56725e-015f}, -{-0.074795f,0.997199f,2.56722e-015f},{-0.0746326f,0.997211f,3.85238e-015f},{0.222381f,0.97496f,-2.51444e-015f}, -{0.074795f,0.997199f,0.0f},{0.222585f,0.974913f,6.27462e-016f},{0.365177f,0.930938f,-4.18677e-015f}, -{0.365379f,0.930859f,-7.34878e-018f},{0.49999f,0.866031f,-8.31048e-016f},{0.499833f,0.866122f,-2.98827e-016f}, -{0.623256f,0.782018f,-2.42255e-016f},{0.82663f,0.562746f,2.14345e-016f},{0.900794f,0.434246f,-3.01398e-016f}, -{0.826061f,0.563581f,-6.76994e-016f},{0.623488f,0.781833f,-1.27366e-015f},{0.732917f,0.680318f,2.83318e-015f}, -{0.733034f,0.680192f,5.45378e-016f},{0.901683f,0.432397f,-2.82967e-015f},{0.955502f,0.294984f,1.20141e-015f}, -{0.955572f,0.294759f,1.26105e-015f},{0.988846f,0.148938f,-3.11202e-016f},{0.988818f,0.149126f,-3.47669e-016f}, -{-0.222381f,0.97496f,2.50997e-015f},{-0.365177f,0.930938f,2.41132e-015f},{-0.222585f,0.974913f,8.95358e-018f}, -{-0.365379f,0.930859f,1.46976e-017f},{-0.499989f,0.866031f,4.45908e-015f},{-0.623256f,0.782018f,-5.01415e-017f}, -{-0.732917f,0.680318f,2.94819e-017f},{-0.623488f,0.781833f,6.03832e-015f},{-0.733034f,0.680192f,1.81008e-015f}, -{-0.826061f,0.563581f,-1.4509e-015f},{-0.82663f,0.562746f,0.0f},{-0.900794f,0.434246f,0.0f}, -{-0.955502f,0.294984f,-1.51883e-015f},{-0.955572f,0.294759f,-7.68766e-017f},{-0.988818f,0.149126f,-7.95513e-017f}, -{-0.988846f,0.148938f,0.0f},{-0.933821f,0.357739f,0.0f},{-0.904255f,0.426992f,0.0f}, -{-0.904263f,0.426976f,0.0f},{-0.869576f,0.4938f,0.0f},{-0.869571f,0.493808f,0.0f}, -{-0.829957f,0.557828f,0.0f},{-0.829967f,0.557812f,0.0f},{-0.785637f,0.618687f,0.0f}, -{-0.78564f,0.618684f,0.0f},{-0.736896f,0.676006f,0.0f},{-0.736809f,0.6761f,0.0f}, -{-0.683915f,0.729561f,0.0f},{-0.683922f,0.729555f,0.0f},{-0.627048f,0.77898f,0.0f}, -{-0.627107f,0.778933f,0.0f},{-0.566722f,0.823909f,0.0f},{-0.566664f,0.823949f,0.0f}, -{-0.503086f,0.864236f,0.0f},{-0.503098f,0.864229f,0.0f},{-0.436614f,0.899649f,0.0f}, -{-0.436655f,0.899629f,0.0f},{-0.367737f,0.92993f,0.0f},{-0.367679f,0.929953f,0.0f}, -{-0.296679f,0.954977f,0.0f},{-0.296721f,0.954964f,0.0f},{-0.223998f,0.97459f,0.0f}, -{-0.224026f,0.974583f,0.0f},{-0.150064f,0.988676f,0.0f},{-0.150035f,0.988681f,0.0f}, -{-0.0752244f,0.997167f,0.0f},{-0.0752458f,0.997165f,0.0f},{-1.35203e-015f,1.0f,0.0f}, -{-1.54518e-015f,1.0f,0.0f},{-0.933815f,0.357756f,0.0f},{-0.958087f,0.286476f,0.0f}, -{-0.958085f,0.286485f,0.0f},{-0.976924f,0.213586f,0.0f},{-0.97692f,0.213604f,0.0f}, -{-0.990224f,0.139487f,0.0f},{-0.990225f,0.139483f,0.0f},{-0.997917f,0.0645077f,0.0f}, -{-0.997909f,0.0646351f,0.0f},{-0.999943f,-0.0106703f,0.0f},{-0.999943f,-0.0106617f,0.0f}, -{-0.996308f,-0.0858467f,0.0f},{-0.996302f,-0.0859221f,0.0f},{-0.987014f,-0.160636f,0.0f}, -{-0.987025f,-0.160567f,0.0f},{-0.972136f,-0.234419f,0.0f},{-0.972139f,-0.234405f,0.0f}, -{-0.95175f,-0.306876f,0.0f},{-0.951735f,-0.306919f,0.0f},{-0.925942f,-0.377666f,0.0f}, -{-0.925965f,-0.377609f,0.0f},{-0.894907f,-0.446253f,0.0f},{-0.894927f,-0.446213f,0.0f}, -{-0.858816f,-0.512285f,0.0f},{-0.858801f,-0.51231f,0.0f},{-0.81782f,-0.575474f,0.0f}, -{-0.817838f,-0.575449f,0.0f},{-0.772206f,-0.635373f,0.0f},{-0.772219f,-0.635356f,0.0f}, -{-0.722222f,-0.691661f,0.0f},{-0.357739f,-0.933821f,0.0f},{-0.426992f,-0.904255f,0.0f}, -{-0.426976f,-0.904263f,0.0f},{-0.4938f,-0.869576f,0.0f},{-0.493808f,-0.869571f,0.0f}, -{-0.557828f,-0.829957f,0.0f},{-0.557812f,-0.829967f,0.0f},{-0.618687f,-0.785637f,0.0f}, -{-0.618684f,-0.78564f,0.0f},{-0.676006f,-0.736896f,0.0f},{-0.6761f,-0.736809f,0.0f}, -{-0.729561f,-0.683915f,0.0f},{-0.729555f,-0.683922f,0.0f},{-0.77898f,-0.627048f,0.0f}, -{-0.778933f,-0.627107f,0.0f},{-0.823909f,-0.566722f,0.0f},{-0.823949f,-0.566664f,0.0f}, -{-0.864236f,-0.503086f,0.0f},{-0.864229f,-0.503098f,0.0f},{-0.899649f,-0.436614f,0.0f}, -{-0.899629f,-0.436655f,0.0f},{-0.92993f,-0.367737f,0.0f},{-0.929953f,-0.367679f,0.0f}, -{-0.954977f,-0.296679f,0.0f},{-0.954964f,-0.296721f,0.0f},{-0.97459f,-0.223998f,0.0f}, -{-0.974583f,-0.224026f,0.0f},{-0.988676f,-0.150064f,0.0f},{-0.988681f,-0.150035f,0.0f}, -{-0.997167f,-0.0752244f,0.0f},{-0.997165f,-0.0752458f,0.0f},{-1.0f,7.72589e-016f,0.0f}, -{-0.357756f,-0.933815f,0.0f},{-0.286476f,-0.958087f,0.0f},{-0.286485f,-0.958085f,0.0f}, -{-0.213586f,-0.976924f,0.0f},{-0.213604f,-0.97692f,0.0f},{-0.139487f,-0.990224f,0.0f}, -{-0.139483f,-0.990225f,0.0f},{-0.0645077f,-0.997917f,0.0f},{-0.0646351f,-0.997909f,0.0f}, -{0.0106703f,-0.999943f,0.0f},{0.0106617f,-0.999943f,0.0f},{0.0858467f,-0.996308f,0.0f}, -{0.0859221f,-0.996302f,0.0f},{0.160636f,-0.987014f,0.0f},{0.160567f,-0.987025f,0.0f}, -{0.234419f,-0.972136f,0.0f},{0.234405f,-0.972139f,0.0f},{0.306876f,-0.95175f,0.0f}, -{0.306919f,-0.951735f,0.0f},{0.377666f,-0.925942f,0.0f},{0.377609f,-0.925965f,0.0f}, -{0.446253f,-0.894907f,0.0f},{0.446213f,-0.894927f,0.0f},{0.512285f,-0.858816f,0.0f}, -{0.51231f,-0.858801f,0.0f},{0.575474f,-0.81782f,0.0f},{0.575449f,-0.817838f,0.0f}, -{0.635373f,-0.772206f,0.0f},{0.635356f,-0.772219f,0.0f},{0.691661f,-0.722222f,0.0f}, -{0.933821f,-0.357739f,0.0f},{0.904255f,-0.426992f,0.0f},{0.904263f,-0.426976f,0.0f}, -{0.869576f,-0.4938f,0.0f},{0.869571f,-0.493808f,0.0f},{0.829957f,-0.557828f,0.0f}, -{0.829967f,-0.557812f,0.0f},{0.785637f,-0.618687f,0.0f},{0.78564f,-0.618684f,0.0f}, -{0.736896f,-0.676006f,0.0f},{0.736809f,-0.6761f,0.0f},{0.683915f,-0.729561f,0.0f}, -{0.683922f,-0.729555f,0.0f},{0.627048f,-0.77898f,0.0f},{0.627107f,-0.778933f,0.0f}, -{0.566722f,-0.823909f,0.0f},{0.566664f,-0.823949f,0.0f},{0.503086f,-0.864236f,0.0f}, -{0.503098f,-0.864229f,0.0f},{0.436614f,-0.899649f,0.0f},{0.436655f,-0.899629f,0.0f}, -{0.367737f,-0.92993f,0.0f},{0.367679f,-0.929953f,0.0f},{0.296679f,-0.954977f,0.0f}, -{0.296721f,-0.954964f,0.0f},{0.223998f,-0.97459f,0.0f},{0.224026f,-0.974583f,0.0f}, -{0.150064f,-0.988676f,0.0f},{0.150035f,-0.988681f,0.0f},{0.0752244f,-0.997167f,0.0f}, -{0.0752458f,-0.997165f,0.0f},{1.93147e-015f,-1.0f,0.0f},{1.54518e-015f,-1.0f,0.0f}, -{0.933815f,-0.357756f,0.0f},{0.958087f,-0.286476f,0.0f},{0.958085f,-0.286485f,0.0f}, -{0.976924f,-0.213586f,0.0f},{0.97692f,-0.213604f,0.0f},{0.990224f,-0.139487f,0.0f}, -{0.990225f,-0.139483f,0.0f},{0.997917f,-0.0645077f,0.0f},{0.997909f,-0.0646351f,0.0f}, -{0.999943f,0.0106703f,0.0f},{0.999943f,0.0106617f,0.0f},{0.996308f,0.0858467f,0.0f}, -{0.996302f,0.0859221f,0.0f},{0.987014f,0.160636f,0.0f},{0.987025f,0.160567f,0.0f}, -{0.972136f,0.234419f,0.0f},{0.972139f,0.234405f,0.0f},{0.95175f,0.306876f,0.0f}, -{0.951735f,0.306919f,0.0f},{0.925942f,0.377666f,0.0f},{0.925965f,0.377609f,0.0f}, -{0.894907f,0.446253f,0.0f},{0.894927f,0.446213f,0.0f},{0.858816f,0.512285f,0.0f}, -{0.858801f,0.51231f,0.0f},{0.81782f,0.575474f,0.0f},{0.817838f,0.575449f,0.0f}, -{0.772206f,0.635373f,0.0f},{0.772219f,0.635356f,0.0f},{0.722222f,0.691661f,0.0f}, -{0.0f,8.67362e-019f,1.0f},{0.0f,-3.25261e-019f,1.0f},{0.0f,-1.0842e-019f,1.0f}, -{0.0f,4.87891e-019f,1.0f},{0.0f,-1.6263e-019f,1.0f},{0.0f,7.04731e-019f,1.0f}, -{0.0f,2.1684e-019f,1.0f},{0.0f,-5.96311e-019f,1.0f},{0.0f,-4.87891e-019f,1.0f}, -{0.0f,-7.04731e-019f,1.0f},{0.0f,1.6263e-019f,1.0f},{0.0f,5.42101e-020f,1.0f}, -{0.0f,3.79471e-019f,1.0f},{0.0f,5.42101e-019f,1.0f},{0.0f,-3.79471e-019f,1.0f}, -{0.0f,-7.58942e-019f,1.0f},{0.0f,-6.50521e-019f,1.0f},{0.0f,7.86047e-019f,1.0f}, -{0.0f,-7.45389e-019f,1.0f},{0.0f,5.69206e-019f,1.0f},{0.0f,2.84603e-019f,1.0f}, -{0.0f,-3.15096e-019f,1.0f},{0.0f,2.43945e-019f,1.0f},{0.0f,-5.42101e-019f,1.0f}, -{0.0f,-2.1684e-019f,1.0f},{0.0f,-3.59142e-019f,1.0f},{0.0f,3.65918e-019f,1.0f}, -{0.0f,2.17158e-019f,1.0f},{0.0f,-6.10181e-019f,1.0f},{0.0f,6.77626e-019f,1.0f}, -{0.0f,-6.87791e-019f,1.0f},{0.0f,-4.60786e-019f,1.0f},{0.0f,-7.31836e-019f,1.0f}, -{0.0f,8.02987e-019f,1.0f},{0.0f,-6.77626e-019f,1.0f},{0.0f,-5.74712e-019f,1.0f}, -{0.0f,-1.76183e-019f,1.0f},{0.0f,2.71051e-019f,1.0f},{0.0f,7.58942e-019f,1.0f}, -{0.0f,-2.71051e-019f,1.0f},{0.0f,-8.13152e-019f,1.0f},{0.0f,5.96311e-019f,1.0f}, -{0.0f,-5.14996e-019f,1.0f},{0.0f,6.50521e-019f,1.0f},{0.0f,3.25261e-019f,1.0f}, -{0.0f,-5.42101e-020f,1.0f},{0.0f,1.0842e-019f,1.0f},{0.0f,4.60786e-019f,1.0f}, -{0.0f,8.26704e-019f,1.0f},{0.0f,2.25311e-019f,1.0f},{0.0f,6.60686e-019f,1.0f}, -{0.0f,-5.57348e-019f,1.0f},{4.16334e-016f,1.0f,0.0f},{0.999314f,0.0370361f,0.0f}, -{0.999323f,-0.036793f,0.0f},{0.999323f,0.0367929f,0.0f},{0.993826f,0.110947f,0.0f}, -{0.993828f,0.110936f,0.0f},{0.982882f,0.184236f,0.0f},{0.982886f,0.184212f,0.0f}, -{0.96655f,0.256477f,0.0f},{0.966539f,0.256521f,0.0f},{0.944889f,0.32739f,0.0f}, -{0.944907f,0.327338f,0.0f},{0.918057f,0.396448f,0.0f},{0.918074f,0.396408f,0.0f}, -{0.886197f,0.463309f,0.0f},{0.886182f,0.463337f,0.0f},{0.849433f,0.527696f,0.0f}, -{0.849456f,0.527659f,0.0f},{0.808016f,0.58916f,0.0f},{0.80806f,0.5891f,0.0f}, -{0.762212f,0.647328f,0.0f},{0.762181f,0.647364f,0.0f},{0.712153f,0.702024f,0.0f}, -{0.712214f,0.701962f,0.0f},{0.658207f,0.752837f,0.0f},{0.658254f,0.752796f,0.0f}, -{0.600685f,0.799486f,0.0f},{0.600678f,0.799491f,0.0f},{0.539832f,0.841773f,0.0f}, -{0.539844f,0.841765f,0.0f},{0.476025f,0.879432f,0.0f},{0.476043f,0.879422f,0.0f}, -{0.409619f,0.912257f,0.0f},{0.409607f,0.912262f,0.0f},{0.340942f,0.940084f,0.0f}, -{0.340954f,0.94008f,0.0f},{0.270403f,0.962747f,0.0f},{0.270418f,0.962743f,0.0f}, -{0.1984f,0.980121f,0.0f},{0.198377f,0.980126f,0.0f},{0.125268f,0.992123f,0.0f}, -{0.125266f,0.992123f,0.0f},{0.0513531f,0.998681f,0.0f},{0.0515068f,0.998673f,0.0f}, -{-0.0226075f,0.999744f,0.0f},{-0.0226241f,0.999744f,0.0f},{-0.0966381f,0.99532f,0.0f}, -{-0.0965597f,0.995327f,0.0f},{-0.170063f,0.985433f,0.0f},{-0.170003f,0.985444f,0.0f}, -{-0.242529f,0.970144f,0.0f},{-0.242546f,0.97014f,0.0f},{-0.313741f,0.949509f,0.0f}, -{-0.313692f,0.949525f,0.0f},{-0.383193f,0.923668f,0.0f},{-0.383138f,0.923691f,0.0f}, -{-0.450489f,0.892782f,0.0f},{-0.450523f,0.892765f,0.0f},{-0.515387f,0.856957f,0.0f}, -{-0.51536f,0.856974f,0.0f},{-0.577428f,0.816442f,0.0f},{-0.577403f,0.816459f,0.0f}, -{-0.636279f,0.771459f,0.0f},{-0.636295f,0.771446f,0.0f},{-0.691661f,0.722222f,0.0f}, -{0.999314f,-0.0370363f,0.0f},{0.993828f,-0.110936f,0.0f},{0.993826f,-0.110947f,0.0f}, -{0.982882f,-0.184236f,0.0f},{0.982886f,-0.184212f,0.0f},{0.966539f,-0.256521f,0.0f}, -{0.96655f,-0.256477f,0.0f},{0.944907f,-0.327338f,0.0f},{0.944889f,-0.32739f,0.0f}, -{0.918057f,-0.396448f,0.0f},{0.918074f,-0.396408f,0.0f},{0.886182f,-0.463337f,0.0f}, -{0.886197f,-0.463309f,0.0f},{0.849456f,-0.527659f,0.0f},{0.849433f,-0.527696f,0.0f}, -{0.808016f,-0.58916f,0.0f},{0.80806f,-0.5891f,0.0f},{0.762181f,-0.647364f,0.0f}, -{0.762212f,-0.647328f,0.0f},{0.712214f,-0.701962f,0.0f},{0.712153f,-0.702024f,0.0f}, -{0.658207f,-0.752837f,0.0f},{0.658255f,-0.752795f,0.0f},{0.600678f,-0.799491f,0.0f}, -{0.600685f,-0.799486f,0.0f},{0.539843f,-0.841765f,0.0f},{0.539832f,-0.841773f,0.0f}, -{0.476025f,-0.879432f,0.0f},{0.476043f,-0.879422f,0.0f},{0.409606f,-0.912262f,0.0f}, -{0.409619f,-0.912257f,0.0f},{0.340954f,-0.94008f,0.0f},{0.340942f,-0.940084f,0.0f}, -{0.270403f,-0.962747f,0.0f},{0.270418f,-0.962743f,0.0f},{0.198378f,-0.980126f,0.0f}, -{0.1984f,-0.980121f,0.0f},{0.125266f,-0.992123f,0.0f},{0.125268f,-0.992123f,0.0f}, -{0.0513531f,-0.998681f,0.0f},{0.0515067f,-0.998673f,0.0f},{-0.0226239f,-0.999744f,0.0f}, -{-0.0226076f,-0.999744f,0.0f},{-0.0965598f,-0.995327f,0.0f},{-0.0966381f,-0.99532f,0.0f}, -{-0.170063f,-0.985433f,0.0f},{-0.170003f,-0.985444f,0.0f},{-0.242546f,-0.97014f,0.0f}, -{-0.242529f,-0.970144f,0.0f},{-0.313693f,-0.949525f,0.0f},{-0.313741f,-0.949509f,0.0f}, -{-0.383193f,-0.923668f,0.0f},{-0.383138f,-0.923691f,0.0f},{-0.450523f,-0.892765f,0.0f}, -{-0.450489f,-0.892782f,0.0f},{-0.51536f,-0.856974f,0.0f},{-0.515387f,-0.856957f,0.0f}, -{-0.577428f,-0.816442f,0.0f},{-0.577403f,-0.816459f,0.0f},{-0.636295f,-0.771446f,0.0f}, -{-0.636279f,-0.771459f,0.0f},{-0.691661f,-0.722222f,0.0f},{6.5746e-016f,-1.0f,0.0f}, -{-2.22045e-016f,-1.0f,0.0f},{1.0f,1.22298e-016f,0.0f},{1.0f,1.11022e-016f,0.0f}, -{-0.0752459f,-0.997165f,0.0f},{-9.09877e-012f,-1.0f,0.0f},{-1.02144e-013f,-1.0f,0.0f}, -{-0.296679f,-0.954977f,0.0f},{-0.223998f,-0.97459f,0.0f},{-0.296721f,-0.954964f,0.0f}, -{-0.224026f,-0.974583f,0.0f},{-0.150034f,-0.988681f,0.0f},{-0.150064f,-0.988676f,0.0f}, -{-0.436614f,-0.899649f,0.0f},{-0.503098f,-0.864229f,0.0f},{-0.503086f,-0.864236f,0.0f}, -{-0.367737f,-0.92993f,0.0f},{-0.436655f,-0.899629f,0.0f},{-0.367679f,-0.929953f,0.0f}, -{-0.736896f,-0.676006f,0.0f},{-0.683915f,-0.729561f,0.0f},{-0.683922f,-0.729555f,0.0f}, -{-0.627048f,-0.77898f,0.0f},{-0.566664f,-0.823949f,0.0f},{-0.627107f,-0.778933f,0.0f}, -{-0.829957f,-0.557828f,0.0f},{-0.829967f,-0.557812f,0.0f},{-0.869576f,-0.4938f,0.0f}, -{-0.736809f,-0.6761f,0.0f},{-0.78564f,-0.618684f,0.0f},{-0.785637f,-0.618687f,0.0f}, -{-0.933821f,-0.357739f,0.0f},{-0.958087f,-0.286476f,0.0f},{-0.933815f,-0.357756f,0.0f}, -{-0.904263f,-0.426976f,0.0f},{-0.904255f,-0.426992f,0.0f},{-0.869571f,-0.493808f,0.0f}, -{-0.997917f,-0.0645078f,0.0f},{-0.990224f,-0.139487f,0.0f},{-0.990224f,-0.139483f,0.0f}, -{-0.97692f,-0.213603f,0.0f},{-0.958085f,-0.286485f,0.0f},{-0.976924f,-0.213586f,0.0f}, -{-0.996308f,0.0858467f,0.0f},{-0.999943f,0.0106617f,0.0f},{-0.996302f,0.085922f,0.0f}, -{-0.997909f,-0.0646351f,0.0f},{-0.999943f,0.0106703f,0.0f},{-0.972139f,0.234405f,0.0f}, -{-0.987025f,0.160567f,0.0f},{-0.972136f,0.234419f,0.0f},{-0.987014f,0.160636f,0.0f}, -{-0.951735f,0.306919f,0.0f},{-0.95175f,0.306876f,0.0f},{-0.925942f,0.377666f,0.0f}, -{-0.925965f,0.377609f,0.0f},{-0.894927f,0.446213f,0.0f},{-0.894907f,0.446253f,0.0f}, -{-0.858801f,0.51231f,0.0f},{-0.858815f,0.512285f,0.0f},{-0.81782f,0.575474f,0.0f}, -{-0.817838f,0.575449f,0.0f},{-0.772219f,0.635356f,0.0f},{-0.772206f,0.635373f,0.0f}, -{-0.722222f,0.691661f,0.0f},{-0.566722f,-0.823909f,0.0f},{-0.0752244f,-0.997167f,0.0f}, -{-1.0f,4.16334e-017f,0.0f},{4.44089e-016f,-1.0f,0.0f},{8.88178e-016f,-1.0f,0.0f}, -{-1.0f,0.0f,-5.55112e-017f},{1.11022e-016f,-1.0f,0.0f},{9.71445e-017f,-1.0f,0.0f}, -{-0.997165f,0.0752459f,0.0f},{-1.0f,9.10186e-012f,0.0f},{-1.0f,1.03206e-013f,0.0f}, -{-0.954977f,0.296679f,0.0f},{-0.97459f,0.223998f,0.0f},{-0.954964f,0.296721f,0.0f}, -{-0.974583f,0.224026f,0.0f},{-0.988681f,0.150034f,0.0f},{-0.988676f,0.150064f,0.0f}, -{-0.899649f,0.436614f,0.0f},{-0.864229f,0.503098f,0.0f},{-0.864236f,0.503086f,0.0f}, -{-0.92993f,0.367737f,0.0f},{-0.899629f,0.436655f,0.0f},{-0.929953f,0.367679f,0.0f}, -{-0.676006f,0.736896f,0.0f},{-0.729561f,0.683915f,0.0f},{-0.729555f,0.683922f,0.0f}, -{-0.77898f,0.627048f,0.0f},{-0.823949f,0.566664f,0.0f},{-0.778933f,0.627107f,0.0f}, -{-0.557828f,0.829957f,0.0f},{-0.557812f,0.829967f,0.0f},{-0.4938f,0.869576f,0.0f}, -{-0.6761f,0.736809f,0.0f},{-0.618684f,0.78564f,0.0f},{-0.618687f,0.785637f,0.0f}, -{-0.357739f,0.933821f,0.0f},{-0.286476f,0.958087f,0.0f},{-0.357756f,0.933815f,0.0f}, -{-0.426976f,0.904263f,0.0f},{-0.426992f,0.904255f,0.0f},{-0.493808f,0.869571f,0.0f}, -{-0.0645078f,0.997917f,0.0f},{-0.139487f,0.990224f,0.0f},{-0.139483f,0.990224f,0.0f}, -{-0.213603f,0.97692f,0.0f},{-0.286485f,0.958085f,0.0f},{-0.213586f,0.976924f,0.0f}, -{0.0858467f,0.996308f,0.0f},{0.0106617f,0.999943f,0.0f},{0.085922f,0.996302f,0.0f}, -{-0.0646351f,0.997909f,0.0f},{0.0106703f,0.999943f,0.0f},{0.234405f,0.972139f,0.0f}, -{0.160567f,0.987025f,0.0f},{0.234419f,0.972136f,0.0f},{0.160636f,0.987014f,0.0f}, -{0.306919f,0.951735f,0.0f},{0.306876f,0.95175f,0.0f},{0.377666f,0.925942f,0.0f}, -{0.377609f,0.925965f,0.0f},{0.446213f,0.894927f,0.0f},{0.446253f,0.894907f,0.0f}, -{0.51231f,0.858801f,0.0f},{0.512285f,0.858815f,0.0f},{0.575474f,0.81782f,0.0f}, -{0.575449f,0.817838f,0.0f},{0.635356f,0.772219f,0.0f},{0.635373f,0.772206f,0.0f}, -{0.691661f,0.722222f,0.0f},{-0.823909f,0.566722f,0.0f},{-0.997167f,0.0752244f,0.0f}, -{-1.32706e-016f,1.0f,0.0f},{-1.38778e-016f,1.0f,0.0f},{8.88178e-016f,1.0f,0.0f}, -{-1.0f,4.81386e-016f,0.0f},{-1.0f,4.71845e-016f,0.0f},{0.0752459f,0.997165f,0.0f}, -{9.09877e-012f,1.0f,0.0f},{1.00502e-013f,1.0f,0.0f},{0.296679f,0.954977f,0.0f}, -{0.223998f,0.97459f,0.0f},{0.296721f,0.954964f,0.0f},{0.224026f,0.974583f,0.0f}, -{0.150034f,0.988681f,0.0f},{0.150064f,0.988676f,0.0f},{0.436614f,0.899649f,0.0f}, -{0.503098f,0.864229f,0.0f},{0.503086f,0.864236f,0.0f},{0.367737f,0.92993f,0.0f}, -{0.436655f,0.899629f,0.0f},{0.367679f,0.929953f,0.0f},{0.736896f,0.676006f,0.0f}, -{0.683915f,0.729561f,0.0f},{0.683922f,0.729555f,0.0f},{0.627048f,0.77898f,0.0f}, -{0.566664f,0.823949f,0.0f},{0.627107f,0.778933f,0.0f},{0.829957f,0.557828f,0.0f}, -{0.829967f,0.557812f,0.0f},{0.869576f,0.4938f,0.0f},{0.736809f,0.6761f,0.0f}, -{0.78564f,0.618684f,0.0f},{0.785637f,0.618687f,0.0f},{0.933821f,0.357739f,0.0f}, -{0.958087f,0.286476f,0.0f},{0.933815f,0.357756f,0.0f},{0.904263f,0.426976f,0.0f}, -{0.904255f,0.426992f,0.0f},{0.869571f,0.493808f,0.0f},{0.997917f,0.0645078f,0.0f}, -{0.990224f,0.139487f,0.0f},{0.990224f,0.139483f,0.0f},{0.97692f,0.213603f,0.0f}, -{0.958085f,0.286485f,0.0f},{0.976924f,0.213586f,0.0f},{0.996308f,-0.0858467f,0.0f}, -{0.999943f,-0.0106617f,0.0f},{0.996302f,-0.085922f,0.0f},{0.997909f,0.0646351f,0.0f}, -{0.999943f,-0.0106703f,0.0f},{0.972139f,-0.234405f,0.0f},{0.987025f,-0.160567f,0.0f}, -{0.972136f,-0.234419f,0.0f},{0.987014f,-0.160636f,0.0f},{0.951735f,-0.306919f,0.0f}, -{0.95175f,-0.306876f,0.0f},{0.925942f,-0.377666f,0.0f},{0.925965f,-0.377609f,0.0f}, -{0.894927f,-0.446213f,0.0f},{0.894907f,-0.446253f,0.0f},{0.858801f,-0.51231f,0.0f}, -{0.858815f,-0.512285f,0.0f},{0.81782f,-0.575474f,0.0f},{0.817838f,-0.575449f,0.0f}, -{0.772219f,-0.635356f,0.0f},{0.772206f,-0.635373f,0.0f},{0.722222f,-0.691661f,0.0f}, -{0.566722f,0.823909f,0.0f},{0.0752244f,0.997167f,0.0f},{1.0f,4.57967e-016f,0.0f}, -{1.0f,4.85723e-016f,0.0f},{-7.21645e-016f,1.0f,0.0f},{1.0f,-3.50885e-016f,0.0f}, -{0.332491f,0.943106f,-1.06997e-016f},{0.412177f,0.911104f,-1.88488e-015f},{0.412177f,0.911104f,-1.20772e-015f}, -{0.250506f,0.968115f,-9.4629e-017f},{0.167145f,0.985932f,6.49454e-016f},{0.0833404f,0.996521f,-1.06395e-016f}, -{-3.81317e-016f,1.0f,0.0f},{-2.02575e-016f,1.0f,0.0f},{0.488686f,0.87246f,7.69425e-016f}, -{0.561215f,0.82767f,0.0f},{0.629065f,0.777353f,3.23897e-015f},{0.629065f,0.777353f,1.61948e-015f}, -{0.412177f,-0.911104f,-1.23041e-015f},{0.332491f,-0.943106f,8.18039e-016f},{0.332491f,-0.943106f,1.62429e-016f}, -{0.488686f,-0.87246f,8.39281e-016f},{0.561215f,-0.82767f,-1.49714e-015f},{0.629065f,-0.777353f,3.04377e-015f}, -{0.250506f,-0.968115f,4.00341e-016f},{0.167145f,-0.985932f,-3.50985e-016f},{0.0833404f,-0.996521f,0.0f}, -{-1.90659e-016f,-1.0f,0.0f},{-0.911104f,-0.412177f,-2.15889e-015f},{-0.943106f,-0.332491f,3.90051e-016f}, -{-0.87246f,-0.488686f,9.96209e-016f},{-0.82767f,-0.561215f,7.42388e-016f},{-0.777353f,-0.629065f,4.00085e-015f}, -{-0.968115f,-0.250506f,-7.78858e-017f},{-0.985932f,-0.167145f,-8.04095e-016f},{-0.996521f,-0.0833404f,1.60342e-016f}, -{-1.0f,-2.02575e-016f,0.0f},{-1.0f,1.90659e-016f,0.0f},{-0.943106f,0.332491f,-6.79919e-016f}, -{-0.911104f,0.412177f,-8.69141e-016f},{-0.911104f,0.412177f,-1.91981e-016f},{-0.968115f,0.250506f,-5.56861e-017f}, -{-0.985932f,0.167145f,7.53839e-017f},{-0.996521f,0.0833404f,-8.12926e-017f},{-1.0f,-1.90659e-016f,0.0f}, -{-1.0f,-1.19162e-017f,0.0f},{-0.87246f,0.488686f,0.0f},{-0.82767f,0.561215f,-1.44481e-015f}, -{-0.777353f,0.629065f,2.98881e-015f},{0.911104f,0.412177f,3.3858e-016f},{0.943106f,0.332491f,-5.79735e-016f}, -{0.943106f,0.332491f,-9.31849e-016f},{0.87246f,0.488686f,9.08471e-016f},{0.82767f,0.561215f,-1.65643e-016f}, -{0.777353f,0.629065f,1.61602e-015f},{0.968115f,0.250506f,3.11543e-016f},{0.985932f,0.167145f,-3.50985e-016f}, -{0.996521f,0.0833404f,-2.14554e-016f},{1.0f,-2.02575e-016f,0.0f},{1.0f,-1.90659e-016f,0.0f}, -{0.943106f,-0.332491f,-5.28171e-016f},{0.911104f,-0.412177f,-7.22542e-016f},{0.911104f,-0.412177f,-4.85178e-016f}, -{0.968115f,-0.250506f,-1.141e-016f},{0.985932f,-0.167145f,1.15043e-016f},{0.996521f,-0.0833404f,-8.63033e-017f}, -{1.0f,3.81317e-016f,0.0f},{1.0f,1.19162e-017f,0.0f},{0.87246f,-0.488686f,0.0f}, -{0.82767f,-0.561215f,-1.57798e-015f},{0.777353f,-0.629065f,3.23897e-015f},{-0.412177f,0.911104f,1.70163e-015f}, -{-0.332491f,0.943106f,-1.00772e-015f},{-0.488686f,0.87246f,-7.17115e-016f},{-0.561215f,0.82767f,-1.39145e-015f}, -{-0.629065f,0.777353f,1.16234e-015f},{-0.250506f,0.968115f,-6.44911e-016f},{-0.167145f,0.985932f,7.93192e-017f}, -{-0.0833404f,0.996521f,0.0f},{-3.93233e-016f,1.0f,0.0f},{-0.332491f,-0.943106f,1.14584e-015f}, -{-0.412177f,-0.911104f,3.3858e-016f},{-0.250506f,-0.968115f,7.28254e-016f},{-0.167145f,-0.985932f,2.83812e-016f}, -{-0.0833404f,-0.996521f,6.91185e-017f},{1.33461e-015f,-1.0f,0.0f},{1.23928e-015f,-1.0f,0.0f}, -{-0.488686f,-0.87246f,3.48283e-016f},{-0.561215f,-0.82767f,-3.02279e-015f},{-0.629065f,-0.777353f,3.48912e-015f}, -{-0.603231f,-0.797567f,9.7061e-017f},{-0.707107f,-0.707107f,6.25761e-016f},{-0.489042f,-0.87226f,5.61393e-016f}, -{-0.368095f,-0.929788f,5.98419e-016f},{-0.244052f,-0.969762f,0.0f},{-0.12036f,-0.99273f,0.0f}, -{1.25607e-015f,-1.0f,0.0f},{1.00486e-015f,-1.0f,0.0f},{-0.797567f,-0.603231f,2.27018e-016f}, -{-0.87226f,-0.489042f,1.04745e-016f},{-0.929788f,-0.368095f,-3.82645e-016f},{-0.969762f,-0.244052f,7.06879e-017f}, -{-0.99273f,-0.12036f,-1.00206e-016f},{-1.0f,2.51215e-016f,0.0f},{-1.0f,-2.35514e-016f,0.0f}, -{0.603231f,0.797567f,-4.82864e-016f},{0.489042f,0.87226f,1.74403e-016f},{0.368095f,0.929788f,4.73817e-016f}, -{0.244052f,0.969762f,0.0f},{0.12036f,0.99273f,0.0f},{1.68e-015f,1.0f,0.0f}, -{1.7585e-015f,1.0f,0.0f},{0.797567f,0.603231f,9.27704e-016f},{0.87226f,0.489042f,6.15491e-016f}, -{0.929788f,0.368095f,-8.95393e-016f},{0.969762f,0.244052f,2.10774e-016f},{0.99273f,0.12036f,-1.30495e-016f}, -{1.0f,1.00486e-015f,0.0f},{1.0f,1.13047e-015f,0.0f},{0.603231f,0.797567f,-7.6998e-016f}, -{0.707107f,0.707107f,2.84437e-016f},{0.489042f,0.87226f,-1.0441e-015f},{0.244052f,0.969762f,-7.02683e-016f}, -{0.12036f,0.99273f,1.27786e-015f},{1.00486e-015f,1.0f,0.0f},{0.797567f,0.603231f,-2.25391e-016f}, -{0.87226f,0.489042f,5.37527e-016f},{0.929788f,0.368095f,-1.30546e-016f},{0.969762f,0.244052f,-2.98079e-017f}, -{0.99273f,0.12036f,-3.75669e-017f},{1.0f,-2.51215e-016f,0.0f},{1.0f,-2.82617e-016f,0.0f}, -{-0.797567f,0.603231f,-2.90369e-016f},{-0.707107f,0.707107f,7.11093e-016f},{-0.87226f,0.489042f,-5.95448e-016f}, -{-0.929788f,0.368095f,1.49605e-016f},{-0.969762f,0.244052f,-3.14148e-016f},{-0.99273f,0.12036f,4.80237e-018f}, -{-1.0f,1.6329e-015f,0.0f},{-1.0f,1.50729e-015f,0.0f},{-0.603231f,0.797567f,-4.64789e-016f}, -{-0.603231f,0.797567f,7.02313e-016f},{-0.489042f,0.87226f,-7.50922e-016f},{-0.368095f,0.929788f,6.962e-016f}, -{-0.244052f,0.969762f,-1.23453e-015f},{-0.12036f,0.99273f,-8.00113e-016f},{2.26093e-015f,1.0f,0.0f}, -{-0.797567f,0.603231f,-6.10381e-016f},{-0.707107f,0.707107f,7.96424e-016f},{-0.87226f,0.489042f,1.12279e-015f}, -{-0.929788f,0.368095f,5.98419e-016f},{-0.969762f,0.244052f,-1.24829e-015f},{-0.99273f,0.12036f,3.87325e-017f}, -{-1.0f,1.00486e-015f,0.0f},{-0.603231f,0.797567f,-3.24079e-016f},{-0.489042f,0.87226f,-5.55587e-016f}, -{-0.368095f,0.929788f,1.15329e-016f},{-0.244052f,0.969762f,1.60913e-016f},{-0.12036f,0.99273f,-5.63777e-017f}, -{1.57009e-017f,1.0f,0.0f},{0.797567f,-0.603231f,-6.2538e-017f},{0.707107f,-0.707107f,9.67086e-016f}, -{0.87226f,-0.489042f,-4.82706e-016f},{0.929788f,-0.368095f,-5.98419e-016f},{0.969762f,-0.244052f,-7.02683e-016f}, -{0.99273f,-0.12036f,3.87325e-017f},{1.0f,-1.13047e-015f,0.0f},{1.0f,-1.00486e-015f,0.0f}, -{0.603231f,-0.797567f,-5.48656e-016f},{0.489042f,-0.87226f,-2.23293e-016f},{0.368095f,-0.929788f,7.5955e-017f}, -{0.244052f,-0.969762f,1.54765e-016f},{0.12036f,-0.99273f,-8.23468e-017f},{2.51215e-016f,-1.0f,0.0f}, -{2.82617e-016f,-1.0f,0.0f},{0.797567f,-0.603231f,1.00269e-015f},{0.707107f,-0.707107f,3.98212e-016f}, -{0.87226f,-0.489042f,-4.89153e-016f},{0.929788f,-0.368095f,3.86513e-016f},{0.969762f,-0.244052f,-4.70184e-016f}, -{0.99273f,-0.12036f,-1.59732e-016f},{1.0f,1.57009e-017f,0.0f},{0.603231f,-0.797567f,5.30581e-016f}, -{0.489042f,-0.87226f,5.79743e-016f},{0.368095f,-0.929788f,2.62961e-017f},{0.244052f,-0.969762f,-7.6875e-016f}, -{0.12036f,-0.99273f,-3.81312e-016f},{-1.00486e-015f,-1.0f,0.0f},{8.79252e-016f,-1.0f,0.0f}, -{-0.603231f,-0.797567f,8.4228e-016f},{-0.707107f,-0.707107f,-3.41324e-016f},{-0.489042f,-0.87226f,-5.59328e-016f}, -{-0.368095f,-0.929788f,3.99015e-016f},{-0.244052f,-0.969762f,1.56037e-016f},{-0.12036f,-0.99273f,1.59732e-016f}, -{3.14019e-017f,-1.0f,0.0f},{-0.797567f,-0.603231f,-7.07442e-016f},{-0.87226f,-0.489042f,-6.64671e-016f}, -{-0.929788f,-0.368095f,-5.51379e-016f},{-0.969762f,-0.244052f,-2.00745e-016f},{-0.99273f,-0.12036f,-3.9822e-016f}, -{-1.0f,-2.00972e-015f,0.0f},{0.988818f,-0.149126f,-7.67832e-016f},{0.826061f,-0.563581f,2.9018e-015f}, -{0.82663f,-0.562746f,2.8975e-015f},{0.900794f,-0.434246f,-7.24697e-017f},{0.901683f,-0.432397f,-1.11318e-015f}, -{0.955572f,-0.294759f,0.0f},{0.955502f,-0.294984f,-7.68711e-017f},{0.499989f,-0.866031f,2.01123e-017f}, -{0.499834f,-0.866121f,-2.20966e-015f},{0.365379f,-0.930859f,2.41113e-015f},{0.623256f,-0.782018f,2.50708e-017f}, -{0.623488f,-0.781833f,-6.03832e-015f},{-0.074795f,-0.997199f,-1.28511e-015f},{-0.0746326f,-0.997211f,2.56875e-015f}, -{0.0746326f,-0.997211f,3.85238e-015f},{0.074795f,-0.997199f,-1.28511e-015f},{0.222585f,-0.974913f,3.76477e-015f}, -{0.222381f,-0.97496f,-2.51891e-015f},{-0.499833f,-0.866122f,2.51854e-015f},{-0.365177f,-0.930938f,-7.34471e-018f}, -{-0.365379f,-0.930859f,-2.39643e-015f},{-0.222381f,-0.97496f,-6.27044e-015f},{-0.222585f,-0.974913f,-1.88686e-015f}, -{-0.732917f,-0.680318f,-2.02688e-017f},{-0.623488f,-0.781833f,7.70465e-016f},{-0.733034f,-0.680192f,-1.18659e-016f}, -{-0.49999f,-0.866031f,-3.06059e-015f},{-0.623256f,-0.782018f,-7.70638e-016f},{-0.82663f,-0.562746f,1.58233e-016f}, -{-0.826061f,-0.563581f,-1.93807e-017f},{-0.901683f,-0.432397f,-2.42199e-016f},{-0.900794f,-0.434246f,7.97856e-016f}, -{-0.955502f,-0.294984f,-5.27632e-016f},{-0.955572f,-0.294759f,7.01229e-016f},{-0.988846f,-0.148938f,8.05299e-016f}, -{-0.988818f,-0.149126f,2.80723e-016f},{0.365177f,-0.930938f,4.77858e-015f},{0.733034f,-0.680192f,0.0f}, -{0.988818f,-0.149126f,9.73577e-020f},{0.988846f,-0.148938f,7.13987e-020f},{0.826061f,-0.563581f,-2.13745e-015f}, -{0.82663f,-0.562746f,-4.24488e-015f},{0.900794f,-0.434246f,2.32072e-015f},{0.901683f,-0.432397f,1.82527e-017f}, -{0.955572f,-0.294759f,7.88519e-018f},{0.955502f,-0.294984f,7.95502e-018f},{0.499989f,-0.866031f,-1.26807e-015f}, -{0.499834f,-0.866121f,1.34088e-015f},{0.365379f,-0.930859f,2.5686e-017f},{0.732917f,-0.680318f,-2.92946e-017f}, -{0.623256f,-0.782018f,-1.62692e-015f},{0.623488f,-0.781833f,-3.16995e-015f},{-0.074795f,-0.997199f,1.5066e-016f}, -{-0.0746326f,-0.997211f,-4.20003e-017f},{0.0746326f,-0.997211f,2.25086e-016f},{0.074795f,-0.997199f,-4.64395e-016f}, -{0.222585f,-0.974913f,2.5747e-017f},{0.222381f,-0.97496f,-5.07382e-016f},{-0.499833f,-0.866122f,1.1214e-015f}, -{-0.365177f,-0.930938f,7.49806e-016f},{-0.365379f,-0.930859f,1.72838e-015f},{-0.222381f,-0.97496f,-6.03215e-016f}, -{-0.222585f,-0.974913f,-9.94176e-016f},{-0.732917f,-0.680318f,-3.92441e-015f},{-0.623488f,-0.781833f,2.38377e-015f}, -{-0.733034f,-0.680192f,-2.48228e-015f},{-0.49999f,-0.866031f,-6.48069e-016f},{-0.623256f,-0.782018f,-4.09408e-016f}, -{-0.82663f,-0.562746f,-2.05981e-015f},{-0.826061f,-0.563581f,3.7841e-015f},{-0.901683f,-0.432397f,-1.58751e-016f}, -{-0.900794f,-0.434246f,-2.68865e-015f},{-0.955502f,-0.294984f,9.23116e-016f},{-0.955572f,-0.294759f,-1.22049e-015f}, -{-0.988846f,-0.148938f,2.44713e-015f},{-0.988818f,-0.149126f,-1.4151e-015f},{0.365177f,-0.930938f,2.58547e-017f}, -{0.733034f,-0.680192f,-1.91654e-015f},{1.0f,-8.32667e-017f,0.0f},{0.988818f,-0.149126f,-7.95513e-017f}, -{0.988846f,-0.148938f,7.95536e-017f},{0.826061f,-0.563581f,-1.38444e-015f},{0.82663f,-0.562746f,-6.65032e-017f}, -{0.900794f,-0.434246f,0.0f},{0.901683f,-0.432397f,7.25413e-017f},{0.955572f,-0.294759f,-7.68766e-017f}, -{0.955502f,-0.294984f,-1.44196e-015f},{0.499989f,-0.866031f,4.43896e-015f},{0.499834f,-0.866121f,-2.24988e-015f}, -{0.732917f,-0.680318f,2.94819e-017f},{0.623488f,-0.781833f,6.01324e-015f},{-0.074795f,-0.997199f,1.50433e-018f}, -{-0.0746326f,-0.997211f,-2.56575e-015f},{0.074795f,-0.997199f,2.56722e-015f},{0.222585f,-0.974913f,8.95358e-018f}, -{0.222381f,-0.97496f,2.50102e-015f},{-0.499833f,-0.866122f,-3.03854e-016f},{-0.365177f,-0.930938f,-4.19778e-015f}, -{-0.365379f,-0.930859f,-3.67439e-018f},{-0.222381f,-0.97496f,-2.50997e-015f},{-0.222585f,-0.974913f,6.22985e-016f}, -{-0.732917f,-0.680318f,2.82765e-015f},{-0.623488f,-0.781833f,-1.30187e-015f},{-0.733034f,-0.680192f,5.98822e-016f}, -{-0.49999f,-0.866031f,-8.36077e-016f},{-0.623256f,-0.782018f,-2.20318e-016f},{-0.82663f,-0.562746f,1.53038e-016f}, -{-0.826061f,-0.563581f,-6.75955e-016f},{-0.901683f,-0.432397f,-2.88011e-015f},{-0.900794f,-0.434246f,-3.52353e-016f}, -{-0.955502f,-0.294984f,1.16297e-015f},{-0.955572f,-0.294759f,1.22171e-015f},{-0.988846f,-0.148938f,-3.33616e-016f}, -{-0.988818f,-0.149126f,-3.70082e-016f},{0.365177f,-0.930938f,2.39664e-015f},{0.733034f,-0.680192f,1.72162e-015f}, -{0.826061f,-0.563581f,4.24246e-015f},{0.82663f,-0.562746f,1.13183e-017f},{0.955572f,-0.294759f,4.92799e-015f}, -{0.955502f,-0.294984f,-4.91179e-015f},{0.499989f,-0.866031f,1.30631e-015f},{0.732917f,-0.680318f,-1.91614e-015f}, -{0.623256f,-0.782018f,-3.23145e-015f},{0.623488f,-0.781833f,-1.56482e-015f},{-0.074795f,-0.997199f,-1.38172e-016f}, -{-0.0746326f,-0.997211f,5.40679e-017f},{0.0746326f,-0.997211f,-6.31192e-017f},{0.074795f,-0.997199f,1.69913e-017f}, -{0.222585f,-0.974913f,3.12261e-016f},{0.222381f,-0.97496f,-2.21129e-016f},{-0.499833f,-0.866122f,-3.26236e-016f}, -{-0.365177f,-0.930938f,-1.90317e-016f},{-0.365379f,-0.930859f,-1.09355e-015f},{-0.222381f,-0.97496f,-3.16963e-016f}, -{-0.222585f,-0.974913f,8.62413e-018f},{-0.732917f,-0.680318f,9.10624e-016f},{-0.623488f,-0.781833f,1.17992e-015f}, -{-0.733034f,-0.680192f,-2.71817e-015f},{-0.49999f,-0.866031f,1.12181e-015f},{-0.623256f,-0.782018f,-2.01394e-015f}, -{-0.82663f,-0.562746f,6.00315e-016f},{-0.826061f,-0.563581f,-1.66541e-015f},{-0.901683f,-0.432397f,-2.84278e-015f}, -{-0.900794f,-0.434246f,5.36253e-016f},{-0.955502f,-0.294984f,3.825e-015f},{-0.955572f,-0.294759f,5.47672e-016f}, -{-0.988846f,-0.148938f,-6.98966e-016f},{-0.988818f,-0.149126f,-2.60588e-015f},{0.733034f,-0.680192f,-2.93964e-017f}, -{1.0f,1.50359e-014f,-3.86165e-015f},{1.0f,2.12271e-014f,-3.86165e-015f},{0.158603f,0.987342f,7.37193e-016f}, -{0.826318f,0.563203f,-1.71427e-015f},{0.642788f,0.766044f,1.27963e-015f},{0.411158f,0.911564f,0.0f}, -{0.944801f,0.327644f,-1.17949e-017f},{-1.0f,-6.25927e-015f,0.0f},{-1.0f,2.50371e-014f,0.0f}, -{-0.327644f,-0.944801f,7.67486e-016f},{-0.911564f,-0.411158f,-2.06375e-015f},{-0.766044f,-0.642788f,-9.796e-016f}, -{-0.563203f,-0.826318f,-7.24964e-016f},{-0.987342f,-0.158603f,-4.26542e-015f},{-1.0f,-3.70074e-015f,0.0f}, -{-0.978254f,-0.207408f,-6.29612e-016f},{-0.50141f,-0.86521f,-1.61356e-016f},{-0.670096f,-0.742274f,0.0f}, -{-0.66887f,-0.743379f,9.08934e-016f},{-0.809606f,-0.586974f,3.77781e-016f},{-0.913862f,-0.406026f,5.88168e-016f}, -{-0.913543f,-0.406743f,-5.23566e-016f},{-0.105163f,-0.994455f,1.28008e-015f},{-0.104013f,-0.994576f,6.69438e-017f}, -{0.104013f,-0.994576f,9.09967e-016f},{-0.499433f,-0.866353f,7.1831e-016f},{-0.308272f,-0.951298f,1.22453e-015f}, -{-0.310578f,-0.950548f,-1.12361e-015f},{0.310578f,-0.950548f,-4.99725e-017f},{0.50141f,-0.86521f,3.66232e-016f}, -{0.499433f,-0.866353f,-6.29753e-016f},{0.308272f,-0.951298f,-5.08799e-016f},{0.105163f,-0.994455f,2.86178e-016f}, -{0.670096f,-0.742274f,-4.81031e-017f},{0.809606f,-0.586974f,1.13659e-015f},{0.808947f,-0.587881f,6.20902e-016f}, -{0.66887f,-0.743379f,-9.0294e-016f},{0.913543f,-0.406743f,5.2606e-016f},{0.913862f,-0.406026f,3.46568e-016f}, -{0.978254f,-0.207408f,-1.03704e-015f},{0.978165f,-0.20783f,1.66019e-015f},{1.0f,1.33227e-015f,0.0f}, -{-0.808947f,-0.587881f,-3.78365e-016f},{-0.978254f,-0.207408f,-1.25922e-015f},{-0.50141f,-0.86521f,3.22711e-016f}, -{-0.670096f,-0.742274f,-4.31279e-016f},{-0.66887f,-0.743379f,4.78444e-016f},{-0.913862f,-0.406026f,0.0f}, -{-0.105163f,-0.994455f,1.17855e-015f},{-0.104013f,-0.994576f,-3.34719e-017f},{0.104013f,-0.994576f,9.26703e-016f}, -{-0.499433f,-0.866353f,5.57591e-016f},{-0.308272f,-0.951298f,1.02612e-015f},{-0.310578f,-0.950548f,-1.22356e-015f}, -{0.310578f,-0.950548f,2.49863e-016f},{0.50141f,-0.86521f,7.29282e-016f},{0.499433f,-0.866353f,-3.48494e-016f}, -{0.308272f,-0.951298f,-3.10392e-016f},{0.105163f,-0.994455f,3.87703e-016f},{0.670096f,-0.742274f,-1.02013e-016f}, -{0.809606f,-0.586974f,1.21801e-015f},{0.808947f,-0.587881f,1.97878e-016f},{0.66887f,-0.743379f,1.18511e-017f}, -{0.913543f,-0.406743f,2.04518e-016f},{0.913862f,-0.406026f,5.70787e-017f},{0.978254f,-0.207408f,-6.1033e-016f}, -{0.978165f,-0.20783f,8.92923e-016f},{1.0f,-2.51651e-015f,0.0f},{-0.808947f,-0.587881f,-8.99009e-016f}, -{-0.670096f,-0.742274f,-9.09012e-016f},{-0.66887f,-0.743379f,-9.56889e-016f},{-0.809606f,-0.586974f,-3.77781e-016f}, -{-0.913543f,-0.406743f,5.23566e-016f},{-0.105163f,-0.994455f,-7.41564e-016f},{-0.104013f,-0.994576f,-6.73588e-016f}, -{0.104013f,-0.994576f,2.86586e-016f},{-0.499433f,-0.866353f,-5.57591e-016f},{-0.308272f,-0.951298f,-1.98406e-016f}, -{-0.310578f,-0.950548f,0.0f},{0.50141f,-0.86521f,-1.06001e-016f},{0.499433f,-0.866353f,1.04548e-015f}, -{0.308272f,-0.951298f,3.0187e-016f},{0.105163f,-0.994455f,1.02774e-015f},{0.670096f,-0.742274f,-6.99179e-016f}, -{0.809606f,-0.586974f,2.73555e-016f},{0.808947f,-0.587881f,-4.6426e-016f},{0.66887f,-0.743379f,1.31462e-016f}, -{0.913543f,-0.406743f,3.51771e-016f},{0.913862f,-0.406026f,-6.53389e-016f},{0.978254f,-0.207408f,-4.75798e-016f}, -{0.978165f,-0.20783f,7.98349e-016f},{-0.978254f,-0.207408f,0.0f},{-0.50141f,-0.86521f,0.0f}, -{-0.670096f,-0.742274f,-4.77733e-016f},{-0.809606f,-0.586974f,6.64356e-016f},{-0.105163f,-0.994455f,-6.06197e-016f}, -{-0.104013f,-0.994576f,-5.06229e-016f},{0.104013f,-0.994576f,3.5353e-016f},{-0.499433f,-0.866353f,-2.36152e-016f}, -{-0.308272f,-0.951298f,0.0f},{-0.310578f,-0.950548f,9.99451e-017f},{0.310578f,-0.950548f,4.99725e-017f}, -{0.50141f,-0.86521f,-3.07696e-016f},{0.499433f,-0.866353f,1.0053e-015f},{0.308272f,-0.951298f,-1.44543e-016f}, -{0.670096f,-0.742274f,-1.23828e-015f},{0.809606f,-0.586974f,6.18708e-017f},{0.808947f,-0.587881f,-1.45674e-015f}, -{0.66887f,-0.743379f,-9.98574e-016f},{0.913543f,-0.406743f,8.75425e-016f},{0.913862f,-0.406026f,1.18582e-016f}, -{0.978254f,-0.207408f,8.24911e-017f},{0.978165f,-0.20783f,1.97076e-016f},{1.0f,2.66454e-015f,0.0f}, -{-0.670096f,-0.742274f,-6.93373e-016f},{-0.809606f,-0.586974f,4.03822e-016f},{-0.913862f,-0.406026f,2.94084e-016f}, -{-0.104013f,-0.994576f,-5.89909e-016f},{0.50141f,-0.86521f,-3.27865e-016f},{0.499433f,-0.866353f,9.45034e-016f}, -{0.308272f,-0.951298f,4.26112e-018f},{0.105163f,-0.994455f,9.60058e-016f},{0.670096f,-0.742274f,-6.85702e-016f}, -{0.809606f,-0.586974f,-1.49813e-016f},{0.808947f,-0.587881f,-3.17829e-016f},{0.66887f,-0.743379f,-5.14273e-016f}, -{0.913543f,-0.406743f,4.89574e-016f},{0.913862f,-0.406026f,-3.27139e-016f},{0.978254f,-0.207408f,2.95231e-016f}, -{0.978165f,-0.20783f,4.59595e-016f},{-0.808947f,-0.587881f,-1.18042e-016f},{-0.105163f,-0.994455f,-6.5696e-016f}, -{-0.104013f,-0.994576f,-6.56853e-016f},{0.104013f,-0.994576f,3.36794e-016f},{-0.308272f,-0.951298f,-9.9203e-017f}, -{-0.310578f,-0.950548f,-9.99451e-017f},{0.310578f,-0.950548f,2.49863e-017f},{0.50141f,-0.86521f,-4.69051e-016f}, -{0.499433f,-0.866353f,9.65124e-016f},{0.308272f,-0.951298f,2.27468e-016f},{0.105163f,-0.994455f,8.92374e-016f}, -{0.670096f,-0.742274f,-7.26134e-016f},{0.809606f,-0.586974f,-5.2113e-017f},{0.808947f,-0.587881f,-9.00466e-017f}, -{0.913543f,-0.406743f,4.25266e-016f},{0.913862f,-0.406026f,-5.24727e-016f},{0.978254f,-0.207408f,9.93815e-018f}, -{0.978165f,-0.20783f,6.42805e-016f},{1.0f,-1.25825e-015f,0.0f},{-0.670096f,-0.742274f,-2.1564e-016f}, -{-0.809606f,-0.586974f,1.15938e-015f},{-0.105163f,-0.994455f,1.31392e-015f},{-0.104013f,-0.994576f,5.02078e-017f}, -{0.104013f,-0.994576f,9.93647e-016f},{0.50141f,-0.86521f,5.07418e-016f},{0.499433f,-0.866353f,-4.48944e-016f}, -{0.308272f,-0.951298f,-6.08002e-016f},{0.105163f,-0.994455f,3.20019e-016f},{0.670096f,-0.742274f,-8.85355e-017f}, -{0.809606f,-0.586974f,7.94639e-016f},{0.808947f,-0.587881f,3.44309e-016f},{0.66887f,-0.743379f,-6.33884e-016f}, -{0.913543f,-0.406743f,3.42322e-016f},{0.913862f,-0.406026f,3.83328e-016f},{0.978254f,-0.207408f,1.60699e-016f}, -{0.978165f,-0.20783f,5.54168e-016f},{-0.105163f,-0.994455f,1.26316e-015f},{-0.104013f,-0.994576f,-1.67359e-017f}, -{0.104013f,-0.994576f,9.76911e-016f},{-0.308272f,-0.951298f,1.12532e-015f},{-0.310578f,-0.950548f,-1.3235e-015f}, -{0.499433f,-0.866353f,-4.28854e-016f},{0.308272f,-0.951298f,-3.84795e-016f},{0.105163f,-0.994455f,2.52336e-016f}, -{0.670096f,-0.742274f,-1.28968e-016f},{0.809606f,-0.586974f,8.92339e-016f},{0.808947f,-0.587881f,5.72092e-016f}, -{0.913543f,-0.406743f,2.78013e-016f},{0.913862f,-0.406026f,1.85741e-016f},{0.978254f,-0.207408f,-1.24594e-016f}, -{0.978165f,-0.20783f,7.37379e-016f},{1.0f,-1.55431e-016f,0.0f},{0.997945f,-0.0640791f,-1.60571e-016f}, -{0.997946f,-0.0640673f,-1.60571e-016f},{0.967287f,-0.253683f,-1.63272e-016f},{0.967317f,-0.25357f,0.0f}, -{0.981554f,-0.191184f,0.0f},{0.981559f,-0.191157f,-1.2303e-016f},{0.991791f,-0.12787f,0.0f}, -{0.991787f,-0.127897f,0.0f},{0.900965f,-0.433892f,0.0f},{0.90096f,-0.433902f,-1.44966e-016f}, -{0.871315f,-0.490723f,0.0f},{0.94917f,-0.314763f,2.02584e-016f},{0.949042f,-0.315149f,3.05405e-016f}, -{0.926953f,-0.375176f,2.98297e-016f},{0.761438f,-0.648238f,6.25816e-016f},{0.761447f,-0.648227f,-3.3112e-016f}, -{0.801406f,-0.598121f,3.21425e-016f},{0.838075f,-0.545555f,4.07138e-017f},{0.838084f,-0.545542f,0.0f}, -{0.871302f,-0.490747f,1.40194e-016f},{0.623505f,-0.781819f,-3.51916e-016f},{0.623476f,-0.781843f,1.00318e-016f}, -{0.572134f,-0.82016f,5.27861e-016f},{0.718357f,-0.695675f,0.0f},{0.718339f,-0.695693f,-3.39459e-016f}, -{0.672313f,-0.740267f,-8.44706e-016f},{0.404769f,-0.914419f,-3.26828e-016f},{0.404803f,-0.914404f,-8.17642e-016f}, -{0.462522f,-0.886608f,7.071e-016f},{0.462558f,-0.886589f,5.70615e-016f},{0.518412f,-0.855131f,5.08662e-016f}, -{0.518376f,-0.855153f,-4.17039e-017f},{0.222542f,-0.974923f,-8.69587e-016f},{0.22251f,-0.97493f,-5.9167e-016f}, -{0.15962f,-0.987179f,-1.07473e-016f},{0.345353f,-0.938473f,6.04008e-016f},{0.284517f,-0.958671f,7.31456e-016f}, -{0.284548f,-0.958662f,-2.28921e-017f},{0.032044f,-0.999486f,-3.39684e-016f},{-0.032044f,-0.999486f,7.88628e-016f}, -{0.0320605f,-0.999486f,1.46027e-015f},{0.0960134f,-0.99538f,9.37778e-016f},{0.0960397f,-0.995377f,4.49568e-016f}, -{0.159589f,-0.987184f,-7.04325e-016f},{-0.22251f,-0.974931f,3.06907e-016f},{-0.159589f,-0.987184f,1.06859e-015f}, -{-0.15962f,-0.987179f,1.95683e-016f},{-0.0960133f,-0.99538f,-1.13812e-016f},{-0.0320605f,-0.999486f,-7.97648e-016f}, -{-0.0960396f,-0.995378f,4.84338e-016f},{-0.345353f,-0.938473f,1.99332e-017f},{-0.284548f,-0.958662f,-6.68238e-016f}, -{-0.345385f,-0.938461f,-1.09868e-015f},{-0.222542f,-0.974923f,-1.56867e-016f},{-0.284517f,-0.958671f,1.31362e-016f}, -{-0.462522f,-0.886608f,-9.48993e-016f},{-0.462558f,-0.886589f,1.0854e-016f},{-0.518376f,-0.855153f,5.61804e-016f}, -{-0.404803f,-0.914404f,3.25668e-017f},{-0.404769f,-0.914419f,-4.32364e-016f},{-0.572101f,-0.820183f,-6.26037e-016f}, -{-0.572134f,-0.82016f,4.29683e-017f},{-0.623475f,-0.781843f,-1.50578e-016f},{-0.518412f,-0.855131f,-1.71017e-016f}, -{-0.672313f,-0.740267f,8.82394e-016f},{-0.718357f,-0.695675f,-6.31165e-017f},{-0.718339f,-0.695693f,-4.2354e-016f}, -{-0.623505f,-0.781819f,-2.57672e-017f},{-0.672288f,-0.740289f,-7.50757e-016f},{-0.761438f,-0.648238f,8.28847e-016f}, -{-0.761447f,-0.648227f,1.98992e-016f},{-0.801409f,-0.598117f,4.42136e-016f},{-0.801406f,-0.598121f,2.0439e-016f}, -{-0.838084f,-0.545542f,1.01789e-015f},{-0.838075f,-0.545555f,-1.0489e-015f},{-0.871302f,-0.490747f,-1.02965e-015f}, -{-0.871315f,-0.490723f,-1.83478e-016f},{-0.900965f,-0.433892f,-6.58133e-016f},{-0.90096f,-0.433902f,-2.94448e-016f}, -{-0.926953f,-0.375176f,-1.1596e-017f},{-0.926902f,-0.375304f,-5.21943e-017f},{-0.949042f,-0.315149f,1.00427e-015f}, -{-0.94917f,-0.314763f,-3.79986e-016f},{-0.967317f,-0.25357f,1.01039e-017f},{-0.967287f,-0.253683f,-1.05575e-015f}, -{-0.981559f,-0.191157f,-6.7854e-016f},{-0.981554f,-0.191184f,5.82473e-016f},{-0.991787f,-0.127897f,-9.23871e-016f}, -{-0.991791f,-0.12787f,2.70854e-016f},{-0.997946f,-0.0640673f,1.3089e-017f},{-0.997945f,-0.0640792f,-1.24113e-016f}, -{-1.0f,-2.36848e-016f,0.0f},{0.345385f,-0.938461f,1.26357e-015f},{0.572101f,-0.820183f,3.5599e-016f}, -{0.672288f,-0.740289f,2.38228e-016f},{0.926902f,-0.375304f,0.0f},{0.801409f,-0.598117f,-3.19533e-016f}, -{1.0f,-1.25825e-016f,0.0f},{0.997945f,-0.0640791f,-4.12418e-017f},{0.967287f,-0.253683f,0.0f}, -{0.981559f,-0.191157f,1.57935e-016f},{0.991791f,-0.12787f,8.2298e-017f},{0.900965f,-0.433892f,1.44967e-016f}, -{0.90096f,-0.433902f,1.44966e-016f},{0.871315f,-0.490723f,-1.40196e-016f},{0.94917f,-0.314763f,-3.05447e-016f}, -{0.949042f,-0.315149f,-3.55535e-016f},{0.926953f,-0.375176f,0.0f},{0.761438f,-0.648238f,0.0f}, -{0.761447f,-0.648227f,0.0f},{0.801406f,-0.598121f,-2.57895e-016f},{0.838075f,-0.545555f,-4.07138e-017f}, -{0.838084f,-0.545542f,-1.34849e-016f},{0.871302f,-0.490747f,0.0f},{0.623505f,-0.781819f,0.0f}, -{0.572134f,-0.82016f,3.55988e-016f},{0.718357f,-0.695675f,1.15585e-016f},{0.718339f,-0.695693f,-1.15582e-016f}, -{0.672313f,-0.740267f,0.0f},{0.404769f,-0.914419f,0.0f},{0.404803f,-0.914404f,-3.25668e-017f}, -{0.462522f,-0.886608f,7.44207e-017f},{0.462558f,-0.886589f,-7.44265e-017f},{0.518412f,-0.855131f,-4.17067e-017f}, -{0.518376f,-0.855153f,0.0f},{0.222542f,-0.974923f,-1.79037e-017f},{0.22251f,-0.97493f,8.95056e-017f}, -{0.15962f,-0.987179f,8.98911e-017f},{0.345353f,-0.938473f,1.94488e-016f},{0.284517f,-0.958671f,4.57793e-017f}, -{0.284548f,-0.958662f,0.0f},{0.032044f,-0.999486f,9.02291e-018f},{-0.032044f,-0.999486f,1.69842e-016f}, -{0.0320605f,-0.999486f,1.5953e-016f},{0.0960134f,-0.99538f,-7.72437e-018f},{0.0960397f,-0.995377f,-7.72649e-018f}, -{0.159589f,-0.987184f,7.70345e-017f},{-0.22251f,-0.974931f,-2.89725e-017f},{-0.159589f,-0.987184f,-1.28391e-017f}, -{-0.15962f,-0.987179f,1.6526e-016f},{-0.0960133f,-0.99538f,0.0f},{-0.0320605f,-0.999486f,0.0f}, -{-0.0960396f,-0.995378f,-7.72648e-017f},{-0.345353f,-0.938473f,-6.16091e-017f},{-0.284548f,-0.958662f,-2.28921e-017f}, -{-0.345385f,-0.938461f,2.77865e-017f},{-0.222542f,-0.974923f,-1.70086e-016f},{-0.284517f,-0.958671f,3.43345e-017f}, -{-0.462522f,-0.886608f,4.27945e-016f},{-0.462558f,-0.886589f,3.44227e-016f},{-0.518376f,-0.855153f,8.12819e-017f}, -{-0.404803f,-0.914404f,5.78629e-019f},{-0.404769f,-0.914419f,-7.35659e-017f},{-0.572101f,-0.820183f,3.96619e-016f}, -{-0.572134f,-0.82016f,-5.38623e-018f},{-0.623475f,-0.781843f,1.1316e-016f},{-0.518412f,-0.855131f,-1.01149e-016f}, -{-0.672313f,-0.740267f,-1.55504e-016f},{-0.718357f,-0.695675f,5.36867e-017f},{-0.718339f,-0.695693f,2.73285e-018f}, -{-0.623505f,-0.781819f,2.14069e-016f},{-0.672288f,-0.740289f,-7.16643e-016f},{-0.761438f,-0.648238f,4.41224e-016f}, -{-0.761447f,-0.648227f,1.00012e-015f},{-0.801409f,-0.598117f,4.432e-016f},{-0.801406f,-0.598121f,-2.6222e-016f}, -{-0.838084f,-0.545542f,8.80097e-016f},{-0.838075f,-0.545555f,-1.06829e-015f},{-0.871302f,-0.490747f,-6.92209e-016f}, -{-0.871315f,-0.490723f,-2.64336e-017f},{-0.900965f,-0.433892f,-5.15123e-016f},{-0.90096f,-0.433902f,-2.3532e-016f}, -{-0.926953f,-0.375176f,3.47011e-016f},{-0.926902f,-0.375304f,-3.89492e-016f},{-0.949042f,-0.315149f,5.83544e-016f}, -{-0.94917f,-0.314763f,-4.7857e-016f},{-0.967317f,-0.25357f,-2.47062e-016f},{-0.967287f,-0.253683f,-8.80075e-016f}, -{-0.981559f,-0.191157f,-5.74475e-016f},{-0.981554f,-0.191184f,6.34e-016f},{-0.991787f,-0.127897f,-1.01223e-015f}, -{-0.991791f,-0.12787f,3.3853e-016f},{-0.997946f,-0.0640673f,4.63968e-017f},{-0.997945f,-0.0640792f,-6.26115e-017f}, -{0.345385f,-0.938461f,5.5573e-017f},{0.572101f,-0.820183f,-9.20521e-017f},{0.672288f,-0.740289f,0.0f}, -{0.926902f,-0.375304f,-2.98281e-016f},{0.801409f,-0.598117f,-3.21425e-016f},{0.997945f,-0.0640791f,0.0f}, -{0.997946f,-0.0640673f,-4.12342e-017f},{0.967317f,-0.25357f,1.632e-016f},{0.981554f,-0.191184f,-1.14042e-015f}, -{0.981559f,-0.191157f,0.0f},{0.90096f,-0.433902f,0.0f},{0.871315f,-0.490723f,3.15833e-016f}, -{0.94917f,-0.314763f,8.13477e-016f},{0.949042f,-0.315149f,1.22162e-015f},{0.761447f,-0.648227f,4.90073e-016f}, -{0.801406f,-0.598121f,9.00746e-016f},{0.838075f,-0.545555f,-1.27065e-017f},{0.838084f,-0.545542f,7.27679e-016f}, -{0.871302f,-0.490747f,2.44929e-016f},{0.623505f,-0.781819f,-6.05077e-016f},{0.623476f,-0.781843f,-2.516e-016f}, -{0.572134f,-0.82016f,-2.63931e-016f},{0.718357f,-0.695675f,-9.10081e-016f},{0.718339f,-0.695693f,9.24657e-016f}, -{0.672313f,-0.740267f,-2.81956e-016f},{0.404769f,-0.914419f,1.0468e-015f},{0.404803f,-0.914404f,-8.82776e-016f}, -{0.462522f,-0.886608f,2.85314e-016f},{0.462558f,-0.886589f,0.0f},{0.518412f,-0.855131f,-2.75184e-016f}, -{0.518376f,-0.855153f,8.25574e-016f},{0.222542f,-0.974923f,-8.5252e-017f},{0.22251f,-0.97493f,0.0f}, -{0.15962f,-0.987179f,6.35356e-016f},{0.345353f,-0.938473f,4.92873e-016f},{0.284517f,-0.958671f,4.00063e-016f}, -{0.284548f,-0.958662f,-8.33935e-016f},{0.032044f,-0.999486f,-3.21639e-016f},{-0.032044f,-0.999486f,1.50507e-016f}, -{0.0320605f,-0.999486f,1.81454e-016f},{0.0960134f,-0.99538f,-3.51215e-016f},{0.0960397f,-0.995377f,5.1138e-016f}, -{0.159589f,-0.987184f,5.84002e-016f},{-0.22251f,-0.974931f,4.34802e-016f},{-0.159589f,-0.987184f,1.07483e-016f}, -{-0.15962f,-0.987179f,7.94194e-016f},{-0.0960133f,-0.99538f,-8.3169e-016f},{-0.0320605f,-0.999486f,-1.71136e-016f}, -{-0.0960396f,-0.995378f,5.42286e-016f},{-0.345353f,-0.938473f,9.12026e-017f},{-0.284548f,-0.958662f,8.33935e-016f}, -{-0.345385f,-0.938461f,-2.46427e-016f},{-0.222542f,-0.974923f,7.84335e-017f},{-0.284517f,-0.958671f,7.85693e-016f}, -{-0.462522f,-0.886608f,-6.04745e-016f},{-0.462558f,-0.886589f,-7.16369e-016f},{-0.518376f,-0.855153f,-5.64993e-016f}, -{-0.404803f,-0.914404f,9.31047e-016f},{-0.404769f,-0.914419f,9.04416e-017f},{-0.572101f,-0.820183f,-3.36032e-016f}, -{-0.572134f,-0.82016f,4.41925e-016f},{-0.623475f,-0.781843f,-3.96109e-016f},{-0.518412f,-0.855131f,4.05468e-016f}, -{-0.672313f,-0.740267f,3.95309e-016f},{-0.718357f,-0.695675f,-3.52831e-017f},{-0.718339f,-0.695693f,-6.88355e-016f}, -{-0.623505f,-0.781819f,1.49682e-015f},{-0.672288f,-0.740289f,4.2753e-016f},{-0.761438f,-0.648238f,-2.74417e-016f}, -{-0.761447f,-0.648227f,-4.56317e-016f},{-0.801409f,-0.598117f,3.33218e-016f},{-0.801406f,-0.598121f,-2.93513e-016f}, -{-0.838084f,-0.545542f,-1.79534e-016f},{-0.838075f,-0.545555f,-4.11108e-017f},{-0.871302f,-0.490747f,1.62859e-016f}, -{-0.871315f,-0.490723f,1.48747e-016f},{-0.900965f,-0.433892f,-8.17489e-017f},{-0.90096f,-0.433902f,3.84887e-018f}, -{-0.926953f,-0.375176f,-5.46007e-017f},{-0.926902f,-0.375304f,-2.73406e-016f},{-0.949042f,-0.315149f,2.13422e-016f}, -{-0.94917f,-0.314763f,1.10395e-016f},{-0.967317f,-0.25357f,1.75065e-016f},{-0.967287f,-0.253683f,1.53602e-017f}, -{-0.981559f,-0.191157f,7.35095e-017f},{-0.981554f,-0.191184f,6.1315e-017f},{-0.991787f,-0.127897f,-1.7478e-017f}, -{-0.991791f,-0.12787f,7.54132e-017f},{-0.997946f,-0.0640673f,-1.02416e-016f},{-0.997945f,-0.0640792f,5.95282e-017f}, -{-1.0f,-3.70074e-018f,0.0f},{0.345385f,-0.938461f,4.92855e-016f},{0.572101f,-0.820183f,1.04271e-016f}, -{0.672288f,-0.740289f,2.81994e-016f},{0.926902f,-0.375304f,-3.55013e-016f},{0.801409f,-0.598117f,-1.60901e-015f}, -{1.0f,2.36848e-016f,0.0f},{1.0f,-2.81256e-016f,0.0f},{0.997946f,-0.0640673f,0.0f}, -{0.967287f,-0.253683f,1.63272e-016f},{0.967317f,-0.25357f,-1.632e-016f},{0.981554f,-0.191184f,-1.26347e-015f}, -{0.991787f,-0.127897f,8.23157e-017f},{0.900965f,-0.433892f,1.43899e-015f},{0.871315f,-0.490723f,1.12157e-015f}, -{0.94917f,-0.314763f,0.0f},{0.949042f,-0.315149f,6.10811e-016f},{0.926953f,-0.375176f,-5.96594e-016f}, -{0.801406f,-0.598121f,7.08268e-016f},{0.838075f,-0.545555f,-5.39391e-016f},{0.838084f,-0.545542f,7.14954e-016f}, -{0.871302f,-0.490747f,1.12155e-015f},{0.623505f,-0.781819f,-2.51592e-016f},{0.623476f,-0.781843f,6.52874e-016f}, -{0.572134f,-0.82016f,-3.6823e-016f},{0.718357f,-0.695675f,4.6234e-016f},{0.718339f,-0.695693f,0.0f}, -{0.672313f,-0.740267f,-2.38221e-016f},{0.404769f,-0.914419f,1.30256e-016f},{0.404803f,-0.914404f,2.60534e-016f}, -{0.518412f,-0.855131f,3.33654e-016f},{0.518376f,-0.855153f,5.84395e-017f},{0.222542f,-0.974923f,0.0f}, -{0.22251f,-0.97493f,7.16044e-017f},{0.15962f,-0.987179f,0.0f},{0.345353f,-0.938473f,0.0f}, -{0.284517f,-0.958671f,2.16945e-016f},{0.032044f,-0.999486f,1.03119e-017f},{-0.032044f,-0.999486f,2.06238e-017f}, -{0.0320605f,-0.999486f,1.50502e-016f},{0.0960134f,-0.99538f,0.0f},{0.0960397f,-0.995377f,0.0f}, -{0.159589f,-0.987184f,5.13564e-017f},{-0.22251f,-0.974931f,7.84341e-017f},{-0.159589f,-0.987184f,-7.70345e-017f}, -{-0.15962f,-0.987179f,2.56832e-017f},{-0.0960133f,-0.99538f,6.17949e-017f},{-0.0320605f,-0.999486f,-1.03172e-017f}, -{-0.0960396f,-0.995378f,-3.09059e-017f},{-0.345353f,-0.938473f,-5.55679e-017f},{-0.284548f,-0.958662f,2.91603e-016f}, -{-0.345385f,-0.938461f,-2.62146e-016f},{-0.222542f,-0.974923f,-7.84335e-017f},{-0.284517f,-0.958671f,-1.08473e-016f}, -{-0.462522f,-0.886608f,-4.03026e-017f},{-0.462558f,-0.886589f,3.72132e-017f},{-0.518376f,-0.855153f,4.17039e-017f}, -{-0.404803f,-0.914404f,2.29125e-016f},{-0.404769f,-0.914419f,7.35659e-017f},{-0.572101f,-0.820183f,-3.29923e-017f}, -{-0.572134f,-0.82016f,0.0f},{-0.623475f,-0.781843f,-1.44509e-016f},{-0.518412f,-0.855131f,-9.58855e-017f}, -{-0.672313f,-0.740267f,8.38658e-017f},{-0.718357f,-0.695675f,-1.14673e-016f},{-0.718339f,-0.695693f,-2.16261e-016f}, -{-0.623505f,-0.781819f,-3.0773e-016f},{-0.672288f,-0.740289f,-3.35459e-016f},{-0.761438f,-0.648238f,1.14033e-016f}, -{-0.761447f,-0.648227f,4.30418e-017f},{-0.801409f,-0.598117f,-4.72926e-019f},{-0.801406f,-0.598121f,6.3766e-017f}, -{-0.838084f,-0.545542f,9.9944e-017f},{-0.838075f,-0.545555f,6.62327e-017f},{-0.871302f,-0.490747f,-2.76664e-016f}, -{-0.871315f,-0.490723f,1.68095e-016f},{-0.900965f,-0.433892f,2.94656e-016f},{-0.90096f,-0.433902f,-2.73174e-016f}, -{-0.926953f,-0.375176f,5.54887e-018f},{-0.926902f,-0.375304f,4.60141e-016f},{-0.949042f,-0.315149f,3.69163e-017f}, -{-0.94917f,-0.314763f,-2.45758e-016f},{-0.967317f,-0.25357f,-1.94496e-016f},{-0.967287f,-0.253683f,6.21497e-017f}, -{-0.981559f,-0.191157f,1.73188e-016f},{-0.981554f,-0.191184f,-1.08839e-017f},{-0.991787f,-0.127897f,-8.76052e-017f}, -{-0.991791f,-0.12787f,-7.90167e-017f},{-0.997946f,-0.0640673f,-1.42163e-017f},{-0.997945f,-0.0640792f,1.54958e-017f}, -{0.345385f,-0.938461f,1.11146e-016f},{0.572101f,-0.820183f,0.0f},{0.672288f,-0.740289f,1.94462e-016f}, -{0.801409f,-0.598117f,-5.15793e-016f},{1.0f,-2.36848e-016f,0.0f},{-0.797567f,-0.603231f,0.0f}, -{-0.87226f,-0.489042f,0.0f},{-0.797567f,-0.603231f,0.0f},{-0.969762f,-0.244052f,0.0f}, -{-0.99273f,-0.12036f,0.0f},{-0.969762f,-0.244052f,0.0f},{-1.0f,6.28037e-016f,0.0f}, -{-0.603231f,-0.797567f,0.0f},{-0.489042f,-0.87226f,0.0f},{-0.603231f,-0.797567f,0.0f}, -{-0.368095f,-0.929788f,0.0f},{-0.244052f,-0.969762f,0.0f},{-0.12036f,-0.99273f,0.0f}, -{-0.244052f,-0.969762f,0.0f},{-8.1854e-013f,-1.0f,0.0f},{2.88897e-015f,-1.0f,0.0f}, -{-0.603231f,0.797567f,0.0f},{-0.489042f,0.87226f,0.0f},{-0.603231f,0.797567f,0.0f}, -{-0.244052f,0.969762f,0.0f},{-0.12036f,0.99273f,0.0f},{-0.244052f,0.969762f,0.0f}, -{-1.25607e-016f,1.0f,0.0f},{2.00972e-015f,1.0f,0.0f},{-0.797567f,0.603231f,0.0f}, -{-0.87226f,0.489042f,0.0f},{-0.797567f,0.603231f,0.0f},{-0.929788f,0.368095f,0.0f}, -{-0.969762f,0.244052f,0.0f},{-0.99273f,0.12036f,0.0f},{-0.969762f,0.244052f,0.0f}, -{-1.0f,8.22559e-013f,0.0f},{-1.0f,-1.88411e-015f,0.0f},{0.797567f,0.603231f,0.0f}, -{0.87226f,0.489042f,0.0f},{0.797567f,0.603231f,0.0f},{0.969762f,0.244052f,0.0f}, -{0.99273f,0.12036f,0.0f},{0.969762f,0.244052f,0.0f},{1.0f,-2.26093e-015f,0.0f}, -{1.0f,-3.01458e-015f,0.0f},{0.603231f,0.797567f,0.0f},{0.489042f,0.87226f,0.0f}, -{0.603231f,0.797567f,0.0f},{0.368095f,0.929788f,0.0f},{0.244052f,0.969762f,0.0f}, -{0.12036f,0.99273f,0.0f},{0.244052f,0.969762f,0.0f},{8.23564e-013f,1.0f,0.0f}, -{0.603231f,-0.797567f,0.0f},{0.489042f,-0.87226f,0.0f},{0.603231f,-0.797567f,0.0f}, -{0.244052f,-0.969762f,0.0f},{0.12036f,-0.99273f,0.0f},{0.244052f,-0.969762f,0.0f}, -{-2.26093e-015f,-1.0f,0.0f},{-3.01458e-015f,-1.0f,0.0f},{0.797567f,-0.603231f,0.0f}, -{0.87226f,-0.489042f,0.0f},{0.797567f,-0.603231f,0.0f},{0.929788f,-0.368095f,0.0f}, -{0.969762f,-0.244052f,0.0f},{0.99273f,-0.12036f,0.0f},{0.969762f,-0.244052f,0.0f}, -{1.0f,-8.23564e-013f,0.0f},{1.0f,1.50729e-015f,0.0f},{-1.0f,-1.89478e-014f,0.0f}, -{-0.950842f,-0.309676f,2.44782e-015f},{-0.952103f,-0.305779f,2.15167e-019f},{8.16528e-017f,-1.0f,1.84438e-017f}, -{-0.309304f,-0.950963f,4.14988e-018f},{-0.307814f,-0.951446f,3.80951e-016f},{-0.588229f,-0.808694f,-7.42514e-016f}, -{-0.811958f,-0.583716f,-2.09799e-015f},{-0.807656f,-0.589654f,2.07649e-015f},{0.587751f,-0.809042f,1.88339e-015f}, -{0.309304f,-0.950963f,-7.93445e-016f},{0.588229f,-0.808694f,1.89378e-016f},{5.24206e-017f,-1.0f,1.84438e-017f}, -{0.307814f,-0.951446f,2.20274e-016f},{0.950842f,-0.309676f,7.07655e-016f},{0.807656f,-0.589654f,1.56255e-015f}, -{0.811958f,-0.583716f,-1.04521e-015f},{0.952103f,-0.305779f,3.26521e-015f},{-0.587751f,-0.809042f,7.71131e-016f}, -{-1.0f,-9.4739e-015f,0.0f},{-1.0f,-1.38778e-017f,0.0f},{-0.950842f,-0.309676f,-7.97239e-016f}, -{-0.952103f,-0.305779f,0.0f},{0.0f,-1.0f,-6.43608e-016f},{-0.309304f,-0.950963f,0.0f}, -{-0.307814f,-0.951446f,1.22472e-015f},{-0.588229f,-0.808694f,-1.04096e-015f},{-0.811958f,-0.583716f,1.50274e-015f}, -{-0.807656f,-0.589654f,1.51802e-015f},{0.587751f,-0.809042f,-5.16272e-016f},{0.309304f,-0.950963f,-1.22487e-015f}, -{0.588229f,-0.808694f,1.03505e-015f},{-1.48864e-033f,-1.0f,-6.43608e-016f},{0.307814f,-0.951446f,-1.84017e-015f}, -{0.950842f,-0.309676f,8.81649e-016f},{0.807656f,-0.589654f,5.11667e-016f},{0.811958f,-0.583716f,6.28859e-016f}, -{0.952103f,-0.305779f,2.03625e-016f},{-0.587751f,-0.809042f,1.04141e-015f},{-0.950842f,-0.309676f,7.97239e-016f}, -{0.0f,-1.0f,1.28722e-015f},{-0.307814f,-0.951446f,-3.67415e-015f},{-0.588229f,-0.808694f,0.0f}, -{-0.811958f,-0.583716f,0.0f},{-0.807656f,-0.589654f,-1.51802e-015f},{0.587751f,-0.809042f,2.64786e-016f}, -{0.309304f,-0.950963f,6.11269e-016f},{0.588229f,-0.808694f,-5.91545e-018f},{-1.18424e-015f,-1.0f,1.28722e-015f}, -{0.307814f,-0.951446f,2.44634e-015f},{0.950842f,-0.309676f,-1.04605e-015f},{0.807656f,-0.589654f,2.88358e-015f}, -{0.811958f,-0.583716f,1.00454e-015f},{0.952103f,-0.305779f,-6.20481e-016f},{-0.587751f,-0.809042f,4.16564e-015f}, -{-0.950842f,-0.309676f,-2.44566e-015f},{-0.952103f,-0.305779f,2.45155e-015f},{4.91127e-017f,-1.0f,-8.5099e-018f}, -{-0.309304f,-0.950963f,4.13264e-016f},{-0.307814f,-0.951446f,8.07812e-016f},{-0.588229f,-0.808694f,1.50932e-015f}, -{-0.811958f,-0.583716f,-1.44928e-018f},{-0.807656f,-0.589654f,-2.07994e-015f},{0.587751f,-0.809042f,-3.86108e-016f}, -{0.309304f,-0.950963f,-1.81296e-016f},{0.588229f,-0.808694f,-7.56836e-016f},{5.40884e-017f,-1.0f,-8.5099e-018f}, -{0.307814f,-0.951446f,1.76305e-017f},{0.950842f,-0.309676f,1.56858e-015f},{0.807656f,-0.589654f,2.21017e-015f}, -{0.811958f,-0.583716f,-1.76554e-015f},{0.952103f,-0.305779f,4.58535e-015f},{-0.587751f,-0.809042f,-1.30906e-017f}, -{0.0f,-1.0f,6.43608e-016f},{-0.309304f,-0.950963f,1.22409e-015f},{-0.307814f,-0.951446f,-4.89886e-015f}, -{-0.588229f,-0.808694f,1.04096e-015f},{0.587751f,-0.809042f,7.85491e-016f},{0.588229f,-0.808694f,-5.26397e-016f}, -{1.48864e-033f,-1.0f,6.43608e-016f},{0.307814f,-0.951446f,3.0587e-015f},{0.950842f,-0.309676f,-6.69229e-016f}, -{0.807656f,-0.589654f,-5.31973e-016f},{0.811958f,-0.583716f,7.2278e-016f},{0.952103f,-0.305779f,-1.28478e-016f}, -{-0.587751f,-0.809042f,0.0f},{0.0f,-1.0f,-1.28722e-015f},{-0.309304f,-0.950963f,-2.44819e-015f}, -{-0.588229f,-0.808694f,-2.08193e-015f},{0.309304f,-0.950963f,-1.83692e-015f},{0.588229f,-0.808694f,1.55553e-015f}, -{1.18424e-015f,-1.0f,-1.28722e-015f},{0.307814f,-0.951446f,-1.22781e-015f},{0.950842f,-0.309676f,6.6054e-016f}, -{0.807656f,-0.589654f,-2.71413e-015f},{0.811958f,-0.583716f,-2.47054e-015f},{0.952103f,-0.305779f,5.72628e-016f}, -{-0.950842f,-0.309676f,-6.17708e-020f},{-0.309304f,-0.950963f,-3.93991e-016f},{-0.307814f,-0.951446f,7.77175e-016f}, -{-0.588229f,-0.808694f,7.71841e-016f},{-0.811958f,-0.583716f,-7.65821e-018f},{-0.807656f,-0.589654f,-2.08202e-015f}, -{0.587751f,-0.809042f,-1.97153e-016f},{0.309304f,-0.950963f,2.01908e-016f},{0.588229f,-0.808694f,-1.32498e-015f}, -{0.307814f,-0.951446f,6.16497e-016f},{0.950842f,-0.309676f,-1.06132e-015f},{0.807656f,-0.589654f,-1.94619e-015f}, -{0.811958f,-0.583716f,5.2254e-016f},{0.952103f,-0.305779f,3.28436e-015f},{-0.587751f,-0.809042f,-7.41994e-016f}, -{-1.0f,9.4739e-015f,0.0f},{-0.950842f,-0.309676f,2.4501e-015f},{-0.952103f,-0.305779f,-2.45069e-015f}, -{-0.309304f,-0.950963f,1.51228e-017f},{-0.307814f,-0.951446f,-3.80858e-016f},{-0.588229f,-0.808694f,-5.03529e-018f}, -{-0.807656f,-0.589654f,2.07857e-015f},{0.587751f,-0.809042f,7.48736e-016f},{0.309304f,-0.950963f,-7.78507e-016f}, -{0.588229f,-0.808694f,3.41962e-019f},{0.950842f,-0.309676f,5.45443e-016f},{0.807656f,-0.589654f,4.02952e-015f}, -{0.811958f,-0.583716f,-7.85697e-016f},{0.952103f,-0.305779f,-5.00849e-015f},{1.0f,-1.06581e-014f,0.0f}, -{-0.587751f,-0.809042f,1.50003e-015f},{-0.978165f,-0.20783f,9.12701e-016f},{-0.978254f,-0.207408f,-1.22532e-015f}, -{-0.50141f,-0.86521f,-2.22742e-015f},{-0.66887f,-0.743379f,2.0214e-015f},{-0.809606f,-0.586974f,-1.30267e-016f}, -{-0.913862f,-0.406026f,-1.94353e-015f},{-0.913543f,-0.406743f,0.0f},{-0.105163f,-0.994455f,3.84023e-015f}, -{-0.104013f,-0.994576f,-8.36797e-018f},{0.104013f,-0.994576f,2.56047e-015f},{-0.499433f,-0.866353f,-2.3509e-015f}, -{-0.308272f,-0.951298f,-1.22453e-015f},{-0.310578f,-0.950548f,3.62071e-015f},{0.310578f,-0.950548f,5.86794e-016f}, -{0.50141f,-0.86521f,-2.52602e-015f},{0.499433f,-0.866353f,4.17189e-015f},{0.308272f,-0.951298f,-1.78719e-015f}, -{0.105163f,-0.994455f,2.56862e-015f},{0.670096f,-0.742274f,-7.90726e-016f},{0.809606f,-0.586974f,-4.90953e-016f}, -{0.808947f,-0.587881f,-5.53829e-016f},{0.66887f,-0.743379f,-1.94741e-015f},{0.913543f,-0.406743f,-2.89332e-016f}, -{0.913862f,-0.406026f,1.7826e-016f},{0.978254f,-0.207408f,1.65571e-016f},{0.978165f,-0.20783f,-9.99953e-016f}, -{-0.808947f,-0.587881f,0.0f},{-0.50141f,-0.86521f,4.03389e-017f},{-0.670096f,-0.742274f,-5.84062e-015f}, -{-0.66887f,-0.743379f,-3.82756e-015f},{-0.913543f,-0.406743f,-1.46991e-016f},{-0.105163f,-0.994455f,2.56862e-015f}, -{0.104013f,-0.994576f,2.56883e-015f},{-0.499433f,-0.866353f,2.19018e-015f},{-0.308272f,-0.951298f,-2.44905e-015f}, -{-0.310578f,-0.950548f,4.89424e-015f},{0.310578f,-0.950548f,-1.88531e-015f},{0.50141f,-0.86521f,-1.70082e-015f}, -{0.499433f,-0.866353f,-3.94332e-015f},{0.308272f,-0.951298f,-1.81199e-015f},{0.105163f,-0.994455f,-1.27585e-015f}, -{0.670096f,-0.742274f,2.60918e-015f},{0.809606f,-0.586974f,9.60728e-017f},{0.808947f,-0.587881f,1.32834e-015f}, -{0.66887f,-0.743379f,-9.1653e-016f},{0.913543f,-0.406743f,-4.16505e-016f},{0.913862f,-0.406026f,5.90121e-016f}, -{0.978254f,-0.207408f,3.34195e-017f},{0.978165f,-0.20783f,6.34323e-016f},{1.0f,-3.14563e-016f,0.0f}, -{-0.808947f,-0.587881f,-1.51346e-015f},{-0.978165f,-0.20783f,1.57389e-016f},{-0.978254f,-0.207408f,-1.06792e-015f}, -{-0.670096f,-0.742274f,-5.67889e-015f},{-0.66887f,-0.743379f,-3.77374e-015f},{-0.809606f,-0.586974f,0.0f}, -{-0.105163f,-0.994455f,2.56015e-015f},{0.104013f,-0.994576f,2.56465e-015f},{-0.499433f,-0.866353f,2.27054e-015f}, -{-0.308272f,-0.951298f,-2.43665e-015f},{-0.310578f,-0.950548f,4.88175e-015f},{0.310578f,-0.950548f,-1.81035e-015f}, -{0.50141f,-0.86521f,-1.69074e-015f},{0.499433f,-0.866353f,-3.89811e-015f},{0.308272f,-0.951298f,-1.81819e-015f}, -{0.105163f,-0.994455f,-1.28008e-015f},{0.670096f,-0.742274f,2.46093e-015f},{0.809606f,-0.586974f,4.51872e-017f}, -{0.808947f,-0.587881f,1.19615e-015f},{0.66887f,-0.743379f,-8.76172e-016f},{0.913543f,-0.406743f,-4.37176e-016f}, -{0.913862f,-0.406026f,6.8432e-016f},{0.978254f,-0.207408f,2.10037e-016f},{0.978165f,-0.20783f,4.6264e-016f}, -{-0.808947f,-0.587881f,-1.64362e-015f},{-0.978165f,-0.20783f,1.22748e-015f},{-0.66887f,-0.743379f,1.80616e-015f}, -{-0.809606f,-0.586974f,6.51336e-017f},{-0.913862f,-0.406026f,-2.09057e-015f},{-0.105163f,-0.994455f,3.82754e-015f}, -{-0.104013f,-0.994576f,0.0f},{0.104013f,-0.994576f,2.57302e-015f},{-0.499433f,-0.866353f,-2.27054e-015f}, -{-0.308272f,-0.951298f,-1.23693e-015f},{-0.310578f,-0.950548f,3.65819e-015f},{0.310578f,-0.950548f,5.80547e-016f}, -{0.50141f,-0.86521f,-2.54115e-015f},{0.499433f,-0.866353f,4.11664e-015f},{0.308272f,-0.951298f,-1.80579e-015f}, -{0.105163f,-0.994455f,2.57285e-015f},{0.670096f,-0.742274f,-6.28996e-016f},{0.809606f,-0.586974f,-5.7237e-016f}, -{0.808947f,-0.587881f,-5.701e-016f},{0.66887f,-0.743379f,-2.03485e-015f},{0.913543f,-0.406743f,-4.37471e-016f}, -{0.913862f,-0.406026f,1.49541e-016f},{0.978254f,-0.207408f,1.87245e-016f},{0.978165f,-0.20783f,-1.1409e-015f}, -{-0.978254f,-0.207408f,-5.00352e-015f},{-0.50141f,-0.86521f,6.9607e-017f},{-0.670096f,-0.742274f,1.78483e-015f}, -{-0.66887f,-0.743379f,-1.19611e-016f},{-0.809606f,-0.586974f,-2.08427e-015f},{-0.913543f,-0.406743f,-6.54457e-017f}, -{-0.105163f,-0.994455f,1.9073e-016f},{-0.104013f,-0.994576f,-3.4779e-016f},{0.104013f,-0.994576f,1.73895e-016f}, -{-0.499433f,-0.866353f,1.49485e-015f},{-0.308272f,-0.951298f,8.70157e-016f},{-0.310578f,-0.950548f,-7.64725e-017f}, -{0.310578f,-0.950548f,-1.90331e-015f},{0.50141f,-0.86521f,-1.84452e-015f},{0.499433f,-0.866353f,-3.48494e-017f}, -{0.308272f,-0.951298f,-3.58546e-016f},{0.105163f,-0.994455f,4.61465e-016f},{0.670096f,-0.742274f,-7.66352e-016f}, -{0.809606f,-0.586974f,-1.39162e-015f},{0.808947f,-0.587881f,-4.28911e-016f},{0.66887f,-0.743379f,-1.68458e-015f}, -{0.913543f,-0.406743f,-2.14927e-016f},{0.913862f,-0.406026f,3.22114e-015f},{0.978254f,-0.207408f,-1.64157e-015f}, -{0.978165f,-0.20783f,4.10552e-015f},{-0.808947f,-0.587881f,-2.08258e-015f},{-0.978165f,-0.20783f,-5.03643e-015f}, -{-0.978254f,-0.207408f,3.33724e-017f},{-0.50141f,-0.86521f,-1.22124e-015f},{-0.670096f,-0.742274f,5.97167e-017f}, -{-0.66887f,-0.743379f,1.60235e-015f},{-0.913862f,-0.406026f,2.35267e-015f},{-0.913543f,-0.406743f,2.28641e-015f}, -{-0.105163f,-0.994455f,-8.00048e-017f},{-0.104013f,-0.994576f,5.3873e-017f},{0.104013f,-0.994576f,-9.38801e-017f}, -{-0.499433f,-0.866353f,-1.07666e-015f},{-0.308272f,-0.951298f,7.65328e-017f},{0.310578f,-0.950548f,2.95481e-016f}, -{0.50141f,-0.86521f,-1.52181e-015f},{0.499433f,-0.866353f,1.2587e-016f},{0.308272f,-0.951298f,-5.56952e-016f}, -{0.105163f,-0.994455f,-8.00048e-017f},{0.670096f,-0.742274f,-1.41327e-015f},{0.809606f,-0.586974f,1.47426e-015f}, -{0.808947f,-0.587881f,4.17136e-016f},{0.66887f,-0.743379f,-7.15979e-016f},{0.913543f,-0.406743f,-2.88423e-016f}, -{0.913862f,-0.406026f,1.97129e-015f},{0.978254f,-0.207408f,-1.91702e-015f},{0.978165f,-0.20783f,1.59714e-015f}, -{1.0f,-1.0066e-014f,0.0f},{-0.50141f,-0.86521f,-1.43006e-015f},{-0.66887f,-0.743379f,1.78177e-015f}, -{-0.913543f,-0.406743f,2.4173e-015f},{-0.105163f,-0.994455f,0.0f},{-0.104013f,-0.994576f,1.33888e-016f}, -{0.104013f,-0.994576f,6.6149e-017f},{-0.499433f,-0.866353f,-1.35545e-015f},{-0.308272f,-0.951298f,2.29599e-016f}, -{0.310578f,-0.950548f,1.42536e-016f},{0.50141f,-0.86521f,-1.55661e-015f},{0.499433f,-0.866353f,3.87464e-017f}, -{0.308272f,-0.951298f,-6.71751e-016f},{0.105163f,-0.994455f,-4.00024e-017f},{0.670096f,-0.742274f,-1.21919e-015f}, -{0.809606f,-0.586974f,1.4477e-015f},{0.808947f,-0.587881f,4.93992e-016f},{0.66887f,-0.743379f,-8.50541e-016f}, -{0.913543f,-0.406743f,-2.17864e-016f},{0.913862f,-0.406026f,2.0356e-015f},{0.978254f,-0.207408f,-1.90767e-015f}, -{0.978165f,-0.20783f,1.60331e-015f},{-0.50141f,-0.86521f,-1.39214e-016f},{-0.670096f,-0.742274f,1.72512e-015f}, -{-0.66887f,-0.743379f,5.98056e-017f},{-0.913543f,-0.406743f,6.54457e-017f},{-0.105163f,-0.994455f,2.70735e-016f}, -{-0.104013f,-0.994576f,-2.67775e-016f},{0.104013f,-0.994576f,3.33924e-016f},{-0.499433f,-0.866353f,1.21606e-015f}, -{-0.308272f,-0.951298f,1.02322e-015f},{0.310578f,-0.950548f,-2.05626e-015f},{0.50141f,-0.86521f,-1.87932e-015f}, -{0.499433f,-0.866353f,-1.21973e-016f},{0.308272f,-0.951298f,-4.73345e-016f},{0.105163f,-0.994455f,5.01467e-016f}, -{0.670096f,-0.742274f,-5.72273e-016f},{0.809606f,-0.586974f,-1.41818e-015f},{0.808947f,-0.587881f,-3.52056e-016f}, -{0.66887f,-0.743379f,-1.81914e-015f},{0.913543f,-0.406743f,-1.44369e-016f},{0.913862f,-0.406026f,3.28545e-015f}, -{0.978254f,-0.207408f,-1.63222e-015f},{0.978165f,-0.20783f,4.11169e-015f},{-0.50141f,-0.86521f,-4.03389e-017f}, -{-0.670096f,-0.742274f,1.91093e-015f},{-0.66887f,-0.743379f,3.82756e-015f},{-0.913862f,-0.406026f,-1.04529e-015f}, -{-0.913543f,-0.406743f,-1.04713e-015f},{-0.105163f,-0.994455f,-2.54323e-015f},{-0.104013f,-0.994576f,-1.29697e-015f}, -{0.104013f,-0.994576f,-1.28442e-015f},{-0.499433f,-0.866353f,-4.42055e-015f},{-0.308272f,-0.951298f,-2.37465e-015f}, -{-0.310578f,-0.950548f,2.40964e-015f},{0.50141f,-0.86521f,3.52965e-017f},{0.499433f,-0.866353f,2.27557e-015f}, -{0.308272f,-0.951298f,2.46765e-015f},{0.105163f,-0.994455f,-2.55169e-015f},{0.670096f,-0.742274f,-1.08164e-015f}, -{0.809606f,-0.586974f,1.7623e-015f},{0.808947f,-0.587881f,-8.13675e-016f},{0.66887f,-0.743379f,-5.12076e-016f}, -{0.913543f,-0.406743f,-1.07269e-015f},{0.913862f,-0.406026f,8.92948e-016f},{0.978254f,-0.207408f,2.07703e-016f}, -{0.978165f,-0.20783f,-1.28498e-015f},{-0.808947f,-0.587881f,1.57854e-015f},{-0.978165f,-0.20783f,1.07009e-015f}, -{-0.50141f,-0.86521f,2.3081e-015f},{-0.670096f,-0.742274f,-5.39099e-017f},{-0.66887f,-0.743379f,-5.38112e-017f}, -{-0.809606f,-0.586974f,-1.64139e-015f},{-0.913862f,-0.406026f,1.47042e-016f},{-0.105163f,-0.994455f,-6.3877e-015f}, -{-0.104013f,-0.994576f,-1.25931e-015f},{0.104013f,-0.994576f,-1.27187e-015f},{-0.308272f,-0.951298f,3.63638e-015f}, -{-0.310578f,-0.950548f,2.44712e-015f},{0.50141f,-0.86521f,8.45368e-016f},{0.499433f,-0.866353f,-2.48405e-015f}, -{0.308272f,-0.951298f,-3.07371e-015f},{0.105163f,-0.994455f,-3.84446e-015f},{0.670096f,-0.742274f,2.29805e-015f}, -{0.809606f,-0.586974f,-1.2864e-016f},{0.808947f,-0.587881f,4.24795e-015f},{0.66887f,-0.743379f,4.38086e-016f}, -{0.913543f,-0.406743f,-1.06091e-015f},{0.913862f,-0.406026f,-6.1115e-016f},{0.978254f,-0.207408f,-6.34059e-017f}, -{0.978165f,-0.20783f,2.90712e-016f},{-0.808947f,-0.587881f,-6.50806e-017f},{-1.0f,-3.70074e-017f,0.0f}, -{-0.978165f,-0.20783f,-3.14777e-016f},{-0.978254f,-0.207408f,1.57403e-016f},{-0.670096f,-0.742274f,1.80311e-015f}, -{-0.913862f,-0.406026f,-1.33937e-015f},{-0.913543f,-0.406743f,-1.34111e-015f},{-0.105163f,-0.994455f,-2.56862e-015f}, -{-0.104013f,-0.994576f,-1.24676e-015f},{0.104013f,-0.994576f,-1.29697e-015f},{-0.308272f,-0.951298f,-2.42425e-015f}, -{-0.310578f,-0.950548f,2.42213e-015f},{0.50141f,-0.86521f,0.0f},{0.499433f,-0.866353f,2.20023e-015f}, -{0.308272f,-0.951298f,2.46145e-015f},{0.105163f,-0.994455f,-2.56439e-015f},{0.670096f,-0.742274f,-1.10185e-015f}, -{0.809606f,-0.586974f,2.00044e-015f},{0.808947f,-0.587881f,-6.46906e-016f},{0.66887f,-0.743379f,-4.85171e-016f}, -{0.913543f,-0.406743f,-9.18809e-016f},{0.913862f,-0.406026f,9.41196e-016f},{0.978254f,-0.207408f,2.63205e-017f}, -{0.978165f,-0.20783f,-1.29405e-015f},{-0.808947f,-0.587881f,1.51346e-015f},{-0.978254f,-0.207408f,-1.57403e-016f}, -{-0.50141f,-0.86521f,2.18708e-015f},{-0.670096f,-0.742274f,1.0782e-016f},{-0.66887f,-0.743379f,-1.07622e-016f}, -{-0.809606f,-0.586974f,-1.51112e-015f},{-0.105163f,-0.994455f,-6.39193e-015f},{-0.104013f,-0.994576f,-1.27187e-015f}, -{0.104013f,-0.994576f,-1.25931e-015f},{-0.499433f,-0.866353f,-2.23036e-015f},{-0.308272f,-0.951298f,3.67358e-015f}, -{0.50141f,-0.86521f,8.65538e-016f},{0.499433f,-0.866353f,-2.50916e-015f},{0.308272f,-0.951298f,-3.06131e-015f}, -{0.105163f,-0.994455f,-3.82754e-015f},{0.670096f,-0.742274f,2.06893e-015f},{0.809606f,-0.586974f,-5.53643e-017f}, -{0.808947f,-0.587881f,4.16863e-015f},{0.66887f,-0.743379f,5.79341e-016f},{0.913543f,-0.406743f,-8.98992e-016f}, -{0.913862f,-0.406026f,-7.47853e-016f},{0.978254f,-0.207408f,6.23321e-017f},{0.978165f,-0.20783f,2.84103e-016f}, -{-0.50141f,-0.86521f,1.36045e-015f},{-0.670096f,-0.742274f,-1.6654e-015f},{-0.66887f,-0.743379f,-1.84157e-015f}, -{-0.913543f,-0.406743f,4.63826e-015f},{-0.104013f,-0.994576f,-4.81677e-016f},{0.104013f,-0.994576f,-4.95542e-016f}, -{-0.499433f,-0.866353f,2.09097e-016f},{-0.310578f,-0.950548f,1.12287e-015f},{0.310578f,-0.950548f,4.95371e-016f}, -{0.50141f,-0.86521f,-3.92318e-016f},{0.308272f,-0.951298f,2.36673e-016f},{0.670096f,-0.742274f,-8.74172e-016f}, -{0.809606f,-0.586974f,-2.30349e-015f},{0.808947f,-0.587881f,-3.42262e-015f},{0.66887f,-0.743379f,-3.93111e-016f}, -{0.913543f,-0.406743f,6.30269e-016f},{0.913862f,-0.406026f,1.6772e-015f},{0.978254f,-0.207408f,-2.36956e-015f}, -{0.978165f,-0.20783f,3.13168e-015f},{1.0f,1.0066e-014f,0.0f},{-0.808947f,-0.587881f,6.24774e-015f}, -{-0.50141f,-0.86521f,1.15163e-015f},{-0.670096f,-0.742274f,-1.72512e-015f},{-0.66887f,-0.743379f,-1.66215e-015f}, -{-0.913543f,-0.406743f,4.76915e-015f},{-0.104013f,-0.994576f,-4.01663e-016f},{0.104013f,-0.994576f,-3.35513e-016f}, -{-0.499433f,-0.866353f,-6.96989e-017f},{0.310578f,-0.950548f,3.42426e-016f},{0.50141f,-0.86521f,-4.27122e-016f}, -{0.308272f,-0.951298f,1.21873e-016f},{0.670096f,-0.742274f,-6.80093e-016f},{0.809606f,-0.586974f,-2.33005e-015f}, -{0.808947f,-0.587881f,-3.34576e-015f},{0.66887f,-0.743379f,-5.27674e-016f},{0.913543f,-0.406743f,7.00828e-016f}, -{0.913862f,-0.406026f,1.74151e-015f},{0.978254f,-0.207408f,-2.3602e-015f},{0.978165f,-0.20783f,3.13785e-015f}, -{-0.913862f,-0.406026f,4.70535e-015f},{0.104013f,-0.994576f,-6.77384e-017f},{-0.308272f,-0.951298f,-1.67214e-016f}, -{-0.310578f,-0.950548f,7.23088e-016f},{0.50141f,-0.86521f,1.83186e-015f},{0.499433f,-0.866353f,-2.8542e-015f}, -{0.308272f,-0.951298f,-7.65328e-017f},{0.105163f,-0.994455f,-4.46105e-016f},{0.809606f,-0.586974f,1.38256e-015f}, -{0.808947f,-0.587881f,2.9875e-016f},{0.66887f,-0.743379f,3.33306e-016f},{0.913543f,-0.406743f,2.97918e-015f}, -{0.913862f,-0.406026f,-3.51524e-015f},{0.978254f,-0.207408f,-2.31593e-015f},{0.978165f,-0.20783f,6.29469e-016f}, -{0.104013f,-0.994576f,-2.27768e-016f},{-0.308272f,-0.951298f,-3.20279e-016f},{0.50141f,-0.86521f,1.86666e-015f}, -{0.499433f,-0.866353f,-2.76708e-015f},{0.308272f,-0.951298f,3.82664e-017f},{0.105163f,-0.994455f,-4.86107e-016f}, -{0.809606f,-0.586974f,1.40912e-015f},{0.808947f,-0.587881f,2.21895e-016f},{0.66887f,-0.743379f,4.67868e-016f}, -{0.913543f,-0.406743f,2.90863e-015f},{0.913862f,-0.406026f,-3.57955e-015f},{0.978254f,-0.207408f,-2.32529e-015f}, -{0.978165f,-0.20783f,6.23297e-016f},{1.0503e-015f,1.0f,-4.4248e-016f},{1.32669e-015f,1.0f,-4.4248e-016f}, -{-0.987342f,0.158603f,0.0f},{-0.563203f,0.826318f,-2.43092e-015f},{-0.766044f,0.642788f,-2.58564e-017f}, -{-0.911564f,0.411158f,-2.41291e-015f},{-0.327644f,0.944801f,1.60877e-016f},{-5.81917e-015f,-1.0f,0.0f}, -{-3.12964e-015f,-1.0f,0.0f},{0.944801f,-0.327644f,-2.48504e-015f},{0.411158f,-0.911564f,5.40403e-016f}, -{0.642788f,-0.766044f,-2.51303e-015f},{0.826318f,-0.563203f,-2.17261e-015f},{0.158603f,-0.987342f,1.69056e-016f}, -{-1.0f,-1.42312e-031f,5.14886e-015f},{-1.0f,-7.0757e-015f,5.14886e-015f},{-0.158603f,-0.987342f,4.87746e-016f}, -{-0.826318f,-0.563203f,2.94231e-016f},{-0.642788f,-0.766044f,-4.19866e-015f},{-0.411158f,-0.911564f,3.66681e-017f}, -{-0.944801f,-0.327644f,4.51725e-015f},{1.0f,-6.25927e-015f,0.0f},{0.327644f,0.944801f,-7.60102e-017f}, -{0.911564f,0.411158f,-8.94506e-016f},{0.766044f,0.642788f,-2.51041e-015f},{0.563203f,0.826318f,1.48317e-015f}, -{0.987342f,0.158603f,-9.73349e-016f},{2.81922e-015f,-1.0f,2.81578e-016f},{2.21116e-015f,-1.0f,2.81578e-016f}, -{0.987342f,-0.158603f,5.08369e-015f},{0.563203f,-0.826318f,-1.72179e-015f},{0.766044f,-0.642788f,2.02384e-015f}, -{0.911564f,-0.411158f,1.10722e-015f},{0.327644f,-0.944801f,-4.42325e-016f},{2.93403e-016f,1.0f,0.0f}, -{-2.34723e-015f,1.0f,0.0f},{-0.944801f,0.327644f,5.27185e-017f},{-0.411158f,0.911564f,-1.08478e-015f}, -{-0.642788f,0.766044f,-1.94526e-015f},{-0.826318f,0.563203f,3.28157e-015f},{-0.158603f,0.987342f,-5.96628e-016f}, -{-0.158603f,0.987342f,-7.51139e-016f},{-1.50359e-014f,1.0f,-3.86165e-015f},{-2.12271e-014f,1.0f,-3.86165e-015f}, -{-0.563203f,0.826318f,-1.74542e-015f},{-0.766044f,0.642788f,1.27192e-015f},{-0.911564f,0.411158f,0.0f}, -{-0.327644f,0.944801f,-1.40602e-017f},{6.25927e-015f,-1.0f,0.0f},{-2.50371e-014f,-1.0f,0.0f}, -{0.944801f,-0.327644f,-7.60102e-017f},{0.411158f,-0.911564f,-1.34268e-016f},{0.642788f,-0.766044f,-1.4597e-015f}, -{0.826318f,-0.563203f,3.3239e-017f},{0.158603f,-0.987342f,-2.36033e-015f},{-1.0f,-1.50359e-014f,-3.86165e-015f}, -{-1.0f,-2.12271e-014f,-3.86165e-015f},{-0.158603f,-0.987342f,7.37193e-016f},{-0.826318f,-0.563203f,-1.7256e-015f}, -{-0.642788f,-0.766044f,1.218e-015f},{-0.411158f,-0.911564f,-7.33362e-017f},{-0.944801f,-0.327644f,-1.94144e-017f}, -{1.0f,6.25927e-015f,0.0f},{1.0f,-2.50371e-014f,0.0f},{0.327644f,0.944801f,8.43496e-016f}, -{0.911564f,0.411158f,-2.04101e-015f},{0.766044f,0.642788f,-9.60208e-016f},{0.563203f,0.826318f,-7.24964e-016f}, -{0.987342f,0.158603f,-4.26811e-015f},{1.50359e-014f,-1.0f,-3.86165e-015f},{2.12271e-014f,-1.0f,-3.86165e-015f}, -{0.987342f,-0.158603f,8.96059e-016f},{0.563203f,-0.826318f,-1.76241e-015f},{0.766044f,-0.642788f,1.23341e-015f}, -{0.911564f,-0.411158f,0.0f},{0.327644f,-0.944801f,-1.48839e-017f},{-6.25927e-015f,1.0f,0.0f}, -{2.50371e-014f,1.0f,0.0f},{-0.944801f,0.327644f,9.19506e-016f},{-0.411158f,0.911564f,-2.04721e-015f}, -{-0.642788f,0.766044f,-9.47279e-016f},{-0.826318f,0.563203f,-6.58486e-016f},{-0.158603f,0.987342f,-4.27439e-015f}, -{-1.0f,-5.52789e-017f,-2.01127e-016f},{-1.0f,-4.42231e-016f,-2.01127e-016f},{-0.158603f,-0.987342f,2.56736e-015f}, -{-0.826318f,-0.563203f,2.03441e-015f},{-0.642788f,-0.766044f,-1.89456e-015f},{-0.411158f,-0.911564f,-2.2806e-015f}, -{-0.944801f,-0.327644f,-6.80855e-016f},{1.0f,-1.02691e-015f,0.0f},{1.0f,7.82409e-016f,0.0f}, -{0.327644f,0.944801f,-4.81193e-015f},{0.911564f,0.411158f,1.02824e-016f},{0.766044f,0.642788f,0.0f}, -{0.563203f,0.826318f,-1.01834e-015f},{0.987342f,0.158603f,1.80074e-016f},{2.43227e-015f,-1.0f,2.81578e-016f}, -{2.65339e-015f,-1.0f,2.81578e-016f},{0.987342f,-0.158603f,-2.51632e-015f},{0.563203f,-0.826318f,-1.48159e-015f}, -{0.766044f,-0.642788f,5.18888e-016f},{0.911564f,-0.411158f,-1.17338e-015f},{0.327644f,-0.944801f,-1.30642e-017f}, -{1.95602e-016f,1.0f,0.0f},{-0.944801f,0.327644f,-4.86465e-015f},{-0.411158f,0.911564f,3.45909e-016f}, -{-0.642788f,0.766044f,5.06146e-016f},{-0.826318f,0.563203f,2.08199e-015f},{-0.158603f,0.987342f,3.01313e-016f}, -{-0.158603f,0.987342f,7.86925e-017f},{1.0f,1.10558e-016f,-2.41353e-016f},{1.0f,4.42231e-016f,-2.41353e-016f}, -{0.158603f,0.987342f,2.56736e-015f},{0.826318f,0.563203f,-1.66982e-016f},{0.642788f,0.766044f,-1.94627e-015f}, -{0.944801f,0.327644f,-1.31395e-015f},{-1.0f,1.95602e-016f,0.0f},{-1.0f,-2.34723e-015f,0.0f}, -{-0.327644f,-0.944801f,-2.37961e-015f},{-0.911564f,-0.411158f,5.88225e-016f},{-0.766044f,-0.642788f,1.27192e-015f}, -{-0.563203f,-0.826318f,-1.10896e-015f},{-0.987342f,-0.158603f,-2.16372e-016f},{1.42312e-031f,-1.0f,5.14886e-015f}, -{7.0757e-015f,-1.0f,5.14886e-015f},{0.987342f,-0.158603f,4.08313e-016f},{0.563203f,-0.826318f,2.82904e-016f}, -{0.766044f,-0.642788f,-4.12933e-015f},{0.327644f,-0.944801f,4.50922e-015f},{6.25927e-015f,1.0f,0.0f}, -{-0.944801f,0.327644f,0.0f},{-0.411158f,0.911564f,-8.71765e-016f},{-0.642788f,0.766044f,-2.4393e-015f}, -{-0.826318f,0.563203f,1.44993e-015f},{-0.158603f,0.987342f,-9.70258e-016f},{1.0f,1.42312e-031f,5.14886e-015f}, -{1.0f,7.0757e-015f,5.14886e-015f},{0.158603f,0.987342f,4.08313e-016f},{0.826318f,0.563203f,2.46089e-016f}, -{0.642788f,0.766044f,-4.11392e-015f},{0.411158f,0.911564f,3.66681e-017f},{0.944801f,0.327644f,4.51313e-015f}, -{-1.0f,6.25927e-015f,0.0f},{-0.911564f,-0.411158f,-8.90371e-016f},{-0.766044f,-0.642788f,-2.52334e-015f}, -{-0.563203f,-0.826318f,1.38345e-015f},{-0.987342f,-0.158603f,-9.72053e-016f},{-1.50359e-014f,1.0f,3.86165e-015f}, -{-1.41514e-014f,1.0f,3.86165e-015f},{-0.563203f,0.826318f,2.60249e-016f},{-0.766044f,0.642788f,-4.12933e-015f}, -{-0.911564f,0.411158f,3.66681e-017f},{-0.327644f,0.944801f,4.53578e-015f},{-1.7213e-014f,-1.0f,0.0f}, -{1.25185e-014f,-1.0f,0.0f},{0.944801f,-0.327644f,1.68699e-015f},{0.411158f,-0.911564f,-2.19388e-015f}, -{0.642788f,-0.766044f,-9.92528e-016f},{0.826318f,-0.563203f,2.89985e-015f},{0.158603f,-0.987342f,-9.67866e-016f}, -{1.0f,8.84462e-016f,1.20676e-016f},{1.0f,4.42231e-016f,1.20676e-016f},{0.826318f,0.563203f,-7.99752e-016f}, -{0.642788f,0.766044f,5.96458e-016f},{0.411158f,0.911564f,1.10722e-015f},{0.944801f,0.327644f,-1.19869e-015f}, -{-1.0f,2.93403e-016f,0.0f},{-0.327644f,-0.944801f,-5.27185e-017f},{-0.327644f,-0.944801f,-2.43232e-015f}, -{-0.911564f,-0.411158f,6.36047e-016f},{-0.563203f,-0.826318f,1.06365e-015f},{-0.987342f,-0.158603f,-1.62229e-016f}, -{1.43725e-015f,1.0f,-3.21804e-016f},{1.76892e-015f,1.0f,-3.21804e-016f},{-0.987342f,0.158603f,2.51632e-015f}, -{-0.563203f,0.826318f,3.20933e-016f},{-0.766044f,0.642788f,1.73942e-015f},{-0.911564f,0.411158f,2.37984e-015f}, -{-0.327644f,0.944801f,5.5243e-017f},{-2.68953e-015f,-1.0f,0.0f},{0.944801f,-0.327644f,-4.81193e-015f}, -{0.411158f,-0.911564f,-1.59493e-015f},{0.642788f,-0.766044f,3.34044e-015f},{0.826318f,-0.563203f,-1.01834e-015f}, -{0.158603f,-0.987342f,-8.62776e-016f},{-1.0f,1.93476e-015f,-2.81578e-016f},{-1.0f,2.21116e-015f,-2.81578e-016f}, -{-0.158603f,-0.987342f,5.10921e-015f},{-0.826318f,-0.563203f,-2.16142e-015f},{-0.642788f,-0.766044f,1.58252e-015f}, -{-0.411158f,-0.911564f,-1.1403e-015f},{-0.944801f,-0.327644f,-1.28754e-015f},{1.0f,-2.78733e-015f,0.0f}, -{1.0f,-1.56482e-015f,0.0f},{0.327644f,0.944801f,0.0f},{0.911564f,0.411158f,2.03571e-015f}, -{0.766044f,0.642788f,-4.90281e-015f},{0.563203f,0.826318f,3.19095e-015f},{0.987342f,0.158603f,-6.10433e-016f} -}; -GLfloat textures[1][2]={{0.0f,0.0f}}; -/*Material indicies*/ -/*{material index,face count}*/ -static int material_ref [1][2] = { -{0,77848} -}; -void MyMaterial(GLenum mode, GLfloat * f, GLfloat alpha) -{ - GLfloat d[4]; - d[0] = f[0]; - d[1] = f[1]; - d[2] = f[2]; - d[3] = alpha; - glMaterialfv(GL_FRONT_AND_BACK, mode, d); -} - -/* - * SelectMaterial uses OpenGL commands to define facet colors. - * - * Returns: - * Nothing - */ - -void SelectMaterial(int i) -{ -// -// Define the reflective properties of the 3D Object faces. -// - glEnd(); - GLfloat alpha = materials[i].alpha; - MyMaterial(GL_AMBIENT, materials[i].ambient, alpha); - MyMaterial(GL_DIFFUSE, materials[i].diffuse, alpha); - MyMaterial(GL_SPECULAR, materials[i].specular, alpha); - MyMaterial(GL_EMISSION, materials[i].emission, alpha); - glMaterialf(GL_FRONT_AND_BACK, GL_SHININESS, materials[i].phExp); - glBegin(GL_TRIANGLES); - -}; - -GLint generatePixhawkCheetah(float red, float green, float blue) -{ - unsigned int i; - int j; - - GLint lid=glGenLists(1); - int mcount=0; - int mindex=0; - glNewList(lid, GL_COMPILE); - - glColor3f(red, green, blue); - - glBegin (GL_TRIANGLES); - for(i=0;i + +This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + +======================================================================*/ + +/** + * @file + * @brief Generates a display list which renders a Pixhawk Cheetah MAV. + * + * @author Lionel Heng + * + */ + +#include "CheetahGL.h" + +#if (defined __APPLE__) & (defined __MACH__) +#include +#include +#else +#include +#include +#endif + + +struct sample_MATERIAL +{ + GLfloat ambient[3]; + GLfloat diffuse[3]; + GLfloat specular[3]; + GLfloat emission[3]; + GLfloat alpha; + GLfloat phExp; + int texture; +}; + +static sample_MATERIAL materials [1] = { + {{0.117647f,0.117647f,0.117647f}, {0.596078f,0.666667f,0.686275f}, {0.301176f,0.301176f,0.301176f}, {0.0f,0.0f,0.0f}, 1.0f,8.0f,-1} //Material #1 +}; + +// 38747 Verticies +// 0 Texture Coordinates +// 22155 Normals +// 77848 Triangles + +static unsigned short face_indicies[77848][9] = { +// Battery3.prt + {0,1,2 ,0,1,0 ,0,0,0}, {3,4,5 ,2,2,3 ,0,0,0}, {3,2,4 ,2,0,2 ,0,0,0}, + {5,4,6 ,3,2,3 ,0,0,0}, {2,3,0 ,0,2,0 ,0,0,0}, {7,1,0 ,1,1,0 ,0,0,0}, + {8,7,9 ,4,1,4 ,0,0,0}, {7,8,1 ,1,4,1 ,0,0,0}, {10,11,12 ,5,6,5 ,0,0,0}, + {13,14,15 ,7,7,8 ,0,0,0}, {13,12,14 ,7,5,7 ,0,0,0}, {15,14,16 ,8,7,8 ,0,0,0}, + {12,13,10 ,5,7,5 ,0,0,0}, {17,11,10 ,9,6,5 ,0,0,0}, {18,17,19 ,10,9,11 ,0,0,0}, + {17,18,11 ,9,10,6 ,0,0,0}, {20,21,22 ,12,13,12 ,0,0,0}, {23,24,25 ,14,14,15 ,0,0,0}, + {23,22,24 ,14,12,14 ,0,0,0}, {25,24,26 ,15,14,15 ,0,0,0}, {22,23,20 ,12,14,12 ,0,0,0}, + {27,21,20 ,13,13,12 ,0,0,0}, {28,27,29 ,16,13,16 ,0,0,0}, {27,28,21 ,13,16,13 ,0,0,0}, + {30,31,32 ,17,18,17 ,0,0,0}, {33,34,35 ,19,19,20 ,0,0,0}, {33,32,34 ,19,17,19 ,0,0,0}, + {35,34,36 ,20,19,20 ,0,0,0}, {32,33,30 ,17,19,17 ,0,0,0}, {37,31,30 ,18,18,17 ,0,0,0}, + {38,37,39 ,21,18,21 ,0,0,0}, {37,38,31 ,18,21,18 ,0,0,0}, {40,41,42 ,22,23,24 ,0,0,0}, + {43,44,45 ,25,26,27 ,0,0,0}, {46,40,42 ,28,22,24 ,0,0,0}, {45,44,46 ,27,26,28 ,0,0,0}, + {44,43,47 ,26,25,29 ,0,0,0}, {42,45,46 ,24,27,28 ,0,0,0}, {48,49,50 ,30,31,32 ,0,0,0}, + {49,51,50 ,31,33,32 ,0,0,0}, {47,52,48 ,29,34,30 ,0,0,0}, {49,48,52 ,31,30,34 ,0,0,0}, + {53,54,55 ,35,36,37 ,0,0,0}, {56,57,51 ,38,39,33 ,0,0,0}, {54,57,56 ,36,39,38 ,0,0,0}, + {54,56,55 ,36,38,37 ,0,0,0}, {55,58,53 ,37,40,35 ,0,0,0}, {50,51,57 ,32,33,39 ,0,0,0}, + {47,43,52 ,29,25,34 ,0,0,0}, {40,59,41 ,22,41,23 ,0,0,0}, {60,59,61 ,42,41,43 ,0,0,0}, + {59,60,41 ,41,42,23 ,0,0,0}, {62,63,61 ,44,45,43 ,0,0,0}, {60,61,63 ,42,43,45 ,0,0,0}, + {62,64,65 ,44,46,47 ,0,0,0}, {65,63,62 ,47,45,44 ,0,0,0}, {66,64,67 ,48,46,49 ,0,0,0}, + {64,66,65 ,46,48,47 ,0,0,0}, {68,69,67 ,50,51,49 ,0,0,0}, {66,67,69 ,48,49,51 ,0,0,0}, + {68,70,71 ,50,52,53 ,0,0,0}, {71,69,68 ,53,51,50 ,0,0,0}, {72,70,73 ,54,52,54 ,0,0,0}, + {70,72,71 ,52,54,53 ,0,0,0}, {74,75,76 ,22,55,24 ,0,0,0}, {77,78,79 ,56,57,58 ,0,0,0}, + {80,74,76 ,59,22,24 ,0,0,0}, {79,78,80 ,58,57,59 ,0,0,0}, {78,77,81 ,57,56,60 ,0,0,0}, + {76,79,80 ,24,58,59 ,0,0,0}, {82,83,84 ,61,62,63 ,0,0,0}, {83,85,84 ,62,64,63 ,0,0,0}, + {81,86,82 ,60,65,61 ,0,0,0}, {83,82,86 ,62,61,65 ,0,0,0}, {87,88,89 ,66,67,68 ,0,0,0}, + {90,91,85 ,69,70,64 ,0,0,0}, {88,91,90 ,67,70,69 ,0,0,0}, {88,90,89 ,67,69,68 ,0,0,0}, + {89,92,87 ,68,66,66 ,0,0,0}, {84,85,91 ,63,64,70 ,0,0,0}, {81,77,86 ,60,56,65 ,0,0,0}, + {74,93,75 ,22,71,55 ,0,0,0}, {94,93,95 ,72,71,43 ,0,0,0}, {93,94,75 ,71,72,55 ,0,0,0}, + {96,97,95 ,73,74,43 ,0,0,0}, {94,95,97 ,72,43,74 ,0,0,0}, {96,98,99 ,73,46,75 ,0,0,0}, + {99,97,96 ,75,74,73 ,0,0,0}, {100,98,101 ,76,46,77 ,0,0,0}, {98,100,99 ,46,76,75 ,0,0,0}, + {102,103,101 ,50,78,77 ,0,0,0}, {100,101,103 ,76,77,78 ,0,0,0}, + {102,104,105 ,50,79,80 ,0,0,0}, {105,103,102 ,80,78,50 ,0,0,0}, + {106,104,107 ,81,79,82 ,0,0,0}, {104,106,105 ,79,81,80 ,0,0,0}, + {108,109,110 ,83,84,85 ,0,0,0}, {111,112,113 ,86,87,88 ,0,0,0}, + {114,108,110 ,89,83,85 ,0,0,0}, {113,112,114 ,88,87,89 ,0,0,0}, + {112,111,115 ,87,86,90 ,0,0,0}, {110,113,114 ,85,88,89 ,0,0,0}, + {116,117,118 ,91,92,93 ,0,0,0}, {117,119,118 ,92,94,93 ,0,0,0}, + {115,120,116 ,90,95,91 ,0,0,0}, {117,116,120 ,92,91,95 ,0,0,0}, + {121,122,123 ,96,97,98 ,0,0,0}, {124,125,119 ,99,100,94 ,0,0,0}, + {122,125,124 ,97,100,99 ,0,0,0}, {122,124,123 ,97,99,98 ,0,0,0}, + {123,126,121 ,98,101,96 ,0,0,0}, {118,119,125 ,93,94,100 ,0,0,0}, + {115,111,120 ,90,86,95 ,0,0,0}, {108,127,109 ,83,102,84 ,0,0,0}, + {128,127,129 ,103,102,104 ,0,0,0}, {127,128,109 ,102,103,84 ,0,0,0}, + {130,131,129 ,105,106,104 ,0,0,0}, {128,129,131 ,103,104,106 ,0,0,0}, + {130,132,133 ,105,107,108 ,0,0,0}, {133,131,130 ,108,106,105 ,0,0,0}, + {134,132,135 ,109,107,110 ,0,0,0}, {132,134,133 ,107,109,108 ,0,0,0}, + {136,137,135 ,111,112,110 ,0,0,0}, {134,135,137 ,109,110,112 ,0,0,0}, + {136,138,139 ,111,113,114 ,0,0,0}, {139,137,136 ,114,112,111 ,0,0,0}, + {140,138,141 ,54,113,54 ,0,0,0}, {138,140,139 ,113,54,114 ,0,0,0}, + {142,143,144 ,83,115,85 ,0,0,0}, {145,146,147 ,116,117,118 ,0,0,0}, + {148,142,144 ,119,83,85 ,0,0,0}, {147,146,148 ,118,117,119 ,0,0,0}, + {146,145,149 ,117,116,120 ,0,0,0}, {144,147,148 ,85,118,119 ,0,0,0}, + {150,151,152 ,121,122,123 ,0,0,0}, {151,153,152 ,122,124,123 ,0,0,0}, + {149,154,150 ,120,125,121 ,0,0,0}, {151,150,154 ,122,121,125 ,0,0,0}, + {155,156,157 ,126,127,128 ,0,0,0}, {158,159,153 ,129,130,124 ,0,0,0}, + {156,159,158 ,127,130,129 ,0,0,0}, {156,158,157 ,127,129,128 ,0,0,0}, + {157,160,155 ,128,35,126 ,0,0,0}, {152,153,159 ,123,124,130 ,0,0,0}, + {149,145,154 ,120,116,125 ,0,0,0}, {142,161,143 ,83,131,115 ,0,0,0}, + {162,161,163 ,132,131,133 ,0,0,0}, {161,162,143 ,131,132,115 ,0,0,0}, + {164,165,163 ,134,74,133 ,0,0,0}, {162,163,165 ,132,133,74 ,0,0,0}, + {164,166,167 ,134,135,108 ,0,0,0}, {167,165,164 ,108,74,134 ,0,0,0}, + {168,166,169 ,136,135,137 ,0,0,0}, {166,168,167 ,135,136,108 ,0,0,0}, + {170,171,169 ,138,139,137 ,0,0,0}, {168,169,171 ,136,137,139 ,0,0,0}, + {170,172,173 ,138,79,80 ,0,0,0}, {173,171,170 ,80,139,138 ,0,0,0}, + {174,172,175 ,140,79,140 ,0,0,0}, {172,174,173 ,79,140,80 ,0,0,0}, + {176,177,178 ,141,142,143 ,0,0,0}, {179,180,181 ,144,145,146 ,0,0,0}, + {182,176,178 ,147,141,143 ,0,0,0}, {181,180,182 ,146,145,147 ,0,0,0}, + {180,179,183 ,145,144,148 ,0,0,0}, {178,181,182 ,143,146,147 ,0,0,0}, + {184,185,186 ,149,150,151 ,0,0,0}, {185,187,186 ,150,152,151 ,0,0,0}, + {183,188,184 ,148,153,149 ,0,0,0}, {185,184,188 ,150,149,153 ,0,0,0}, + {189,190,191 ,126,154,155 ,0,0,0}, {192,193,187 ,156,157,152 ,0,0,0}, + {190,193,192 ,154,157,156 ,0,0,0}, {190,192,191 ,154,156,155 ,0,0,0}, + {191,194,189 ,155,35,126 ,0,0,0}, {186,187,193 ,151,152,157 ,0,0,0}, + {183,179,188 ,148,144,153 ,0,0,0}, {176,195,177 ,141,158,142 ,0,0,0}, + {196,195,197 ,159,158,160 ,0,0,0}, {195,196,177 ,158,159,142 ,0,0,0}, + {198,199,197 ,161,162,160 ,0,0,0}, {196,197,199 ,159,160,162 ,0,0,0}, + {198,200,201 ,161,163,164 ,0,0,0}, {201,199,198 ,164,162,161 ,0,0,0}, + {202,200,203 ,165,163,166 ,0,0,0}, {200,202,201 ,163,165,164 ,0,0,0}, + {204,205,203 ,167,168,166 ,0,0,0}, {202,203,205 ,165,166,168 ,0,0,0}, + {204,206,207 ,167,169,170 ,0,0,0}, {207,205,204 ,170,168,167 ,0,0,0}, + {208,206,209 ,140,169,140 ,0,0,0}, {206,208,207 ,169,140,170 ,0,0,0}, + {210,211,212 ,171,172,173 ,0,0,0}, {213,214,215 ,174,175,176 ,0,0,0}, + {216,210,212 ,177,171,173 ,0,0,0}, {215,214,216 ,176,175,177 ,0,0,0}, + {214,213,217 ,175,174,178 ,0,0,0}, {212,215,216 ,173,176,177 ,0,0,0}, + {218,219,220 ,179,180,181 ,0,0,0}, {219,221,220 ,180,182,181 ,0,0,0}, + {217,222,218 ,178,183,179 ,0,0,0}, {219,218,222 ,180,179,183 ,0,0,0}, + {223,224,225 ,35,184,185 ,0,0,0}, {226,227,221 ,186,187,182 ,0,0,0}, + {224,227,226 ,184,187,186 ,0,0,0}, {224,226,225 ,184,186,185 ,0,0,0}, + {225,228,223 ,185,40,35 ,0,0,0}, {220,221,227 ,181,182,187 ,0,0,0}, + {217,213,222 ,178,174,183 ,0,0,0}, {210,229,211 ,171,188,172 ,0,0,0}, + {230,229,231 ,189,188,104 ,0,0,0}, {229,230,211 ,188,189,172 ,0,0,0}, + {232,233,231 ,190,45,104 ,0,0,0}, {230,231,233 ,189,104,45 ,0,0,0}, + {232,234,235 ,190,191,192 ,0,0,0}, {235,233,232 ,192,45,190 ,0,0,0}, + {236,234,237 ,193,191,194 ,0,0,0}, {234,236,235 ,191,193,192 ,0,0,0}, + {238,239,237 ,111,195,194 ,0,0,0}, {236,237,239 ,193,194,195 ,0,0,0}, + {238,240,241 ,111,52,53 ,0,0,0}, {241,239,238 ,53,195,111 ,0,0,0}, + {242,240,243 ,54,52,54 ,0,0,0}, {240,242,241 ,52,54,53 ,0,0,0}, + {244,245,246 ,196,197,197 ,0,0,0}, {247,248,249 ,198,196,198 ,0,0,0}, + {248,244,246 ,196,196,197 ,0,0,0}, {247,249,250 ,198,198,199 ,0,0,0}, + {251,252,253 ,200,82,200 ,0,0,0}, {250,249,254 ,199,198,199 ,0,0,0}, + {254,253,250 ,199,200,199 ,0,0,0}, {253,254,251 ,200,199,200 ,0,0,0}, + {252,251,255 ,82,200,201 ,0,0,0}, {248,247,244 ,196,198,196 ,0,0,0}, + {256,246,245 ,202,197,197 ,0,0,0}, {257,256,258 ,203,202,202 ,0,0,0}, + {245,258,256 ,197,202,202 ,0,0,0}, {259,260,257 ,203,204,203 ,0,0,0}, + {257,258,259 ,203,202,203 ,0,0,0}, {260,261,262 ,204,204,205 ,0,0,0}, + {261,260,259 ,204,204,203 ,0,0,0}, {261,263,262 ,204,205,205 ,0,0,0}, + {264,265,266 ,206,207,208 ,0,0,0}, {267,264,268 ,209,206,210 ,0,0,0}, + {264,267,265 ,206,209,207 ,0,0,0}, {269,270,268 ,211,212,210 ,0,0,0}, + {267,268,270 ,209,210,212 ,0,0,0}, {269,271,272 ,211,213,214 ,0,0,0}, + {272,270,269 ,214,212,211 ,0,0,0}, {273,271,274 ,215,213,216 ,0,0,0}, + {271,273,272 ,213,215,214 ,0,0,0}, {275,276,274 ,217,218,216 ,0,0,0}, + {273,274,276 ,215,216,218 ,0,0,0}, {275,277,278 ,217,219,220 ,0,0,0}, + {278,276,275 ,220,218,217 ,0,0,0}, {279,278,277 ,221,220,219 ,0,0,0}, + {279,280,278 ,221,221,220 ,0,0,0}, {264,266,281 ,206,208,222 ,0,0,0}, + {282,283,266 ,223,224,208 ,0,0,0}, {281,266,283 ,222,208,224 ,0,0,0}, + {282,284,285 ,223,225,226 ,0,0,0}, {285,283,282 ,226,224,223 ,0,0,0}, + {286,284,287 ,227,225,228 ,0,0,0}, {284,286,285 ,225,227,226 ,0,0,0}, + {288,289,287 ,229,230,228 ,0,0,0}, {286,287,289 ,227,228,230 ,0,0,0}, + {288,290,291 ,229,231,232 ,0,0,0}, {291,289,288 ,232,230,229 ,0,0,0}, + {292,290,293 ,233,231,234 ,0,0,0}, {290,292,291 ,231,233,232 ,0,0,0}, + {293,294,292 ,234,235,233 ,0,0,0}, {292,294,295 ,233,235,235 ,0,0,0}, + {296,297,298 ,236,237,238 ,0,0,0}, {299,300,296 ,239,240,236 ,0,0,0}, + {296,298,299 ,236,238,239 ,0,0,0}, {300,301,302 ,240,241,242 ,0,0,0}, + {301,300,299 ,241,240,239 ,0,0,0}, {303,302,304 ,243,242,244 ,0,0,0}, + {301,304,302 ,241,244,242 ,0,0,0}, {305,306,303 ,245,246,243 ,0,0,0}, + {303,304,305 ,243,244,245 ,0,0,0}, {307,306,305 ,247,246,245 ,0,0,0}, + {307,308,306 ,247,126,246 ,0,0,0}, {298,297,309 ,238,237,248 ,0,0,0}, + {309,310,311 ,248,249,250 ,0,0,0}, {310,309,297 ,249,248,237 ,0,0,0}, + {312,311,313 ,251,250,252 ,0,0,0}, {310,313,311 ,249,252,250 ,0,0,0}, + {314,315,312 ,253,254,251 ,0,0,0}, {312,313,314 ,251,252,253 ,0,0,0}, + {315,316,317 ,254,255,256 ,0,0,0}, {316,315,314 ,255,254,253 ,0,0,0}, + {316,318,317 ,255,257,256 ,0,0,0}, {317,318,319 ,256,257,257 ,0,0,0}, + {320,321,322 ,258,259,260 ,0,0,0}, {323,320,324 ,261,258,262 ,0,0,0}, + {320,323,321 ,258,261,259 ,0,0,0}, {325,326,324 ,263,264,262 ,0,0,0}, + {323,324,326 ,261,262,264 ,0,0,0}, {325,327,328 ,263,265,266 ,0,0,0}, + {328,326,325 ,266,264,263 ,0,0,0}, {329,327,330 ,267,265,268 ,0,0,0}, + {327,329,328 ,265,267,266 ,0,0,0}, {331,332,330 ,269,270,268 ,0,0,0}, + {329,330,332 ,267,268,270 ,0,0,0}, {331,333,334 ,269,271,272 ,0,0,0}, + {334,332,331 ,272,270,269 ,0,0,0}, {335,334,333 ,273,272,271 ,0,0,0}, + {335,336,334 ,273,273,272 ,0,0,0}, {320,322,337 ,258,260,274 ,0,0,0}, + {338,339,322 ,275,276,260 ,0,0,0}, {337,322,339 ,274,260,276 ,0,0,0}, + {338,340,341 ,275,277,278 ,0,0,0}, {341,339,338 ,278,276,275 ,0,0,0}, + {342,340,343 ,279,277,280 ,0,0,0}, {340,342,341 ,277,279,278 ,0,0,0}, + {344,345,343 ,281,282,280 ,0,0,0}, {342,343,345 ,279,280,282 ,0,0,0}, + {344,346,347 ,281,283,284 ,0,0,0}, {347,345,344 ,284,282,281 ,0,0,0}, + {348,346,349 ,285,283,286 ,0,0,0}, {346,348,347 ,283,285,284 ,0,0,0}, + {349,350,348 ,286,257,285 ,0,0,0}, {348,350,351 ,285,257,257 ,0,0,0}, + {352,353,354 ,287,288,288 ,0,0,0}, {355,356,357 ,289,287,289 ,0,0,0}, + {356,352,354 ,287,287,288 ,0,0,0}, {355,357,358 ,289,289,290 ,0,0,0}, + {359,360,361 ,291,82,291 ,0,0,0}, {358,357,362 ,290,289,290 ,0,0,0}, + {362,361,358 ,290,291,290 ,0,0,0}, {361,362,359 ,291,290,291 ,0,0,0}, + {360,359,363 ,82,291,292 ,0,0,0}, {356,355,352 ,287,289,287 ,0,0,0}, + {364,354,353 ,293,288,288 ,0,0,0}, {365,364,366 ,203,293,293 ,0,0,0}, + {353,366,364 ,288,293,293 ,0,0,0}, {367,368,365 ,203,294,203 ,0,0,0}, + {365,366,367 ,203,293,203 ,0,0,0}, {368,369,370 ,294,294,205 ,0,0,0}, + {369,368,367 ,294,294,203 ,0,0,0}, {369,371,370 ,294,205,205 ,0,0,0}, + {372,373,374 ,295,296,295 ,0,0,0}, {375,373,376 ,296,296,297 ,0,0,0}, + {373,375,374 ,296,296,295 ,0,0,0}, {377,378,376 ,298,297,297 ,0,0,0}, + {375,376,378 ,296,297,297 ,0,0,0}, {377,379,380 ,298,299,298 ,0,0,0}, + {380,378,377 ,298,297,298 ,0,0,0}, {379,381,380 ,299,300,298 ,0,0,0}, + {382,372,374 ,301,295,295 ,0,0,0}, {383,384,382 ,302,301,301 ,0,0,0}, + {372,382,384 ,295,301,301 ,0,0,0}, {383,385,386 ,302,303,302 ,0,0,0}, + {386,384,383 ,302,301,302 ,0,0,0}, {387,385,388 ,303,303,304 ,0,0,0}, + {385,387,386 ,303,303,302 ,0,0,0}, {387,388,389 ,303,304,304 ,0,0,0}, + {390,391,392 ,305,306,305 ,0,0,0}, {393,391,394 ,306,306,307 ,0,0,0}, + {391,393,392 ,306,306,305 ,0,0,0}, {395,396,394 ,308,307,307 ,0,0,0}, + {393,394,396 ,306,307,307 ,0,0,0}, {395,397,398 ,308,309,308 ,0,0,0}, + {398,396,395 ,308,307,308 ,0,0,0}, {397,399,398 ,309,310,308 ,0,0,0}, + {400,390,392 ,311,305,305 ,0,0,0}, {401,402,400 ,312,311,311 ,0,0,0}, + {390,400,402 ,305,311,311 ,0,0,0}, {401,403,404 ,312,313,312 ,0,0,0}, + {404,402,401 ,312,311,312 ,0,0,0}, {405,403,406 ,313,313,314 ,0,0,0}, + {403,405,404 ,313,313,312 ,0,0,0}, {405,406,407 ,313,314,314 ,0,0,0}, + {408,399,397 ,315,309,309 ,0,0,0}, {409,410,411 ,316,317,317 ,0,0,0}, + {412,413,414 ,318,318,315 ,0,0,0}, {415,416,417 ,319,319,320 ,0,0,0}, + {418,419,420 ,316,321,321 ,0,0,0}, {421,422,417 ,322,320,320 ,0,0,0}, + {415,417,422 ,319,320,320 ,0,0,0}, {423,422,421 ,323,320,322 ,0,0,0}, + {419,416,420 ,321,319,321 ,0,0,0}, {420,416,415 ,321,319,319 ,0,0,0}, + {418,410,409 ,316,317,316 ,0,0,0}, {418,409,419 ,316,316,321 ,0,0,0}, + {411,413,412 ,317,318,318 ,0,0,0}, {410,413,411 ,317,318,317 ,0,0,0}, + {408,414,399 ,315,315,309 ,0,0,0}, {412,414,408 ,318,315,315 ,0,0,0}, + {424,425,426 ,324,324,324 ,0,0,0}, {424,426,427 ,324,324,324 ,0,0,0}, + {428,429,430 ,325,326,325 ,0,0,0}, {431,432,428 ,327,327,325 ,0,0,0}, + {428,430,431 ,325,325,327 ,0,0,0}, {432,433,434 ,327,328,329 ,0,0,0}, + {433,432,431 ,328,327,327 ,0,0,0}, {435,434,436 ,330,329,331 ,0,0,0}, + {433,436,434 ,328,331,329 ,0,0,0}, {437,438,435 ,332,332,330 ,0,0,0}, + {435,436,437 ,330,331,332 ,0,0,0}, {438,439,440 ,332,333,334 ,0,0,0}, + {439,438,437 ,333,332,332 ,0,0,0}, {441,440,442 ,335,334,335 ,0,0,0}, + {439,442,440 ,333,335,334 ,0,0,0}, {443,444,441 ,336,336,335 ,0,0,0}, + {441,442,443 ,335,335,336 ,0,0,0}, {430,429,445 ,325,326,337 ,0,0,0}, + {446,445,447 ,338,337,339 ,0,0,0}, {429,447,445 ,326,339,337 ,0,0,0}, + {448,449,446 ,340,341,338 ,0,0,0}, {446,447,448 ,338,339,340 ,0,0,0}, + {449,450,451 ,341,342,343 ,0,0,0}, {450,449,448 ,342,341,340 ,0,0,0}, + {452,451,453 ,344,343,345 ,0,0,0}, {450,453,451 ,342,345,343 ,0,0,0}, + {454,455,452 ,346,347,344 ,0,0,0}, {452,453,454 ,344,345,346 ,0,0,0}, + {455,456,457 ,347,348,349 ,0,0,0}, {456,455,454 ,348,347,346 ,0,0,0}, + {456,28,457 ,348,16,349 ,0,0,0}, {457,28,29 ,349,16,350 ,0,0,0}, + {458,381,379 ,351,299,299 ,0,0,0}, {459,460,461 ,352,353,353 ,0,0,0}, + {462,463,464 ,354,354,351 ,0,0,0}, {465,466,467 ,355,355,356 ,0,0,0}, + {468,469,470 ,352,357,357 ,0,0,0}, {471,472,467 ,358,356,356 ,0,0,0}, + {465,467,472 ,355,356,356 ,0,0,0}, {473,472,471 ,359,356,358 ,0,0,0}, + {469,466,470 ,357,355,357 ,0,0,0}, {470,466,465 ,357,355,355 ,0,0,0}, + {468,460,459 ,352,353,352 ,0,0,0}, {468,459,469 ,352,352,357 ,0,0,0}, + {461,463,462 ,353,354,354 ,0,0,0}, {460,463,461 ,353,354,353 ,0,0,0}, + {458,464,381 ,351,351,299 ,0,0,0}, {462,464,458 ,354,351,351 ,0,0,0}, + {474,475,476 ,360,324,360 ,0,0,0}, {475,474,477 ,324,360,324 ,0,0,0}, + {478,479,480 ,361,362,361 ,0,0,0}, {481,482,478 ,363,363,361 ,0,0,0}, + {478,480,481 ,361,361,363 ,0,0,0}, {482,483,484 ,363,364,365 ,0,0,0}, + {483,482,481 ,364,363,363 ,0,0,0}, {485,484,486 ,366,365,367 ,0,0,0}, + {483,486,484 ,364,367,365 ,0,0,0}, {487,488,485 ,368,369,366 ,0,0,0}, + {485,486,487 ,366,367,368 ,0,0,0}, {488,489,490 ,369,370,370 ,0,0,0}, + {489,488,487 ,370,369,368 ,0,0,0}, {491,490,492 ,371,370,371 ,0,0,0}, + {489,492,490 ,370,371,370 ,0,0,0}, {493,494,491 ,372,372,371 ,0,0,0}, + {491,492,493 ,371,371,372 ,0,0,0}, {480,479,495 ,361,362,373 ,0,0,0}, + {496,495,497 ,374,373,375 ,0,0,0}, {479,497,495 ,362,375,373 ,0,0,0}, + {498,499,496 ,376,377,374 ,0,0,0}, {496,497,498 ,374,375,376 ,0,0,0}, + {499,500,501 ,377,378,379 ,0,0,0}, {500,499,498 ,378,377,376 ,0,0,0}, + {502,501,503 ,380,379,381 ,0,0,0}, {500,503,501 ,378,381,379 ,0,0,0}, + {504,505,502 ,382,383,380 ,0,0,0}, {502,503,504 ,380,381,382 ,0,0,0}, + {505,506,507 ,383,384,385 ,0,0,0}, {506,505,504 ,384,383,382 ,0,0,0}, + {506,8,507 ,384,4,385 ,0,0,0}, {507,8,9 ,385,4,386 ,0,0,0}, {363,508,509 ,387,388,388 ,0,0,0}, + {510,511,512 ,389,389,390 ,0,0,0}, {513,514,515 ,390,391,391 ,0,0,0}, + {516,517,518 ,392,393,392 ,0,0,0}, {519,520,521 ,394,394,393 ,0,0,0}, + {522,523,518 ,395,395,392 ,0,0,0}, {516,518,523 ,392,392,395 ,0,0,0}, + {522,524,525 ,395,396,396 ,0,0,0}, {525,523,522 ,396,395,395 ,0,0,0}, + {516,521,517 ,392,393,393 ,0,0,0}, {515,514,508 ,391,391,388 ,0,0,0}, + {521,520,517 ,393,394,393 ,0,0,0}, {519,510,520 ,394,389,394 ,0,0,0}, + {511,513,512 ,389,390,390 ,0,0,0}, {519,511,510 ,394,389,389 ,0,0,0}, + {512,513,515 ,390,390,391 ,0,0,0}, {363,509,360 ,387,388,397 ,0,0,0}, + {508,514,509 ,388,391,388 ,0,0,0}, {526,527,528 ,398,399,400 ,0,0,0}, + {529,528,530 ,401,400,402 ,0,0,0}, {527,530,528 ,399,402,400 ,0,0,0}, + {530,531,532 ,402,403,404 ,0,0,0}, {532,529,530 ,404,401,402 ,0,0,0}, + {533,531,534 ,405,403,406 ,0,0,0}, {531,533,532 ,403,405,404 ,0,0,0}, + {535,536,534 ,407,408,406 ,0,0,0}, {533,534,536 ,405,406,408 ,0,0,0}, + {535,537,538 ,407,409,410 ,0,0,0}, {538,536,535 ,410,408,407 ,0,0,0}, + {539,537,540 ,411,409,412 ,0,0,0}, {537,539,538 ,409,411,410 ,0,0,0}, + {541,539,542 ,413,411,414 ,0,0,0}, {540,542,539 ,412,414,411 ,0,0,0}, + {543,544,541 ,415,416,413 ,0,0,0}, {541,542,543 ,413,414,415 ,0,0,0}, + {545,543,546 ,417,415,418 ,0,0,0}, {543,545,544 ,415,417,416 ,0,0,0}, + {547,548,546 ,419,420,418 ,0,0,0}, {545,546,548 ,417,418,420 ,0,0,0}, + {547,549,550 ,419,421,422 ,0,0,0}, {550,548,547 ,422,420,419 ,0,0,0}, + {551,549,552 ,423,421,424 ,0,0,0}, {549,551,550 ,421,423,422 ,0,0,0}, + {553,554,552 ,425,426,424 ,0,0,0}, {551,552,554 ,423,424,426 ,0,0,0}, + {555,556,554 ,427,427,426 ,0,0,0}, {554,553,555 ,426,425,427 ,0,0,0}, + {527,526,557 ,399,398,428 ,0,0,0}, {557,558,559 ,428,429,430 ,0,0,0}, + {558,557,526 ,429,428,398 ,0,0,0}, {560,561,558 ,431,432,429 ,0,0,0}, + {559,558,561 ,430,429,432 ,0,0,0}, {560,562,563 ,431,433,434 ,0,0,0}, + {563,561,560 ,434,432,431 ,0,0,0}, {564,562,565 ,435,433,436 ,0,0,0}, + {562,564,563 ,433,435,434 ,0,0,0}, {566,567,565 ,437,438,436 ,0,0,0}, + {564,565,567 ,435,436,438 ,0,0,0}, {566,568,569 ,437,439,440 ,0,0,0}, + {569,567,566 ,440,438,437 ,0,0,0}, {569,570,571 ,440,441,442 ,0,0,0}, + {570,569,568 ,441,440,439 ,0,0,0}, {572,571,573 ,443,442,444 ,0,0,0}, + {570,573,571 ,441,444,442 ,0,0,0}, {573,574,575 ,444,445,446 ,0,0,0}, + {575,572,573 ,446,443,444 ,0,0,0}, {576,574,577 ,447,445,448 ,0,0,0}, + {574,576,575 ,445,447,446 ,0,0,0}, {578,579,577 ,449,450,448 ,0,0,0}, + {576,577,579 ,447,448,450 ,0,0,0}, {578,580,581 ,449,451,452 ,0,0,0}, + {581,579,578 ,452,450,449 ,0,0,0}, {582,580,583 ,453,451,454 ,0,0,0}, + {580,582,581 ,451,453,452 ,0,0,0}, {583,584,582 ,454,455,453 ,0,0,0}, + {582,584,585 ,453,455,456 ,0,0,0}, {586,587,588 ,457,458,459 ,0,0,0}, + {586,588,589 ,457,459,460 ,0,0,0}, {590,336,335 ,461,273,273 ,0,0,0}, + {591,592,593 ,462,463,464 ,0,0,0}, {594,595,596 ,465,466,467 ,0,0,0}, + {597,598,599 ,468,469,470 ,0,0,0}, {600,601,602 ,471,472,473 ,0,0,0}, + {603,604,605 ,474,475,476 ,0,0,0}, {606,607,608 ,477,478,479 ,0,0,0}, + {609,610,611 ,480,481,482 ,0,0,0}, {609,612,604 ,480,483,475 ,0,0,0}, + {613,610,614 ,484,481,485 ,0,0,0}, {610,613,611 ,481,484,482 ,0,0,0}, + {615,616,614 ,486,487,485 ,0,0,0}, {613,614,616 ,484,485,487 ,0,0,0}, + {617,618,616 ,488,488,487 ,0,0,0}, {616,615,617 ,487,486,488 ,0,0,0}, + {605,604,612 ,476,475,483 ,0,0,0}, {609,611,612 ,480,482,483 ,0,0,0}, + {606,603,607 ,477,474,478 ,0,0,0}, {603,605,607 ,474,476,478 ,0,0,0}, + {599,606,597 ,470,477,468 ,0,0,0}, {606,608,597 ,477,479,468 ,0,0,0}, + {602,601,598 ,473,472,469 ,0,0,0}, {602,598,597 ,473,469,468 ,0,0,0}, + {600,592,591 ,471,463,462 ,0,0,0}, {600,591,601 ,471,462,472 ,0,0,0}, + {593,595,594 ,464,466,465 ,0,0,0}, {592,595,593 ,463,466,464 ,0,0,0}, + {590,596,619 ,461,467,489 ,0,0,0}, {594,596,590 ,465,467,461 ,0,0,0}, + {336,590,619 ,273,461,489 ,0,0,0}, {620,621,622 ,490,491,492 ,0,0,0}, + {623,624,621 ,493,494,491 ,0,0,0}, {625,626,627 ,495,496,497 ,0,0,0}, + {625,620,622 ,495,490,492 ,0,0,0}, {628,629,630 ,498,499,500 ,0,0,0}, + {627,620,625 ,497,490,495 ,0,0,0}, {626,630,629 ,496,500,499 ,0,0,0}, + {631,628,630 ,501,498,500 ,0,0,0}, {627,626,629 ,497,496,499 ,0,0,0}, + {632,633,634 ,502,503,504 ,0,0,0}, {635,632,634 ,505,502,504 ,0,0,0}, + {636,631,633 ,506,501,503 ,0,0,0}, {633,632,636 ,503,502,506 ,0,0,0}, + {634,637,635 ,504,507,505 ,0,0,0}, {631,636,628 ,501,506,498 ,0,0,0}, + {635,637,638 ,505,507,508 ,0,0,0}, {622,621,624 ,492,491,494 ,0,0,0}, + {639,638,637 ,508,508,507 ,0,0,0}, {623,640,641 ,493,509,510 ,0,0,0}, + {641,624,623 ,510,494,493 ,0,0,0}, {642,640,643 ,511,509,512 ,0,0,0}, + {640,642,641 ,509,511,510 ,0,0,0}, {644,645,643 ,513,514,512 ,0,0,0}, + {642,643,645 ,511,512,514 ,0,0,0}, {644,646,647 ,513,515,516 ,0,0,0}, + {647,645,644 ,516,514,513 ,0,0,0}, {648,646,649 ,517,515,518 ,0,0,0}, + {646,648,647 ,515,517,516 ,0,0,0}, {650,651,649 ,519,520,518 ,0,0,0}, + {648,649,651 ,517,518,520 ,0,0,0}, {650,652,653 ,519,521,522 ,0,0,0}, + {653,651,650 ,522,520,519 ,0,0,0}, {654,652,655 ,523,521,524 ,0,0,0}, + {652,654,653 ,521,523,522 ,0,0,0}, {654,655,656 ,523,524,525 ,0,0,0}, + {656,655,657 ,525,524,525 ,0,0,0}, {658,308,307 ,526,527,247 ,0,0,0}, + {659,660,661 ,528,529,530 ,0,0,0}, {662,663,664 ,531,532,533 ,0,0,0}, + {665,666,667 ,534,535,536 ,0,0,0}, {668,669,670 ,537,538,539 ,0,0,0}, + {671,672,673 ,540,541,542 ,0,0,0}, {674,671,667 ,543,540,536 ,0,0,0}, + {675,673,676 ,544,542,545 ,0,0,0}, {672,676,673 ,541,545,542 ,0,0,0}, + {677,678,675 ,546,546,544 ,0,0,0}, {675,676,677 ,544,545,546 ,0,0,0}, + {666,674,667 ,535,543,536 ,0,0,0}, {674,672,671 ,543,541,540 ,0,0,0}, + {670,669,665 ,539,538,534 ,0,0,0}, {669,666,665 ,538,535,534 ,0,0,0}, + {659,661,668 ,528,530,537 ,0,0,0}, {659,668,670 ,528,537,539 ,0,0,0}, + {660,663,662 ,529,532,531 ,0,0,0}, {660,662,661 ,529,531,530 ,0,0,0}, + {664,679,658 ,533,547,526 ,0,0,0}, {663,679,664 ,532,547,533 ,0,0,0}, + {308,658,679 ,527,526,547 ,0,0,0}, {680,681,682 ,548,549,550 ,0,0,0}, + {683,684,681 ,551,552,549 ,0,0,0}, {685,686,687 ,553,554,555 ,0,0,0}, + {685,680,682 ,553,548,550 ,0,0,0}, {688,689,690 ,556,557,558 ,0,0,0}, + {687,680,685 ,555,548,553 ,0,0,0}, {686,690,689 ,554,558,557 ,0,0,0}, + {691,688,690 ,559,556,558 ,0,0,0}, {687,686,689 ,555,554,557 ,0,0,0}, + {692,693,694 ,560,561,562 ,0,0,0}, {695,692,694 ,563,560,562 ,0,0,0}, + {696,691,693 ,564,559,561 ,0,0,0}, {693,692,696 ,561,560,564 ,0,0,0}, + {694,697,695 ,562,565,563 ,0,0,0}, {691,696,688 ,559,564,556 ,0,0,0}, + {695,697,698 ,563,565,508 ,0,0,0}, {682,681,684 ,550,549,552 ,0,0,0}, + {699,698,697 ,508,508,565 ,0,0,0}, {683,700,701 ,551,566,567 ,0,0,0}, + {701,684,683 ,567,552,551 ,0,0,0}, {702,700,703 ,568,566,569 ,0,0,0}, + {700,702,701 ,566,568,567 ,0,0,0}, {704,705,703 ,570,571,569 ,0,0,0}, + {702,703,705 ,568,569,571 ,0,0,0}, {704,706,707 ,570,572,573 ,0,0,0}, + {707,705,704 ,573,571,570 ,0,0,0}, {708,706,709 ,574,572,575 ,0,0,0}, + {706,708,707 ,572,574,573 ,0,0,0}, {710,711,709 ,576,577,575 ,0,0,0}, + {708,709,711 ,574,575,577 ,0,0,0}, {710,712,713 ,576,578,579 ,0,0,0}, + {713,711,710 ,579,577,576 ,0,0,0}, {714,712,715 ,580,578,581 ,0,0,0}, + {712,714,713 ,578,580,579 ,0,0,0}, {714,715,716 ,580,581,525 ,0,0,0}, + {716,715,717 ,525,581,525 ,0,0,0}, {718,280,279 ,582,221,221 ,0,0,0}, + {719,720,721 ,583,584,585 ,0,0,0}, {722,723,724 ,586,587,588 ,0,0,0}, + {725,726,727 ,589,590,591 ,0,0,0}, {728,729,730 ,592,593,594 ,0,0,0}, + {731,732,733 ,595,596,597 ,0,0,0}, {734,735,736 ,598,599,600 ,0,0,0}, + {737,738,739 ,601,602,603 ,0,0,0}, {737,740,732 ,601,604,596 ,0,0,0}, + {741,738,742 ,605,602,606 ,0,0,0}, {738,741,739 ,602,605,603 ,0,0,0}, + {743,744,742 ,607,608,606 ,0,0,0}, {741,742,744 ,605,606,608 ,0,0,0}, + {745,746,744 ,546,546,608 ,0,0,0}, {744,743,745 ,608,607,546 ,0,0,0}, + {733,732,740 ,597,596,604 ,0,0,0}, {737,739,740 ,601,603,604 ,0,0,0}, + {734,731,735 ,598,595,599 ,0,0,0}, {731,733,735 ,595,597,599 ,0,0,0}, + {727,734,725 ,591,598,589 ,0,0,0}, {734,736,725 ,598,600,589 ,0,0,0}, + {730,729,726 ,594,593,590 ,0,0,0}, {730,726,725 ,594,590,589 ,0,0,0}, + {728,720,719 ,592,584,583 ,0,0,0}, {728,719,729 ,592,583,593 ,0,0,0}, + {721,723,722 ,585,587,586 ,0,0,0}, {720,723,721 ,584,587,585 ,0,0,0}, + {718,724,747 ,582,588,609 ,0,0,0}, {722,724,718 ,586,588,582 ,0,0,0}, + {280,718,747 ,221,582,609 ,0,0,0}, {748,749,750 ,610,611,610 ,0,0,0}, + {749,748,751 ,611,610,611 ,0,0,0}, {752,753,754 ,612,613,614 ,0,0,0}, + {755,754,756 ,615,614,616 ,0,0,0}, {753,756,754 ,613,616,614 ,0,0,0}, + {756,757,758 ,616,617,618 ,0,0,0}, {758,755,756 ,618,615,616 ,0,0,0}, + {759,757,760 ,619,617,620 ,0,0,0}, {757,759,758 ,617,619,618 ,0,0,0}, + {761,762,760 ,621,622,620 ,0,0,0}, {759,760,762 ,619,620,622 ,0,0,0}, + {761,763,764 ,621,623,624 ,0,0,0}, {764,762,761 ,624,622,621 ,0,0,0}, + {765,763,766 ,625,623,626 ,0,0,0}, {763,765,764 ,623,625,624 ,0,0,0}, + {767,765,768 ,627,625,628 ,0,0,0}, {766,768,765 ,626,628,625 ,0,0,0}, + {769,770,767 ,629,630,627 ,0,0,0}, {767,768,769 ,627,628,629 ,0,0,0}, + {771,769,772 ,631,629,632 ,0,0,0}, {769,771,770 ,629,631,630 ,0,0,0}, + {773,774,772 ,633,634,632 ,0,0,0}, {771,772,774 ,631,632,634 ,0,0,0}, + {773,775,776 ,633,635,636 ,0,0,0}, {776,774,773 ,636,634,633 ,0,0,0}, + {777,775,778 ,637,635,638 ,0,0,0}, {775,777,776 ,635,637,636 ,0,0,0}, + {779,780,778 ,639,640,638 ,0,0,0}, {777,778,780 ,637,638,640 ,0,0,0}, + {781,782,780 ,641,641,640 ,0,0,0}, {780,779,781 ,640,639,641 ,0,0,0}, + {753,752,783 ,613,612,642 ,0,0,0}, {783,784,785 ,642,643,644 ,0,0,0}, + {784,783,752 ,643,642,612 ,0,0,0}, {786,787,784 ,645,646,643 ,0,0,0}, + {785,784,787 ,644,643,646 ,0,0,0}, {786,788,789 ,645,647,648 ,0,0,0}, + {789,787,786 ,648,646,645 ,0,0,0}, {790,788,791 ,649,647,650 ,0,0,0}, + {788,790,789 ,647,649,648 ,0,0,0}, {792,793,791 ,651,652,650 ,0,0,0}, + {790,791,793 ,649,650,652 ,0,0,0}, {792,794,795 ,651,653,654 ,0,0,0}, + {795,793,792 ,654,652,651 ,0,0,0}, {795,796,797 ,654,655,656 ,0,0,0}, + {796,795,794 ,655,654,653 ,0,0,0}, {798,797,799 ,657,656,658 ,0,0,0}, + {796,799,797 ,655,658,656 ,0,0,0}, {799,800,801 ,658,659,660 ,0,0,0}, + {801,798,799 ,660,657,658 ,0,0,0}, {802,800,803 ,661,659,662 ,0,0,0}, + {800,802,801 ,659,661,660 ,0,0,0}, {804,805,803 ,663,664,662 ,0,0,0}, + {802,803,805 ,661,662,664 ,0,0,0}, {804,806,807 ,663,665,666 ,0,0,0}, + {807,805,804 ,666,664,663 ,0,0,0}, {808,806,809 ,667,665,668 ,0,0,0}, + {806,808,807 ,665,667,666 ,0,0,0}, {809,810,808 ,668,669,667 ,0,0,0}, + {808,810,811 ,667,669,670 ,0,0,0}, {255,812,813 ,671,672,672 ,0,0,0}, + {814,815,816 ,673,674,675 ,0,0,0}, {817,818,819 ,675,676,676 ,0,0,0}, + {820,821,822 ,677,678,677 ,0,0,0}, {823,824,825 ,679,679,678 ,0,0,0}, + {826,827,822 ,680,680,677 ,0,0,0}, {820,822,827 ,677,677,680 ,0,0,0}, + {826,828,829 ,680,396,396 ,0,0,0}, {829,827,826 ,396,680,680 ,0,0,0}, + {820,825,821 ,677,678,678 ,0,0,0}, {819,818,812 ,676,676,672 ,0,0,0}, + {825,824,821 ,678,679,678 ,0,0,0}, {823,814,824 ,679,673,679 ,0,0,0}, + {815,817,816 ,674,675,675 ,0,0,0}, {823,815,814 ,679,674,673 ,0,0,0}, + {816,817,819 ,675,675,676 ,0,0,0}, {255,813,252 ,671,672,681 ,0,0,0}, + {812,818,813 ,672,676,672 ,0,0,0}, {18,19,830 ,21,21,21 ,0,0,0}, + {18,830,831 ,21,21,21 ,0,0,0}, {832,833,834 ,682,683,684 ,0,0,0}, + {835,836,834 ,685,686,684 ,0,0,0}, {832,834,836 ,682,684,686 ,0,0,0}, + {835,837,838 ,685,687,688 ,0,0,0}, {838,836,835 ,688,686,685 ,0,0,0}, + {839,837,840 ,689,687,690 ,0,0,0}, {837,839,838 ,687,689,688 ,0,0,0}, + {841,842,840 ,691,692,690 ,0,0,0}, {839,840,842 ,689,690,692 ,0,0,0}, + {841,843,844 ,691,693,694 ,0,0,0}, {844,842,841 ,694,692,691 ,0,0,0}, + {845,843,846 ,695,693,696 ,0,0,0}, {843,845,844 ,693,695,694 ,0,0,0}, + {847,848,846 ,697,698,696 ,0,0,0}, {845,846,848 ,695,696,698 ,0,0,0}, + {847,849,850 ,697,699,700 ,0,0,0}, {850,848,847 ,700,698,697 ,0,0,0}, + {851,849,852 ,701,699,702 ,0,0,0}, {849,851,850 ,699,701,700 ,0,0,0}, + {853,854,852 ,641,703,702 ,0,0,0}, {851,852,854 ,701,702,703 ,0,0,0}, + {855,854,853 ,641,703,641 ,0,0,0}, {856,833,832 ,704,683,682 ,0,0,0}, + {857,856,858 ,705,704,706 ,0,0,0}, {856,857,833 ,704,705,683 ,0,0,0}, + {859,860,858 ,707,708,706 ,0,0,0}, {857,858,860 ,705,706,708 ,0,0,0}, + {859,861,862 ,707,709,710 ,0,0,0}, {862,860,859 ,710,708,707 ,0,0,0}, + {863,861,864 ,711,709,712 ,0,0,0}, {861,863,862 ,709,711,710 ,0,0,0}, + {865,866,864 ,713,714,712 ,0,0,0}, {863,864,866 ,711,712,714 ,0,0,0}, + {865,867,868 ,713,715,716 ,0,0,0}, {868,866,865 ,716,714,713 ,0,0,0}, + {869,867,870 ,717,715,718 ,0,0,0}, {867,869,868 ,715,717,716 ,0,0,0}, + {871,872,870 ,719,720,718 ,0,0,0}, {869,870,872 ,717,718,720 ,0,0,0}, + {871,873,874 ,719,721,722 ,0,0,0}, {874,872,871 ,722,720,719 ,0,0,0}, + {875,873,876 ,723,721,456 ,0,0,0}, {873,875,874 ,721,723,722 ,0,0,0}, + {875,876,877 ,723,456,724 ,0,0,0}, {38,39,878 ,21,725,725 ,0,0,0}, + {38,878,879 ,21,725,21 ,0,0,0}, {312,41,311 ,726,726,726 ,0,0,0}, + {92,836,880 ,727,727,726 ,0,0,0}, {672,674,881 ,726,726,726 ,0,0,0}, + {856,832,92 ,727,727,727 ,0,0,0}, {89,856,92 ,726,727,727 ,0,0,0}, + {56,882,883 ,726,726,726 ,0,0,0}, {254,458,251 ,726,726,726 ,0,0,0}, + {858,89,90 ,726,726,726 ,0,0,0}, {861,85,83 ,727,726,726 ,0,0,0}, + {884,880,838 ,726,726,726 ,0,0,0}, {885,886,887 ,726,726,726 ,0,0,0}, + {774,888,889 ,727,727,727 ,0,0,0}, {545,890,891 ,726,726,727 ,0,0,0}, + {884,839,892 ,726,726,726 ,0,0,0}, {893,765,894 ,726,726,726 ,0,0,0}, + {764,893,895 ,727,726,726 ,0,0,0}, {842,896,892 ,727,726,726 ,0,0,0}, + {83,86,864 ,726,727,726 ,0,0,0}, {897,194,759 ,726,727,726 ,0,0,0}, + {803,800,196 ,726,726,726 ,0,0,0}, {898,896,844 ,727,726,726 ,0,0,0}, + {77,865,86 ,727,726,727 ,0,0,0}, {899,848,900 ,727,727,727 ,0,0,0}, + {899,898,845 ,727,727,727 ,0,0,0}, {901,900,851 ,726,727,726 ,0,0,0}, + {850,900,848 ,726,727,727 ,0,0,0}, {902,855,903 ,727,726,726 ,0,0,0}, + {902,901,854 ,727,726,726 ,0,0,0}, {903,904,905 ,726,726,726 ,0,0,0}, + {906,907,106 ,726,726,727 ,0,0,0}, {870,79,871 ,726,727,726 ,0,0,0}, + {908,909,906 ,727,727,726 ,0,0,0}, {910,904,911 ,727,726,726 ,0,0,0}, + {99,100,912 ,727,726,726 ,0,0,0}, {518,407,522 ,726,726,726 ,0,0,0}, + {913,914,524 ,727,726,726 ,0,0,0}, {907,915,916 ,726,726,727 ,0,0,0}, + {510,391,390 ,726,726,727 ,0,0,0}, {917,598,918 ,726,726,728 ,0,0,0}, + {508,363,397 ,727,726,727 ,0,0,0}, {918,601,591 ,728,726,726 ,0,0,0}, + {128,342,109 ,728,726,726 ,0,0,0}, {131,339,341 ,726,728,726 ,0,0,0}, + {348,113,110 ,726,726,726 ,0,0,0}, {919,920,604 ,726,726,726 ,0,0,0}, + {113,351,111 ,726,726,726 ,0,0,0}, {359,362,412 ,726,726,727 ,0,0,0}, + {921,124,119 ,726,726,726 ,0,0,0}, {126,123,922 ,726,726,726 ,0,0,0}, + {923,924,589 ,727,726,726 ,0,0,0}, {652,441,444 ,726,726,726 ,0,0,0}, + {925,584,162 ,726,726,726 ,0,0,0}, {926,927,928 ,727,727,726 ,0,0,0}, + {144,583,580 ,726,727,726 ,0,0,0}, {929,930,556 ,727,726,727 ,0,0,0}, + {931,550,932 ,726,726,727 ,0,0,0}, {154,573,151 ,727,726,726 ,0,0,0}, + {933,533,536 ,727,726,726 ,0,0,0}, {526,934,935 ,727,726,726 ,0,0,0}, + {160,157,562 ,727,726,726 ,0,0,0}, {160,560,558 ,727,726,727 ,0,0,0}, + {158,565,157 ,726,727,726 ,0,0,0}, {566,158,153 ,727,726,726 ,0,0,0}, + {935,558,526 ,726,727,727 ,0,0,0}, {936,934,528 ,726,726,726 ,0,0,0}, + {151,570,568 ,726,727,726 ,0,0,0}, {529,937,936 ,727,726,726 ,0,0,0}, + {933,937,532 ,727,726,727 ,0,0,0}, {145,574,154 ,727,726,727 ,0,0,0}, + {538,938,939 ,726,727,727 ,0,0,0}, {939,933,536 ,727,727,726 ,0,0,0}, + {891,940,541 ,727,726,727 ,0,0,0}, {539,940,938 ,726,726,727 ,0,0,0}, + {941,556,930 ,727,727,726 ,0,0,0}, {551,942,932 ,726,726,727 ,0,0,0}, + {554,556,942 ,726,727,726 ,0,0,0}, {942,556,941 ,726,727,727 ,0,0,0}, + {548,931,890 ,726,726,726 ,0,0,0}, {551,554,942 ,726,726,726 ,0,0,0}, + {174,930,929 ,727,726,727 ,0,0,0}, {927,943,168 ,727,726,726 ,0,0,0}, + {174,929,944 ,727,727,726 ,0,0,0}, {168,171,927 ,726,727,727 ,0,0,0}, + {943,167,168 ,726,727,726 ,0,0,0}, {926,928,945 ,727,726,726 ,0,0,0}, + {946,926,945 ,726,727,726 ,0,0,0}, {947,948,589 ,726,726,726 ,0,0,0}, + {589,946,945 ,726,726,726 ,0,0,0}, {948,370,946 ,726,726,726 ,0,0,0}, + {589,879,949 ,726,727,726 ,0,0,0}, {650,440,441 ,726,726,726 ,0,0,0}, + {950,588,951 ,726,726,726 ,0,0,0}, {655,444,952 ,726,726,726 ,0,0,0}, + {593,953,591 ,726,726,726 ,0,0,0}, {953,593,954 ,726,726,726 ,0,0,0}, + {327,139,330 ,726,726,726 ,0,0,0}, {955,333,956 ,726,726,726 ,0,0,0}, + {956,331,140 ,726,726,726 ,0,0,0}, {957,335,955 ,726,726,726 ,0,0,0}, + {335,957,590 ,726,726,726 ,0,0,0}, {333,331,956 ,726,726,726 ,0,0,0}, + {594,590,957 ,726,726,726 ,0,0,0}, {333,955,335 ,726,726,726 ,0,0,0}, + {140,331,330 ,726,726,726 ,0,0,0}, {594,957,954 ,726,726,726 ,0,0,0}, + {137,139,325 ,726,726,726 ,0,0,0}, {919,606,958 ,726,729,726 ,0,0,0}, + {324,320,134 ,726,726,726 ,0,0,0}, {345,110,109 ,726,726,726 ,0,0,0}, + {919,603,606 ,726,726,729 ,0,0,0}, {111,959,120 ,726,728,726 ,0,0,0}, + {920,960,609 ,726,726,726 ,0,0,0}, {921,961,124 ,726,726,726 ,0,0,0}, + {959,921,117 ,728,726,726 ,0,0,0}, {354,364,416 ,727,727,727 ,0,0,0}, + {416,419,354 ,727,727,727 ,0,0,0}, {356,354,419 ,726,727,727 ,0,0,0}, + {962,664,658 ,726,726,726 ,0,0,0}, {419,409,356 ,727,726,726 ,0,0,0}, + {515,508,395 ,726,727,726 ,0,0,0}, {408,359,412 ,727,726,727 ,0,0,0}, + {409,411,357 ,726,726,727 ,0,0,0}, {421,365,368 ,726,726,726 ,0,0,0}, + {614,610,963 ,726,726,726 ,0,0,0}, {363,359,408 ,726,726,727 ,0,0,0}, + {435,646,644 ,726,726,726 ,0,0,0}, {964,965,617 ,726,726,726 ,0,0,0}, + {963,610,960 ,726,726,726 ,0,0,0}, {411,362,357 ,726,726,727 ,0,0,0}, + {357,356,409 ,727,726,726 ,0,0,0}, {434,435,644 ,726,726,726 ,0,0,0}, + {615,964,617 ,726,726,726 ,0,0,0}, {961,966,967 ,726,726,726 ,0,0,0}, + {123,124,922 ,726,726,726 ,0,0,0}, {968,36,657 ,726,726,726 ,0,0,0}, + {966,950,951 ,726,726,726 ,0,0,0}, {966,951,967 ,726,726,726 ,0,0,0}, + {646,438,649 ,726,726,726 ,0,0,0}, {417,416,364 ,726,727,727 ,0,0,0}, + {628,453,629 ,726,728,728 ,0,0,0}, {629,450,627 ,728,728,726 ,0,0,0}, + {515,394,512 ,726,726,726 ,0,0,0}, {429,621,447 ,726,726,728 ,0,0,0}, + {512,394,391 ,726,726,726 ,0,0,0}, {510,512,391 ,726,726,726 ,0,0,0}, + {402,517,520 ,727,726,726 ,0,0,0}, {390,520,510 ,727,726,726 ,0,0,0}, + {494,969,715 ,726,726,726 ,0,0,0}, {520,390,402 ,726,727,727 ,0,0,0}, + {970,971,16 ,726,726,726 ,0,0,0}, {972,973,974 ,726,726,726 ,0,0,0}, + {975,974,26 ,726,726,726 ,0,0,0}, {976,676,977 ,726,726,726 ,0,0,0}, + {973,972,978 ,726,726,726 ,0,0,0}, {305,72,307 ,726,726,726 ,0,0,0}, + {51,882,56 ,726,726,726 ,0,0,0}, {979,980,662 ,726,726,726 ,0,0,0}, + {962,658,72 ,726,726,726 ,0,0,0}, {662,664,979 ,726,726,726 ,0,0,0}, + {962,979,664 ,726,726,726 ,0,0,0}, {981,661,980 ,726,726,726 ,0,0,0}, + {661,662,980 ,726,726,726 ,0,0,0}, {981,982,668 ,726,726,726 ,0,0,0}, + {658,307,72 ,726,726,726 ,0,0,0}, {71,304,69 ,726,726,726 ,0,0,0}, + {982,983,669 ,726,728,726 ,0,0,0}, {63,309,60 ,726,726,728 ,0,0,0}, + {299,66,301 ,726,726,726 ,0,0,0}, {45,319,43 ,726,726,726 ,0,0,0}, + {42,315,317 ,726,726,726 ,0,0,0}, {729,984,985 ,726,726,726 ,0,0,0}, + {882,49,986 ,726,726,728 ,0,0,0}, {986,52,43 ,728,726,726 ,0,0,0}, + {881,977,672 ,726,726,726 ,0,0,0}, {12,987,14 ,726,726,726 ,0,0,0}, + {677,988,989 ,726,726,726 ,0,0,0}, {990,991,992 ,727,727,726 ,0,0,0}, + {485,706,704 ,726,726,726 ,0,0,0}, {425,993,11 ,726,726,726 ,0,0,0}, + {715,969,717 ,726,726,726 ,0,0,0}, {16,971,994 ,726,726,726 ,0,0,0}, + {709,490,710 ,726,726,726 ,0,0,0}, {262,995,996 ,726,726,727 ,0,0,0}, + {246,459,248 ,727,727,726 ,0,0,0}, {256,469,246 ,727,727,727 ,0,0,0}, + {255,251,379 ,726,726,727 ,0,0,0}, {248,459,461 ,726,727,726 ,0,0,0}, + {373,819,376 ,726,726,727 ,0,0,0}, {681,479,683 ,726,726,726 ,0,0,0}, + {814,372,384 ,726,726,727 ,0,0,0}, {208,997,998 ,727,726,726 ,0,0,0}, + {999,748,1000 ,726,726,726 ,0,0,0}, {387,822,821 ,726,726,726 ,0,0,0}, + {389,1001,826 ,726,726,726 ,0,0,0}, {885,887,1002 ,726,726,728 ,0,0,0}, + {1003,1004,751 ,726,726,726 ,0,0,0}, {886,1005,887 ,726,726,726 ,0,0,0}, + {742,738,1006 ,726,728,726 ,0,0,0}, {228,1007,1008 ,726,726,726 ,0,0,0}, + {286,213,285 ,726,726,726 ,0,0,0}, {295,1007,225 ,726,726,726 ,0,0,0}, + {1009,1008,1005 ,726,726,726 ,0,0,0}, {275,236,277 ,726,726,726 ,0,0,0}, + {281,283,215 ,726,726,726 ,0,0,0}, {719,721,984 ,726,726,726 ,0,0,0}, + {722,242,721 ,726,726,726 ,0,0,0}, {1010,726,985 ,726,728,726 ,0,0,0}, + {729,985,726 ,726,726,728 ,0,0,0}, {727,726,1010 ,726,728,726 ,0,0,0}, + {984,729,719 ,726,726,726 ,0,0,0}, {984,721,242 ,726,726,726 ,0,0,0}, + {1010,1011,727 ,726,726,726 ,0,0,0}, {1012,731,1011 ,726,726,726 ,0,0,0}, + {1011,734,727 ,726,726,726 ,0,0,0}, {1012,1013,732 ,726,728,726 ,0,0,0}, + {722,718,241 ,726,726,726 ,0,0,0}, {269,230,271 ,726,728,726 ,0,0,0}, + {279,277,239 ,726,726,726 ,0,0,0}, {212,264,281 ,726,726,726 ,0,0,0}, + {230,268,211 ,728,726,726 ,0,0,0}, {286,222,213 ,726,726,726 ,0,0,0}, + {291,221,219 ,726,726,726 ,0,0,0}, {221,295,226 ,726,726,726 ,0,0,0}, + {1014,1006,738 ,726,726,728 ,0,0,0}, {289,219,222 ,726,726,726 ,0,0,0}, + {1015,743,1006 ,726,726,726 ,0,0,0}, {886,1016,1005 ,726,726,726 ,0,0,0}, + {1017,1018,1019 ,726,726,726 ,0,0,0}, {6,4,698 ,726,726,726 ,0,0,0}, + {8,695,1 ,726,726,726 ,0,0,0}, {799,178,177 ,726,726,727 ,0,0,0}, + {1020,782,1021 ,727,726,726 ,0,0,0}, {386,824,384 ,727,726,727 ,0,0,0}, + {1022,1002,751 ,726,728,726 ,0,0,0}, {1002,1022,885 ,728,726,726 ,0,0,0}, + {751,6,1022 ,726,726,726 ,0,0,0}, {780,1023,777 ,726,726,726 ,0,0,0}, + {791,188,179 ,726,727,727 ,0,0,0}, {759,194,758 ,726,727,726 ,0,0,0}, + {770,1024,894 ,726,727,726 ,0,0,0}, {755,758,191 ,726,726,726 ,0,0,0}, + {897,762,895 ,726,726,726 ,0,0,0}, {191,192,754 ,726,726,726 ,0,0,0}, + {784,187,185 ,726,726,726 ,0,0,0}, {185,786,784 ,726,726,726 ,0,0,0}, + {770,894,767 ,726,726,726 ,0,0,0}, {188,788,185 ,727,727,726 ,0,0,0}, + {1024,771,889 ,727,726,727 ,0,0,0}, {179,181,792 ,727,727,726 ,0,0,0}, + {888,776,1023 ,727,726,726 ,0,0,0}, {796,794,178 ,726,726,726 ,0,0,0}, + {1025,1026,1021 ,726,726,726 ,0,0,0}, {201,804,199 ,727,727,726 ,0,0,0}, + {1027,1028,1029 ,726,726,727 ,0,0,0}, {1030,1025,1028 ,727,726,726 ,0,0,0}, + {1031,1029,1032 ,726,727,727 ,0,0,0}, {1032,1029,1028 ,727,727,726 ,0,0,0}, + {814,384,824 ,726,727,726 ,0,0,0}, {998,1029,1031 ,726,727,726 ,0,0,0}, + {205,207,810 ,727,726,727 ,0,0,0}, {386,387,821 ,727,726,726 ,0,0,0}, + {208,998,1033 ,727,726,726 ,0,0,0}, {1032,1034,1031 ,727,727,726 ,0,0,0}, + {997,1029,998 ,726,727,726 ,0,0,0}, {828,1035,999 ,726,726,726 ,0,0,0}, + {1034,999,1000 ,727,726,726 ,0,0,0}, {1034,1000,1031 ,727,726,726 ,0,0,0}, + {386,821,824 ,727,726,726 ,0,0,0}, {372,816,373 ,726,726,726 ,0,0,0}, + {819,373,816 ,726,726,726 ,0,0,0}, {816,372,814 ,726,726,726 ,0,0,0}, + {377,255,379 ,727,726,727 ,0,0,0}, {376,812,377 ,727,727,727 ,0,0,0}, + {251,458,379 ,726,726,727 ,0,0,0}, {500,689,503 ,726,728,726 ,0,0,0}, + {462,458,254 ,726,726,726 ,0,0,0}, {461,462,249 ,726,726,727 ,0,0,0}, + {249,462,254 ,727,726,726 ,0,0,0}, {461,249,248 ,726,727,726 ,0,0,0}, + {991,990,1036 ,727,727,727 ,0,0,0}, {257,466,256 ,726,726,727 ,0,0,0}, + {246,469,459 ,727,727,727 ,0,0,0}, {1037,1038,916 ,727,727,727 ,0,0,0}, + {404,517,402 ,726,726,727 ,0,0,0}, {518,405,407 ,726,726,726 ,0,0,0}, + {404,518,517 ,726,726,726 ,0,0,0}, {407,913,522 ,726,727,726 ,0,0,0}, + {1039,1040,524 ,726,726,726 ,0,0,0}, {916,106,907 ,727,727,726 ,0,0,0}, + {1041,906,909 ,727,726,727 ,0,0,0}, {906,1041,907 ,726,727,726 ,0,0,0}, + {911,909,908 ,726,727,727 ,0,0,0}, {94,1042,876 ,726,726,726 ,0,0,0}, + {589,588,38 ,726,726,726 ,0,0,0}, {1043,657,655 ,726,726,726 ,0,0,0}, + {368,370,1044 ,726,726,726 ,0,0,0}, {589,38,879 ,726,726,727 ,0,0,0}, + {368,1045,421 ,726,726,726 ,0,0,0}, {589,949,923 ,726,726,727 ,0,0,0}, + {946,589,948 ,726,726,726 ,0,0,0}, {924,947,589 ,726,726,726 ,0,0,0}, + {1046,1044,370 ,726,726,726 ,0,0,0}, {948,1046,370 ,726,726,726 ,0,0,0}, + {1044,1045,368 ,726,726,726 ,0,0,0}, {417,365,421 ,726,726,726 ,0,0,0}, + {417,364,365 ,726,727,726 ,0,0,0}, {644,643,434 ,726,726,726 ,0,0,0}, + {643,640,432 ,726,726,726 ,0,0,0}, {640,623,428 ,726,726,726 ,0,0,0}, + {623,621,429 ,726,726,726 ,0,0,0}, {620,447,621 ,726,728,726 ,0,0,0}, + {411,412,362 ,726,727,726 ,0,0,0}, {434,643,432 ,726,726,726 ,0,0,0}, + {408,397,363 ,727,727,726 ,0,0,0}, {428,432,640 ,726,726,726 ,0,0,0}, + {448,620,627 ,726,726,726 ,0,0,0}, {397,395,508 ,727,726,727 ,0,0,0}, + {428,623,429 ,726,726,726 ,0,0,0}, {636,454,628 ,726,726,726 ,0,0,0}, + {395,394,515 ,726,726,726 ,0,0,0}, {447,620,448 ,728,726,726 ,0,0,0}, + {28,456,632 ,726,726,726 ,0,0,0}, {453,450,629 ,728,728,728 ,0,0,0}, + {635,638,21 ,726,726,726 ,0,0,0}, {454,453,628 ,726,728,726 ,0,0,0}, + {22,638,24 ,726,726,726 ,0,0,0}, {456,454,636 ,726,726,726 ,0,0,0}, + {907,1041,1047 ,726,727,726 ,0,0,0}, {404,405,518 ,726,726,726 ,0,0,0}, + {1040,1047,1041 ,726,726,727 ,0,0,0}, {1039,524,914 ,726,726,726 ,0,0,0}, + {913,524,522 ,727,726,726 ,0,0,0}, {1040,1039,1047 ,726,726,726 ,0,0,0}, + {1048,1036,915 ,726,727,726 ,0,0,0}, {990,992,831 ,727,726,727 ,0,0,0}, + {907,1048,915 ,726,726,726 ,0,0,0}, {105,1049,103 ,726,727,727 ,0,0,0}, + {992,426,831 ,726,727,727 ,0,0,0}, {1050,1051,262 ,726,726,726 ,0,0,0}, + {488,709,706 ,726,726,726 ,0,0,0}, {712,710,491 ,726,726,728 ,0,0,0}, + {26,1052,975 ,726,726,726 ,0,0,0}, {28,632,635 ,726,726,726 ,0,0,0}, + {717,994,971 ,726,726,726 ,0,0,0}, {978,972,1053 ,726,726,726 ,0,0,0}, + {1052,26,24 ,726,726,726 ,0,0,0}, {1052,24,638 ,726,726,726 ,0,0,0}, + {22,21,638 ,726,726,726 ,0,0,0}, {21,28,635 ,726,726,726 ,0,0,0}, + {456,636,632 ,726,726,726 ,0,0,0}, {450,448,627 ,728,726,726 ,0,0,0}, + {438,440,649 ,726,726,726 ,0,0,0}, {435,438,646 ,726,726,726 ,0,0,0}, + {650,441,652 ,726,726,726 ,0,0,0}, {649,440,650 ,726,726,726 ,0,0,0}, + {652,444,655 ,726,726,726 ,0,0,0}, {952,1043,655 ,726,726,726 ,0,0,0}, + {1043,968,657 ,726,726,726 ,0,0,0}, {950,657,36 ,726,726,726 ,0,0,0}, + {34,588,36 ,726,726,726 ,0,0,0}, {950,36,588 ,726,726,726 ,0,0,0}, + {31,588,32 ,726,726,726 ,0,0,0}, {588,34,32 ,726,726,726 ,0,0,0}, + {38,588,31 ,726,726,726 ,0,0,0}, {485,704,484 ,726,726,726 ,0,0,0}, + {426,425,18 ,727,726,726 ,0,0,0}, {257,471,467 ,726,726,726 ,0,0,0}, + {426,18,831 ,727,726,727 ,0,0,0}, {471,260,1051 ,726,726,726 ,0,0,0}, + {991,1036,1048 ,727,727,726 ,0,0,0}, {105,916,1038 ,726,727,727 ,0,0,0}, + {1037,996,995 ,727,727,726 ,0,0,0}, {1037,995,1038 ,727,726,727 ,0,0,0}, + {996,1050,262 ,727,726,726 ,0,0,0}, {1051,260,262 ,726,726,726 ,0,0,0}, + {471,257,260 ,726,726,726 ,0,0,0}, {466,257,467 ,726,726,726 ,0,0,0}, + {466,469,256 ,726,727,727 ,0,0,0}, {703,482,484 ,726,726,726 ,0,0,0}, + {700,478,482 ,726,726,726 ,0,0,0}, {683,479,478 ,726,726,726 ,0,0,0}, + {681,497,479 ,726,729,726 ,0,0,0}, {704,703,484 ,726,726,726 ,0,0,0}, + {680,498,497 ,726,726,729 ,0,0,0}, {703,700,482 ,726,726,726 ,0,0,0}, + {687,500,498 ,726,726,726 ,0,0,0}, {377,812,255 ,727,727,726 ,0,0,0}, + {700,683,478 ,726,726,726 ,0,0,0}, {688,504,503 ,726,726,726 ,0,0,0}, + {376,819,812 ,727,726,727 ,0,0,0}, {681,680,497 ,726,726,729 ,0,0,0}, + {506,504,696 ,726,726,726 ,0,0,0}, {680,687,498 ,726,726,726 ,0,0,0}, + {695,8,692 ,726,726,726 ,0,0,0}, {503,689,688 ,726,728,726 ,0,0,0}, + {475,751,748 ,727,726,726 ,0,0,0}, {688,696,504 ,726,726,726 ,0,0,0}, + {826,1054,828 ,726,726,726 ,0,0,0}, {389,822,387 ,726,726,726 ,0,0,0}, + {1001,1055,826 ,726,727,726 ,0,0,0}, {822,389,826 ,726,726,726 ,0,0,0}, + {1055,1054,826 ,727,726,726 ,0,0,0}, {999,1035,748 ,726,726,726 ,0,0,0}, + {1054,1035,828 ,726,726,726 ,0,0,0}, {1056,748,1057 ,726,726,727 ,0,0,0}, + {748,1035,1057 ,726,726,727 ,0,0,0}, {1058,748,1059 ,726,726,726 ,0,0,0}, + {748,1056,1059 ,726,726,726 ,0,0,0}, {748,1058,475 ,726,726,727 ,0,0,0}, + {477,751,475 ,726,726,727 ,0,0,0}, {2,695,698 ,726,726,726 ,0,0,0}, + {751,1060,1003 ,726,726,726 ,0,0,0}, {751,477,1060 ,726,726,726 ,0,0,0}, + {6,698,1022 ,726,726,726 ,0,0,0}, {1004,6,751 ,726,726,726 ,0,0,0}, + {4,2,698 ,726,726,726 ,0,0,0}, {2,1,695 ,726,726,726 ,0,0,0}, + {506,692,8 ,726,726,726 ,0,0,0}, {506,696,692 ,726,726,726 ,0,0,0}, + {500,687,689 ,726,726,728 ,0,0,0}, {488,490,709 ,726,726,726 ,0,0,0}, + {485,488,706 ,726,726,726 ,0,0,0}, {490,491,710 ,726,728,726 ,0,0,0}, + {491,494,712 ,728,726,726 ,0,0,0}, {715,712,494 ,726,726,726 ,0,0,0}, + {1061,717,969 ,726,726,726 ,0,0,0}, {975,972,974 ,726,726,726 ,0,0,0}, + {1061,994,717 ,726,726,726 ,0,0,0}, {58,14,1062 ,726,726,726 ,0,0,0}, + {987,12,993 ,726,726,726 ,0,0,0}, {1062,14,987 ,726,726,726 ,0,0,0}, + {425,11,18 ,726,726,726 ,0,0,0}, {993,12,11 ,726,726,726 ,0,0,0}, + {1014,737,1013 ,726,726,728 ,0,0,0}, {235,274,233 ,726,726,726 ,0,0,0}, + {215,283,213 ,726,726,726 ,0,0,0}, {731,734,1011 ,726,726,726 ,0,0,0}, + {732,731,1012 ,726,726,726 ,0,0,0}, {737,732,1013 ,726,726,728 ,0,0,0}, + {738,737,1014 ,728,726,726 ,0,0,0}, {745,743,1015 ,726,726,726 ,0,0,0}, + {743,742,1006 ,726,726,726 ,0,0,0}, {1018,1017,1016 ,726,726,726 ,0,0,0}, + {745,1063,1019 ,726,726,726 ,0,0,0}, {1063,745,1015 ,726,726,726 ,0,0,0}, + {1064,1017,1019 ,726,726,726 ,0,0,0}, {1063,1064,1019 ,726,726,726 ,0,0,0}, + {1016,886,1018 ,726,726,726 ,0,0,0}, {1005,1008,887 ,726,726,726 ,0,0,0}, + {228,1008,1009 ,726,726,726 ,0,0,0}, {225,1007,228 ,726,726,726 ,0,0,0}, + {226,295,225 ,726,726,726 ,0,0,0}, {291,292,221 ,726,726,726 ,0,0,0}, + {295,221,292 ,726,726,726 ,0,0,0}, {289,291,219 ,726,726,726 ,0,0,0}, + {286,289,222 ,726,726,726 ,0,0,0}, {283,285,213 ,726,726,726 ,0,0,0}, + {281,215,212 ,726,726,726 ,0,0,0}, {264,212,211 ,726,726,726 ,0,0,0}, + {269,268,230 ,726,726,728 ,0,0,0}, {268,264,211 ,726,726,726 ,0,0,0}, + {233,271,230 ,726,726,728 ,0,0,0}, {235,275,274 ,726,726,726 ,0,0,0}, + {233,274,271 ,726,726,726 ,0,0,0}, {236,239,277 ,726,726,726 ,0,0,0}, + {235,236,275 ,726,726,726 ,0,0,0}, {279,239,718 ,726,726,726 ,0,0,0}, + {722,241,242 ,726,726,726 ,0,0,0}, {718,239,241 ,726,726,726 ,0,0,0}, + {1023,780,1020 ,726,726,727 ,0,0,0}, {202,806,201 ,726,727,727 ,0,0,0}, + {178,794,181 ,726,726,727 ,0,0,0}, {1030,1028,1027 ,727,726,726 ,0,0,0}, + {1026,1025,1030 ,726,726,727 ,0,0,0}, {782,1025,1021 ,726,726,726 ,0,0,0}, + {780,782,1020 ,726,726,727 ,0,0,0}, {776,777,1023 ,726,726,726 ,0,0,0}, + {774,776,888 ,727,726,727 ,0,0,0}, {771,774,889 ,726,727,727 ,0,0,0}, + {770,771,1024 ,726,726,727 ,0,0,0}, {765,767,894 ,726,726,726 ,0,0,0}, + {764,765,893 ,727,726,726 ,0,0,0}, {762,764,895 ,726,727,726 ,0,0,0}, + {759,762,897 ,726,726,726 ,0,0,0}, {758,194,191 ,726,727,726 ,0,0,0}, + {754,755,191 ,726,726,726 ,0,0,0}, {752,754,192 ,727,726,726 ,0,0,0}, + {784,752,187 ,726,727,726 ,0,0,0}, {752,192,187 ,727,726,726 ,0,0,0}, + {788,786,185 ,727,726,726 ,0,0,0}, {791,788,188 ,726,727,727 ,0,0,0}, + {792,791,179 ,726,726,727 ,0,0,0}, {794,792,181 ,726,726,727 ,0,0,0}, + {799,796,178 ,726,726,726 ,0,0,0}, {800,799,177 ,726,726,727 ,0,0,0}, + {199,803,196 ,726,726,726 ,0,0,0}, {196,800,177 ,726,726,727 ,0,0,0}, + {201,806,804 ,727,727,727 ,0,0,0}, {199,804,803 ,726,727,726 ,0,0,0}, + {202,809,806 ,726,726,727 ,0,0,0}, {205,810,202 ,727,727,726 ,0,0,0}, + {809,202,810 ,726,726,727 ,0,0,0}, {810,207,1033 ,727,726,726 ,0,0,0}, + {208,1033,207 ,727,726,726 ,0,0,0}, {145,147,577 ,727,727,726 ,0,0,0}, + {545,891,544 ,726,727,727 ,0,0,0}, {144,578,147 ,726,727,727 ,0,0,0}, + {550,551,932 ,726,726,727 ,0,0,0}, {548,550,931 ,726,726,726 ,0,0,0}, + {545,548,890 ,726,726,726 ,0,0,0}, {541,544,891 ,727,727,727 ,0,0,0}, + {539,541,940 ,726,727,726 ,0,0,0}, {538,539,938 ,726,726,727 ,0,0,0}, + {536,538,939 ,726,726,727 ,0,0,0}, {532,533,933 ,727,726,727 ,0,0,0}, + {529,532,937 ,727,727,726 ,0,0,0}, {528,529,936 ,726,727,726 ,0,0,0}, + {526,528,934 ,727,726,726 ,0,0,0}, {558,935,160 ,727,726,727 ,0,0,0}, + {562,560,160 ,726,726,727 ,0,0,0}, {565,562,157 ,727,726,726 ,0,0,0}, + {566,565,158 ,727,727,726 ,0,0,0}, {568,153,151 ,726,726,726 ,0,0,0}, + {566,153,568 ,727,726,726 ,0,0,0}, {573,570,151 ,726,727,726 ,0,0,0}, + {574,573,154 ,726,726,727 ,0,0,0}, {577,574,145 ,726,726,727 ,0,0,0}, + {578,577,147 ,727,726,727 ,0,0,0}, {143,583,144 ,727,727,726 ,0,0,0}, + {580,578,144 ,726,727,726 ,0,0,0}, {584,143,162 ,726,727,726 ,0,0,0}, + {143,584,583 ,727,726,727 ,0,0,0}, {162,165,925 ,726,726,726 ,0,0,0}, + {943,925,167 ,726,726,727 ,0,0,0}, {165,167,925 ,726,727,726 ,0,0,0}, + {927,171,928 ,727,727,726 ,0,0,0}, {173,944,171 ,726,726,727 ,0,0,0}, + {928,171,944 ,726,727,726 ,0,0,0}, {174,944,173 ,727,726,726 ,0,0,0}, + {917,958,599 ,726,726,726 ,0,0,0}, {133,320,337 ,726,726,728 ,0,0,0}, + {347,348,110 ,728,726,726 ,0,0,0}, {593,594,954 ,726,726,726 ,0,0,0}, + {591,953,918 ,726,726,728 ,0,0,0}, {598,601,918 ,726,726,728 ,0,0,0}, + {599,598,917 ,726,726,726 ,0,0,0}, {606,599,958 ,729,726,726 ,0,0,0}, + {604,603,919 ,726,726,726 ,0,0,0}, {609,604,920 ,726,726,726 ,0,0,0}, + {610,609,960 ,726,726,726 ,0,0,0}, {964,615,614 ,726,726,726 ,0,0,0}, + {614,963,964 ,726,726,726 ,0,0,0}, {617,1065,1066 ,726,726,726 ,0,0,0}, + {1065,617,965 ,726,726,726 ,0,0,0}, {1066,126,922 ,726,726,726 ,0,0,0}, + {1065,126,1066 ,726,726,726 ,0,0,0}, {124,961,967 ,726,726,726 ,0,0,0}, + {124,967,922 ,726,726,726 ,0,0,0}, {117,921,119 ,726,726,726 ,0,0,0}, + {120,959,117 ,726,728,726 ,0,0,0}, {351,959,111 ,726,728,726 ,0,0,0}, + {348,351,113 ,726,726,726 ,0,0,0}, {342,345,109 ,726,726,726 ,0,0,0}, + {345,347,110 ,726,728,726 ,0,0,0}, {341,342,128 ,726,726,728 ,0,0,0}, + {131,337,339 ,726,728,728 ,0,0,0}, {131,341,128 ,726,726,728 ,0,0,0}, + {133,134,320 ,726,726,726 ,0,0,0}, {131,133,337 ,726,726,728 ,0,0,0}, + {134,137,324 ,726,726,726 ,0,0,0}, {325,139,327 ,726,726,726 ,0,0,0}, + {324,137,325 ,726,726,726 ,0,0,0}, {330,139,140 ,726,726,726 ,0,0,0}, + {873,871,76 ,726,726,726 ,0,0,0}, {867,77,870 ,727,727,726 ,0,0,0}, + {910,911,1067 ,727,726,726 ,0,0,0}, {1067,911,908 ,726,726,727 ,0,0,0}, + {905,904,910 ,726,726,727 ,0,0,0}, {855,904,903 ,726,726,726 ,0,0,0}, + {854,855,902 ,726,726,727 ,0,0,0}, {851,854,901 ,726,726,726 ,0,0,0}, + {850,851,900 ,726,726,727 ,0,0,0}, {845,848,899 ,727,727,727 ,0,0,0}, + {844,845,898 ,726,727,727 ,0,0,0}, {842,844,896 ,727,726,726 ,0,0,0}, + {839,842,892 ,726,727,726 ,0,0,0}, {838,839,884 ,726,726,726 ,0,0,0}, + {836,838,880 ,727,726,726 ,0,0,0}, {832,836,92 ,727,727,727 ,0,0,0}, + {858,856,89 ,726,727,726 ,0,0,0}, {859,858,90 ,726,726,726 ,0,0,0}, + {861,859,85 ,727,726,726 ,0,0,0}, {859,90,85 ,726,726,726 ,0,0,0}, + {864,861,83 ,726,727,726 ,0,0,0}, {865,864,86 ,726,726,727 ,0,0,0}, + {867,865,77 ,727,726,727 ,0,0,0}, {79,870,77 ,727,726,727 ,0,0,0}, + {75,873,76 ,727,726,726 ,0,0,0}, {76,871,79 ,726,726,727 ,0,0,0}, + {876,75,94 ,726,727,726 ,0,0,0}, {75,876,873 ,727,726,726 ,0,0,0}, + {94,97,1042 ,726,726,726 ,0,0,0}, {912,1042,99 ,726,726,727 ,0,0,0}, + {97,99,1042 ,726,727,726 ,0,0,0}, {912,100,1049 ,726,726,727 ,0,0,0}, + {1049,105,1038 ,727,726,727 ,0,0,0}, {1049,100,103 ,727,726,727 ,0,0,0}, + {916,105,106 ,727,726,727 ,0,0,0}, {983,674,666 ,728,726,726 ,0,0,0}, + {65,298,63 ,726,726,726 ,0,0,0}, {317,45,42 ,726,726,726 ,0,0,0}, + {668,661,981 ,726,726,726 ,0,0,0}, {669,668,982 ,726,726,726 ,0,0,0}, + {666,669,983 ,726,726,728 ,0,0,0}, {881,674,983 ,726,726,728 ,0,0,0}, + {676,672,977 ,726,726,726 ,0,0,0}, {976,988,677 ,726,726,726 ,0,0,0}, + {677,676,976 ,726,726,726 ,0,0,0}, {1068,989,988 ,726,726,726 ,0,0,0}, + {55,16,14 ,726,726,726 ,0,0,0}, {989,1069,1053 ,726,726,726 ,0,0,0}, + {1069,989,1068 ,726,726,726 ,0,0,0}, {55,14,58 ,726,726,726 ,0,0,0}, + {1069,978,1053 ,726,726,726 ,0,0,0}, {58,1062,26 ,726,726,726 ,0,0,0}, + {58,26,974 ,726,726,726 ,0,0,0}, {55,970,16 ,726,726,726 ,0,0,0}, + {55,56,883 ,726,726,726 ,0,0,0}, {55,883,970 ,726,726,726 ,0,0,0}, + {49,882,51 ,726,726,726 ,0,0,0}, {52,986,49 ,726,728,726 ,0,0,0}, + {319,986,43 ,726,728,726 ,0,0,0}, {317,319,45 ,726,726,726 ,0,0,0}, + {315,42,41 ,726,726,726 ,0,0,0}, {60,311,41 ,728,726,726 ,0,0,0}, + {312,315,41 ,726,726,726 ,0,0,0}, {63,298,309 ,726,726,726 ,0,0,0}, + {60,309,311 ,728,726,726 ,0,0,0}, {65,299,298 ,726,726,726 ,0,0,0}, + {66,69,301 ,726,726,726 ,0,0,0}, {65,66,299 ,726,726,726 ,0,0,0}, + {304,71,305 ,726,726,726 ,0,0,0}, {301,69,304 ,726,726,726 ,0,0,0}, + {72,305,71 ,726,726,726 ,0,0,0}, {1070,371,1071 ,730,730,730 ,0,0,0}, + {267,231,229 ,730,730,730 ,0,0,0}, {88,860,91 ,730,730,730 ,0,0,0}, + {1072,1073,1074 ,730,730,730 ,0,0,0}, {1075,741,744 ,730,730,730 ,0,0,0}, + {460,247,463 ,730,730,730 ,0,0,0}, {483,702,705 ,730,730,730 ,0,0,0}, + {263,1076,1077 ,730,730,730 ,0,0,0}, {1078,1079,1080 ,730,730,730 ,0,0,0}, + {1076,263,1081 ,730,730,730 ,0,0,0}, {1082,1083,104 ,730,730,730 ,0,0,0}, + {849,1084,1085 ,730,730,730 ,0,0,0}, {1082,102,101 ,730,730,730 ,0,0,0}, + {84,862,863 ,730,730,730 ,0,0,0}, {81,82,866 ,730,730,730 ,0,0,0}, + {1086,1087,843 ,730,730,730 ,0,0,0}, {93,877,95 ,730,730,730 ,0,0,0}, + {834,833,87 ,730,730,730 ,0,0,0}, {835,1088,837 ,730,730,730 ,0,0,0}, + {74,874,875 ,730,730,730 ,0,0,0}, {1089,1090,98 ,730,730,730 ,0,0,0}, + {159,156,564 ,730,730,730 ,0,0,0}, {80,78,872 ,730,730,730 ,0,0,0}, + {527,557,1091 ,730,730,730 ,0,0,0}, {875,877,93 ,730,730,730 ,0,0,0}, + {81,868,78 ,730,730,730 ,0,0,0}, {142,582,161 ,730,730,730 ,0,0,0}, + {1092,1093,535 ,730,730,730 ,0,0,0}, {833,857,87 ,730,730,730 ,0,0,0}, + {1089,96,95 ,730,730,730 ,0,0,0}, {1093,1094,537 ,730,730,730 ,0,0,0}, + {150,569,571 ,730,730,730 ,0,0,0}, {834,87,1095 ,730,730,730 ,0,0,0}, + {1090,1082,101 ,730,730,730 ,0,0,0}, {798,195,176 ,730,730,730 ,0,0,0}, + {802,198,197 ,730,730,730 ,0,0,0}, {840,837,1096 ,730,730,730 ,0,0,0}, + {837,1088,1096 ,730,730,730 ,0,0,0}, {1097,1086,841 ,730,730,730 ,0,0,0}, + {1084,849,847 ,730,730,730 ,0,0,0}, {1087,1084,846 ,730,730,730 ,0,0,0}, + {852,1085,1098 ,730,730,730 ,0,0,0}, {1099,1100,1101 ,730,730,730 ,0,0,0}, + {263,261,1081 ,730,730,730 ,0,0,0}, {1102,1103,1083 ,730,730,730 ,0,0,0}, + {261,259,473 ,730,730,730 ,0,0,0}, {1104,1105,1106 ,730,730,730 ,0,0,0}, + {1107,1108,1109 ,730,730,730 ,0,0,0}, {244,247,460 ,730,730,730 ,0,0,0}, + {381,464,253 ,730,730,730 ,0,0,0}, {711,713,492 ,730,730,730 ,0,0,0}, + {690,686,501 ,730,730,730 ,0,0,0}, {1072,1110,1111 ,730,730,730 ,0,0,0}, + {1112,1075,744 ,730,730,730 ,0,0,0}, {1113,1114,740 ,730,730,730 ,0,0,0}, + {1115,728,730 ,730,730,730 ,0,0,0}, {733,1114,1116 ,730,730,730 ,0,0,0}, + {240,238,747 ,730,730,730 ,0,0,0}, {725,1117,1118 ,730,730,730 ,0,0,0}, + {1119,1120,1121 ,730,730,730 ,0,0,0}, {1122,1123,1124 ,730,730,730 ,0,0,0}, + {507,694,693 ,730,730,730 ,0,0,0}, {1121,749,1119 ,730,730,730 ,0,0,0}, + {1125,1126,1127 ,730,730,730 ,0,0,0}, {1128,750,1129 ,730,730,730 ,0,0,0}, + {1130,775,1131 ,730,730,730 ,0,0,0}, {779,1132,781 ,730,730,730 ,0,0,0}, + {1133,1134,769 ,730,730,730 ,0,0,0}, {203,811,204 ,730,730,730 ,0,0,0}, + {1135,766,763 ,730,730,730 ,0,0,0}, {193,190,753 ,730,730,730 ,0,0,0}, + {180,790,793 ,730,730,730 ,0,0,0}, {1136,1125,1127 ,730,730,730 ,0,0,0}, + {1135,763,1137 ,730,730,730 ,0,0,0}, {760,189,1138 ,730,730,730 ,0,0,0}, + {206,811,1139 ,730,730,730 ,0,0,0}, {805,200,198 ,730,730,730 ,0,0,0}, + {176,182,795 ,730,730,730 ,0,0,0}, {787,184,785 ,730,730,730 ,0,0,0}, + {789,790,183 ,730,730,730 ,0,0,0}, {195,801,197 ,730,730,730 ,0,0,0}, + {186,783,785 ,730,730,730 ,0,0,0}, {189,760,757 ,730,730,730 ,0,0,0}, + {756,190,757 ,730,730,730 ,0,0,0}, {808,811,203 ,730,730,730 ,0,0,0}, + {203,200,807 ,730,730,730 ,0,0,0}, {209,1139,1140 ,730,730,730 ,0,0,0}, + {1137,763,761 ,730,730,730 ,0,0,0}, {1140,1136,1141 ,730,730,730 ,0,0,0}, + {216,214,282 ,730,730,730 ,0,0,0}, {195,798,801 ,730,730,730 ,0,0,0}, + {1135,1133,766 ,730,730,730 ,0,0,0}, {1142,772,1134 ,730,730,730 ,0,0,0}, + {775,1130,778 ,730,730,730 ,0,0,0}, {1131,773,1142 ,730,730,730 ,0,0,0}, + {1132,1143,781 ,730,730,730 ,0,0,0}, {1136,1127,1144 ,730,730,730 ,0,0,0}, + {1145,1144,1146 ,730,730,730 ,0,0,0}, {1126,1125,1147 ,730,730,730 ,0,0,0}, + {1148,1126,1147 ,730,730,730 ,0,0,0}, {1149,1150,750 ,730,730,730 ,0,0,0}, + {750,1148,1147 ,730,730,730 ,0,0,0}, {1150,829,1148 ,730,730,730 ,0,0,0}, + {388,827,1151 ,730,730,730 ,0,0,0}, {693,505,507 ,730,730,730 ,0,0,0}, + {7,697,9 ,730,730,730 ,0,0,0}, {1152,243,723 ,730,730,730 ,0,0,0}, + {294,227,224 ,730,730,730 ,0,0,0}, {232,272,273 ,730,730,730 ,0,0,0}, + {237,234,276 ,730,730,730 ,0,0,0}, {284,214,287 ,730,730,730 ,0,0,0}, + {218,288,217 ,730,730,730 ,0,0,0}, {267,229,265 ,730,730,730 ,0,0,0}, + {210,266,265 ,730,730,730 ,0,0,0}, {272,231,270 ,730,730,730 ,0,0,0}, + {238,280,747 ,730,730,730 ,0,0,0}, {232,273,234 ,730,730,730 ,0,0,0}, + {739,1075,1113 ,730,730,730 ,0,0,0}, {1112,746,1074 ,730,730,730 ,0,0,0}, + {735,1117,736 ,730,730,730 ,0,0,0}, {1116,735,733 ,730,730,730 ,0,0,0}, + {728,1152,720 ,730,730,730 ,0,0,0}, {730,1118,1115 ,730,730,730 ,0,0,0}, + {278,238,237 ,730,730,730 ,0,0,0}, {240,724,243 ,730,730,730 ,0,0,0}, + {385,383,825 ,730,730,730 ,0,0,0}, {685,496,499 ,730,730,730 ,0,0,0}, + {486,705,707 ,730,730,730 ,0,0,0}, {250,463,247 ,730,730,730 ,0,0,0}, + {480,701,481 ,730,730,730 ,0,0,0}, {637,29,27 ,730,730,730 ,0,0,0}, + {701,702,481 ,730,730,730 ,0,0,0}, {480,684,701 ,730,730,730 ,0,0,0}, + {682,496,685 ,730,730,730 ,0,0,0}, {690,501,502 ,730,730,730 ,0,0,0}, + {691,690,502 ,730,730,730 ,0,0,0}, {1122,1153,1154 ,730,730,730 ,0,0,0}, + {1155,223,1123 ,730,730,730 ,0,0,0}, {1122,1154,1123 ,730,730,730 ,0,0,0}, + {691,505,693 ,730,730,730 ,0,0,0}, {1124,1123,223 ,730,730,730 ,0,0,0}, + {1154,1120,1119 ,730,730,730 ,0,0,0}, {1120,1154,1153 ,730,730,730 ,0,0,0}, + {699,3,5 ,730,730,730 ,0,0,0}, {502,505,691 ,730,730,730 ,0,0,0}, + {686,499,501 ,730,730,730 ,0,0,0}, {685,499,686 ,730,730,730 ,0,0,0}, + {684,495,682 ,730,730,730 ,0,0,0}, {374,817,815 ,730,730,730 ,0,0,0}, + {818,375,378 ,730,730,730 ,0,0,0}, {253,464,250 ,730,730,730 ,0,0,0}, + {1156,716,1157 ,730,730,730 ,0,0,0}, {713,714,493 ,730,730,730 ,0,0,0}, + {424,17,1158 ,730,730,730 ,0,0,0}, {637,634,29 ,730,730,730 ,0,0,0}, + {1159,714,716 ,730,730,730 ,0,0,0}, {639,27,20 ,730,730,730 ,0,0,0}, + {1160,25,1161 ,730,730,730 ,0,0,0}, {64,62,296 ,730,730,730 ,0,0,0}, + {40,316,314 ,730,730,730 ,0,0,0}, {70,68,303 ,730,730,730 ,0,0,0}, + {1162,73,679 ,730,730,730 ,0,0,0}, {1163,670,1164 ,730,730,730 ,0,0,0}, + {313,59,314 ,730,730,730 ,0,0,0}, {1165,1166,675 ,730,730,730 ,0,0,0}, + {1167,1168,1169 ,730,730,730 ,0,0,0}, {302,68,67 ,730,730,730 ,0,0,0}, + {61,297,62 ,730,730,730 ,0,0,0}, {660,1170,1171 ,730,730,730 ,0,0,0}, + {308,73,306 ,730,730,730 ,0,0,0}, {1172,1164,665 ,730,730,730 ,0,0,0}, + {1173,1167,1174 ,730,730,730 ,0,0,0}, {1175,673,1166 ,730,730,730 ,0,0,0}, + {1172,671,1175 ,730,730,730 ,0,0,0}, {678,1169,1165 ,730,730,730 ,0,0,0}, + {671,1172,667 ,730,730,730 ,0,0,0}, {1162,663,1171 ,730,730,730 ,0,0,0}, + {1170,659,1163 ,730,730,730 ,0,0,0}, {361,414,413 ,730,730,730 ,0,0,0}, + {64,300,67 ,730,730,730 ,0,0,0}, {73,70,306 ,730,730,730 ,0,0,0}, + {310,61,59 ,730,730,730 ,0,0,0}, {633,631,455 ,730,730,730 ,0,0,0}, + {626,625,449 ,730,730,730 ,0,0,0}, {452,631,630 ,730,730,730 ,0,0,0}, + {455,631,452 ,730,730,730 ,0,0,0}, {633,457,634 ,730,730,730 ,0,0,0}, + {1176,318,44 ,730,730,730 ,0,0,0}, {1177,1160,1161 ,730,730,730 ,0,0,0}, + {451,452,630 ,730,730,730 ,0,0,0}, {457,633,455 ,730,730,730 ,0,0,0}, + {53,25,1178 ,730,730,730 ,0,0,0}, {1179,48,50 ,730,730,730 ,0,0,0}, + {27,639,637 ,730,730,730 ,0,0,0}, {20,23,639 ,730,730,730 ,0,0,0}, + {25,53,1161 ,730,730,730 ,0,0,0}, {29,634,457 ,730,730,730 ,0,0,0}, + {1180,1181,525 ,730,730,730 ,0,0,0}, {630,626,451 ,730,730,730 ,0,0,0}, + {451,626,449 ,730,730,730 ,0,0,0}, {519,400,392 ,730,730,730 ,0,0,0}, + {449,625,446 ,730,730,730 ,0,0,0}, {393,513,511 ,730,730,730 ,0,0,0}, + {445,446,622 ,730,730,730 ,0,0,0}, {431,430,641 ,730,730,730 ,0,0,0}, + {624,430,445 ,730,730,730 ,0,0,0}, {645,436,433 ,730,730,730 ,0,0,0}, + {433,431,642 ,730,730,730 ,0,0,0}, {420,352,418 ,730,730,730 ,0,0,0}, + {355,358,410 ,730,730,730 ,0,0,0}, {366,422,367 ,730,730,730 ,0,0,0}, + {423,1182,369 ,730,730,730 ,0,0,0}, {1183,125,1184 ,730,730,730 ,0,0,0}, + {654,1185,443 ,730,730,730 ,0,0,0}, {108,349,346 ,730,730,730 ,0,0,0}, + {132,321,135 ,730,730,730 ,0,0,0}, {108,344,127 ,730,730,730 ,0,0,0}, + {613,616,1186 ,730,730,730 ,0,0,0}, {1187,597,1188 ,730,730,730 ,0,0,0}, + {1189,1190,612 ,730,730,730 ,0,0,0}, {596,1191,1192 ,730,730,730 ,0,0,0}, + {328,329,138 ,730,730,730 ,0,0,0}, {616,618,1186 ,730,730,730 ,0,0,0}, + {135,323,136 ,730,730,730 ,0,0,0}, {611,1193,1189 ,730,730,730 ,0,0,0}, + {1194,334,1195 ,730,730,730 ,0,0,0}, {602,1196,600 ,730,730,730 ,0,0,0}, + {605,1197,607 ,730,730,730 ,0,0,0}, {1188,608,1197 ,730,730,730 ,0,0,0}, + {1196,602,1187 ,730,730,730 ,0,0,0}, {595,1198,1191 ,730,730,730 ,0,0,0}, + {1198,592,1196 ,730,730,730 ,0,0,0}, {612,1190,605 ,730,730,730 ,0,0,0}, + {1192,1195,336 ,730,730,730 ,0,0,0}, {596,1192,619 ,730,730,730 ,0,0,0}, + {141,138,329 ,730,730,730 ,0,0,0}, {1194,141,332 ,730,730,730 ,0,0,0}, + {618,1199,1200 ,730,730,730 ,0,0,0}, {1200,1186,618 ,730,730,730 ,0,0,0}, + {322,321,132 ,730,730,730 ,0,0,0}, {136,326,138 ,730,730,730 ,0,0,0}, + {130,129,340 ,730,730,730 ,0,0,0}, {322,130,338 ,730,730,730 ,0,0,0}, + {121,1201,1202 ,730,730,730 ,0,0,0}, {343,129,127 ,730,730,730 ,0,0,0}, + {118,125,1183 ,730,730,730 ,0,0,0}, {350,112,1203 ,730,730,730 ,0,0,0}, + {366,415,422 ,730,730,730 ,0,0,0}, {116,118,1183 ,730,730,730 ,0,0,0}, + {1204,1205,1184 ,730,730,730 ,0,0,0}, {1205,1204,1206 ,730,730,730 ,0,0,0}, + {30,33,587 ,730,730,730 ,0,0,0}, {587,1207,1206 ,730,730,730 ,0,0,0}, + {1205,1206,1207 ,730,730,730 ,0,0,0}, {1207,587,35 ,730,730,730 ,0,0,0}, + {656,35,1208 ,730,730,730 ,0,0,0}, {540,1209,542 ,730,730,730 ,0,0,0}, + {582,142,581 ,730,730,730 ,0,0,0}, {1210,546,1211 ,730,730,730 ,0,0,0}, + {542,1211,543 ,730,730,730 ,0,0,0}, {1094,1209,540 ,730,730,730 ,0,0,0}, + {530,1212,1213 ,730,730,730 ,0,0,0}, {1092,534,531 ,730,730,730 ,0,0,0}, + {559,155,1214 ,730,730,730 ,0,0,0}, {1091,1212,527 ,730,730,730 ,0,0,0}, + {1215,164,163 ,730,730,730 ,0,0,0}, {561,563,155 ,730,730,730 ,0,0,0}, + {579,142,148 ,730,730,730 ,0,0,0}, {575,576,146 ,730,730,730 ,0,0,0}, + {585,163,161 ,730,730,730 ,0,0,0}, {575,149,572 ,730,730,730 ,0,0,0}, + {166,1215,1216 ,730,730,730 ,0,0,0}, {567,152,159 ,730,730,730 ,0,0,0}, + {155,559,561 ,730,730,730 ,0,0,0}, {1217,169,1216 ,730,730,730 ,0,0,0}, + {170,169,1217 ,730,730,730 ,0,0,0}, {530,527,1212 ,730,730,730 ,0,0,0}, + {552,549,1218 ,730,730,730 ,0,0,0}, {1219,547,1210 ,730,730,730 ,0,0,0}, + {552,1220,553 ,730,730,730 ,0,0,0}, {1218,549,1219 ,730,730,730 ,0,0,0}, + {553,1220,555 ,730,730,730 ,0,0,0}, {172,1221,175 ,730,730,730 ,0,0,0}, + {1217,1222,1223 ,730,730,730 ,0,0,0}, {172,170,1221 ,730,730,730 ,0,0,0}, + {1224,1222,1070 ,730,730,730 ,0,0,0}, {1222,1224,1223 ,730,730,730 ,0,0,0}, + {353,420,415 ,730,730,730 ,0,0,0}, {1224,1070,586 ,730,730,730 ,0,0,0}, + {420,353,352 ,730,730,730 ,0,0,0}, {366,353,415 ,730,730,730 ,0,0,0}, + {352,355,418 ,730,730,730 ,0,0,0}, {410,358,413 ,730,730,730 ,0,0,0}, + {418,355,410 ,730,730,730 ,0,0,0}, {436,647,437 ,730,730,730 ,0,0,0}, + {430,624,641 ,730,730,730 ,0,0,0}, {399,414,1225 ,730,730,730 ,0,0,0}, + {399,1225,360 ,730,730,730 ,0,0,0}, {360,509,399 ,730,730,730 ,0,0,0}, + {514,396,398 ,730,730,730 ,0,0,0}, {439,437,648 ,730,730,730 ,0,0,0}, + {413,358,361 ,730,730,730 ,0,0,0}, {641,642,431 ,730,730,730 ,0,0,0}, + {439,651,442 ,730,730,730 ,0,0,0}, {642,645,433 ,730,730,730 ,0,0,0}, + {654,443,653 ,730,730,730 ,0,0,0}, {645,647,436 ,730,730,730 ,0,0,0}, + {39,586,878 ,730,730,730 ,0,0,0}, {648,651,439 ,730,730,730 ,0,0,0}, + {371,1226,1227 ,730,730,730 ,0,0,0}, {423,367,422 ,730,730,730 ,0,0,0}, + {1182,1226,369 ,730,730,730 ,0,0,0}, {367,423,369 ,730,730,730 ,0,0,0}, + {369,1226,371 ,730,730,730 ,0,0,0}, {1070,1071,586 ,730,730,730 ,0,0,0}, + {1227,1071,371 ,730,730,730 ,0,0,0}, {1228,586,1229 ,730,730,730 ,0,0,0}, + {586,1071,1229 ,730,730,730 ,0,0,0}, {1230,586,1231 ,730,730,730 ,0,0,0}, + {586,1228,1231 ,730,730,730 ,0,0,0}, {586,1230,878 ,730,730,730 ,0,0,0}, + {1232,654,656 ,730,730,730 ,0,0,0}, {586,39,587 ,730,730,730 ,0,0,0}, + {587,37,30 ,730,730,730 ,0,0,0}, {587,39,37 ,730,730,730 ,0,0,0}, + {35,656,1207 ,730,730,730 ,0,0,0}, {33,35,587 ,730,730,730 ,0,0,0}, + {1208,1232,656 ,730,730,730 ,0,0,0}, {1232,1185,654 ,730,730,730 ,0,0,0}, + {442,653,443 ,730,730,730 ,0,0,0}, {653,442,651 ,730,730,730 ,0,0,0}, + {437,647,648 ,730,730,730 ,0,0,0}, {445,622,624 ,730,730,730 ,0,0,0}, + {446,625,622 ,730,730,730 ,0,0,0}, {519,392,511 ,730,730,730 ,0,0,0}, + {399,509,398 ,730,730,730 ,0,0,0}, {521,401,400 ,730,730,730 ,0,0,0}, + {396,514,513 ,730,730,730 ,0,0,0}, {406,403,516 ,730,730,730 ,0,0,0}, + {511,392,393 ,730,730,730 ,0,0,0}, {525,1233,1234 ,730,730,730 ,0,0,0}, + {521,400,519 ,730,730,730 ,0,0,0}, {15,54,13 ,730,730,730 ,0,0,0}, + {401,521,516 ,730,730,730 ,0,0,0}, {1178,13,53 ,730,730,730 ,0,0,0}, + {1160,1235,25 ,730,730,730 ,0,0,0}, {639,23,1235 ,730,730,730 ,0,0,0}, + {25,1235,23 ,730,730,730 ,0,0,0}, {17,10,1158 ,730,730,730 ,0,0,0}, + {1236,13,1178 ,730,730,730 ,0,0,0}, {1237,54,15 ,730,730,730 ,0,0,0}, + {424,19,17 ,730,730,730 ,0,0,0}, {1238,1237,15 ,730,730,730 ,0,0,0}, + {705,486,483 ,730,730,730 ,0,0,0}, {245,470,258 ,730,730,730 ,0,0,0}, + {1239,1240,1101 ,730,730,730 ,0,0,0}, {472,259,465 ,730,730,730 ,0,0,0}, + {406,523,1234 ,730,730,730 ,0,0,0}, {1077,1241,263 ,730,730,730 ,0,0,0}, + {1109,1100,1099 ,730,730,730 ,0,0,0}, {1240,1181,1180 ,730,730,730 ,0,0,0}, + {1240,1180,1101 ,730,730,730 ,0,0,0}, {1181,1233,525 ,730,730,730 ,0,0,0}, + {1234,523,525 ,730,730,730 ,0,0,0}, {406,516,523 ,730,730,730 ,0,0,0}, + {401,516,403 ,730,730,730 ,0,0,0}, {513,393,396 ,730,730,730 ,0,0,0}, + {509,514,398 ,730,730,730 ,0,0,0}, {253,252,381 ,730,730,730 ,0,0,0}, + {252,813,380 ,730,730,730 ,0,0,0}, {707,708,487 ,730,730,730 ,0,0,0}, + {464,463,250 ,730,730,730 ,0,0,0}, {483,481,702 ,730,730,730 ,0,0,0}, + {489,708,711 ,730,730,730 ,0,0,0}, {245,244,468 ,730,730,730 ,0,0,0}, + {460,468,244 ,730,730,730 ,0,0,0}, {486,707,487 ,730,730,730 ,0,0,0}, + {470,465,258 ,730,730,730 ,0,0,0}, {489,711,492 ,730,730,730 ,0,0,0}, + {472,473,259 ,730,730,730 ,0,0,0}, {258,465,259 ,730,730,730 ,0,0,0}, + {427,830,19 ,730,730,730 ,0,0,0}, {1242,1105,1239 ,730,730,730 ,0,0,0}, + {1239,1103,1242 ,730,730,730 ,0,0,0}, {473,1081,261 ,730,730,730 ,0,0,0}, + {1109,1099,1107 ,730,730,730 ,0,0,0}, {1241,1102,1083 ,730,730,730 ,0,0,0}, + {1077,1102,1241 ,730,730,730 ,0,0,0}, {1106,1105,1242 ,730,730,730 ,0,0,0}, + {1104,1243,1244 ,730,730,730 ,0,0,0}, {1243,1104,1106 ,730,730,730 ,0,0,0}, + {1244,830,427 ,730,730,730 ,0,0,0}, {1243,830,1244 ,730,730,730 ,0,0,0}, + {424,427,19 ,730,730,730 ,0,0,0}, {10,13,1236 ,730,730,730 ,0,0,0}, + {10,1236,1158 ,730,730,730 ,0,0,0}, {1245,54,1237 ,730,730,730 ,0,0,0}, + {1238,15,1157 ,730,730,730 ,0,0,0}, {1238,1157,716 ,730,730,730 ,0,0,0}, + {1156,1159,716 ,730,730,730 ,0,0,0}, {1159,493,714 ,730,730,730 ,0,0,0}, + {713,493,492 ,730,730,730 ,0,0,0}, {489,487,708 ,730,730,730 ,0,0,0}, + {480,495,684 ,730,730,730 ,0,0,0}, {495,496,682 ,730,730,730 ,0,0,0}, + {815,382,374 ,730,730,730 ,0,0,0}, {381,252,380 ,730,730,730 ,0,0,0}, + {382,823,383 ,730,730,730 ,0,0,0}, {813,818,378 ,730,730,730 ,0,0,0}, + {820,827,388 ,730,730,730 ,0,0,0}, {374,375,817 ,730,730,730 ,0,0,0}, + {815,823,382 ,730,730,730 ,0,0,0}, {825,383,823 ,730,730,730 ,0,0,0}, + {697,694,9 ,730,730,730 ,0,0,0}, {694,507,9 ,730,730,730 ,0,0,0}, + {0,699,697 ,730,730,730 ,0,0,0}, {0,697,7 ,730,730,730 ,0,0,0}, + {5,1121,699 ,730,730,730 ,0,0,0}, {0,3,699 ,730,730,730 ,0,0,0}, + {749,1121,5 ,730,730,730 ,0,0,0}, {1246,749,1247 ,730,730,730 ,0,0,0}, + {749,5,1247 ,730,730,730 ,0,0,0}, {749,1246,1248 ,730,730,730 ,0,0,0}, + {749,474,476 ,730,730,730 ,0,0,0}, {749,1248,474 ,730,730,730 ,0,0,0}, + {1249,827,1250 ,730,730,730 ,0,0,0}, {749,476,750 ,730,730,730 ,0,0,0}, + {750,1251,1129 ,730,730,730 ,0,0,0}, {750,476,1251 ,730,730,730 ,0,0,0}, + {1148,750,1150 ,730,730,730 ,0,0,0}, {1128,1149,750 ,730,730,730 ,0,0,0}, + {829,1250,827 ,730,730,730 ,0,0,0}, {1150,1250,829 ,730,730,730 ,0,0,0}, + {1249,1151,827 ,730,730,730 ,0,0,0}, {385,820,388 ,730,730,730 ,0,0,0}, + {385,825,820 ,730,730,730 ,0,0,0}, {375,818,817 ,730,730,730 ,0,0,0}, + {378,380,813 ,730,730,730 ,0,0,0}, {1153,1122,1252 ,730,730,730 ,0,0,0}, + {290,218,220 ,730,730,730 ,0,0,0}, {1111,1110,1252 ,730,730,730 ,0,0,0}, + {1110,1153,1252 ,730,730,730 ,0,0,0}, {1073,1072,1111 ,730,730,730 ,0,0,0}, + {746,1072,1074 ,730,730,730 ,0,0,0}, {744,746,1112 ,730,730,730 ,0,0,0}, + {739,741,1075 ,730,730,730 ,0,0,0}, {740,739,1113 ,730,730,730 ,0,0,0}, + {733,740,1114 ,730,730,730 ,0,0,0}, {735,1116,1117 ,730,730,730 ,0,0,0}, + {725,736,1117 ,730,730,730 ,0,0,0}, {730,725,1118 ,730,730,730 ,0,0,0}, + {728,1115,1152 ,730,730,730 ,0,0,0}, {723,720,1152 ,730,730,730 ,0,0,0}, + {724,723,243 ,730,730,730 ,0,0,0}, {747,724,240 ,730,730,730 ,0,0,0}, + {278,280,238 ,730,730,730 ,0,0,0}, {276,278,237 ,730,730,730 ,0,0,0}, + {273,276,234 ,730,730,730 ,0,0,0}, {272,232,231 ,730,730,730 ,0,0,0}, + {267,270,231 ,730,730,730 ,0,0,0}, {265,229,210 ,730,730,730 ,0,0,0}, + {266,210,216 ,730,730,730 ,0,0,0}, {284,282,214 ,730,730,730 ,0,0,0}, + {282,266,216 ,730,730,730 ,0,0,0}, {217,287,214 ,730,730,730 ,0,0,0}, + {218,290,288 ,730,730,730 ,0,0,0}, {217,288,287 ,730,730,730 ,0,0,0}, + {220,293,290 ,730,730,730 ,0,0,0}, {227,294,220 ,730,730,730 ,0,0,0}, + {293,220,294 ,730,730,730 ,0,0,0}, {294,224,1155 ,730,730,730 ,0,0,0}, + {223,1155,224 ,730,730,730 ,0,0,0}, {1138,1137,761 ,730,730,730 ,0,0,0}, + {761,760,1138 ,730,730,730 ,0,0,0}, {769,768,1133 ,730,730,730 ,0,0,0}, + {766,1133,768 ,730,730,730 ,0,0,0}, {772,769,1134 ,730,730,730 ,0,0,0}, + {773,772,1142 ,730,730,730 ,0,0,0}, {775,773,1131 ,730,730,730 ,0,0,0}, + {1130,1132,779 ,730,730,730 ,0,0,0}, {779,778,1130 ,730,730,730 ,0,0,0}, + {1144,1253,1146 ,730,730,730 ,0,0,0}, {1253,1143,1254 ,730,730,730 ,0,0,0}, + {1143,1253,781 ,730,730,730 ,0,0,0}, {1254,1146,1253 ,730,730,730 ,0,0,0}, + {1144,1145,1136 ,730,730,730 ,0,0,0}, {1136,1140,1125 ,730,730,730 ,0,0,0}, + {209,1140,1141 ,730,730,730 ,0,0,0}, {206,1139,209 ,730,730,730 ,0,0,0}, + {204,811,206 ,730,730,730 ,0,0,0}, {807,808,203 ,730,730,730 ,0,0,0}, + {805,807,200 ,730,730,730 ,0,0,0}, {802,805,198 ,730,730,730 ,0,0,0}, + {801,802,197 ,730,730,730 ,0,0,0}, {798,176,797 ,730,730,730 ,0,0,0}, + {793,795,182 ,730,730,730 ,0,0,0}, {795,797,176 ,730,730,730 ,0,0,0}, + {183,790,180 ,730,730,730 ,0,0,0}, {180,793,182 ,730,730,730 ,0,0,0}, + {184,789,183 ,730,730,730 ,0,0,0}, {184,186,785 ,730,730,730 ,0,0,0}, + {184,787,789 ,730,730,730 ,0,0,0}, {186,193,783 ,730,730,730 ,0,0,0}, + {753,190,756 ,730,730,730 ,0,0,0}, {783,193,753 ,730,730,730 ,0,0,0}, + {757,190,189 ,730,730,730 ,0,0,0}, {1214,1091,557 ,730,730,730 ,0,0,0}, + {1214,557,559 ,730,730,730 ,0,0,0}, {531,1213,1092 ,730,730,730 ,0,0,0}, + {530,1213,531 ,730,730,730 ,0,0,0}, {535,534,1092 ,730,730,730 ,0,0,0}, + {537,535,1093 ,730,730,730 ,0,0,0}, {540,537,1094 ,730,730,730 ,0,0,0}, + {542,1209,1211 ,730,730,730 ,0,0,0}, {546,543,1211 ,730,730,730 ,0,0,0}, + {547,546,1210 ,730,730,730 ,0,0,0}, {549,547,1219 ,730,730,730 ,0,0,0}, + {1221,170,1223 ,730,730,730 ,0,0,0}, {552,1218,1220 ,730,730,730 ,0,0,0}, + {1255,555,1220 ,730,730,730 ,0,0,0}, {555,1256,1257 ,730,730,730 ,0,0,0}, + {1256,555,1255 ,730,730,730 ,0,0,0}, {1257,175,1221 ,730,730,730 ,0,0,0}, + {1256,175,1257 ,730,730,730 ,0,0,0}, {170,1217,1223 ,730,730,730 ,0,0,0}, + {166,1216,169 ,730,730,730 ,0,0,0}, {164,1215,166 ,730,730,730 ,0,0,0}, + {585,1215,163 ,730,730,730 ,0,0,0}, {582,585,161 ,730,730,730 ,0,0,0}, + {579,581,142 ,730,730,730 ,0,0,0}, {576,579,148 ,730,730,730 ,0,0,0}, + {149,575,146 ,730,730,730 ,0,0,0}, {146,576,148 ,730,730,730 ,0,0,0}, + {150,572,149 ,730,730,730 ,0,0,0}, {150,152,569 ,730,730,730 ,0,0,0}, + {150,571,572 ,730,730,730 ,0,0,0}, {567,159,564 ,730,730,730 ,0,0,0}, + {569,152,567 ,730,730,730 ,0,0,0}, {564,156,563 ,730,730,730 ,0,0,0}, + {155,563,156 ,730,730,730 ,0,0,0}, {1201,1199,618 ,730,730,730 ,0,0,0}, + {121,1199,1201 ,730,730,730 ,0,0,0}, {611,613,1193 ,730,730,730 ,0,0,0}, + {613,1186,1193 ,730,730,730 ,0,0,0}, {612,611,1189 ,730,730,730 ,0,0,0}, + {605,1190,1197 ,730,730,730 ,0,0,0}, {608,607,1197 ,730,730,730 ,0,0,0}, + {597,608,1188 ,730,730,730 ,0,0,0}, {602,597,1187 ,730,730,730 ,0,0,0}, + {592,600,1196 ,730,730,730 ,0,0,0}, {595,592,1198 ,730,730,730 ,0,0,0}, + {596,595,1191 ,730,730,730 ,0,0,0}, {336,619,1192 ,730,730,730 ,0,0,0}, + {334,336,1195 ,730,730,730 ,0,0,0}, {332,334,1194 ,730,730,730 ,0,0,0}, + {329,332,141 ,730,730,730 ,0,0,0}, {326,328,138 ,730,730,730 ,0,0,0}, + {323,326,136 ,730,730,730 ,0,0,0}, {321,323,135 ,730,730,730 ,0,0,0}, + {322,132,130 ,730,730,730 ,0,0,0}, {340,338,130 ,730,730,730 ,0,0,0}, + {343,340,129 ,730,730,730 ,0,0,0}, {344,343,127 ,730,730,730 ,0,0,0}, + {114,349,108 ,730,730,730 ,0,0,0}, {346,344,108 ,730,730,730 ,0,0,0}, + {350,114,112 ,730,730,730 ,0,0,0}, {114,350,349 ,730,730,730 ,0,0,0}, + {112,115,1203 ,730,730,730 ,0,0,0}, {1183,1203,116 ,730,730,730 ,0,0,0}, + {115,116,1203 ,730,730,730 ,0,0,0}, {1184,125,1204 ,730,730,730 ,0,0,0}, + {122,1202,125 ,730,730,730 ,0,0,0}, {1204,125,1202 ,730,730,730 ,0,0,0}, + {121,1202,122 ,730,730,730 ,0,0,0}, {1095,1088,835 ,730,730,730 ,0,0,0}, + {1095,835,834 ,730,730,730 ,0,0,0}, {841,840,1097 ,730,730,730 ,0,0,0}, + {840,1096,1097 ,730,730,730 ,0,0,0}, {843,841,1086 ,730,730,730 ,0,0,0}, + {846,843,1087 ,730,730,730 ,0,0,0}, {847,846,1084 ,730,730,730 ,0,0,0}, + {852,849,1085 ,730,730,730 ,0,0,0}, {1098,1079,853 ,730,730,730 ,0,0,0}, + {853,852,1098 ,730,730,730 ,0,0,0}, {104,1103,107 ,730,730,730 ,0,0,0}, + {1258,1078,1080 ,730,730,730 ,0,0,0}, {1079,1078,853 ,730,730,730 ,0,0,0}, + {1107,1258,1108 ,730,730,730 ,0,0,0}, {1258,1107,1078 ,730,730,730 ,0,0,0}, + {1103,1239,107 ,730,730,730 ,0,0,0}, {1100,107,1239 ,730,730,730 ,0,0,0}, + {1100,1239,1101 ,730,730,730 ,0,0,0}, {104,1083,1103 ,730,730,730 ,0,0,0}, + {104,102,1082 ,730,730,730 ,0,0,0}, {98,1090,101 ,730,730,730 ,0,0,0}, + {96,1089,98 ,730,730,730 ,0,0,0}, {877,1089,95 ,730,730,730 ,0,0,0}, + {875,93,74 ,730,730,730 ,0,0,0}, {874,74,80 ,730,730,730 ,0,0,0}, + {869,872,78 ,730,730,730 ,0,0,0}, {872,874,80 ,730,730,730 ,0,0,0}, + {81,866,868 ,730,730,730 ,0,0,0}, {78,868,869 ,730,730,730 ,0,0,0}, + {82,863,866 ,730,730,730 ,0,0,0}, {84,91,862 ,730,730,730 ,0,0,0}, + {82,84,863 ,730,730,730 ,0,0,0}, {860,88,857 ,730,730,730 ,0,0,0}, + {862,91,860 ,730,730,730 ,0,0,0}, {87,857,88 ,730,730,730 ,0,0,0}, + {1259,1177,1260 ,730,730,730 ,0,0,0}, {1177,1161,1260 ,730,730,730 ,0,0,0}, + {1173,1174,1259 ,730,730,730 ,0,0,0}, {1174,1177,1259 ,730,730,730 ,0,0,0}, + {1168,1167,1173 ,730,730,730 ,0,0,0}, {678,1167,1169 ,730,730,730 ,0,0,0}, + {675,678,1165 ,730,730,730 ,0,0,0}, {673,675,1166 ,730,730,730 ,0,0,0}, + {671,673,1175 ,730,730,730 ,0,0,0}, {665,667,1172 ,730,730,730 ,0,0,0}, + {670,665,1164 ,730,730,730 ,0,0,0}, {659,670,1163 ,730,730,730 ,0,0,0}, + {660,659,1170 ,730,730,730 ,0,0,0}, {663,660,1171 ,730,730,730 ,0,0,0}, + {679,663,1162 ,730,730,730 ,0,0,0}, {308,679,73 ,730,730,730 ,0,0,0}, + {303,306,70 ,730,730,730 ,0,0,0}, {302,303,68 ,730,730,730 ,0,0,0}, + {300,302,67 ,730,730,730 ,0,0,0}, {296,300,64 ,730,730,730 ,0,0,0}, + {297,296,62 ,730,730,730 ,0,0,0}, {310,297,61 ,730,730,730 ,0,0,0}, + {313,310,59 ,730,730,730 ,0,0,0}, {46,316,40 ,730,730,730 ,0,0,0}, + {40,314,59 ,730,730,730 ,0,0,0}, {318,46,44 ,730,730,730 ,0,0,0}, + {46,318,316 ,730,730,730 ,0,0,0}, {44,47,1176 ,730,730,730 ,0,0,0}, + {1179,1176,48 ,730,730,730 ,0,0,0}, {47,48,1176 ,730,730,730 ,0,0,0}, + {50,57,1179 ,730,730,730 ,0,0,0}, {54,1245,57 ,730,730,730 ,0,0,0}, + {1179,57,1245 ,730,730,730 ,0,0,0}, {53,13,54 ,730,730,730 ,0,0,0}, + {468,470,245 ,730,730,730 ,0,0,0}, {414,361,1225 ,730,730,730 ,0,0,0}, + {361,360,1225 ,730,730,730 ,0,0,0}, {228,1009,1124 ,731,732,733 ,0,0,0}, + {1017,1111,1016 ,734,735,736 ,0,0,0}, {1252,1122,1005 ,737,738,739 ,0,0,0}, + {1112,1015,1075 ,740,741,742 ,0,0,0}, {1064,1063,1074 ,743,744,745 ,0,0,0}, + {1013,1116,1114 ,746,747,748 ,0,0,0}, {1014,1113,1006 ,749,750,751 ,0,0,0}, + {1011,1118,1117 ,752,753,754 ,0,0,0}, {1117,1116,1012 ,754,747,755 ,0,0,0}, + {1118,1010,1115 ,753,756,757 ,0,0,0}, {1010,1118,1011 ,756,753,752 ,0,0,0}, + {1152,1115,985 ,758,757,759 ,0,0,0}, {1010,985,1115 ,756,759,757 ,0,0,0}, + {984,243,1152 ,760,761,758 ,0,0,0}, {1152,985,984 ,758,759,760 ,0,0,0}, + {242,243,984 ,761,761,760 ,0,0,0}, {1014,1013,1114 ,749,746,748 ,0,0,0}, + {1116,1013,1012 ,747,746,755 ,0,0,0}, {1011,1117,1012 ,752,754,755 ,0,0,0}, + {1014,1114,1113 ,749,748,750 ,0,0,0}, {1006,1113,1075 ,751,750,742 ,0,0,0}, + {1015,1112,1063 ,741,740,744 ,0,0,0}, {1015,1006,1075 ,741,751,742 ,0,0,0}, + {1064,1074,1073 ,743,745,762 ,0,0,0}, {1074,1063,1112 ,745,744,740 ,0,0,0}, + {1073,1111,1017 ,762,735,734 ,0,0,0}, {1073,1017,1064 ,762,734,743 ,0,0,0}, + {1005,1016,1252 ,739,736,737 ,0,0,0}, {1111,1252,1016 ,735,737,736 ,0,0,0}, + {1122,1009,1005 ,738,732,739 ,0,0,0}, {228,1124,223 ,731,733,35 ,0,0,0}, + {1009,1122,1124 ,732,738,733 ,0,0,0}, {194,897,1138 ,763,764,765 ,0,0,0}, + {894,1133,893 ,766,767,768 ,0,0,0}, {1135,1137,895 ,769,770,771 ,0,0,0}, + {1131,888,1130 ,772,773,774 ,0,0,0}, {1024,889,1142 ,775,776,777 ,0,0,0}, + {1021,1254,1143 ,778,779,780 ,0,0,0}, {1020,1132,1023 ,781,782,783 ,0,0,0}, + {1030,1145,1146 ,784,785,786 ,0,0,0}, {1146,1254,1026 ,786,779,787 ,0,0,0}, + {1145,1027,1136 ,785,788,789 ,0,0,0}, {1027,1145,1030 ,788,785,784 ,0,0,0}, + {1141,1136,1029 ,790,789,791 ,0,0,0}, {1027,1029,1136 ,788,791,789 ,0,0,0}, + {997,209,1141 ,792,793,790 ,0,0,0}, {1141,1029,997 ,790,791,792 ,0,0,0}, + {208,209,997 ,793,793,792 ,0,0,0}, {1020,1021,1143 ,781,778,780 ,0,0,0}, + {1254,1021,1026 ,779,778,787 ,0,0,0}, {1030,1146,1026 ,784,786,787 ,0,0,0}, + {1020,1143,1132 ,781,780,782 ,0,0,0}, {1023,1132,1130 ,783,782,774 ,0,0,0}, + {888,1131,889 ,773,772,776 ,0,0,0}, {888,1023,1130 ,773,783,774 ,0,0,0}, + {1024,1142,1134 ,775,777,794 ,0,0,0}, {1142,889,1131 ,777,776,772 ,0,0,0}, + {1134,1133,894 ,794,767,766 ,0,0,0}, {1134,894,1024 ,794,766,775 ,0,0,0}, + {895,893,1135 ,771,768,769 ,0,0,0}, {1133,1135,893 ,767,769,768 ,0,0,0}, + {1137,897,895 ,770,764,771 ,0,0,0}, {194,1138,189 ,763,765,126 ,0,0,0}, + {897,1137,1138 ,764,770,765 ,0,0,0}, {160,935,1214 ,763,795,796 ,0,0,0}, + {937,1213,936 ,797,798,799 ,0,0,0}, {1212,1091,934 ,800,801,802 ,0,0,0}, + {1094,938,1209 ,803,804,805 ,0,0,0}, {933,939,1093 ,806,807,808 ,0,0,0}, + {890,1219,1210 ,809,810,811 ,0,0,0}, {891,1211,940 ,812,813,814 ,0,0,0}, + {932,1220,1218 ,815,816,817 ,0,0,0}, {1218,1219,931 ,817,810,818 ,0,0,0}, + {1220,942,1255 ,816,819,820 ,0,0,0}, {942,1220,932 ,819,816,815 ,0,0,0}, + {1256,1255,941 ,821,820,822 ,0,0,0}, {942,941,1255 ,819,822,820 ,0,0,0}, + {930,175,1256 ,823,793,821 ,0,0,0}, {1256,941,930 ,821,822,823 ,0,0,0}, + {174,175,930 ,793,793,823 ,0,0,0}, {891,890,1210 ,812,809,811 ,0,0,0}, + {1219,890,931 ,810,809,818 ,0,0,0}, {932,1218,931 ,815,817,818 ,0,0,0}, + {891,1210,1211 ,812,811,813 ,0,0,0}, {940,1211,1209 ,814,813,805 ,0,0,0}, + {938,1094,939 ,804,803,807 ,0,0,0}, {938,940,1209 ,804,814,805 ,0,0,0}, + {933,1093,1092 ,806,808,824 ,0,0,0}, {1093,939,1094 ,808,807,803 ,0,0,0}, + {1092,1213,937 ,824,798,797 ,0,0,0}, {1092,937,933 ,824,797,806 ,0,0,0}, + {934,936,1212 ,802,799,800 ,0,0,0}, {1213,1212,936 ,798,800,799 ,0,0,0}, + {1091,935,934 ,801,795,802 ,0,0,0}, {160,1214,155 ,763,796,126 ,0,0,0}, + {935,1091,1214 ,795,801,796 ,0,0,0}, {126,1065,1199 ,731,795,796 ,0,0,0}, + {963,1193,964 ,825,826,799 ,0,0,0}, {1186,1200,965 ,827,828,829 ,0,0,0}, + {1197,919,1188 ,830,831,805 ,0,0,0}, {960,920,1190 ,832,833,834 ,0,0,0}, + {918,1198,1196 ,835,836,837 ,0,0,0}, {917,1187,958 ,838,839,814 ,0,0,0}, + {954,1192,1191 ,840,841,842 ,0,0,0}, {1191,1198,953 ,842,836,843 ,0,0,0}, + {1192,957,1195 ,841,844,845 ,0,0,0}, {957,1192,954 ,844,841,840 ,0,0,0}, + {1194,1195,955 ,846,845,847 ,0,0,0}, {957,955,1195 ,844,847,845 ,0,0,0}, + {956,141,1194 ,848,761,846 ,0,0,0}, {1194,955,956 ,846,847,848 ,0,0,0}, + {140,141,956 ,761,761,848 ,0,0,0}, {917,918,1196 ,838,835,837 ,0,0,0}, + {1198,918,953 ,836,835,843 ,0,0,0}, {954,1191,953 ,840,842,843 ,0,0,0}, + {917,1196,1187 ,838,837,839 ,0,0,0}, {958,1187,1188 ,814,839,805 ,0,0,0}, + {919,1197,920 ,831,830,833 ,0,0,0}, {919,958,1188 ,831,814,805 ,0,0,0}, + {960,1190,1189 ,832,834,849 ,0,0,0}, {1190,920,1197 ,834,833,830 ,0,0,0}, + {1189,1193,963 ,849,826,825 ,0,0,0}, {1189,963,960 ,849,825,832 ,0,0,0}, + {965,964,1186 ,829,799,827 ,0,0,0}, {1193,1186,964 ,826,827,799 ,0,0,0}, + {1200,1065,965 ,828,795,829 ,0,0,0}, {126,1199,121 ,731,796,35 ,0,0,0}, + {1065,1200,1199 ,795,828,796 ,0,0,0}, {92,880,1095 ,850,851,852 ,0,0,0}, + {896,1097,892 ,853,854,855 ,0,0,0}, {1096,1088,884 ,856,801,857 ,0,0,0}, + {1084,900,1085 ,830,858,859 ,0,0,0}, {898,899,1087 ,860,861,862 ,0,0,0}, + {903,1080,1079 ,863,864,865 ,0,0,0}, {902,1098,901 ,866,867,868 ,0,0,0}, + {910,1108,1258 ,869,870,871 ,0,0,0}, {1258,1080,905 ,871,864,872 ,0,0,0}, + {1108,1067,1109 ,870,873,874 ,0,0,0}, {1067,1108,910 ,873,870,869 ,0,0,0}, + {1100,1109,908 ,875,874,876 ,0,0,0}, {1067,908,1109 ,873,876,874 ,0,0,0}, + {906,107,1100 ,877,82,875 ,0,0,0}, {1100,908,906 ,875,876,877 ,0,0,0}, + {106,107,906 ,878,82,877 ,0,0,0}, {902,903,1079 ,866,863,865 ,0,0,0}, + {1080,903,905 ,864,863,872 ,0,0,0}, {910,1258,905 ,869,871,872 ,0,0,0}, + {902,1079,1098 ,866,865,867 ,0,0,0}, {901,1098,1085 ,868,867,859 ,0,0,0}, + {900,1084,899 ,858,830,861 ,0,0,0}, {900,901,1085 ,858,868,859 ,0,0,0}, + {898,1087,1086 ,860,862,879 ,0,0,0}, {1087,899,1084 ,862,861,830 ,0,0,0}, + {1086,1097,896 ,879,854,853 ,0,0,0}, {1086,896,898 ,879,853,860 ,0,0,0}, + {884,892,1096 ,857,855,856 ,0,0,0}, {1097,1096,892 ,854,856,855 ,0,0,0}, + {1088,880,884 ,801,851,857 ,0,0,0}, {92,1095,87 ,850,852,850 ,0,0,0}, + {880,1088,1095 ,851,801,852 ,0,0,0}, {58,974,1161 ,731,851,880 ,0,0,0}, + {1069,1173,978 ,881,882,855 ,0,0,0}, {1259,1260,973 ,856,801,857 ,0,0,0}, + {1165,976,1166 ,883,884,859 ,0,0,0}, {1068,988,1169 ,860,885,834 ,0,0,0}, + {983,1164,1172 ,886,887,888 ,0,0,0}, {881,1175,977 ,889,890,868 ,0,0,0}, + {981,1170,1163 ,891,892,893 ,0,0,0}, {1163,1164,982 ,893,887,894 ,0,0,0}, + {1170,980,1171 ,892,895,896 ,0,0,0}, {980,1170,981 ,895,892,891 ,0,0,0}, + {1162,1171,979 ,897,896,898 ,0,0,0}, {980,979,1171 ,895,898,896 ,0,0,0}, + {962,73,1162 ,899,761,897 ,0,0,0}, {1162,979,962 ,897,898,899 ,0,0,0}, + {72,73,962 ,761,761,899 ,0,0,0}, {881,983,1172 ,889,886,888 ,0,0,0}, + {1164,983,982 ,887,886,894 ,0,0,0}, {981,1163,982 ,891,893,894 ,0,0,0}, + {881,1172,1175 ,889,888,890 ,0,0,0}, {977,1175,1166 ,868,890,859 ,0,0,0}, + {976,1165,988 ,884,883,885 ,0,0,0}, {976,977,1166 ,884,868,859 ,0,0,0}, + {1068,1169,1168 ,860,834,849 ,0,0,0}, {1169,988,1165 ,834,885,883 ,0,0,0}, + {1168,1173,1069 ,849,882,881 ,0,0,0}, {1168,1069,1068 ,849,881,860 ,0,0,0}, + {973,978,1259 ,857,855,856 ,0,0,0}, {1173,1259,978 ,882,856,855 ,0,0,0}, + {1260,974,973 ,801,851,857 ,0,0,0}, {58,1161,53 ,731,880,35 ,0,0,0}, + {974,1260,1161 ,851,801,880 ,0,0,0}, {36,968,1208 ,20,900,900 ,0,0,0}, + {952,443,1185 ,901,336,901 ,0,0,0}, {1185,1232,1043 ,901,902,902 ,0,0,0}, + {444,443,952 ,336,336,901 ,0,0,0}, {968,1232,1208 ,900,902,900 ,0,0,0}, + {1232,968,1043 ,902,900,902 ,0,0,0}, {952,1185,1043 ,901,901,902 ,0,0,0}, + {1208,35,36 ,900,20,20 ,0,0,0}, {1229,1071,948 ,903,904,905 ,0,0,0}, + {947,924,1228 ,906,907,908 ,0,0,0}, {947,1228,1229 ,906,908,903 ,0,0,0}, + {947,1229,948 ,906,903,905 ,0,0,0}, {1230,1231,923 ,909,910,911 ,0,0,0}, + {1231,924,923 ,910,907,911 ,0,0,0}, {1228,924,1231 ,908,907,910 ,0,0,0}, + {949,879,878 ,912,21,21 ,0,0,0}, {949,878,1230 ,912,21,909 ,0,0,0}, + {923,949,1230 ,911,912,909 ,0,0,0}, {948,1071,1046 ,905,904,913 ,0,0,0}, + {1044,1046,1227 ,914,913,915 ,0,0,0}, {1071,1227,1046 ,904,915,913 ,0,0,0}, + {1226,1045,1044 ,916,917,914 ,0,0,0}, {1044,1227,1226 ,914,915,916 ,0,0,0}, + {1045,1182,421 ,917,918,322 ,0,0,0}, {1182,1045,1226 ,918,917,916 ,0,0,0}, + {1182,423,421 ,918,322,322 ,0,0,0}, {26,1062,1178 ,15,919,920 ,0,0,0}, + {993,424,1158 ,921,922,921 ,0,0,0}, {1158,1236,987 ,921,923,923 ,0,0,0}, + {425,424,993 ,924,922,921 ,0,0,0}, {1062,1236,1178 ,919,923,920 ,0,0,0}, + {1236,1062,987 ,923,919,923 ,0,0,0}, {993,1158,987 ,921,921,923 ,0,0,0}, + {1178,25,26 ,920,15,15 ,0,0,0}, {16,994,1157 ,8,925,925 ,0,0,0}, + {969,493,1159 ,926,372,926 ,0,0,0}, {1159,1156,1061 ,926,927,927 ,0,0,0}, + {494,493,969 ,372,372,926 ,0,0,0}, {994,1156,1157 ,925,927,925 ,0,0,0}, + {1156,994,1061 ,927,925,927 ,0,0,0}, {969,1159,1061 ,926,926,927 ,0,0,0}, + {1157,15,16 ,925,8,8 ,0,0,0}, {1240,1239,907 ,928,929,930 ,0,0,0}, + {1240,1047,1181 ,928,931,932 ,0,0,0}, {1047,1240,907 ,931,928,930 ,0,0,0}, + {914,1233,1039 ,933,934,935 ,0,0,0}, {1039,1233,1181 ,935,934,932 ,0,0,0}, + {406,1234,913 ,314,936,937 ,0,0,0}, {913,407,406 ,937,314,314 ,0,0,0}, + {913,1234,914 ,937,936,933 ,0,0,0}, {914,1234,1233 ,933,936,934 ,0,0,0}, + {1181,1047,1039 ,932,931,935 ,0,0,0}, {907,1239,1048 ,930,929,938 ,0,0,0}, + {991,1048,1105 ,939,938,940 ,0,0,0}, {1239,1105,1048 ,929,940,938 ,0,0,0}, + {1104,992,991 ,941,942,939 ,0,0,0}, {991,1105,1104 ,939,940,941 ,0,0,0}, + {992,1244,426 ,942,943,944 ,0,0,0}, {1244,992,1104 ,943,942,941 ,0,0,0}, + {1244,427,426 ,943,324,944 ,0,0,0}, {1103,1102,1037 ,945,946,947 ,0,0,0}, + {1103,916,1242 ,945,948,949 ,0,0,0}, {916,1103,1037 ,948,945,947 ,0,0,0}, + {1036,1106,915 ,950,951,952 ,0,0,0}, {915,1106,1242 ,952,951,949 ,0,0,0}, + {830,1243,990 ,953,954,955 ,0,0,0}, {990,831,830 ,955,21,953 ,0,0,0}, + {990,1243,1036 ,955,954,950 ,0,0,0}, {1036,1243,1106 ,950,954,951 ,0,0,0}, + {1242,916,915 ,949,948,952 ,0,0,0}, {1037,1102,996 ,947,946,956 ,0,0,0}, + {1050,996,1077 ,957,956,958 ,0,0,0}, {1102,1077,996 ,946,958,956 ,0,0,0}, + {1076,1051,1050 ,959,960,957 ,0,0,0}, {1050,1077,1076 ,957,958,959 ,0,0,0}, + {1051,1081,471 ,960,961,358 ,0,0,0}, {1081,1051,1076 ,961,960,959 ,0,0,0}, + {1081,473,471 ,961,358,358 ,0,0,0}, {1150,1149,1057 ,962,963,964 ,0,0,0}, + {1035,1054,1250 ,965,966,967 ,0,0,0}, {1035,1250,1150 ,965,967,962 ,0,0,0}, + {1035,1150,1057 ,965,962,964 ,0,0,0}, {1151,1249,1055 ,968,969,970 ,0,0,0}, + {1249,1054,1055 ,969,966,970 ,0,0,0}, {1250,1054,1249 ,967,966,969 ,0,0,0}, + {1001,389,388 ,971,304,304 ,0,0,0}, {1001,388,1151 ,971,304,968 ,0,0,0}, + {1055,1001,1151 ,970,971,968 ,0,0,0}, {1057,1149,1056 ,964,963,972 ,0,0,0}, + {1059,1056,1128 ,973,972,974 ,0,0,0}, {1149,1128,1056 ,963,974,972 ,0,0,0}, + {1129,1058,1059 ,975,976,973 ,0,0,0}, {1059,1128,1129 ,973,974,975 ,0,0,0}, + {1058,1251,475 ,976,977,324 ,0,0,0}, {1251,1058,1129 ,977,976,975 ,0,0,0}, + {1251,476,475 ,977,978,324 ,0,0,0}, {6,1004,1247 ,3,979,979 ,0,0,0}, + {1060,474,1248 ,980,324,980 ,0,0,0}, {1248,1246,1003 ,980,981,981 ,0,0,0}, + {477,474,1060 ,982,324,980 ,0,0,0}, {1004,1246,1247 ,979,981,979 ,0,0,0}, + {1246,1004,1003 ,981,979,981 ,0,0,0}, {1060,1248,1003 ,980,980,981 ,0,0,0}, + {1247,5,6 ,979,3,3 ,0,0,0}, {1154,887,1123 ,983,983,984 ,0,0,0}, + {1008,1007,1155 ,984,985,986 ,0,0,0}, {1123,1008,1155 ,984,984,986 ,0,0,0}, + {1007,295,294 ,985,235,235 ,0,0,0}, {1155,1007,294 ,986,985,235 ,0,0,0}, + {1123,887,1008 ,984,983,984 ,0,0,0}, {1002,887,1154 ,987,983,983 ,0,0,0}, + {1002,1119,751 ,987,987,988 ,0,0,0}, {1119,1002,1154 ,987,987,983 ,0,0,0}, + {1119,749,751 ,987,988,988 ,0,0,0}, {1018,886,1153 ,989,990,990 ,0,0,0}, + {885,1121,1120 ,991,992,991 ,0,0,0}, {1153,886,1120 ,990,990,991 ,0,0,0}, + {698,699,1022 ,508,508,992 ,0,0,0}, {1121,885,1022 ,992,991,992 ,0,0,0}, + {1022,699,1121 ,992,508,992 ,0,0,0}, {885,1120,886 ,991,991,990 ,0,0,0}, + {1153,1110,1018 ,990,989,989 ,0,0,0}, {1110,1072,1019 ,989,993,994 ,0,0,0}, + {1019,1018,1110 ,994,989,989 ,0,0,0}, {745,1072,746 ,546,993,546 ,0,0,0}, + {1072,745,1019 ,993,546,994 ,0,0,0}, {970,883,1245 ,995,996,996 ,0,0,0}, + {882,1176,1179 ,997,998,997 ,0,0,0}, {1245,883,1179 ,996,996,997 ,0,0,0}, + {319,318,986 ,257,257,998 ,0,0,0}, {1176,882,986 ,998,997,998 ,0,0,0}, + {986,318,1176 ,998,257,998 ,0,0,0}, {882,1179,883 ,997,997,996 ,0,0,0}, + {1245,1237,970 ,996,995,995 ,0,0,0}, {1237,1238,971 ,995,999,999 ,0,0,0}, + {971,970,1237 ,999,995,995 ,0,0,0}, {717,1238,716 ,525,999,525 ,0,0,0}, + {1238,717,971 ,999,525,999 ,0,0,0}, {1053,972,1177 ,1000,1001,1001 ,0,0,0}, + {975,1235,1160 ,1002,1003,1004 ,0,0,0}, {1177,972,1160 ,1001,1001,1004 ,0,0,0}, + {638,639,1052 ,508,508,1003 ,0,0,0}, {1235,975,1052 ,1003,1002,1003 ,0,0,0}, + {1052,639,1235 ,1003,508,1003 ,0,0,0}, {975,1160,972 ,1002,1004,1001 ,0,0,0}, + {1177,1174,1053 ,1001,1000,1000 ,0,0,0}, {1174,1167,989 ,1000,1005,1005 ,0,0,0}, + {989,1053,1174 ,1005,1000,1000 ,0,0,0}, {677,1167,678 ,546,1005,546 ,0,0,0}, + {1167,677,989 ,1005,546,1005 ,0,0,0}, {966,961,1184 ,1006,1007,1007 ,0,0,0}, + {921,1203,1183 ,1008,1009,1008 ,0,0,0}, {1184,961,1183 ,1007,1007,1008 ,0,0,0}, + {351,350,959 ,257,257,1009 ,0,0,0}, {1203,921,959 ,1009,1008,1009 ,0,0,0}, + {959,350,1203 ,1009,257,1009 ,0,0,0}, {921,1183,961 ,1008,1008,1007 ,0,0,0}, + {1184,1205,966 ,1007,1006,1006 ,0,0,0}, {1205,1207,950 ,1006,1010,1010 ,0,0,0}, + {950,966,1205 ,1010,1006,1006 ,0,0,0}, {657,1207,656 ,525,1010,525 ,0,0,0}, + {1207,657,950 ,1010,525,1010 ,0,0,0}, {1202,922,1204 ,1011,1011,1012 ,0,0,0}, + {967,951,1206 ,1012,1013,1013 ,0,0,0}, {1204,967,1206 ,1012,1012,1013 ,0,0,0}, + {951,588,587 ,1013,324,324 ,0,0,0}, {1206,951,587 ,1013,1013,324 ,0,0,0}, + {1204,922,967 ,1012,1011,1012 ,0,0,0}, {1066,922,1202 ,1014,1011,1011 ,0,0,0}, + {1066,1201,617 ,1014,1014,488 ,0,0,0}, {1201,1066,1202 ,1014,1014,1011 ,0,0,0}, + {1201,618,617 ,1014,488,488 ,0,0,0}, {1223,928,1221 ,1015,1015,1016 ,0,0,0}, + {944,929,1257 ,1016,1017,1017 ,0,0,0}, {1221,944,1257 ,1016,1016,1017 ,0,0,0}, + {929,556,555 ,1017,427,427 ,0,0,0}, {1257,929,555 ,1017,1017,427 ,0,0,0}, + {1221,928,944 ,1016,1015,1016 ,0,0,0}, {945,928,1223 ,1018,1015,1015 ,0,0,0}, + {945,1224,589 ,1018,1018,1019 ,0,0,0}, {1224,945,1223 ,1018,1018,1015 ,0,0,0}, + {1224,586,589 ,1018,324,1019 ,0,0,0}, {943,927,1217 ,1020,1021,1021 ,0,0,0}, + {926,1070,1222 ,1022,1023,1022 ,0,0,0}, {1217,927,1222 ,1021,1021,1022 ,0,0,0}, + {370,371,946 ,205,205,1023 ,0,0,0}, {1070,926,946 ,1023,1022,1023 ,0,0,0}, + {946,371,1070 ,1023,205,1023 ,0,0,0}, {926,1222,927 ,1022,1022,1021 ,0,0,0}, + {1217,1216,943 ,1021,1020,1020 ,0,0,0}, {1216,1215,925 ,1020,1024,1024 ,0,0,0}, + {925,943,1216 ,1024,1020,1020 ,0,0,0}, {584,1215,585 ,456,1024,456 ,0,0,0}, + {1215,584,925 ,1024,456,1024 ,0,0,0}, {1041,909,1099 ,1025,1026,1026 ,0,0,0}, + {911,1078,1107 ,1027,1028,1027 ,0,0,0}, {1099,909,1107 ,1026,1026,1027 ,0,0,0}, + {855,853,904 ,641,641,1028 ,0,0,0}, {1078,911,904 ,1028,1027,1028 ,0,0,0}, + {904,853,1078 ,1028,641,1028 ,0,0,0}, {911,1107,909 ,1027,1027,1026 ,0,0,0}, + {1099,1101,1041 ,1026,1025,1025 ,0,0,0}, {1101,1180,1040 ,1025,1029,1029 ,0,0,0}, + {1040,1041,1101 ,1029,1025,1025 ,0,0,0}, {524,1180,525 ,396,1029,396 ,0,0,0}, + {1180,524,1040 ,1029,396,1029 ,0,0,0}, {912,1049,1082 ,1030,1031,1031 ,0,0,0}, + {1038,1241,1083 ,1032,1033,1032 ,0,0,0}, {1082,1049,1083 ,1031,1031,1032 ,0,0,0}, + {262,263,995 ,205,205,1033 ,0,0,0}, {1241,1038,995 ,1033,1032,1033 ,0,0,0}, + {995,263,1241 ,1033,205,1033 ,0,0,0}, {1038,1083,1049 ,1032,1032,1031 ,0,0,0}, + {1082,1090,912 ,1031,1030,1030 ,0,0,0}, {1090,1089,1042 ,1030,1034,1034 ,0,0,0}, + {1042,912,1090 ,1034,1030,1030 ,0,0,0}, {876,1089,877 ,456,1034,456 ,0,0,0}, + {1089,876,1042 ,1034,456,1034 ,0,0,0}, {1034,1032,1127 ,1035,1036,1036 ,0,0,0}, + {1028,1253,1144 ,1037,1038,1037 ,0,0,0}, {1127,1032,1144 ,1036,1036,1037 ,0,0,0}, + {782,781,1025 ,641,641,1038 ,0,0,0}, {1253,1028,1025 ,1038,1037,1038 ,0,0,0}, + {1025,781,1253 ,1038,641,1038 ,0,0,0}, {1028,1144,1032 ,1037,1037,1036 ,0,0,0}, + {1127,1126,1034 ,1036,1035,1035 ,0,0,0}, {1126,1148,999 ,1035,1039,1040 ,0,0,0}, + {999,1034,1126 ,1040,1035,1035 ,0,0,0}, {828,1148,829 ,396,1039,396 ,0,0,0}, + {1148,828,999 ,1039,396,1040 ,0,0,0}, {1140,998,1125 ,1041,1041,1042 ,0,0,0}, + {1031,1000,1147 ,1042,1043,1044 ,0,0,0}, {1125,1031,1147 ,1042,1042,1044 ,0,0,0}, + {1000,748,750 ,1043,1045,1045 ,0,0,0}, {1147,1000,750 ,1044,1043,1045 ,0,0,0}, + {1125,998,1031 ,1042,1041,1042 ,0,0,0}, {1033,998,1140 ,1046,1041,1041 ,0,0,0}, + {1033,1139,810 ,1046,1046,670 ,0,0,0}, {1139,1033,1140 ,1046,1046,1041 ,0,0,0}, + {1139,811,810 ,1046,670,670 ,0,0,0} +// BladeProtector2.prt + , {1261,1262,1263 ,126,1047,1048 ,0,0,0}, {1264,1265,1266 ,1049,1050,1051 ,0,0,0}, + {1267,1261,1263 ,1052,126,1048 ,0,0,0}, {1266,1265,1267 ,1051,1050,1052 ,0,0,0}, + {1265,1264,1268 ,1050,1049,1053 ,0,0,0}, {1263,1266,1267 ,1048,1051,1052 ,0,0,0}, + {1269,1270,1271 ,1054,1055,1056 ,0,0,0}, {1270,1272,1271 ,1055,1057,1056 ,0,0,0}, + {1268,1273,1269 ,1053,1058,1054 ,0,0,0}, {1270,1269,1273 ,1055,1054,1058 ,0,0,0}, + {1274,1275,1276 ,21,1059,1060 ,0,0,0}, {1277,1278,1272 ,1061,1062,1057 ,0,0,0}, + {1275,1278,1277 ,1059,1062,1061 ,0,0,0}, {1275,1277,1276 ,1059,1061,1060 ,0,0,0}, + {1276,1279,1274 ,1060,1063,21 ,0,0,0}, {1271,1272,1278 ,1056,1057,1062 ,0,0,0}, + {1268,1264,1273 ,1053,1049,1058 ,0,0,0}, {1261,1280,1262 ,126,1064,1047 ,0,0,0}, + {1281,1280,1282 ,1065,1064,1066 ,0,0,0}, {1280,1281,1262 ,1064,1065,1047 ,0,0,0}, + {1283,1284,1282 ,1067,1068,1066 ,0,0,0}, {1281,1282,1284 ,1065,1066,1068 ,0,0,0}, + {1283,1285,1286 ,1067,1069,1070 ,0,0,0}, {1286,1284,1283 ,1070,1068,1067 ,0,0,0}, + {1287,1285,1288 ,1071,1069,1072 ,0,0,0}, {1285,1287,1286 ,1069,1071,1070 ,0,0,0}, + {1289,1290,1288 ,1073,1074,1072 ,0,0,0}, {1287,1288,1290 ,1071,1072,1074 ,0,0,0}, + {1289,1291,1292 ,1073,1075,1076 ,0,0,0}, {1292,1290,1289 ,1076,1074,1073 ,0,0,0}, + {1293,1291,1294 ,1077,1075,1078 ,0,0,0}, {1291,1293,1292 ,1075,1077,1076 ,0,0,0}, + {1295,1296,1297 ,126,1079,126 ,0,0,0}, {1298,1299,1300 ,1080,1081,1082 ,0,0,0}, + {1301,1295,1297 ,1083,126,126 ,0,0,0}, {1300,1299,1301 ,1082,1081,1083 ,0,0,0}, + {1299,1298,1302 ,1081,1080,1084 ,0,0,0}, {1297,1300,1301 ,126,1082,1083 ,0,0,0}, + {1303,1304,1305 ,1085,1086,1087 ,0,0,0}, {1304,1306,1305 ,1086,1088,1087 ,0,0,0}, + {1302,1307,1303 ,1084,1089,1085 ,0,0,0}, {1304,1303,1307 ,1086,1085,1089 ,0,0,0}, + {1308,1309,1310 ,1090,1091,1092 ,0,0,0}, {1311,1312,1306 ,1093,1094,1088 ,0,0,0}, + {1309,1312,1311 ,1091,1094,1093 ,0,0,0}, {1309,1311,1310 ,1091,1093,1092 ,0,0,0}, + {1310,1313,1308 ,1092,1095,1090 ,0,0,0}, {1305,1306,1312 ,1087,1088,1094 ,0,0,0}, + {1302,1298,1307 ,1084,1080,1089 ,0,0,0}, {1295,1314,1296 ,126,1096,1079 ,0,0,0}, + {1315,1314,1316 ,1097,1096,1098 ,0,0,0}, {1314,1315,1296 ,1096,1097,1079 ,0,0,0}, + {1317,1318,1316 ,1099,1100,1098 ,0,0,0}, {1315,1316,1318 ,1097,1098,1100 ,0,0,0}, + {1317,1319,1320 ,1099,1101,1102 ,0,0,0}, {1320,1318,1317 ,1102,1100,1099 ,0,0,0}, + {1321,1319,1322 ,1103,1101,1072 ,0,0,0}, {1319,1321,1320 ,1101,1103,1102 ,0,0,0}, + {1323,1324,1322 ,1104,1074,1072 ,0,0,0}, {1321,1322,1324 ,1103,1072,1074 ,0,0,0}, + {1323,1325,1326 ,1104,1105,1106 ,0,0,0}, {1326,1324,1323 ,1106,1074,1104 ,0,0,0}, + {1327,1325,1328 ,1107,1105,324 ,0,0,0}, {1325,1327,1326 ,1105,1107,1106 ,0,0,0}, + {1329,1330,1331 ,1108,1109,1108 ,0,0,0}, {1332,1333,1334 ,1110,1111,1112 ,0,0,0}, + {1332,1331,1333 ,1110,1108,1111 ,0,0,0}, {1334,1333,1335 ,1112,1111,1112 ,0,0,0}, + {1331,1332,1329 ,1108,1110,1108 ,0,0,0}, {1336,1330,1329 ,1109,1109,1108 ,0,0,0}, + {1337,1336,1338 ,1113,1109,1113 ,0,0,0}, {1336,1337,1330 ,1109,1113,1109 ,0,0,0}, + {1339,1340,1341 ,1114,1115,1114 ,0,0,0}, {1342,1340,1343 ,1115,1115,1116 ,0,0,0}, + {1340,1342,1341 ,1115,1115,1114 ,0,0,0}, {1344,1345,1343 ,1117,1116,1116 ,0,0,0}, + {1342,1343,1345 ,1115,1116,1116 ,0,0,0}, {1344,1346,1347 ,1117,1118,1117 ,0,0,0}, + {1347,1345,1344 ,1117,1116,1117 ,0,0,0}, {1346,1348,1347 ,1118,1119,1117 ,0,0,0}, + {1349,1339,1341 ,1120,1114,1114 ,0,0,0}, {1350,1351,1349 ,1121,1120,1120 ,0,0,0}, + {1339,1349,1351 ,1114,1120,1120 ,0,0,0}, {1350,1352,1353 ,1121,1122,1121 ,0,0,0}, + {1353,1351,1350 ,1121,1120,1121 ,0,0,0}, {1354,1352,1355 ,1122,1122,1123 ,0,0,0}, + {1352,1354,1353 ,1122,1122,1121 ,0,0,0}, {1354,1355,1356 ,1122,1123,1124 ,0,0,0}, + {1357,1358,1359 ,1125,1126,1127 ,0,0,0}, {1360,1361,1357 ,1128,1129,1125 ,0,0,0}, + {1357,1359,1360 ,1125,1127,1128 ,0,0,0}, {1361,1362,1363 ,1129,1130,1131 ,0,0,0}, + {1362,1361,1360 ,1130,1129,1128 ,0,0,0}, {1364,1363,1365 ,1132,1131,1133 ,0,0,0}, + {1362,1365,1363 ,1130,1133,1131 ,0,0,0}, {1366,1367,1364 ,1134,1135,1132 ,0,0,0}, + {1364,1365,1366 ,1132,1133,1134 ,0,0,0}, {1367,1368,1369 ,1135,1136,1137 ,0,0,0}, + {1368,1367,1366 ,1136,1135,1134 ,0,0,0}, {1370,1369,1371 ,1138,1137,1139 ,0,0,0}, + {1368,1371,1369 ,1136,1139,1137 ,0,0,0}, {1372,1373,1370 ,1140,1141,1138 ,0,0,0}, + {1370,1371,1372 ,1138,1139,1140 ,0,0,0}, {1373,1374,1375 ,1141,1142,1143 ,0,0,0}, + {1374,1373,1372 ,1142,1141,1140 ,0,0,0}, {1376,1375,1377 ,1144,1143,1145 ,0,0,0}, + {1374,1377,1375 ,1142,1145,1143 ,0,0,0}, {1378,1379,1376 ,1146,1147,1144 ,0,0,0}, + {1376,1377,1378 ,1144,1145,1146 ,0,0,0}, {1379,1380,1381 ,1147,1148,1149 ,0,0,0}, + {1380,1379,1378 ,1148,1147,1146 ,0,0,0}, {1382,1381,1383 ,1150,1149,1151 ,0,0,0}, + {1380,1383,1381 ,1148,1151,1149 ,0,0,0}, {1384,1385,1382 ,1152,1153,1150 ,0,0,0}, + {1382,1383,1384 ,1150,1151,1152 ,0,0,0}, {1385,1386,1387 ,1153,1154,1155 ,0,0,0}, + {1386,1385,1384 ,1154,1153,1152 ,0,0,0}, {1388,1387,1389 ,1156,1155,1157 ,0,0,0}, + {1386,1389,1387 ,1154,1157,1155 ,0,0,0}, {1390,1391,1388 ,1158,1159,1156 ,0,0,0}, + {1388,1389,1390 ,1156,1157,1158 ,0,0,0}, {1391,1392,1393 ,1159,1160,1161 ,0,0,0}, + {1392,1391,1390 ,1160,1159,1158 ,0,0,0}, {1394,1393,1395 ,1162,1161,1163 ,0,0,0}, + {1392,1395,1393 ,1160,1163,1161 ,0,0,0}, {1396,1397,1394 ,1164,1164,1162 ,0,0,0}, + {1394,1395,1396 ,1162,1163,1164 ,0,0,0}, {1359,1358,1398 ,1127,1126,1165 ,0,0,0}, + {1399,1398,1400 ,1166,1165,1167 ,0,0,0}, {1358,1400,1398 ,1126,1167,1165 ,0,0,0}, + {1401,1402,1399 ,1168,1169,1166 ,0,0,0}, {1399,1400,1401 ,1166,1167,1168 ,0,0,0}, + {1402,1403,1404 ,1169,1170,1171 ,0,0,0}, {1403,1402,1401 ,1170,1169,1168 ,0,0,0}, + {1405,1404,1406 ,1172,1171,1173 ,0,0,0}, {1403,1406,1404 ,1170,1173,1171 ,0,0,0}, + {1407,1408,1405 ,1174,1175,1172 ,0,0,0}, {1405,1406,1407 ,1172,1173,1174 ,0,0,0}, + {1408,1409,1410 ,1175,1176,1177 ,0,0,0}, {1409,1408,1407 ,1176,1175,1174 ,0,0,0}, + {1411,1410,1412 ,1178,1177,1179 ,0,0,0}, {1409,1412,1410 ,1176,1179,1177 ,0,0,0}, + {1413,1414,1411 ,1180,1181,1178 ,0,0,0}, {1411,1412,1413 ,1178,1179,1180 ,0,0,0}, + {1414,1415,1416 ,1181,1182,1183 ,0,0,0}, {1415,1414,1413 ,1182,1181,1180 ,0,0,0}, + {1417,1416,1418 ,1184,1183,1185 ,0,0,0}, {1415,1418,1416 ,1182,1185,1183 ,0,0,0}, + {1419,1420,1417 ,1186,1187,1184 ,0,0,0}, {1417,1418,1419 ,1184,1185,1186 ,0,0,0}, + {1420,1421,1422 ,1187,1188,1189 ,0,0,0}, {1421,1420,1419 ,1188,1187,1186 ,0,0,0}, + {1423,1422,1424 ,1190,1189,1191 ,0,0,0}, {1421,1424,1422 ,1188,1191,1189 ,0,0,0}, + {1425,1426,1423 ,1192,1193,1190 ,0,0,0}, {1423,1424,1425 ,1190,1191,1192 ,0,0,0}, + {1426,1427,1428 ,1193,1194,1195 ,0,0,0}, {1427,1426,1425 ,1194,1193,1192 ,0,0,0}, + {1429,1428,1430 ,1196,1195,1197 ,0,0,0}, {1427,1430,1428 ,1194,1197,1195 ,0,0,0}, + {1431,1432,1429 ,1198,1199,1196 ,0,0,0}, {1429,1430,1431 ,1196,1197,1198 ,0,0,0}, + {1432,1433,1434 ,1199,1200,1201 ,0,0,0}, {1433,1432,1431 ,1200,1199,1198 ,0,0,0}, + {1433,1435,1434 ,1200,1202,1201 ,0,0,0}, {1434,1435,1436 ,1201,1202,1203 ,0,0,0}, + {1437,1438,1435 ,1204,1204,1205 ,0,0,0}, {1437,1439,1438 ,1204,1206,1204 ,0,0,0}, + {1439,1437,1440 ,1206,1204,1206 ,0,0,0}, {1436,1435,1438 ,324,1205,1204 ,0,0,0}, + {1441,1442,1443 ,1207,1208,1207 ,0,0,0}, {1444,1445,1442 ,1209,1210,1208 ,0,0,0}, + {1442,1445,1443 ,1208,1210,1207 ,0,0,0}, {1446,1447,1444 ,1211,1212,1209 ,0,0,0}, + {1444,1442,1446 ,1209,1208,1211 ,0,0,0}, {1447,1448,1449 ,1212,1213,1214 ,0,0,0}, + {1448,1447,1446 ,1213,1212,1211 ,0,0,0}, {1450,1449,1451 ,1215,1214,1216 ,0,0,0}, + {1448,1451,1449 ,1213,1216,1214 ,0,0,0}, {1452,1450,1453 ,1217,1215,1218 ,0,0,0}, + {1450,1451,1453 ,1215,1216,1218 ,0,0,0}, {1454,1450,1452 ,1217,1215,1217 ,0,0,0}, + {1455,1441,1443 ,1219,1207,1207 ,0,0,0}, {1456,1455,1457 ,1220,1219,1221 ,0,0,0}, + {1456,1441,1455 ,1220,1207,1219 ,0,0,0}, {1458,1457,1459 ,1222,1221,1223 ,0,0,0}, + {1455,1459,1457 ,1219,1223,1221 ,0,0,0}, {1460,1461,1458 ,1224,1225,1222 ,0,0,0}, + {1458,1459,1460 ,1222,1223,1224 ,0,0,0}, {1461,1462,1463 ,1225,1226,1227 ,0,0,0}, + {1462,1461,1460 ,1226,1225,1224 ,0,0,0}, {1463,1464,1337 ,1227,1228,1113 ,0,0,0}, + {1462,1464,1463 ,1226,1228,1227 ,0,0,0}, {1463,1337,1338 ,1227,1113,1113 ,0,0,0}, + {1465,1466,1467 ,1229,1230,1231 ,0,0,0}, {1465,1468,1469 ,1229,1232,1233 ,0,0,0}, + {1467,1466,1470 ,1231,1230,1234 ,0,0,0}, {1470,1466,1471 ,1234,1230,1235 ,0,0,0}, + {1470,1471,1472 ,1234,1235,1236 ,0,0,0}, {1473,1472,1471 ,1237,1236,1235 ,0,0,0}, + {1472,1473,1474 ,1236,1237,1238 ,0,0,0}, {1475,1474,1473 ,1239,1238,1237 ,0,0,0}, + {1475,1476,1477 ,1239,1240,1241 ,0,0,0}, {1474,1475,1477 ,1238,1239,1241 ,0,0,0}, + {1467,1468,1465 ,1231,1232,1229 ,0,0,0}, {1477,1476,1478 ,1241,1240,1242 ,0,0,0}, + {1479,1478,1480 ,1243,1242,1244 ,0,0,0}, {1480,1478,1476 ,1244,1242,1240 ,0,0,0}, + {1479,1480,1481 ,1243,1244,1243 ,0,0,0}, {1482,1469,1483 ,1245,1233,1246 ,0,0,0}, + {1468,1483,1469 ,1232,1246,1233 ,0,0,0}, {1484,1485,1482 ,1247,1248,1245 ,0,0,0}, + {1482,1483,1484 ,1245,1246,1247 ,0,0,0}, {1485,1486,1487 ,1248,1249,1250 ,0,0,0}, + {1486,1485,1484 ,1249,1248,1247 ,0,0,0}, {1488,1487,1489 ,1251,1250,1252 ,0,0,0}, + {1486,1489,1487 ,1249,1252,1250 ,0,0,0}, {1490,1491,1488 ,1253,1254,1251 ,0,0,0}, + {1488,1489,1490 ,1251,1252,1253 ,0,0,0}, {1491,1492,1493 ,1254,1255,1256 ,0,0,0}, + {1492,1491,1490 ,1255,1254,1253 ,0,0,0}, {1494,1493,1495 ,1257,1256,1258 ,0,0,0}, + {1492,1495,1493 ,1255,1258,1256 ,0,0,0}, {1494,1495,1496 ,1257,1258,1257 ,0,0,0}, + {1497,1498,1499 ,1259,1260,1259 ,0,0,0}, {1499,1500,1497 ,1259,1261,1259 ,0,0,0}, + {1501,1502,1498 ,1260,1262,1260 ,0,0,0}, {1503,1500,1499 ,1261,1261,1259 ,0,0,0}, + {1497,1501,1498 ,1259,1260,1260 ,0,0,0}, {1501,1504,1502 ,1260,1262,1262 ,0,0,0}, + {1505,1504,1506 ,1263,1262,1263 ,0,0,0}, {1506,1494,1496 ,1263,1257,1257 ,0,0,0}, + {1505,1502,1504 ,1263,1262,1262 ,0,0,0}, {1506,1496,1505 ,1263,1257,1263 ,0,0,0}, + {1507,1503,1508 ,1264,1261,1264 ,0,0,0}, {1503,1507,1500 ,1261,1264,1261 ,0,0,0}, + {1509,1510,1508 ,1265,1265,1264 ,0,0,0}, {1507,1508,1510 ,1264,1264,1265 ,0,0,0}, + {1509,1511,1512 ,1265,1266,1266 ,0,0,0}, {1512,1510,1509 ,1266,1265,1265 ,0,0,0}, + {1513,1511,1514 ,1267,1266,1267 ,0,0,0}, {1511,1513,1512 ,1266,1267,1266 ,0,0,0}, + {1513,1514,1355 ,1267,1267,1268 ,0,0,0}, {1355,1514,1356 ,1268,1267,1269 ,0,0,0}, + {1515,1348,1346 ,1270,1271,1272 ,0,0,0}, {1516,1517,1518 ,1273,1274,1274 ,0,0,0}, + {1519,1520,1521 ,1275,1275,1270 ,0,0,0}, {1522,1523,1524 ,1276,1276,1277 ,0,0,0}, + {1525,1526,1527 ,1273,1278,1278 ,0,0,0}, {1528,1529,1524 ,1279,1277,1277 ,0,0,0}, + {1522,1524,1529 ,1276,1277,1277 ,0,0,0}, {1530,1529,1528 ,1280,1277,1279 ,0,0,0}, + {1526,1523,1527 ,1278,1276,1278 ,0,0,0}, {1527,1523,1522 ,1278,1276,1276 ,0,0,0}, + {1525,1517,1516 ,1273,1274,1273 ,0,0,0}, {1525,1516,1526 ,1273,1273,1278 ,0,0,0}, + {1518,1520,1519 ,1274,1275,1275 ,0,0,0}, {1517,1520,1518 ,1274,1275,1274 ,0,0,0}, + {1515,1521,1348 ,1270,1270,1271 ,0,0,0}, {1519,1521,1515 ,1275,1270,1270 ,0,0,0}, + {1531,1532,1533 ,1281,1281,1282 ,0,0,0}, {1533,1532,1534 ,1282,1281,1282 ,0,0,0}, + {1532,1531,1535 ,1281,1281,1283 ,0,0,0}, {1536,1535,1531 ,1284,1283,1281 ,0,0,0}, + {1537,1538,1536 ,1285,1285,1284 ,0,0,0}, {1539,1533,1534 ,1286,1282,1282 ,0,0,0}, + {1530,1528,1537 ,1287,1288,1285 ,0,0,0}, {1538,1537,1528 ,1285,1285,1288 ,0,0,0}, + {1536,1538,1535 ,1284,1285,1283 ,0,0,0}, {1540,1539,1541 ,1289,1286,1286 ,0,0,0}, + {1534,1541,1539 ,1282,1286,1286 ,0,0,0}, {1542,1543,1540 ,1289,1290,1289 ,0,0,0}, + {1540,1541,1542 ,1289,1286,1289 ,0,0,0}, {1543,1544,1545 ,1290,1290,1291 ,0,0,0}, + {1544,1543,1542 ,1290,1290,1289 ,0,0,0}, {1546,1545,1547 ,1292,1291,1291 ,0,0,0}, + {1544,1547,1545 ,1290,1291,1291 ,0,0,0}, {1546,1547,1548 ,1292,1291,1292 ,0,0,0}, + {1549,1550,1551 ,1293,1293,1294 ,0,0,0}, {1552,1553,1551 ,1295,1296,1294 ,0,0,0}, + {1549,1551,1553 ,1293,1294,1296 ,0,0,0}, {1552,1554,1555 ,1295,1297,1298 ,0,0,0}, + {1555,1553,1552 ,1298,1296,1295 ,0,0,0}, {1556,1554,1557 ,1299,1297,1300 ,0,0,0}, + {1554,1556,1555 ,1297,1299,1298 ,0,0,0}, {1558,1559,1557 ,1301,1302,1300 ,0,0,0}, + {1556,1557,1559 ,1299,1300,1302 ,0,0,0}, {1558,1560,1561 ,1301,1303,1304 ,0,0,0}, + {1561,1559,1558 ,1304,1302,1301 ,0,0,0}, {1562,1560,1563 ,1305,1303,1306 ,0,0,0}, + {1560,1562,1561 ,1303,1305,1304 ,0,0,0}, {1564,1565,1563 ,1307,1308,1306 ,0,0,0}, + {1562,1563,1565 ,1305,1306,1308 ,0,0,0}, {1564,1566,1567 ,1307,1309,1310 ,0,0,0}, + {1567,1565,1564 ,1310,1308,1307 ,0,0,0}, {1568,1566,1569 ,1311,1309,1312 ,0,0,0}, + {1566,1568,1567 ,1309,1311,1310 ,0,0,0}, {1570,1571,1569 ,1313,1314,1312 ,0,0,0}, + {1568,1569,1571 ,1311,1312,1314 ,0,0,0}, {1570,1572,1573 ,1313,1315,1316 ,0,0,0}, + {1573,1571,1570 ,1316,1314,1313 ,0,0,0}, {1574,1572,1575 ,1317,1315,1318 ,0,0,0}, + {1572,1574,1573 ,1315,1317,1316 ,0,0,0}, {1576,1577,1575 ,1319,1320,1318 ,0,0,0}, + {1574,1575,1577 ,1317,1318,1320 ,0,0,0}, {1576,1578,1579 ,1319,1321,1322 ,0,0,0}, + {1579,1577,1576 ,1322,1320,1319 ,0,0,0}, {1580,1578,1581 ,1323,1321,1324 ,0,0,0}, + {1578,1580,1579 ,1321,1323,1322 ,0,0,0}, {1546,1582,1581 ,1292,1325,1324 ,0,0,0}, + {1580,1581,1582 ,1323,1324,1325 ,0,0,0}, {1548,1582,1546 ,1292,1325,1292 ,0,0,0}, + {1583,1550,1549 ,1326,1293,1293 ,0,0,0}, {1584,1583,1585 ,1327,1326,1328 ,0,0,0}, + {1583,1584,1550 ,1326,1327,1293 ,0,0,0}, {1586,1587,1585 ,1329,1330,1328 ,0,0,0}, + {1584,1585,1587 ,1327,1328,1330 ,0,0,0}, {1586,1588,1589 ,1329,1331,1332 ,0,0,0}, + {1589,1587,1586 ,1332,1330,1329 ,0,0,0}, {1590,1588,1591 ,1333,1331,1334 ,0,0,0}, + {1588,1590,1589 ,1331,1333,1332 ,0,0,0}, {1592,1593,1591 ,1335,1336,1334 ,0,0,0}, + {1590,1591,1593 ,1333,1334,1336 ,0,0,0}, {1592,1594,1595 ,1335,1337,1338 ,0,0,0}, + {1595,1593,1592 ,1338,1336,1335 ,0,0,0}, {1596,1594,1597 ,1339,1337,1340 ,0,0,0}, + {1594,1596,1595 ,1337,1339,1338 ,0,0,0}, {1598,1599,1597 ,1341,1342,1340 ,0,0,0}, + {1596,1597,1599 ,1339,1340,1342 ,0,0,0}, {1598,1600,1601 ,1341,1343,1344 ,0,0,0}, + {1601,1599,1598 ,1344,1342,1341 ,0,0,0}, {1602,1600,1603 ,1345,1343,1346 ,0,0,0}, + {1600,1602,1601 ,1343,1345,1344 ,0,0,0}, {1604,1605,1603 ,1347,1348,1346 ,0,0,0}, + {1602,1603,1605 ,1345,1346,1348 ,0,0,0}, {1604,1606,1607 ,1347,1349,1350 ,0,0,0}, + {1607,1605,1604 ,1350,1348,1347 ,0,0,0}, {1608,1606,1609 ,1351,1349,1352 ,0,0,0}, + {1606,1608,1607 ,1349,1351,1350 ,0,0,0}, {1610,1611,1609 ,1353,1354,1352 ,0,0,0}, + {1608,1609,1611 ,1351,1352,1354 ,0,0,0}, {1610,1612,1613 ,1353,1355,1356 ,0,0,0}, + {1613,1611,1610 ,1356,1354,1353 ,0,0,0}, {1614,1612,1615 ,1357,1355,1358 ,0,0,0}, + {1612,1614,1613 ,1355,1357,1356 ,0,0,0}, {1614,1615,1616 ,1357,1358,1358 ,0,0,0}, + {1617,1615,1618 ,1359,1360,1359 ,0,0,0}, {1615,1617,1616 ,1360,1359,1360 ,0,0,0}, + {1619,1620,1621 ,1361,1362,1363 ,0,0,0}, {1622,1623,1624 ,1364,1365,1366 ,0,0,0}, + {1625,1619,1621 ,1367,1361,1363 ,0,0,0}, {1623,1621,1620 ,1365,1363,1362 ,0,0,0}, + {1626,1619,1625 ,1368,1361,1367 ,0,0,0}, {1627,1628,1629 ,1369,1370,1371 ,0,0,0}, + {1626,1625,1627 ,1368,1367,1369 ,0,0,0}, {1630,1628,1631 ,1372,1370,1373 ,0,0,0}, + {1627,1629,1626 ,1369,1371,1368 ,0,0,0}, {1628,1630,1629 ,1370,1372,1371 ,0,0,0}, + {1631,1632,1633 ,1373,1374,1375 ,0,0,0}, {1620,1624,1623 ,1362,1366,1365 ,0,0,0}, + {1634,1635,1636 ,1376,1377,1378 ,0,0,0}, {1637,1633,1632 ,1379,1375,1374 ,0,0,0}, + {1637,1638,1639 ,1379,1380,1381 ,0,0,0}, {1634,1636,1639 ,1376,1378,1381 ,0,0,0}, + {1634,1639,1638 ,1376,1381,1380 ,0,0,0}, {1636,1635,1640 ,1378,1377,1382 ,0,0,0}, + {1641,1642,1643 ,1383,1384,1385 ,0,0,0}, {1640,1641,1643 ,1382,1383,1385 ,0,0,0}, + {1641,1640,1635 ,1383,1382,1377 ,0,0,0}, {1642,1644,1643 ,1384,1386,1385 ,0,0,0}, + {1638,1637,1632 ,1380,1379,1374 ,0,0,0}, {1644,1645,1646 ,1386,1387,1388 ,0,0,0}, + {1644,1642,1645 ,1386,1384,1387 ,0,0,0}, {1647,1648,1649 ,1389,1390,1391 ,0,0,0}, + {1650,1649,1648 ,1392,1391,1390 ,0,0,0}, {1650,1651,1649 ,1392,1393,1391 ,0,0,0}, + {1651,1646,1645 ,1393,1388,1387 ,0,0,0}, {1651,1650,1646 ,1393,1392,1388 ,0,0,0}, + {1633,1630,1631 ,1375,1372,1373 ,0,0,0}, {1652,1653,1647 ,1394,1395,1389 ,0,0,0}, + {1654,1655,1652 ,1396,1397,1394 ,0,0,0}, {1618,1655,1654 ,1398,1397,1396 ,0,0,0}, + {1648,1647,1653 ,1390,1389,1395 ,0,0,0}, {1655,1653,1652 ,1397,1395,1394 ,0,0,0}, + {1617,1618,1654 ,1398,1398,1396 ,0,0,0}, {1656,1657,1622 ,1399,1400,1364 ,0,0,0}, + {1622,1624,1656 ,1364,1366,1399 ,0,0,0}, {1657,1658,1659 ,1400,1401,1402 ,0,0,0}, + {1658,1657,1656 ,1401,1400,1399 ,0,0,0}, {1660,1659,1661 ,1403,1402,1404 ,0,0,0}, + {1658,1661,1659 ,1401,1404,1402 ,0,0,0}, {1662,1663,1660 ,1405,1406,1403 ,0,0,0}, + {1660,1661,1662 ,1403,1404,1405 ,0,0,0}, {1663,1664,1665 ,1406,1407,1408 ,0,0,0}, + {1664,1663,1662 ,1407,1406,1405 ,0,0,0}, {1666,1665,1667 ,1409,1408,1410 ,0,0,0}, + {1664,1667,1665 ,1407,1410,1408 ,0,0,0}, {1668,1669,1666 ,1411,1412,1409 ,0,0,0}, + {1666,1667,1668 ,1409,1410,1411 ,0,0,0}, {1669,1670,1671 ,1412,1413,1414 ,0,0,0}, + {1670,1669,1668 ,1413,1412,1411 ,0,0,0}, {1672,1671,1673 ,1415,1414,1416 ,0,0,0}, + {1670,1673,1671 ,1413,1416,1414 ,0,0,0}, {1674,1675,1672 ,1417,1418,1415 ,0,0,0}, + {1672,1673,1674 ,1415,1416,1417 ,0,0,0}, {1675,1676,1677 ,1418,1419,1420 ,0,0,0}, + {1676,1675,1674 ,1419,1418,1417 ,0,0,0}, {1678,1677,1679 ,1421,1420,1422 ,0,0,0}, + {1676,1679,1677 ,1419,1422,1420 ,0,0,0}, {1680,1681,1678 ,1423,1424,1421 ,0,0,0}, + {1678,1679,1680 ,1421,1422,1423 ,0,0,0}, {1681,1682,1683 ,1424,1425,1426 ,0,0,0}, + {1682,1681,1680 ,1425,1424,1423 ,0,0,0}, {1684,1683,1685 ,1427,1426,1428 ,0,0,0}, + {1682,1685,1683 ,1425,1428,1426 ,0,0,0}, {1686,1687,1684 ,1429,1430,1427 ,0,0,0}, + {1684,1685,1686 ,1427,1428,1429 ,0,0,0}, {1687,1688,1689 ,1430,1431,1432 ,0,0,0}, + {1688,1687,1686 ,1431,1430,1429 ,0,0,0}, {1690,1689,1691 ,1433,1432,1434 ,0,0,0}, + {1688,1691,1689 ,1431,1434,1432 ,0,0,0}, {1690,1691,1692 ,1433,1434,1433 ,0,0,0}, + {1693,1694,1695 ,1435,1435,1435 ,0,0,0}, {1694,1693,1696 ,1435,1435,1435 ,0,0,0}, + {1697,1698,1699 ,1436,1437,1438 ,0,0,0}, {1700,1701,1702 ,1439,1440,1441 ,0,0,0}, + {1698,1703,1699 ,1437,1442,1438 ,0,0,0}, {1697,1699,1704 ,1436,1438,1443 ,0,0,0}, + {1700,1697,1704 ,1439,1436,1443 ,0,0,0}, {1705,1706,1703 ,1444,1445,1442 ,0,0,0}, + {1705,1703,1698 ,1444,1442,1437 ,0,0,0}, {1707,1708,1709 ,1446,1447,1448 ,0,0,0}, + {1706,1705,1707 ,1445,1444,1446 ,0,0,0}, {1707,1709,1706 ,1446,1448,1445 ,0,0,0}, + {1708,1710,1709 ,1447,1449,1448 ,0,0,0}, {1701,1700,1704 ,1440,1439,1443 ,0,0,0}, + {1708,1711,1710 ,1447,1450,1449 ,0,0,0}, {1712,1713,1714 ,1451,1452,1453 ,0,0,0}, + {1712,1714,1711 ,1451,1453,1450 ,0,0,0}, {1713,1712,1715 ,1452,1451,1454 ,0,0,0}, + {1716,1717,1715 ,1455,1456,1454 ,0,0,0}, {1717,1713,1715 ,1456,1452,1454 ,0,0,0}, + {1718,1719,1720 ,1457,1458,1459 ,0,0,0}, {1717,1716,1721 ,1456,1455,1460 ,0,0,0}, + {1722,1723,1721 ,1461,1462,1460 ,0,0,0}, {1719,1718,1723 ,1458,1457,1462 ,0,0,0}, + {1719,1723,1722 ,1458,1462,1461 ,0,0,0}, {1718,1720,1724 ,1457,1459,1463 ,0,0,0}, + {1716,1722,1721 ,1455,1461,1460 ,0,0,0}, {1725,1724,1726 ,1464,1463,1465 ,0,0,0}, + {1725,1726,1727 ,1464,1465,1466 ,0,0,0}, {1726,1724,1720 ,1465,1463,1459 ,0,0,0}, + {1728,1729,1730 ,1467,1468,1469 ,0,0,0}, {1714,1710,1711 ,1453,1449,1450 ,0,0,0}, + {1728,1731,1727 ,1467,1470,1466 ,0,0,0}, {1731,1728,1730 ,1470,1467,1469 ,0,0,0}, + {1729,1732,1733 ,1468,1471,1472 ,0,0,0}, {1733,1730,1729 ,1472,1469,1468 ,0,0,0}, + {1734,1735,1732 ,1473,1474,1471 ,0,0,0}, {1733,1732,1735 ,1472,1471,1474 ,0,0,0}, + {1734,1696,1693 ,1473,1475,1475 ,0,0,0}, {1734,1693,1735 ,1473,1475,1474 ,0,0,0}, + {1727,1731,1725 ,1466,1470,1464 ,0,0,0}, {1736,1702,1737 ,1476,1441,1477 ,0,0,0}, + {1701,1737,1702 ,1440,1477,1441 ,0,0,0}, {1738,1739,1736 ,1478,1479,1476 ,0,0,0}, + {1736,1737,1738 ,1476,1477,1478 ,0,0,0}, {1739,1740,1741 ,1479,1480,1481 ,0,0,0}, + {1740,1739,1738 ,1480,1479,1478 ,0,0,0}, {1742,1741,1743 ,1482,1481,1483 ,0,0,0}, + {1740,1743,1741 ,1480,1483,1481 ,0,0,0}, {1744,1745,1742 ,1484,1485,1482 ,0,0,0}, + {1742,1743,1744 ,1482,1483,1484 ,0,0,0}, {1745,1746,1747 ,1485,1486,1487 ,0,0,0}, + {1746,1745,1744 ,1486,1485,1484 ,0,0,0}, {1748,1747,1749 ,1488,1487,1489 ,0,0,0}, + {1746,1749,1747 ,1486,1489,1487 ,0,0,0}, {1750,1751,1748 ,1490,1491,1488 ,0,0,0}, + {1748,1749,1750 ,1488,1489,1490 ,0,0,0}, {1751,1752,1753 ,1491,1492,1493 ,0,0,0}, + {1752,1751,1750 ,1492,1491,1490 ,0,0,0}, {1754,1753,1755 ,1494,1493,1495 ,0,0,0}, + {1752,1755,1753 ,1492,1495,1493 ,0,0,0}, {1756,1757,1754 ,1496,1497,1494 ,0,0,0}, + {1754,1755,1756 ,1494,1495,1496 ,0,0,0}, {1757,1758,1759 ,1497,1498,1499 ,0,0,0}, + {1758,1757,1756 ,1498,1497,1496 ,0,0,0}, {1760,1759,1761 ,1500,1499,1501 ,0,0,0}, + {1758,1761,1759 ,1498,1501,1499 ,0,0,0}, {1762,1763,1760 ,1502,1503,1500 ,0,0,0}, + {1760,1761,1762 ,1500,1501,1502 ,0,0,0}, {1763,1764,1765 ,1503,1504,1505 ,0,0,0}, + {1764,1763,1762 ,1504,1503,1502 ,0,0,0}, {1766,1765,1767 ,1506,1505,1507 ,0,0,0}, + {1764,1767,1765 ,1504,1507,1505 ,0,0,0}, {1768,1769,1766 ,1508,1509,1506 ,0,0,0}, + {1766,1767,1768 ,1506,1507,1508 ,0,0,0}, {1769,1770,1771 ,1509,1510,1511 ,0,0,0}, + {1770,1769,1768 ,1510,1509,1508 ,0,0,0}, {1772,1771,1773 ,1512,1511,1513 ,0,0,0}, + {1770,1773,1771 ,1510,1513,1511 ,0,0,0}, {1772,1773,1774 ,1512,1513,1514 ,0,0,0}, + {1775,1776,1777 ,1515,1516,1517 ,0,0,0}, {1778,1779,1777 ,1518,1519,1517 ,0,0,0}, + {1775,1777,1779 ,1515,1517,1519 ,0,0,0}, {1778,1780,1781 ,1518,1520,1521 ,0,0,0}, + {1781,1779,1778 ,1521,1519,1518 ,0,0,0}, {1782,1780,1783 ,1522,1520,1523 ,0,0,0}, + {1780,1782,1781 ,1520,1522,1521 ,0,0,0}, {1784,1785,1783 ,1524,1525,1523 ,0,0,0}, + {1782,1783,1785 ,1522,1523,1525 ,0,0,0}, {1784,1786,1787 ,1524,1526,1527 ,0,0,0}, + {1787,1785,1784 ,1527,1525,1524 ,0,0,0}, {1788,1786,1789 ,1528,1526,1529 ,0,0,0}, + {1786,1788,1787 ,1526,1528,1527 ,0,0,0}, {1790,1791,1789 ,1530,1531,1529 ,0,0,0}, + {1788,1789,1791 ,1528,1529,1531 ,0,0,0}, {1790,1792,1793 ,1530,1532,1533 ,0,0,0}, + {1793,1791,1790 ,1533,1531,1530 ,0,0,0}, {1794,1792,1795 ,1534,1532,1535 ,0,0,0}, + {1792,1794,1793 ,1532,1534,1533 ,0,0,0}, {1796,1797,1795 ,1536,1537,1535 ,0,0,0}, + {1794,1795,1797 ,1534,1535,1537 ,0,0,0}, {1796,1798,1799 ,1536,1538,1539 ,0,0,0}, + {1799,1797,1796 ,1539,1537,1536 ,0,0,0}, {1800,1798,1801 ,1540,1538,1541 ,0,0,0}, + {1798,1800,1799 ,1538,1540,1539 ,0,0,0}, {1802,1803,1801 ,1542,1543,1541 ,0,0,0}, + {1800,1801,1803 ,1540,1541,1543 ,0,0,0}, {1802,1804,1805 ,1542,1544,1545 ,0,0,0}, + {1805,1803,1802 ,1545,1543,1542 ,0,0,0}, {1806,1804,1807 ,1546,1544,1547 ,0,0,0}, + {1804,1806,1805 ,1544,1546,1545 ,0,0,0}, {1808,1809,1807 ,1548,1549,1547 ,0,0,0}, + {1806,1807,1809 ,1546,1547,1549 ,0,0,0}, {1808,1810,1811 ,1548,1550,1551 ,0,0,0}, + {1811,1809,1808 ,1551,1549,1548 ,0,0,0}, {1812,1810,1813 ,1552,1550,1553 ,0,0,0}, + {1810,1812,1811 ,1550,1552,1551 ,0,0,0}, {1814,1815,1813 ,1554,1555,1553 ,0,0,0}, + {1812,1813,1815 ,1552,1553,1555 ,0,0,0}, {1814,1816,1817 ,1554,1556,1557 ,0,0,0}, + {1817,1815,1814 ,1557,1555,1554 ,0,0,0}, {1818,1816,1819 ,1558,1556,1559 ,0,0,0}, + {1816,1818,1817 ,1556,1558,1557 ,0,0,0}, {1820,1821,1819 ,1560,1561,1559 ,0,0,0}, + {1818,1819,1821 ,1558,1559,1561 ,0,0,0}, {1820,1822,1823 ,1560,1562,1563 ,0,0,0}, + {1823,1821,1820 ,1563,1561,1560 ,0,0,0}, {1824,1822,1825 ,1564,1562,1565 ,0,0,0}, + {1822,1824,1823 ,1562,1564,1563 ,0,0,0}, {1826,1827,1825 ,1566,1567,1565 ,0,0,0}, + {1824,1825,1827 ,1564,1565,1567 ,0,0,0}, {1826,1828,1829 ,1566,1568,1569 ,0,0,0}, + {1829,1827,1826 ,1569,1567,1566 ,0,0,0}, {1830,1828,1831 ,1570,1568,1571 ,0,0,0}, + {1828,1830,1829 ,1568,1570,1569 ,0,0,0}, {1772,1832,1831 ,1572,1573,1571 ,0,0,0}, + {1830,1831,1832 ,1570,1571,1573 ,0,0,0}, {1774,1832,1772 ,1574,1573,1572 ,0,0,0}, + {1833,1776,1775 ,1575,1516,1515 ,0,0,0}, {1834,1833,1835 ,1576,1575,1577 ,0,0,0}, + {1833,1834,1776 ,1575,1576,1516 ,0,0,0}, {1836,1837,1835 ,1578,1579,1577 ,0,0,0}, + {1834,1835,1837 ,1576,1577,1579 ,0,0,0}, {1836,1838,1839 ,1578,1580,1581 ,0,0,0}, + {1839,1837,1836 ,1581,1579,1578 ,0,0,0}, {1840,1838,1841 ,1582,1580,1583 ,0,0,0}, + {1838,1840,1839 ,1580,1582,1581 ,0,0,0}, {1842,1843,1841 ,1584,1585,1583 ,0,0,0}, + {1840,1841,1843 ,1582,1583,1585 ,0,0,0}, {1842,1844,1845 ,1584,1586,1587 ,0,0,0}, + {1845,1843,1842 ,1587,1585,1584 ,0,0,0}, {1846,1844,1847 ,1588,1586,1589 ,0,0,0}, + {1844,1846,1845 ,1586,1588,1587 ,0,0,0}, {1848,1849,1847 ,1590,1591,1589 ,0,0,0}, + {1846,1847,1849 ,1588,1589,1591 ,0,0,0}, {1848,1850,1851 ,1590,1592,1593 ,0,0,0}, + {1851,1849,1848 ,1593,1591,1590 ,0,0,0}, {1852,1850,1853 ,1594,1592,1595 ,0,0,0}, + {1850,1852,1851 ,1592,1594,1593 ,0,0,0}, {1854,1855,1853 ,1596,1597,1595 ,0,0,0}, + {1852,1853,1855 ,1594,1595,1597 ,0,0,0}, {1854,1856,1857 ,1596,1598,1599 ,0,0,0}, + {1857,1855,1854 ,1599,1597,1596 ,0,0,0}, {1858,1856,1859 ,1600,1598,1601 ,0,0,0}, + {1856,1858,1857 ,1598,1600,1599 ,0,0,0}, {1860,1861,1859 ,1602,1603,1601 ,0,0,0}, + {1858,1859,1861 ,1600,1601,1603 ,0,0,0}, {1860,1862,1863 ,1602,1604,1605 ,0,0,0}, + {1863,1861,1860 ,1605,1603,1602 ,0,0,0}, {1864,1862,1865 ,1606,1604,1607 ,0,0,0}, + {1862,1864,1863 ,1604,1606,1605 ,0,0,0}, {1866,1867,1865 ,1608,1609,1607 ,0,0,0}, + {1864,1865,1867 ,1606,1607,1609 ,0,0,0}, {1866,1868,1869 ,1608,1610,1611 ,0,0,0}, + {1869,1867,1866 ,1611,1609,1608 ,0,0,0}, {1870,1868,1871 ,1612,1610,1613 ,0,0,0}, + {1868,1870,1869 ,1610,1612,1611 ,0,0,0}, {1872,1873,1871 ,1614,1615,1613 ,0,0,0}, + {1870,1871,1873 ,1612,1613,1615 ,0,0,0}, {1872,1874,1875 ,1614,1616,1617 ,0,0,0}, + {1875,1873,1872 ,1617,1615,1614 ,0,0,0}, {1876,1874,1877 ,1618,1616,1619 ,0,0,0}, + {1874,1876,1875 ,1616,1618,1617 ,0,0,0}, {1878,1879,1877 ,1620,1621,1619 ,0,0,0}, + {1876,1877,1879 ,1618,1619,1621 ,0,0,0}, {1878,1880,1881 ,1620,1622,1623 ,0,0,0}, + {1881,1879,1878 ,1623,1621,1620 ,0,0,0}, {1882,1880,1883 ,1624,1622,1625 ,0,0,0}, + {1880,1882,1881 ,1622,1624,1623 ,0,0,0}, {1884,1885,1883 ,1626,1627,1625 ,0,0,0}, + {1882,1883,1885 ,1624,1625,1627 ,0,0,0}, {1884,1886,1887 ,1626,1628,1629 ,0,0,0}, + {1887,1885,1884 ,1629,1627,1626 ,0,0,0}, {1888,1886,1889 ,1630,1628,21 ,0,0,0}, + {1886,1888,1887 ,1628,1630,1629 ,0,0,0}, {1888,1889,1890 ,1630,21,1631 ,0,0,0}, + {1891,1892,1893 ,1632,1633,1634 ,0,0,0}, {1894,1895,1896 ,1635,1636,1637 ,0,0,0}, + {1892,1897,1893 ,1633,1638,1634 ,0,0,0}, {1891,1893,1898 ,1632,1634,1639 ,0,0,0}, + {1894,1891,1898 ,1635,1632,1639 ,0,0,0}, {1899,1900,1897 ,1640,1641,1638 ,0,0,0}, + {1899,1897,1892 ,1640,1638,1633 ,0,0,0}, {1901,1902,1903 ,1642,1643,1644 ,0,0,0}, + {1900,1899,1901 ,1641,1640,1642 ,0,0,0}, {1901,1903,1900 ,1642,1644,1641 ,0,0,0}, + {1902,1904,1903 ,1643,1645,1644 ,0,0,0}, {1895,1894,1898 ,1636,1635,1639 ,0,0,0}, + {1902,1905,1904 ,1643,1646,1645 ,0,0,0}, {1906,1907,1908 ,1647,1648,1649 ,0,0,0}, + {1906,1908,1905 ,1647,1649,1646 ,0,0,0}, {1907,1906,1909 ,1648,1647,1650 ,0,0,0}, + {1910,1911,1909 ,1651,1652,1650 ,0,0,0}, {1911,1907,1909 ,1652,1648,1650 ,0,0,0}, + {1912,1913,1914 ,1653,1654,1655 ,0,0,0}, {1911,1910,1915 ,1652,1651,1656 ,0,0,0}, + {1916,1917,1915 ,1657,1658,1656 ,0,0,0}, {1913,1912,1917 ,1654,1653,1658 ,0,0,0}, + {1913,1917,1916 ,1654,1658,1657 ,0,0,0}, {1912,1914,1918 ,1653,1655,1659 ,0,0,0}, + {1910,1916,1915 ,1651,1657,1656 ,0,0,0}, {1919,1918,1920 ,1660,1659,1661 ,0,0,0}, + {1919,1920,1921 ,1660,1661,1662 ,0,0,0}, {1920,1918,1914 ,1661,1659,1655 ,0,0,0}, + {1922,1923,1924 ,1663,1664,1665 ,0,0,0}, {1908,1904,1905 ,1649,1645,1646 ,0,0,0}, + {1922,1925,1921 ,1663,1666,1662 ,0,0,0}, {1925,1922,1924 ,1666,1663,1665 ,0,0,0}, + {1923,1926,1927 ,1664,1667,1668 ,0,0,0}, {1927,1924,1923 ,1668,1665,1664 ,0,0,0}, + {1928,1929,1926 ,1669,1670,1667 ,0,0,0}, {1927,1926,1929 ,1668,1667,1670 ,0,0,0}, + {1928,1890,1889 ,1669,1671,1672 ,0,0,0}, {1928,1889,1929 ,1669,1672,1670 ,0,0,0}, + {1921,1925,1919 ,1662,1666,1660 ,0,0,0}, {1930,1896,1931 ,1673,1637,1674 ,0,0,0}, + {1895,1931,1896 ,1636,1674,1637 ,0,0,0}, {1932,1933,1930 ,1675,1676,1673 ,0,0,0}, + {1930,1931,1932 ,1673,1674,1675 ,0,0,0}, {1933,1934,1935 ,1676,1677,1678 ,0,0,0}, + {1934,1933,1932 ,1677,1676,1675 ,0,0,0}, {1936,1935,1937 ,1679,1678,1680 ,0,0,0}, + {1934,1937,1935 ,1677,1680,1678 ,0,0,0}, {1938,1939,1936 ,1681,1682,1679 ,0,0,0}, + {1936,1937,1938 ,1679,1680,1681 ,0,0,0}, {1939,1940,1941 ,1682,1683,1684 ,0,0,0}, + {1940,1939,1938 ,1683,1682,1681 ,0,0,0}, {1942,1941,1943 ,1685,1684,1686 ,0,0,0}, + {1940,1943,1941 ,1683,1686,1684 ,0,0,0}, {1944,1945,1942 ,1687,1688,1685 ,0,0,0}, + {1942,1943,1944 ,1685,1686,1687 ,0,0,0}, {1945,1946,1947 ,1688,1689,1690 ,0,0,0}, + {1946,1945,1944 ,1689,1688,1687 ,0,0,0}, {1948,1947,1949 ,1691,1690,1692 ,0,0,0}, + {1946,1949,1947 ,1689,1692,1690 ,0,0,0}, {1950,1951,1948 ,1693,1694,1691 ,0,0,0}, + {1948,1949,1950 ,1691,1692,1693 ,0,0,0}, {1951,1952,1953 ,1694,1695,1696 ,0,0,0}, + {1952,1951,1950 ,1695,1694,1693 ,0,0,0}, {1954,1953,1955 ,1697,1696,1698 ,0,0,0}, + {1952,1955,1953 ,1695,1698,1696 ,0,0,0}, {1956,1957,1954 ,1699,1700,1697 ,0,0,0}, + {1954,1955,1956 ,1697,1698,1699 ,0,0,0}, {1957,1958,1959 ,1700,1701,1702 ,0,0,0}, + {1958,1957,1956 ,1701,1700,1699 ,0,0,0}, {1960,1959,1961 ,1703,1702,1704 ,0,0,0}, + {1958,1961,1959 ,1701,1704,1702 ,0,0,0}, {1962,1963,1960 ,1705,1706,1703 ,0,0,0}, + {1960,1961,1962 ,1703,1704,1705 ,0,0,0}, {1963,1964,1965 ,1706,1707,1708 ,0,0,0}, + {1964,1963,1962 ,1707,1706,1705 ,0,0,0}, {1966,1965,1967 ,1709,1708,1710 ,0,0,0}, + {1964,1967,1965 ,1707,1710,1708 ,0,0,0}, {1966,1967,1968 ,1709,1710,1709 ,0,0,0}, + {1969,1966,1968 ,1711,1711,1711 ,0,0,0}, {1966,1969,1970 ,1711,1711,1711 ,0,0,0}, + {1971,1972,1973 ,1712,1713,1714 ,0,0,0}, {1974,1975,1971 ,1715,1716,1712 ,0,0,0}, + {1971,1973,1974 ,1712,1714,1715 ,0,0,0}, {1975,1976,1977 ,1716,1717,1718 ,0,0,0}, + {1976,1975,1974 ,1717,1716,1715 ,0,0,0}, {1978,1977,1979 ,1719,1718,1720 ,0,0,0}, + {1976,1979,1977 ,1717,1720,1718 ,0,0,0}, {1980,1981,1978 ,1721,1722,1719 ,0,0,0}, + {1978,1979,1980 ,1719,1720,1721 ,0,0,0}, {1981,1982,1983 ,1722,1723,1724 ,0,0,0}, + {1982,1981,1980 ,1723,1722,1721 ,0,0,0}, {1984,1983,1985 ,1725,1724,1726 ,0,0,0}, + {1982,1985,1983 ,1723,1726,1724 ,0,0,0}, {1986,1987,1984 ,1727,1728,1725 ,0,0,0}, + {1984,1985,1986 ,1725,1726,1727 ,0,0,0}, {1987,1988,1989 ,1728,1729,1730 ,0,0,0}, + {1988,1987,1986 ,1729,1728,1727 ,0,0,0}, {1990,1989,1991 ,1731,1730,1732 ,0,0,0}, + {1988,1991,1989 ,1729,1732,1730 ,0,0,0}, {1992,1993,1990 ,1733,1734,1731 ,0,0,0}, + {1990,1991,1992 ,1731,1732,1733 ,0,0,0}, {1993,1994,1995 ,1734,1735,1736 ,0,0,0}, + {1994,1993,1992 ,1735,1734,1733 ,0,0,0}, {1996,1995,1997 ,1737,1736,1738 ,0,0,0}, + {1994,1997,1995 ,1735,1738,1736 ,0,0,0}, {1998,1999,1996 ,1739,1740,1737 ,0,0,0}, + {1996,1997,1998 ,1737,1738,1739 ,0,0,0}, {1999,2000,2001 ,1740,1741,1742 ,0,0,0}, + {2000,1999,1998 ,1741,1740,1739 ,0,0,0}, {2002,2001,2003 ,1743,1742,1744 ,0,0,0}, + {2000,2003,2001 ,1741,1744,1742 ,0,0,0}, {2004,2005,2002 ,1745,1746,1743 ,0,0,0}, + {2002,2003,2004 ,1743,1744,1745 ,0,0,0}, {2005,2006,2007 ,1746,1747,1748 ,0,0,0}, + {2006,2005,2004 ,1747,1746,1745 ,0,0,0}, {2008,2007,2009 ,1749,1748,1750 ,0,0,0}, + {2006,2009,2007 ,1747,1750,1748 ,0,0,0}, {1970,1969,2008 ,1751,1751,1749 ,0,0,0}, + {2008,2009,1970 ,1749,1750,1751 ,0,0,0}, {1973,1972,2010 ,1714,1713,1752 ,0,0,0}, + {2011,2010,2012 ,1753,1752,1754 ,0,0,0}, {1972,2012,2010 ,1713,1754,1752 ,0,0,0}, + {2013,2014,2011 ,1755,1756,1753 ,0,0,0}, {2011,2012,2013 ,1753,1754,1755 ,0,0,0}, + {2014,2015,2016 ,1756,1757,1758 ,0,0,0}, {2015,2014,2013 ,1757,1756,1755 ,0,0,0}, + {2017,2016,2018 ,1759,1758,1760 ,0,0,0}, {2015,2018,2016 ,1757,1760,1758 ,0,0,0}, + {2019,2020,2017 ,1761,1762,1759 ,0,0,0}, {2017,2018,2019 ,1759,1760,1761 ,0,0,0}, + {2020,2021,2022 ,1762,1763,1764 ,0,0,0}, {2021,2020,2019 ,1763,1762,1761 ,0,0,0}, + {2023,2022,2024 ,1765,1764,1766 ,0,0,0}, {2021,2024,2022 ,1763,1766,1764 ,0,0,0}, + {2025,2026,2023 ,1767,1768,1765 ,0,0,0}, {2023,2024,2025 ,1765,1766,1767 ,0,0,0}, + {2026,2027,2028 ,1768,1769,1770 ,0,0,0}, {2027,2026,2025 ,1769,1768,1767 ,0,0,0}, + {2029,2028,2030 ,1771,1770,1772 ,0,0,0}, {2027,2030,2028 ,1769,1772,1770 ,0,0,0}, + {2031,2032,2029 ,1773,1774,1771 ,0,0,0}, {2029,2030,2031 ,1771,1772,1773 ,0,0,0}, + {2032,2033,2034 ,1774,1775,1776 ,0,0,0}, {2033,2032,2031 ,1775,1774,1773 ,0,0,0}, + {2035,2034,2036 ,1777,1776,1778 ,0,0,0}, {2033,2036,2034 ,1775,1778,1776 ,0,0,0}, + {2037,2038,2035 ,1779,1780,1777 ,0,0,0}, {2035,2036,2037 ,1777,1778,1779 ,0,0,0}, + {2038,2039,2040 ,1780,1781,1782 ,0,0,0}, {2039,2038,2037 ,1781,1780,1779 ,0,0,0}, + {2041,2040,2042 ,1783,1782,1784 ,0,0,0}, {2039,2042,2040 ,1781,1784,1782 ,0,0,0}, + {2043,2044,2041 ,1785,1786,1783 ,0,0,0}, {2041,2042,2043 ,1783,1784,1785 ,0,0,0}, + {2044,2045,2046 ,1786,1787,1788 ,0,0,0}, {2045,2044,2043 ,1787,1786,1785 ,0,0,0}, + {2045,1695,2046 ,1787,1789,1788 ,0,0,0}, {2046,1695,1694 ,1788,1789,1789 ,0,0,0}, + {1396,1692,1397 ,1790,1791,1790 ,0,0,0}, {1692,1396,1690 ,1791,1790,1791 ,0,0,0}, + {1917,1419,1418 ,1792,1792,1792 ,0,0,0}, {1695,2045,1618 ,1792,726,726 ,0,0,0}, + {2039,1648,2042 ,726,726,726 ,0,0,0}, {1735,1693,1615 ,726,726,726 ,0,0,0}, + {1636,1640,2030 ,726,726,726 ,0,0,0}, {1644,2036,2033 ,726,726,726 ,0,0,0}, + {2015,1626,2018 ,726,726,726 ,0,0,0}, {2024,2021,1633 ,726,726,726 ,0,0,0}, + {2012,1620,1619 ,726,726,726 ,0,0,0}, {2013,2012,1619 ,726,726,726 ,0,0,0}, + {1412,1409,1908 ,1792,726,1792 ,0,0,0}, {1925,1924,1427 ,1792,726,1792 ,0,0,0}, + {1893,1897,1401 ,1792,1792,726 ,0,0,0}, {1403,1897,1900 ,726,1792,726 ,0,0,0}, + {1931,1357,1361 ,726,726,726 ,0,0,0}, {1357,1895,1358 ,726,1792,1792 ,0,0,0}, + {1934,1364,1937 ,1792,726,726 ,0,0,0}, {1363,1934,1932 ,1792,1792,1792 ,0,0,0}, + {1373,1944,1943 ,1793,1792,1792 ,0,0,0}, {1369,1940,1938 ,726,1792,1792 ,0,0,0}, + {1946,1944,1375 ,1792,1792,1792 ,0,0,0}, {1373,1375,1944 ,1793,1792,1792 ,0,0,0}, + {1950,1949,1379 ,1792,1793,726 ,0,0,0}, {1946,1375,1376 ,1792,1792,1792 ,0,0,0}, + {1952,1950,1381 ,1792,1792,1792 ,0,0,0}, {1379,1949,1376 ,726,1793,1792 ,0,0,0}, + {1382,1955,1952 ,1792,726,1792 ,0,0,0}, {1952,1381,1382 ,1792,1792,1792 ,0,0,0}, + {1955,1385,1956 ,726,726,726 ,0,0,0}, {1385,1955,1382 ,726,726,1792 ,0,0,0}, + {1958,1956,1387 ,726,726,726 ,0,0,0}, {1388,1958,1387 ,726,726,726 ,0,0,0}, + {1393,1962,1391 ,726,1792,1792 ,0,0,0}, {1961,1958,1388 ,726,726,726 ,0,0,0}, + {1394,1397,1964 ,726,726,726 ,0,0,0}, {1391,1962,1961 ,1792,1792,726 ,0,0,0}, + {1397,1967,1964 ,726,1792,726 ,0,0,0}, {1962,1394,1964 ,1792,726,726 ,0,0,0}, + {1987,1668,1984 ,726,726,726 ,0,0,0}, {1397,1968,1967 ,726,726,1792 ,0,0,0}, + {1918,1421,1912 ,1792,726,726 ,0,0,0}, {1932,1361,1363 ,1792,726,1792 ,0,0,0}, + {1940,1369,1370 ,1792,726,1792 ,0,0,0}, {1943,1370,1373 ,1792,1792,1793 ,0,0,0}, + {1367,1369,1938 ,1792,726,1792 ,0,0,0}, {1937,1364,1367 ,726,726,1792 ,0,0,0}, + {1895,1357,1931 ,1792,726,726 ,0,0,0}, {1931,1361,1932 ,726,726,1792 ,0,0,0}, + {1893,1400,1898 ,1792,1792,1792 ,0,0,0}, {1898,1358,1895 ,1792,1792,1792 ,0,0,0}, + {1561,1740,1559 ,726,726,1792 ,0,0,0}, {1400,1358,1898 ,1792,1792,1792 ,0,0,0}, + {1903,1407,1406 ,1792,1792,726 ,0,0,0}, {1900,1406,1403 ,726,726,726 ,0,0,0}, + {1904,1409,1407 ,726,726,1792 ,0,0,0}, {1903,1406,1900 ,1792,726,726 ,0,0,0}, + {1911,1415,1413 ,1792,1792,1792 ,0,0,0}, {1412,1908,1907 ,1792,1792,726 ,0,0,0}, + {1912,1419,1917 ,726,1792,1792 ,0,0,0}, {1415,1915,1418 ,1792,1792,1792 ,0,0,0}, + {1425,1424,1919 ,726,726,726 ,0,0,0}, {1421,1419,1912 ,726,1792,726 ,0,0,0}, + {1919,1424,1918 ,726,726,1792 ,0,0,0}, {1767,1764,1547 ,1792,726,726 ,0,0,0}, + {1927,1431,1430 ,1793,726,726 ,0,0,0}, {1344,1326,1346 ,1792,1793,726 ,0,0,0}, + {1433,1929,1435 ,1792,726,1792 ,0,0,0}, {1351,1353,1318 ,726,1792,726 ,0,0,0}, + {1315,1353,1354 ,726,1792,1792 ,0,0,0}, {1514,1511,1307 ,726,726,726 ,0,0,0}, + {1514,1298,1300 ,726,726,1792 ,0,0,0}, {1817,1489,1815 ,726,1792,1792 ,0,0,0}, + {1508,1503,1770 ,1792,726,726 ,0,0,0}, {1877,1874,2047 ,726,726,726 ,0,0,0}, + {1788,1472,1787 ,726,1792,1792 ,0,0,0}, {2048,2049,1838 ,1792,1792,726 ,0,0,0}, + {1293,2050,2051 ,1792,726,726 ,0,0,0}, {1844,1842,2052 ,726,1792,726 ,0,0,0}, + {2052,1842,2049 ,726,1792,1792 ,0,0,0}, {1266,1263,1335 ,726,726,1792 ,0,0,0}, + {2052,1335,1847 ,726,1792,1792 ,0,0,0}, {1333,1331,1264 ,1792,1792,1792 ,0,0,0}, + {1264,1331,1273 ,1792,1792,1792 ,0,0,0}, {1854,1853,1262 ,1792,726,726 ,0,0,0}, + {1841,1838,2049 ,1792,726,1792 ,0,0,0}, {1479,2048,1836 ,726,1792,726 ,0,0,0}, + {1454,2053,1450 ,726,1792,1792 ,0,0,0}, {2054,2055,2050 ,1792,1792,726 ,0,0,0}, + {1445,2056,2057 ,726,1792,1792 ,0,0,0}, {1833,1478,1479 ,1792,726,726 ,0,0,0}, + {1479,1836,1835 ,726,726,1792 ,0,0,0}, {1775,1478,1833 ,1792,726,1792 ,0,0,0}, + {1872,1871,2058 ,726,1792,1792 ,0,0,0}, {1477,1478,1779 ,1792,726,726 ,0,0,0}, + {1779,1781,1477 ,726,726,1792 ,0,0,0}, {1878,1877,2059 ,1792,726,1792 ,0,0,0}, + {1474,1477,1782 ,726,1792,726 ,0,0,0}, {1880,2060,1883 ,726,1792,1792 ,0,0,0}, + {1785,1474,1782 ,1792,726,726 ,0,0,0}, {1437,1884,1440 ,1792,726,1792 ,0,0,0}, + {1474,1787,1472 ,726,1792,1792 ,0,0,0}, {1797,1468,1467 ,1792,726,726 ,0,0,0}, + {1793,1467,1470 ,1792,726,1792 ,0,0,0}, {1484,1483,1805 ,1793,726,1792 ,0,0,0}, + {1468,1797,1799 ,726,1792,1792 ,0,0,0}, {1812,1486,1811 ,1792,1792,1792 ,0,0,0}, + {1486,1484,1809 ,1792,1793,1792 ,0,0,0}, {1495,1492,1823 ,1792,726,726 ,0,0,0}, + {1455,2061,1459 ,1792,726,1792 ,0,0,0}, {2062,2063,2064 ,1792,1792,1792 ,0,0,0}, + {1496,1827,1829 ,726,726,726 ,0,0,0}, {1498,1502,1774 ,1792,1792,1792 ,0,0,0}, + {2065,1516,2066 ,726,726,726 ,0,0,0}, {2067,1526,1516 ,1792,1792,726 ,0,0,0}, + {1519,1515,2068 ,726,726,726 ,0,0,0}, {1518,2069,2066 ,726,1792,726 ,0,0,0}, + {1356,1297,1296 ,726,726,1792 ,0,0,0}, {1340,1339,1320 ,1792,726,726 ,0,0,0}, + {2069,1518,1519 ,1792,726,726 ,0,0,0}, {1886,1437,1889 ,1792,1792,1792 ,0,0,0}, + {1343,1321,1324 ,726,1792,726 ,0,0,0}, {1544,1542,1767 ,1792,1792,1792 ,0,0,0}, + {1929,1889,1435 ,726,1792,1792 ,0,0,0}, {1582,1548,1764 ,1793,726,726 ,0,0,0}, + {1433,1431,1929 ,1792,726,726 ,0,0,0}, {2019,1629,1630 ,726,726,726 ,0,0,0}, + {1975,1656,1971 ,726,726,726 ,0,0,0}, {1658,1975,1977 ,726,726,726 ,0,0,0}, + {1737,1556,1738 ,1792,726,726 ,0,0,0}, {1412,1907,1413 ,1792,726,1792 ,0,0,0}, + {1929,1431,1927 ,726,726,1793 ,0,0,0}, {1924,1927,1430 ,726,1793,726 ,0,0,0}, + {1425,1925,1427 ,726,1792,1792 ,0,0,0}, {1427,1924,1430 ,1792,726,726 ,0,0,0}, + {1415,1911,1915 ,1792,1792,1792 ,0,0,0}, {1421,1918,1424 ,726,1792,726 ,0,0,0}, + {1425,1919,1925 ,726,726,1792 ,0,0,0}, {1917,1418,1915 ,1792,1792,1792 ,0,0,0}, + {1907,1911,1413 ,726,1792,1792 ,0,0,0}, {1908,1409,1904 ,1792,726,726 ,0,0,0}, + {1740,1561,1743 ,726,726,726 ,0,0,0}, {1903,1904,1407 ,1792,726,1792 ,0,0,0}, + {1971,1656,1624 ,726,726,726 ,0,0,0}, {1624,1972,1971 ,726,726,726 ,0,0,0}, + {1972,1624,1620 ,726,726,726 ,0,0,0}, {1626,2013,1619 ,726,726,726 ,0,0,0}, + {1620,2012,1972 ,726,726,726 ,0,0,0}, {1555,1556,1737 ,1792,726,1792 ,0,0,0}, + {2019,2018,1629 ,726,726,726 ,0,0,0}, {2018,1626,1629 ,726,726,726 ,0,0,0}, + {1710,1714,1591 ,726,1792,1792 ,0,0,0}, {2021,2019,1630 ,726,726,726 ,0,0,0}, + {1637,2024,1633 ,726,726,726 ,0,0,0}, {2025,1637,1639 ,726,726,726 ,0,0,0}, + {1637,2025,2024 ,726,726,726 ,0,0,0}, {1636,2027,1639 ,726,726,726 ,0,0,0}, + {2025,1639,2027 ,726,726,726 ,0,0,0}, {2027,1636,2030 ,726,726,726 ,0,0,0}, + {1640,1643,2031 ,726,726,726 ,0,0,0}, {1592,1591,1714 ,726,1792,1792 ,0,0,0}, + {2033,1643,1644 ,726,726,726 ,0,0,0}, {1643,2033,2031 ,726,726,726 ,0,0,0}, + {2037,2036,1646 ,726,726,726 ,0,0,0}, {1731,1609,1606 ,726,1792,1792 ,0,0,0}, + {1644,1646,2036 ,726,726,726 ,0,0,0}, {1650,2039,2037 ,726,726,726 ,0,0,0}, + {2037,1646,1650 ,726,726,726 ,0,0,0}, {2039,1650,1648 ,726,726,726 ,0,0,0}, + {1648,1653,2042 ,726,726,726 ,0,0,0}, {2042,1653,2043 ,726,726,726 ,0,0,0}, + {2043,1655,2045 ,726,726,726 ,0,0,0}, {1733,1612,1610 ,1792,726,1793 ,0,0,0}, + {1655,2043,1653 ,726,726,726 ,0,0,0}, {1534,1770,1768 ,726,726,1793 ,0,0,0}, + {1310,1311,1509 ,1793,726,726 ,0,0,0}, {1580,1582,1762 ,726,1793,726 ,0,0,0}, + {1768,1542,1541 ,1793,1792,1792 ,0,0,0}, {1579,1580,1761 ,1792,726,726 ,0,0,0}, + {1577,1579,1758 ,726,1792,726 ,0,0,0}, {1764,1548,1547 ,726,726,726 ,0,0,0}, + {1574,1577,1756 ,1792,726,1792 ,0,0,0}, {1764,1762,1582 ,726,726,1793 ,0,0,0}, + {1573,1574,1755 ,726,1792,1792 ,0,0,0}, {1762,1761,1580 ,726,726,726 ,0,0,0}, + {1571,1573,1752 ,1792,726,1792 ,0,0,0}, {1761,1758,1579 ,726,726,1792 ,0,0,0}, + {1568,1750,1749 ,1792,726,726 ,0,0,0}, {1758,1756,1577 ,726,1792,726 ,0,0,0}, + {1567,1749,1746 ,726,726,1792 ,0,0,0}, {1756,1755,1574 ,1792,1792,1792 ,0,0,0}, + {1565,1746,1744 ,1792,1792,726 ,0,0,0}, {1743,1562,1744 ,726,1792,726 ,0,0,0}, + {1568,1571,1750 ,1792,1792,726 ,0,0,0}, {1740,1738,1559 ,726,726,1792 ,0,0,0}, + {1568,1749,1567 ,1792,726,726 ,0,0,0}, {1977,1978,1661 ,726,726,726 ,0,0,0}, + {1746,1565,1567 ,1792,1792,726 ,0,0,0}, {1978,1981,1662 ,726,726,726 ,0,0,0}, + {1744,1562,1565 ,726,1792,1792 ,0,0,0}, {1981,1983,1664 ,726,726,726 ,0,0,0}, + {1400,1893,1401 ,1792,1792,726 ,0,0,0}, {1401,1897,1403 ,726,1792,726 ,0,0,0}, + {1738,1556,1559 ,726,726,1792 ,0,0,0}, {1667,1664,1983 ,726,726,726 ,0,0,0}, + {1658,1656,1975 ,726,726,726 ,0,0,0}, {1667,1984,1668 ,726,726,726 ,0,0,0}, + {1661,1658,1977 ,726,726,726 ,0,0,0}, {1987,1670,1668 ,726,726,726 ,0,0,0}, + {1662,1661,1978 ,726,726,726 ,0,0,0}, {1989,1673,1670 ,726,726,726 ,0,0,0}, + {1664,1662,1981 ,726,726,726 ,0,0,0}, {1364,1934,1363 ,726,1792,1792 ,0,0,0}, + {1674,1673,1990 ,726,726,726 ,0,0,0}, {1983,1984,1667 ,726,726,726 ,0,0,0}, + {1676,1674,1993 ,726,726,726 ,0,0,0}, {1676,1993,1995 ,726,726,726 ,0,0,0}, + {1367,1938,1937 ,1792,1792,726 ,0,0,0}, {1987,1989,1670 ,726,726,726 ,0,0,0}, + {1370,1943,1940 ,1792,1792,1792 ,0,0,0}, {1996,1679,1995 ,726,726,726 ,0,0,0}, + {1989,1990,1673 ,726,726,726 ,0,0,0}, {1680,1996,1999 ,726,726,726 ,0,0,0}, + {1990,1993,1674 ,726,726,726 ,0,0,0}, {1376,1949,1946 ,1792,1793,1792 ,0,0,0}, + {1995,1679,1676 ,726,726,726 ,0,0,0}, {1999,2001,1682 ,726,726,726 ,0,0,0}, + {1680,1679,1996 ,726,726,726 ,0,0,0}, {2002,1685,2001 ,726,726,726 ,0,0,0}, + {1379,1381,1950 ,726,1792,1792 ,0,0,0}, {2005,1686,2002 ,726,726,726 ,0,0,0}, + {1682,1680,1999 ,726,726,726 ,0,0,0}, {1385,1387,1956 ,726,726,726 ,0,0,0}, + {2001,1685,1682 ,726,726,726 ,0,0,0}, {1688,2005,2007 ,726,726,726 ,0,0,0}, + {1388,1391,1961 ,726,1792,726 ,0,0,0}, {2002,1686,1685 ,726,726,726 ,0,0,0}, + {1691,1688,2007 ,1792,726,726 ,0,0,0}, {1692,1691,2008 ,726,1792,726 ,0,0,0}, + {1393,1394,1962 ,726,726,1792 ,0,0,0}, {1691,2007,2008 ,1792,726,726 ,0,0,0}, + {1969,1968,1692 ,1792,726,726 ,0,0,0}, {1968,1397,1692 ,726,726,726 ,0,0,0}, + {2008,1969,1692 ,726,1792,726 ,0,0,0}, {2005,1688,1686 ,726,726,726 ,0,0,0}, + {1555,1737,1701 ,1792,1792,1792 ,0,0,0}, {1553,1701,1704 ,1792,1792,1792 ,0,0,0}, + {1549,1704,1699 ,1792,1792,1792 ,0,0,0}, {1583,1699,1703 ,726,1792,726 ,0,0,0}, + {1703,1706,1585 ,726,1792,1792 ,0,0,0}, {1626,2015,2013 ,726,726,726 ,0,0,0}, + {1701,1553,1555 ,1792,1792,1792 ,0,0,0}, {1706,1709,1586 ,1792,1792,726 ,0,0,0}, + {1704,1549,1553 ,1792,1792,1792 ,0,0,0}, {1630,1633,2021 ,726,726,726 ,0,0,0}, + {1549,1699,1583 ,1792,1792,726 ,0,0,0}, {1710,1588,1709 ,726,726,1792 ,0,0,0}, + {1703,1585,1583 ,726,1792,726 ,0,0,0}, {1592,1714,1713 ,726,1792,1792 ,0,0,0}, + {1706,1586,1585 ,1792,726,1792 ,0,0,0}, {1594,1592,1713 ,1792,726,1792 ,0,0,0}, + {1709,1588,1586 ,1792,726,726 ,0,0,0}, {1717,1597,1594 ,726,1792,1792 ,0,0,0}, + {1710,1591,1588 ,726,1792,726 ,0,0,0}, {1721,1598,1597 ,726,726,1792 ,0,0,0}, + {1723,1600,1598 ,1792,726,726 ,0,0,0}, {2030,1640,2031 ,726,726,726 ,0,0,0}, + {1594,1713,1717 ,1792,1792,726 ,0,0,0}, {1718,1603,1600 ,726,1792,726 ,0,0,0}, + {1597,1717,1721 ,1792,726,726 ,0,0,0}, {1603,1724,1604 ,1792,726,1792 ,0,0,0}, + {1598,1721,1723 ,726,726,1792 ,0,0,0}, {1606,1604,1725 ,1792,1792,726 ,0,0,0}, + {1603,1718,1724 ,1792,726,726 ,0,0,0}, {1609,1731,1730 ,1792,726,1792 ,0,0,0}, + {1604,1724,1725 ,1792,726,726 ,0,0,0}, {1733,1610,1730 ,1792,1793,1792 ,0,0,0}, + {1606,1725,1731 ,1792,726,726 ,0,0,0}, {1733,1615,1612 ,1792,726,726 ,0,0,0}, + {1610,1609,1730 ,1793,1792,1792 ,0,0,0}, {1615,1693,1618 ,726,726,726 ,0,0,0}, + {1695,1618,1693 ,1792,726,726 ,0,0,0}, {2045,1655,1618 ,726,726,726 ,0,0,0}, + {1733,1735,1615 ,1792,726,726 ,0,0,0}, {1600,1723,1718 ,726,1792,726 ,0,0,0}, + {1562,1743,1561 ,1792,726,726 ,0,0,0}, {1573,1755,1752 ,726,1792,1792 ,0,0,0}, + {1571,1752,1750 ,1792,1792,726 ,0,0,0}, {1490,1817,1818 ,1792,726,1792 ,0,0,0}, + {1544,1767,1547 ,1792,1792,726 ,0,0,0}, {1505,1496,1830 ,1792,726,726 ,0,0,0}, + {1768,1767,1542 ,1793,1792,1792 ,0,0,0}, {1532,1535,2070 ,726,1792,1792 ,0,0,0}, + {1534,1768,1541 ,726,1793,1792 ,0,0,0}, {2071,1524,1523 ,1792,1792,726 ,0,0,0}, + {1515,1346,1327 ,726,726,726 ,0,0,0}, {1526,2072,1523 ,1792,726,726 ,0,0,0}, + {1515,1327,2068 ,726,726,726 ,0,0,0}, {1773,1503,1499 ,726,726,1792 ,0,0,0}, + {1495,1823,1824 ,1792,726,726 ,0,0,0}, {2057,1455,1443 ,1792,1792,1792 ,0,0,0}, + {1812,1815,1489 ,1792,1792,1792 ,0,0,0}, {1484,1805,1806 ,1793,1792,1793 ,0,0,0}, + {1793,1794,1467 ,1792,1792,726 ,0,0,0}, {1847,1335,1848 ,1792,1792,1792 ,0,0,0}, + {1470,1788,1791 ,1792,726,1792 ,0,0,0}, {1800,1483,1468 ,726,726,726 ,0,0,0}, + {1483,1800,1803 ,726,726,1792 ,0,0,0}, {1486,1809,1811 ,1792,1792,1792 ,0,0,0}, + {1821,1490,1818 ,726,1792,1792 ,0,0,0}, {1821,1492,1490 ,726,726,1792 ,0,0,0}, + {1496,1495,1827 ,726,1792,726 ,0,0,0}, {1830,1832,1505 ,726,726,1792 ,0,0,0}, + {1505,1774,1502 ,1792,1792,1792 ,0,0,0}, {1499,1498,1773 ,1792,1792,726 ,0,0,0}, + {2071,2073,1524 ,1792,726,1792 ,0,0,0}, {2074,2075,1538 ,726,1792,726 ,0,0,0}, + {2075,2076,1538 ,1792,726,726 ,0,0,0}, {2077,2070,1535 ,726,1792,1792 ,0,0,0}, + {2070,2078,1532 ,1792,726,726 ,0,0,0}, {1503,1773,1770 ,726,726,726 ,0,0,0}, + {1774,1773,1498 ,1792,726,1792 ,0,0,0}, {1774,1505,1832 ,1792,1792,726 ,0,0,0}, + {1830,1496,1829 ,726,726,726 ,0,0,0}, {1827,1495,1824 ,726,1792,726 ,0,0,0}, + {1823,1492,1821 ,726,726,726 ,0,0,0}, {1490,1489,1817 ,1792,1792,726 ,0,0,0}, + {1489,1486,1812 ,1792,1792,1792 ,0,0,0}, {1484,1806,1809 ,1793,1793,1792 ,0,0,0}, + {1483,1803,1805 ,726,1792,1792 ,0,0,0}, {1468,1799,1800 ,726,1792,726 ,0,0,0}, + {1467,1794,1797 ,726,1792,1792 ,0,0,0}, {1470,1791,1793 ,1792,1792,1792 ,0,0,0}, + {1470,1472,1788 ,1792,1792,726 ,0,0,0}, {1474,1785,1787 ,726,1792,1792 ,0,0,0}, + {1477,1781,1782 ,1792,726,726 ,0,0,0}, {1478,1775,1779 ,726,1792,726 ,0,0,0}, + {1479,1835,1833 ,726,1792,1792 ,0,0,0}, {2048,1838,1836 ,1792,726,726 ,0,0,0}, + {2049,1842,1841 ,1792,1792,1792 ,0,0,0}, {2052,1847,1844 ,726,1792,726 ,0,0,0}, + {1266,1333,1264 ,726,1792,1792 ,0,0,0}, {1270,1273,1331 ,1792,1792,1792 ,0,0,0}, + {1850,1848,1263 ,1792,1792,726 ,0,0,0}, {1330,1272,1270 ,1792,726,1792 ,0,0,0}, + {1276,1337,1464 ,1792,726,1792 ,0,0,0}, {2079,2064,2080 ,726,1792,1792 ,0,0,0}, + {1449,2081,1447 ,726,1792,1792 ,0,0,0}, {2082,1449,1450 ,726,726,1792 ,0,0,0}, + {1444,2056,1445 ,1792,1792,726 ,0,0,0}, {1444,1447,2083 ,1792,1792,726 ,0,0,0}, + {2084,1454,2063 ,726,726,1792 ,0,0,0}, {2085,1460,1459 ,1792,1792,1792 ,0,0,0}, + {2079,2055,2054 ,726,1792,1792 ,0,0,0}, {1286,1859,1284 ,1792,1792,1792 ,0,0,0}, + {1281,1856,1854 ,1792,1792,1792 ,0,0,0}, {1290,1292,1865 ,1792,1792,726 ,0,0,0}, + {1287,1862,1860 ,726,726,726 ,0,0,0}, {1871,1293,2051 ,1792,1792,726 ,0,0,0}, + {2051,2058,1871 ,726,1792,1792 ,0,0,0}, {1868,1293,1871 ,726,1792,1792 ,0,0,0}, + {1868,1866,1292 ,726,726,1792 ,0,0,0}, {1874,1872,2058 ,726,726,1792 ,0,0,0}, + {2059,1877,2047 ,1792,726,726 ,0,0,0}, {2047,1874,2058 ,726,726,1792 ,0,0,0}, + {2059,1880,1878 ,1792,726,1792 ,0,0,0}, {2060,1440,1883 ,1792,1792,1792 ,0,0,0}, + {2059,2060,1880 ,1792,1792,726 ,0,0,0}, {1884,1883,1440 ,726,1792,1792 ,0,0,0}, + {1884,1437,1886 ,726,1792,1792 ,0,0,0}, {1889,1437,1435 ,1792,1792,1792 ,0,0,0}, + {1509,1306,1511 ,726,1792,726 ,0,0,0}, {2068,2069,1519 ,726,1792,726 ,0,0,0}, + {1300,1297,1356 ,1792,726,726 ,0,0,0}, {2066,1516,1518 ,726,726,726 ,0,0,0}, + {2067,1516,2065 ,1792,726,726 ,0,0,0}, {2072,1526,2067 ,726,1792,1792 ,0,0,0}, + {2071,1523,2072 ,1792,726,726 ,0,0,0}, {1528,1524,2073 ,1792,1792,726 ,0,0,0}, + {1528,2086,1538 ,1792,1792,726 ,0,0,0}, {2086,1528,2073 ,1792,1792,726 ,0,0,0}, + {2086,2074,1538 ,1792,726,726 ,0,0,0}, {1535,2076,2077 ,1792,726,726 ,0,0,0}, + {2076,1535,1538 ,726,1792,726 ,0,0,0}, {1534,1313,1770 ,726,726,726 ,0,0,0}, + {2078,1313,1534 ,726,726,726 ,0,0,0}, {2078,1534,1532 ,726,726,726 ,0,0,0}, + {1313,1310,1770 ,726,1793,726 ,0,0,0}, {1508,1310,1509 ,1792,1793,726 ,0,0,0}, + {1310,1508,1770 ,1793,1792,726 ,0,0,0}, {1311,1306,1509 ,726,1792,726 ,0,0,0}, + {1304,1307,1511 ,726,726,726 ,0,0,0}, {1306,1304,1511 ,1792,726,726 ,0,0,0}, + {1307,1298,1514 ,726,726,726 ,0,0,0}, {1300,1356,1514 ,1792,726,726 ,0,0,0}, + {1354,1356,1296 ,1792,726,1792 ,0,0,0}, {1318,1353,1315 ,726,1792,726 ,0,0,0}, + {1315,1354,1296 ,726,1792,1792 ,0,0,0}, {1320,1351,1318 ,726,726,726 ,0,0,0}, + {1320,1321,1340 ,726,1792,1792 ,0,0,0}, {1320,1339,1351 ,726,726,726 ,0,0,0}, + {1343,1324,1344 ,726,726,1792 ,0,0,0}, {1340,1321,1343 ,1792,1792,726 ,0,0,0}, + {1346,1326,1327 ,726,1793,726 ,0,0,0}, {1344,1324,1326 ,1792,726,1793 ,0,0,0}, + {1460,2087,1462 ,1792,726,1792 ,0,0,0}, {2051,2050,2055 ,726,726,1792 ,0,0,0}, + {1464,1462,1279 ,1792,1792,1792 ,0,0,0}, {2079,2080,2055 ,726,1792,1792 ,0,0,0}, + {2064,2063,2080 ,1792,1792,1792 ,0,0,0}, {2084,2063,2062 ,726,1792,1792 ,0,0,0}, + {2053,1454,2084 ,1792,726,726 ,0,0,0}, {2082,1450,2053 ,726,1792,1792 ,0,0,0}, + {2081,1449,2082 ,1792,726,726 ,0,0,0}, {2083,1447,2081 ,726,1792,1792 ,0,0,0}, + {2056,1444,2083 ,1792,1792,726 ,0,0,0}, {1443,1445,2057 ,1792,726,1792 ,0,0,0}, + {2061,1455,2057 ,726,1792,1792 ,0,0,0}, {2085,1459,2061 ,1792,1792,726 ,0,0,0}, + {2087,1460,2085 ,726,1792,1792 ,0,0,0}, {1279,1462,2087 ,1792,1792,726 ,0,0,0}, + {1276,1464,1279 ,1792,1792,1792 ,0,0,0}, {1277,1337,1276 ,1792,726,1792 ,0,0,0}, + {1330,1277,1272 ,1792,1792,726 ,0,0,0}, {1277,1330,1337 ,1792,1792,726 ,0,0,0}, + {1270,1331,1330 ,1792,1792,1792 ,0,0,0}, {1335,1333,1266 ,1792,1792,726 ,0,0,0}, + {1850,1263,1262 ,1792,726,726 ,0,0,0}, {1263,1848,1335 ,726,1792,1792 ,0,0,0}, + {1281,1854,1262 ,1792,1792,726 ,0,0,0}, {1853,1850,1262 ,726,1792,726 ,0,0,0}, + {1284,1856,1281 ,1792,1792,1792 ,0,0,0}, {1286,1860,1859 ,1792,726,1792 ,0,0,0}, + {1284,1859,1856 ,1792,1792,1792 ,0,0,0}, {1287,1290,1862 ,726,1792,726 ,0,0,0}, + {1286,1287,1860 ,1792,726,726 ,0,0,0}, {1865,1292,1866 ,726,1792,726 ,0,0,0}, + {1862,1290,1865 ,726,1792,726 ,0,0,0}, {1868,1292,1293 ,726,1792,1792 ,0,0,0}, + {1616,1734,1732 ,730,730,730 ,0,0,0}, {1398,1894,1359 ,730,730,730 ,0,0,0}, + {1469,1802,1801 ,730,730,730 ,0,0,0}, {1728,1611,1729 ,730,730,730 ,0,0,0}, + {1602,1605,1720 ,730,730,730 ,0,0,0}, {1607,1608,1727 ,730,730,730 ,0,0,0}, + {1593,1595,1712 ,730,730,730 ,0,0,0}, {1596,1599,1716 ,730,730,730 ,0,0,0}, + {1697,1700,1551 ,730,730,730 ,0,0,0}, {1587,1589,1707 ,730,730,730 ,0,0,0}, + {1896,1360,1359 ,730,730,730 ,0,0,0}, {1741,1558,1739 ,730,730,730 ,0,0,0}, + {1368,1936,1939 ,730,730,730 ,0,0,0}, {1942,1945,1374 ,730,730,730 ,0,0,0}, + {1930,1933,1362 ,730,730,730 ,0,0,0}, {1936,1368,1366 ,730,730,730 ,0,0,0}, + {1399,1892,1891 ,730,730,730 ,0,0,0}, {1360,1896,1930 ,730,730,730 ,0,0,0}, + {1404,1405,1901 ,730,730,730 ,0,0,0}, {1974,1657,1976 ,730,730,730 ,0,0,0}, + {1902,1408,1905 ,730,730,730 ,0,0,0}, {1405,1902,1901 ,730,730,730 ,0,0,0}, + {1417,1916,1416 ,730,730,730 ,0,0,0}, {1410,1906,1905 ,730,730,730 ,0,0,0}, + {1923,1922,1428 ,730,730,730 ,0,0,0}, {1921,1920,1423 ,730,730,730 ,0,0,0}, + {1429,1432,1926 ,730,730,730 ,0,0,0}, {2088,1840,1843 ,730,730,730 ,0,0,0}, + {1475,1473,1784 ,730,730,730 ,0,0,0}, {1278,1338,1336 ,730,730,730 ,0,0,0}, + {1288,1863,1864 ,730,730,730 ,0,0,0}, {1438,1888,1890 ,730,730,730 ,0,0,0}, + {1928,1436,1890 ,730,730,730 ,0,0,0}, {2089,2090,1882 ,730,730,730 ,0,0,0}, + {1291,1289,1867 ,730,730,730 ,0,0,0}, {2089,1882,1885 ,730,730,730 ,0,0,0}, + {1879,1881,2090 ,730,730,730 ,0,0,0}, {1441,2091,1442 ,730,730,730 ,0,0,0}, + {1890,1436,1438 ,730,730,730 ,0,0,0}, {1802,1469,1482 ,730,730,730 ,0,0,0}, + {2092,1481,1839 ,730,730,730 ,0,0,0}, {1780,1778,1476 ,730,730,730 ,0,0,0}, + {1288,1864,1289 ,730,730,730 ,0,0,0}, {1334,1849,1851 ,730,730,730 ,0,0,0}, + {1432,1434,1928 ,730,730,730 ,0,0,0}, {1332,1265,1329 ,730,730,730 ,0,0,0}, + {1268,1269,1329 ,730,730,730 ,0,0,0}, {2093,1457,1458 ,730,730,730 ,0,0,0}, + {2089,1885,1439 ,730,730,730 ,0,0,0}, {1438,1439,1887 ,730,730,730 ,0,0,0}, + {2094,1879,2090 ,730,730,730 ,0,0,0}, {1875,1876,2095 ,730,730,730 ,0,0,0}, + {2095,1876,2094 ,730,730,730 ,0,0,0}, {2094,1876,1879 ,730,730,730 ,0,0,0}, + {2090,1881,1882 ,730,730,730 ,0,0,0}, {2096,2097,2098 ,730,730,730 ,0,0,0}, + {1347,1348,1325 ,730,730,730 ,0,0,0}, {1885,1887,1439 ,730,730,730 ,0,0,0}, + {1869,1291,1867 ,730,730,730 ,0,0,0}, {1888,1438,1887 ,730,730,730 ,0,0,0}, + {2099,1453,1451 ,730,730,730 ,0,0,0}, {1458,1461,2100 ,730,730,730 ,0,0,0}, + {1463,1338,1275 ,730,730,730 ,0,0,0}, {1461,1463,1274 ,730,730,730 ,0,0,0}, + {1928,1434,1436 ,730,730,730 ,0,0,0}, {1442,2101,1446 ,730,730,730 ,0,0,0}, + {2102,1456,1457 ,730,730,730 ,0,0,0}, {1334,1851,1261 ,730,730,730 ,0,0,0}, + {1446,2103,1448 ,730,730,730 ,0,0,0}, {1285,1863,1288 ,730,730,730 ,0,0,0}, + {1863,1285,1861 ,730,730,730 ,0,0,0}, {1776,1480,1777 ,730,730,730 ,0,0,0}, + {1792,1466,1795 ,730,730,730 ,0,0,0}, {1789,1786,1471 ,730,730,730 ,0,0,0}, + {1810,1808,1485 ,730,730,730 ,0,0,0}, {1798,1465,1469 ,730,730,730 ,0,0,0}, + {1810,1485,1487 ,730,730,730 ,0,0,0}, {1428,1429,1923 ,730,730,730 ,0,0,0}, + {1432,1928,1926 ,730,730,730 ,0,0,0}, {1926,1923,1429 ,730,730,730 ,0,0,0}, + {1942,1372,1941 ,730,730,730 ,0,0,0}, {1921,1423,1426 ,730,730,730 ,0,0,0}, + {1922,1426,1428 ,730,730,730 ,0,0,0}, {1422,1423,1920 ,730,730,730 ,0,0,0}, + {1921,1426,1922 ,730,730,730 ,0,0,0}, {1422,1914,1420 ,730,730,730 ,0,0,0}, + {1913,1417,1420 ,730,730,730 ,0,0,0}, {1920,1914,1422 ,730,730,730 ,0,0,0}, + {1417,1913,1916 ,730,730,730 ,0,0,0}, {1420,1914,1913 ,730,730,730 ,0,0,0}, + {1751,1570,1569 ,730,730,730 ,0,0,0}, {1910,1414,1416 ,730,730,730 ,0,0,0}, + {1414,1909,1411 ,730,730,730 ,0,0,0}, {1909,1906,1411 ,730,730,730 ,0,0,0}, + {1906,1410,1411 ,730,730,730 ,0,0,0}, {1905,1408,1410 ,730,730,730 ,0,0,0}, + {1902,1405,1408 ,730,730,730 ,0,0,0}, {1402,1899,1892 ,730,730,730 ,0,0,0}, + {1404,1901,1899 ,730,730,730 ,0,0,0}, {1399,1891,1398 ,730,730,730 ,0,0,0}, + {1894,1896,1359 ,730,730,730 ,0,0,0}, {1362,1933,1365 ,730,730,730 ,0,0,0}, + {1366,1365,1935 ,730,730,730 ,0,0,0}, {1368,1939,1371 ,730,730,730 ,0,0,0}, + {1366,1935,1936 ,730,730,730 ,0,0,0}, {1371,1941,1372 ,730,730,730 ,0,0,0}, + {1371,1939,1941 ,730,730,730 ,0,0,0}, {1377,1945,1947 ,730,730,730 ,0,0,0}, + {1374,1372,1942 ,730,730,730 ,0,0,0}, {1378,1377,1947 ,730,730,730 ,0,0,0}, + {1378,1947,1948 ,730,730,730 ,0,0,0}, {1380,1948,1951 ,730,730,730 ,0,0,0}, + {1378,1948,1380 ,730,730,730 ,0,0,0}, {1951,1383,1380 ,730,730,730 ,0,0,0}, + {1951,1953,1383 ,730,730,730 ,0,0,0}, {1383,1953,1384 ,730,730,730 ,0,0,0}, + {1365,1933,1935 ,730,730,730 ,0,0,0}, {1386,1384,1954 ,730,730,730 ,0,0,0}, + {1384,1953,1954 ,730,730,730 ,0,0,0}, {1957,1389,1386 ,730,730,730 ,0,0,0}, + {1957,1386,1954 ,730,730,730 ,0,0,0}, {1389,1959,1390 ,730,730,730 ,0,0,0}, + {1390,1960,1392 ,730,730,730 ,0,0,0}, {1960,1390,1959 ,730,730,730 ,0,0,0}, + {1960,1963,1395 ,730,730,730 ,0,0,0}, {1687,2006,2004 ,730,730,730 ,0,0,0}, + {1396,1395,1963 ,730,730,730 ,0,0,0}, {1966,1970,1690 ,730,730,730 ,0,0,0}, + {1689,2009,2006 ,730,730,730 ,0,0,0}, {1362,1360,1930 ,730,730,730 ,0,0,0}, + {1623,2010,1621 ,730,730,730 ,0,0,0}, {2009,1689,1690 ,730,730,730 ,0,0,0}, + {1891,1894,1398 ,730,730,730 ,0,0,0}, {1745,1563,1742 ,730,730,730 ,0,0,0}, + {1566,1564,1747 ,730,730,730 ,0,0,0}, {1564,1563,1745 ,730,730,730 ,0,0,0}, + {1560,1558,1741 ,730,730,730 ,0,0,0}, {1741,1742,1560 ,730,730,730 ,0,0,0}, + {1739,1557,1736 ,730,730,730 ,0,0,0}, {1739,1558,1557 ,730,730,730 ,0,0,0}, + {1702,1736,1554 ,730,730,730 ,0,0,0}, {1557,1554,1736 ,730,730,730 ,0,0,0}, + {1552,1700,1702 ,730,730,730 ,0,0,0}, {1702,1554,1552 ,730,730,730 ,0,0,0}, + {1698,1550,1584 ,730,730,730 ,0,0,0}, {1551,1700,1552 ,730,730,730 ,0,0,0}, + {1584,1587,1705 ,730,730,730 ,0,0,0}, {1550,1698,1697 ,730,730,730 ,0,0,0}, + {1698,1584,1705 ,730,730,730 ,0,0,0}, {1711,1708,1590 ,730,730,730 ,0,0,0}, + {1632,2022,2023 ,730,730,730 ,0,0,0}, {1593,1711,1590 ,730,730,730 ,0,0,0}, + {1589,1590,1708 ,730,730,730 ,0,0,0}, {1715,1596,1716 ,730,730,730 ,0,0,0}, + {1712,1711,1593 ,730,730,730 ,0,0,0}, {1599,1722,1716 ,730,730,730 ,0,0,0}, + {1596,1715,1595 ,730,730,730 ,0,0,0}, {1602,1719,1601 ,730,730,730 ,0,0,0}, + {1601,1719,1722 ,730,730,730 ,0,0,0}, {1726,1720,1605 ,730,730,730 ,0,0,0}, + {1720,1719,1602 ,730,730,730 ,0,0,0}, {1608,1728,1727 ,730,730,730 ,0,0,0}, + {1607,1727,1726 ,730,730,730 ,0,0,0}, {1732,1613,1614 ,730,730,730 ,0,0,0}, + {1613,1729,1611 ,730,730,730 ,0,0,0}, {1732,1614,1616 ,730,730,730 ,0,0,0}, + {1963,1965,1396 ,730,730,730 ,0,0,0}, {1966,1396,1965 ,730,730,730 ,0,0,0}, + {1684,2003,1683 ,730,730,730 ,0,0,0}, {1395,1392,1960 ,730,730,730 ,0,0,0}, + {1689,2006,1687 ,730,730,730 ,0,0,0}, {1389,1957,1959 ,730,730,730 ,0,0,0}, + {1681,1683,2000 ,730,730,730 ,0,0,0}, {2004,2003,1684 ,730,730,730 ,0,0,0}, + {1678,1681,1998 ,730,730,730 ,0,0,0}, {2003,2000,1683 ,730,730,730 ,0,0,0}, + {1997,1677,1678 ,730,730,730 ,0,0,0}, {1994,1675,1677 ,730,730,730 ,0,0,0}, + {1998,1681,2000 ,730,730,730 ,0,0,0}, {1992,1672,1675 ,730,730,730 ,0,0,0}, + {1997,1678,1998 ,730,730,730 ,0,0,0}, {1374,1945,1377 ,730,730,730 ,0,0,0}, + {1997,1994,1677 ,730,730,730 ,0,0,0}, {1991,1988,1671 ,730,730,730 ,0,0,0}, + {1994,1992,1675 ,730,730,730 ,0,0,0}, {1988,1986,1669 ,730,730,730 ,0,0,0}, + {1986,1985,1666 ,730,730,730 ,0,0,0}, {1985,1982,1665 ,730,730,730 ,0,0,0}, + {1672,1991,1671 ,730,730,730 ,0,0,0}, {1982,1980,1663 ,730,730,730 ,0,0,0}, + {1671,1988,1669 ,730,730,730 ,0,0,0}, {1979,1660,1980 ,730,730,730 ,0,0,0}, + {1669,1986,1666 ,730,730,730 ,0,0,0}, {1659,1979,1976 ,730,730,730 ,0,0,0}, + {1666,1985,1665 ,730,730,730 ,0,0,0}, {1657,1974,1622 ,730,730,730 ,0,0,0}, + {1665,1982,1663 ,730,730,730 ,0,0,0}, {1623,1622,1973 ,730,730,730 ,0,0,0}, + {1980,1660,1663 ,730,730,730 ,0,0,0}, {1621,2011,1625 ,730,730,730 ,0,0,0}, + {1659,1660,1979 ,730,730,730 ,0,0,0}, {1748,1566,1747 ,730,730,730 ,0,0,0}, + {1404,1899,1402 ,730,730,730 ,0,0,0}, {1402,1892,1399 ,730,730,730 ,0,0,0}, + {1622,1974,1973 ,730,730,730 ,0,0,0}, {1748,1751,1569 ,730,730,730 ,0,0,0}, + {1623,1973,2010 ,730,730,730 ,0,0,0}, {1751,1753,1570 ,730,730,730 ,0,0,0}, + {1621,2010,2011 ,730,730,730 ,0,0,0}, {1753,1754,1572 ,730,730,730 ,0,0,0}, + {1754,1757,1575 ,730,730,730 ,0,0,0}, {1745,1747,1564 ,730,730,730 ,0,0,0}, + {1757,1759,1576 ,730,730,730 ,0,0,0}, {1569,1566,1748 ,730,730,730 ,0,0,0}, + {1759,1760,1578 ,730,730,730 ,0,0,0}, {1416,1916,1910 ,730,730,730 ,0,0,0}, + {1414,1910,1909 ,730,730,730 ,0,0,0}, {1753,1572,1570 ,730,730,730 ,0,0,0}, + {1545,1763,1765 ,730,730,730 ,0,0,0}, {1754,1575,1572 ,730,730,730 ,0,0,0}, + {1537,2104,2105 ,730,730,730 ,0,0,0}, {1757,1576,1575 ,730,730,730 ,0,0,0}, + {1342,1345,1322 ,730,730,730 ,0,0,0}, {1316,1350,1317 ,730,730,730 ,0,0,0}, + {1581,1763,1546 ,730,730,730 ,0,0,0}, {1500,1769,1771 ,730,730,730 ,0,0,0}, + {1506,1504,1772 ,730,730,730 ,0,0,0}, {1319,1341,1342 ,730,730,730 ,0,0,0}, + {1494,1828,1826 ,730,730,730 ,0,0,0}, {2106,1520,2107 ,730,730,730 ,0,0,0}, + {1769,1500,1507 ,730,730,730 ,0,0,0}, {1488,1819,1816 ,730,730,730 ,0,0,0}, + {1870,1294,1291 ,730,730,730 ,0,0,0}, {2108,1873,2095 ,730,730,730 ,0,0,0}, + {1875,2095,1873 ,730,730,730 ,0,0,0}, {1873,2108,1294 ,730,730,730 ,0,0,0}, + {2109,2110,2111 ,730,730,730 ,0,0,0}, {1873,1294,1870 ,730,730,730 ,0,0,0}, + {1869,1870,1291 ,730,730,730 ,0,0,0}, {1271,1336,1269 ,730,730,730 ,0,0,0}, + {2102,2091,1456 ,730,730,730 ,0,0,0}, {2112,2113,2114 ,730,730,730 ,0,0,0}, + {1776,1834,1480 ,730,730,730 ,0,0,0}, {1466,1790,1471 ,730,730,730 ,0,0,0}, + {1807,1482,1485 ,730,730,730 ,0,0,0}, {1820,1491,1493 ,730,730,730 ,0,0,0}, + {1820,1819,1491 ,730,730,730 ,0,0,0}, {1822,1493,1825 ,730,730,730 ,0,0,0}, + {1816,1814,1488 ,730,730,730 ,0,0,0}, {1814,1813,1487 ,730,730,730 ,0,0,0}, + {1482,1807,1804 ,730,730,730 ,0,0,0}, {1798,1796,1465 ,730,730,730 ,0,0,0}, + {1465,1795,1466 ,730,730,730 ,0,0,0}, {1790,1789,1471 ,730,730,730 ,0,0,0}, + {1784,1783,1475 ,730,730,730 ,0,0,0}, {1780,1476,1475 ,730,730,730 ,0,0,0}, + {1825,1494,1826 ,730,730,730 ,0,0,0}, {1778,1777,1476 ,730,730,730 ,0,0,0}, + {1834,1481,1480 ,730,730,730 ,0,0,0}, {1837,1839,1481 ,730,730,730 ,0,0,0}, + {1845,2115,2088 ,730,730,730 ,0,0,0}, {2115,1845,1846 ,730,730,730 ,0,0,0}, + {1334,2115,1849 ,730,730,730 ,0,0,0}, {1280,1852,1855 ,730,730,730 ,0,0,0}, + {1283,1282,1858 ,730,730,730 ,0,0,0}, {1280,1261,1852 ,730,730,730 ,0,0,0}, + {1846,1849,2115 ,730,730,730 ,0,0,0}, {1843,1845,2088 ,730,730,730 ,0,0,0}, + {1839,1840,2092 ,730,730,730 ,0,0,0}, {1840,2088,2092 ,730,730,730 ,0,0,0}, + {1834,1837,1481 ,730,730,730 ,0,0,0}, {1777,1480,1476 ,730,730,730 ,0,0,0}, + {1780,1475,1783 ,730,730,730 ,0,0,0}, {1473,1471,1786 ,730,730,730 ,0,0,0}, + {1473,1786,1784 ,730,730,730 ,0,0,0}, {1466,1792,1790 ,730,730,730 ,0,0,0}, + {1465,1796,1795 ,730,730,730 ,0,0,0}, {1469,1801,1798 ,730,730,730 ,0,0,0}, + {1482,1804,1802 ,730,730,730 ,0,0,0}, {1485,1808,1807 ,730,730,730 ,0,0,0}, + {1487,1813,1810 ,730,730,730 ,0,0,0}, {1487,1488,1814 ,730,730,730 ,0,0,0}, + {1488,1491,1819 ,730,730,730 ,0,0,0}, {1493,1822,1820 ,730,730,730 ,0,0,0}, + {1493,1494,1825 ,730,730,730 ,0,0,0}, {1494,1506,1828 ,730,730,730 ,0,0,0}, + {1506,1772,1831 ,730,730,730 ,0,0,0}, {1828,1506,1831 ,730,730,730 ,0,0,0}, + {1772,1504,1501 ,730,730,730 ,0,0,0}, {1501,1497,1771 ,730,730,730 ,0,0,0}, + {1771,1772,1501 ,730,730,730 ,0,0,0}, {1323,1322,1345 ,730,730,730 ,0,0,0}, + {1500,1771,1497 ,730,730,730 ,0,0,0}, {1302,1512,1513 ,730,730,730 ,0,0,0}, + {1323,1345,1347 ,730,730,730 ,0,0,0}, {1348,1521,1328 ,730,730,730 ,0,0,0}, + {1347,1325,1323 ,730,730,730 ,0,0,0}, {1348,1328,1325 ,730,730,730 ,0,0,0}, + {1529,2116,1522 ,730,730,730 ,0,0,0}, {1525,2117,1517 ,730,730,730 ,0,0,0}, + {2118,1530,2119 ,730,730,730 ,0,0,0}, {1537,2120,2119 ,730,730,730 ,0,0,0}, + {1352,1314,1355 ,730,730,730 ,0,0,0}, {2121,1536,2122 ,730,730,730 ,0,0,0}, + {1316,1314,1352 ,730,730,730 ,0,0,0}, {1765,1540,1543 ,730,730,730 ,0,0,0}, + {1766,1539,1540 ,730,730,730 ,0,0,0}, {1305,1512,1303 ,730,730,730 ,0,0,0}, + {1513,1299,1302 ,730,730,730 ,0,0,0}, {1305,1312,1510 ,730,730,730 ,0,0,0}, + {1533,1539,1766 ,730,730,730 ,0,0,0}, {1533,1766,1769 ,730,730,730 ,0,0,0}, + {1540,1765,1766 ,730,730,730 ,0,0,0}, {1545,1765,1543 ,730,730,730 ,0,0,0}, + {1546,1763,1545 ,730,730,730 ,0,0,0}, {1760,1763,1581 ,730,730,730 ,0,0,0}, + {1578,1760,1581 ,730,730,730 ,0,0,0}, {1576,1759,1578 ,730,730,730 ,0,0,0}, + {1625,2014,1627 ,730,730,730 ,0,0,0}, {2017,1627,2016 ,730,730,730 ,0,0,0}, + {1560,1742,1563 ,730,730,730 ,0,0,0}, {2020,1628,2017 ,730,730,730 ,0,0,0}, + {2020,1631,1628 ,730,730,730 ,0,0,0}, {2022,1632,1631 ,730,730,730 ,0,0,0}, + {2014,1625,2011 ,730,730,730 ,0,0,0}, {2023,1638,1632 ,730,730,730 ,0,0,0}, + {2016,1627,2014 ,730,730,730 ,0,0,0}, {1550,1697,1551 ,730,730,730 ,0,0,0}, + {1634,1638,2026 ,730,730,730 ,0,0,0}, {1628,1627,2017 ,730,730,730 ,0,0,0}, + {1635,1634,2028 ,730,730,730 ,0,0,0}, {2020,2022,1631 ,730,730,730 ,0,0,0}, + {1641,1635,2029 ,730,730,730 ,0,0,0}, {1589,1708,1707 ,730,730,730 ,0,0,0}, + {1587,1707,1705 ,730,730,730 ,0,0,0}, {1638,2023,2026 ,730,730,730 ,0,0,0}, + {1642,1641,2032 ,730,730,730 ,0,0,0}, {1642,2032,2034 ,730,730,730 ,0,0,0}, + {2026,2028,1634 ,730,730,730 ,0,0,0}, {1595,1715,1712 ,730,730,730 ,0,0,0}, + {1635,2028,2029 ,730,730,730 ,0,0,0}, {2034,2035,1645 ,730,730,730 ,0,0,0}, + {2038,1651,2035 ,730,730,730 ,0,0,0}, {2029,2032,1641 ,730,730,730 ,0,0,0}, + {1645,1642,2034 ,730,730,730 ,0,0,0}, {2040,1649,2038 ,730,730,730 ,0,0,0}, + {1599,1601,1722 ,730,730,730 ,0,0,0}, {2041,1647,2040 ,730,730,730 ,0,0,0}, + {1651,1645,2035 ,730,730,730 ,0,0,0}, {1605,1607,1726 ,730,730,730 ,0,0,0}, + {2038,1649,1651 ,730,730,730 ,0,0,0}, {2041,2044,1652 ,730,730,730 ,0,0,0}, + {1608,1611,1728 ,730,730,730 ,0,0,0}, {2040,1647,1649 ,730,730,730 ,0,0,0}, + {1654,1652,2044 ,730,730,730 ,0,0,0}, {1654,2046,1617 ,730,730,730 ,0,0,0}, + {1729,1613,1732 ,730,730,730 ,0,0,0}, {1654,2044,2046 ,730,730,730 ,0,0,0}, + {1696,1616,1617 ,730,730,730 ,0,0,0}, {1734,1616,1696 ,730,730,730 ,0,0,0}, + {2046,1694,1617 ,730,730,730 ,0,0,0}, {1696,1617,1694 ,730,730,730 ,0,0,0}, + {2041,1652,1647 ,730,730,730 ,0,0,0}, {1657,1659,1976 ,730,730,730 ,0,0,0}, + {1991,1672,1992 ,730,730,730 ,0,0,0}, {2004,1684,1687 ,730,730,730 ,0,0,0}, + {1966,1690,1396 ,730,730,730 ,0,0,0}, {1970,2009,1690 ,730,730,730 ,0,0,0}, + {1317,1349,1319 ,730,730,730 ,0,0,0}, {2123,1525,1527 ,730,730,730 ,0,0,0}, + {1529,2118,2116 ,730,730,730 ,0,0,0}, {1319,1342,1322 ,730,730,730 ,0,0,0}, + {1319,1349,1341 ,730,730,730 ,0,0,0}, {1317,1350,1349 ,730,730,730 ,0,0,0}, + {1316,1352,1350 ,730,730,730 ,0,0,0}, {1531,1533,2124 ,730,730,730 ,0,0,0}, + {1295,1301,1355 ,730,730,730 ,0,0,0}, {1295,1355,1314 ,730,730,730 ,0,0,0}, + {1513,1301,1299 ,730,730,730 ,0,0,0}, {1301,1513,1355 ,730,730,730 ,0,0,0}, + {1308,1533,1769 ,730,730,730 ,0,0,0}, {1305,1510,1512 ,730,730,730 ,0,0,0}, + {1302,1303,1512 ,730,730,730 ,0,0,0}, {1309,1510,1312 ,730,730,730 ,0,0,0}, + {1769,1309,1308 ,730,730,730 ,0,0,0}, {1507,1309,1769 ,730,730,730 ,0,0,0}, + {1309,1507,1510 ,730,730,730 ,0,0,0}, {1308,2124,1533 ,730,730,730 ,0,0,0}, + {1531,2122,1536 ,730,730,730 ,0,0,0}, {2124,2122,1531 ,730,730,730 ,0,0,0}, + {1536,2104,1537 ,730,730,730 ,0,0,0}, {2121,2104,1536 ,730,730,730 ,0,0,0}, + {2105,2120,1537 ,730,730,730 ,0,0,0}, {2119,1530,1537 ,730,730,730 ,0,0,0}, + {2118,1529,1530 ,730,730,730 ,0,0,0}, {2125,1522,2116 ,730,730,730 ,0,0,0}, + {1527,2125,2123 ,730,730,730 ,0,0,0}, {2125,1527,1522 ,730,730,730 ,0,0,0}, + {2123,2126,1525 ,730,730,730 ,0,0,0}, {2117,2107,1517 ,730,730,730 ,0,0,0}, + {2126,2117,1525 ,730,730,730 ,0,0,0}, {1520,2106,1521 ,730,730,730 ,0,0,0}, + {1517,2107,1520 ,730,730,730 ,0,0,0}, {1328,1521,2106 ,730,730,730 ,0,0,0}, + {1332,1334,1267 ,730,730,730 ,0,0,0}, {1864,1867,1289 ,730,730,730 ,0,0,0}, + {1451,1448,2127 ,730,730,730 ,0,0,0}, {1283,1858,1861 ,730,730,730 ,0,0,0}, + {1861,1285,1283 ,730,730,730 ,0,0,0}, {1857,1858,1282 ,730,730,730 ,0,0,0}, + {1857,1280,1855 ,730,730,730 ,0,0,0}, {1280,1857,1282 ,730,730,730 ,0,0,0}, + {1852,1261,1851 ,730,730,730 ,0,0,0}, {1261,1267,1334 ,730,730,730 ,0,0,0}, + {1267,1265,1332 ,730,730,730 ,0,0,0}, {1265,1268,1329 ,730,730,730 ,0,0,0}, + {1269,1336,1329 ,730,730,730 ,0,0,0}, {1278,1336,1271 ,730,730,730 ,0,0,0}, + {1275,1338,1278 ,730,730,730 ,0,0,0}, {1274,1463,1275 ,730,730,730 ,0,0,0}, + {2100,1461,1274 ,730,730,730 ,0,0,0}, {2093,1458,2100 ,730,730,730 ,0,0,0}, + {2102,1457,2093 ,730,730,730 ,0,0,0}, {1441,1456,2091 ,730,730,730 ,0,0,0}, + {2101,1442,2091 ,730,730,730 ,0,0,0}, {2103,1446,2101 ,730,730,730 ,0,0,0}, + {2127,1448,2103 ,730,730,730 ,0,0,0}, {2128,1453,2099 ,730,730,730 ,0,0,0}, + {2099,1451,2127 ,730,730,730 ,0,0,0}, {1452,2128,2114 ,730,730,730 ,0,0,0}, + {2128,1452,1453 ,730,730,730 ,0,0,0}, {2112,2097,2113 ,730,730,730 ,0,0,0}, + {1452,2114,2113 ,730,730,730 ,0,0,0}, {2096,2098,2109 ,730,730,730 ,0,0,0}, + {2113,2097,2096 ,730,730,730 ,0,0,0}, {2109,2111,2108 ,730,730,730 ,0,0,0}, + {2109,2098,2110 ,730,730,730 ,0,0,0}, {1294,2108,2111 ,730,730,730 ,0,0,0}, + {2108,2095,2058 ,1794,1795,1796 ,0,0,0}, {2109,2051,2055 ,1797,1798,1799 ,0,0,0}, + {2051,2108,2058 ,1798,1794,1796 ,0,0,0}, {2108,2051,2109 ,1794,1798,1797 ,0,0,0}, + {2113,2080,2063 ,1800,1801,1802 ,0,0,0}, {2109,2055,2096 ,1797,1799,1803 ,0,0,0}, + {2113,2096,2080 ,1800,1803,1801 ,0,0,0}, {2063,1454,1452 ,1802,1217,1217 ,0,0,0}, + {2063,1452,2113 ,1802,1217,1800 ,0,0,0}, {2080,2096,2055 ,1801,1803,1799 ,0,0,0}, + {2095,2047,2058 ,1795,1804,1796 ,0,0,0}, {2059,2047,2094 ,1805,1804,1806 ,0,0,0}, + {2095,2094,2047 ,1795,1806,1804 ,0,0,0}, {2090,2060,2059 ,1807,1808,1805 ,0,0,0}, + {2059,2094,2090 ,1805,1806,1807 ,0,0,0}, {2060,2089,1440 ,1808,1809,1206 ,0,0,0}, + {2089,2060,2090 ,1809,1808,1807 ,0,0,0}, {2089,1439,1440 ,1809,1206,1206 ,0,0,0}, + {1335,2052,2115 ,1112,1810,1810 ,0,0,0}, {2048,1481,2092 ,1811,1243,1812 ,0,0,0}, + {2092,2088,2049 ,1812,1813,1813 ,0,0,0}, {1479,1481,2048 ,1243,1243,1811 ,0,0,0}, + {2052,2088,2115 ,1810,1813,1810 ,0,0,0}, {2088,2052,2049 ,1813,1810,1813 ,0,0,0}, + {2048,2092,2049 ,1811,1812,1813 ,0,0,0}, {2115,1334,1335 ,1810,1112,1112 ,0,0,0}, + {1313,2078,2124 ,1814,1815,1816 ,0,0,0}, {2076,2104,2077 ,1817,1818,1819 ,0,0,0}, + {2121,2122,2070 ,1820,1821,1822 ,0,0,0}, {2119,2086,2118 ,1823,1824,82 ,0,0,0}, + {2075,2074,2120 ,1825,1826,1827 ,0,0,0}, {2072,2123,2125 ,1828,1829,1830 ,0,0,0}, + {2071,2116,2073 ,1831,1832,1833 ,0,0,0}, {2065,2117,2126 ,1834,1835,1836 ,0,0,0}, + {2126,2123,2067 ,1836,1829,1837 ,0,0,0}, {2117,2066,2107 ,1835,1838,1839 ,0,0,0}, + {2066,2117,2065 ,1838,1835,1834 ,0,0,0}, {2106,2107,2069 ,1840,1839,1841 ,0,0,0}, + {2066,2069,2107 ,1838,1841,1839 ,0,0,0}, {2068,1328,2106 ,1842,324,1840 ,0,0,0}, + {2106,2069,2068 ,1840,1841,1842 ,0,0,0}, {1327,1328,2068 ,1843,324,1842 ,0,0,0}, + {2071,2072,2125 ,1831,1828,1830 ,0,0,0}, {2123,2072,2067 ,1829,1828,1837 ,0,0,0}, + {2065,2126,2067 ,1834,1836,1837 ,0,0,0}, {2071,2125,2116 ,1831,1830,1832 ,0,0,0}, + {2073,2116,2118 ,1833,1832,82 ,0,0,0}, {2086,2119,2074 ,1824,1823,1826 ,0,0,0}, + {2086,2073,2118 ,1824,1833,82 ,0,0,0}, {2075,2120,2105 ,1825,1827,1844 ,0,0,0}, + {2120,2074,2119 ,1827,1826,1823 ,0,0,0}, {2105,2104,2076 ,1844,1818,1817 ,0,0,0}, + {2105,2076,2075 ,1844,1817,1825 ,0,0,0}, {2070,2077,2121 ,1822,1819,1820 ,0,0,0}, + {2104,2121,2077 ,1818,1820,1819 ,0,0,0}, {2122,2078,2070 ,1821,1815,1822 ,0,0,0}, + {1313,2124,1308 ,1814,1816,1845 ,0,0,0}, {2078,2122,2124 ,1815,1821,1816 ,0,0,0}, + {1279,2087,2100 ,1846,1847,1848 ,0,0,0}, {2057,2091,2061 ,1849,1850,1851 ,0,0,0}, + {2102,2093,2085 ,1820,1852,1822 ,0,0,0}, {2127,2081,2099 ,1853,1854,82 ,0,0,0}, + {2056,2083,2103 ,1855,1856,1857 ,0,0,0}, {2084,2112,2114 ,1858,1859,1860 ,0,0,0}, + {2053,2128,2082 ,1861,1862,82 ,0,0,0}, {2064,2098,2097 ,1863,1864,1865 ,0,0,0}, + {2097,2112,2062 ,1865,1859,1866 ,0,0,0}, {2098,2079,2110 ,1864,1867,1868 ,0,0,0}, + {2079,2098,2064 ,1867,1864,1863 ,0,0,0}, {2111,2110,2054 ,1869,1868,1870 ,0,0,0}, + {2079,2054,2110 ,1867,1870,1868 ,0,0,0}, {2050,1294,2111 ,1871,1872,1869 ,0,0,0}, + {2111,2054,2050 ,1869,1870,1871 ,0,0,0}, {1293,1294,2050 ,1873,1872,1871 ,0,0,0}, + {2053,2084,2114 ,1861,1858,1860 ,0,0,0}, {2112,2084,2062 ,1859,1858,1866 ,0,0,0}, + {2064,2097,2062 ,1863,1865,1866 ,0,0,0}, {2053,2114,2128 ,1861,1860,1862 ,0,0,0}, + {2082,2128,2099 ,82,1862,82 ,0,0,0}, {2081,2127,2083 ,1854,1853,1856 ,0,0,0}, + {2081,2082,2099 ,1854,82,82 ,0,0,0}, {2056,2103,2101 ,1855,1857,1874 ,0,0,0}, + {2103,2083,2127 ,1857,1856,1853 ,0,0,0}, {2101,2091,2057 ,1874,1850,1849 ,0,0,0}, + {2101,2057,2056 ,1874,1849,1855 ,0,0,0}, {2085,2061,2102 ,1822,1851,1820 ,0,0,0}, + {2091,2102,2061 ,1850,1820,1851 ,0,0,0}, {2093,2087,2085 ,1852,1847,1822 ,0,0,0}, + {1279,2100,1274 ,1846,1848,21 ,0,0,0}, {2087,2093,2100 ,1847,1852,1848 ,0,0,0} +// BladeProtector2.prt + , {2129,2130,2131 ,82,1824,1833 ,0,0,0}, {2132,2133,2134 ,1828,1830,1831 ,0,0,0}, + {2135,2129,2131 ,1832,82,1833 ,0,0,0}, {2134,2133,2135 ,1831,1830,1832 ,0,0,0}, + {2133,2132,2136 ,1830,1828,1829 ,0,0,0}, {2131,2134,2135 ,1833,1831,1832 ,0,0,0}, + {2137,2138,2139 ,1836,1834,1835 ,0,0,0}, {2138,2140,2139 ,1834,1838,1835 ,0,0,0}, + {2136,2141,2137 ,1829,1837,1836 ,0,0,0}, {2138,2137,2141 ,1834,1836,1837 ,0,0,0}, + {2142,2143,2144 ,324,1840,1842 ,0,0,0}, {2145,2146,2140 ,1841,1839,1838 ,0,0,0}, + {2143,2146,2145 ,1840,1839,1841 ,0,0,0}, {2143,2145,2144 ,1840,1841,1842 ,0,0,0}, + {2144,2147,2142 ,1842,1843,324 ,0,0,0}, {2139,2140,2146 ,1835,1838,1839 ,0,0,0}, + {2136,2132,2141 ,1829,1828,1837 ,0,0,0}, {2129,2148,2130 ,82,1823,1824 ,0,0,0}, + {2149,2148,2150 ,1826,1823,1827 ,0,0,0}, {2148,2149,2130 ,1823,1826,1824 ,0,0,0}, + {2151,2152,2150 ,1844,1825,1827 ,0,0,0}, {2149,2150,2152 ,1826,1827,1825 ,0,0,0}, + {2151,2153,2154 ,1844,1818,1817 ,0,0,0}, {2154,2152,2151 ,1817,1825,1844 ,0,0,0}, + {2155,2153,2156 ,1819,1818,1820 ,0,0,0}, {2153,2155,2154 ,1818,1819,1817 ,0,0,0}, + {2157,2158,2156 ,1821,1822,1820 ,0,0,0}, {2155,2156,2158 ,1819,1820,1822 ,0,0,0}, + {2157,2159,2160 ,1821,1816,1815 ,0,0,0}, {2160,2158,2157 ,1815,1822,1821 ,0,0,0}, + {2161,2159,2162 ,1814,1816,1845 ,0,0,0}, {2159,2161,2160 ,1816,1814,1815 ,0,0,0}, + {2163,2164,2165 ,82,1854,82 ,0,0,0}, {2166,2167,2168 ,1858,1860,1861 ,0,0,0}, + {2169,2163,2165 ,1862,82,82 ,0,0,0}, {2168,2167,2169 ,1861,1860,1862 ,0,0,0}, + {2167,2166,2170 ,1860,1858,1859 ,0,0,0}, {2165,2168,2169 ,82,1861,1862 ,0,0,0}, + {2171,2172,2173 ,1865,1863,1864 ,0,0,0}, {2172,2174,2173 ,1863,1867,1864 ,0,0,0}, + {2170,2175,2171 ,1859,1866,1865 ,0,0,0}, {2172,2171,2175 ,1863,1865,1866 ,0,0,0}, + {2176,2177,2178 ,1872,1869,1871 ,0,0,0}, {2179,2180,2174 ,1870,1868,1867 ,0,0,0}, + {2177,2180,2179 ,1869,1868,1870 ,0,0,0}, {2177,2179,2178 ,1869,1870,1871 ,0,0,0}, + {2178,2181,2176 ,1871,1873,1872 ,0,0,0}, {2173,2174,2180 ,1864,1867,1868 ,0,0,0}, + {2170,2166,2175 ,1859,1858,1866 ,0,0,0}, {2163,2182,2164 ,82,1853,1854 ,0,0,0}, + {2183,2182,2184 ,1856,1853,1857 ,0,0,0}, {2182,2183,2164 ,1853,1856,1854 ,0,0,0}, + {2185,2186,2184 ,1874,1855,1857 ,0,0,0}, {2183,2184,2186 ,1856,1857,1855 ,0,0,0}, + {2185,2187,2188 ,1874,1850,1849 ,0,0,0}, {2188,2186,2185 ,1849,1855,1874 ,0,0,0}, + {2189,2187,2190 ,1851,1850,1820 ,0,0,0}, {2187,2189,2188 ,1850,1851,1849 ,0,0,0}, + {2191,2192,2190 ,1852,1822,1820 ,0,0,0}, {2189,2190,2192 ,1851,1820,1822 ,0,0,0}, + {2191,2193,2194 ,1852,1848,1847 ,0,0,0}, {2194,2192,2191 ,1847,1822,1852 ,0,0,0}, + {2195,2193,2196 ,1846,1848,21 ,0,0,0}, {2193,2195,2194 ,1848,1846,1847 ,0,0,0}, + {2197,2198,2199 ,1875,1876,1875 ,0,0,0}, {2200,2201,2202 ,1877,1878,1879 ,0,0,0}, + {2200,2199,2201 ,1877,1875,1878 ,0,0,0}, {2202,2201,2203 ,1879,1878,1879 ,0,0,0}, + {2199,2200,2197 ,1875,1877,1875 ,0,0,0}, {2204,2198,2197 ,1876,1876,1875 ,0,0,0}, + {2205,2204,2206 ,1880,1876,1880 ,0,0,0}, {2204,2205,2198 ,1876,1880,1876 ,0,0,0}, + {2207,2208,2209 ,1207,1881,1207 ,0,0,0}, {2210,2208,2211 ,1881,1881,1882 ,0,0,0}, + {2208,2210,2209 ,1881,1881,1207 ,0,0,0}, {2212,2213,2211 ,1883,1882,1882 ,0,0,0}, + {2210,2211,2213 ,1881,1882,1882 ,0,0,0}, {2212,2214,2215 ,1883,1884,1883 ,0,0,0}, + {2215,2213,2212 ,1883,1882,1883 ,0,0,0}, {2214,2216,2215 ,1884,1885,1883 ,0,0,0}, + {2217,2207,2209 ,1886,1207,1207 ,0,0,0}, {2218,2219,2217 ,1887,1886,1886 ,0,0,0}, + {2207,2217,2219 ,1207,1886,1886 ,0,0,0}, {2218,2220,2221 ,1887,1888,1887 ,0,0,0}, + {2221,2219,2218 ,1887,1886,1887 ,0,0,0}, {2222,2220,2223 ,1888,1888,1889 ,0,0,0}, + {2220,2222,2221 ,1888,1888,1887 ,0,0,0}, {2222,2223,2224 ,1888,1889,1890 ,0,0,0}, + {2225,2226,2227 ,1891,1892,1893 ,0,0,0}, {2228,2229,2225 ,1894,1895,1891 ,0,0,0}, + {2225,2227,2228 ,1891,1893,1894 ,0,0,0}, {2229,2230,2231 ,1895,1896,1897 ,0,0,0}, + {2230,2229,2228 ,1896,1895,1894 ,0,0,0}, {2232,2231,2233 ,1898,1897,1899 ,0,0,0}, + {2230,2233,2231 ,1896,1899,1897 ,0,0,0}, {2234,2235,2232 ,1900,1901,1898 ,0,0,0}, + {2232,2233,2234 ,1898,1899,1900 ,0,0,0}, {2235,2236,2237 ,1901,1902,1903 ,0,0,0}, + {2236,2235,2234 ,1902,1901,1900 ,0,0,0}, {2238,2237,2239 ,1904,1903,1905 ,0,0,0}, + {2236,2239,2237 ,1902,1905,1903 ,0,0,0}, {2240,2241,2238 ,1906,1907,1904 ,0,0,0}, + {2238,2239,2240 ,1904,1905,1906 ,0,0,0}, {2241,2242,2243 ,1907,1908,1909 ,0,0,0}, + {2242,2241,2240 ,1908,1907,1906 ,0,0,0}, {2244,2243,2245 ,1910,1909,1911 ,0,0,0}, + {2242,2245,2243 ,1908,1911,1909 ,0,0,0}, {2246,2247,2244 ,1912,1913,1910 ,0,0,0}, + {2244,2245,2246 ,1910,1911,1912 ,0,0,0}, {2247,2248,2249 ,1913,1914,1915 ,0,0,0}, + {2248,2247,2246 ,1914,1913,1912 ,0,0,0}, {2250,2249,2251 ,1916,1915,1917 ,0,0,0}, + {2248,2251,2249 ,1914,1917,1915 ,0,0,0}, {2252,2253,2250 ,1918,1919,1916 ,0,0,0}, + {2250,2251,2252 ,1916,1917,1918 ,0,0,0}, {2253,2254,2255 ,1919,1920,1921 ,0,0,0}, + {2254,2253,2252 ,1920,1919,1918 ,0,0,0}, {2256,2255,2257 ,1922,1921,1923 ,0,0,0}, + {2254,2257,2255 ,1920,1923,1921 ,0,0,0}, {2258,2259,2256 ,1924,1925,1922 ,0,0,0}, + {2256,2257,2258 ,1922,1923,1924 ,0,0,0}, {2259,2260,2261 ,1925,1926,1927 ,0,0,0}, + {2260,2259,2258 ,1926,1925,1924 ,0,0,0}, {2262,2261,2263 ,1928,1927,1929 ,0,0,0}, + {2260,2263,2261 ,1926,1929,1927 ,0,0,0}, {2264,2265,2262 ,1930,1930,1928 ,0,0,0}, + {2262,2263,2264 ,1928,1929,1930 ,0,0,0}, {2227,2226,2266 ,1893,1892,1931 ,0,0,0}, + {2267,2266,2268 ,1932,1931,1933 ,0,0,0}, {2226,2268,2266 ,1892,1933,1931 ,0,0,0}, + {2269,2270,2267 ,1934,1935,1932 ,0,0,0}, {2267,2268,2269 ,1932,1933,1934 ,0,0,0}, + {2270,2271,2272 ,1935,1936,1937 ,0,0,0}, {2271,2270,2269 ,1936,1935,1934 ,0,0,0}, + {2273,2272,2274 ,1938,1937,1939 ,0,0,0}, {2271,2274,2272 ,1936,1939,1937 ,0,0,0}, + {2275,2276,2273 ,1940,1941,1938 ,0,0,0}, {2273,2274,2275 ,1938,1939,1940 ,0,0,0}, + {2276,2277,2278 ,1941,1942,1943 ,0,0,0}, {2277,2276,2275 ,1942,1941,1940 ,0,0,0}, + {2279,2278,2280 ,1944,1943,1945 ,0,0,0}, {2277,2280,2278 ,1942,1945,1943 ,0,0,0}, + {2281,2282,2279 ,1946,1947,1944 ,0,0,0}, {2279,2280,2281 ,1944,1945,1946 ,0,0,0}, + {2282,2283,2284 ,1947,1948,1949 ,0,0,0}, {2283,2282,2281 ,1948,1947,1946 ,0,0,0}, + {2285,2284,2286 ,1950,1949,1951 ,0,0,0}, {2283,2286,2284 ,1948,1951,1949 ,0,0,0}, + {2287,2288,2285 ,1952,1953,1950 ,0,0,0}, {2285,2286,2287 ,1950,1951,1952 ,0,0,0}, + {2288,2289,2290 ,1953,1954,1955 ,0,0,0}, {2289,2288,2287 ,1954,1953,1952 ,0,0,0}, + {2291,2290,2292 ,1956,1955,1957 ,0,0,0}, {2289,2292,2290 ,1954,1957,1955 ,0,0,0}, + {2293,2294,2291 ,1958,1959,1956 ,0,0,0}, {2291,2292,2293 ,1956,1957,1958 ,0,0,0}, + {2294,2295,2296 ,1959,1960,1961 ,0,0,0}, {2295,2294,2293 ,1960,1959,1958 ,0,0,0}, + {2297,2296,2298 ,1962,1961,1963 ,0,0,0}, {2295,2298,2296 ,1960,1963,1961 ,0,0,0}, + {2299,2300,2297 ,1964,1965,1962 ,0,0,0}, {2297,2298,2299 ,1962,1963,1964 ,0,0,0}, + {2300,2301,2302 ,1965,1966,1967 ,0,0,0}, {2301,2300,2299 ,1966,1965,1964 ,0,0,0}, + {2301,2303,2302 ,1966,1968,1967 ,0,0,0}, {2302,2303,2304 ,1967,1968,1969 ,0,0,0}, + {2305,2306,2303 ,1970,1970,1971 ,0,0,0}, {2305,2307,2306 ,1970,1972,1970 ,0,0,0}, + {2307,2305,2308 ,1972,1970,1972 ,0,0,0}, {2304,2303,2306 ,21,1971,1970 ,0,0,0}, + {2309,2310,2311 ,1114,1973,1114 ,0,0,0}, {2312,2313,2310 ,1974,1975,1973 ,0,0,0}, + {2310,2313,2311 ,1973,1975,1114 ,0,0,0}, {2314,2315,2312 ,1976,1977,1974 ,0,0,0}, + {2312,2310,2314 ,1974,1973,1976 ,0,0,0}, {2315,2316,2317 ,1977,1978,1979 ,0,0,0}, + {2316,2315,2314 ,1978,1977,1976 ,0,0,0}, {2318,2317,2319 ,1980,1979,1981 ,0,0,0}, + {2316,2319,2317 ,1978,1981,1979 ,0,0,0}, {2320,2318,2321 ,1982,1980,1983 ,0,0,0}, + {2318,2319,2321 ,1980,1981,1983 ,0,0,0}, {2322,2318,2320 ,1982,1980,1982 ,0,0,0}, + {2323,2309,2311 ,1984,1114,1114 ,0,0,0}, {2324,2323,2325 ,1985,1984,1986 ,0,0,0}, + {2324,2309,2323 ,1985,1114,1984 ,0,0,0}, {2326,2325,2327 ,1987,1986,1988 ,0,0,0}, + {2323,2327,2325 ,1984,1988,1986 ,0,0,0}, {2328,2329,2326 ,1989,1990,1987 ,0,0,0}, + {2326,2327,2328 ,1987,1988,1989 ,0,0,0}, {2329,2330,2331 ,1990,1991,1992 ,0,0,0}, + {2330,2329,2328 ,1991,1990,1989 ,0,0,0}, {2331,2332,2205 ,1992,1993,1880 ,0,0,0}, + {2330,2332,2331 ,1991,1993,1992 ,0,0,0}, {2331,2205,2206 ,1992,1880,1880 ,0,0,0}, + {2333,2334,2335 ,1994,1995,1996 ,0,0,0}, {2333,2336,2337 ,1994,1997,1998 ,0,0,0}, + {2335,2334,2338 ,1996,1995,1999 ,0,0,0}, {2338,2334,2339 ,1999,1995,2000 ,0,0,0}, + {2338,2339,2340 ,1999,2000,2001 ,0,0,0}, {2341,2340,2339 ,2002,2001,2000 ,0,0,0}, + {2340,2341,2342 ,2001,2002,2003 ,0,0,0}, {2343,2342,2341 ,2004,2003,2002 ,0,0,0}, + {2343,2344,2345 ,2004,2005,2006 ,0,0,0}, {2342,2343,2345 ,2003,2004,2006 ,0,0,0}, + {2335,2336,2333 ,1996,1997,1994 ,0,0,0}, {2345,2344,2346 ,2006,2005,2007 ,0,0,0}, + {2347,2346,2348 ,2008,2007,2009 ,0,0,0}, {2348,2346,2344 ,2009,2007,2005 ,0,0,0}, + {2347,2348,2349 ,2008,2009,2008 ,0,0,0}, {2350,2337,2351 ,2010,1998,2011 ,0,0,0}, + {2336,2351,2337 ,1997,2011,1998 ,0,0,0}, {2352,2353,2350 ,2012,2013,2010 ,0,0,0}, + {2350,2351,2352 ,2010,2011,2012 ,0,0,0}, {2353,2354,2355 ,2013,2014,2015 ,0,0,0}, + {2354,2353,2352 ,2014,2013,2012 ,0,0,0}, {2356,2355,2357 ,2016,2015,2017 ,0,0,0}, + {2354,2357,2355 ,2014,2017,2015 ,0,0,0}, {2358,2359,2356 ,2018,2019,2016 ,0,0,0}, + {2356,2357,2358 ,2016,2017,2018 ,0,0,0}, {2359,2360,2361 ,2019,2020,2021 ,0,0,0}, + {2360,2359,2358 ,2020,2019,2018 ,0,0,0}, {2362,2361,2363 ,2022,2021,2023 ,0,0,0}, + {2360,2363,2361 ,2020,2023,2021 ,0,0,0}, {2362,2363,2364 ,2022,2023,2022 ,0,0,0}, + {2365,2366,2367 ,2024,2025,2024 ,0,0,0}, {2367,2368,2365 ,2024,2026,2024 ,0,0,0}, + {2369,2370,2366 ,2025,2027,2025 ,0,0,0}, {2371,2368,2367 ,2026,2026,2024 ,0,0,0}, + {2365,2369,2366 ,2024,2025,2025 ,0,0,0}, {2369,2372,2370 ,2025,2027,2027 ,0,0,0}, + {2373,2372,2374 ,2028,2027,2028 ,0,0,0}, {2374,2362,2364 ,2028,2022,2022 ,0,0,0}, + {2373,2370,2372 ,2028,2027,2027 ,0,0,0}, {2374,2364,2373 ,2028,2022,2028 ,0,0,0}, + {2375,2371,2376 ,2029,2026,2029 ,0,0,0}, {2371,2375,2368 ,2026,2029,2026 ,0,0,0}, + {2377,2378,2376 ,2030,2030,2029 ,0,0,0}, {2375,2376,2378 ,2029,2029,2030 ,0,0,0}, + {2377,2379,2380 ,2030,2031,2031 ,0,0,0}, {2380,2378,2377 ,2031,2030,2030 ,0,0,0}, + {2381,2379,2382 ,2032,2031,2032 ,0,0,0}, {2379,2381,2380 ,2031,2032,2031 ,0,0,0}, + {2381,2382,2223 ,2032,2032,2033 ,0,0,0}, {2223,2382,2224 ,2033,2032,2034 ,0,0,0}, + {2383,2216,2214 ,2035,2036,2037 ,0,0,0}, {2384,2385,2386 ,2038,2039,2039 ,0,0,0}, + {2387,2388,2389 ,2040,2040,2035 ,0,0,0}, {2390,2391,2392 ,2041,2041,2042 ,0,0,0}, + {2393,2394,2395 ,2038,2043,2043 ,0,0,0}, {2396,2397,2392 ,2044,2042,2042 ,0,0,0}, + {2390,2392,2397 ,2041,2042,2042 ,0,0,0}, {2398,2397,2396 ,2045,2042,2044 ,0,0,0}, + {2394,2391,2395 ,2043,2041,2043 ,0,0,0}, {2395,2391,2390 ,2043,2041,2041 ,0,0,0}, + {2393,2385,2384 ,2038,2039,2038 ,0,0,0}, {2393,2384,2394 ,2038,2038,2043 ,0,0,0}, + {2386,2388,2387 ,2039,2040,2040 ,0,0,0}, {2385,2388,2386 ,2039,2040,2039 ,0,0,0}, + {2383,2389,2216 ,2035,2035,2036 ,0,0,0}, {2387,2389,2383 ,2040,2035,2035 ,0,0,0}, + {2399,2400,2401 ,2046,2046,2047 ,0,0,0}, {2401,2400,2402 ,2047,2046,2047 ,0,0,0}, + {2400,2399,2403 ,2046,2046,2048 ,0,0,0}, {2404,2403,2399 ,2049,2048,2046 ,0,0,0}, + {2405,2406,2404 ,2050,2050,2049 ,0,0,0}, {2407,2401,2402 ,2051,2047,2047 ,0,0,0}, + {2398,2396,2405 ,2052,2053,2050 ,0,0,0}, {2406,2405,2396 ,2050,2050,2053 ,0,0,0}, + {2404,2406,2403 ,2049,2050,2048 ,0,0,0}, {2408,2407,2409 ,2054,2051,2051 ,0,0,0}, + {2402,2409,2407 ,2047,2051,2051 ,0,0,0}, {2410,2411,2408 ,2054,2055,2054 ,0,0,0}, + {2408,2409,2410 ,2054,2051,2054 ,0,0,0}, {2411,2412,2413 ,2055,2055,2056 ,0,0,0}, + {2412,2411,2410 ,2055,2055,2054 ,0,0,0}, {2414,2413,2415 ,2057,2056,2056 ,0,0,0}, + {2412,2415,2413 ,2055,2056,2056 ,0,0,0}, {2414,2415,2416 ,2057,2056,2057 ,0,0,0}, + {2417,2418,2419 ,2058,2058,2059 ,0,0,0}, {2420,2421,2419 ,2060,2061,2059 ,0,0,0}, + {2417,2419,2421 ,2058,2059,2061 ,0,0,0}, {2420,2422,2423 ,2060,2062,2063 ,0,0,0}, + {2423,2421,2420 ,2063,2061,2060 ,0,0,0}, {2424,2422,2425 ,2064,2062,2065 ,0,0,0}, + {2422,2424,2423 ,2062,2064,2063 ,0,0,0}, {2426,2427,2425 ,2066,2067,2065 ,0,0,0}, + {2424,2425,2427 ,2064,2065,2067 ,0,0,0}, {2426,2428,2429 ,2066,2068,2069 ,0,0,0}, + {2429,2427,2426 ,2069,2067,2066 ,0,0,0}, {2430,2428,2431 ,2070,2068,2071 ,0,0,0}, + {2428,2430,2429 ,2068,2070,2069 ,0,0,0}, {2432,2433,2431 ,2072,2073,2071 ,0,0,0}, + {2430,2431,2433 ,2070,2071,2073 ,0,0,0}, {2432,2434,2435 ,2072,2074,2075 ,0,0,0}, + {2435,2433,2432 ,2075,2073,2072 ,0,0,0}, {2436,2434,2437 ,2076,2074,2077 ,0,0,0}, + {2434,2436,2435 ,2074,2076,2075 ,0,0,0}, {2438,2439,2437 ,2078,2079,2077 ,0,0,0}, + {2436,2437,2439 ,2076,2077,2079 ,0,0,0}, {2438,2440,2441 ,2078,2080,2081 ,0,0,0}, + {2441,2439,2438 ,2081,2079,2078 ,0,0,0}, {2442,2440,2443 ,2082,2080,2083 ,0,0,0}, + {2440,2442,2441 ,2080,2082,2081 ,0,0,0}, {2444,2445,2443 ,2084,2085,2083 ,0,0,0}, + {2442,2443,2445 ,2082,2083,2085 ,0,0,0}, {2444,2446,2447 ,2084,2086,2087 ,0,0,0}, + {2447,2445,2444 ,2087,2085,2084 ,0,0,0}, {2448,2446,2449 ,2088,2086,2089 ,0,0,0}, + {2446,2448,2447 ,2086,2088,2087 ,0,0,0}, {2414,2450,2449 ,2057,2090,2089 ,0,0,0}, + {2448,2449,2450 ,2088,2089,2090 ,0,0,0}, {2416,2450,2414 ,2057,2090,2057 ,0,0,0}, + {2451,2418,2417 ,2091,2058,2058 ,0,0,0}, {2452,2451,2453 ,2092,2091,2093 ,0,0,0}, + {2451,2452,2418 ,2091,2092,2058 ,0,0,0}, {2454,2455,2453 ,2094,2095,2093 ,0,0,0}, + {2452,2453,2455 ,2092,2093,2095 ,0,0,0}, {2454,2456,2457 ,2094,2096,2097 ,0,0,0}, + {2457,2455,2454 ,2097,2095,2094 ,0,0,0}, {2458,2456,2459 ,2098,2096,2099 ,0,0,0}, + {2456,2458,2457 ,2096,2098,2097 ,0,0,0}, {2460,2461,2459 ,2100,2101,2099 ,0,0,0}, + {2458,2459,2461 ,2098,2099,2101 ,0,0,0}, {2460,2462,2463 ,2100,2102,2103 ,0,0,0}, + {2463,2461,2460 ,2103,2101,2100 ,0,0,0}, {2464,2462,2465 ,2104,2102,2105 ,0,0,0}, + {2462,2464,2463 ,2102,2104,2103 ,0,0,0}, {2466,2467,2465 ,2106,2107,2105 ,0,0,0}, + {2464,2465,2467 ,2104,2105,2107 ,0,0,0}, {2466,2468,2469 ,2106,2108,2109 ,0,0,0}, + {2469,2467,2466 ,2109,2107,2106 ,0,0,0}, {2470,2468,2471 ,2110,2108,2111 ,0,0,0}, + {2468,2470,2469 ,2108,2110,2109 ,0,0,0}, {2472,2473,2471 ,2112,2113,2111 ,0,0,0}, + {2470,2471,2473 ,2110,2111,2113 ,0,0,0}, {2472,2474,2475 ,2112,2114,2115 ,0,0,0}, + {2475,2473,2472 ,2115,2113,2112 ,0,0,0}, {2476,2474,2477 ,2116,2114,2117 ,0,0,0}, + {2474,2476,2475 ,2114,2116,2115 ,0,0,0}, {2478,2479,2477 ,2118,2119,2117 ,0,0,0}, + {2476,2477,2479 ,2116,2117,2119 ,0,0,0}, {2478,2480,2481 ,2118,2120,2121 ,0,0,0}, + {2481,2479,2478 ,2121,2119,2118 ,0,0,0}, {2482,2480,2483 ,2122,2120,2123 ,0,0,0}, + {2480,2482,2481 ,2120,2122,2121 ,0,0,0}, {2482,2483,2484 ,2122,2123,2123 ,0,0,0}, + {2485,2483,2486 ,1435,2124,1435 ,0,0,0}, {2483,2485,2484 ,2124,1435,2124 ,0,0,0}, + {2487,2488,2489 ,2125,2126,2127 ,0,0,0}, {2490,2491,2492 ,2128,2129,2130 ,0,0,0}, + {2493,2487,2489 ,2131,2125,2127 ,0,0,0}, {2491,2489,2488 ,2129,2127,2126 ,0,0,0}, + {2494,2487,2493 ,2132,2125,2131 ,0,0,0}, {2495,2496,2497 ,2133,2134,2135 ,0,0,0}, + {2494,2493,2495 ,2132,2131,2133 ,0,0,0}, {2498,2496,2499 ,2136,2134,2137 ,0,0,0}, + {2495,2497,2494 ,2133,2135,2132 ,0,0,0}, {2496,2498,2497 ,2134,2136,2135 ,0,0,0}, + {2499,2500,2501 ,2137,2138,2139 ,0,0,0}, {2488,2492,2491 ,2126,2130,2129 ,0,0,0}, + {2502,2503,2504 ,2140,2141,2142 ,0,0,0}, {2505,2501,2500 ,2143,2139,2138 ,0,0,0}, + {2505,2506,2507 ,2143,2144,2145 ,0,0,0}, {2502,2504,2507 ,2140,2142,2145 ,0,0,0}, + {2502,2507,2506 ,2140,2145,2144 ,0,0,0}, {2504,2503,2508 ,2142,2141,2146 ,0,0,0}, + {2509,2510,2511 ,2147,2148,2149 ,0,0,0}, {2508,2509,2511 ,2146,2147,2149 ,0,0,0}, + {2509,2508,2503 ,2147,2146,2141 ,0,0,0}, {2510,2512,2511 ,2148,2150,2149 ,0,0,0}, + {2506,2505,2500 ,2144,2143,2138 ,0,0,0}, {2512,2513,2514 ,2150,2151,2152 ,0,0,0}, + {2512,2510,2513 ,2150,2148,2151 ,0,0,0}, {2515,2516,2517 ,2153,2154,2155 ,0,0,0}, + {2518,2517,2516 ,2156,2155,2154 ,0,0,0}, {2518,2519,2517 ,2156,2157,2155 ,0,0,0}, + {2519,2514,2513 ,2157,2152,2151 ,0,0,0}, {2519,2518,2514 ,2157,2156,2152 ,0,0,0}, + {2501,2498,2499 ,2139,2136,2137 ,0,0,0}, {2520,2521,2515 ,2158,2159,2153 ,0,0,0}, + {2522,2523,2520 ,2160,2161,2158 ,0,0,0}, {2486,2523,2522 ,2162,2161,2160 ,0,0,0}, + {2516,2515,2521 ,2154,2153,2159 ,0,0,0}, {2523,2521,2520 ,2161,2159,2158 ,0,0,0}, + {2485,2486,2522 ,2162,2162,2160 ,0,0,0}, {2524,2525,2490 ,2163,2164,2128 ,0,0,0}, + {2490,2492,2524 ,2128,2130,2163 ,0,0,0}, {2525,2526,2527 ,2164,2165,2166 ,0,0,0}, + {2526,2525,2524 ,2165,2164,2163 ,0,0,0}, {2528,2527,2529 ,2167,2166,2168 ,0,0,0}, + {2526,2529,2527 ,2165,2168,2166 ,0,0,0}, {2530,2531,2528 ,2169,2170,2167 ,0,0,0}, + {2528,2529,2530 ,2167,2168,2169 ,0,0,0}, {2531,2532,2533 ,2170,2171,2172 ,0,0,0}, + {2532,2531,2530 ,2171,2170,2169 ,0,0,0}, {2534,2533,2535 ,2173,2172,2174 ,0,0,0}, + {2532,2535,2533 ,2171,2174,2172 ,0,0,0}, {2536,2537,2534 ,2175,2176,2173 ,0,0,0}, + {2534,2535,2536 ,2173,2174,2175 ,0,0,0}, {2537,2538,2539 ,2176,2177,2178 ,0,0,0}, + {2538,2537,2536 ,2177,2176,2175 ,0,0,0}, {2540,2539,2541 ,2179,2178,2180 ,0,0,0}, + {2538,2541,2539 ,2177,2180,2178 ,0,0,0}, {2542,2543,2540 ,2181,2182,2179 ,0,0,0}, + {2540,2541,2542 ,2179,2180,2181 ,0,0,0}, {2543,2544,2545 ,2182,2183,2184 ,0,0,0}, + {2544,2543,2542 ,2183,2182,2181 ,0,0,0}, {2546,2545,2547 ,2185,2184,2186 ,0,0,0}, + {2544,2547,2545 ,2183,2186,2184 ,0,0,0}, {2548,2549,2546 ,2187,2188,2185 ,0,0,0}, + {2546,2547,2548 ,2185,2186,2187 ,0,0,0}, {2549,2550,2551 ,2188,2189,2190 ,0,0,0}, + {2550,2549,2548 ,2189,2188,2187 ,0,0,0}, {2552,2551,2553 ,2191,2190,2192 ,0,0,0}, + {2550,2553,2551 ,2189,2192,2190 ,0,0,0}, {2554,2555,2552 ,2193,2194,2191 ,0,0,0}, + {2552,2553,2554 ,2191,2192,2193 ,0,0,0}, {2555,2556,2557 ,2194,2195,2196 ,0,0,0}, + {2556,2555,2554 ,2195,2194,2193 ,0,0,0}, {2558,2557,2559 ,2197,2196,2198 ,0,0,0}, + {2556,2559,2557 ,2195,2198,2196 ,0,0,0}, {2558,2559,2560 ,2197,2198,2197 ,0,0,0}, + {2561,2562,2563 ,1359,1359,1359 ,0,0,0}, {2562,2561,2564 ,1359,1359,1359 ,0,0,0}, + {2565,2566,2567 ,2199,2200,2201 ,0,0,0}, {2568,2569,2570 ,2202,2203,2204 ,0,0,0}, + {2566,2571,2567 ,2200,2205,2201 ,0,0,0}, {2565,2567,2572 ,2199,2201,2206 ,0,0,0}, + {2568,2565,2572 ,2202,2199,2206 ,0,0,0}, {2573,2574,2571 ,2207,2208,2205 ,0,0,0}, + {2573,2571,2566 ,2207,2205,2200 ,0,0,0}, {2575,2576,2577 ,2209,2210,2211 ,0,0,0}, + {2574,2573,2575 ,2208,2207,2209 ,0,0,0}, {2575,2577,2574 ,2209,2211,2208 ,0,0,0}, + {2576,2578,2577 ,2210,2212,2211 ,0,0,0}, {2569,2568,2572 ,2203,2202,2206 ,0,0,0}, + {2576,2579,2578 ,2210,2213,2212 ,0,0,0}, {2580,2581,2582 ,2214,2215,2216 ,0,0,0}, + {2580,2582,2579 ,2214,2216,2213 ,0,0,0}, {2581,2580,2583 ,2215,2214,2217 ,0,0,0}, + {2584,2585,2583 ,2218,2219,2217 ,0,0,0}, {2585,2581,2583 ,2219,2215,2217 ,0,0,0}, + {2586,2587,2588 ,2220,2221,2222 ,0,0,0}, {2585,2584,2589 ,2219,2218,2223 ,0,0,0}, + {2590,2591,2589 ,2224,2225,2223 ,0,0,0}, {2587,2586,2591 ,2221,2220,2225 ,0,0,0}, + {2587,2591,2590 ,2221,2225,2224 ,0,0,0}, {2586,2588,2592 ,2220,2222,2226 ,0,0,0}, + {2584,2590,2589 ,2218,2224,2223 ,0,0,0}, {2593,2592,2594 ,2227,2226,2228 ,0,0,0}, + {2593,2594,2595 ,2227,2228,2229 ,0,0,0}, {2594,2592,2588 ,2228,2226,2222 ,0,0,0}, + {2596,2597,2598 ,2230,2231,2232 ,0,0,0}, {2582,2578,2579 ,2216,2212,2213 ,0,0,0}, + {2596,2599,2595 ,2230,2233,2229 ,0,0,0}, {2599,2596,2598 ,2233,2230,2232 ,0,0,0}, + {2597,2600,2601 ,2231,2234,2235 ,0,0,0}, {2601,2598,2597 ,2235,2232,2231 ,0,0,0}, + {2602,2603,2600 ,2236,2237,2234 ,0,0,0}, {2601,2600,2603 ,2235,2234,2237 ,0,0,0}, + {2602,2564,2561 ,2236,2238,2238 ,0,0,0}, {2602,2561,2603 ,2236,2238,2237 ,0,0,0}, + {2595,2599,2593 ,2229,2233,2227 ,0,0,0}, {2604,2570,2605 ,2239,2204,2240 ,0,0,0}, + {2569,2605,2570 ,2203,2240,2204 ,0,0,0}, {2606,2607,2604 ,2241,2242,2239 ,0,0,0}, + {2604,2605,2606 ,2239,2240,2241 ,0,0,0}, {2607,2608,2609 ,2242,2243,2244 ,0,0,0}, + {2608,2607,2606 ,2243,2242,2241 ,0,0,0}, {2610,2609,2611 ,2245,2244,2246 ,0,0,0}, + {2608,2611,2609 ,2243,2246,2244 ,0,0,0}, {2612,2613,2610 ,2247,2248,2245 ,0,0,0}, + {2610,2611,2612 ,2245,2246,2247 ,0,0,0}, {2613,2614,2615 ,2248,2249,2250 ,0,0,0}, + {2614,2613,2612 ,2249,2248,2247 ,0,0,0}, {2616,2615,2617 ,2251,2250,2252 ,0,0,0}, + {2614,2617,2615 ,2249,2252,2250 ,0,0,0}, {2618,2619,2616 ,2253,2254,2251 ,0,0,0}, + {2616,2617,2618 ,2251,2252,2253 ,0,0,0}, {2619,2620,2621 ,2254,2255,2256 ,0,0,0}, + {2620,2619,2618 ,2255,2254,2253 ,0,0,0}, {2622,2621,2623 ,2257,2256,2258 ,0,0,0}, + {2620,2623,2621 ,2255,2258,2256 ,0,0,0}, {2624,2625,2622 ,2259,2260,2257 ,0,0,0}, + {2622,2623,2624 ,2257,2258,2259 ,0,0,0}, {2625,2626,2627 ,2260,2261,2262 ,0,0,0}, + {2626,2625,2624 ,2261,2260,2259 ,0,0,0}, {2628,2627,2629 ,2263,2262,2264 ,0,0,0}, + {2626,2629,2627 ,2261,2264,2262 ,0,0,0}, {2630,2631,2628 ,2265,2266,2263 ,0,0,0}, + {2628,2629,2630 ,2263,2264,2265 ,0,0,0}, {2631,2632,2633 ,2266,2267,2268 ,0,0,0}, + {2632,2631,2630 ,2267,2266,2265 ,0,0,0}, {2634,2633,2635 ,2269,2268,2270 ,0,0,0}, + {2632,2635,2633 ,2267,2270,2268 ,0,0,0}, {2636,2637,2634 ,2271,2272,2269 ,0,0,0}, + {2634,2635,2636 ,2269,2270,2271 ,0,0,0}, {2637,2638,2639 ,2272,2273,2274 ,0,0,0}, + {2638,2637,2636 ,2273,2272,2271 ,0,0,0}, {2640,2639,2641 ,2275,2274,2276 ,0,0,0}, + {2638,2641,2639 ,2273,2276,2274 ,0,0,0}, {2640,2641,2642 ,2275,2276,2277 ,0,0,0}, + {2643,2644,2645 ,2278,2279,2280 ,0,0,0}, {2646,2647,2645 ,2281,2282,2280 ,0,0,0}, + {2643,2645,2647 ,2278,2280,2282 ,0,0,0}, {2646,2648,2649 ,2281,2283,2284 ,0,0,0}, + {2649,2647,2646 ,2284,2282,2281 ,0,0,0}, {2650,2648,2651 ,2285,2283,2286 ,0,0,0}, + {2648,2650,2649 ,2283,2285,2284 ,0,0,0}, {2652,2653,2651 ,2287,2288,2286 ,0,0,0}, + {2650,2651,2653 ,2285,2286,2288 ,0,0,0}, {2652,2654,2655 ,2287,2289,2290 ,0,0,0}, + {2655,2653,2652 ,2290,2288,2287 ,0,0,0}, {2656,2654,2657 ,2291,2289,2292 ,0,0,0}, + {2654,2656,2655 ,2289,2291,2290 ,0,0,0}, {2658,2659,2657 ,2293,2294,2292 ,0,0,0}, + {2656,2657,2659 ,2291,2292,2294 ,0,0,0}, {2658,2660,2661 ,2293,2295,2296 ,0,0,0}, + {2661,2659,2658 ,2296,2294,2293 ,0,0,0}, {2662,2660,2663 ,2297,2295,2298 ,0,0,0}, + {2660,2662,2661 ,2295,2297,2296 ,0,0,0}, {2664,2665,2663 ,2299,2300,2298 ,0,0,0}, + {2662,2663,2665 ,2297,2298,2300 ,0,0,0}, {2664,2666,2667 ,2299,2301,2302 ,0,0,0}, + {2667,2665,2664 ,2302,2300,2299 ,0,0,0}, {2668,2666,2669 ,2303,2301,2304 ,0,0,0}, + {2666,2668,2667 ,2301,2303,2302 ,0,0,0}, {2670,2671,2669 ,2305,2306,2304 ,0,0,0}, + {2668,2669,2671 ,2303,2304,2306 ,0,0,0}, {2670,2672,2673 ,2305,2307,2308 ,0,0,0}, + {2673,2671,2670 ,2308,2306,2305 ,0,0,0}, {2674,2672,2675 ,2309,2307,2310 ,0,0,0}, + {2672,2674,2673 ,2307,2309,2308 ,0,0,0}, {2676,2677,2675 ,2311,2312,2310 ,0,0,0}, + {2674,2675,2677 ,2309,2310,2312 ,0,0,0}, {2676,2678,2679 ,2311,2313,2314 ,0,0,0}, + {2679,2677,2676 ,2314,2312,2311 ,0,0,0}, {2680,2678,2681 ,2315,2313,2316 ,0,0,0}, + {2678,2680,2679 ,2313,2315,2314 ,0,0,0}, {2682,2683,2681 ,2317,2318,2316 ,0,0,0}, + {2680,2681,2683 ,2315,2316,2318 ,0,0,0}, {2682,2684,2685 ,2317,2319,2320 ,0,0,0}, + {2685,2683,2682 ,2320,2318,2317 ,0,0,0}, {2686,2684,2687 ,2321,2319,2322 ,0,0,0}, + {2684,2686,2685 ,2319,2321,2320 ,0,0,0}, {2688,2689,2687 ,2323,2324,2322 ,0,0,0}, + {2686,2687,2689 ,2321,2322,2324 ,0,0,0}, {2688,2690,2691 ,2323,2325,2326 ,0,0,0}, + {2691,2689,2688 ,2326,2324,2323 ,0,0,0}, {2692,2690,2693 ,2327,2325,2328 ,0,0,0}, + {2690,2692,2691 ,2325,2327,2326 ,0,0,0}, {2694,2695,2693 ,2329,2330,2328 ,0,0,0}, + {2692,2693,2695 ,2327,2328,2330 ,0,0,0}, {2694,2696,2697 ,2329,2331,2332 ,0,0,0}, + {2697,2695,2694 ,2332,2330,2329 ,0,0,0}, {2698,2696,2699 ,2333,2331,2334 ,0,0,0}, + {2696,2698,2697 ,2331,2333,2332 ,0,0,0}, {2640,2700,2699 ,2335,2336,2334 ,0,0,0}, + {2698,2699,2700 ,2333,2334,2336 ,0,0,0}, {2642,2700,2640 ,2337,2336,2335 ,0,0,0}, + {2701,2644,2643 ,2338,2279,2278 ,0,0,0}, {2702,2701,2703 ,2339,2338,2340 ,0,0,0}, + {2701,2702,2644 ,2338,2339,2279 ,0,0,0}, {2704,2705,2703 ,2341,2342,2340 ,0,0,0}, + {2702,2703,2705 ,2339,2340,2342 ,0,0,0}, {2704,2706,2707 ,2341,2343,2344 ,0,0,0}, + {2707,2705,2704 ,2344,2342,2341 ,0,0,0}, {2708,2706,2709 ,2345,2343,2346 ,0,0,0}, + {2706,2708,2707 ,2343,2345,2344 ,0,0,0}, {2710,2711,2709 ,2347,2348,2346 ,0,0,0}, + {2708,2709,2711 ,2345,2346,2348 ,0,0,0}, {2710,2712,2713 ,2347,2349,2350 ,0,0,0}, + {2713,2711,2710 ,2350,2348,2347 ,0,0,0}, {2714,2712,2715 ,2351,2349,2352 ,0,0,0}, + {2712,2714,2713 ,2349,2351,2350 ,0,0,0}, {2716,2717,2715 ,2353,2354,2352 ,0,0,0}, + {2714,2715,2717 ,2351,2352,2354 ,0,0,0}, {2716,2718,2719 ,2353,2355,2356 ,0,0,0}, + {2719,2717,2716 ,2356,2354,2353 ,0,0,0}, {2720,2718,2721 ,2357,2355,2358 ,0,0,0}, + {2718,2720,2719 ,2355,2357,2356 ,0,0,0}, {2722,2723,2721 ,2359,2360,2358 ,0,0,0}, + {2720,2721,2723 ,2357,2358,2360 ,0,0,0}, {2722,2724,2725 ,2359,2361,2362 ,0,0,0}, + {2725,2723,2722 ,2362,2360,2359 ,0,0,0}, {2726,2724,2727 ,2363,2361,2364 ,0,0,0}, + {2724,2726,2725 ,2361,2363,2362 ,0,0,0}, {2728,2729,2727 ,2365,2366,2364 ,0,0,0}, + {2726,2727,2729 ,2363,2364,2366 ,0,0,0}, {2728,2730,2731 ,2365,2367,2368 ,0,0,0}, + {2731,2729,2728 ,2368,2366,2365 ,0,0,0}, {2732,2730,2733 ,2369,2367,2370 ,0,0,0}, + {2730,2732,2731 ,2367,2369,2368 ,0,0,0}, {2734,2735,2733 ,2371,2372,2370 ,0,0,0}, + {2732,2733,2735 ,2369,2370,2372 ,0,0,0}, {2734,2736,2737 ,2371,2373,2374 ,0,0,0}, + {2737,2735,2734 ,2374,2372,2371 ,0,0,0}, {2738,2736,2739 ,2375,2373,2376 ,0,0,0}, + {2736,2738,2737 ,2373,2375,2374 ,0,0,0}, {2740,2741,2739 ,2377,2378,2376 ,0,0,0}, + {2738,2739,2741 ,2375,2376,2378 ,0,0,0}, {2740,2742,2743 ,2377,2379,2380 ,0,0,0}, + {2743,2741,2740 ,2380,2378,2377 ,0,0,0}, {2744,2742,2745 ,2381,2379,2382 ,0,0,0}, + {2742,2744,2743 ,2379,2381,2380 ,0,0,0}, {2746,2747,2745 ,2383,2384,2382 ,0,0,0}, + {2744,2745,2747 ,2381,2382,2384 ,0,0,0}, {2746,2748,2749 ,2383,2385,2386 ,0,0,0}, + {2749,2747,2746 ,2386,2384,2383 ,0,0,0}, {2750,2748,2751 ,2387,2385,2388 ,0,0,0}, + {2748,2750,2749 ,2385,2387,2386 ,0,0,0}, {2752,2753,2751 ,2389,2390,2388 ,0,0,0}, + {2750,2751,2753 ,2387,2388,2390 ,0,0,0}, {2752,2754,2755 ,2389,2391,2392 ,0,0,0}, + {2755,2753,2752 ,2392,2390,2389 ,0,0,0}, {2756,2754,2757 ,2393,2391,324 ,0,0,0}, + {2754,2756,2755 ,2391,2393,2392 ,0,0,0}, {2756,2757,2758 ,2393,324,2394 ,0,0,0}, + {2759,2760,2761 ,2395,2396,2397 ,0,0,0}, {2762,2763,2764 ,2398,2399,2400 ,0,0,0}, + {2760,2765,2761 ,2396,2401,2397 ,0,0,0}, {2759,2761,2766 ,2395,2397,2402 ,0,0,0}, + {2762,2759,2766 ,2398,2395,2402 ,0,0,0}, {2767,2768,2765 ,2403,2404,2401 ,0,0,0}, + {2767,2765,2760 ,2403,2401,2396 ,0,0,0}, {2769,2770,2771 ,2405,2406,2407 ,0,0,0}, + {2768,2767,2769 ,2404,2403,2405 ,0,0,0}, {2769,2771,2768 ,2405,2407,2404 ,0,0,0}, + {2770,2772,2771 ,2406,2408,2407 ,0,0,0}, {2763,2762,2766 ,2399,2398,2402 ,0,0,0}, + {2770,2773,2772 ,2406,2409,2408 ,0,0,0}, {2774,2775,2776 ,2410,2411,2412 ,0,0,0}, + {2774,2776,2773 ,2410,2412,2409 ,0,0,0}, {2775,2774,2777 ,2411,2410,2413 ,0,0,0}, + {2778,2779,2777 ,2414,2415,2413 ,0,0,0}, {2779,2775,2777 ,2415,2411,2413 ,0,0,0}, + {2780,2781,2782 ,2416,2417,2418 ,0,0,0}, {2779,2778,2783 ,2415,2414,2419 ,0,0,0}, + {2784,2785,2783 ,2420,2421,2419 ,0,0,0}, {2781,2780,2785 ,2417,2416,2421 ,0,0,0}, + {2781,2785,2784 ,2417,2421,2420 ,0,0,0}, {2780,2782,2786 ,2416,2418,2422 ,0,0,0}, + {2778,2784,2783 ,2414,2420,2419 ,0,0,0}, {2787,2786,2788 ,2423,2422,2424 ,0,0,0}, + {2787,2788,2789 ,2423,2424,2425 ,0,0,0}, {2788,2786,2782 ,2424,2422,2418 ,0,0,0}, + {2790,2791,2792 ,2426,2427,2428 ,0,0,0}, {2776,2772,2773 ,2412,2408,2409 ,0,0,0}, + {2790,2793,2789 ,2426,2429,2425 ,0,0,0}, {2793,2790,2792 ,2429,2426,2428 ,0,0,0}, + {2791,2794,2795 ,2427,2430,2431 ,0,0,0}, {2795,2792,2791 ,2431,2428,2427 ,0,0,0}, + {2796,2797,2794 ,2432,2433,2430 ,0,0,0}, {2795,2794,2797 ,2431,2430,2433 ,0,0,0}, + {2796,2758,2757 ,2432,2434,2435 ,0,0,0}, {2796,2757,2797 ,2432,2435,2433 ,0,0,0}, + {2789,2793,2787 ,2425,2429,2423 ,0,0,0}, {2798,2764,2799 ,2436,2400,2437 ,0,0,0}, + {2763,2799,2764 ,2399,2437,2400 ,0,0,0}, {2800,2801,2798 ,2438,2439,2436 ,0,0,0}, + {2798,2799,2800 ,2436,2437,2438 ,0,0,0}, {2801,2802,2803 ,2439,2440,2441 ,0,0,0}, + {2802,2801,2800 ,2440,2439,2438 ,0,0,0}, {2804,2803,2805 ,2442,2441,2443 ,0,0,0}, + {2802,2805,2803 ,2440,2443,2441 ,0,0,0}, {2806,2807,2804 ,2444,2445,2442 ,0,0,0}, + {2804,2805,2806 ,2442,2443,2444 ,0,0,0}, {2807,2808,2809 ,2445,2446,2447 ,0,0,0}, + {2808,2807,2806 ,2446,2445,2444 ,0,0,0}, {2810,2809,2811 ,2448,2447,2449 ,0,0,0}, + {2808,2811,2809 ,2446,2449,2447 ,0,0,0}, {2812,2813,2810 ,2450,2451,2448 ,0,0,0}, + {2810,2811,2812 ,2448,2449,2450 ,0,0,0}, {2813,2814,2815 ,2451,2452,2453 ,0,0,0}, + {2814,2813,2812 ,2452,2451,2450 ,0,0,0}, {2816,2815,2817 ,2454,2453,2455 ,0,0,0}, + {2814,2817,2815 ,2452,2455,2453 ,0,0,0}, {2818,2819,2816 ,2456,2457,2454 ,0,0,0}, + {2816,2817,2818 ,2454,2455,2456 ,0,0,0}, {2819,2820,2821 ,2457,2458,2459 ,0,0,0}, + {2820,2819,2818 ,2458,2457,2456 ,0,0,0}, {2822,2821,2823 ,2460,2459,2461 ,0,0,0}, + {2820,2823,2821 ,2458,2461,2459 ,0,0,0}, {2824,2825,2822 ,2462,2463,2460 ,0,0,0}, + {2822,2823,2824 ,2460,2461,2462 ,0,0,0}, {2825,2826,2827 ,2463,2464,2465 ,0,0,0}, + {2826,2825,2824 ,2464,2463,2462 ,0,0,0}, {2828,2827,2829 ,2466,2465,2467 ,0,0,0}, + {2826,2829,2827 ,2464,2467,2465 ,0,0,0}, {2830,2831,2828 ,2468,2469,2466 ,0,0,0}, + {2828,2829,2830 ,2466,2467,2468 ,0,0,0}, {2831,2832,2833 ,2469,2470,2471 ,0,0,0}, + {2832,2831,2830 ,2470,2469,2468 ,0,0,0}, {2834,2833,2835 ,2472,2471,2473 ,0,0,0}, + {2832,2835,2833 ,2470,2473,2471 ,0,0,0}, {2834,2835,2836 ,2472,2473,2472 ,0,0,0}, + {2837,2834,2836 ,1790,1790,1790 ,0,0,0}, {2834,2837,2838 ,1790,1790,1790 ,0,0,0}, + {2839,2840,2841 ,2474,2475,2476 ,0,0,0}, {2842,2843,2839 ,2477,2478,2474 ,0,0,0}, + {2839,2841,2842 ,2474,2476,2477 ,0,0,0}, {2843,2844,2845 ,2478,2479,2480 ,0,0,0}, + {2844,2843,2842 ,2479,2478,2477 ,0,0,0}, {2846,2845,2847 ,2481,2480,2482 ,0,0,0}, + {2844,2847,2845 ,2479,2482,2480 ,0,0,0}, {2848,2849,2846 ,2483,2484,2481 ,0,0,0}, + {2846,2847,2848 ,2481,2482,2483 ,0,0,0}, {2849,2850,2851 ,2484,2485,2486 ,0,0,0}, + {2850,2849,2848 ,2485,2484,2483 ,0,0,0}, {2852,2851,2853 ,2487,2486,2488 ,0,0,0}, + {2850,2853,2851 ,2485,2488,2486 ,0,0,0}, {2854,2855,2852 ,2489,2490,2487 ,0,0,0}, + {2852,2853,2854 ,2487,2488,2489 ,0,0,0}, {2855,2856,2857 ,2490,2491,2492 ,0,0,0}, + {2856,2855,2854 ,2491,2490,2489 ,0,0,0}, {2858,2857,2859 ,2493,2492,2494 ,0,0,0}, + {2856,2859,2857 ,2491,2494,2492 ,0,0,0}, {2860,2861,2858 ,2495,2496,2493 ,0,0,0}, + {2858,2859,2860 ,2493,2494,2495 ,0,0,0}, {2861,2862,2863 ,2496,2497,2498 ,0,0,0}, + {2862,2861,2860 ,2497,2496,2495 ,0,0,0}, {2864,2863,2865 ,2499,2498,2500 ,0,0,0}, + {2862,2865,2863 ,2497,2500,2498 ,0,0,0}, {2866,2867,2864 ,2501,2502,2499 ,0,0,0}, + {2864,2865,2866 ,2499,2500,2501 ,0,0,0}, {2867,2868,2869 ,2502,2503,2504 ,0,0,0}, + {2868,2867,2866 ,2503,2502,2501 ,0,0,0}, {2870,2869,2871 ,2505,2504,2506 ,0,0,0}, + {2868,2871,2869 ,2503,2506,2504 ,0,0,0}, {2872,2873,2870 ,2507,2508,2505 ,0,0,0}, + {2870,2871,2872 ,2505,2506,2507 ,0,0,0}, {2873,2874,2875 ,2508,2509,2510 ,0,0,0}, + {2874,2873,2872 ,2509,2508,2507 ,0,0,0}, {2876,2875,2877 ,2511,2510,2512 ,0,0,0}, + {2874,2877,2875 ,2509,2512,2510 ,0,0,0}, {2838,2837,2876 ,2513,2513,2511 ,0,0,0}, + {2876,2877,2838 ,2511,2512,2513 ,0,0,0}, {2841,2840,2878 ,2476,2475,2514 ,0,0,0}, + {2879,2878,2880 ,2515,2514,2516 ,0,0,0}, {2840,2880,2878 ,2475,2516,2514 ,0,0,0}, + {2881,2882,2879 ,2517,2518,2515 ,0,0,0}, {2879,2880,2881 ,2515,2516,2517 ,0,0,0}, + {2882,2883,2884 ,2518,2519,2520 ,0,0,0}, {2883,2882,2881 ,2519,2518,2517 ,0,0,0}, + {2885,2884,2886 ,2521,2520,2522 ,0,0,0}, {2883,2886,2884 ,2519,2522,2520 ,0,0,0}, + {2887,2888,2885 ,2523,2524,2521 ,0,0,0}, {2885,2886,2887 ,2521,2522,2523 ,0,0,0}, + {2888,2889,2890 ,2524,2525,2526 ,0,0,0}, {2889,2888,2887 ,2525,2524,2523 ,0,0,0}, + {2891,2890,2892 ,2527,2526,2528 ,0,0,0}, {2889,2892,2890 ,2525,2528,2526 ,0,0,0}, + {2893,2894,2891 ,2529,2530,2527 ,0,0,0}, {2891,2892,2893 ,2527,2528,2529 ,0,0,0}, + {2894,2895,2896 ,2530,2531,2532 ,0,0,0}, {2895,2894,2893 ,2531,2530,2529 ,0,0,0}, + {2897,2896,2898 ,2533,2532,2534 ,0,0,0}, {2895,2898,2896 ,2531,2534,2532 ,0,0,0}, + {2899,2900,2897 ,2535,2536,2533 ,0,0,0}, {2897,2898,2899 ,2533,2534,2535 ,0,0,0}, + {2900,2901,2902 ,2536,2537,2538 ,0,0,0}, {2901,2900,2899 ,2537,2536,2535 ,0,0,0}, + {2903,2902,2904 ,2539,2538,2540 ,0,0,0}, {2901,2904,2902 ,2537,2540,2538 ,0,0,0}, + {2905,2906,2903 ,2541,2542,2539 ,0,0,0}, {2903,2904,2905 ,2539,2540,2541 ,0,0,0}, + {2906,2907,2908 ,2542,2543,2544 ,0,0,0}, {2907,2906,2905 ,2543,2542,2541 ,0,0,0}, + {2909,2908,2910 ,2545,2544,2546 ,0,0,0}, {2907,2910,2908 ,2543,2546,2544 ,0,0,0}, + {2911,2912,2909 ,2547,2548,2545 ,0,0,0}, {2909,2910,2911 ,2545,2546,2547 ,0,0,0}, + {2912,2913,2914 ,2548,2549,2550 ,0,0,0}, {2913,2912,2911 ,2549,2548,2547 ,0,0,0}, + {2913,2563,2914 ,2549,2551,2550 ,0,0,0}, {2914,2563,2562 ,2550,2551,2551 ,0,0,0}, + {2264,2560,2265 ,1711,2552,1711 ,0,0,0}, {2560,2264,2558 ,2552,1711,2552 ,0,0,0}, + {2785,2287,2286 ,1793,1793,1793 ,0,0,0}, {2563,2913,2486 ,1793,726,726 ,0,0,0}, + {2907,2516,2910 ,726,726,726 ,0,0,0}, {2603,2561,2483 ,726,726,726 ,0,0,0}, + {2504,2508,2898 ,726,726,726 ,0,0,0}, {2512,2904,2901 ,726,726,726 ,0,0,0}, + {2883,2494,2886 ,726,726,726 ,0,0,0}, {2892,2889,2501 ,726,726,726 ,0,0,0}, + {2880,2488,2487 ,726,726,726 ,0,0,0}, {2881,2880,2487 ,726,726,726 ,0,0,0}, + {2280,2277,2776 ,1793,726,1793 ,0,0,0}, {2793,2792,2295 ,1793,726,1793 ,0,0,0}, + {2761,2765,2269 ,1793,1793,726 ,0,0,0}, {2271,2765,2768 ,726,1793,726 ,0,0,0}, + {2799,2225,2229 ,726,726,726 ,0,0,0}, {2225,2763,2226 ,726,1793,1793 ,0,0,0}, + {2802,2232,2805 ,1793,726,726 ,0,0,0}, {2231,2802,2800 ,1793,1793,1793 ,0,0,0}, + {2241,2812,2811 ,1792,1793,1793 ,0,0,0}, {2237,2808,2806 ,726,1793,1793 ,0,0,0}, + {2814,2812,2243 ,1793,1793,1793 ,0,0,0}, {2241,2243,2812 ,1792,1793,1793 ,0,0,0}, + {2818,2817,2247 ,1793,1792,726 ,0,0,0}, {2814,2243,2244 ,1793,1793,1793 ,0,0,0}, + {2820,2818,2249 ,1793,1793,1793 ,0,0,0}, {2247,2817,2244 ,726,1792,1793 ,0,0,0}, + {2250,2823,2820 ,1793,726,1793 ,0,0,0}, {2820,2249,2250 ,1793,1793,1793 ,0,0,0}, + {2823,2253,2824 ,726,726,726 ,0,0,0}, {2253,2823,2250 ,726,726,1793 ,0,0,0}, + {2826,2824,2255 ,726,726,726 ,0,0,0}, {2256,2826,2255 ,726,726,726 ,0,0,0}, + {2261,2830,2259 ,726,1793,1793 ,0,0,0}, {2829,2826,2256 ,726,726,726 ,0,0,0}, + {2262,2265,2832 ,726,726,726 ,0,0,0}, {2259,2830,2829 ,1793,1793,726 ,0,0,0}, + {2265,2835,2832 ,726,1793,726 ,0,0,0}, {2830,2262,2832 ,1793,726,726 ,0,0,0}, + {2855,2536,2852 ,726,726,726 ,0,0,0}, {2265,2836,2835 ,726,726,1793 ,0,0,0}, + {2786,2289,2780 ,1793,726,726 ,0,0,0}, {2800,2229,2231 ,1793,726,1793 ,0,0,0}, + {2808,2237,2238 ,1793,726,1793 ,0,0,0}, {2811,2238,2241 ,1793,1793,1792 ,0,0,0}, + {2235,2237,2806 ,1793,726,1793 ,0,0,0}, {2805,2232,2235 ,726,726,1793 ,0,0,0}, + {2763,2225,2799 ,1793,726,726 ,0,0,0}, {2799,2229,2800 ,726,726,1793 ,0,0,0}, + {2761,2268,2766 ,1793,1793,1793 ,0,0,0}, {2766,2226,2763 ,1793,1793,1793 ,0,0,0}, + {2429,2608,2427 ,726,726,1793 ,0,0,0}, {2268,2226,2766 ,1793,1793,1793 ,0,0,0}, + {2771,2275,2274 ,1793,1793,726 ,0,0,0}, {2768,2274,2271 ,726,726,726 ,0,0,0}, + {2772,2277,2275 ,726,726,1793 ,0,0,0}, {2771,2274,2768 ,1793,726,726 ,0,0,0}, + {2779,2283,2281 ,1793,1793,1793 ,0,0,0}, {2280,2776,2775 ,1793,1793,726 ,0,0,0}, + {2780,2287,2785 ,726,1793,1793 ,0,0,0}, {2283,2783,2286 ,1793,1793,1793 ,0,0,0}, + {2293,2292,2787 ,726,726,726 ,0,0,0}, {2289,2287,2780 ,726,1793,726 ,0,0,0}, + {2787,2292,2786 ,726,726,1793 ,0,0,0}, {2635,2632,2415 ,1793,726,726 ,0,0,0}, + {2795,2299,2298 ,1792,726,726 ,0,0,0}, {2212,2194,2214 ,1793,1792,726 ,0,0,0}, + {2301,2797,2303 ,1793,726,1793 ,0,0,0}, {2219,2221,2186 ,726,1793,726 ,0,0,0}, + {2183,2221,2222 ,726,1793,1793 ,0,0,0}, {2382,2379,2175 ,726,726,726 ,0,0,0}, + {2382,2166,2168 ,726,726,1793 ,0,0,0}, {2685,2357,2683 ,726,1793,1793 ,0,0,0}, + {2376,2371,2638 ,1793,726,726 ,0,0,0}, {2745,2742,2915 ,726,726,726 ,0,0,0}, + {2656,2340,2655 ,726,1793,1793 ,0,0,0}, {2916,2917,2706 ,1793,1793,726 ,0,0,0}, + {2161,2918,2919 ,1793,726,726 ,0,0,0}, {2712,2710,2920 ,726,1793,726 ,0,0,0}, + {2920,2710,2917 ,726,1793,1793 ,0,0,0}, {2134,2131,2203 ,726,726,1793 ,0,0,0}, + {2920,2203,2715 ,726,1793,1793 ,0,0,0}, {2201,2199,2132 ,1793,1793,1793 ,0,0,0}, + {2132,2199,2141 ,1793,1793,1793 ,0,0,0}, {2722,2721,2130 ,1793,726,726 ,0,0,0}, + {2709,2706,2917 ,1793,726,1793 ,0,0,0}, {2347,2916,2704 ,726,1793,726 ,0,0,0}, + {2322,2921,2318 ,726,1793,1793 ,0,0,0}, {2922,2923,2918 ,1793,1793,726 ,0,0,0}, + {2313,2924,2925 ,726,1793,1793 ,0,0,0}, {2701,2346,2347 ,1793,726,726 ,0,0,0}, + {2347,2704,2703 ,726,726,1793 ,0,0,0}, {2643,2346,2701 ,1793,726,1793 ,0,0,0}, + {2740,2739,2926 ,726,1793,1793 ,0,0,0}, {2345,2346,2647 ,1793,726,726 ,0,0,0}, + {2647,2649,2345 ,726,726,1793 ,0,0,0}, {2746,2745,2927 ,1793,726,1793 ,0,0,0}, + {2342,2345,2650 ,726,1793,726 ,0,0,0}, {2748,2928,2751 ,726,1793,1793 ,0,0,0}, + {2653,2342,2650 ,1793,726,726 ,0,0,0}, {2305,2752,2308 ,1793,726,1793 ,0,0,0}, + {2342,2655,2340 ,726,1793,1793 ,0,0,0}, {2665,2336,2335 ,1793,726,726 ,0,0,0}, + {2661,2335,2338 ,1793,726,1793 ,0,0,0}, {2352,2351,2673 ,1792,726,1793 ,0,0,0}, + {2336,2665,2667 ,726,1793,1793 ,0,0,0}, {2680,2354,2679 ,1793,1793,1793 ,0,0,0}, + {2354,2352,2677 ,1793,1792,1793 ,0,0,0}, {2363,2360,2691 ,1793,726,726 ,0,0,0}, + {2323,2929,2327 ,1793,726,1793 ,0,0,0}, {2930,2931,2932 ,1793,1793,1793 ,0,0,0}, + {2364,2695,2697 ,726,726,726 ,0,0,0}, {2366,2370,2642 ,1793,1793,1793 ,0,0,0}, + {2933,2384,2934 ,726,726,726 ,0,0,0}, {2935,2394,2384 ,1793,1793,726 ,0,0,0}, + {2387,2383,2936 ,726,726,726 ,0,0,0}, {2386,2937,2934 ,726,1793,726 ,0,0,0}, + {2224,2165,2164 ,726,726,1793 ,0,0,0}, {2208,2207,2188 ,1793,726,726 ,0,0,0}, + {2937,2386,2387 ,1793,726,726 ,0,0,0}, {2754,2305,2757 ,1793,1793,1793 ,0,0,0}, + {2211,2189,2192 ,726,1793,726 ,0,0,0}, {2412,2410,2635 ,1793,1793,1793 ,0,0,0}, + {2797,2757,2303 ,726,1793,1793 ,0,0,0}, {2450,2416,2632 ,1792,726,726 ,0,0,0}, + {2301,2299,2797 ,1793,726,726 ,0,0,0}, {2887,2497,2498 ,726,726,726 ,0,0,0}, + {2843,2524,2839 ,726,726,726 ,0,0,0}, {2526,2843,2845 ,726,726,726 ,0,0,0}, + {2605,2424,2606 ,1793,726,726 ,0,0,0}, {2280,2775,2281 ,1793,726,1793 ,0,0,0}, + {2797,2299,2795 ,726,726,1792 ,0,0,0}, {2792,2795,2298 ,726,1792,726 ,0,0,0}, + {2293,2793,2295 ,726,1793,1793 ,0,0,0}, {2295,2792,2298 ,1793,726,726 ,0,0,0}, + {2283,2779,2783 ,1793,1793,1793 ,0,0,0}, {2289,2786,2292 ,726,1793,726 ,0,0,0}, + {2293,2787,2793 ,726,726,1793 ,0,0,0}, {2785,2286,2783 ,1793,1793,1793 ,0,0,0}, + {2775,2779,2281 ,726,1793,1793 ,0,0,0}, {2776,2277,2772 ,1793,726,726 ,0,0,0}, + {2608,2429,2611 ,726,726,726 ,0,0,0}, {2771,2772,2275 ,1793,726,1793 ,0,0,0}, + {2839,2524,2492 ,726,726,726 ,0,0,0}, {2492,2840,2839 ,726,726,726 ,0,0,0}, + {2840,2492,2488 ,726,726,726 ,0,0,0}, {2494,2881,2487 ,726,726,726 ,0,0,0}, + {2488,2880,2840 ,726,726,726 ,0,0,0}, {2423,2424,2605 ,1793,726,1793 ,0,0,0}, + {2887,2886,2497 ,726,726,726 ,0,0,0}, {2886,2494,2497 ,726,726,726 ,0,0,0}, + {2578,2582,2459 ,726,1793,1793 ,0,0,0}, {2889,2887,2498 ,726,726,726 ,0,0,0}, + {2505,2892,2501 ,726,726,726 ,0,0,0}, {2893,2505,2507 ,726,726,726 ,0,0,0}, + {2505,2893,2892 ,726,726,726 ,0,0,0}, {2504,2895,2507 ,726,726,726 ,0,0,0}, + {2893,2507,2895 ,726,726,726 ,0,0,0}, {2895,2504,2898 ,726,726,726 ,0,0,0}, + {2508,2511,2899 ,726,726,726 ,0,0,0}, {2460,2459,2582 ,726,1793,1793 ,0,0,0}, + {2901,2511,2512 ,726,726,726 ,0,0,0}, {2511,2901,2899 ,726,726,726 ,0,0,0}, + {2905,2904,2514 ,726,726,726 ,0,0,0}, {2599,2477,2474 ,726,1793,1793 ,0,0,0}, + {2512,2514,2904 ,726,726,726 ,0,0,0}, {2518,2907,2905 ,726,726,726 ,0,0,0}, + {2905,2514,2518 ,726,726,726 ,0,0,0}, {2907,2518,2516 ,726,726,726 ,0,0,0}, + {2516,2521,2910 ,726,726,726 ,0,0,0}, {2910,2521,2911 ,726,726,726 ,0,0,0}, + {2911,2523,2913 ,726,726,726 ,0,0,0}, {2601,2480,2478 ,1793,726,1792 ,0,0,0}, + {2523,2911,2521 ,726,726,726 ,0,0,0}, {2402,2638,2636 ,726,726,1792 ,0,0,0}, + {2178,2179,2377 ,1792,726,726 ,0,0,0}, {2448,2450,2630 ,726,1792,726 ,0,0,0}, + {2636,2410,2409 ,1792,1793,1793 ,0,0,0}, {2447,2448,2629 ,1793,726,726 ,0,0,0}, + {2445,2447,2626 ,726,1793,726 ,0,0,0}, {2632,2416,2415 ,726,726,726 ,0,0,0}, + {2442,2445,2624 ,1793,726,1793 ,0,0,0}, {2632,2630,2450 ,726,726,1792 ,0,0,0}, + {2441,2442,2623 ,726,1793,1793 ,0,0,0}, {2630,2629,2448 ,726,726,726 ,0,0,0}, + {2439,2441,2620 ,1793,726,1793 ,0,0,0}, {2629,2626,2447 ,726,726,1793 ,0,0,0}, + {2436,2618,2617 ,1793,726,726 ,0,0,0}, {2626,2624,2445 ,726,1793,726 ,0,0,0}, + {2435,2617,2614 ,726,726,1793 ,0,0,0}, {2624,2623,2442 ,1793,1793,1793 ,0,0,0}, + {2433,2614,2612 ,1793,1793,726 ,0,0,0}, {2611,2430,2612 ,726,1793,726 ,0,0,0}, + {2436,2439,2618 ,1793,1793,726 ,0,0,0}, {2608,2606,2427 ,726,726,1793 ,0,0,0}, + {2436,2617,2435 ,1793,726,726 ,0,0,0}, {2845,2846,2529 ,726,726,726 ,0,0,0}, + {2614,2433,2435 ,1793,1793,726 ,0,0,0}, {2846,2849,2530 ,726,726,726 ,0,0,0}, + {2612,2430,2433 ,726,1793,1793 ,0,0,0}, {2849,2851,2532 ,726,726,726 ,0,0,0}, + {2268,2761,2269 ,1793,1793,726 ,0,0,0}, {2269,2765,2271 ,726,1793,726 ,0,0,0}, + {2606,2424,2427 ,726,726,1793 ,0,0,0}, {2535,2532,2851 ,726,726,726 ,0,0,0}, + {2526,2524,2843 ,726,726,726 ,0,0,0}, {2535,2852,2536 ,726,726,726 ,0,0,0}, + {2529,2526,2845 ,726,726,726 ,0,0,0}, {2855,2538,2536 ,726,726,726 ,0,0,0}, + {2530,2529,2846 ,726,726,726 ,0,0,0}, {2857,2541,2538 ,726,726,726 ,0,0,0}, + {2532,2530,2849 ,726,726,726 ,0,0,0}, {2232,2802,2231 ,726,1793,1793 ,0,0,0}, + {2542,2541,2858 ,726,726,726 ,0,0,0}, {2851,2852,2535 ,726,726,726 ,0,0,0}, + {2544,2542,2861 ,726,726,726 ,0,0,0}, {2544,2861,2863 ,726,726,726 ,0,0,0}, + {2235,2806,2805 ,1793,1793,726 ,0,0,0}, {2855,2857,2538 ,726,726,726 ,0,0,0}, + {2238,2811,2808 ,1793,1793,1793 ,0,0,0}, {2864,2547,2863 ,726,726,726 ,0,0,0}, + {2857,2858,2541 ,726,726,726 ,0,0,0}, {2548,2864,2867 ,726,726,726 ,0,0,0}, + {2858,2861,2542 ,726,726,726 ,0,0,0}, {2244,2817,2814 ,1793,1792,1793 ,0,0,0}, + {2863,2547,2544 ,726,726,726 ,0,0,0}, {2867,2869,2550 ,726,726,726 ,0,0,0}, + {2548,2547,2864 ,726,726,726 ,0,0,0}, {2870,2553,2869 ,726,726,726 ,0,0,0}, + {2247,2249,2818 ,726,1793,1793 ,0,0,0}, {2873,2554,2870 ,726,726,726 ,0,0,0}, + {2550,2548,2867 ,726,726,726 ,0,0,0}, {2253,2255,2824 ,726,726,726 ,0,0,0}, + {2869,2553,2550 ,726,726,726 ,0,0,0}, {2556,2873,2875 ,726,726,726 ,0,0,0}, + {2256,2259,2829 ,726,1793,726 ,0,0,0}, {2870,2554,2553 ,726,726,726 ,0,0,0}, + {2559,2556,2875 ,1793,726,726 ,0,0,0}, {2560,2559,2876 ,726,1793,726 ,0,0,0}, + {2261,2262,2830 ,726,726,1793 ,0,0,0}, {2559,2875,2876 ,1793,726,726 ,0,0,0}, + {2837,2836,2560 ,1793,726,726 ,0,0,0}, {2836,2265,2560 ,726,726,726 ,0,0,0}, + {2876,2837,2560 ,726,1793,726 ,0,0,0}, {2873,2556,2554 ,726,726,726 ,0,0,0}, + {2423,2605,2569 ,1793,1793,1793 ,0,0,0}, {2421,2569,2572 ,1793,1793,1793 ,0,0,0}, + {2417,2572,2567 ,1793,1793,1793 ,0,0,0}, {2451,2567,2571 ,726,1793,726 ,0,0,0}, + {2571,2574,2453 ,726,1793,1793 ,0,0,0}, {2494,2883,2881 ,726,726,726 ,0,0,0}, + {2569,2421,2423 ,1793,1793,1793 ,0,0,0}, {2574,2577,2454 ,1793,1793,726 ,0,0,0}, + {2572,2417,2421 ,1793,1793,1793 ,0,0,0}, {2498,2501,2889 ,726,726,726 ,0,0,0}, + {2417,2567,2451 ,1793,1793,726 ,0,0,0}, {2578,2456,2577 ,726,726,1793 ,0,0,0}, + {2571,2453,2451 ,726,1793,726 ,0,0,0}, {2460,2582,2581 ,726,1793,1793 ,0,0,0}, + {2574,2454,2453 ,1793,726,1793 ,0,0,0}, {2462,2460,2581 ,1793,726,1793 ,0,0,0}, + {2577,2456,2454 ,1793,726,726 ,0,0,0}, {2585,2465,2462 ,726,1793,1793 ,0,0,0}, + {2578,2459,2456 ,726,1793,726 ,0,0,0}, {2589,2466,2465 ,726,726,1793 ,0,0,0}, + {2591,2468,2466 ,1793,726,726 ,0,0,0}, {2898,2508,2899 ,726,726,726 ,0,0,0}, + {2462,2581,2585 ,1793,1793,726 ,0,0,0}, {2586,2471,2468 ,726,1793,726 ,0,0,0}, + {2465,2585,2589 ,1793,726,726 ,0,0,0}, {2471,2592,2472 ,1793,726,1793 ,0,0,0}, + {2466,2589,2591 ,726,726,1793 ,0,0,0}, {2474,2472,2593 ,1793,1793,726 ,0,0,0}, + {2471,2586,2592 ,1793,726,726 ,0,0,0}, {2477,2599,2598 ,1793,726,1793 ,0,0,0}, + {2472,2592,2593 ,1793,726,726 ,0,0,0}, {2601,2478,2598 ,1793,1792,1793 ,0,0,0}, + {2474,2593,2599 ,1793,726,726 ,0,0,0}, {2601,2483,2480 ,1793,726,726 ,0,0,0}, + {2478,2477,2598 ,1792,1793,1793 ,0,0,0}, {2483,2561,2486 ,726,726,726 ,0,0,0}, + {2563,2486,2561 ,1793,726,726 ,0,0,0}, {2913,2523,2486 ,726,726,726 ,0,0,0}, + {2601,2603,2483 ,1793,726,726 ,0,0,0}, {2468,2591,2586 ,726,1793,726 ,0,0,0}, + {2430,2611,2429 ,1793,726,726 ,0,0,0}, {2441,2623,2620 ,726,1793,1793 ,0,0,0}, + {2439,2620,2618 ,1793,1793,726 ,0,0,0}, {2358,2685,2686 ,1793,726,1793 ,0,0,0}, + {2412,2635,2415 ,1793,1793,726 ,0,0,0}, {2373,2364,2698 ,1793,726,726 ,0,0,0}, + {2636,2635,2410 ,1792,1793,1793 ,0,0,0}, {2400,2403,2938 ,726,1793,1793 ,0,0,0}, + {2402,2636,2409 ,726,1792,1793 ,0,0,0}, {2939,2392,2391 ,1793,1793,726 ,0,0,0}, + {2383,2214,2195 ,726,726,726 ,0,0,0}, {2394,2940,2391 ,1793,726,726 ,0,0,0}, + {2383,2195,2936 ,726,726,726 ,0,0,0}, {2641,2371,2367 ,726,726,1793 ,0,0,0}, + {2363,2691,2692 ,1793,726,726 ,0,0,0}, {2925,2323,2311 ,1793,1793,1793 ,0,0,0}, + {2680,2683,2357 ,1793,1793,1793 ,0,0,0}, {2352,2673,2674 ,1792,1793,1792 ,0,0,0}, + {2661,2662,2335 ,1793,1793,726 ,0,0,0}, {2715,2203,2716 ,1793,1793,1793 ,0,0,0}, + {2338,2656,2659 ,1793,726,1793 ,0,0,0}, {2668,2351,2336 ,726,726,726 ,0,0,0}, + {2351,2668,2671 ,726,726,1793 ,0,0,0}, {2354,2677,2679 ,1793,1793,1793 ,0,0,0}, + {2689,2358,2686 ,726,1793,1793 ,0,0,0}, {2689,2360,2358 ,726,726,1793 ,0,0,0}, + {2364,2363,2695 ,726,1793,726 ,0,0,0}, {2698,2700,2373 ,726,726,1793 ,0,0,0}, + {2373,2642,2370 ,1793,1793,1793 ,0,0,0}, {2367,2366,2641 ,1793,1793,726 ,0,0,0}, + {2939,2941,2392 ,1793,726,1793 ,0,0,0}, {2942,2943,2406 ,726,1793,726 ,0,0,0}, + {2943,2944,2406 ,1793,726,726 ,0,0,0}, {2945,2938,2403 ,726,1793,1793 ,0,0,0}, + {2938,2946,2400 ,1793,726,726 ,0,0,0}, {2371,2641,2638 ,726,726,726 ,0,0,0}, + {2642,2641,2366 ,1793,726,1793 ,0,0,0}, {2642,2373,2700 ,1793,1793,726 ,0,0,0}, + {2698,2364,2697 ,726,726,726 ,0,0,0}, {2695,2363,2692 ,726,1793,726 ,0,0,0}, + {2691,2360,2689 ,726,726,726 ,0,0,0}, {2358,2357,2685 ,1793,1793,726 ,0,0,0}, + {2357,2354,2680 ,1793,1793,1793 ,0,0,0}, {2352,2674,2677 ,1792,1792,1793 ,0,0,0}, + {2351,2671,2673 ,726,1793,1793 ,0,0,0}, {2336,2667,2668 ,726,1793,726 ,0,0,0}, + {2335,2662,2665 ,726,1793,1793 ,0,0,0}, {2338,2659,2661 ,1793,1793,1793 ,0,0,0}, + {2338,2340,2656 ,1793,1793,726 ,0,0,0}, {2342,2653,2655 ,726,1793,1793 ,0,0,0}, + {2345,2649,2650 ,1793,726,726 ,0,0,0}, {2346,2643,2647 ,726,1793,726 ,0,0,0}, + {2347,2703,2701 ,726,1793,1793 ,0,0,0}, {2916,2706,2704 ,1793,726,726 ,0,0,0}, + {2917,2710,2709 ,1793,1793,1793 ,0,0,0}, {2920,2715,2712 ,726,1793,726 ,0,0,0}, + {2134,2201,2132 ,726,1793,1793 ,0,0,0}, {2138,2141,2199 ,1793,1793,1793 ,0,0,0}, + {2718,2716,2131 ,1793,1793,726 ,0,0,0}, {2198,2140,2138 ,1793,726,1793 ,0,0,0}, + {2144,2205,2332 ,1793,726,1793 ,0,0,0}, {2947,2932,2948 ,726,1793,1793 ,0,0,0}, + {2317,2949,2315 ,726,1793,1793 ,0,0,0}, {2950,2317,2318 ,726,726,1793 ,0,0,0}, + {2312,2924,2313 ,1793,1793,726 ,0,0,0}, {2312,2315,2951 ,1793,1793,726 ,0,0,0}, + {2952,2322,2931 ,726,726,1793 ,0,0,0}, {2953,2328,2327 ,1793,1793,1793 ,0,0,0}, + {2947,2923,2922 ,726,1793,1793 ,0,0,0}, {2154,2727,2152 ,1793,1793,1793 ,0,0,0}, + {2149,2724,2722 ,1793,1793,1793 ,0,0,0}, {2158,2160,2733 ,1793,1793,726 ,0,0,0}, + {2155,2730,2728 ,726,726,726 ,0,0,0}, {2739,2161,2919 ,1793,1793,726 ,0,0,0}, + {2919,2926,2739 ,726,1793,1793 ,0,0,0}, {2736,2161,2739 ,726,1793,1793 ,0,0,0}, + {2736,2734,2160 ,726,726,1793 ,0,0,0}, {2742,2740,2926 ,726,726,1793 ,0,0,0}, + {2927,2745,2915 ,1793,726,726 ,0,0,0}, {2915,2742,2926 ,726,726,1793 ,0,0,0}, + {2927,2748,2746 ,1793,726,1793 ,0,0,0}, {2928,2308,2751 ,1793,1793,1793 ,0,0,0}, + {2927,2928,2748 ,1793,1793,726 ,0,0,0}, {2752,2751,2308 ,726,1793,1793 ,0,0,0}, + {2752,2305,2754 ,726,1793,1793 ,0,0,0}, {2757,2305,2303 ,1793,1793,1793 ,0,0,0}, + {2377,2174,2379 ,726,1793,726 ,0,0,0}, {2936,2937,2387 ,726,1793,726 ,0,0,0}, + {2168,2165,2224 ,1793,726,726 ,0,0,0}, {2934,2384,2386 ,726,726,726 ,0,0,0}, + {2935,2384,2933 ,1793,726,726 ,0,0,0}, {2940,2394,2935 ,726,1793,1793 ,0,0,0}, + {2939,2391,2940 ,1793,726,726 ,0,0,0}, {2396,2392,2941 ,1793,1793,726 ,0,0,0}, + {2396,2954,2406 ,1793,1793,726 ,0,0,0}, {2954,2396,2941 ,1793,1793,726 ,0,0,0}, + {2954,2942,2406 ,1793,726,726 ,0,0,0}, {2403,2944,2945 ,1793,726,726 ,0,0,0}, + {2944,2403,2406 ,726,1793,726 ,0,0,0}, {2402,2181,2638 ,726,726,726 ,0,0,0}, + {2946,2181,2402 ,726,726,726 ,0,0,0}, {2946,2402,2400 ,726,726,726 ,0,0,0}, + {2181,2178,2638 ,726,1792,726 ,0,0,0}, {2376,2178,2377 ,1793,1792,726 ,0,0,0}, + {2178,2376,2638 ,1792,1793,726 ,0,0,0}, {2179,2174,2377 ,726,1793,726 ,0,0,0}, + {2172,2175,2379 ,726,726,726 ,0,0,0}, {2174,2172,2379 ,1793,726,726 ,0,0,0}, + {2175,2166,2382 ,726,726,726 ,0,0,0}, {2168,2224,2382 ,1793,726,726 ,0,0,0}, + {2222,2224,2164 ,1793,726,1793 ,0,0,0}, {2186,2221,2183 ,726,1793,726 ,0,0,0}, + {2183,2222,2164 ,726,1793,1793 ,0,0,0}, {2188,2219,2186 ,726,726,726 ,0,0,0}, + {2188,2189,2208 ,726,1793,1793 ,0,0,0}, {2188,2207,2219 ,726,726,726 ,0,0,0}, + {2211,2192,2212 ,726,726,1793 ,0,0,0}, {2208,2189,2211 ,1793,1793,726 ,0,0,0}, + {2214,2194,2195 ,726,1792,726 ,0,0,0}, {2212,2192,2194 ,1793,726,1792 ,0,0,0}, + {2328,2955,2330 ,1793,726,1793 ,0,0,0}, {2919,2918,2923 ,726,726,1793 ,0,0,0}, + {2332,2330,2147 ,1793,1793,1793 ,0,0,0}, {2947,2948,2923 ,726,1793,1793 ,0,0,0}, + {2932,2931,2948 ,1793,1793,1793 ,0,0,0}, {2952,2931,2930 ,726,1793,1793 ,0,0,0}, + {2921,2322,2952 ,1793,726,726 ,0,0,0}, {2950,2318,2921 ,726,1793,1793 ,0,0,0}, + {2949,2317,2950 ,1793,726,726 ,0,0,0}, {2951,2315,2949 ,726,1793,1793 ,0,0,0}, + {2924,2312,2951 ,1793,1793,726 ,0,0,0}, {2311,2313,2925 ,1793,726,1793 ,0,0,0}, + {2929,2323,2925 ,726,1793,1793 ,0,0,0}, {2953,2327,2929 ,1793,1793,726 ,0,0,0}, + {2955,2328,2953 ,726,1793,1793 ,0,0,0}, {2147,2330,2955 ,1793,1793,726 ,0,0,0}, + {2144,2332,2147 ,1793,1793,1793 ,0,0,0}, {2145,2205,2144 ,1793,726,1793 ,0,0,0}, + {2198,2145,2140 ,1793,1793,726 ,0,0,0}, {2145,2198,2205 ,1793,1793,726 ,0,0,0}, + {2138,2199,2198 ,1793,1793,1793 ,0,0,0}, {2203,2201,2134 ,1793,1793,726 ,0,0,0}, + {2718,2131,2130 ,1793,726,726 ,0,0,0}, {2131,2716,2203 ,726,1793,1793 ,0,0,0}, + {2149,2722,2130 ,1793,1793,726 ,0,0,0}, {2721,2718,2130 ,726,1793,726 ,0,0,0}, + {2152,2724,2149 ,1793,1793,1793 ,0,0,0}, {2154,2728,2727 ,1793,726,1793 ,0,0,0}, + {2152,2727,2724 ,1793,1793,1793 ,0,0,0}, {2155,2158,2730 ,726,1793,726 ,0,0,0}, + {2154,2155,2728 ,1793,726,726 ,0,0,0}, {2733,2160,2734 ,726,1793,726 ,0,0,0}, + {2730,2158,2733 ,726,1793,726 ,0,0,0}, {2736,2160,2161 ,726,1793,1793 ,0,0,0}, + {2484,2602,2600 ,730,730,730 ,0,0,0}, {2266,2762,2227 ,730,730,730 ,0,0,0}, + {2337,2670,2669 ,730,730,730 ,0,0,0}, {2596,2479,2597 ,730,730,730 ,0,0,0}, + {2470,2473,2588 ,730,730,730 ,0,0,0}, {2475,2476,2595 ,730,730,730 ,0,0,0}, + {2461,2463,2580 ,730,730,730 ,0,0,0}, {2464,2467,2584 ,730,730,730 ,0,0,0}, + {2565,2568,2419 ,730,730,730 ,0,0,0}, {2455,2457,2575 ,730,730,730 ,0,0,0}, + {2764,2228,2227 ,730,730,730 ,0,0,0}, {2609,2426,2607 ,730,730,730 ,0,0,0}, + {2236,2804,2807 ,730,730,730 ,0,0,0}, {2810,2813,2242 ,730,730,730 ,0,0,0}, + {2798,2801,2230 ,730,730,730 ,0,0,0}, {2804,2236,2234 ,730,730,730 ,0,0,0}, + {2267,2760,2759 ,730,730,730 ,0,0,0}, {2228,2764,2798 ,730,730,730 ,0,0,0}, + {2272,2273,2769 ,730,730,730 ,0,0,0}, {2842,2525,2844 ,730,730,730 ,0,0,0}, + {2770,2276,2773 ,730,730,730 ,0,0,0}, {2273,2770,2769 ,730,730,730 ,0,0,0}, + {2285,2784,2284 ,730,730,730 ,0,0,0}, {2278,2774,2773 ,730,730,730 ,0,0,0}, + {2791,2790,2296 ,730,730,730 ,0,0,0}, {2789,2788,2291 ,730,730,730 ,0,0,0}, + {2297,2300,2794 ,730,730,730 ,0,0,0}, {2956,2708,2711 ,730,730,730 ,0,0,0}, + {2343,2341,2652 ,730,730,730 ,0,0,0}, {2146,2206,2204 ,730,730,730 ,0,0,0}, + {2156,2731,2732 ,730,730,730 ,0,0,0}, {2306,2756,2758 ,730,730,730 ,0,0,0}, + {2796,2304,2758 ,730,730,730 ,0,0,0}, {2957,2958,2750 ,730,730,730 ,0,0,0}, + {2159,2157,2735 ,730,730,730 ,0,0,0}, {2957,2750,2753 ,730,730,730 ,0,0,0}, + {2747,2749,2958 ,730,730,730 ,0,0,0}, {2309,2959,2310 ,730,730,730 ,0,0,0}, + {2758,2304,2306 ,730,730,730 ,0,0,0}, {2670,2337,2350 ,730,730,730 ,0,0,0}, + {2960,2349,2707 ,730,730,730 ,0,0,0}, {2648,2646,2344 ,730,730,730 ,0,0,0}, + {2156,2732,2157 ,730,730,730 ,0,0,0}, {2202,2717,2719 ,730,730,730 ,0,0,0}, + {2300,2302,2796 ,730,730,730 ,0,0,0}, {2200,2133,2197 ,730,730,730 ,0,0,0}, + {2136,2137,2197 ,730,730,730 ,0,0,0}, {2961,2325,2326 ,730,730,730 ,0,0,0}, + {2957,2753,2307 ,730,730,730 ,0,0,0}, {2306,2307,2755 ,730,730,730 ,0,0,0}, + {2962,2747,2958 ,730,730,730 ,0,0,0}, {2743,2744,2963 ,730,730,730 ,0,0,0}, + {2963,2744,2962 ,730,730,730 ,0,0,0}, {2962,2744,2747 ,730,730,730 ,0,0,0}, + {2958,2749,2750 ,730,730,730 ,0,0,0}, {2964,2965,2966 ,730,730,730 ,0,0,0}, + {2215,2216,2193 ,730,730,730 ,0,0,0}, {2753,2755,2307 ,730,730,730 ,0,0,0}, + {2737,2159,2735 ,730,730,730 ,0,0,0}, {2756,2306,2755 ,730,730,730 ,0,0,0}, + {2967,2321,2319 ,730,730,730 ,0,0,0}, {2326,2329,2968 ,730,730,730 ,0,0,0}, + {2331,2206,2143 ,730,730,730 ,0,0,0}, {2329,2331,2142 ,730,730,730 ,0,0,0}, + {2796,2302,2304 ,730,730,730 ,0,0,0}, {2310,2969,2314 ,730,730,730 ,0,0,0}, + {2970,2324,2325 ,730,730,730 ,0,0,0}, {2202,2719,2129 ,730,730,730 ,0,0,0}, + {2314,2971,2316 ,730,730,730 ,0,0,0}, {2153,2731,2156 ,730,730,730 ,0,0,0}, + {2731,2153,2729 ,730,730,730 ,0,0,0}, {2644,2348,2645 ,730,730,730 ,0,0,0}, + {2660,2334,2663 ,730,730,730 ,0,0,0}, {2657,2654,2339 ,730,730,730 ,0,0,0}, + {2678,2676,2353 ,730,730,730 ,0,0,0}, {2666,2333,2337 ,730,730,730 ,0,0,0}, + {2678,2353,2355 ,730,730,730 ,0,0,0}, {2296,2297,2791 ,730,730,730 ,0,0,0}, + {2300,2796,2794 ,730,730,730 ,0,0,0}, {2794,2791,2297 ,730,730,730 ,0,0,0}, + {2810,2240,2809 ,730,730,730 ,0,0,0}, {2789,2291,2294 ,730,730,730 ,0,0,0}, + {2790,2294,2296 ,730,730,730 ,0,0,0}, {2290,2291,2788 ,730,730,730 ,0,0,0}, + {2789,2294,2790 ,730,730,730 ,0,0,0}, {2290,2782,2288 ,730,730,730 ,0,0,0}, + {2781,2285,2288 ,730,730,730 ,0,0,0}, {2788,2782,2290 ,730,730,730 ,0,0,0}, + {2285,2781,2784 ,730,730,730 ,0,0,0}, {2288,2782,2781 ,730,730,730 ,0,0,0}, + {2619,2438,2437 ,730,730,730 ,0,0,0}, {2778,2282,2284 ,730,730,730 ,0,0,0}, + {2282,2777,2279 ,730,730,730 ,0,0,0}, {2777,2774,2279 ,730,730,730 ,0,0,0}, + {2774,2278,2279 ,730,730,730 ,0,0,0}, {2773,2276,2278 ,730,730,730 ,0,0,0}, + {2770,2273,2276 ,730,730,730 ,0,0,0}, {2270,2767,2760 ,730,730,730 ,0,0,0}, + {2272,2769,2767 ,730,730,730 ,0,0,0}, {2267,2759,2266 ,730,730,730 ,0,0,0}, + {2762,2764,2227 ,730,730,730 ,0,0,0}, {2230,2801,2233 ,730,730,730 ,0,0,0}, + {2234,2233,2803 ,730,730,730 ,0,0,0}, {2236,2807,2239 ,730,730,730 ,0,0,0}, + {2234,2803,2804 ,730,730,730 ,0,0,0}, {2239,2809,2240 ,730,730,730 ,0,0,0}, + {2239,2807,2809 ,730,730,730 ,0,0,0}, {2245,2813,2815 ,730,730,730 ,0,0,0}, + {2242,2240,2810 ,730,730,730 ,0,0,0}, {2246,2245,2815 ,730,730,730 ,0,0,0}, + {2246,2815,2816 ,730,730,730 ,0,0,0}, {2248,2816,2819 ,730,730,730 ,0,0,0}, + {2246,2816,2248 ,730,730,730 ,0,0,0}, {2819,2251,2248 ,730,730,730 ,0,0,0}, + {2819,2821,2251 ,730,730,730 ,0,0,0}, {2251,2821,2252 ,730,730,730 ,0,0,0}, + {2233,2801,2803 ,730,730,730 ,0,0,0}, {2254,2252,2822 ,730,730,730 ,0,0,0}, + {2252,2821,2822 ,730,730,730 ,0,0,0}, {2825,2257,2254 ,730,730,730 ,0,0,0}, + {2825,2254,2822 ,730,730,730 ,0,0,0}, {2257,2827,2258 ,730,730,730 ,0,0,0}, + {2258,2828,2260 ,730,730,730 ,0,0,0}, {2828,2258,2827 ,730,730,730 ,0,0,0}, + {2828,2831,2263 ,730,730,730 ,0,0,0}, {2555,2874,2872 ,730,730,730 ,0,0,0}, + {2264,2263,2831 ,730,730,730 ,0,0,0}, {2834,2838,2558 ,730,730,730 ,0,0,0}, + {2557,2877,2874 ,730,730,730 ,0,0,0}, {2230,2228,2798 ,730,730,730 ,0,0,0}, + {2491,2878,2489 ,730,730,730 ,0,0,0}, {2877,2557,2558 ,730,730,730 ,0,0,0}, + {2759,2762,2266 ,730,730,730 ,0,0,0}, {2613,2431,2610 ,730,730,730 ,0,0,0}, + {2434,2432,2615 ,730,730,730 ,0,0,0}, {2432,2431,2613 ,730,730,730 ,0,0,0}, + {2428,2426,2609 ,730,730,730 ,0,0,0}, {2609,2610,2428 ,730,730,730 ,0,0,0}, + {2607,2425,2604 ,730,730,730 ,0,0,0}, {2607,2426,2425 ,730,730,730 ,0,0,0}, + {2570,2604,2422 ,730,730,730 ,0,0,0}, {2425,2422,2604 ,730,730,730 ,0,0,0}, + {2420,2568,2570 ,730,730,730 ,0,0,0}, {2570,2422,2420 ,730,730,730 ,0,0,0}, + {2566,2418,2452 ,730,730,730 ,0,0,0}, {2419,2568,2420 ,730,730,730 ,0,0,0}, + {2452,2455,2573 ,730,730,730 ,0,0,0}, {2418,2566,2565 ,730,730,730 ,0,0,0}, + {2566,2452,2573 ,730,730,730 ,0,0,0}, {2579,2576,2458 ,730,730,730 ,0,0,0}, + {2500,2890,2891 ,730,730,730 ,0,0,0}, {2461,2579,2458 ,730,730,730 ,0,0,0}, + {2457,2458,2576 ,730,730,730 ,0,0,0}, {2583,2464,2584 ,730,730,730 ,0,0,0}, + {2580,2579,2461 ,730,730,730 ,0,0,0}, {2467,2590,2584 ,730,730,730 ,0,0,0}, + {2464,2583,2463 ,730,730,730 ,0,0,0}, {2470,2587,2469 ,730,730,730 ,0,0,0}, + {2469,2587,2590 ,730,730,730 ,0,0,0}, {2594,2588,2473 ,730,730,730 ,0,0,0}, + {2588,2587,2470 ,730,730,730 ,0,0,0}, {2476,2596,2595 ,730,730,730 ,0,0,0}, + {2475,2595,2594 ,730,730,730 ,0,0,0}, {2600,2481,2482 ,730,730,730 ,0,0,0}, + {2481,2597,2479 ,730,730,730 ,0,0,0}, {2600,2482,2484 ,730,730,730 ,0,0,0}, + {2831,2833,2264 ,730,730,730 ,0,0,0}, {2834,2264,2833 ,730,730,730 ,0,0,0}, + {2552,2871,2551 ,730,730,730 ,0,0,0}, {2263,2260,2828 ,730,730,730 ,0,0,0}, + {2557,2874,2555 ,730,730,730 ,0,0,0}, {2257,2825,2827 ,730,730,730 ,0,0,0}, + {2549,2551,2868 ,730,730,730 ,0,0,0}, {2872,2871,2552 ,730,730,730 ,0,0,0}, + {2546,2549,2866 ,730,730,730 ,0,0,0}, {2871,2868,2551 ,730,730,730 ,0,0,0}, + {2865,2545,2546 ,730,730,730 ,0,0,0}, {2862,2543,2545 ,730,730,730 ,0,0,0}, + {2866,2549,2868 ,730,730,730 ,0,0,0}, {2860,2540,2543 ,730,730,730 ,0,0,0}, + {2865,2546,2866 ,730,730,730 ,0,0,0}, {2242,2813,2245 ,730,730,730 ,0,0,0}, + {2865,2862,2545 ,730,730,730 ,0,0,0}, {2859,2856,2539 ,730,730,730 ,0,0,0}, + {2862,2860,2543 ,730,730,730 ,0,0,0}, {2856,2854,2537 ,730,730,730 ,0,0,0}, + {2854,2853,2534 ,730,730,730 ,0,0,0}, {2853,2850,2533 ,730,730,730 ,0,0,0}, + {2540,2859,2539 ,730,730,730 ,0,0,0}, {2850,2848,2531 ,730,730,730 ,0,0,0}, + {2539,2856,2537 ,730,730,730 ,0,0,0}, {2847,2528,2848 ,730,730,730 ,0,0,0}, + {2537,2854,2534 ,730,730,730 ,0,0,0}, {2527,2847,2844 ,730,730,730 ,0,0,0}, + {2534,2853,2533 ,730,730,730 ,0,0,0}, {2525,2842,2490 ,730,730,730 ,0,0,0}, + {2533,2850,2531 ,730,730,730 ,0,0,0}, {2491,2490,2841 ,730,730,730 ,0,0,0}, + {2848,2528,2531 ,730,730,730 ,0,0,0}, {2489,2879,2493 ,730,730,730 ,0,0,0}, + {2527,2528,2847 ,730,730,730 ,0,0,0}, {2616,2434,2615 ,730,730,730 ,0,0,0}, + {2272,2767,2270 ,730,730,730 ,0,0,0}, {2270,2760,2267 ,730,730,730 ,0,0,0}, + {2490,2842,2841 ,730,730,730 ,0,0,0}, {2616,2619,2437 ,730,730,730 ,0,0,0}, + {2491,2841,2878 ,730,730,730 ,0,0,0}, {2619,2621,2438 ,730,730,730 ,0,0,0}, + {2489,2878,2879 ,730,730,730 ,0,0,0}, {2621,2622,2440 ,730,730,730 ,0,0,0}, + {2622,2625,2443 ,730,730,730 ,0,0,0}, {2613,2615,2432 ,730,730,730 ,0,0,0}, + {2625,2627,2444 ,730,730,730 ,0,0,0}, {2437,2434,2616 ,730,730,730 ,0,0,0}, + {2627,2628,2446 ,730,730,730 ,0,0,0}, {2284,2784,2778 ,730,730,730 ,0,0,0}, + {2282,2778,2777 ,730,730,730 ,0,0,0}, {2621,2440,2438 ,730,730,730 ,0,0,0}, + {2413,2631,2633 ,730,730,730 ,0,0,0}, {2622,2443,2440 ,730,730,730 ,0,0,0}, + {2405,2972,2973 ,730,730,730 ,0,0,0}, {2625,2444,2443 ,730,730,730 ,0,0,0}, + {2210,2213,2190 ,730,730,730 ,0,0,0}, {2184,2218,2185 ,730,730,730 ,0,0,0}, + {2449,2631,2414 ,730,730,730 ,0,0,0}, {2368,2637,2639 ,730,730,730 ,0,0,0}, + {2374,2372,2640 ,730,730,730 ,0,0,0}, {2187,2209,2210 ,730,730,730 ,0,0,0}, + {2362,2696,2694 ,730,730,730 ,0,0,0}, {2974,2388,2975 ,730,730,730 ,0,0,0}, + {2637,2368,2375 ,730,730,730 ,0,0,0}, {2356,2687,2684 ,730,730,730 ,0,0,0}, + {2738,2162,2159 ,730,730,730 ,0,0,0}, {2976,2741,2963 ,730,730,730 ,0,0,0}, + {2743,2963,2741 ,730,730,730 ,0,0,0}, {2741,2976,2162 ,730,730,730 ,0,0,0}, + {2977,2978,2979 ,730,730,730 ,0,0,0}, {2741,2162,2738 ,730,730,730 ,0,0,0}, + {2737,2738,2159 ,730,730,730 ,0,0,0}, {2139,2204,2137 ,730,730,730 ,0,0,0}, + {2970,2959,2324 ,730,730,730 ,0,0,0}, {2980,2981,2982 ,730,730,730 ,0,0,0}, + {2644,2702,2348 ,730,730,730 ,0,0,0}, {2334,2658,2339 ,730,730,730 ,0,0,0}, + {2675,2350,2353 ,730,730,730 ,0,0,0}, {2688,2359,2361 ,730,730,730 ,0,0,0}, + {2688,2687,2359 ,730,730,730 ,0,0,0}, {2690,2361,2693 ,730,730,730 ,0,0,0}, + {2684,2682,2356 ,730,730,730 ,0,0,0}, {2682,2681,2355 ,730,730,730 ,0,0,0}, + {2350,2675,2672 ,730,730,730 ,0,0,0}, {2666,2664,2333 ,730,730,730 ,0,0,0}, + {2333,2663,2334 ,730,730,730 ,0,0,0}, {2658,2657,2339 ,730,730,730 ,0,0,0}, + {2652,2651,2343 ,730,730,730 ,0,0,0}, {2648,2344,2343 ,730,730,730 ,0,0,0}, + {2693,2362,2694 ,730,730,730 ,0,0,0}, {2646,2645,2344 ,730,730,730 ,0,0,0}, + {2702,2349,2348 ,730,730,730 ,0,0,0}, {2705,2707,2349 ,730,730,730 ,0,0,0}, + {2713,2983,2956 ,730,730,730 ,0,0,0}, {2983,2713,2714 ,730,730,730 ,0,0,0}, + {2202,2983,2717 ,730,730,730 ,0,0,0}, {2148,2720,2723 ,730,730,730 ,0,0,0}, + {2151,2150,2726 ,730,730,730 ,0,0,0}, {2148,2129,2720 ,730,730,730 ,0,0,0}, + {2714,2717,2983 ,730,730,730 ,0,0,0}, {2711,2713,2956 ,730,730,730 ,0,0,0}, + {2707,2708,2960 ,730,730,730 ,0,0,0}, {2708,2956,2960 ,730,730,730 ,0,0,0}, + {2702,2705,2349 ,730,730,730 ,0,0,0}, {2645,2348,2344 ,730,730,730 ,0,0,0}, + {2648,2343,2651 ,730,730,730 ,0,0,0}, {2341,2339,2654 ,730,730,730 ,0,0,0}, + {2341,2654,2652 ,730,730,730 ,0,0,0}, {2334,2660,2658 ,730,730,730 ,0,0,0}, + {2333,2664,2663 ,730,730,730 ,0,0,0}, {2337,2669,2666 ,730,730,730 ,0,0,0}, + {2350,2672,2670 ,730,730,730 ,0,0,0}, {2353,2676,2675 ,730,730,730 ,0,0,0}, + {2355,2681,2678 ,730,730,730 ,0,0,0}, {2355,2356,2682 ,730,730,730 ,0,0,0}, + {2356,2359,2687 ,730,730,730 ,0,0,0}, {2361,2690,2688 ,730,730,730 ,0,0,0}, + {2361,2362,2693 ,730,730,730 ,0,0,0}, {2362,2374,2696 ,730,730,730 ,0,0,0}, + {2374,2640,2699 ,730,730,730 ,0,0,0}, {2696,2374,2699 ,730,730,730 ,0,0,0}, + {2640,2372,2369 ,730,730,730 ,0,0,0}, {2369,2365,2639 ,730,730,730 ,0,0,0}, + {2639,2640,2369 ,730,730,730 ,0,0,0}, {2191,2190,2213 ,730,730,730 ,0,0,0}, + {2368,2639,2365 ,730,730,730 ,0,0,0}, {2170,2380,2381 ,730,730,730 ,0,0,0}, + {2191,2213,2215 ,730,730,730 ,0,0,0}, {2216,2389,2196 ,730,730,730 ,0,0,0}, + {2215,2193,2191 ,730,730,730 ,0,0,0}, {2216,2196,2193 ,730,730,730 ,0,0,0}, + {2397,2984,2390 ,730,730,730 ,0,0,0}, {2393,2985,2385 ,730,730,730 ,0,0,0}, + {2986,2398,2987 ,730,730,730 ,0,0,0}, {2405,2988,2987 ,730,730,730 ,0,0,0}, + {2220,2182,2223 ,730,730,730 ,0,0,0}, {2989,2404,2990 ,730,730,730 ,0,0,0}, + {2184,2182,2220 ,730,730,730 ,0,0,0}, {2633,2408,2411 ,730,730,730 ,0,0,0}, + {2634,2407,2408 ,730,730,730 ,0,0,0}, {2173,2380,2171 ,730,730,730 ,0,0,0}, + {2381,2167,2170 ,730,730,730 ,0,0,0}, {2173,2180,2378 ,730,730,730 ,0,0,0}, + {2401,2407,2634 ,730,730,730 ,0,0,0}, {2401,2634,2637 ,730,730,730 ,0,0,0}, + {2408,2633,2634 ,730,730,730 ,0,0,0}, {2413,2633,2411 ,730,730,730 ,0,0,0}, + {2414,2631,2413 ,730,730,730 ,0,0,0}, {2628,2631,2449 ,730,730,730 ,0,0,0}, + {2446,2628,2449 ,730,730,730 ,0,0,0}, {2444,2627,2446 ,730,730,730 ,0,0,0}, + {2493,2882,2495 ,730,730,730 ,0,0,0}, {2885,2495,2884 ,730,730,730 ,0,0,0}, + {2428,2610,2431 ,730,730,730 ,0,0,0}, {2888,2496,2885 ,730,730,730 ,0,0,0}, + {2888,2499,2496 ,730,730,730 ,0,0,0}, {2890,2500,2499 ,730,730,730 ,0,0,0}, + {2882,2493,2879 ,730,730,730 ,0,0,0}, {2891,2506,2500 ,730,730,730 ,0,0,0}, + {2884,2495,2882 ,730,730,730 ,0,0,0}, {2418,2565,2419 ,730,730,730 ,0,0,0}, + {2502,2506,2894 ,730,730,730 ,0,0,0}, {2496,2495,2885 ,730,730,730 ,0,0,0}, + {2503,2502,2896 ,730,730,730 ,0,0,0}, {2888,2890,2499 ,730,730,730 ,0,0,0}, + {2509,2503,2897 ,730,730,730 ,0,0,0}, {2457,2576,2575 ,730,730,730 ,0,0,0}, + {2455,2575,2573 ,730,730,730 ,0,0,0}, {2506,2891,2894 ,730,730,730 ,0,0,0}, + {2510,2509,2900 ,730,730,730 ,0,0,0}, {2510,2900,2902 ,730,730,730 ,0,0,0}, + {2894,2896,2502 ,730,730,730 ,0,0,0}, {2463,2583,2580 ,730,730,730 ,0,0,0}, + {2503,2896,2897 ,730,730,730 ,0,0,0}, {2902,2903,2513 ,730,730,730 ,0,0,0}, + {2906,2519,2903 ,730,730,730 ,0,0,0}, {2897,2900,2509 ,730,730,730 ,0,0,0}, + {2513,2510,2902 ,730,730,730 ,0,0,0}, {2908,2517,2906 ,730,730,730 ,0,0,0}, + {2467,2469,2590 ,730,730,730 ,0,0,0}, {2909,2515,2908 ,730,730,730 ,0,0,0}, + {2519,2513,2903 ,730,730,730 ,0,0,0}, {2473,2475,2594 ,730,730,730 ,0,0,0}, + {2906,2517,2519 ,730,730,730 ,0,0,0}, {2909,2912,2520 ,730,730,730 ,0,0,0}, + {2476,2479,2596 ,730,730,730 ,0,0,0}, {2908,2515,2517 ,730,730,730 ,0,0,0}, + {2522,2520,2912 ,730,730,730 ,0,0,0}, {2522,2914,2485 ,730,730,730 ,0,0,0}, + {2597,2481,2600 ,730,730,730 ,0,0,0}, {2522,2912,2914 ,730,730,730 ,0,0,0}, + {2564,2484,2485 ,730,730,730 ,0,0,0}, {2602,2484,2564 ,730,730,730 ,0,0,0}, + {2914,2562,2485 ,730,730,730 ,0,0,0}, {2564,2485,2562 ,730,730,730 ,0,0,0}, + {2909,2520,2515 ,730,730,730 ,0,0,0}, {2525,2527,2844 ,730,730,730 ,0,0,0}, + {2859,2540,2860 ,730,730,730 ,0,0,0}, {2872,2552,2555 ,730,730,730 ,0,0,0}, + {2834,2558,2264 ,730,730,730 ,0,0,0}, {2838,2877,2558 ,730,730,730 ,0,0,0}, + {2185,2217,2187 ,730,730,730 ,0,0,0}, {2991,2393,2395 ,730,730,730 ,0,0,0}, + {2397,2986,2984 ,730,730,730 ,0,0,0}, {2187,2210,2190 ,730,730,730 ,0,0,0}, + {2187,2217,2209 ,730,730,730 ,0,0,0}, {2185,2218,2217 ,730,730,730 ,0,0,0}, + {2184,2220,2218 ,730,730,730 ,0,0,0}, {2399,2401,2992 ,730,730,730 ,0,0,0}, + {2163,2169,2223 ,730,730,730 ,0,0,0}, {2163,2223,2182 ,730,730,730 ,0,0,0}, + {2381,2169,2167 ,730,730,730 ,0,0,0}, {2169,2381,2223 ,730,730,730 ,0,0,0}, + {2176,2401,2637 ,730,730,730 ,0,0,0}, {2173,2378,2380 ,730,730,730 ,0,0,0}, + {2170,2171,2380 ,730,730,730 ,0,0,0}, {2177,2378,2180 ,730,730,730 ,0,0,0}, + {2637,2177,2176 ,730,730,730 ,0,0,0}, {2375,2177,2637 ,730,730,730 ,0,0,0}, + {2177,2375,2378 ,730,730,730 ,0,0,0}, {2176,2992,2401 ,730,730,730 ,0,0,0}, + {2399,2990,2404 ,730,730,730 ,0,0,0}, {2992,2990,2399 ,730,730,730 ,0,0,0}, + {2404,2972,2405 ,730,730,730 ,0,0,0}, {2989,2972,2404 ,730,730,730 ,0,0,0}, + {2973,2988,2405 ,730,730,730 ,0,0,0}, {2987,2398,2405 ,730,730,730 ,0,0,0}, + {2986,2397,2398 ,730,730,730 ,0,0,0}, {2993,2390,2984 ,730,730,730 ,0,0,0}, + {2395,2993,2991 ,730,730,730 ,0,0,0}, {2993,2395,2390 ,730,730,730 ,0,0,0}, + {2991,2994,2393 ,730,730,730 ,0,0,0}, {2985,2975,2385 ,730,730,730 ,0,0,0}, + {2994,2985,2393 ,730,730,730 ,0,0,0}, {2388,2974,2389 ,730,730,730 ,0,0,0}, + {2385,2975,2388 ,730,730,730 ,0,0,0}, {2196,2389,2974 ,730,730,730 ,0,0,0}, + {2200,2202,2135 ,730,730,730 ,0,0,0}, {2732,2735,2157 ,730,730,730 ,0,0,0}, + {2319,2316,2995 ,730,730,730 ,0,0,0}, {2151,2726,2729 ,730,730,730 ,0,0,0}, + {2729,2153,2151 ,730,730,730 ,0,0,0}, {2725,2726,2150 ,730,730,730 ,0,0,0}, + {2725,2148,2723 ,730,730,730 ,0,0,0}, {2148,2725,2150 ,730,730,730 ,0,0,0}, + {2720,2129,2719 ,730,730,730 ,0,0,0}, {2129,2135,2202 ,730,730,730 ,0,0,0}, + {2135,2133,2200 ,730,730,730 ,0,0,0}, {2133,2136,2197 ,730,730,730 ,0,0,0}, + {2137,2204,2197 ,730,730,730 ,0,0,0}, {2146,2204,2139 ,730,730,730 ,0,0,0}, + {2143,2206,2146 ,730,730,730 ,0,0,0}, {2142,2331,2143 ,730,730,730 ,0,0,0}, + {2968,2329,2142 ,730,730,730 ,0,0,0}, {2961,2326,2968 ,730,730,730 ,0,0,0}, + {2970,2325,2961 ,730,730,730 ,0,0,0}, {2309,2324,2959 ,730,730,730 ,0,0,0}, + {2969,2310,2959 ,730,730,730 ,0,0,0}, {2971,2314,2969 ,730,730,730 ,0,0,0}, + {2995,2316,2971 ,730,730,730 ,0,0,0}, {2996,2321,2967 ,730,730,730 ,0,0,0}, + {2967,2319,2995 ,730,730,730 ,0,0,0}, {2320,2996,2982 ,730,730,730 ,0,0,0}, + {2996,2320,2321 ,730,730,730 ,0,0,0}, {2980,2965,2981 ,730,730,730 ,0,0,0}, + {2320,2982,2981 ,730,730,730 ,0,0,0}, {2964,2966,2977 ,730,730,730 ,0,0,0}, + {2981,2965,2964 ,730,730,730 ,0,0,0}, {2977,2979,2976 ,730,730,730 ,0,0,0}, + {2977,2966,2978 ,730,730,730 ,0,0,0}, {2162,2976,2979 ,730,730,730 ,0,0,0}, + {2976,2963,2926 ,2553,2554,2555 ,0,0,0}, {2977,2919,2923 ,2556,2557,2558 ,0,0,0}, + {2919,2976,2926 ,2557,2553,2555 ,0,0,0}, {2976,2919,2977 ,2553,2557,2556 ,0,0,0}, + {2981,2948,2931 ,2559,2560,2561 ,0,0,0}, {2977,2923,2964 ,2556,2558,2562 ,0,0,0}, + {2981,2964,2948 ,2559,2562,2560 ,0,0,0}, {2931,2322,2320 ,2561,1982,1982 ,0,0,0}, + {2931,2320,2981 ,2561,1982,2559 ,0,0,0}, {2948,2964,2923 ,2560,2562,2558 ,0,0,0}, + {2963,2915,2926 ,2554,2563,2555 ,0,0,0}, {2927,2915,2962 ,2564,2563,2565 ,0,0,0}, + {2963,2962,2915 ,2554,2565,2563 ,0,0,0}, {2958,2928,2927 ,2566,2567,2564 ,0,0,0}, + {2927,2962,2958 ,2564,2565,2566 ,0,0,0}, {2928,2957,2308 ,2567,2568,1972 ,0,0,0}, + {2957,2928,2958 ,2568,2567,2566 ,0,0,0}, {2957,2307,2308 ,2568,1972,1972 ,0,0,0}, + {2203,2920,2983 ,1879,2569,2569 ,0,0,0}, {2916,2349,2960 ,2570,2008,2571 ,0,0,0}, + {2960,2956,2917 ,2571,2572,2572 ,0,0,0}, {2347,2349,2916 ,2008,2008,2570 ,0,0,0}, + {2920,2956,2983 ,2569,2572,2569 ,0,0,0}, {2956,2920,2917 ,2572,2569,2572 ,0,0,0}, + {2916,2960,2917 ,2570,2571,2572 ,0,0,0}, {2983,2202,2203 ,2569,1879,1879 ,0,0,0}, + {2181,2946,2992 ,1077,1076,1075 ,0,0,0}, {2944,2972,2945 ,1070,1069,1071 ,0,0,0}, + {2989,2990,2938 ,1072,1073,1074 ,0,0,0}, {2987,2954,2986 ,1064,1047,126 ,0,0,0}, + {2943,2942,2988 ,1068,1065,1066 ,0,0,0}, {2940,2991,2993 ,1049,1053,1050 ,0,0,0}, + {2939,2984,2941 ,1051,1052,1048 ,0,0,0}, {2933,2985,2994 ,1055,1056,1054 ,0,0,0}, + {2994,2991,2935 ,1054,1053,1058 ,0,0,0}, {2985,2934,2975 ,1056,1057,1062 ,0,0,0}, + {2934,2985,2933 ,1057,1056,1055 ,0,0,0}, {2974,2975,2937 ,1059,1062,1061 ,0,0,0}, + {2934,2937,2975 ,1057,1061,1062 ,0,0,0}, {2936,2196,2974 ,1060,21,1059 ,0,0,0}, + {2974,2937,2936 ,1059,1061,1060 ,0,0,0}, {2195,2196,2936 ,1063,21,1060 ,0,0,0}, + {2939,2940,2993 ,1051,1049,1050 ,0,0,0}, {2991,2940,2935 ,1053,1049,1058 ,0,0,0}, + {2933,2994,2935 ,1055,1054,1058 ,0,0,0}, {2939,2993,2984 ,1051,1050,1052 ,0,0,0}, + {2941,2984,2986 ,1048,1052,126 ,0,0,0}, {2954,2987,2942 ,1047,1064,1065 ,0,0,0}, + {2954,2941,2986 ,1047,1048,126 ,0,0,0}, {2943,2988,2973 ,1068,1066,1067 ,0,0,0}, + {2988,2942,2987 ,1066,1065,1064 ,0,0,0}, {2973,2972,2944 ,1067,1069,1070 ,0,0,0}, + {2973,2944,2943 ,1067,1070,1068 ,0,0,0}, {2938,2945,2989 ,1074,1071,1072 ,0,0,0}, + {2972,2989,2945 ,1069,1072,1071 ,0,0,0}, {2990,2946,2938 ,1073,1076,1074 ,0,0,0}, + {2181,2992,2176 ,1077,1075,1078 ,0,0,0}, {2946,2990,2992 ,1076,1073,1075 ,0,0,0}, + {2147,2955,2968 ,1107,1106,1105 ,0,0,0}, {2925,2959,2929 ,1102,1101,1103 ,0,0,0}, + {2970,2961,2953 ,1072,1104,1074 ,0,0,0}, {2995,2949,2967 ,1096,1079,126 ,0,0,0}, + {2924,2951,2971 ,1100,1097,1098 ,0,0,0}, {2952,2980,2982 ,1080,1084,1081 ,0,0,0}, + {2921,2996,2950 ,1082,1083,126 ,0,0,0}, {2932,2966,2965 ,1086,1087,1085 ,0,0,0}, + {2965,2980,2930 ,1085,1084,1089 ,0,0,0}, {2966,2947,2978 ,1087,1088,1094 ,0,0,0}, + {2947,2966,2932 ,1088,1087,1086 ,0,0,0}, {2979,2978,2922 ,1091,1094,1093 ,0,0,0}, + {2947,2922,2978 ,1088,1093,1094 ,0,0,0}, {2918,2162,2979 ,1092,1090,1091 ,0,0,0}, + {2979,2922,2918 ,1091,1093,1092 ,0,0,0}, {2161,2162,2918 ,1095,1090,1092 ,0,0,0}, + {2921,2952,2982 ,1082,1080,1081 ,0,0,0}, {2980,2952,2930 ,1084,1080,1089 ,0,0,0}, + {2932,2965,2930 ,1086,1085,1089 ,0,0,0}, {2921,2982,2996 ,1082,1081,1083 ,0,0,0}, + {2950,2996,2967 ,126,1083,126 ,0,0,0}, {2949,2995,2951 ,1079,1096,1097 ,0,0,0}, + {2949,2950,2967 ,1079,126,126 ,0,0,0}, {2924,2971,2969 ,1100,1098,1099 ,0,0,0}, + {2971,2951,2995 ,1098,1097,1096 ,0,0,0}, {2969,2959,2925 ,1099,1101,1102 ,0,0,0}, + {2969,2925,2924 ,1099,1102,1100 ,0,0,0}, {2953,2929,2970 ,1074,1103,1072 ,0,0,0}, + {2959,2970,2929 ,1101,1072,1103 ,0,0,0}, {2961,2955,2953 ,1104,1106,1074 ,0,0,0}, + {2147,2968,2142 ,1107,1105,324 ,0,0,0}, {2955,2961,2968 ,1106,1104,1105 ,0,0,0} +// BladeProtector2.prt + , {2997,2998,2999 ,324,2573,2574 ,0,0,0}, {3000,3001,3002 ,2575,2576,2577 ,0,0,0}, + {3003,2997,2999 ,2578,324,2574 ,0,0,0}, {3002,3001,3003 ,2577,2576,2578 ,0,0,0}, + {3001,3000,3004 ,2576,2575,2579 ,0,0,0}, {2999,3002,3003 ,2574,2577,2578 ,0,0,0}, + {3005,3006,3007 ,2580,2581,2582 ,0,0,0}, {3006,3008,3007 ,2581,2583,2582 ,0,0,0}, + {3004,3009,3005 ,2579,2584,2580 ,0,0,0}, {3006,3005,3009 ,2581,2580,2584 ,0,0,0}, + {3010,3011,3012 ,126,2585,2586 ,0,0,0}, {3013,3014,3008 ,2587,2588,2583 ,0,0,0}, + {3011,3014,3013 ,2585,2588,2587 ,0,0,0}, {3011,3013,3012 ,2585,2587,2586 ,0,0,0}, + {3012,3015,3010 ,2586,2589,126 ,0,0,0}, {3007,3008,3014 ,2582,2583,2588 ,0,0,0}, + {3004,3000,3009 ,2579,2575,2584 ,0,0,0}, {2997,3016,2998 ,324,2590,2573 ,0,0,0}, + {3017,3016,3018 ,2591,2590,2592 ,0,0,0}, {3016,3017,2998 ,2590,2591,2573 ,0,0,0}, + {3019,3020,3018 ,2593,2594,2592 ,0,0,0}, {3017,3018,3020 ,2591,2592,2594 ,0,0,0}, + {3019,3021,3022 ,2593,2595,2596 ,0,0,0}, {3022,3020,3019 ,2596,2594,2593 ,0,0,0}, + {3023,3021,3024 ,2597,2595,2598 ,0,0,0}, {3021,3023,3022 ,2595,2597,2596 ,0,0,0}, + {3025,3026,3024 ,2599,139,2598 ,0,0,0}, {3023,3024,3026 ,2597,2598,139 ,0,0,0}, + {3025,3027,3028 ,2599,2600,53 ,0,0,0}, {3028,3026,3025 ,53,139,2599 ,0,0,0}, + {3029,3027,3030 ,2601,2600,2602 ,0,0,0}, {3027,3029,3028 ,2600,2601,53 ,0,0,0}, + {3031,3032,3033 ,324,2603,324 ,0,0,0}, {3034,3035,3036 ,2604,2605,2606 ,0,0,0}, + {3037,3031,3033 ,2607,324,324 ,0,0,0}, {3036,3035,3037 ,2606,2605,2607 ,0,0,0}, + {3035,3034,3038 ,2605,2604,2608 ,0,0,0}, {3033,3036,3037 ,324,2606,2607 ,0,0,0}, + {3039,3040,3041 ,2609,2610,2611 ,0,0,0}, {3040,3042,3041 ,2610,2612,2611 ,0,0,0}, + {3038,3043,3039 ,2608,2613,2609 ,0,0,0}, {3040,3039,3043 ,2610,2609,2613 ,0,0,0}, + {3044,3045,3046 ,2614,2615,2616 ,0,0,0}, {3047,3048,3042 ,2617,2618,2612 ,0,0,0}, + {3045,3048,3047 ,2615,2618,2617 ,0,0,0}, {3045,3047,3046 ,2615,2617,2616 ,0,0,0}, + {3046,3049,3044 ,2616,2619,2614 ,0,0,0}, {3041,3042,3048 ,2611,2612,2618 ,0,0,0}, + {3038,3034,3043 ,2608,2604,2613 ,0,0,0}, {3031,3050,3032 ,324,2620,2603 ,0,0,0}, + {3051,3050,3052 ,2621,2620,2622 ,0,0,0}, {3050,3051,3032 ,2620,2621,2603 ,0,0,0}, + {3053,3054,3052 ,2623,2624,2622 ,0,0,0}, {3051,3052,3054 ,2621,2622,2624 ,0,0,0}, + {3053,3055,3056 ,2623,2625,2626 ,0,0,0}, {3056,3054,3053 ,2626,2624,2623 ,0,0,0}, + {3057,3055,3058 ,2627,2625,2598 ,0,0,0}, {3055,3057,3056 ,2625,2627,2626 ,0,0,0}, + {3059,3060,3058 ,111,139,2598 ,0,0,0}, {3057,3058,3060 ,2627,2598,139 ,0,0,0}, + {3059,3061,3062 ,111,2628,2629 ,0,0,0}, {3062,3060,3059 ,2629,139,111 ,0,0,0}, + {3063,3061,3064 ,2630,2628,82 ,0,0,0}, {3061,3063,3062 ,2628,2630,2629 ,0,0,0}, + {3065,3066,3067 ,2631,2632,2631 ,0,0,0}, {3068,3069,3070 ,2633,2634,2635 ,0,0,0}, + {3068,3067,3069 ,2633,2631,2634 ,0,0,0}, {3070,3069,3071 ,2635,2634,2635 ,0,0,0}, + {3067,3068,3065 ,2631,2633,2631 ,0,0,0}, {3072,3066,3065 ,2632,2632,2631 ,0,0,0}, + {3073,3072,3074 ,2636,2632,2636 ,0,0,0}, {3072,3073,3066 ,2632,2636,2632 ,0,0,0}, + {3075,3076,3077 ,1273,1278,1273 ,0,0,0}, {3078,3076,3079 ,1278,1278,1276 ,0,0,0}, + {3076,3078,3077 ,1278,1278,1273 ,0,0,0}, {3080,3081,3079 ,1277,1276,1276 ,0,0,0}, + {3078,3079,3081 ,1278,1276,1276 ,0,0,0}, {3080,3082,3083 ,1277,2637,1277 ,0,0,0}, + {3083,3081,3080 ,1277,1276,1277 ,0,0,0}, {3082,3084,3083 ,2637,2638,1277 ,0,0,0}, + {3085,3075,3077 ,1274,1273,1273 ,0,0,0}, {3086,3087,3085 ,1275,1274,1274 ,0,0,0}, + {3075,3085,3087 ,1273,1274,1274 ,0,0,0}, {3086,3088,3089 ,1275,1270,1275 ,0,0,0}, + {3089,3087,3086 ,1275,1274,1275 ,0,0,0}, {3090,3088,3091 ,1270,1270,2639 ,0,0,0}, + {3088,3090,3089 ,1270,1270,1275 ,0,0,0}, {3090,3091,3092 ,1270,2639,2640 ,0,0,0}, + {3093,3094,3095 ,2641,2642,2643 ,0,0,0}, {3096,3097,3093 ,2644,2645,2641 ,0,0,0}, + {3093,3095,3096 ,2641,2643,2644 ,0,0,0}, {3097,3098,3099 ,2645,2646,2647 ,0,0,0}, + {3098,3097,3096 ,2646,2645,2644 ,0,0,0}, {3100,3099,3101 ,2648,2647,2649 ,0,0,0}, + {3098,3101,3099 ,2646,2649,2647 ,0,0,0}, {3102,3103,3100 ,2650,2651,2648 ,0,0,0}, + {3100,3101,3102 ,2648,2649,2650 ,0,0,0}, {3103,3104,3105 ,2651,2652,2653 ,0,0,0}, + {3104,3103,3102 ,2652,2651,2650 ,0,0,0}, {3106,3105,3107 ,2654,2653,2655 ,0,0,0}, + {3104,3107,3105 ,2652,2655,2653 ,0,0,0}, {3108,3109,3106 ,2656,2657,2654 ,0,0,0}, + {3106,3107,3108 ,2654,2655,2656 ,0,0,0}, {3109,3110,3111 ,2657,2658,2659 ,0,0,0}, + {3110,3109,3108 ,2658,2657,2656 ,0,0,0}, {3112,3111,3113 ,2660,2659,2661 ,0,0,0}, + {3110,3113,3111 ,2658,2661,2659 ,0,0,0}, {3114,3115,3112 ,2662,2663,2660 ,0,0,0}, + {3112,3113,3114 ,2660,2661,2662 ,0,0,0}, {3115,3116,3117 ,2663,2664,2665 ,0,0,0}, + {3116,3115,3114 ,2664,2663,2662 ,0,0,0}, {3118,3117,3119 ,2666,2665,2667 ,0,0,0}, + {3116,3119,3117 ,2664,2667,2665 ,0,0,0}, {3120,3121,3118 ,2668,2669,2666 ,0,0,0}, + {3118,3119,3120 ,2666,2667,2668 ,0,0,0}, {3121,3122,3123 ,2669,2670,2671 ,0,0,0}, + {3122,3121,3120 ,2670,2669,2668 ,0,0,0}, {3124,3123,3125 ,2672,2671,2673 ,0,0,0}, + {3122,3125,3123 ,2670,2673,2671 ,0,0,0}, {3126,3127,3124 ,2674,2675,2672 ,0,0,0}, + {3124,3125,3126 ,2672,2673,2674 ,0,0,0}, {3127,3128,3129 ,2675,2676,2677 ,0,0,0}, + {3128,3127,3126 ,2676,2675,2674 ,0,0,0}, {3130,3129,3131 ,2678,2677,2679 ,0,0,0}, + {3128,3131,3129 ,2676,2679,2677 ,0,0,0}, {3132,3133,3130 ,2680,2680,2678 ,0,0,0}, + {3130,3131,3132 ,2678,2679,2680 ,0,0,0}, {3095,3094,3134 ,2643,2642,2681 ,0,0,0}, + {3135,3134,3136 ,2682,2681,2683 ,0,0,0}, {3094,3136,3134 ,2642,2683,2681 ,0,0,0}, + {3137,3138,3135 ,2684,2685,2682 ,0,0,0}, {3135,3136,3137 ,2682,2683,2684 ,0,0,0}, + {3138,3139,3140 ,2685,2686,2687 ,0,0,0}, {3139,3138,3137 ,2686,2685,2684 ,0,0,0}, + {3141,3140,3142 ,2688,2687,2689 ,0,0,0}, {3139,3142,3140 ,2686,2689,2687 ,0,0,0}, + {3143,3144,3141 ,2690,2691,2688 ,0,0,0}, {3141,3142,3143 ,2688,2689,2690 ,0,0,0}, + {3144,3145,3146 ,2691,2692,2693 ,0,0,0}, {3145,3144,3143 ,2692,2691,2690 ,0,0,0}, + {3147,3146,3148 ,2694,2693,2695 ,0,0,0}, {3145,3148,3146 ,2692,2695,2693 ,0,0,0}, + {3149,3150,3147 ,2696,2697,2694 ,0,0,0}, {3147,3148,3149 ,2694,2695,2696 ,0,0,0}, + {3150,3151,3152 ,2697,2698,2699 ,0,0,0}, {3151,3150,3149 ,2698,2697,2696 ,0,0,0}, + {3153,3152,3154 ,2700,2699,2701 ,0,0,0}, {3151,3154,3152 ,2698,2701,2699 ,0,0,0}, + {3155,3156,3153 ,2702,2703,2700 ,0,0,0}, {3153,3154,3155 ,2700,2701,2702 ,0,0,0}, + {3156,3157,3158 ,2703,2704,2705 ,0,0,0}, {3157,3156,3155 ,2704,2703,2702 ,0,0,0}, + {3159,3158,3160 ,2706,2705,2707 ,0,0,0}, {3157,3160,3158 ,2704,2707,2705 ,0,0,0}, + {3161,3162,3159 ,2708,2709,2706 ,0,0,0}, {3159,3160,3161 ,2706,2707,2708 ,0,0,0}, + {3162,3163,3164 ,2709,2710,2711 ,0,0,0}, {3163,3162,3161 ,2710,2709,2708 ,0,0,0}, + {3165,3164,3166 ,2712,2711,2713 ,0,0,0}, {3163,3166,3164 ,2710,2713,2711 ,0,0,0}, + {3167,3168,3165 ,2714,2715,2712 ,0,0,0}, {3165,3166,3167 ,2712,2713,2714 ,0,0,0}, + {3168,3169,3170 ,2715,2716,2717 ,0,0,0}, {3169,3168,3167 ,2716,2715,2714 ,0,0,0}, + {3169,3171,3170 ,2716,2718,2717 ,0,0,0}, {3170,3171,3172 ,2717,2718,2719 ,0,0,0}, + {3173,3174,3171 ,2720,2720,2721 ,0,0,0}, {3173,3175,3174 ,2720,2722,2720 ,0,0,0}, + {3175,3173,3176 ,2722,2720,2722 ,0,0,0}, {3172,3171,3174 ,82,2721,2720 ,0,0,0}, + {3177,3178,3179 ,2038,2723,2038 ,0,0,0}, {3180,3181,3178 ,2724,2725,2723 ,0,0,0}, + {3178,3181,3179 ,2723,2725,2038 ,0,0,0}, {3182,3183,3180 ,2726,2727,2724 ,0,0,0}, + {3180,3178,3182 ,2724,2723,2726 ,0,0,0}, {3183,3184,3185 ,2727,2728,2729 ,0,0,0}, + {3184,3183,3182 ,2728,2727,2726 ,0,0,0}, {3186,3185,3187 ,2730,2729,2731 ,0,0,0}, + {3184,3187,3185 ,2728,2731,2729 ,0,0,0}, {3188,3186,3189 ,2732,2730,2733 ,0,0,0}, + {3186,3187,3189 ,2730,2731,2733 ,0,0,0}, {3190,3186,3188 ,2732,2730,2732 ,0,0,0}, + {3191,3177,3179 ,2734,2038,2038 ,0,0,0}, {3192,3191,3193 ,2735,2734,2736 ,0,0,0}, + {3192,3177,3191 ,2735,2038,2734 ,0,0,0}, {3194,3193,3195 ,2737,2736,2738 ,0,0,0}, + {3191,3195,3193 ,2734,2738,2736 ,0,0,0}, {3196,3197,3194 ,2739,2740,2737 ,0,0,0}, + {3194,3195,3196 ,2737,2738,2739 ,0,0,0}, {3197,3198,3199 ,2740,2741,2742 ,0,0,0}, + {3198,3197,3196 ,2741,2740,2739 ,0,0,0}, {3199,3200,3073 ,2742,2743,2636 ,0,0,0}, + {3198,3200,3199 ,2741,2743,2742 ,0,0,0}, {3199,3073,3074 ,2742,2636,2636 ,0,0,0}, + {3201,3202,3203 ,2744,2745,2746 ,0,0,0}, {3201,3204,3205 ,2744,2747,2748 ,0,0,0}, + {3203,3202,3206 ,2746,2745,2749 ,0,0,0}, {3206,3202,3207 ,2749,2745,2750 ,0,0,0}, + {3206,3207,3208 ,2749,2750,2751 ,0,0,0}, {3209,3208,3207 ,2752,2751,2750 ,0,0,0}, + {3208,3209,3210 ,2751,2752,2753 ,0,0,0}, {3211,3210,3209 ,2754,2753,2752 ,0,0,0}, + {3211,3212,3213 ,2754,2755,2756 ,0,0,0}, {3210,3211,3213 ,2753,2754,2756 ,0,0,0}, + {3203,3204,3201 ,2746,2747,2744 ,0,0,0}, {3213,3212,3214 ,2756,2755,2757 ,0,0,0}, + {3215,3214,3216 ,2758,2757,2759 ,0,0,0}, {3216,3214,3212 ,2759,2757,2755 ,0,0,0}, + {3215,3216,3217 ,2758,2759,2758 ,0,0,0}, {3218,3205,3219 ,2760,2748,2761 ,0,0,0}, + {3204,3219,3205 ,2747,2761,2748 ,0,0,0}, {3220,3221,3218 ,2762,2763,2760 ,0,0,0}, + {3218,3219,3220 ,2760,2761,2762 ,0,0,0}, {3221,3222,3223 ,2763,2764,2765 ,0,0,0}, + {3222,3221,3220 ,2764,2763,2762 ,0,0,0}, {3224,3223,3225 ,2766,2765,2767 ,0,0,0}, + {3222,3225,3223 ,2764,2767,2765 ,0,0,0}, {3226,3227,3224 ,2768,2769,2766 ,0,0,0}, + {3224,3225,3226 ,2766,2767,2768 ,0,0,0}, {3227,3228,3229 ,2769,2770,2771 ,0,0,0}, + {3228,3227,3226 ,2770,2769,2768 ,0,0,0}, {3230,3229,3231 ,2772,2771,2773 ,0,0,0}, + {3228,3231,3229 ,2770,2773,2771 ,0,0,0}, {3230,3231,3232 ,2772,2773,2772 ,0,0,0}, + {3233,3234,3235 ,2774,2775,2774 ,0,0,0}, {3235,3236,3233 ,2774,2776,2774 ,0,0,0}, + {3237,3238,3234 ,2775,2777,2775 ,0,0,0}, {3239,3236,3235 ,2776,2776,2774 ,0,0,0}, + {3233,3237,3234 ,2774,2775,2775 ,0,0,0}, {3237,3240,3238 ,2775,2777,2777 ,0,0,0}, + {3241,3240,3242 ,2778,2777,2778 ,0,0,0}, {3242,3230,3232 ,2778,2772,2772 ,0,0,0}, + {3241,3238,3240 ,2778,2777,2777 ,0,0,0}, {3242,3232,3241 ,2778,2772,2778 ,0,0,0}, + {3243,3239,3244 ,2779,2776,2779 ,0,0,0}, {3239,3243,3236 ,2776,2779,2776 ,0,0,0}, + {3245,3246,3244 ,2780,2780,2779 ,0,0,0}, {3243,3244,3246 ,2779,2779,2780 ,0,0,0}, + {3245,3247,3248 ,2780,2781,2781 ,0,0,0}, {3248,3246,3245 ,2781,2780,2780 ,0,0,0}, + {3249,3247,3250 ,2782,2781,2782 ,0,0,0}, {3247,3249,3248 ,2781,2782,2781 ,0,0,0}, + {3249,3250,3091 ,2782,2782,2783 ,0,0,0}, {3091,3250,3092 ,2783,2782,2784 ,0,0,0}, + {3251,3084,3082 ,1888,2785,2786 ,0,0,0}, {3252,3253,3254 ,1207,1886,1886 ,0,0,0}, + {3255,3256,3257 ,1887,1887,1888 ,0,0,0}, {3258,3259,3260 ,1882,1882,1883 ,0,0,0}, + {3261,3262,3263 ,1207,1881,1881 ,0,0,0}, {3264,3265,3260 ,2787,1883,1883 ,0,0,0}, + {3258,3260,3265 ,1882,1883,1883 ,0,0,0}, {3266,3265,3264 ,2788,1883,2787 ,0,0,0}, + {3262,3259,3263 ,1881,1882,1881 ,0,0,0}, {3263,3259,3258 ,1881,1882,1882 ,0,0,0}, + {3261,3253,3252 ,1207,1886,1207 ,0,0,0}, {3261,3252,3262 ,1207,1207,1881 ,0,0,0}, + {3254,3256,3255 ,1886,1887,1887 ,0,0,0}, {3253,3256,3254 ,1886,1887,1886 ,0,0,0}, + {3251,3257,3084 ,1888,1888,2785 ,0,0,0}, {3255,3257,3251 ,1887,1888,1888 ,0,0,0}, + {3267,3268,3269 ,2789,2789,2790 ,0,0,0}, {3269,3268,3270 ,2790,2789,2790 ,0,0,0}, + {3268,3267,3271 ,2789,2789,2791 ,0,0,0}, {3272,3271,3267 ,2792,2791,2789 ,0,0,0}, + {3273,3274,3272 ,2793,2793,2792 ,0,0,0}, {3275,3269,3270 ,2794,2790,2790 ,0,0,0}, + {3266,3264,3273 ,2795,2796,2793 ,0,0,0}, {3274,3273,3264 ,2793,2793,2796 ,0,0,0}, + {3272,3274,3271 ,2792,2793,2791 ,0,0,0}, {3276,3275,3277 ,2797,2794,2794 ,0,0,0}, + {3270,3277,3275 ,2790,2794,2794 ,0,0,0}, {3278,3279,3276 ,2797,2798,2797 ,0,0,0}, + {3276,3277,3278 ,2797,2794,2797 ,0,0,0}, {3279,3280,3281 ,2798,2798,2799 ,0,0,0}, + {3280,3279,3278 ,2798,2798,2797 ,0,0,0}, {3282,3281,3283 ,2800,2799,2799 ,0,0,0}, + {3280,3283,3281 ,2798,2799,2799 ,0,0,0}, {3282,3283,3284 ,2800,2799,2800 ,0,0,0}, + {3285,3286,3287 ,2801,2801,2802 ,0,0,0}, {3288,3289,3287 ,2803,2804,2802 ,0,0,0}, + {3285,3287,3289 ,2801,2802,2804 ,0,0,0}, {3288,3290,3291 ,2803,2805,2806 ,0,0,0}, + {3291,3289,3288 ,2806,2804,2803 ,0,0,0}, {3292,3290,3293 ,2807,2805,2808 ,0,0,0}, + {3290,3292,3291 ,2805,2807,2806 ,0,0,0}, {3294,3295,3293 ,2809,2810,2808 ,0,0,0}, + {3292,3293,3295 ,2807,2808,2810 ,0,0,0}, {3294,3296,3297 ,2809,2811,2812 ,0,0,0}, + {3297,3295,3294 ,2812,2810,2809 ,0,0,0}, {3298,3296,3299 ,2813,2811,2814 ,0,0,0}, + {3296,3298,3297 ,2811,2813,2812 ,0,0,0}, {3300,3301,3299 ,2815,2816,2814 ,0,0,0}, + {3298,3299,3301 ,2813,2814,2816 ,0,0,0}, {3300,3302,3303 ,2815,2817,2818 ,0,0,0}, + {3303,3301,3300 ,2818,2816,2815 ,0,0,0}, {3304,3302,3305 ,2819,2817,2820 ,0,0,0}, + {3302,3304,3303 ,2817,2819,2818 ,0,0,0}, {3306,3307,3305 ,2821,2822,2820 ,0,0,0}, + {3304,3305,3307 ,2819,2820,2822 ,0,0,0}, {3306,3308,3309 ,2821,2823,2824 ,0,0,0}, + {3309,3307,3306 ,2824,2822,2821 ,0,0,0}, {3310,3308,3311 ,2825,2823,2826 ,0,0,0}, + {3308,3310,3309 ,2823,2825,2824 ,0,0,0}, {3312,3313,3311 ,2827,2828,2826 ,0,0,0}, + {3310,3311,3313 ,2825,2826,2828 ,0,0,0}, {3312,3314,3315 ,2827,2829,2830 ,0,0,0}, + {3315,3313,3312 ,2830,2828,2827 ,0,0,0}, {3316,3314,3317 ,2831,2829,2832 ,0,0,0}, + {3314,3316,3315 ,2829,2831,2830 ,0,0,0}, {3282,3318,3317 ,2800,2833,2832 ,0,0,0}, + {3316,3317,3318 ,2831,2832,2833 ,0,0,0}, {3284,3318,3282 ,2800,2833,2800 ,0,0,0}, + {3319,3286,3285 ,2834,2801,2801 ,0,0,0}, {3320,3319,3321 ,2835,2834,2836 ,0,0,0}, + {3319,3320,3286 ,2834,2835,2801 ,0,0,0}, {3322,3323,3321 ,2837,2838,2836 ,0,0,0}, + {3320,3321,3323 ,2835,2836,2838 ,0,0,0}, {3322,3324,3325 ,2837,2839,2840 ,0,0,0}, + {3325,3323,3322 ,2840,2838,2837 ,0,0,0}, {3326,3324,3327 ,2841,2839,2842 ,0,0,0}, + {3324,3326,3325 ,2839,2841,2840 ,0,0,0}, {3328,3329,3327 ,2843,2844,2842 ,0,0,0}, + {3326,3327,3329 ,2841,2842,2844 ,0,0,0}, {3328,3330,3331 ,2843,2845,2846 ,0,0,0}, + {3331,3329,3328 ,2846,2844,2843 ,0,0,0}, {3332,3330,3333 ,2847,2845,2848 ,0,0,0}, + {3330,3332,3331 ,2845,2847,2846 ,0,0,0}, {3334,3335,3333 ,2849,2850,2848 ,0,0,0}, + {3332,3333,3335 ,2847,2848,2850 ,0,0,0}, {3334,3336,3337 ,2849,2851,2852 ,0,0,0}, + {3337,3335,3334 ,2852,2850,2849 ,0,0,0}, {3338,3336,3339 ,2853,2851,2854 ,0,0,0}, + {3336,3338,3337 ,2851,2853,2852 ,0,0,0}, {3340,3341,3339 ,2855,2856,2854 ,0,0,0}, + {3338,3339,3341 ,2853,2854,2856 ,0,0,0}, {3340,3342,3343 ,2855,2857,2858 ,0,0,0}, + {3343,3341,3340 ,2858,2856,2855 ,0,0,0}, {3344,3342,3345 ,2859,2857,2860 ,0,0,0}, + {3342,3344,3343 ,2857,2859,2858 ,0,0,0}, {3346,3347,3345 ,2861,2862,2860 ,0,0,0}, + {3344,3345,3347 ,2859,2860,2862 ,0,0,0}, {3346,3348,3349 ,2861,2863,2864 ,0,0,0}, + {3349,3347,3346 ,2864,2862,2861 ,0,0,0}, {3350,3348,3351 ,2865,2863,2866 ,0,0,0}, + {3348,3350,3349 ,2863,2865,2864 ,0,0,0}, {3350,3351,3352 ,2865,2866,2866 ,0,0,0}, + {3353,3351,3354 ,2162,2867,2162 ,0,0,0}, {3351,3353,3352 ,2867,2162,2867 ,0,0,0}, + {3355,3356,3357 ,2868,2869,2870 ,0,0,0}, {3358,3359,3360 ,2871,2872,2873 ,0,0,0}, + {3361,3355,3357 ,2874,2868,2870 ,0,0,0}, {3359,3357,3356 ,2872,2870,2869 ,0,0,0}, + {3362,3355,3361 ,2875,2868,2874 ,0,0,0}, {3363,3364,3365 ,2876,2877,2878 ,0,0,0}, + {3362,3361,3363 ,2875,2874,2876 ,0,0,0}, {3366,3364,3367 ,2879,2877,2880 ,0,0,0}, + {3363,3365,3362 ,2876,2878,2875 ,0,0,0}, {3364,3366,3365 ,2877,2879,2878 ,0,0,0}, + {3367,3368,3369 ,2880,2881,2882 ,0,0,0}, {3356,3360,3359 ,2869,2873,2872 ,0,0,0}, + {3370,3371,3372 ,2883,2884,2885 ,0,0,0}, {3373,3369,3368 ,2886,2882,2881 ,0,0,0}, + {3373,3374,3375 ,2886,2887,2888 ,0,0,0}, {3370,3372,3375 ,2883,2885,2888 ,0,0,0}, + {3370,3375,3374 ,2883,2888,2887 ,0,0,0}, {3372,3371,3376 ,2885,2884,2889 ,0,0,0}, + {3377,3378,3379 ,2890,2891,2892 ,0,0,0}, {3376,3377,3379 ,2889,2890,2892 ,0,0,0}, + {3377,3376,3371 ,2890,2889,2884 ,0,0,0}, {3378,3380,3379 ,2891,2893,2892 ,0,0,0}, + {3374,3373,3368 ,2887,2886,2881 ,0,0,0}, {3380,3381,3382 ,2893,2894,2895 ,0,0,0}, + {3380,3378,3381 ,2893,2891,2894 ,0,0,0}, {3383,3384,3385 ,2896,2897,2898 ,0,0,0}, + {3386,3385,3384 ,2899,2898,2897 ,0,0,0}, {3386,3387,3385 ,2899,2900,2898 ,0,0,0}, + {3387,3382,3381 ,2900,2895,2894 ,0,0,0}, {3387,3386,3382 ,2900,2899,2895 ,0,0,0}, + {3369,3366,3367 ,2882,2879,2880 ,0,0,0}, {3388,3389,3383 ,2901,2902,2896 ,0,0,0}, + {3390,3391,3388 ,2903,2904,2901 ,0,0,0}, {3354,3391,3390 ,1359,2904,2903 ,0,0,0}, + {3384,3383,3389 ,2897,2896,2902 ,0,0,0}, {3391,3389,3388 ,2904,2902,2901 ,0,0,0}, + {3353,3354,3390 ,1359,1359,2903 ,0,0,0}, {3392,3393,3358 ,2905,2906,2871 ,0,0,0}, + {3358,3360,3392 ,2871,2873,2905 ,0,0,0}, {3393,3394,3395 ,2906,2907,2908 ,0,0,0}, + {3394,3393,3392 ,2907,2906,2905 ,0,0,0}, {3396,3395,3397 ,2909,2908,2910 ,0,0,0}, + {3394,3397,3395 ,2907,2910,2908 ,0,0,0}, {3398,3399,3396 ,2911,2912,2909 ,0,0,0}, + {3396,3397,3398 ,2909,2910,2911 ,0,0,0}, {3399,3400,3401 ,2912,2913,2914 ,0,0,0}, + {3400,3399,3398 ,2913,2912,2911 ,0,0,0}, {3402,3401,3403 ,2915,2914,2916 ,0,0,0}, + {3400,3403,3401 ,2913,2916,2914 ,0,0,0}, {3404,3405,3402 ,2917,2918,2915 ,0,0,0}, + {3402,3403,3404 ,2915,2916,2917 ,0,0,0}, {3405,3406,3407 ,2918,2919,2920 ,0,0,0}, + {3406,3405,3404 ,2919,2918,2917 ,0,0,0}, {3408,3407,3409 ,2921,2920,2922 ,0,0,0}, + {3406,3409,3407 ,2919,2922,2920 ,0,0,0}, {3410,3411,3408 ,2923,2924,2921 ,0,0,0}, + {3408,3409,3410 ,2921,2922,2923 ,0,0,0}, {3411,3412,3413 ,2924,2925,2926 ,0,0,0}, + {3412,3411,3410 ,2925,2924,2923 ,0,0,0}, {3414,3413,3415 ,2927,2926,2928 ,0,0,0}, + {3412,3415,3413 ,2925,2928,2926 ,0,0,0}, {3416,3417,3414 ,2929,2930,2927 ,0,0,0}, + {3414,3415,3416 ,2927,2928,2929 ,0,0,0}, {3417,3418,3419 ,2930,2931,2932 ,0,0,0}, + {3418,3417,3416 ,2931,2930,2929 ,0,0,0}, {3420,3419,3421 ,2933,2932,2934 ,0,0,0}, + {3418,3421,3419 ,2931,2934,2932 ,0,0,0}, {3422,3423,3420 ,2935,2936,2933 ,0,0,0}, + {3420,3421,3422 ,2933,2934,2935 ,0,0,0}, {3423,3424,3425 ,2936,2937,2938 ,0,0,0}, + {3424,3423,3422 ,2937,2936,2935 ,0,0,0}, {3426,3425,3427 ,1711,2938,2939 ,0,0,0}, + {3424,3427,3425 ,2937,2939,2938 ,0,0,0}, {3426,3427,3428 ,1711,2939,1711 ,0,0,0}, + {3429,3430,3431 ,1398,1398,1398 ,0,0,0}, {3430,3429,3432 ,1398,1398,1398 ,0,0,0}, + {3433,3434,3435 ,2940,2941,2942 ,0,0,0}, {3436,3437,3438 ,2943,2944,2945 ,0,0,0}, + {3434,3439,3435 ,2941,2946,2942 ,0,0,0}, {3433,3435,3440 ,2940,2942,2947 ,0,0,0}, + {3436,3433,3440 ,2943,2940,2947 ,0,0,0}, {3441,3442,3439 ,2948,2949,2946 ,0,0,0}, + {3441,3439,3434 ,2948,2946,2941 ,0,0,0}, {3443,3444,3445 ,2950,2951,2952 ,0,0,0}, + {3442,3441,3443 ,2949,2948,2950 ,0,0,0}, {3443,3445,3442 ,2950,2952,2949 ,0,0,0}, + {3444,3446,3445 ,2951,2953,2952 ,0,0,0}, {3437,3436,3440 ,2944,2943,2947 ,0,0,0}, + {3444,3447,3446 ,2951,2954,2953 ,0,0,0}, {3448,3449,3450 ,2955,2956,2957 ,0,0,0}, + {3448,3450,3447 ,2955,2957,2954 ,0,0,0}, {3449,3448,3451 ,2956,2955,2958 ,0,0,0}, + {3452,3453,3451 ,2959,2960,2958 ,0,0,0}, {3453,3449,3451 ,2960,2956,2958 ,0,0,0}, + {3454,3455,3456 ,2961,2962,2963 ,0,0,0}, {3453,3452,3457 ,2960,2959,2964 ,0,0,0}, + {3458,3459,3457 ,2965,2966,2964 ,0,0,0}, {3455,3454,3459 ,2962,2961,2966 ,0,0,0}, + {3455,3459,3458 ,2962,2966,2965 ,0,0,0}, {3454,3456,3460 ,2961,2963,2967 ,0,0,0}, + {3452,3458,3457 ,2959,2965,2964 ,0,0,0}, {3461,3460,3462 ,2968,2967,2969 ,0,0,0}, + {3461,3462,3463 ,2968,2969,2970 ,0,0,0}, {3462,3460,3456 ,2969,2967,2963 ,0,0,0}, + {3464,3465,3466 ,2971,2972,2973 ,0,0,0}, {3450,3446,3447 ,2957,2953,2954 ,0,0,0}, + {3464,3467,3463 ,2971,2974,2970 ,0,0,0}, {3467,3464,3466 ,2974,2971,2973 ,0,0,0}, + {3465,3468,3469 ,2972,2975,2976 ,0,0,0}, {3469,3466,3465 ,2976,2973,2972 ,0,0,0}, + {3470,3471,3468 ,2977,2978,2975 ,0,0,0}, {3469,3468,3471 ,2976,2975,2978 ,0,0,0}, + {3470,3432,3429 ,2977,2979,2979 ,0,0,0}, {3470,3429,3471 ,2977,2979,2978 ,0,0,0}, + {3463,3467,3461 ,2970,2974,2968 ,0,0,0}, {3472,3438,3473 ,2980,2945,2981 ,0,0,0}, + {3437,3473,3438 ,2944,2981,2945 ,0,0,0}, {3474,3475,3472 ,2982,2983,2980 ,0,0,0}, + {3472,3473,3474 ,2980,2981,2982 ,0,0,0}, {3475,3476,3477 ,2983,2984,2985 ,0,0,0}, + {3476,3475,3474 ,2984,2983,2982 ,0,0,0}, {3478,3477,3479 ,2986,2985,2987 ,0,0,0}, + {3476,3479,3477 ,2984,2987,2985 ,0,0,0}, {3480,3481,3478 ,2988,2989,2986 ,0,0,0}, + {3478,3479,3480 ,2986,2987,2988 ,0,0,0}, {3481,3482,3483 ,2989,2990,2991 ,0,0,0}, + {3482,3481,3480 ,2990,2989,2988 ,0,0,0}, {3484,3483,3485 ,2992,2991,2993 ,0,0,0}, + {3482,3485,3483 ,2990,2993,2991 ,0,0,0}, {3486,3487,3484 ,2994,2995,2992 ,0,0,0}, + {3484,3485,3486 ,2992,2993,2994 ,0,0,0}, {3487,3488,3489 ,2995,2996,2997 ,0,0,0}, + {3488,3487,3486 ,2996,2995,2994 ,0,0,0}, {3490,3489,3491 ,2998,2997,2999 ,0,0,0}, + {3488,3491,3489 ,2996,2999,2997 ,0,0,0}, {3492,3493,3490 ,3000,3001,2998 ,0,0,0}, + {3490,3491,3492 ,2998,2999,3000 ,0,0,0}, {3493,3494,3495 ,3001,3002,3003 ,0,0,0}, + {3494,3493,3492 ,3002,3001,3000 ,0,0,0}, {3496,3495,3497 ,3004,3003,3005 ,0,0,0}, + {3494,3497,3495 ,3002,3005,3003 ,0,0,0}, {3498,3499,3496 ,3006,3007,3004 ,0,0,0}, + {3496,3497,3498 ,3004,3005,3006 ,0,0,0}, {3499,3500,3501 ,3007,3008,3009 ,0,0,0}, + {3500,3499,3498 ,3008,3007,3006 ,0,0,0}, {3502,3501,3503 ,3010,3009,3011 ,0,0,0}, + {3500,3503,3501 ,3008,3011,3009 ,0,0,0}, {3504,3505,3502 ,3012,3013,3010 ,0,0,0}, + {3502,3503,3504 ,3010,3011,3012 ,0,0,0}, {3505,3506,3507 ,3013,3014,3015 ,0,0,0}, + {3506,3505,3504 ,3014,3013,3012 ,0,0,0}, {3508,3507,3509 ,3016,3015,3017 ,0,0,0}, + {3506,3509,3507 ,3014,3017,3015 ,0,0,0}, {3508,3509,3510 ,3016,3017,3018 ,0,0,0}, + {3511,3512,3513 ,3019,3020,3021 ,0,0,0}, {3514,3515,3513 ,3022,3023,3021 ,0,0,0}, + {3511,3513,3515 ,3019,3021,3023 ,0,0,0}, {3514,3516,3517 ,3022,3024,3025 ,0,0,0}, + {3517,3515,3514 ,3025,3023,3022 ,0,0,0}, {3518,3516,3519 ,3026,3024,3027 ,0,0,0}, + {3516,3518,3517 ,3024,3026,3025 ,0,0,0}, {3520,3521,3519 ,3028,3029,3027 ,0,0,0}, + {3518,3519,3521 ,3026,3027,3029 ,0,0,0}, {3520,3522,3523 ,3028,3030,3031 ,0,0,0}, + {3523,3521,3520 ,3031,3029,3028 ,0,0,0}, {3524,3522,3525 ,3032,3030,3033 ,0,0,0}, + {3522,3524,3523 ,3030,3032,3031 ,0,0,0}, {3526,3527,3525 ,3034,3035,3033 ,0,0,0}, + {3524,3525,3527 ,3032,3033,3035 ,0,0,0}, {3526,3528,3529 ,3034,3036,3037 ,0,0,0}, + {3529,3527,3526 ,3037,3035,3034 ,0,0,0}, {3530,3528,3531 ,3038,3036,3039 ,0,0,0}, + {3528,3530,3529 ,3036,3038,3037 ,0,0,0}, {3532,3533,3531 ,3040,3041,3039 ,0,0,0}, + {3530,3531,3533 ,3038,3039,3041 ,0,0,0}, {3532,3534,3535 ,3040,3042,3043 ,0,0,0}, + {3535,3533,3532 ,3043,3041,3040 ,0,0,0}, {3536,3534,3537 ,3044,3042,3045 ,0,0,0}, + {3534,3536,3535 ,3042,3044,3043 ,0,0,0}, {3538,3539,3537 ,3046,3047,3045 ,0,0,0}, + {3536,3537,3539 ,3044,3045,3047 ,0,0,0}, {3538,3540,3541 ,3046,3048,3049 ,0,0,0}, + {3541,3539,3538 ,3049,3047,3046 ,0,0,0}, {3542,3540,3543 ,3050,3048,3051 ,0,0,0}, + {3540,3542,3541 ,3048,3050,3049 ,0,0,0}, {3544,3545,3543 ,3052,3053,3051 ,0,0,0}, + {3542,3543,3545 ,3050,3051,3053 ,0,0,0}, {3544,3546,3547 ,3052,3054,3055 ,0,0,0}, + {3547,3545,3544 ,3055,3053,3052 ,0,0,0}, {3548,3546,3549 ,3056,3054,3057 ,0,0,0}, + {3546,3548,3547 ,3054,3056,3055 ,0,0,0}, {3550,3551,3549 ,3058,3059,3057 ,0,0,0}, + {3548,3549,3551 ,3056,3057,3059 ,0,0,0}, {3550,3552,3553 ,3058,3060,3061 ,0,0,0}, + {3553,3551,3550 ,3061,3059,3058 ,0,0,0}, {3554,3552,3555 ,3062,3060,3063 ,0,0,0}, + {3552,3554,3553 ,3060,3062,3061 ,0,0,0}, {3556,3557,3555 ,3064,3065,3063 ,0,0,0}, + {3554,3555,3557 ,3062,3063,3065 ,0,0,0}, {3556,3558,3559 ,3064,3066,3067 ,0,0,0}, + {3559,3557,3556 ,3067,3065,3064 ,0,0,0}, {3560,3558,3561 ,3068,3066,3069 ,0,0,0}, + {3558,3560,3559 ,3066,3068,3067 ,0,0,0}, {3562,3563,3561 ,3070,3071,3069 ,0,0,0}, + {3560,3561,3563 ,3068,3069,3071 ,0,0,0}, {3562,3564,3565 ,3070,3072,3073 ,0,0,0}, + {3565,3563,3562 ,3073,3071,3070 ,0,0,0}, {3566,3564,3567 ,3074,3072,3075 ,0,0,0}, + {3564,3566,3565 ,3072,3074,3073 ,0,0,0}, {3508,3568,3567 ,3076,3077,3075 ,0,0,0}, + {3566,3567,3568 ,3074,3075,3077 ,0,0,0}, {3510,3568,3508 ,3078,3077,3076 ,0,0,0}, + {3569,3512,3511 ,3079,3020,3019 ,0,0,0}, {3570,3569,3571 ,3080,3079,3081 ,0,0,0}, + {3569,3570,3512 ,3079,3080,3020 ,0,0,0}, {3572,3573,3571 ,3082,3083,3081 ,0,0,0}, + {3570,3571,3573 ,3080,3081,3083 ,0,0,0}, {3572,3574,3575 ,3082,3084,3085 ,0,0,0}, + {3575,3573,3572 ,3085,3083,3082 ,0,0,0}, {3576,3574,3577 ,3086,3084,3087 ,0,0,0}, + {3574,3576,3575 ,3084,3086,3085 ,0,0,0}, {3578,3579,3577 ,3088,3089,3087 ,0,0,0}, + {3576,3577,3579 ,3086,3087,3089 ,0,0,0}, {3578,3580,3581 ,3088,3090,3091 ,0,0,0}, + {3581,3579,3578 ,3091,3089,3088 ,0,0,0}, {3582,3580,3583 ,3092,3090,3093 ,0,0,0}, + {3580,3582,3581 ,3090,3092,3091 ,0,0,0}, {3584,3585,3583 ,3094,3095,3093 ,0,0,0}, + {3582,3583,3585 ,3092,3093,3095 ,0,0,0}, {3584,3586,3587 ,3094,3096,3097 ,0,0,0}, + {3587,3585,3584 ,3097,3095,3094 ,0,0,0}, {3588,3586,3589 ,3098,3096,3099 ,0,0,0}, + {3586,3588,3587 ,3096,3098,3097 ,0,0,0}, {3590,3591,3589 ,3100,3101,3099 ,0,0,0}, + {3588,3589,3591 ,3098,3099,3101 ,0,0,0}, {3590,3592,3593 ,3100,3102,3103 ,0,0,0}, + {3593,3591,3590 ,3103,3101,3100 ,0,0,0}, {3594,3592,3595 ,3104,3102,3105 ,0,0,0}, + {3592,3594,3593 ,3102,3104,3103 ,0,0,0}, {3596,3597,3595 ,3106,3107,3105 ,0,0,0}, + {3594,3595,3597 ,3104,3105,3107 ,0,0,0}, {3596,3598,3599 ,3106,3108,3109 ,0,0,0}, + {3599,3597,3596 ,3109,3107,3106 ,0,0,0}, {3600,3598,3601 ,3110,3108,3111 ,0,0,0}, + {3598,3600,3599 ,3108,3110,3109 ,0,0,0}, {3602,3603,3601 ,3112,3113,3111 ,0,0,0}, + {3600,3601,3603 ,3110,3111,3113 ,0,0,0}, {3602,3604,3605 ,3112,3114,3115 ,0,0,0}, + {3605,3603,3602 ,3115,3113,3112 ,0,0,0}, {3606,3604,3607 ,3116,3114,3117 ,0,0,0}, + {3604,3606,3605 ,3114,3116,3115 ,0,0,0}, {3608,3609,3607 ,3118,3119,3117 ,0,0,0}, + {3606,3607,3609 ,3116,3117,3119 ,0,0,0}, {3608,3610,3611 ,3118,3120,3121 ,0,0,0}, + {3611,3609,3608 ,3121,3119,3118 ,0,0,0}, {3612,3610,3613 ,3122,3120,3123 ,0,0,0}, + {3610,3612,3611 ,3120,3122,3121 ,0,0,0}, {3614,3615,3613 ,3124,3125,3123 ,0,0,0}, + {3612,3613,3615 ,3122,3123,3125 ,0,0,0}, {3614,3616,3617 ,3124,3126,3127 ,0,0,0}, + {3617,3615,3614 ,3127,3125,3124 ,0,0,0}, {3618,3616,3619 ,3128,3126,3129 ,0,0,0}, + {3616,3618,3617 ,3126,3128,3127 ,0,0,0}, {3620,3621,3619 ,3130,3131,3129 ,0,0,0}, + {3618,3619,3621 ,3128,3129,3131 ,0,0,0}, {3620,3622,3623 ,3130,3132,3133 ,0,0,0}, + {3623,3621,3620 ,3133,3131,3130 ,0,0,0}, {3624,3622,3625 ,3134,3132,126 ,0,0,0}, + {3622,3624,3623 ,3132,3134,3133 ,0,0,0}, {3624,3625,3626 ,3134,126,3135 ,0,0,0}, + {3627,3628,3629 ,3136,3137,3138 ,0,0,0}, {3630,3631,3632 ,3139,3140,3141 ,0,0,0}, + {3628,3633,3629 ,3137,3142,3138 ,0,0,0}, {3627,3629,3634 ,3136,3138,3143 ,0,0,0}, + {3630,3627,3634 ,3139,3136,3143 ,0,0,0}, {3635,3636,3633 ,3144,3145,3142 ,0,0,0}, + {3635,3633,3628 ,3144,3142,3137 ,0,0,0}, {3637,3638,3639 ,3146,3147,3148 ,0,0,0}, + {3636,3635,3637 ,3145,3144,3146 ,0,0,0}, {3637,3639,3636 ,3146,3148,3145 ,0,0,0}, + {3638,3640,3639 ,3147,3149,3148 ,0,0,0}, {3631,3630,3634 ,3140,3139,3143 ,0,0,0}, + {3638,3641,3640 ,3147,3150,3149 ,0,0,0}, {3642,3643,3644 ,3151,3152,3153 ,0,0,0}, + {3642,3644,3641 ,3151,3153,3150 ,0,0,0}, {3643,3642,3645 ,3152,3151,3154 ,0,0,0}, + {3646,3647,3645 ,3155,3156,3154 ,0,0,0}, {3647,3643,3645 ,3156,3152,3154 ,0,0,0}, + {3648,3649,3650 ,3157,3158,3159 ,0,0,0}, {3647,3646,3651 ,3156,3155,3160 ,0,0,0}, + {3652,3653,3651 ,3161,3162,3160 ,0,0,0}, {3649,3648,3653 ,3158,3157,3162 ,0,0,0}, + {3649,3653,3652 ,3158,3162,3161 ,0,0,0}, {3648,3650,3654 ,3157,3159,3163 ,0,0,0}, + {3646,3652,3651 ,3155,3161,3160 ,0,0,0}, {3655,3654,3656 ,3164,3163,3165 ,0,0,0}, + {3655,3656,3657 ,3164,3165,3166 ,0,0,0}, {3656,3654,3650 ,3165,3163,3159 ,0,0,0}, + {3658,3659,3660 ,3167,3168,3169 ,0,0,0}, {3644,3640,3641 ,3153,3149,3150 ,0,0,0}, + {3658,3661,3657 ,3167,3170,3166 ,0,0,0}, {3661,3658,3660 ,3170,3167,3169 ,0,0,0}, + {3659,3662,3663 ,3168,3171,3172 ,0,0,0}, {3663,3660,3659 ,3172,3169,3168 ,0,0,0}, + {3664,3665,3662 ,3173,3174,3171 ,0,0,0}, {3663,3662,3665 ,3172,3171,3174 ,0,0,0}, + {3664,3626,3625 ,3173,3175,3176 ,0,0,0}, {3664,3625,3665 ,3173,3176,3174 ,0,0,0}, + {3657,3661,3655 ,3166,3170,3164 ,0,0,0}, {3666,3632,3667 ,3177,3141,3178 ,0,0,0}, + {3631,3667,3632 ,3140,3178,3141 ,0,0,0}, {3668,3669,3666 ,3179,3180,3177 ,0,0,0}, + {3666,3667,3668 ,3177,3178,3179 ,0,0,0}, {3669,3670,3671 ,3180,3181,3182 ,0,0,0}, + {3670,3669,3668 ,3181,3180,3179 ,0,0,0}, {3672,3671,3673 ,3183,3182,3184 ,0,0,0}, + {3670,3673,3671 ,3181,3184,3182 ,0,0,0}, {3674,3675,3672 ,3185,3186,3183 ,0,0,0}, + {3672,3673,3674 ,3183,3184,3185 ,0,0,0}, {3675,3676,3677 ,3186,3187,3188 ,0,0,0}, + {3676,3675,3674 ,3187,3186,3185 ,0,0,0}, {3678,3677,3679 ,3189,3188,3190 ,0,0,0}, + {3676,3679,3677 ,3187,3190,3188 ,0,0,0}, {3680,3681,3678 ,3191,3192,3189 ,0,0,0}, + {3678,3679,3680 ,3189,3190,3191 ,0,0,0}, {3681,3682,3683 ,3192,3193,3194 ,0,0,0}, + {3682,3681,3680 ,3193,3192,3191 ,0,0,0}, {3684,3683,3685 ,3195,3194,3196 ,0,0,0}, + {3682,3685,3683 ,3193,3196,3194 ,0,0,0}, {3686,3687,3684 ,3197,3198,3195 ,0,0,0}, + {3684,3685,3686 ,3195,3196,3197 ,0,0,0}, {3687,3688,3689 ,3198,3199,3200 ,0,0,0}, + {3688,3687,3686 ,3199,3198,3197 ,0,0,0}, {3690,3689,3691 ,3201,3200,3202 ,0,0,0}, + {3688,3691,3689 ,3199,3202,3200 ,0,0,0}, {3692,3693,3690 ,3203,3204,3201 ,0,0,0}, + {3690,3691,3692 ,3201,3202,3203 ,0,0,0}, {3693,3694,3695 ,3204,3205,3206 ,0,0,0}, + {3694,3693,3692 ,3205,3204,3203 ,0,0,0}, {3696,3695,3697 ,3207,3206,3208 ,0,0,0}, + {3694,3697,3695 ,3205,3208,3206 ,0,0,0}, {3698,3699,3696 ,3209,3210,3207 ,0,0,0}, + {3696,3697,3698 ,3207,3208,3209 ,0,0,0}, {3699,3700,3701 ,3210,3211,3212 ,0,0,0}, + {3700,3699,3698 ,3211,3210,3209 ,0,0,0}, {3702,3701,3703 ,3213,3212,3214 ,0,0,0}, + {3700,3703,3701 ,3211,3214,3212 ,0,0,0}, {3702,3703,3704 ,3213,3214,3213 ,0,0,0}, + {3705,3702,3704 ,2197,2197,2197 ,0,0,0}, {3702,3705,3706 ,2197,2197,2197 ,0,0,0}, + {3707,3708,3709 ,3215,3216,3217 ,0,0,0}, {3710,3711,3707 ,3218,3219,3215 ,0,0,0}, + {3707,3709,3710 ,3215,3217,3218 ,0,0,0}, {3711,3712,3713 ,3219,3220,3221 ,0,0,0}, + {3712,3711,3710 ,3220,3219,3218 ,0,0,0}, {3714,3713,3715 ,3222,3221,3223 ,0,0,0}, + {3712,3715,3713 ,3220,3223,3221 ,0,0,0}, {3716,3717,3714 ,3224,3225,3222 ,0,0,0}, + {3714,3715,3716 ,3222,3223,3224 ,0,0,0}, {3717,3718,3719 ,3225,3226,3227 ,0,0,0}, + {3718,3717,3716 ,3226,3225,3224 ,0,0,0}, {3720,3719,3721 ,3228,3227,3229 ,0,0,0}, + {3718,3721,3719 ,3226,3229,3227 ,0,0,0}, {3722,3723,3720 ,3230,3231,3228 ,0,0,0}, + {3720,3721,3722 ,3228,3229,3230 ,0,0,0}, {3723,3724,3725 ,3231,3232,3233 ,0,0,0}, + {3724,3723,3722 ,3232,3231,3230 ,0,0,0}, {3726,3725,3727 ,3234,3233,3235 ,0,0,0}, + {3724,3727,3725 ,3232,3235,3233 ,0,0,0}, {3728,3729,3726 ,3236,3237,3234 ,0,0,0}, + {3726,3727,3728 ,3234,3235,3236 ,0,0,0}, {3729,3730,3731 ,3237,3238,3239 ,0,0,0}, + {3730,3729,3728 ,3238,3237,3236 ,0,0,0}, {3732,3731,3733 ,3240,3239,3241 ,0,0,0}, + {3730,3733,3731 ,3238,3241,3239 ,0,0,0}, {3734,3735,3732 ,3242,3243,3240 ,0,0,0}, + {3732,3733,3734 ,3240,3241,3242 ,0,0,0}, {3735,3736,3737 ,3243,3244,3245 ,0,0,0}, + {3736,3735,3734 ,3244,3243,3242 ,0,0,0}, {3738,3737,3739 ,3246,3245,3247 ,0,0,0}, + {3736,3739,3737 ,3244,3247,3245 ,0,0,0}, {3740,3741,3738 ,3248,3249,3246 ,0,0,0}, + {3738,3739,3740 ,3246,3247,3248 ,0,0,0}, {3741,3742,3743 ,3249,3250,3251 ,0,0,0}, + {3742,3741,3740 ,3250,3249,3248 ,0,0,0}, {3744,3743,3745 ,3252,3251,3253 ,0,0,0}, + {3742,3745,3743 ,3250,3253,3251 ,0,0,0}, {3706,3705,3744 ,3254,3254,3252 ,0,0,0}, + {3744,3745,3706 ,3252,3253,3254 ,0,0,0}, {3709,3708,3746 ,3217,3216,3255 ,0,0,0}, + {3747,3746,3748 ,3256,3255,3257 ,0,0,0}, {3708,3748,3746 ,3216,3257,3255 ,0,0,0}, + {3749,3750,3747 ,3258,3259,3256 ,0,0,0}, {3747,3748,3749 ,3256,3257,3258 ,0,0,0}, + {3750,3751,3752 ,3259,3260,3261 ,0,0,0}, {3751,3750,3749 ,3260,3259,3258 ,0,0,0}, + {3753,3752,3754 ,3262,3261,3263 ,0,0,0}, {3751,3754,3752 ,3260,3263,3261 ,0,0,0}, + {3755,3756,3753 ,3264,3265,3262 ,0,0,0}, {3753,3754,3755 ,3262,3263,3264 ,0,0,0}, + {3756,3757,3758 ,3265,3266,3267 ,0,0,0}, {3757,3756,3755 ,3266,3265,3264 ,0,0,0}, + {3759,3758,3760 ,3268,3267,3269 ,0,0,0}, {3757,3760,3758 ,3266,3269,3267 ,0,0,0}, + {3761,3762,3759 ,3270,3271,3268 ,0,0,0}, {3759,3760,3761 ,3268,3269,3270 ,0,0,0}, + {3762,3763,3764 ,3271,3272,3273 ,0,0,0}, {3763,3762,3761 ,3272,3271,3270 ,0,0,0}, + {3765,3764,3766 ,3274,3273,3275 ,0,0,0}, {3763,3766,3764 ,3272,3275,3273 ,0,0,0}, + {3767,3768,3765 ,3276,3277,3274 ,0,0,0}, {3765,3766,3767 ,3274,3275,3276 ,0,0,0}, + {3768,3769,3770 ,3277,3278,3279 ,0,0,0}, {3769,3768,3767 ,3278,3277,3276 ,0,0,0}, + {3771,3770,3772 ,3280,3279,3281 ,0,0,0}, {3769,3772,3770 ,3278,3281,3279 ,0,0,0}, + {3773,3774,3771 ,3282,3283,3280 ,0,0,0}, {3771,3772,3773 ,3280,3281,3282 ,0,0,0}, + {3774,3775,3776 ,3283,3284,3285 ,0,0,0}, {3775,3774,3773 ,3284,3283,3282 ,0,0,0}, + {3777,3776,3778 ,3286,3285,3287 ,0,0,0}, {3775,3778,3776 ,3284,3287,3285 ,0,0,0}, + {3779,3780,3777 ,3288,3289,3286 ,0,0,0}, {3777,3778,3779 ,3286,3287,3288 ,0,0,0}, + {3780,3781,3782 ,3289,3290,3291 ,0,0,0}, {3781,3780,3779 ,3290,3289,3288 ,0,0,0}, + {3781,3431,3782 ,3290,3292,3291 ,0,0,0}, {3782,3431,3430 ,3291,3292,3292 ,0,0,0}, + {3132,3428,3133 ,1433,3293,1433 ,0,0,0}, {3428,3132,3426 ,3293,1433,3293 ,0,0,0}, + {3653,3155,3154 ,3294,3294,3294 ,0,0,0}, {3431,3781,3354 ,3294,726,726 ,0,0,0}, + {3775,3384,3778 ,726,726,726 ,0,0,0}, {3471,3429,3351 ,726,726,726 ,0,0,0}, + {3372,3376,3766 ,726,726,726 ,0,0,0}, {3380,3772,3769 ,726,726,726 ,0,0,0}, + {3751,3362,3754 ,726,726,726 ,0,0,0}, {3760,3757,3369 ,726,726,726 ,0,0,0}, + {3748,3356,3355 ,726,726,726 ,0,0,0}, {3749,3748,3355 ,726,726,726 ,0,0,0}, + {3148,3145,3644 ,3294,726,3294 ,0,0,0}, {3661,3660,3163 ,3294,726,3294 ,0,0,0}, + {3629,3633,3137 ,3294,3294,726 ,0,0,0}, {3139,3633,3636 ,726,3294,726 ,0,0,0}, + {3667,3093,3097 ,726,726,726 ,0,0,0}, {3093,3631,3094 ,726,3294,3294 ,0,0,0}, + {3670,3100,3673 ,3294,726,726 ,0,0,0}, {3099,3670,3668 ,3294,3294,3294 ,0,0,0}, + {3109,3680,3679 ,3295,3294,3294 ,0,0,0}, {3105,3676,3674 ,726,3294,3294 ,0,0,0}, + {3682,3680,3111 ,3294,3294,3294 ,0,0,0}, {3109,3111,3680 ,3295,3294,3294 ,0,0,0}, + {3686,3685,3115 ,3294,3295,726 ,0,0,0}, {3682,3111,3112 ,3294,3294,3294 ,0,0,0}, + {3688,3686,3117 ,3294,3294,3294 ,0,0,0}, {3115,3685,3112 ,726,3295,3294 ,0,0,0}, + {3118,3691,3688 ,3294,726,3294 ,0,0,0}, {3688,3117,3118 ,3294,3294,3294 ,0,0,0}, + {3691,3121,3692 ,726,726,726 ,0,0,0}, {3121,3691,3118 ,726,726,3294 ,0,0,0}, + {3694,3692,3123 ,726,726,726 ,0,0,0}, {3124,3694,3123 ,726,726,726 ,0,0,0}, + {3129,3698,3127 ,726,3294,3294 ,0,0,0}, {3697,3694,3124 ,726,726,726 ,0,0,0}, + {3130,3133,3700 ,726,726,726 ,0,0,0}, {3127,3698,3697 ,3294,3294,726 ,0,0,0}, + {3133,3703,3700 ,726,3294,726 ,0,0,0}, {3698,3130,3700 ,3294,726,726 ,0,0,0}, + {3723,3404,3720 ,726,726,726 ,0,0,0}, {3133,3704,3703 ,726,726,3294 ,0,0,0}, + {3654,3157,3648 ,3294,726,726 ,0,0,0}, {3668,3097,3099 ,3294,726,3294 ,0,0,0}, + {3676,3105,3106 ,3294,726,3294 ,0,0,0}, {3679,3106,3109 ,3294,3294,3295 ,0,0,0}, + {3103,3105,3674 ,3294,726,3294 ,0,0,0}, {3673,3100,3103 ,726,726,3294 ,0,0,0}, + {3631,3093,3667 ,3294,726,726 ,0,0,0}, {3667,3097,3668 ,726,726,3294 ,0,0,0}, + {3629,3136,3634 ,3294,3294,3294 ,0,0,0}, {3634,3094,3631 ,3294,3294,3294 ,0,0,0}, + {3297,3476,3295 ,726,726,3294 ,0,0,0}, {3136,3094,3634 ,3294,3294,3294 ,0,0,0}, + {3639,3143,3142 ,3294,3294,726 ,0,0,0}, {3636,3142,3139 ,726,726,726 ,0,0,0}, + {3640,3145,3143 ,726,726,3294 ,0,0,0}, {3639,3142,3636 ,3294,726,726 ,0,0,0}, + {3647,3151,3149 ,3294,3294,3294 ,0,0,0}, {3148,3644,3643 ,3294,3294,726 ,0,0,0}, + {3648,3155,3653 ,726,3294,3294 ,0,0,0}, {3151,3651,3154 ,3294,3294,3294 ,0,0,0}, + {3161,3160,3655 ,726,726,726 ,0,0,0}, {3157,3155,3648 ,726,3294,726 ,0,0,0}, + {3655,3160,3654 ,726,726,3294 ,0,0,0}, {3503,3500,3283 ,3294,726,726 ,0,0,0}, + {3663,3167,3166 ,3295,726,726 ,0,0,0}, {3080,3062,3082 ,3294,3295,726 ,0,0,0}, + {3169,3665,3171 ,3294,726,3294 ,0,0,0}, {3087,3089,3054 ,726,3294,726 ,0,0,0}, + {3051,3089,3090 ,726,3294,3294 ,0,0,0}, {3250,3247,3043 ,726,726,726 ,0,0,0}, + {3250,3034,3036 ,726,726,3294 ,0,0,0}, {3553,3225,3551 ,726,3294,3294 ,0,0,0}, + {3244,3239,3506 ,3294,726,726 ,0,0,0}, {3613,3610,3783 ,726,726,726 ,0,0,0}, + {3524,3208,3523 ,726,3294,3294 ,0,0,0}, {3784,3785,3574 ,3294,3294,726 ,0,0,0}, + {3029,3786,3787 ,3294,726,726 ,0,0,0}, {3580,3578,3788 ,726,3294,726 ,0,0,0}, + {3788,3578,3785 ,726,3294,3294 ,0,0,0}, {3002,2999,3071 ,726,726,3294 ,0,0,0}, + {3788,3071,3583 ,726,3294,3294 ,0,0,0}, {3069,3067,3000 ,3294,3294,3294 ,0,0,0}, + {3000,3067,3009 ,3294,3294,3294 ,0,0,0}, {3590,3589,2998 ,3294,726,726 ,0,0,0}, + {3577,3574,3785 ,3294,726,3294 ,0,0,0}, {3215,3784,3572 ,726,3294,726 ,0,0,0}, + {3190,3789,3186 ,726,3294,3294 ,0,0,0}, {3790,3791,3786 ,3294,3294,726 ,0,0,0}, + {3181,3792,3793 ,726,3294,3294 ,0,0,0}, {3569,3214,3215 ,3294,726,726 ,0,0,0}, + {3215,3572,3571 ,726,726,3294 ,0,0,0}, {3511,3214,3569 ,3294,726,3294 ,0,0,0}, + {3608,3607,3794 ,726,3294,3294 ,0,0,0}, {3213,3214,3515 ,3294,726,726 ,0,0,0}, + {3515,3517,3213 ,726,726,3294 ,0,0,0}, {3614,3613,3795 ,3294,726,3294 ,0,0,0}, + {3210,3213,3518 ,726,3294,726 ,0,0,0}, {3616,3796,3619 ,726,3294,3294 ,0,0,0}, + {3521,3210,3518 ,3294,726,726 ,0,0,0}, {3173,3620,3176 ,3294,726,3294 ,0,0,0}, + {3210,3523,3208 ,726,3294,3294 ,0,0,0}, {3533,3204,3203 ,3294,726,726 ,0,0,0}, + {3529,3203,3206 ,3294,726,3294 ,0,0,0}, {3220,3219,3541 ,3295,726,3294 ,0,0,0}, + {3204,3533,3535 ,726,3294,3294 ,0,0,0}, {3548,3222,3547 ,3294,3294,3294 ,0,0,0}, + {3222,3220,3545 ,3294,3295,3294 ,0,0,0}, {3231,3228,3559 ,3294,726,726 ,0,0,0}, + {3191,3797,3195 ,3294,726,3294 ,0,0,0}, {3798,3799,3800 ,3294,3294,3294 ,0,0,0}, + {3232,3563,3565 ,726,726,726 ,0,0,0}, {3234,3238,3510 ,3294,3294,3294 ,0,0,0}, + {3801,3252,3802 ,726,726,726 ,0,0,0}, {3803,3262,3252 ,3294,3294,726 ,0,0,0}, + {3255,3251,3804 ,726,726,726 ,0,0,0}, {3254,3805,3802 ,726,3294,726 ,0,0,0}, + {3092,3033,3032 ,726,726,3294 ,0,0,0}, {3076,3075,3056 ,3294,726,726 ,0,0,0}, + {3805,3254,3255 ,3294,726,726 ,0,0,0}, {3622,3173,3625 ,3294,3294,3294 ,0,0,0}, + {3079,3057,3060 ,726,3294,726 ,0,0,0}, {3280,3278,3503 ,3294,3294,3294 ,0,0,0}, + {3665,3625,3171 ,726,3294,3294 ,0,0,0}, {3318,3284,3500 ,3295,726,726 ,0,0,0}, + {3169,3167,3665 ,3294,726,726 ,0,0,0}, {3755,3365,3366 ,726,726,726 ,0,0,0}, + {3711,3392,3707 ,726,726,726 ,0,0,0}, {3394,3711,3713 ,726,726,726 ,0,0,0}, + {3473,3292,3474 ,3294,726,726 ,0,0,0}, {3148,3643,3149 ,3294,726,3294 ,0,0,0}, + {3665,3167,3663 ,726,726,3295 ,0,0,0}, {3660,3663,3166 ,726,3295,726 ,0,0,0}, + {3161,3661,3163 ,726,3294,3294 ,0,0,0}, {3163,3660,3166 ,3294,726,726 ,0,0,0}, + {3151,3647,3651 ,3294,3294,3294 ,0,0,0}, {3157,3654,3160 ,726,3294,726 ,0,0,0}, + {3161,3655,3661 ,726,726,3294 ,0,0,0}, {3653,3154,3651 ,3294,3294,3294 ,0,0,0}, + {3643,3647,3149 ,726,3294,3294 ,0,0,0}, {3644,3145,3640 ,3294,726,726 ,0,0,0}, + {3476,3297,3479 ,726,726,726 ,0,0,0}, {3639,3640,3143 ,3294,726,3294 ,0,0,0}, + {3707,3392,3360 ,726,726,726 ,0,0,0}, {3360,3708,3707 ,726,726,726 ,0,0,0}, + {3708,3360,3356 ,726,726,726 ,0,0,0}, {3362,3749,3355 ,726,726,726 ,0,0,0}, + {3356,3748,3708 ,726,726,726 ,0,0,0}, {3291,3292,3473 ,3294,726,3294 ,0,0,0}, + {3755,3754,3365 ,726,726,726 ,0,0,0}, {3754,3362,3365 ,726,726,726 ,0,0,0}, + {3446,3450,3327 ,726,3294,3294 ,0,0,0}, {3757,3755,3366 ,726,726,726 ,0,0,0}, + {3373,3760,3369 ,726,726,726 ,0,0,0}, {3761,3373,3375 ,726,726,726 ,0,0,0}, + {3373,3761,3760 ,726,726,726 ,0,0,0}, {3372,3763,3375 ,726,726,726 ,0,0,0}, + {3761,3375,3763 ,726,726,726 ,0,0,0}, {3763,3372,3766 ,726,726,726 ,0,0,0}, + {3376,3379,3767 ,726,726,726 ,0,0,0}, {3328,3327,3450 ,726,3294,3294 ,0,0,0}, + {3769,3379,3380 ,726,726,726 ,0,0,0}, {3379,3769,3767 ,726,726,726 ,0,0,0}, + {3773,3772,3382 ,726,726,726 ,0,0,0}, {3467,3345,3342 ,726,3294,3294 ,0,0,0}, + {3380,3382,3772 ,726,726,726 ,0,0,0}, {3386,3775,3773 ,726,726,726 ,0,0,0}, + {3773,3382,3386 ,726,726,726 ,0,0,0}, {3775,3386,3384 ,726,726,726 ,0,0,0}, + {3384,3389,3778 ,726,726,726 ,0,0,0}, {3778,3389,3779 ,726,726,726 ,0,0,0}, + {3779,3391,3781 ,726,726,726 ,0,0,0}, {3469,3348,3346 ,3294,726,3295 ,0,0,0}, + {3391,3779,3389 ,726,726,726 ,0,0,0}, {3270,3506,3504 ,726,726,3295 ,0,0,0}, + {3046,3047,3245 ,3295,726,726 ,0,0,0}, {3316,3318,3498 ,726,3295,726 ,0,0,0}, + {3504,3278,3277 ,3295,3294,3294 ,0,0,0}, {3315,3316,3497 ,3294,726,726 ,0,0,0}, + {3313,3315,3494 ,726,3294,726 ,0,0,0}, {3500,3284,3283 ,726,726,726 ,0,0,0}, + {3310,3313,3492 ,3294,726,3294 ,0,0,0}, {3500,3498,3318 ,726,726,3295 ,0,0,0}, + {3309,3310,3491 ,726,3294,3294 ,0,0,0}, {3498,3497,3316 ,726,726,726 ,0,0,0}, + {3307,3309,3488 ,3294,726,3294 ,0,0,0}, {3497,3494,3315 ,726,726,3294 ,0,0,0}, + {3304,3486,3485 ,3294,726,726 ,0,0,0}, {3494,3492,3313 ,726,3294,726 ,0,0,0}, + {3303,3485,3482 ,726,726,3294 ,0,0,0}, {3492,3491,3310 ,3294,3294,3294 ,0,0,0}, + {3301,3482,3480 ,3294,3294,726 ,0,0,0}, {3479,3298,3480 ,726,3294,726 ,0,0,0}, + {3304,3307,3486 ,3294,3294,726 ,0,0,0}, {3476,3474,3295 ,726,726,3294 ,0,0,0}, + {3304,3485,3303 ,3294,726,726 ,0,0,0}, {3713,3714,3397 ,726,726,726 ,0,0,0}, + {3482,3301,3303 ,3294,3294,726 ,0,0,0}, {3714,3717,3398 ,726,726,726 ,0,0,0}, + {3480,3298,3301 ,726,3294,3294 ,0,0,0}, {3717,3719,3400 ,726,726,726 ,0,0,0}, + {3136,3629,3137 ,3294,3294,726 ,0,0,0}, {3137,3633,3139 ,726,3294,726 ,0,0,0}, + {3474,3292,3295 ,726,726,3294 ,0,0,0}, {3403,3400,3719 ,726,726,726 ,0,0,0}, + {3394,3392,3711 ,726,726,726 ,0,0,0}, {3403,3720,3404 ,726,726,726 ,0,0,0}, + {3397,3394,3713 ,726,726,726 ,0,0,0}, {3723,3406,3404 ,726,726,726 ,0,0,0}, + {3398,3397,3714 ,726,726,726 ,0,0,0}, {3725,3409,3406 ,726,726,726 ,0,0,0}, + {3400,3398,3717 ,726,726,726 ,0,0,0}, {3100,3670,3099 ,726,3294,3294 ,0,0,0}, + {3410,3409,3726 ,726,726,726 ,0,0,0}, {3719,3720,3403 ,726,726,726 ,0,0,0}, + {3412,3410,3729 ,726,726,726 ,0,0,0}, {3412,3729,3731 ,726,726,726 ,0,0,0}, + {3103,3674,3673 ,3294,3294,726 ,0,0,0}, {3723,3725,3406 ,726,726,726 ,0,0,0}, + {3106,3679,3676 ,3294,3294,3294 ,0,0,0}, {3732,3415,3731 ,726,726,726 ,0,0,0}, + {3725,3726,3409 ,726,726,726 ,0,0,0}, {3416,3732,3735 ,726,726,726 ,0,0,0}, + {3726,3729,3410 ,726,726,726 ,0,0,0}, {3112,3685,3682 ,3294,3295,3294 ,0,0,0}, + {3731,3415,3412 ,726,726,726 ,0,0,0}, {3735,3737,3418 ,726,726,726 ,0,0,0}, + {3416,3415,3732 ,726,726,726 ,0,0,0}, {3738,3421,3737 ,726,726,726 ,0,0,0}, + {3115,3117,3686 ,726,3294,3294 ,0,0,0}, {3741,3422,3738 ,726,726,726 ,0,0,0}, + {3418,3416,3735 ,726,726,726 ,0,0,0}, {3121,3123,3692 ,726,726,726 ,0,0,0}, + {3737,3421,3418 ,726,726,726 ,0,0,0}, {3424,3741,3743 ,726,726,726 ,0,0,0}, + {3124,3127,3697 ,726,3294,726 ,0,0,0}, {3738,3422,3421 ,726,726,726 ,0,0,0}, + {3427,3424,3743 ,3294,726,726 ,0,0,0}, {3428,3427,3744 ,726,3294,726 ,0,0,0}, + {3129,3130,3698 ,726,726,3294 ,0,0,0}, {3427,3743,3744 ,3294,726,726 ,0,0,0}, + {3705,3704,3428 ,3294,726,726 ,0,0,0}, {3704,3133,3428 ,726,726,726 ,0,0,0}, + {3744,3705,3428 ,726,3294,726 ,0,0,0}, {3741,3424,3422 ,726,726,726 ,0,0,0}, + {3291,3473,3437 ,3294,3294,3294 ,0,0,0}, {3289,3437,3440 ,3294,3294,3294 ,0,0,0}, + {3285,3440,3435 ,3294,3294,3294 ,0,0,0}, {3319,3435,3439 ,726,3294,726 ,0,0,0}, + {3439,3442,3321 ,726,3294,3294 ,0,0,0}, {3362,3751,3749 ,726,726,726 ,0,0,0}, + {3437,3289,3291 ,3294,3294,3294 ,0,0,0}, {3442,3445,3322 ,3294,3294,726 ,0,0,0}, + {3440,3285,3289 ,3294,3294,3294 ,0,0,0}, {3366,3369,3757 ,726,726,726 ,0,0,0}, + {3285,3435,3319 ,3294,3294,726 ,0,0,0}, {3446,3324,3445 ,726,726,3294 ,0,0,0}, + {3439,3321,3319 ,726,3294,726 ,0,0,0}, {3328,3450,3449 ,726,3294,3294 ,0,0,0}, + {3442,3322,3321 ,3294,726,3294 ,0,0,0}, {3330,3328,3449 ,3294,726,3294 ,0,0,0}, + {3445,3324,3322 ,3294,726,726 ,0,0,0}, {3453,3333,3330 ,726,3294,3294 ,0,0,0}, + {3446,3327,3324 ,726,3294,726 ,0,0,0}, {3457,3334,3333 ,726,726,3294 ,0,0,0}, + {3459,3336,3334 ,3294,726,726 ,0,0,0}, {3766,3376,3767 ,726,726,726 ,0,0,0}, + {3330,3449,3453 ,3294,3294,726 ,0,0,0}, {3454,3339,3336 ,726,3294,726 ,0,0,0}, + {3333,3453,3457 ,3294,726,726 ,0,0,0}, {3339,3460,3340 ,3294,726,3294 ,0,0,0}, + {3334,3457,3459 ,726,726,3294 ,0,0,0}, {3342,3340,3461 ,3294,3294,726 ,0,0,0}, + {3339,3454,3460 ,3294,726,726 ,0,0,0}, {3345,3467,3466 ,3294,726,3294 ,0,0,0}, + {3340,3460,3461 ,3294,726,726 ,0,0,0}, {3469,3346,3466 ,3294,3295,3294 ,0,0,0}, + {3342,3461,3467 ,3294,726,726 ,0,0,0}, {3469,3351,3348 ,3294,726,726 ,0,0,0}, + {3346,3345,3466 ,3295,3294,3294 ,0,0,0}, {3351,3429,3354 ,726,726,726 ,0,0,0}, + {3431,3354,3429 ,3294,726,726 ,0,0,0}, {3781,3391,3354 ,726,726,726 ,0,0,0}, + {3469,3471,3351 ,3294,726,726 ,0,0,0}, {3336,3459,3454 ,726,3294,726 ,0,0,0}, + {3298,3479,3297 ,3294,726,726 ,0,0,0}, {3309,3491,3488 ,726,3294,3294 ,0,0,0}, + {3307,3488,3486 ,3294,3294,726 ,0,0,0}, {3226,3553,3554 ,3294,726,3294 ,0,0,0}, + {3280,3503,3283 ,3294,3294,726 ,0,0,0}, {3241,3232,3566 ,3294,726,726 ,0,0,0}, + {3504,3503,3278 ,3295,3294,3294 ,0,0,0}, {3268,3271,3806 ,726,3294,3294 ,0,0,0}, + {3270,3504,3277 ,726,3295,3294 ,0,0,0}, {3807,3260,3259 ,3294,3294,726 ,0,0,0}, + {3251,3082,3063 ,726,726,726 ,0,0,0}, {3262,3808,3259 ,3294,726,726 ,0,0,0}, + {3251,3063,3804 ,726,726,726 ,0,0,0}, {3509,3239,3235 ,726,726,3294 ,0,0,0}, + {3231,3559,3560 ,3294,726,726 ,0,0,0}, {3793,3191,3179 ,3294,3294,3294 ,0,0,0}, + {3548,3551,3225 ,3294,3294,3294 ,0,0,0}, {3220,3541,3542 ,3295,3294,3295 ,0,0,0}, + {3529,3530,3203 ,3294,3294,726 ,0,0,0}, {3583,3071,3584 ,3294,3294,3294 ,0,0,0}, + {3206,3524,3527 ,3294,726,3294 ,0,0,0}, {3536,3219,3204 ,726,726,726 ,0,0,0}, + {3219,3536,3539 ,726,726,3294 ,0,0,0}, {3222,3545,3547 ,3294,3294,3294 ,0,0,0}, + {3557,3226,3554 ,726,3294,3294 ,0,0,0}, {3557,3228,3226 ,726,726,3294 ,0,0,0}, + {3232,3231,3563 ,726,3294,726 ,0,0,0}, {3566,3568,3241 ,726,726,3294 ,0,0,0}, + {3241,3510,3238 ,3294,3294,3294 ,0,0,0}, {3235,3234,3509 ,3294,3294,726 ,0,0,0}, + {3807,3809,3260 ,3294,726,3294 ,0,0,0}, {3810,3811,3274 ,726,3294,726 ,0,0,0}, + {3811,3812,3274 ,3294,726,726 ,0,0,0}, {3813,3806,3271 ,726,3294,3294 ,0,0,0}, + {3806,3814,3268 ,3294,726,726 ,0,0,0}, {3239,3509,3506 ,726,726,726 ,0,0,0}, + {3510,3509,3234 ,3294,726,3294 ,0,0,0}, {3510,3241,3568 ,3294,3294,726 ,0,0,0}, + {3566,3232,3565 ,726,726,726 ,0,0,0}, {3563,3231,3560 ,726,3294,726 ,0,0,0}, + {3559,3228,3557 ,726,726,726 ,0,0,0}, {3226,3225,3553 ,3294,3294,726 ,0,0,0}, + {3225,3222,3548 ,3294,3294,3294 ,0,0,0}, {3220,3542,3545 ,3295,3295,3294 ,0,0,0}, + {3219,3539,3541 ,726,3294,3294 ,0,0,0}, {3204,3535,3536 ,726,3294,726 ,0,0,0}, + {3203,3530,3533 ,726,3294,3294 ,0,0,0}, {3206,3527,3529 ,3294,3294,3294 ,0,0,0}, + {3206,3208,3524 ,3294,3294,726 ,0,0,0}, {3210,3521,3523 ,726,3294,3294 ,0,0,0}, + {3213,3517,3518 ,3294,726,726 ,0,0,0}, {3214,3511,3515 ,726,3294,726 ,0,0,0}, + {3215,3571,3569 ,726,3294,3294 ,0,0,0}, {3784,3574,3572 ,3294,726,726 ,0,0,0}, + {3785,3578,3577 ,3294,3294,3294 ,0,0,0}, {3788,3583,3580 ,726,3294,726 ,0,0,0}, + {3002,3069,3000 ,726,3294,3294 ,0,0,0}, {3006,3009,3067 ,3294,3294,3294 ,0,0,0}, + {3586,3584,2999 ,3294,3294,726 ,0,0,0}, {3066,3008,3006 ,3294,726,3294 ,0,0,0}, + {3012,3073,3200 ,3294,726,3294 ,0,0,0}, {3815,3800,3816 ,726,3294,3294 ,0,0,0}, + {3185,3817,3183 ,726,3294,3294 ,0,0,0}, {3818,3185,3186 ,726,726,3294 ,0,0,0}, + {3180,3792,3181 ,3294,3294,726 ,0,0,0}, {3180,3183,3819 ,3294,3294,726 ,0,0,0}, + {3820,3190,3799 ,726,726,3294 ,0,0,0}, {3821,3196,3195 ,3294,3294,3294 ,0,0,0}, + {3815,3791,3790 ,726,3294,3294 ,0,0,0}, {3022,3595,3020 ,3294,3294,3294 ,0,0,0}, + {3017,3592,3590 ,3294,3294,3294 ,0,0,0}, {3026,3028,3601 ,3294,3294,726 ,0,0,0}, + {3023,3598,3596 ,726,726,726 ,0,0,0}, {3607,3029,3787 ,3294,3294,726 ,0,0,0}, + {3787,3794,3607 ,726,3294,3294 ,0,0,0}, {3604,3029,3607 ,726,3294,3294 ,0,0,0}, + {3604,3602,3028 ,726,726,3294 ,0,0,0}, {3610,3608,3794 ,726,726,3294 ,0,0,0}, + {3795,3613,3783 ,3294,726,726 ,0,0,0}, {3783,3610,3794 ,726,726,3294 ,0,0,0}, + {3795,3616,3614 ,3294,726,3294 ,0,0,0}, {3796,3176,3619 ,3294,3294,3294 ,0,0,0}, + {3795,3796,3616 ,3294,3294,726 ,0,0,0}, {3620,3619,3176 ,726,3294,3294 ,0,0,0}, + {3620,3173,3622 ,726,3294,3294 ,0,0,0}, {3625,3173,3171 ,3294,3294,3294 ,0,0,0}, + {3245,3042,3247 ,726,3294,726 ,0,0,0}, {3804,3805,3255 ,726,3294,726 ,0,0,0}, + {3036,3033,3092 ,3294,726,726 ,0,0,0}, {3802,3252,3254 ,726,726,726 ,0,0,0}, + {3803,3252,3801 ,3294,726,726 ,0,0,0}, {3808,3262,3803 ,726,3294,3294 ,0,0,0}, + {3807,3259,3808 ,3294,726,726 ,0,0,0}, {3264,3260,3809 ,3294,3294,726 ,0,0,0}, + {3264,3822,3274 ,3294,3294,726 ,0,0,0}, {3822,3264,3809 ,3294,3294,726 ,0,0,0}, + {3822,3810,3274 ,3294,726,726 ,0,0,0}, {3271,3812,3813 ,3294,726,726 ,0,0,0}, + {3812,3271,3274 ,726,3294,726 ,0,0,0}, {3270,3049,3506 ,726,726,726 ,0,0,0}, + {3814,3049,3270 ,726,726,726 ,0,0,0}, {3814,3270,3268 ,726,726,726 ,0,0,0}, + {3049,3046,3506 ,726,3295,726 ,0,0,0}, {3244,3046,3245 ,3294,3295,726 ,0,0,0}, + {3046,3244,3506 ,3295,3294,726 ,0,0,0}, {3047,3042,3245 ,726,3294,726 ,0,0,0}, + {3040,3043,3247 ,726,726,726 ,0,0,0}, {3042,3040,3247 ,3294,726,726 ,0,0,0}, + {3043,3034,3250 ,726,726,726 ,0,0,0}, {3036,3092,3250 ,3294,726,726 ,0,0,0}, + {3090,3092,3032 ,3294,726,3294 ,0,0,0}, {3054,3089,3051 ,726,3294,726 ,0,0,0}, + {3051,3090,3032 ,726,3294,3294 ,0,0,0}, {3056,3087,3054 ,726,726,726 ,0,0,0}, + {3056,3057,3076 ,726,3294,3294 ,0,0,0}, {3056,3075,3087 ,726,726,726 ,0,0,0}, + {3079,3060,3080 ,726,726,3294 ,0,0,0}, {3076,3057,3079 ,3294,3294,726 ,0,0,0}, + {3082,3062,3063 ,726,3295,726 ,0,0,0}, {3080,3060,3062 ,3294,726,3295 ,0,0,0}, + {3196,3823,3198 ,3294,726,3294 ,0,0,0}, {3787,3786,3791 ,726,726,3294 ,0,0,0}, + {3200,3198,3015 ,3294,3294,3294 ,0,0,0}, {3815,3816,3791 ,726,3294,3294 ,0,0,0}, + {3800,3799,3816 ,3294,3294,3294 ,0,0,0}, {3820,3799,3798 ,726,3294,3294 ,0,0,0}, + {3789,3190,3820 ,3294,726,726 ,0,0,0}, {3818,3186,3789 ,726,3294,3294 ,0,0,0}, + {3817,3185,3818 ,3294,726,726 ,0,0,0}, {3819,3183,3817 ,726,3294,3294 ,0,0,0}, + {3792,3180,3819 ,3294,3294,726 ,0,0,0}, {3179,3181,3793 ,3294,726,3294 ,0,0,0}, + {3797,3191,3793 ,726,3294,3294 ,0,0,0}, {3821,3195,3797 ,3294,3294,726 ,0,0,0}, + {3823,3196,3821 ,726,3294,3294 ,0,0,0}, {3015,3198,3823 ,3294,3294,726 ,0,0,0}, + {3012,3200,3015 ,3294,3294,3294 ,0,0,0}, {3013,3073,3012 ,3294,726,3294 ,0,0,0}, + {3066,3013,3008 ,3294,3294,726 ,0,0,0}, {3013,3066,3073 ,3294,3294,726 ,0,0,0}, + {3006,3067,3066 ,3294,3294,3294 ,0,0,0}, {3071,3069,3002 ,3294,3294,726 ,0,0,0}, + {3586,2999,2998 ,3294,726,726 ,0,0,0}, {2999,3584,3071 ,726,3294,3294 ,0,0,0}, + {3017,3590,2998 ,3294,3294,726 ,0,0,0}, {3589,3586,2998 ,726,3294,726 ,0,0,0}, + {3020,3592,3017 ,3294,3294,3294 ,0,0,0}, {3022,3596,3595 ,3294,726,3294 ,0,0,0}, + {3020,3595,3592 ,3294,3294,3294 ,0,0,0}, {3023,3026,3598 ,726,3294,726 ,0,0,0}, + {3022,3023,3596 ,3294,726,726 ,0,0,0}, {3601,3028,3602 ,726,3294,726 ,0,0,0}, + {3598,3026,3601 ,726,3294,726 ,0,0,0}, {3604,3028,3029 ,726,3294,3294 ,0,0,0}, + {3352,3470,3468 ,730,730,730 ,0,0,0}, {3134,3630,3095 ,730,730,730 ,0,0,0}, + {3205,3538,3537 ,730,730,730 ,0,0,0}, {3464,3347,3465 ,730,730,730 ,0,0,0}, + {3338,3341,3456 ,730,730,730 ,0,0,0}, {3343,3344,3463 ,730,730,730 ,0,0,0}, + {3329,3331,3448 ,730,730,730 ,0,0,0}, {3332,3335,3452 ,730,730,730 ,0,0,0}, + {3433,3436,3287 ,730,730,730 ,0,0,0}, {3323,3325,3443 ,730,730,730 ,0,0,0}, + {3632,3096,3095 ,730,730,730 ,0,0,0}, {3477,3294,3475 ,730,730,730 ,0,0,0}, + {3104,3672,3675 ,730,730,730 ,0,0,0}, {3678,3681,3110 ,730,730,730 ,0,0,0}, + {3666,3669,3098 ,730,730,730 ,0,0,0}, {3672,3104,3102 ,730,730,730 ,0,0,0}, + {3135,3628,3627 ,730,730,730 ,0,0,0}, {3096,3632,3666 ,730,730,730 ,0,0,0}, + {3140,3141,3637 ,730,730,730 ,0,0,0}, {3710,3393,3712 ,730,730,730 ,0,0,0}, + {3638,3144,3641 ,730,730,730 ,0,0,0}, {3141,3638,3637 ,730,730,730 ,0,0,0}, + {3153,3652,3152 ,730,730,730 ,0,0,0}, {3146,3642,3641 ,730,730,730 ,0,0,0}, + {3659,3658,3164 ,730,730,730 ,0,0,0}, {3657,3656,3159 ,730,730,730 ,0,0,0}, + {3165,3168,3662 ,730,730,730 ,0,0,0}, {3824,3576,3579 ,730,730,730 ,0,0,0}, + {3211,3209,3520 ,730,730,730 ,0,0,0}, {3014,3074,3072 ,730,730,730 ,0,0,0}, + {3024,3599,3600 ,730,730,730 ,0,0,0}, {3174,3624,3626 ,730,730,730 ,0,0,0}, + {3664,3172,3626 ,730,730,730 ,0,0,0}, {3825,3826,3618 ,730,730,730 ,0,0,0}, + {3027,3025,3603 ,730,730,730 ,0,0,0}, {3825,3618,3621 ,730,730,730 ,0,0,0}, + {3615,3617,3826 ,730,730,730 ,0,0,0}, {3177,3827,3178 ,730,730,730 ,0,0,0}, + {3626,3172,3174 ,730,730,730 ,0,0,0}, {3538,3205,3218 ,730,730,730 ,0,0,0}, + {3828,3217,3575 ,730,730,730 ,0,0,0}, {3516,3514,3212 ,730,730,730 ,0,0,0}, + {3024,3600,3025 ,730,730,730 ,0,0,0}, {3070,3585,3587 ,730,730,730 ,0,0,0}, + {3168,3170,3664 ,730,730,730 ,0,0,0}, {3068,3001,3065 ,730,730,730 ,0,0,0}, + {3004,3005,3065 ,730,730,730 ,0,0,0}, {3829,3193,3194 ,730,730,730 ,0,0,0}, + {3825,3621,3175 ,730,730,730 ,0,0,0}, {3174,3175,3623 ,730,730,730 ,0,0,0}, + {3830,3615,3826 ,730,730,730 ,0,0,0}, {3611,3612,3831 ,730,730,730 ,0,0,0}, + {3831,3612,3830 ,730,730,730 ,0,0,0}, {3830,3612,3615 ,730,730,730 ,0,0,0}, + {3826,3617,3618 ,730,730,730 ,0,0,0}, {3832,3833,3834 ,730,730,730 ,0,0,0}, + {3083,3084,3061 ,730,730,730 ,0,0,0}, {3621,3623,3175 ,730,730,730 ,0,0,0}, + {3605,3027,3603 ,730,730,730 ,0,0,0}, {3624,3174,3623 ,730,730,730 ,0,0,0}, + {3835,3189,3187 ,730,730,730 ,0,0,0}, {3194,3197,3836 ,730,730,730 ,0,0,0}, + {3199,3074,3011 ,730,730,730 ,0,0,0}, {3197,3199,3010 ,730,730,730 ,0,0,0}, + {3664,3170,3172 ,730,730,730 ,0,0,0}, {3178,3837,3182 ,730,730,730 ,0,0,0}, + {3838,3192,3193 ,730,730,730 ,0,0,0}, {3070,3587,2997 ,730,730,730 ,0,0,0}, + {3182,3839,3184 ,730,730,730 ,0,0,0}, {3021,3599,3024 ,730,730,730 ,0,0,0}, + {3599,3021,3597 ,730,730,730 ,0,0,0}, {3512,3216,3513 ,730,730,730 ,0,0,0}, + {3528,3202,3531 ,730,730,730 ,0,0,0}, {3525,3522,3207 ,730,730,730 ,0,0,0}, + {3546,3544,3221 ,730,730,730 ,0,0,0}, {3534,3201,3205 ,730,730,730 ,0,0,0}, + {3546,3221,3223 ,730,730,730 ,0,0,0}, {3164,3165,3659 ,730,730,730 ,0,0,0}, + {3168,3664,3662 ,730,730,730 ,0,0,0}, {3662,3659,3165 ,730,730,730 ,0,0,0}, + {3678,3108,3677 ,730,730,730 ,0,0,0}, {3657,3159,3162 ,730,730,730 ,0,0,0}, + {3658,3162,3164 ,730,730,730 ,0,0,0}, {3158,3159,3656 ,730,730,730 ,0,0,0}, + {3657,3162,3658 ,730,730,730 ,0,0,0}, {3158,3650,3156 ,730,730,730 ,0,0,0}, + {3649,3153,3156 ,730,730,730 ,0,0,0}, {3656,3650,3158 ,730,730,730 ,0,0,0}, + {3153,3649,3652 ,730,730,730 ,0,0,0}, {3156,3650,3649 ,730,730,730 ,0,0,0}, + {3487,3306,3305 ,730,730,730 ,0,0,0}, {3646,3150,3152 ,730,730,730 ,0,0,0}, + {3150,3645,3147 ,730,730,730 ,0,0,0}, {3645,3642,3147 ,730,730,730 ,0,0,0}, + {3642,3146,3147 ,730,730,730 ,0,0,0}, {3641,3144,3146 ,730,730,730 ,0,0,0}, + {3638,3141,3144 ,730,730,730 ,0,0,0}, {3138,3635,3628 ,730,730,730 ,0,0,0}, + {3140,3637,3635 ,730,730,730 ,0,0,0}, {3135,3627,3134 ,730,730,730 ,0,0,0}, + {3630,3632,3095 ,730,730,730 ,0,0,0}, {3098,3669,3101 ,730,730,730 ,0,0,0}, + {3102,3101,3671 ,730,730,730 ,0,0,0}, {3104,3675,3107 ,730,730,730 ,0,0,0}, + {3102,3671,3672 ,730,730,730 ,0,0,0}, {3107,3677,3108 ,730,730,730 ,0,0,0}, + {3107,3675,3677 ,730,730,730 ,0,0,0}, {3113,3681,3683 ,730,730,730 ,0,0,0}, + {3110,3108,3678 ,730,730,730 ,0,0,0}, {3114,3113,3683 ,730,730,730 ,0,0,0}, + {3114,3683,3684 ,730,730,730 ,0,0,0}, {3116,3684,3687 ,730,730,730 ,0,0,0}, + {3114,3684,3116 ,730,730,730 ,0,0,0}, {3687,3119,3116 ,730,730,730 ,0,0,0}, + {3687,3689,3119 ,730,730,730 ,0,0,0}, {3119,3689,3120 ,730,730,730 ,0,0,0}, + {3101,3669,3671 ,730,730,730 ,0,0,0}, {3122,3120,3690 ,730,730,730 ,0,0,0}, + {3120,3689,3690 ,730,730,730 ,0,0,0}, {3693,3125,3122 ,730,730,730 ,0,0,0}, + {3693,3122,3690 ,730,730,730 ,0,0,0}, {3125,3695,3126 ,730,730,730 ,0,0,0}, + {3126,3696,3128 ,730,730,730 ,0,0,0}, {3696,3126,3695 ,730,730,730 ,0,0,0}, + {3696,3699,3131 ,730,730,730 ,0,0,0}, {3423,3742,3740 ,730,730,730 ,0,0,0}, + {3132,3131,3699 ,730,730,730 ,0,0,0}, {3702,3706,3426 ,730,730,730 ,0,0,0}, + {3425,3745,3742 ,730,730,730 ,0,0,0}, {3098,3096,3666 ,730,730,730 ,0,0,0}, + {3359,3746,3357 ,730,730,730 ,0,0,0}, {3745,3425,3426 ,730,730,730 ,0,0,0}, + {3627,3630,3134 ,730,730,730 ,0,0,0}, {3481,3299,3478 ,730,730,730 ,0,0,0}, + {3302,3300,3483 ,730,730,730 ,0,0,0}, {3300,3299,3481 ,730,730,730 ,0,0,0}, + {3296,3294,3477 ,730,730,730 ,0,0,0}, {3477,3478,3296 ,730,730,730 ,0,0,0}, + {3475,3293,3472 ,730,730,730 ,0,0,0}, {3475,3294,3293 ,730,730,730 ,0,0,0}, + {3438,3472,3290 ,730,730,730 ,0,0,0}, {3293,3290,3472 ,730,730,730 ,0,0,0}, + {3288,3436,3438 ,730,730,730 ,0,0,0}, {3438,3290,3288 ,730,730,730 ,0,0,0}, + {3434,3286,3320 ,730,730,730 ,0,0,0}, {3287,3436,3288 ,730,730,730 ,0,0,0}, + {3320,3323,3441 ,730,730,730 ,0,0,0}, {3286,3434,3433 ,730,730,730 ,0,0,0}, + {3434,3320,3441 ,730,730,730 ,0,0,0}, {3447,3444,3326 ,730,730,730 ,0,0,0}, + {3368,3758,3759 ,730,730,730 ,0,0,0}, {3329,3447,3326 ,730,730,730 ,0,0,0}, + {3325,3326,3444 ,730,730,730 ,0,0,0}, {3451,3332,3452 ,730,730,730 ,0,0,0}, + {3448,3447,3329 ,730,730,730 ,0,0,0}, {3335,3458,3452 ,730,730,730 ,0,0,0}, + {3332,3451,3331 ,730,730,730 ,0,0,0}, {3338,3455,3337 ,730,730,730 ,0,0,0}, + {3337,3455,3458 ,730,730,730 ,0,0,0}, {3462,3456,3341 ,730,730,730 ,0,0,0}, + {3456,3455,3338 ,730,730,730 ,0,0,0}, {3344,3464,3463 ,730,730,730 ,0,0,0}, + {3343,3463,3462 ,730,730,730 ,0,0,0}, {3468,3349,3350 ,730,730,730 ,0,0,0}, + {3349,3465,3347 ,730,730,730 ,0,0,0}, {3468,3350,3352 ,730,730,730 ,0,0,0}, + {3699,3701,3132 ,730,730,730 ,0,0,0}, {3702,3132,3701 ,730,730,730 ,0,0,0}, + {3420,3739,3419 ,730,730,730 ,0,0,0}, {3131,3128,3696 ,730,730,730 ,0,0,0}, + {3425,3742,3423 ,730,730,730 ,0,0,0}, {3125,3693,3695 ,730,730,730 ,0,0,0}, + {3417,3419,3736 ,730,730,730 ,0,0,0}, {3740,3739,3420 ,730,730,730 ,0,0,0}, + {3414,3417,3734 ,730,730,730 ,0,0,0}, {3739,3736,3419 ,730,730,730 ,0,0,0}, + {3733,3413,3414 ,730,730,730 ,0,0,0}, {3730,3411,3413 ,730,730,730 ,0,0,0}, + {3734,3417,3736 ,730,730,730 ,0,0,0}, {3728,3408,3411 ,730,730,730 ,0,0,0}, + {3733,3414,3734 ,730,730,730 ,0,0,0}, {3110,3681,3113 ,730,730,730 ,0,0,0}, + {3733,3730,3413 ,730,730,730 ,0,0,0}, {3727,3724,3407 ,730,730,730 ,0,0,0}, + {3730,3728,3411 ,730,730,730 ,0,0,0}, {3724,3722,3405 ,730,730,730 ,0,0,0}, + {3722,3721,3402 ,730,730,730 ,0,0,0}, {3721,3718,3401 ,730,730,730 ,0,0,0}, + {3408,3727,3407 ,730,730,730 ,0,0,0}, {3718,3716,3399 ,730,730,730 ,0,0,0}, + {3407,3724,3405 ,730,730,730 ,0,0,0}, {3715,3396,3716 ,730,730,730 ,0,0,0}, + {3405,3722,3402 ,730,730,730 ,0,0,0}, {3395,3715,3712 ,730,730,730 ,0,0,0}, + {3402,3721,3401 ,730,730,730 ,0,0,0}, {3393,3710,3358 ,730,730,730 ,0,0,0}, + {3401,3718,3399 ,730,730,730 ,0,0,0}, {3359,3358,3709 ,730,730,730 ,0,0,0}, + {3716,3396,3399 ,730,730,730 ,0,0,0}, {3357,3747,3361 ,730,730,730 ,0,0,0}, + {3395,3396,3715 ,730,730,730 ,0,0,0}, {3484,3302,3483 ,730,730,730 ,0,0,0}, + {3140,3635,3138 ,730,730,730 ,0,0,0}, {3138,3628,3135 ,730,730,730 ,0,0,0}, + {3358,3710,3709 ,730,730,730 ,0,0,0}, {3484,3487,3305 ,730,730,730 ,0,0,0}, + {3359,3709,3746 ,730,730,730 ,0,0,0}, {3487,3489,3306 ,730,730,730 ,0,0,0}, + {3357,3746,3747 ,730,730,730 ,0,0,0}, {3489,3490,3308 ,730,730,730 ,0,0,0}, + {3490,3493,3311 ,730,730,730 ,0,0,0}, {3481,3483,3300 ,730,730,730 ,0,0,0}, + {3493,3495,3312 ,730,730,730 ,0,0,0}, {3305,3302,3484 ,730,730,730 ,0,0,0}, + {3495,3496,3314 ,730,730,730 ,0,0,0}, {3152,3652,3646 ,730,730,730 ,0,0,0}, + {3150,3646,3645 ,730,730,730 ,0,0,0}, {3489,3308,3306 ,730,730,730 ,0,0,0}, + {3281,3499,3501 ,730,730,730 ,0,0,0}, {3490,3311,3308 ,730,730,730 ,0,0,0}, + {3273,3840,3841 ,730,730,730 ,0,0,0}, {3493,3312,3311 ,730,730,730 ,0,0,0}, + {3078,3081,3058 ,730,730,730 ,0,0,0}, {3052,3086,3053 ,730,730,730 ,0,0,0}, + {3317,3499,3282 ,730,730,730 ,0,0,0}, {3236,3505,3507 ,730,730,730 ,0,0,0}, + {3242,3240,3508 ,730,730,730 ,0,0,0}, {3055,3077,3078 ,730,730,730 ,0,0,0}, + {3230,3564,3562 ,730,730,730 ,0,0,0}, {3842,3256,3843 ,730,730,730 ,0,0,0}, + {3505,3236,3243 ,730,730,730 ,0,0,0}, {3224,3555,3552 ,730,730,730 ,0,0,0}, + {3606,3030,3027 ,730,730,730 ,0,0,0}, {3844,3609,3831 ,730,730,730 ,0,0,0}, + {3611,3831,3609 ,730,730,730 ,0,0,0}, {3609,3844,3030 ,730,730,730 ,0,0,0}, + {3845,3846,3847 ,730,730,730 ,0,0,0}, {3609,3030,3606 ,730,730,730 ,0,0,0}, + {3605,3606,3027 ,730,730,730 ,0,0,0}, {3007,3072,3005 ,730,730,730 ,0,0,0}, + {3838,3827,3192 ,730,730,730 ,0,0,0}, {3848,3849,3850 ,730,730,730 ,0,0,0}, + {3512,3570,3216 ,730,730,730 ,0,0,0}, {3202,3526,3207 ,730,730,730 ,0,0,0}, + {3543,3218,3221 ,730,730,730 ,0,0,0}, {3556,3227,3229 ,730,730,730 ,0,0,0}, + {3556,3555,3227 ,730,730,730 ,0,0,0}, {3558,3229,3561 ,730,730,730 ,0,0,0}, + {3552,3550,3224 ,730,730,730 ,0,0,0}, {3550,3549,3223 ,730,730,730 ,0,0,0}, + {3218,3543,3540 ,730,730,730 ,0,0,0}, {3534,3532,3201 ,730,730,730 ,0,0,0}, + {3201,3531,3202 ,730,730,730 ,0,0,0}, {3526,3525,3207 ,730,730,730 ,0,0,0}, + {3520,3519,3211 ,730,730,730 ,0,0,0}, {3516,3212,3211 ,730,730,730 ,0,0,0}, + {3561,3230,3562 ,730,730,730 ,0,0,0}, {3514,3513,3212 ,730,730,730 ,0,0,0}, + {3570,3217,3216 ,730,730,730 ,0,0,0}, {3573,3575,3217 ,730,730,730 ,0,0,0}, + {3581,3851,3824 ,730,730,730 ,0,0,0}, {3851,3581,3582 ,730,730,730 ,0,0,0}, + {3070,3851,3585 ,730,730,730 ,0,0,0}, {3016,3588,3591 ,730,730,730 ,0,0,0}, + {3019,3018,3594 ,730,730,730 ,0,0,0}, {3016,2997,3588 ,730,730,730 ,0,0,0}, + {3582,3585,3851 ,730,730,730 ,0,0,0}, {3579,3581,3824 ,730,730,730 ,0,0,0}, + {3575,3576,3828 ,730,730,730 ,0,0,0}, {3576,3824,3828 ,730,730,730 ,0,0,0}, + {3570,3573,3217 ,730,730,730 ,0,0,0}, {3513,3216,3212 ,730,730,730 ,0,0,0}, + {3516,3211,3519 ,730,730,730 ,0,0,0}, {3209,3207,3522 ,730,730,730 ,0,0,0}, + {3209,3522,3520 ,730,730,730 ,0,0,0}, {3202,3528,3526 ,730,730,730 ,0,0,0}, + {3201,3532,3531 ,730,730,730 ,0,0,0}, {3205,3537,3534 ,730,730,730 ,0,0,0}, + {3218,3540,3538 ,730,730,730 ,0,0,0}, {3221,3544,3543 ,730,730,730 ,0,0,0}, + {3223,3549,3546 ,730,730,730 ,0,0,0}, {3223,3224,3550 ,730,730,730 ,0,0,0}, + {3224,3227,3555 ,730,730,730 ,0,0,0}, {3229,3558,3556 ,730,730,730 ,0,0,0}, + {3229,3230,3561 ,730,730,730 ,0,0,0}, {3230,3242,3564 ,730,730,730 ,0,0,0}, + {3242,3508,3567 ,730,730,730 ,0,0,0}, {3564,3242,3567 ,730,730,730 ,0,0,0}, + {3508,3240,3237 ,730,730,730 ,0,0,0}, {3237,3233,3507 ,730,730,730 ,0,0,0}, + {3507,3508,3237 ,730,730,730 ,0,0,0}, {3059,3058,3081 ,730,730,730 ,0,0,0}, + {3236,3507,3233 ,730,730,730 ,0,0,0}, {3038,3248,3249 ,730,730,730 ,0,0,0}, + {3059,3081,3083 ,730,730,730 ,0,0,0}, {3084,3257,3064 ,730,730,730 ,0,0,0}, + {3083,3061,3059 ,730,730,730 ,0,0,0}, {3084,3064,3061 ,730,730,730 ,0,0,0}, + {3265,3852,3258 ,730,730,730 ,0,0,0}, {3261,3853,3253 ,730,730,730 ,0,0,0}, + {3854,3266,3855 ,730,730,730 ,0,0,0}, {3273,3856,3855 ,730,730,730 ,0,0,0}, + {3088,3050,3091 ,730,730,730 ,0,0,0}, {3857,3272,3858 ,730,730,730 ,0,0,0}, + {3052,3050,3088 ,730,730,730 ,0,0,0}, {3501,3276,3279 ,730,730,730 ,0,0,0}, + {3502,3275,3276 ,730,730,730 ,0,0,0}, {3041,3248,3039 ,730,730,730 ,0,0,0}, + {3249,3035,3038 ,730,730,730 ,0,0,0}, {3041,3048,3246 ,730,730,730 ,0,0,0}, + {3269,3275,3502 ,730,730,730 ,0,0,0}, {3269,3502,3505 ,730,730,730 ,0,0,0}, + {3276,3501,3502 ,730,730,730 ,0,0,0}, {3281,3501,3279 ,730,730,730 ,0,0,0}, + {3282,3499,3281 ,730,730,730 ,0,0,0}, {3496,3499,3317 ,730,730,730 ,0,0,0}, + {3314,3496,3317 ,730,730,730 ,0,0,0}, {3312,3495,3314 ,730,730,730 ,0,0,0}, + {3361,3750,3363 ,730,730,730 ,0,0,0}, {3753,3363,3752 ,730,730,730 ,0,0,0}, + {3296,3478,3299 ,730,730,730 ,0,0,0}, {3756,3364,3753 ,730,730,730 ,0,0,0}, + {3756,3367,3364 ,730,730,730 ,0,0,0}, {3758,3368,3367 ,730,730,730 ,0,0,0}, + {3750,3361,3747 ,730,730,730 ,0,0,0}, {3759,3374,3368 ,730,730,730 ,0,0,0}, + {3752,3363,3750 ,730,730,730 ,0,0,0}, {3286,3433,3287 ,730,730,730 ,0,0,0}, + {3370,3374,3762 ,730,730,730 ,0,0,0}, {3364,3363,3753 ,730,730,730 ,0,0,0}, + {3371,3370,3764 ,730,730,730 ,0,0,0}, {3756,3758,3367 ,730,730,730 ,0,0,0}, + {3377,3371,3765 ,730,730,730 ,0,0,0}, {3325,3444,3443 ,730,730,730 ,0,0,0}, + {3323,3443,3441 ,730,730,730 ,0,0,0}, {3374,3759,3762 ,730,730,730 ,0,0,0}, + {3378,3377,3768 ,730,730,730 ,0,0,0}, {3378,3768,3770 ,730,730,730 ,0,0,0}, + {3762,3764,3370 ,730,730,730 ,0,0,0}, {3331,3451,3448 ,730,730,730 ,0,0,0}, + {3371,3764,3765 ,730,730,730 ,0,0,0}, {3770,3771,3381 ,730,730,730 ,0,0,0}, + {3774,3387,3771 ,730,730,730 ,0,0,0}, {3765,3768,3377 ,730,730,730 ,0,0,0}, + {3381,3378,3770 ,730,730,730 ,0,0,0}, {3776,3385,3774 ,730,730,730 ,0,0,0}, + {3335,3337,3458 ,730,730,730 ,0,0,0}, {3777,3383,3776 ,730,730,730 ,0,0,0}, + {3387,3381,3771 ,730,730,730 ,0,0,0}, {3341,3343,3462 ,730,730,730 ,0,0,0}, + {3774,3385,3387 ,730,730,730 ,0,0,0}, {3777,3780,3388 ,730,730,730 ,0,0,0}, + {3344,3347,3464 ,730,730,730 ,0,0,0}, {3776,3383,3385 ,730,730,730 ,0,0,0}, + {3390,3388,3780 ,730,730,730 ,0,0,0}, {3390,3782,3353 ,730,730,730 ,0,0,0}, + {3465,3349,3468 ,730,730,730 ,0,0,0}, {3390,3780,3782 ,730,730,730 ,0,0,0}, + {3432,3352,3353 ,730,730,730 ,0,0,0}, {3470,3352,3432 ,730,730,730 ,0,0,0}, + {3782,3430,3353 ,730,730,730 ,0,0,0}, {3432,3353,3430 ,730,730,730 ,0,0,0}, + {3777,3388,3383 ,730,730,730 ,0,0,0}, {3393,3395,3712 ,730,730,730 ,0,0,0}, + {3727,3408,3728 ,730,730,730 ,0,0,0}, {3740,3420,3423 ,730,730,730 ,0,0,0}, + {3702,3426,3132 ,730,730,730 ,0,0,0}, {3706,3745,3426 ,730,730,730 ,0,0,0}, + {3053,3085,3055 ,730,730,730 ,0,0,0}, {3859,3261,3263 ,730,730,730 ,0,0,0}, + {3265,3854,3852 ,730,730,730 ,0,0,0}, {3055,3078,3058 ,730,730,730 ,0,0,0}, + {3055,3085,3077 ,730,730,730 ,0,0,0}, {3053,3086,3085 ,730,730,730 ,0,0,0}, + {3052,3088,3086 ,730,730,730 ,0,0,0}, {3267,3269,3860 ,730,730,730 ,0,0,0}, + {3031,3037,3091 ,730,730,730 ,0,0,0}, {3031,3091,3050 ,730,730,730 ,0,0,0}, + {3249,3037,3035 ,730,730,730 ,0,0,0}, {3037,3249,3091 ,730,730,730 ,0,0,0}, + {3044,3269,3505 ,730,730,730 ,0,0,0}, {3041,3246,3248 ,730,730,730 ,0,0,0}, + {3038,3039,3248 ,730,730,730 ,0,0,0}, {3045,3246,3048 ,730,730,730 ,0,0,0}, + {3505,3045,3044 ,730,730,730 ,0,0,0}, {3243,3045,3505 ,730,730,730 ,0,0,0}, + {3045,3243,3246 ,730,730,730 ,0,0,0}, {3044,3860,3269 ,730,730,730 ,0,0,0}, + {3267,3858,3272 ,730,730,730 ,0,0,0}, {3860,3858,3267 ,730,730,730 ,0,0,0}, + {3272,3840,3273 ,730,730,730 ,0,0,0}, {3857,3840,3272 ,730,730,730 ,0,0,0}, + {3841,3856,3273 ,730,730,730 ,0,0,0}, {3855,3266,3273 ,730,730,730 ,0,0,0}, + {3854,3265,3266 ,730,730,730 ,0,0,0}, {3861,3258,3852 ,730,730,730 ,0,0,0}, + {3263,3861,3859 ,730,730,730 ,0,0,0}, {3861,3263,3258 ,730,730,730 ,0,0,0}, + {3859,3862,3261 ,730,730,730 ,0,0,0}, {3853,3843,3253 ,730,730,730 ,0,0,0}, + {3862,3853,3261 ,730,730,730 ,0,0,0}, {3256,3842,3257 ,730,730,730 ,0,0,0}, + {3253,3843,3256 ,730,730,730 ,0,0,0}, {3064,3257,3842 ,730,730,730 ,0,0,0}, + {3068,3070,3003 ,730,730,730 ,0,0,0}, {3600,3603,3025 ,730,730,730 ,0,0,0}, + {3187,3184,3863 ,730,730,730 ,0,0,0}, {3019,3594,3597 ,730,730,730 ,0,0,0}, + {3597,3021,3019 ,730,730,730 ,0,0,0}, {3593,3594,3018 ,730,730,730 ,0,0,0}, + {3593,3016,3591 ,730,730,730 ,0,0,0}, {3016,3593,3018 ,730,730,730 ,0,0,0}, + {3588,2997,3587 ,730,730,730 ,0,0,0}, {2997,3003,3070 ,730,730,730 ,0,0,0}, + {3003,3001,3068 ,730,730,730 ,0,0,0}, {3001,3004,3065 ,730,730,730 ,0,0,0}, + {3005,3072,3065 ,730,730,730 ,0,0,0}, {3014,3072,3007 ,730,730,730 ,0,0,0}, + {3011,3074,3014 ,730,730,730 ,0,0,0}, {3010,3199,3011 ,730,730,730 ,0,0,0}, + {3836,3197,3010 ,730,730,730 ,0,0,0}, {3829,3194,3836 ,730,730,730 ,0,0,0}, + {3838,3193,3829 ,730,730,730 ,0,0,0}, {3177,3192,3827 ,730,730,730 ,0,0,0}, + {3837,3178,3827 ,730,730,730 ,0,0,0}, {3839,3182,3837 ,730,730,730 ,0,0,0}, + {3863,3184,3839 ,730,730,730 ,0,0,0}, {3864,3189,3835 ,730,730,730 ,0,0,0}, + {3835,3187,3863 ,730,730,730 ,0,0,0}, {3188,3864,3850 ,730,730,730 ,0,0,0}, + {3864,3188,3189 ,730,730,730 ,0,0,0}, {3848,3833,3849 ,730,730,730 ,0,0,0}, + {3188,3850,3849 ,730,730,730 ,0,0,0}, {3832,3834,3845 ,730,730,730 ,0,0,0}, + {3849,3833,3832 ,730,730,730 ,0,0,0}, {3845,3847,3844 ,730,730,730 ,0,0,0}, + {3845,3834,3846 ,730,730,730 ,0,0,0}, {3030,3844,3847 ,730,730,730 ,0,0,0}, + {3844,3831,3794 ,3296,3297,3298 ,0,0,0}, {3845,3787,3791 ,3299,3300,3301 ,0,0,0}, + {3787,3844,3794 ,3300,3296,3298 ,0,0,0}, {3844,3787,3845 ,3296,3300,3299 ,0,0,0}, + {3849,3816,3799 ,3302,3303,3304 ,0,0,0}, {3845,3791,3832 ,3299,3301,3305 ,0,0,0}, + {3849,3832,3816 ,3302,3305,3303 ,0,0,0}, {3799,3190,3188 ,3304,2732,2732 ,0,0,0}, + {3799,3188,3849 ,3304,2732,3302 ,0,0,0}, {3816,3832,3791 ,3303,3305,3301 ,0,0,0}, + {3831,3783,3794 ,3297,3306,3298 ,0,0,0}, {3795,3783,3830 ,3307,3306,3308 ,0,0,0}, + {3831,3830,3783 ,3297,3308,3306 ,0,0,0}, {3826,3796,3795 ,3309,3310,3307 ,0,0,0}, + {3795,3830,3826 ,3307,3308,3309 ,0,0,0}, {3796,3825,3176 ,3310,3311,2722 ,0,0,0}, + {3825,3796,3826 ,3311,3310,3309 ,0,0,0}, {3825,3175,3176 ,3311,2722,2722 ,0,0,0}, + {3071,3788,3851 ,2635,3312,3312 ,0,0,0}, {3784,3217,3828 ,3313,2758,3314 ,0,0,0}, + {3828,3824,3785 ,3314,3315,3315 ,0,0,0}, {3215,3217,3784 ,2758,2758,3313 ,0,0,0}, + {3788,3824,3851 ,3312,3315,3312 ,0,0,0}, {3824,3788,3785 ,3315,3312,3315 ,0,0,0}, + {3784,3828,3785 ,3313,3314,3315 ,0,0,0}, {3851,3070,3071 ,3312,2635,2635 ,0,0,0}, + {3049,3814,3860 ,3316,795,3317 ,0,0,0}, {3812,3840,3813 ,3318,3319,3320 ,0,0,0}, + {3857,3858,3806 ,3321,3322,857 ,0,0,0}, {3855,3822,3854 ,3323,3324,21 ,0,0,0}, + {3811,3810,3856 ,3325,3326,3327 ,0,0,0}, {3808,3859,3861 ,3328,3329,3330 ,0,0,0}, + {3807,3852,3809 ,3331,3332,3333 ,0,0,0}, {3801,3853,3862 ,3334,3335,3336 ,0,0,0}, + {3862,3859,3803 ,3336,3329,3337 ,0,0,0}, {3853,3802,3843 ,3335,3338,3339 ,0,0,0}, + {3802,3853,3801 ,3338,3335,3334 ,0,0,0}, {3842,3843,3805 ,3340,3339,3341 ,0,0,0}, + {3802,3805,3843 ,3338,3341,3339 ,0,0,0}, {3804,3064,3842 ,3342,82,3340 ,0,0,0}, + {3842,3805,3804 ,3340,3341,3342 ,0,0,0}, {3063,3064,3804 ,3343,82,3342 ,0,0,0}, + {3807,3808,3861 ,3331,3328,3330 ,0,0,0}, {3859,3808,3803 ,3329,3328,3337 ,0,0,0}, + {3801,3862,3803 ,3334,3336,3337 ,0,0,0}, {3807,3861,3852 ,3331,3330,3332 ,0,0,0}, + {3809,3852,3854 ,3333,3332,21 ,0,0,0}, {3822,3855,3810 ,3324,3323,3326 ,0,0,0}, + {3822,3809,3854 ,3324,3333,21 ,0,0,0}, {3811,3856,3841 ,3325,3327,3344 ,0,0,0}, + {3856,3810,3855 ,3327,3326,3323 ,0,0,0}, {3841,3840,3812 ,3344,3319,3318 ,0,0,0}, + {3841,3812,3811 ,3344,3318,3325 ,0,0,0}, {3806,3813,3857 ,857,3320,3321 ,0,0,0}, + {3840,3857,3813 ,3319,3321,3320 ,0,0,0}, {3858,3814,3806 ,3322,795,857 ,0,0,0}, + {3049,3860,3044 ,3316,3317,3345 ,0,0,0}, {3814,3858,3860 ,795,3322,3317 ,0,0,0}, + {3015,3823,3836 ,3346,3347,3348 ,0,0,0}, {3793,3827,3797 ,3349,3350,3351 ,0,0,0}, + {3838,3829,3821 ,3321,801,857 ,0,0,0}, {3863,3817,3835 ,3352,3353,21 ,0,0,0}, + {3792,3819,3839 ,3354,807,3355 ,0,0,0}, {3820,3848,3850 ,3356,3357,3358 ,0,0,0}, + {3789,3864,3818 ,3359,3360,21 ,0,0,0}, {3800,3834,3833 ,3361,3362,3363 ,0,0,0}, + {3833,3848,3798 ,3363,3357,3364 ,0,0,0}, {3834,3815,3846 ,3362,3365,3366 ,0,0,0}, + {3815,3834,3800 ,3365,3362,3361 ,0,0,0}, {3847,3846,3790 ,3367,3366,3368 ,0,0,0}, + {3815,3790,3846 ,3365,3368,3366 ,0,0,0}, {3786,3030,3847 ,3369,3370,3367 ,0,0,0}, + {3847,3790,3786 ,3367,3368,3369 ,0,0,0}, {3029,3030,3786 ,3371,3370,3369 ,0,0,0}, + {3789,3820,3850 ,3359,3356,3358 ,0,0,0}, {3848,3820,3798 ,3357,3356,3364 ,0,0,0}, + {3800,3833,3798 ,3361,3363,3364 ,0,0,0}, {3789,3850,3864 ,3359,3358,3360 ,0,0,0}, + {3818,3864,3835 ,21,3360,21 ,0,0,0}, {3817,3863,3819 ,3353,3352,807 ,0,0,0}, + {3817,3818,3835 ,3353,21,21 ,0,0,0}, {3792,3839,3837 ,3354,3355,3372 ,0,0,0}, + {3839,3819,3863 ,3355,807,3352 ,0,0,0}, {3837,3827,3793 ,3372,3350,3349 ,0,0,0}, + {3837,3793,3792 ,3372,3349,3354 ,0,0,0}, {3821,3797,3838 ,857,3351,3321 ,0,0,0}, + {3827,3838,3797 ,3350,3321,3351 ,0,0,0}, {3829,3823,3821 ,801,3347,857 ,0,0,0}, + {3015,3836,3010 ,3346,3348,126 ,0,0,0}, {3823,3829,3836 ,3347,801,3348 ,0,0,0} +// BladeProtector2.prt + , {3865,3866,3867 ,21,3324,3333 ,0,0,0}, {3868,3869,3870 ,3328,3330,3331 ,0,0,0}, + {3871,3865,3867 ,3332,21,3333 ,0,0,0}, {3870,3869,3871 ,3331,3330,3332 ,0,0,0}, + {3869,3868,3872 ,3330,3328,3329 ,0,0,0}, {3867,3870,3871 ,3333,3331,3332 ,0,0,0}, + {3873,3874,3875 ,3336,3334,3335 ,0,0,0}, {3874,3876,3875 ,3334,3338,3335 ,0,0,0}, + {3872,3877,3873 ,3329,3337,3336 ,0,0,0}, {3874,3873,3877 ,3334,3336,3337 ,0,0,0}, + {3878,3879,3880 ,82,3340,3342 ,0,0,0}, {3881,3882,3876 ,3341,3339,3338 ,0,0,0}, + {3879,3882,3881 ,3340,3339,3341 ,0,0,0}, {3879,3881,3880 ,3340,3341,3342 ,0,0,0}, + {3880,3883,3878 ,3342,3343,82 ,0,0,0}, {3875,3876,3882 ,3335,3338,3339 ,0,0,0}, + {3872,3868,3877 ,3329,3328,3337 ,0,0,0}, {3865,3884,3866 ,21,3323,3324 ,0,0,0}, + {3885,3884,3886 ,3326,3323,3327 ,0,0,0}, {3884,3885,3866 ,3323,3326,3324 ,0,0,0}, + {3887,3888,3886 ,3344,3325,3327 ,0,0,0}, {3885,3886,3888 ,3326,3327,3325 ,0,0,0}, + {3887,3889,3890 ,3344,3319,3318 ,0,0,0}, {3890,3888,3887 ,3318,3325,3344 ,0,0,0}, + {3891,3889,3892 ,3320,3319,3321 ,0,0,0}, {3889,3891,3890 ,3319,3320,3318 ,0,0,0}, + {3893,3894,3892 ,3322,857,3321 ,0,0,0}, {3891,3892,3894 ,3320,3321,857 ,0,0,0}, + {3893,3895,3896 ,3322,3317,795 ,0,0,0}, {3896,3894,3893 ,795,857,3322 ,0,0,0}, + {3897,3895,3898 ,3316,3317,3345 ,0,0,0}, {3895,3897,3896 ,3317,3316,795 ,0,0,0}, + {3899,3900,3901 ,21,3353,21 ,0,0,0}, {3902,3903,3904 ,3356,3358,3359 ,0,0,0}, + {3905,3899,3901 ,3360,21,21 ,0,0,0}, {3904,3903,3905 ,3359,3358,3360 ,0,0,0}, + {3903,3902,3906 ,3358,3356,3357 ,0,0,0}, {3901,3904,3905 ,21,3359,3360 ,0,0,0}, + {3907,3908,3909 ,3363,3361,3362 ,0,0,0}, {3908,3910,3909 ,3361,3365,3362 ,0,0,0}, + {3906,3911,3907 ,3357,3364,3363 ,0,0,0}, {3908,3907,3911 ,3361,3363,3364 ,0,0,0}, + {3912,3913,3914 ,3370,3367,3369 ,0,0,0}, {3915,3916,3910 ,3368,3366,3365 ,0,0,0}, + {3913,3916,3915 ,3367,3366,3368 ,0,0,0}, {3913,3915,3914 ,3367,3368,3369 ,0,0,0}, + {3914,3917,3912 ,3369,3371,3370 ,0,0,0}, {3909,3910,3916 ,3362,3365,3366 ,0,0,0}, + {3906,3902,3911 ,3357,3356,3364 ,0,0,0}, {3899,3918,3900 ,21,3352,3353 ,0,0,0}, + {3919,3918,3920 ,807,3352,3355 ,0,0,0}, {3918,3919,3900 ,3352,807,3353 ,0,0,0}, + {3921,3922,3920 ,3372,3354,3355 ,0,0,0}, {3919,3920,3922 ,807,3355,3354 ,0,0,0}, + {3921,3923,3924 ,3372,3350,3349 ,0,0,0}, {3924,3922,3921 ,3349,3354,3372 ,0,0,0}, + {3925,3923,3926 ,3351,3350,3321 ,0,0,0}, {3923,3925,3924 ,3350,3351,3349 ,0,0,0}, + {3927,3928,3926 ,801,857,3321 ,0,0,0}, {3925,3926,3928 ,3351,3321,857 ,0,0,0}, + {3927,3929,3930 ,801,3348,3347 ,0,0,0}, {3930,3928,3927 ,3347,857,801 ,0,0,0}, + {3931,3929,3932 ,3346,3348,126 ,0,0,0}, {3929,3931,3930 ,3348,3346,3347 ,0,0,0}, + {3933,3934,3935 ,3373,3374,3373 ,0,0,0}, {3936,3937,3938 ,3375,3376,3377 ,0,0,0}, + {3936,3935,3937 ,3375,3373,3376 ,0,0,0}, {3938,3937,3939 ,3377,3376,3377 ,0,0,0}, + {3935,3936,3933 ,3373,3375,3373 ,0,0,0}, {3940,3934,3933 ,3374,3374,3373 ,0,0,0}, + {3941,3940,3942 ,3378,3374,3378 ,0,0,0}, {3940,3941,3934 ,3374,3378,3374 ,0,0,0}, + {3943,3944,3945 ,2038,2043,2038 ,0,0,0}, {3946,3944,3947 ,2043,2043,2041 ,0,0,0}, + {3944,3946,3945 ,2043,2043,2038 ,0,0,0}, {3948,3949,3947 ,2042,2041,2041 ,0,0,0}, + {3946,3947,3949 ,2043,2041,2041 ,0,0,0}, {3948,3950,3951 ,2042,3379,2042 ,0,0,0}, + {3951,3949,3948 ,2042,2041,2042 ,0,0,0}, {3950,3952,3951 ,3379,3380,2042 ,0,0,0}, + {3953,3943,3945 ,2039,2038,2038 ,0,0,0}, {3954,3955,3953 ,2040,2039,2039 ,0,0,0}, + {3943,3953,3955 ,2038,2039,2039 ,0,0,0}, {3954,3956,3957 ,2040,2035,2040 ,0,0,0}, + {3957,3955,3954 ,2040,2039,2040 ,0,0,0}, {3958,3956,3959 ,2035,2035,3381 ,0,0,0}, + {3956,3958,3957 ,2035,2035,2040 ,0,0,0}, {3958,3959,3960 ,2035,3381,3382 ,0,0,0}, + {3961,3962,3963 ,3383,3384,3385 ,0,0,0}, {3964,3965,3961 ,3386,3387,3383 ,0,0,0}, + {3961,3963,3964 ,3383,3385,3386 ,0,0,0}, {3965,3966,3967 ,3387,3388,3389 ,0,0,0}, + {3966,3965,3964 ,3388,3387,3386 ,0,0,0}, {3968,3967,3969 ,3390,3389,3391 ,0,0,0}, + {3966,3969,3967 ,3388,3391,3389 ,0,0,0}, {3970,3971,3968 ,3392,3393,3390 ,0,0,0}, + {3968,3969,3970 ,3390,3391,3392 ,0,0,0}, {3971,3972,3973 ,3393,3394,3395 ,0,0,0}, + {3972,3971,3970 ,3394,3393,3392 ,0,0,0}, {3974,3973,3975 ,3396,3395,3397 ,0,0,0}, + {3972,3975,3973 ,3394,3397,3395 ,0,0,0}, {3976,3977,3974 ,3398,3399,3396 ,0,0,0}, + {3974,3975,3976 ,3396,3397,3398 ,0,0,0}, {3977,3978,3979 ,3399,3400,3401 ,0,0,0}, + {3978,3977,3976 ,3400,3399,3398 ,0,0,0}, {3980,3979,3981 ,3402,3401,3403 ,0,0,0}, + {3978,3981,3979 ,3400,3403,3401 ,0,0,0}, {3982,3983,3980 ,3404,3405,3402 ,0,0,0}, + {3980,3981,3982 ,3402,3403,3404 ,0,0,0}, {3983,3984,3985 ,3405,3406,3407 ,0,0,0}, + {3984,3983,3982 ,3406,3405,3404 ,0,0,0}, {3986,3985,3987 ,3408,3407,3409 ,0,0,0}, + {3984,3987,3985 ,3406,3409,3407 ,0,0,0}, {3988,3989,3986 ,3410,3411,3408 ,0,0,0}, + {3986,3987,3988 ,3408,3409,3410 ,0,0,0}, {3989,3990,3991 ,3411,3412,3413 ,0,0,0}, + {3990,3989,3988 ,3412,3411,3410 ,0,0,0}, {3992,3991,3993 ,3414,3413,3415 ,0,0,0}, + {3990,3993,3991 ,3412,3415,3413 ,0,0,0}, {3994,3995,3992 ,3416,3417,3414 ,0,0,0}, + {3992,3993,3994 ,3414,3415,3416 ,0,0,0}, {3995,3996,3997 ,3417,3418,3419 ,0,0,0}, + {3996,3995,3994 ,3418,3417,3416 ,0,0,0}, {3998,3997,3999 ,3420,3419,3421 ,0,0,0}, + {3996,3999,3997 ,3418,3421,3419 ,0,0,0}, {4000,4001,3998 ,3422,3422,3420 ,0,0,0}, + {3998,3999,4000 ,3420,3421,3422 ,0,0,0}, {3963,3962,4002 ,3385,3384,3423 ,0,0,0}, + {4003,4002,4004 ,3424,3423,3425 ,0,0,0}, {3962,4004,4002 ,3384,3425,3423 ,0,0,0}, + {4005,4006,4003 ,3426,3427,3424 ,0,0,0}, {4003,4004,4005 ,3424,3425,3426 ,0,0,0}, + {4006,4007,4008 ,3427,3428,3429 ,0,0,0}, {4007,4006,4005 ,3428,3427,3426 ,0,0,0}, + {4009,4008,4010 ,3430,3429,3431 ,0,0,0}, {4007,4010,4008 ,3428,3431,3429 ,0,0,0}, + {4011,4012,4009 ,3432,3433,3430 ,0,0,0}, {4009,4010,4011 ,3430,3431,3432 ,0,0,0}, + {4012,4013,4014 ,3433,3434,3435 ,0,0,0}, {4013,4012,4011 ,3434,3433,3432 ,0,0,0}, + {4015,4014,4016 ,3436,3435,3437 ,0,0,0}, {4013,4016,4014 ,3434,3437,3435 ,0,0,0}, + {4017,4018,4015 ,3438,3439,3436 ,0,0,0}, {4015,4016,4017 ,3436,3437,3438 ,0,0,0}, + {4018,4019,4020 ,3439,3440,3441 ,0,0,0}, {4019,4018,4017 ,3440,3439,3438 ,0,0,0}, + {4021,4020,4022 ,3442,3441,3443 ,0,0,0}, {4019,4022,4020 ,3440,3443,3441 ,0,0,0}, + {4023,4024,4021 ,3444,3445,3442 ,0,0,0}, {4021,4022,4023 ,3442,3443,3444 ,0,0,0}, + {4024,4025,4026 ,3445,3446,3447 ,0,0,0}, {4025,4024,4023 ,3446,3445,3444 ,0,0,0}, + {4027,4026,4028 ,3448,3447,3449 ,0,0,0}, {4025,4028,4026 ,3446,3449,3447 ,0,0,0}, + {4029,4030,4027 ,3450,3451,3448 ,0,0,0}, {4027,4028,4029 ,3448,3449,3450 ,0,0,0}, + {4030,4031,4032 ,3451,3452,3453 ,0,0,0}, {4031,4030,4029 ,3452,3451,3450 ,0,0,0}, + {4033,4032,4034 ,3454,3453,3455 ,0,0,0}, {4031,4034,4032 ,3452,3455,3453 ,0,0,0}, + {4035,4036,4033 ,3456,3457,3454 ,0,0,0}, {4033,4034,4035 ,3454,3455,3456 ,0,0,0}, + {4036,4037,4038 ,3457,3458,3459 ,0,0,0}, {4037,4036,4035 ,3458,3457,3456 ,0,0,0}, + {4037,4039,4038 ,3458,3460,3459 ,0,0,0}, {4038,4039,4040 ,3459,3460,3461 ,0,0,0}, + {4041,4042,4039 ,3462,3462,3463 ,0,0,0}, {4041,4043,4042 ,3462,3464,3462 ,0,0,0}, + {4043,4041,4044 ,3464,3462,3464 ,0,0,0}, {4040,4039,4042 ,126,3463,3462 ,0,0,0}, + {4045,4046,4047 ,1273,3465,1273 ,0,0,0}, {4048,4049,4046 ,3466,3467,3465 ,0,0,0}, + {4046,4049,4047 ,3465,3467,1273 ,0,0,0}, {4050,4051,4048 ,3468,3469,3466 ,0,0,0}, + {4048,4046,4050 ,3466,3465,3468 ,0,0,0}, {4051,4052,4053 ,3469,3470,3471 ,0,0,0}, + {4052,4051,4050 ,3470,3469,3468 ,0,0,0}, {4054,4053,4055 ,3472,3471,3473 ,0,0,0}, + {4052,4055,4053 ,3470,3473,3471 ,0,0,0}, {4056,4054,4057 ,3474,3472,3475 ,0,0,0}, + {4054,4055,4057 ,3472,3473,3475 ,0,0,0}, {4058,4054,4056 ,3474,3472,3474 ,0,0,0}, + {4059,4045,4047 ,3476,1273,1273 ,0,0,0}, {4060,4059,4061 ,3477,3476,3478 ,0,0,0}, + {4060,4045,4059 ,3477,1273,3476 ,0,0,0}, {4062,4061,4063 ,3479,3478,3480 ,0,0,0}, + {4059,4063,4061 ,3476,3480,3478 ,0,0,0}, {4064,4065,4062 ,3481,3482,3479 ,0,0,0}, + {4062,4063,4064 ,3479,3480,3481 ,0,0,0}, {4065,4066,4067 ,3482,3483,3484 ,0,0,0}, + {4066,4065,4064 ,3483,3482,3481 ,0,0,0}, {4067,4068,3941 ,3484,3485,3378 ,0,0,0}, + {4066,4068,4067 ,3483,3485,3484 ,0,0,0}, {4067,3941,3942 ,3484,3378,3378 ,0,0,0}, + {4069,4070,4071 ,3486,3487,3488 ,0,0,0}, {4069,4072,4073 ,3486,3489,3490 ,0,0,0}, + {4071,4070,4074 ,3488,3487,3491 ,0,0,0}, {4074,4070,4075 ,3491,3487,3492 ,0,0,0}, + {4074,4075,4076 ,3491,3492,3493 ,0,0,0}, {4077,4076,4075 ,3494,3493,3492 ,0,0,0}, + {4076,4077,4078 ,3493,3494,3495 ,0,0,0}, {4079,4078,4077 ,3496,3495,3494 ,0,0,0}, + {4079,4080,4081 ,3496,3497,3498 ,0,0,0}, {4078,4079,4081 ,3495,3496,3498 ,0,0,0}, + {4071,4072,4069 ,3488,3489,3486 ,0,0,0}, {4081,4080,4082 ,3498,3497,3499 ,0,0,0}, + {4083,4082,4084 ,3500,3499,3501 ,0,0,0}, {4084,4082,4080 ,3501,3499,3497 ,0,0,0}, + {4083,4084,4085 ,3500,3501,3500 ,0,0,0}, {4086,4073,4087 ,3502,3490,3503 ,0,0,0}, + {4072,4087,4073 ,3489,3503,3490 ,0,0,0}, {4088,4089,4086 ,3504,3505,3502 ,0,0,0}, + {4086,4087,4088 ,3502,3503,3504 ,0,0,0}, {4089,4090,4091 ,3505,3506,3507 ,0,0,0}, + {4090,4089,4088 ,3506,3505,3504 ,0,0,0}, {4092,4091,4093 ,3508,3507,3509 ,0,0,0}, + {4090,4093,4091 ,3506,3509,3507 ,0,0,0}, {4094,4095,4092 ,3510,3511,3508 ,0,0,0}, + {4092,4093,4094 ,3508,3509,3510 ,0,0,0}, {4095,4096,4097 ,3511,3512,3513 ,0,0,0}, + {4096,4095,4094 ,3512,3511,3510 ,0,0,0}, {4098,4097,4099 ,3514,3513,3515 ,0,0,0}, + {4096,4099,4097 ,3512,3515,3513 ,0,0,0}, {4098,4099,4100 ,3514,3515,3514 ,0,0,0}, + {4101,4102,4103 ,3516,3517,3516 ,0,0,0}, {4103,4104,4101 ,3516,3518,3516 ,0,0,0}, + {4105,4106,4102 ,3517,3519,3517 ,0,0,0}, {4107,4104,4103 ,3518,3518,3516 ,0,0,0}, + {4101,4105,4102 ,3516,3517,3517 ,0,0,0}, {4105,4108,4106 ,3517,3519,3519 ,0,0,0}, + {4109,4108,4110 ,3520,3519,3520 ,0,0,0}, {4110,4098,4100 ,3520,3514,3514 ,0,0,0}, + {4109,4106,4108 ,3520,3519,3519 ,0,0,0}, {4110,4100,4109 ,3520,3514,3520 ,0,0,0}, + {4111,4107,4112 ,3521,3518,3521 ,0,0,0}, {4107,4111,4104 ,3518,3521,3518 ,0,0,0}, + {4113,4114,4112 ,3522,3522,3521 ,0,0,0}, {4111,4112,4114 ,3521,3521,3522 ,0,0,0}, + {4113,4115,4116 ,3522,3523,3523 ,0,0,0}, {4116,4114,4113 ,3523,3522,3522 ,0,0,0}, + {4117,4115,4118 ,3524,3523,3524 ,0,0,0}, {4115,4117,4116 ,3523,3524,3523 ,0,0,0}, + {4117,4118,3959 ,3524,3524,3525 ,0,0,0}, {3959,4118,3960 ,3525,3524,3526 ,0,0,0}, + {4119,3952,3950 ,1122,3527,3528 ,0,0,0}, {4120,4121,4122 ,1114,1120,1120 ,0,0,0}, + {4123,4124,4125 ,1121,1121,1122 ,0,0,0}, {4126,4127,4128 ,1116,1116,1117 ,0,0,0}, + {4129,4130,4131 ,1114,1115,1115 ,0,0,0}, {4132,4133,4128 ,3529,1117,1117 ,0,0,0}, + {4126,4128,4133 ,1116,1117,1117 ,0,0,0}, {4134,4133,4132 ,3530,1117,3529 ,0,0,0}, + {4130,4127,4131 ,1115,1116,1115 ,0,0,0}, {4131,4127,4126 ,1115,1116,1116 ,0,0,0}, + {4129,4121,4120 ,1114,1120,1114 ,0,0,0}, {4129,4120,4130 ,1114,1114,1115 ,0,0,0}, + {4122,4124,4123 ,1120,1121,1121 ,0,0,0}, {4121,4124,4122 ,1120,1121,1120 ,0,0,0}, + {4119,4125,3952 ,1122,1122,3527 ,0,0,0}, {4123,4125,4119 ,1121,1122,1122 ,0,0,0}, + {4135,4136,4137 ,3531,3531,3532 ,0,0,0}, {4137,4136,4138 ,3532,3531,3532 ,0,0,0}, + {4136,4135,4139 ,3531,3531,3533 ,0,0,0}, {4140,4139,4135 ,3534,3533,3531 ,0,0,0}, + {4141,4142,4140 ,3535,3535,3534 ,0,0,0}, {4143,4137,4138 ,3536,3532,3532 ,0,0,0}, + {4134,4132,4141 ,3537,3538,3535 ,0,0,0}, {4142,4141,4132 ,3535,3535,3538 ,0,0,0}, + {4140,4142,4139 ,3534,3535,3533 ,0,0,0}, {4144,4143,4145 ,3539,3536,3536 ,0,0,0}, + {4138,4145,4143 ,3532,3536,3536 ,0,0,0}, {4146,4147,4144 ,3539,3540,3539 ,0,0,0}, + {4144,4145,4146 ,3539,3536,3539 ,0,0,0}, {4147,4148,4149 ,3540,3540,3541 ,0,0,0}, + {4148,4147,4146 ,3540,3540,3539 ,0,0,0}, {4150,4149,4151 ,3542,3541,3541 ,0,0,0}, + {4148,4151,4149 ,3540,3541,3541 ,0,0,0}, {4150,4151,4152 ,3542,3541,3542 ,0,0,0}, + {4153,4154,4155 ,3543,3543,3544 ,0,0,0}, {4156,4157,4155 ,3545,3546,3544 ,0,0,0}, + {4153,4155,4157 ,3543,3544,3546 ,0,0,0}, {4156,4158,4159 ,3545,3547,3548 ,0,0,0}, + {4159,4157,4156 ,3548,3546,3545 ,0,0,0}, {4160,4158,4161 ,3549,3547,3550 ,0,0,0}, + {4158,4160,4159 ,3547,3549,3548 ,0,0,0}, {4162,4163,4161 ,3551,3552,3550 ,0,0,0}, + {4160,4161,4163 ,3549,3550,3552 ,0,0,0}, {4162,4164,4165 ,3551,3553,3554 ,0,0,0}, + {4165,4163,4162 ,3554,3552,3551 ,0,0,0}, {4166,4164,4167 ,3555,3553,3556 ,0,0,0}, + {4164,4166,4165 ,3553,3555,3554 ,0,0,0}, {4168,4169,4167 ,3557,3558,3556 ,0,0,0}, + {4166,4167,4169 ,3555,3556,3558 ,0,0,0}, {4168,4170,4171 ,3557,3559,3560 ,0,0,0}, + {4171,4169,4168 ,3560,3558,3557 ,0,0,0}, {4172,4170,4173 ,3561,3559,3562 ,0,0,0}, + {4170,4172,4171 ,3559,3561,3560 ,0,0,0}, {4174,4175,4173 ,3563,3564,3562 ,0,0,0}, + {4172,4173,4175 ,3561,3562,3564 ,0,0,0}, {4174,4176,4177 ,3563,3565,3566 ,0,0,0}, + {4177,4175,4174 ,3566,3564,3563 ,0,0,0}, {4178,4176,4179 ,3567,3565,3568 ,0,0,0}, + {4176,4178,4177 ,3565,3567,3566 ,0,0,0}, {4180,4181,4179 ,3569,3570,3568 ,0,0,0}, + {4178,4179,4181 ,3567,3568,3570 ,0,0,0}, {4180,4182,4183 ,3569,3571,3572 ,0,0,0}, + {4183,4181,4180 ,3572,3570,3569 ,0,0,0}, {4184,4182,4185 ,3573,3571,3574 ,0,0,0}, + {4182,4184,4183 ,3571,3573,3572 ,0,0,0}, {4150,4186,4185 ,3542,3575,3574 ,0,0,0}, + {4184,4185,4186 ,3573,3574,3575 ,0,0,0}, {4152,4186,4150 ,3542,3575,3542 ,0,0,0}, + {4187,4154,4153 ,3576,3543,3543 ,0,0,0}, {4188,4187,4189 ,3577,3576,3578 ,0,0,0}, + {4187,4188,4154 ,3576,3577,3543 ,0,0,0}, {4190,4191,4189 ,3579,3580,3578 ,0,0,0}, + {4188,4189,4191 ,3577,3578,3580 ,0,0,0}, {4190,4192,4193 ,3579,3581,3582 ,0,0,0}, + {4193,4191,4190 ,3582,3580,3579 ,0,0,0}, {4194,4192,4195 ,3583,3581,3584 ,0,0,0}, + {4192,4194,4193 ,3581,3583,3582 ,0,0,0}, {4196,4197,4195 ,3585,3586,3584 ,0,0,0}, + {4194,4195,4197 ,3583,3584,3586 ,0,0,0}, {4196,4198,4199 ,3585,3587,3588 ,0,0,0}, + {4199,4197,4196 ,3588,3586,3585 ,0,0,0}, {4200,4198,4201 ,3589,3587,3590 ,0,0,0}, + {4198,4200,4199 ,3587,3589,3588 ,0,0,0}, {4202,4203,4201 ,3591,3592,3590 ,0,0,0}, + {4200,4201,4203 ,3589,3590,3592 ,0,0,0}, {4202,4204,4205 ,3591,3593,3594 ,0,0,0}, + {4205,4203,4202 ,3594,3592,3591 ,0,0,0}, {4206,4204,4207 ,3595,3593,3596 ,0,0,0}, + {4204,4206,4205 ,3593,3595,3594 ,0,0,0}, {4208,4209,4207 ,3597,3598,3596 ,0,0,0}, + {4206,4207,4209 ,3595,3596,3598 ,0,0,0}, {4208,4210,4211 ,3597,3599,3600 ,0,0,0}, + {4211,4209,4208 ,3600,3598,3597 ,0,0,0}, {4212,4210,4213 ,3601,3599,3602 ,0,0,0}, + {4210,4212,4211 ,3599,3601,3600 ,0,0,0}, {4214,4215,4213 ,3603,3604,3602 ,0,0,0}, + {4212,4213,4215 ,3601,3602,3604 ,0,0,0}, {4214,4216,4217 ,3603,3605,3606 ,0,0,0}, + {4217,4215,4214 ,3606,3604,3603 ,0,0,0}, {4218,4216,4219 ,3607,3605,3608 ,0,0,0}, + {4216,4218,4217 ,3605,3607,3606 ,0,0,0}, {4218,4219,4220 ,3607,3608,3608 ,0,0,0}, + {4221,4219,4222 ,1398,3609,1398 ,0,0,0}, {4219,4221,4220 ,3609,1398,3609 ,0,0,0}, + {4223,4224,4225 ,3610,3611,3612 ,0,0,0}, {4226,4227,4228 ,3613,3614,3615 ,0,0,0}, + {4229,4223,4225 ,3616,3610,3612 ,0,0,0}, {4227,4225,4224 ,3614,3612,3611 ,0,0,0}, + {4230,4223,4229 ,3617,3610,3616 ,0,0,0}, {4231,4232,4233 ,3618,3619,3620 ,0,0,0}, + {4230,4229,4231 ,3617,3616,3618 ,0,0,0}, {4234,4232,4235 ,3621,3619,3622 ,0,0,0}, + {4231,4233,4230 ,3618,3620,3617 ,0,0,0}, {4232,4234,4233 ,3619,3621,3620 ,0,0,0}, + {4235,4236,4237 ,3622,3623,3624 ,0,0,0}, {4224,4228,4227 ,3611,3615,3614 ,0,0,0}, + {4238,4239,4240 ,3625,3626,3627 ,0,0,0}, {4241,4237,4236 ,3628,3624,3623 ,0,0,0}, + {4241,4242,4243 ,3628,3629,3630 ,0,0,0}, {4238,4240,4243 ,3625,3627,3630 ,0,0,0}, + {4238,4243,4242 ,3625,3630,3629 ,0,0,0}, {4240,4239,4244 ,3627,3626,3631 ,0,0,0}, + {4245,4246,4247 ,3632,3633,3634 ,0,0,0}, {4244,4245,4247 ,3631,3632,3634 ,0,0,0}, + {4245,4244,4239 ,3632,3631,3626 ,0,0,0}, {4246,4248,4247 ,3633,3635,3634 ,0,0,0}, + {4242,4241,4236 ,3629,3628,3623 ,0,0,0}, {4248,4249,4250 ,3635,3636,3637 ,0,0,0}, + {4248,4246,4249 ,3635,3633,3636 ,0,0,0}, {4251,4252,4253 ,3638,3639,3640 ,0,0,0}, + {4254,4253,4252 ,3641,3640,3639 ,0,0,0}, {4254,4255,4253 ,3641,3642,3640 ,0,0,0}, + {4255,4250,4249 ,3642,3637,3636 ,0,0,0}, {4255,4254,4250 ,3642,3641,3637 ,0,0,0}, + {4237,4234,4235 ,3624,3621,3622 ,0,0,0}, {4256,4257,4251 ,3643,3644,3638 ,0,0,0}, + {4258,4259,4256 ,3645,3646,3643 ,0,0,0}, {4222,4259,4258 ,1435,3646,3645 ,0,0,0}, + {4252,4251,4257 ,3639,3638,3644 ,0,0,0}, {4259,4257,4256 ,3646,3644,3643 ,0,0,0}, + {4221,4222,4258 ,1435,1435,3645 ,0,0,0}, {4260,4261,4226 ,3647,3648,3613 ,0,0,0}, + {4226,4228,4260 ,3613,3615,3647 ,0,0,0}, {4261,4262,4263 ,3648,3649,3650 ,0,0,0}, + {4262,4261,4260 ,3649,3648,3647 ,0,0,0}, {4264,4263,4265 ,3651,3650,3652 ,0,0,0}, + {4262,4265,4263 ,3649,3652,3650 ,0,0,0}, {4266,4267,4264 ,3653,3654,3651 ,0,0,0}, + {4264,4265,4266 ,3651,3652,3653 ,0,0,0}, {4267,4268,4269 ,3654,3655,3656 ,0,0,0}, + {4268,4267,4266 ,3655,3654,3653 ,0,0,0}, {4270,4269,4271 ,3657,3656,3658 ,0,0,0}, + {4268,4271,4269 ,3655,3658,3656 ,0,0,0}, {4272,4273,4270 ,3659,3660,3657 ,0,0,0}, + {4270,4271,4272 ,3657,3658,3659 ,0,0,0}, {4273,4274,4275 ,3660,3661,3662 ,0,0,0}, + {4274,4273,4272 ,3661,3660,3659 ,0,0,0}, {4276,4275,4277 ,3663,3662,3664 ,0,0,0}, + {4274,4277,4275 ,3661,3664,3662 ,0,0,0}, {4278,4279,4276 ,3665,3666,3663 ,0,0,0}, + {4276,4277,4278 ,3663,3664,3665 ,0,0,0}, {4279,4280,4281 ,3666,3667,3668 ,0,0,0}, + {4280,4279,4278 ,3667,3666,3665 ,0,0,0}, {4282,4281,4283 ,3669,3668,3670 ,0,0,0}, + {4280,4283,4281 ,3667,3670,3668 ,0,0,0}, {4284,4285,4282 ,3671,3672,3669 ,0,0,0}, + {4282,4283,4284 ,3669,3670,3671 ,0,0,0}, {4285,4286,4287 ,3672,3673,3674 ,0,0,0}, + {4286,4285,4284 ,3673,3672,3671 ,0,0,0}, {4288,4287,4289 ,3675,3674,3676 ,0,0,0}, + {4286,4289,4287 ,3673,3676,3674 ,0,0,0}, {4290,4291,4288 ,3677,3678,3675 ,0,0,0}, + {4288,4289,4290 ,3675,3676,3677 ,0,0,0}, {4291,4292,4293 ,3678,3679,3680 ,0,0,0}, + {4292,4291,4290 ,3679,3678,3677 ,0,0,0}, {4294,4293,4295 ,1790,3680,3681 ,0,0,0}, + {4292,4295,4293 ,3679,3681,3680 ,0,0,0}, {4294,4295,4296 ,1790,3681,1790 ,0,0,0}, + {4297,4298,4299 ,2162,2162,2162 ,0,0,0}, {4298,4297,4300 ,2162,2162,2162 ,0,0,0}, + {4301,4302,4303 ,3682,3683,3684 ,0,0,0}, {4304,4305,4306 ,3685,3686,3687 ,0,0,0}, + {4302,4307,4303 ,3683,3688,3684 ,0,0,0}, {4301,4303,4308 ,3682,3684,3689 ,0,0,0}, + {4304,4301,4308 ,3685,3682,3689 ,0,0,0}, {4309,4310,4307 ,3690,3691,3688 ,0,0,0}, + {4309,4307,4302 ,3690,3688,3683 ,0,0,0}, {4311,4312,4313 ,3692,3693,3694 ,0,0,0}, + {4310,4309,4311 ,3691,3690,3692 ,0,0,0}, {4311,4313,4310 ,3692,3694,3691 ,0,0,0}, + {4312,4314,4313 ,3693,3695,3694 ,0,0,0}, {4305,4304,4308 ,3686,3685,3689 ,0,0,0}, + {4312,4315,4314 ,3693,3696,3695 ,0,0,0}, {4316,4317,4318 ,3697,3698,3699 ,0,0,0}, + {4316,4318,4315 ,3697,3699,3696 ,0,0,0}, {4317,4316,4319 ,3698,3697,3700 ,0,0,0}, + {4320,4321,4319 ,3701,3702,3700 ,0,0,0}, {4321,4317,4319 ,3702,3698,3700 ,0,0,0}, + {4322,4323,4324 ,3703,3704,3705 ,0,0,0}, {4321,4320,4325 ,3702,3701,3706 ,0,0,0}, + {4326,4327,4325 ,3707,3708,3706 ,0,0,0}, {4323,4322,4327 ,3704,3703,3708 ,0,0,0}, + {4323,4327,4326 ,3704,3708,3707 ,0,0,0}, {4322,4324,4328 ,3703,3705,3709 ,0,0,0}, + {4320,4326,4325 ,3701,3707,3706 ,0,0,0}, {4329,4328,4330 ,3710,3709,3711 ,0,0,0}, + {4329,4330,4331 ,3710,3711,3712 ,0,0,0}, {4330,4328,4324 ,3711,3709,3705 ,0,0,0}, + {4332,4333,4334 ,3713,3714,3715 ,0,0,0}, {4318,4314,4315 ,3699,3695,3696 ,0,0,0}, + {4332,4335,4331 ,3713,3716,3712 ,0,0,0}, {4335,4332,4334 ,3716,3713,3715 ,0,0,0}, + {4333,4336,4337 ,3714,3717,3718 ,0,0,0}, {4337,4334,4333 ,3718,3715,3714 ,0,0,0}, + {4338,4339,4336 ,3719,3720,3717 ,0,0,0}, {4337,4336,4339 ,3718,3717,3720 ,0,0,0}, + {4338,4300,4297 ,3719,3721,3721 ,0,0,0}, {4338,4297,4339 ,3719,3721,3720 ,0,0,0}, + {4331,4335,4329 ,3712,3716,3710 ,0,0,0}, {4340,4306,4341 ,3722,3687,3723 ,0,0,0}, + {4305,4341,4306 ,3686,3723,3687 ,0,0,0}, {4342,4343,4340 ,3724,3725,3722 ,0,0,0}, + {4340,4341,4342 ,3722,3723,3724 ,0,0,0}, {4343,4344,4345 ,3725,3726,3727 ,0,0,0}, + {4344,4343,4342 ,3726,3725,3724 ,0,0,0}, {4346,4345,4347 ,3728,3727,3729 ,0,0,0}, + {4344,4347,4345 ,3726,3729,3727 ,0,0,0}, {4348,4349,4346 ,3730,3731,3728 ,0,0,0}, + {4346,4347,4348 ,3728,3729,3730 ,0,0,0}, {4349,4350,4351 ,3731,3732,3733 ,0,0,0}, + {4350,4349,4348 ,3732,3731,3730 ,0,0,0}, {4352,4351,4353 ,3734,3733,3735 ,0,0,0}, + {4350,4353,4351 ,3732,3735,3733 ,0,0,0}, {4354,4355,4352 ,3736,3737,3734 ,0,0,0}, + {4352,4353,4354 ,3734,3735,3736 ,0,0,0}, {4355,4356,4357 ,3737,3738,3739 ,0,0,0}, + {4356,4355,4354 ,3738,3737,3736 ,0,0,0}, {4358,4357,4359 ,3740,3739,3741 ,0,0,0}, + {4356,4359,4357 ,3738,3741,3739 ,0,0,0}, {4360,4361,4358 ,3742,3743,3740 ,0,0,0}, + {4358,4359,4360 ,3740,3741,3742 ,0,0,0}, {4361,4362,4363 ,3743,3744,3745 ,0,0,0}, + {4362,4361,4360 ,3744,3743,3742 ,0,0,0}, {4364,4363,4365 ,3746,3745,3747 ,0,0,0}, + {4362,4365,4363 ,3744,3747,3745 ,0,0,0}, {4366,4367,4364 ,3748,3749,3746 ,0,0,0}, + {4364,4365,4366 ,3746,3747,3748 ,0,0,0}, {4367,4368,4369 ,3749,3750,3751 ,0,0,0}, + {4368,4367,4366 ,3750,3749,3748 ,0,0,0}, {4370,4369,4371 ,3752,3751,3753 ,0,0,0}, + {4368,4371,4369 ,3750,3753,3751 ,0,0,0}, {4372,4373,4370 ,3754,3755,3752 ,0,0,0}, + {4370,4371,4372 ,3752,3753,3754 ,0,0,0}, {4373,4374,4375 ,3755,3756,3757 ,0,0,0}, + {4374,4373,4372 ,3756,3755,3754 ,0,0,0}, {4376,4375,4377 ,3758,3757,3759 ,0,0,0}, + {4374,4377,4375 ,3756,3759,3757 ,0,0,0}, {4376,4377,4378 ,3758,3759,3760 ,0,0,0}, + {4379,4380,4381 ,3761,3762,3763 ,0,0,0}, {4382,4383,4381 ,3764,3765,3763 ,0,0,0}, + {4379,4381,4383 ,3761,3763,3765 ,0,0,0}, {4382,4384,4385 ,3764,3766,3767 ,0,0,0}, + {4385,4383,4382 ,3767,3765,3764 ,0,0,0}, {4386,4384,4387 ,3768,3766,3769 ,0,0,0}, + {4384,4386,4385 ,3766,3768,3767 ,0,0,0}, {4388,4389,4387 ,3770,3771,3769 ,0,0,0}, + {4386,4387,4389 ,3768,3769,3771 ,0,0,0}, {4388,4390,4391 ,3770,3772,3773 ,0,0,0}, + {4391,4389,4388 ,3773,3771,3770 ,0,0,0}, {4392,4390,4393 ,3774,3772,3775 ,0,0,0}, + {4390,4392,4391 ,3772,3774,3773 ,0,0,0}, {4394,4395,4393 ,3776,3777,3775 ,0,0,0}, + {4392,4393,4395 ,3774,3775,3777 ,0,0,0}, {4394,4396,4397 ,3776,3778,3779 ,0,0,0}, + {4397,4395,4394 ,3779,3777,3776 ,0,0,0}, {4398,4396,4399 ,3780,3778,3781 ,0,0,0}, + {4396,4398,4397 ,3778,3780,3779 ,0,0,0}, {4400,4401,4399 ,3782,3783,3781 ,0,0,0}, + {4398,4399,4401 ,3780,3781,3783 ,0,0,0}, {4400,4402,4403 ,3782,3784,3785 ,0,0,0}, + {4403,4401,4400 ,3785,3783,3782 ,0,0,0}, {4404,4402,4405 ,3786,3784,3787 ,0,0,0}, + {4402,4404,4403 ,3784,3786,3785 ,0,0,0}, {4406,4407,4405 ,3788,3789,3787 ,0,0,0}, + {4404,4405,4407 ,3786,3787,3789 ,0,0,0}, {4406,4408,4409 ,3788,3790,3791 ,0,0,0}, + {4409,4407,4406 ,3791,3789,3788 ,0,0,0}, {4410,4408,4411 ,3792,3790,3793 ,0,0,0}, + {4408,4410,4409 ,3790,3792,3791 ,0,0,0}, {4412,4413,4411 ,3794,3795,3793 ,0,0,0}, + {4410,4411,4413 ,3792,3793,3795 ,0,0,0}, {4412,4414,4415 ,3794,3796,3797 ,0,0,0}, + {4415,4413,4412 ,3797,3795,3794 ,0,0,0}, {4416,4414,4417 ,3798,3796,3799 ,0,0,0}, + {4414,4416,4415 ,3796,3798,3797 ,0,0,0}, {4418,4419,4417 ,3800,3801,3799 ,0,0,0}, + {4416,4417,4419 ,3798,3799,3801 ,0,0,0}, {4418,4420,4421 ,3800,3802,3803 ,0,0,0}, + {4421,4419,4418 ,3803,3801,3800 ,0,0,0}, {4422,4420,4423 ,3804,3802,3805 ,0,0,0}, + {4420,4422,4421 ,3802,3804,3803 ,0,0,0}, {4424,4425,4423 ,3806,3807,3805 ,0,0,0}, + {4422,4423,4425 ,3804,3805,3807 ,0,0,0}, {4424,4426,4427 ,3806,3808,3809 ,0,0,0}, + {4427,4425,4424 ,3809,3807,3806 ,0,0,0}, {4428,4426,4429 ,3810,3808,3811 ,0,0,0}, + {4426,4428,4427 ,3808,3810,3809 ,0,0,0}, {4430,4431,4429 ,3812,3813,3811 ,0,0,0}, + {4428,4429,4431 ,3810,3811,3813 ,0,0,0}, {4430,4432,4433 ,3812,3814,3815 ,0,0,0}, + {4433,4431,4430 ,3815,3813,3812 ,0,0,0}, {4434,4432,4435 ,3816,3814,3817 ,0,0,0}, + {4432,4434,4433 ,3814,3816,3815 ,0,0,0}, {4376,4436,4435 ,3818,3819,3817 ,0,0,0}, + {4434,4435,4436 ,3816,3817,3819 ,0,0,0}, {4378,4436,4376 ,3820,3819,3818 ,0,0,0}, + {4437,4380,4379 ,3821,3762,3761 ,0,0,0}, {4438,4437,4439 ,3822,3821,3823 ,0,0,0}, + {4437,4438,4380 ,3821,3822,3762 ,0,0,0}, {4440,4441,4439 ,3824,3825,3823 ,0,0,0}, + {4438,4439,4441 ,3822,3823,3825 ,0,0,0}, {4440,4442,4443 ,3824,3826,3827 ,0,0,0}, + {4443,4441,4440 ,3827,3825,3824 ,0,0,0}, {4444,4442,4445 ,3828,3826,3829 ,0,0,0}, + {4442,4444,4443 ,3826,3828,3827 ,0,0,0}, {4446,4447,4445 ,3830,3831,3829 ,0,0,0}, + {4444,4445,4447 ,3828,3829,3831 ,0,0,0}, {4446,4448,4449 ,3830,3832,3833 ,0,0,0}, + {4449,4447,4446 ,3833,3831,3830 ,0,0,0}, {4450,4448,4451 ,3834,3832,3835 ,0,0,0}, + {4448,4450,4449 ,3832,3834,3833 ,0,0,0}, {4452,4453,4451 ,3836,3837,3835 ,0,0,0}, + {4450,4451,4453 ,3834,3835,3837 ,0,0,0}, {4452,4454,4455 ,3836,3838,3839 ,0,0,0}, + {4455,4453,4452 ,3839,3837,3836 ,0,0,0}, {4456,4454,4457 ,3840,3838,3841 ,0,0,0}, + {4454,4456,4455 ,3838,3840,3839 ,0,0,0}, {4458,4459,4457 ,3842,3843,3841 ,0,0,0}, + {4456,4457,4459 ,3840,3841,3843 ,0,0,0}, {4458,4460,4461 ,3842,3844,3845 ,0,0,0}, + {4461,4459,4458 ,3845,3843,3842 ,0,0,0}, {4462,4460,4463 ,3846,3844,3847 ,0,0,0}, + {4460,4462,4461 ,3844,3846,3845 ,0,0,0}, {4464,4465,4463 ,3848,3849,3847 ,0,0,0}, + {4462,4463,4465 ,3846,3847,3849 ,0,0,0}, {4464,4466,4467 ,3848,3850,3851 ,0,0,0}, + {4467,4465,4464 ,3851,3849,3848 ,0,0,0}, {4468,4466,4469 ,3852,3850,3853 ,0,0,0}, + {4466,4468,4467 ,3850,3852,3851 ,0,0,0}, {4470,4471,4469 ,3854,3855,3853 ,0,0,0}, + {4468,4469,4471 ,3852,3853,3855 ,0,0,0}, {4470,4472,4473 ,3854,3856,3857 ,0,0,0}, + {4473,4471,4470 ,3857,3855,3854 ,0,0,0}, {4474,4472,4475 ,3858,3856,3859 ,0,0,0}, + {4472,4474,4473 ,3856,3858,3857 ,0,0,0}, {4476,4477,4475 ,3860,3861,3859 ,0,0,0}, + {4474,4475,4477 ,3858,3859,3861 ,0,0,0}, {4476,4478,4479 ,3860,3862,3863 ,0,0,0}, + {4479,4477,4476 ,3863,3861,3860 ,0,0,0}, {4480,4478,4481 ,3864,3862,3865 ,0,0,0}, + {4478,4480,4479 ,3862,3864,3863 ,0,0,0}, {4482,4483,4481 ,3866,3867,3865 ,0,0,0}, + {4480,4481,4483 ,3864,3865,3867 ,0,0,0}, {4482,4484,4485 ,3866,3868,3869 ,0,0,0}, + {4485,4483,4482 ,3869,3867,3866 ,0,0,0}, {4486,4484,4487 ,3870,3868,3871 ,0,0,0}, + {4484,4486,4485 ,3868,3870,3869 ,0,0,0}, {4488,4489,4487 ,3872,3873,3871 ,0,0,0}, + {4486,4487,4489 ,3870,3871,3873 ,0,0,0}, {4488,4490,4491 ,3872,3874,3875 ,0,0,0}, + {4491,4489,4488 ,3875,3873,3872 ,0,0,0}, {4492,4490,4493 ,3876,3874,82 ,0,0,0}, + {4490,4492,4491 ,3874,3876,3875 ,0,0,0}, {4492,4493,4494 ,3876,82,3877 ,0,0,0}, + {4495,4496,4497 ,3878,3879,3880 ,0,0,0}, {4498,4499,4500 ,3881,3882,3883 ,0,0,0}, + {4496,4501,4497 ,3879,3884,3880 ,0,0,0}, {4495,4497,4502 ,3878,3880,3885 ,0,0,0}, + {4498,4495,4502 ,3881,3878,3885 ,0,0,0}, {4503,4504,4501 ,3886,3887,3884 ,0,0,0}, + {4503,4501,4496 ,3886,3884,3879 ,0,0,0}, {4505,4506,4507 ,3888,3889,3890 ,0,0,0}, + {4504,4503,4505 ,3887,3886,3888 ,0,0,0}, {4505,4507,4504 ,3888,3890,3887 ,0,0,0}, + {4506,4508,4507 ,3889,3891,3890 ,0,0,0}, {4499,4498,4502 ,3882,3881,3885 ,0,0,0}, + {4506,4509,4508 ,3889,3892,3891 ,0,0,0}, {4510,4511,4512 ,3893,3894,3895 ,0,0,0}, + {4510,4512,4509 ,3893,3895,3892 ,0,0,0}, {4511,4510,4513 ,3894,3893,3896 ,0,0,0}, + {4514,4515,4513 ,3897,3898,3896 ,0,0,0}, {4515,4511,4513 ,3898,3894,3896 ,0,0,0}, + {4516,4517,4518 ,3899,3900,3901 ,0,0,0}, {4515,4514,4519 ,3898,3897,3902 ,0,0,0}, + {4520,4521,4519 ,3903,3904,3902 ,0,0,0}, {4517,4516,4521 ,3900,3899,3904 ,0,0,0}, + {4517,4521,4520 ,3900,3904,3903 ,0,0,0}, {4516,4518,4522 ,3899,3901,3905 ,0,0,0}, + {4514,4520,4519 ,3897,3903,3902 ,0,0,0}, {4523,4522,4524 ,3906,3905,3907 ,0,0,0}, + {4523,4524,4525 ,3906,3907,3908 ,0,0,0}, {4524,4522,4518 ,3907,3905,3901 ,0,0,0}, + {4526,4527,4528 ,3909,3910,3911 ,0,0,0}, {4512,4508,4509 ,3895,3891,3892 ,0,0,0}, + {4526,4529,4525 ,3909,3912,3908 ,0,0,0}, {4529,4526,4528 ,3912,3909,3911 ,0,0,0}, + {4527,4530,4531 ,3910,3913,3914 ,0,0,0}, {4531,4528,4527 ,3914,3911,3910 ,0,0,0}, + {4532,4533,4530 ,3915,3916,3913 ,0,0,0}, {4531,4530,4533 ,3914,3913,3916 ,0,0,0}, + {4532,4494,4493 ,3915,3917,3918 ,0,0,0}, {4532,4493,4533 ,3915,3918,3916 ,0,0,0}, + {4525,4529,4523 ,3908,3912,3906 ,0,0,0}, {4534,4500,4535 ,3919,3883,3920 ,0,0,0}, + {4499,4535,4500 ,3882,3920,3883 ,0,0,0}, {4536,4537,4534 ,3921,3922,3919 ,0,0,0}, + {4534,4535,4536 ,3919,3920,3921 ,0,0,0}, {4537,4538,4539 ,3922,3923,3924 ,0,0,0}, + {4538,4537,4536 ,3923,3922,3921 ,0,0,0}, {4540,4539,4541 ,3925,3924,3926 ,0,0,0}, + {4538,4541,4539 ,3923,3926,3924 ,0,0,0}, {4542,4543,4540 ,3927,3928,3925 ,0,0,0}, + {4540,4541,4542 ,3925,3926,3927 ,0,0,0}, {4543,4544,4545 ,3928,3929,3930 ,0,0,0}, + {4544,4543,4542 ,3929,3928,3927 ,0,0,0}, {4546,4545,4547 ,3931,3930,3932 ,0,0,0}, + {4544,4547,4545 ,3929,3932,3930 ,0,0,0}, {4548,4549,4546 ,3933,3934,3931 ,0,0,0}, + {4546,4547,4548 ,3931,3932,3933 ,0,0,0}, {4549,4550,4551 ,3934,3935,3936 ,0,0,0}, + {4550,4549,4548 ,3935,3934,3933 ,0,0,0}, {4552,4551,4553 ,3937,3936,3938 ,0,0,0}, + {4550,4553,4551 ,3935,3938,3936 ,0,0,0}, {4554,4555,4552 ,3939,3940,3937 ,0,0,0}, + {4552,4553,4554 ,3937,3938,3939 ,0,0,0}, {4555,4556,4557 ,3940,3941,3942 ,0,0,0}, + {4556,4555,4554 ,3941,3940,3939 ,0,0,0}, {4558,4557,4559 ,3943,3942,3944 ,0,0,0}, + {4556,4559,4557 ,3941,3944,3942 ,0,0,0}, {4560,4561,4558 ,3945,3946,3943 ,0,0,0}, + {4558,4559,4560 ,3943,3944,3945 ,0,0,0}, {4561,4562,4563 ,3946,3947,3948 ,0,0,0}, + {4562,4561,4560 ,3947,3946,3945 ,0,0,0}, {4564,4563,4565 ,3949,3948,3950 ,0,0,0}, + {4562,4565,4563 ,3947,3950,3948 ,0,0,0}, {4566,4567,4564 ,3951,3952,3949 ,0,0,0}, + {4564,4565,4566 ,3949,3950,3951 ,0,0,0}, {4567,4568,4569 ,3952,3953,3954 ,0,0,0}, + {4568,4567,4566 ,3953,3952,3951 ,0,0,0}, {4570,4569,4571 ,3955,3954,3956 ,0,0,0}, + {4568,4571,4569 ,3953,3956,3954 ,0,0,0}, {4570,4571,4572 ,3955,3956,3955 ,0,0,0}, + {4573,4570,4572 ,1433,1433,1433 ,0,0,0}, {4570,4573,4574 ,1433,1433,1433 ,0,0,0}, + {4575,4576,4577 ,3957,3958,3959 ,0,0,0}, {4578,4579,4575 ,3960,3961,3957 ,0,0,0}, + {4575,4577,4578 ,3957,3959,3960 ,0,0,0}, {4579,4580,4581 ,3961,3962,3963 ,0,0,0}, + {4580,4579,4578 ,3962,3961,3960 ,0,0,0}, {4582,4581,4583 ,3964,3963,3965 ,0,0,0}, + {4580,4583,4581 ,3962,3965,3963 ,0,0,0}, {4584,4585,4582 ,3966,3967,3964 ,0,0,0}, + {4582,4583,4584 ,3964,3965,3966 ,0,0,0}, {4585,4586,4587 ,3967,3968,3969 ,0,0,0}, + {4586,4585,4584 ,3968,3967,3966 ,0,0,0}, {4588,4587,4589 ,3970,3969,3971 ,0,0,0}, + {4586,4589,4587 ,3968,3971,3969 ,0,0,0}, {4590,4591,4588 ,3972,3973,3970 ,0,0,0}, + {4588,4589,4590 ,3970,3971,3972 ,0,0,0}, {4591,4592,4593 ,3973,3974,3975 ,0,0,0}, + {4592,4591,4590 ,3974,3973,3972 ,0,0,0}, {4594,4593,4595 ,3976,3975,3977 ,0,0,0}, + {4592,4595,4593 ,3974,3977,3975 ,0,0,0}, {4596,4597,4594 ,3978,3979,3976 ,0,0,0}, + {4594,4595,4596 ,3976,3977,3978 ,0,0,0}, {4597,4598,4599 ,3979,3980,3981 ,0,0,0}, + {4598,4597,4596 ,3980,3979,3978 ,0,0,0}, {4600,4599,4601 ,3982,3981,3983 ,0,0,0}, + {4598,4601,4599 ,3980,3983,3981 ,0,0,0}, {4602,4603,4600 ,3984,3985,3982 ,0,0,0}, + {4600,4601,4602 ,3982,3983,3984 ,0,0,0}, {4603,4604,4605 ,3985,3986,3987 ,0,0,0}, + {4604,4603,4602 ,3986,3985,3984 ,0,0,0}, {4606,4605,4607 ,3988,3987,3989 ,0,0,0}, + {4604,4607,4605 ,3986,3989,3987 ,0,0,0}, {4608,4609,4606 ,3990,3991,3988 ,0,0,0}, + {4606,4607,4608 ,3988,3989,3990 ,0,0,0}, {4609,4610,4611 ,3991,3992,3993 ,0,0,0}, + {4610,4609,4608 ,3992,3991,3990 ,0,0,0}, {4612,4611,4613 ,3994,3993,3995 ,0,0,0}, + {4610,4613,4611 ,3992,3995,3993 ,0,0,0}, {4574,4573,4612 ,3996,3996,3994 ,0,0,0}, + {4612,4613,4574 ,3994,3995,3996 ,0,0,0}, {4577,4576,4614 ,3959,3958,3997 ,0,0,0}, + {4615,4614,4616 ,3998,3997,3999 ,0,0,0}, {4576,4616,4614 ,3958,3999,3997 ,0,0,0}, + {4617,4618,4615 ,4000,4001,3998 ,0,0,0}, {4615,4616,4617 ,3998,3999,4000 ,0,0,0}, + {4618,4619,4620 ,4001,4002,4003 ,0,0,0}, {4619,4618,4617 ,4002,4001,4000 ,0,0,0}, + {4621,4620,4622 ,4004,4003,4005 ,0,0,0}, {4619,4622,4620 ,4002,4005,4003 ,0,0,0}, + {4623,4624,4621 ,4006,4007,4004 ,0,0,0}, {4621,4622,4623 ,4004,4005,4006 ,0,0,0}, + {4624,4625,4626 ,4007,4008,4009 ,0,0,0}, {4625,4624,4623 ,4008,4007,4006 ,0,0,0}, + {4627,4626,4628 ,4010,4009,4011 ,0,0,0}, {4625,4628,4626 ,4008,4011,4009 ,0,0,0}, + {4629,4630,4627 ,4012,4013,4010 ,0,0,0}, {4627,4628,4629 ,4010,4011,4012 ,0,0,0}, + {4630,4631,4632 ,4013,4014,4015 ,0,0,0}, {4631,4630,4629 ,4014,4013,4012 ,0,0,0}, + {4633,4632,4634 ,4016,4015,4017 ,0,0,0}, {4631,4634,4632 ,4014,4017,4015 ,0,0,0}, + {4635,4636,4633 ,4018,4019,4016 ,0,0,0}, {4633,4634,4635 ,4016,4017,4018 ,0,0,0}, + {4636,4637,4638 ,4019,4020,4021 ,0,0,0}, {4637,4636,4635 ,4020,4019,4018 ,0,0,0}, + {4639,4638,4640 ,4022,4021,4023 ,0,0,0}, {4637,4640,4638 ,4020,4023,4021 ,0,0,0}, + {4641,4642,4639 ,4024,4025,4022 ,0,0,0}, {4639,4640,4641 ,4022,4023,4024 ,0,0,0}, + {4642,4643,4644 ,4025,4026,4027 ,0,0,0}, {4643,4642,4641 ,4026,4025,4024 ,0,0,0}, + {4645,4644,4646 ,4028,4027,4029 ,0,0,0}, {4643,4646,4644 ,4026,4029,4027 ,0,0,0}, + {4647,4648,4645 ,4030,4031,4028 ,0,0,0}, {4645,4646,4647 ,4028,4029,4030 ,0,0,0}, + {4648,4649,4650 ,4031,4032,4033 ,0,0,0}, {4649,4648,4647 ,4032,4031,4030 ,0,0,0}, + {4649,4299,4650 ,4032,4034,4033 ,0,0,0}, {4650,4299,4298 ,4033,4034,4034 ,0,0,0}, + {4000,4296,4001 ,2197,4035,2197 ,0,0,0}, {4296,4000,4294 ,4035,2197,4035 ,0,0,0}, + {4521,4023,4022 ,3295,3295,3295 ,0,0,0}, {4299,4649,4222 ,3295,726,726 ,0,0,0}, + {4643,4252,4646 ,726,726,726 ,0,0,0}, {4339,4297,4219 ,726,726,726 ,0,0,0}, + {4240,4244,4634 ,726,726,726 ,0,0,0}, {4248,4640,4637 ,726,726,726 ,0,0,0}, + {4619,4230,4622 ,726,726,726 ,0,0,0}, {4628,4625,4237 ,726,726,726 ,0,0,0}, + {4616,4224,4223 ,726,726,726 ,0,0,0}, {4617,4616,4223 ,726,726,726 ,0,0,0}, + {4016,4013,4512 ,3295,726,3295 ,0,0,0}, {4529,4528,4031 ,3295,726,3295 ,0,0,0}, + {4497,4501,4005 ,3295,3295,726 ,0,0,0}, {4007,4501,4504 ,726,3295,726 ,0,0,0}, + {4535,3961,3965 ,726,726,726 ,0,0,0}, {3961,4499,3962 ,726,3295,3295 ,0,0,0}, + {4538,3968,4541 ,3295,726,726 ,0,0,0}, {3967,4538,4536 ,3295,3295,3295 ,0,0,0}, + {3977,4548,4547 ,3294,3295,3295 ,0,0,0}, {3973,4544,4542 ,726,3295,3295 ,0,0,0}, + {4550,4548,3979 ,3295,3295,3295 ,0,0,0}, {3977,3979,4548 ,3294,3295,3295 ,0,0,0}, + {4554,4553,3983 ,3295,3294,726 ,0,0,0}, {4550,3979,3980 ,3295,3295,3295 ,0,0,0}, + {4556,4554,3985 ,3295,3295,3295 ,0,0,0}, {3983,4553,3980 ,726,3294,3295 ,0,0,0}, + {3986,4559,4556 ,3295,726,3295 ,0,0,0}, {4556,3985,3986 ,3295,3295,3295 ,0,0,0}, + {4559,3989,4560 ,726,726,726 ,0,0,0}, {3989,4559,3986 ,726,726,3295 ,0,0,0}, + {4562,4560,3991 ,726,726,726 ,0,0,0}, {3992,4562,3991 ,726,726,726 ,0,0,0}, + {3997,4566,3995 ,726,3295,3295 ,0,0,0}, {4565,4562,3992 ,726,726,726 ,0,0,0}, + {3998,4001,4568 ,726,726,726 ,0,0,0}, {3995,4566,4565 ,3295,3295,726 ,0,0,0}, + {4001,4571,4568 ,726,3295,726 ,0,0,0}, {4566,3998,4568 ,3295,726,726 ,0,0,0}, + {4591,4272,4588 ,726,726,726 ,0,0,0}, {4001,4572,4571 ,726,726,3295 ,0,0,0}, + {4522,4025,4516 ,3295,726,726 ,0,0,0}, {4536,3965,3967 ,3295,726,3295 ,0,0,0}, + {4544,3973,3974 ,3295,726,3295 ,0,0,0}, {4547,3974,3977 ,3295,3295,3294 ,0,0,0}, + {3971,3973,4542 ,3295,726,3295 ,0,0,0}, {4541,3968,3971 ,726,726,3295 ,0,0,0}, + {4499,3961,4535 ,3295,726,726 ,0,0,0}, {4535,3965,4536 ,726,726,3295 ,0,0,0}, + {4497,4004,4502 ,3295,3295,3295 ,0,0,0}, {4502,3962,4499 ,3295,3295,3295 ,0,0,0}, + {4165,4344,4163 ,726,726,3295 ,0,0,0}, {4004,3962,4502 ,3295,3295,3295 ,0,0,0}, + {4507,4011,4010 ,3295,3295,726 ,0,0,0}, {4504,4010,4007 ,726,726,726 ,0,0,0}, + {4508,4013,4011 ,726,726,3295 ,0,0,0}, {4507,4010,4504 ,3295,726,726 ,0,0,0}, + {4515,4019,4017 ,3295,3295,3295 ,0,0,0}, {4016,4512,4511 ,3295,3295,726 ,0,0,0}, + {4516,4023,4521 ,726,3295,3295 ,0,0,0}, {4019,4519,4022 ,3295,3295,3295 ,0,0,0}, + {4029,4028,4523 ,726,726,726 ,0,0,0}, {4025,4023,4516 ,726,3295,726 ,0,0,0}, + {4523,4028,4522 ,726,726,3295 ,0,0,0}, {4371,4368,4151 ,3295,726,726 ,0,0,0}, + {4531,4035,4034 ,3294,726,726 ,0,0,0}, {3948,3930,3950 ,3295,3294,726 ,0,0,0}, + {4037,4533,4039 ,3295,726,3295 ,0,0,0}, {3955,3957,3922 ,726,3295,726 ,0,0,0}, + {3919,3957,3958 ,726,3295,3295 ,0,0,0}, {4118,4115,3911 ,726,726,726 ,0,0,0}, + {4118,3902,3904 ,726,726,3295 ,0,0,0}, {4421,4093,4419 ,726,3295,3295 ,0,0,0}, + {4112,4107,4374 ,3295,726,726 ,0,0,0}, {4481,4478,4651 ,726,726,726 ,0,0,0}, + {4392,4076,4391 ,726,3295,3295 ,0,0,0}, {4652,4653,4442 ,3295,3295,726 ,0,0,0}, + {3897,4654,4655 ,3295,726,726 ,0,0,0}, {4448,4446,4656 ,726,3295,726 ,0,0,0}, + {4656,4446,4653 ,726,3295,3295 ,0,0,0}, {3870,3867,3939 ,726,726,3295 ,0,0,0}, + {4656,3939,4451 ,726,3295,3295 ,0,0,0}, {3937,3935,3868 ,3295,3295,3295 ,0,0,0}, + {3868,3935,3877 ,3295,3295,3295 ,0,0,0}, {4458,4457,3866 ,3295,726,726 ,0,0,0}, + {4445,4442,4653 ,3295,726,3295 ,0,0,0}, {4083,4652,4440 ,726,3295,726 ,0,0,0}, + {4058,4657,4054 ,726,3295,3295 ,0,0,0}, {4658,4659,4654 ,3295,3295,726 ,0,0,0}, + {4049,4660,4661 ,726,3295,3295 ,0,0,0}, {4437,4082,4083 ,3295,726,726 ,0,0,0}, + {4083,4440,4439 ,726,726,3295 ,0,0,0}, {4379,4082,4437 ,3295,726,3295 ,0,0,0}, + {4476,4475,4662 ,726,3295,3295 ,0,0,0}, {4081,4082,4383 ,3295,726,726 ,0,0,0}, + {4383,4385,4081 ,726,726,3295 ,0,0,0}, {4482,4481,4663 ,3295,726,3295 ,0,0,0}, + {4078,4081,4386 ,726,3295,726 ,0,0,0}, {4484,4664,4487 ,726,3295,3295 ,0,0,0}, + {4389,4078,4386 ,3295,726,726 ,0,0,0}, {4041,4488,4044 ,3295,726,3295 ,0,0,0}, + {4078,4391,4076 ,726,3295,3295 ,0,0,0}, {4401,4072,4071 ,3295,726,726 ,0,0,0}, + {4397,4071,4074 ,3295,726,3295 ,0,0,0}, {4088,4087,4409 ,3294,726,3295 ,0,0,0}, + {4072,4401,4403 ,726,3295,3295 ,0,0,0}, {4416,4090,4415 ,3295,3295,3295 ,0,0,0}, + {4090,4088,4413 ,3295,3294,3295 ,0,0,0}, {4099,4096,4427 ,3295,726,726 ,0,0,0}, + {4059,4665,4063 ,3295,726,3295 ,0,0,0}, {4666,4667,4668 ,3295,3295,3295 ,0,0,0}, + {4100,4431,4433 ,726,726,726 ,0,0,0}, {4102,4106,4378 ,3295,3295,3295 ,0,0,0}, + {4669,4120,4670 ,726,726,726 ,0,0,0}, {4671,4130,4120 ,3295,3295,726 ,0,0,0}, + {4123,4119,4672 ,726,726,726 ,0,0,0}, {4122,4673,4670 ,726,3295,726 ,0,0,0}, + {3960,3901,3900 ,726,726,3295 ,0,0,0}, {3944,3943,3924 ,3295,726,726 ,0,0,0}, + {4673,4122,4123 ,3295,726,726 ,0,0,0}, {4490,4041,4493 ,3295,3295,3295 ,0,0,0}, + {3947,3925,3928 ,726,3295,726 ,0,0,0}, {4148,4146,4371 ,3295,3295,3295 ,0,0,0}, + {4533,4493,4039 ,726,3295,3295 ,0,0,0}, {4186,4152,4368 ,3294,726,726 ,0,0,0}, + {4037,4035,4533 ,3295,726,726 ,0,0,0}, {4623,4233,4234 ,726,726,726 ,0,0,0}, + {4579,4260,4575 ,726,726,726 ,0,0,0}, {4262,4579,4581 ,726,726,726 ,0,0,0}, + {4341,4160,4342 ,3295,726,726 ,0,0,0}, {4016,4511,4017 ,3295,726,3295 ,0,0,0}, + {4533,4035,4531 ,726,726,3294 ,0,0,0}, {4528,4531,4034 ,726,3294,726 ,0,0,0}, + {4029,4529,4031 ,726,3295,3295 ,0,0,0}, {4031,4528,4034 ,3295,726,726 ,0,0,0}, + {4019,4515,4519 ,3295,3295,3295 ,0,0,0}, {4025,4522,4028 ,726,3295,726 ,0,0,0}, + {4029,4523,4529 ,726,726,3295 ,0,0,0}, {4521,4022,4519 ,3295,3295,3295 ,0,0,0}, + {4511,4515,4017 ,726,3295,3295 ,0,0,0}, {4512,4013,4508 ,3295,726,726 ,0,0,0}, + {4344,4165,4347 ,726,726,726 ,0,0,0}, {4507,4508,4011 ,3295,726,3295 ,0,0,0}, + {4575,4260,4228 ,726,726,726 ,0,0,0}, {4228,4576,4575 ,726,726,726 ,0,0,0}, + {4576,4228,4224 ,726,726,726 ,0,0,0}, {4230,4617,4223 ,726,726,726 ,0,0,0}, + {4224,4616,4576 ,726,726,726 ,0,0,0}, {4159,4160,4341 ,3295,726,3295 ,0,0,0}, + {4623,4622,4233 ,726,726,726 ,0,0,0}, {4622,4230,4233 ,726,726,726 ,0,0,0}, + {4314,4318,4195 ,726,3295,3295 ,0,0,0}, {4625,4623,4234 ,726,726,726 ,0,0,0}, + {4241,4628,4237 ,726,726,726 ,0,0,0}, {4629,4241,4243 ,726,726,726 ,0,0,0}, + {4241,4629,4628 ,726,726,726 ,0,0,0}, {4240,4631,4243 ,726,726,726 ,0,0,0}, + {4629,4243,4631 ,726,726,726 ,0,0,0}, {4631,4240,4634 ,726,726,726 ,0,0,0}, + {4244,4247,4635 ,726,726,726 ,0,0,0}, {4196,4195,4318 ,726,3295,3295 ,0,0,0}, + {4637,4247,4248 ,726,726,726 ,0,0,0}, {4247,4637,4635 ,726,726,726 ,0,0,0}, + {4641,4640,4250 ,726,726,726 ,0,0,0}, {4335,4213,4210 ,726,3295,3295 ,0,0,0}, + {4248,4250,4640 ,726,726,726 ,0,0,0}, {4254,4643,4641 ,726,726,726 ,0,0,0}, + {4641,4250,4254 ,726,726,726 ,0,0,0}, {4643,4254,4252 ,726,726,726 ,0,0,0}, + {4252,4257,4646 ,726,726,726 ,0,0,0}, {4646,4257,4647 ,726,726,726 ,0,0,0}, + {4647,4259,4649 ,726,726,726 ,0,0,0}, {4337,4216,4214 ,3295,726,3294 ,0,0,0}, + {4259,4647,4257 ,726,726,726 ,0,0,0}, {4138,4374,4372 ,726,726,3294 ,0,0,0}, + {3914,3915,4113 ,3294,726,726 ,0,0,0}, {4184,4186,4366 ,726,3294,726 ,0,0,0}, + {4372,4146,4145 ,3294,3295,3295 ,0,0,0}, {4183,4184,4365 ,3295,726,726 ,0,0,0}, + {4181,4183,4362 ,726,3295,726 ,0,0,0}, {4368,4152,4151 ,726,726,726 ,0,0,0}, + {4178,4181,4360 ,3295,726,3295 ,0,0,0}, {4368,4366,4186 ,726,726,3294 ,0,0,0}, + {4177,4178,4359 ,726,3295,3295 ,0,0,0}, {4366,4365,4184 ,726,726,726 ,0,0,0}, + {4175,4177,4356 ,3295,726,3295 ,0,0,0}, {4365,4362,4183 ,726,726,3295 ,0,0,0}, + {4172,4354,4353 ,3295,726,726 ,0,0,0}, {4362,4360,4181 ,726,3295,726 ,0,0,0}, + {4171,4353,4350 ,726,726,3295 ,0,0,0}, {4360,4359,4178 ,3295,3295,3295 ,0,0,0}, + {4169,4350,4348 ,3295,3295,726 ,0,0,0}, {4347,4166,4348 ,726,3295,726 ,0,0,0}, + {4172,4175,4354 ,3295,3295,726 ,0,0,0}, {4344,4342,4163 ,726,726,3295 ,0,0,0}, + {4172,4353,4171 ,3295,726,726 ,0,0,0}, {4581,4582,4265 ,726,726,726 ,0,0,0}, + {4350,4169,4171 ,3295,3295,726 ,0,0,0}, {4582,4585,4266 ,726,726,726 ,0,0,0}, + {4348,4166,4169 ,726,3295,3295 ,0,0,0}, {4585,4587,4268 ,726,726,726 ,0,0,0}, + {4004,4497,4005 ,3295,3295,726 ,0,0,0}, {4005,4501,4007 ,726,3295,726 ,0,0,0}, + {4342,4160,4163 ,726,726,3295 ,0,0,0}, {4271,4268,4587 ,726,726,726 ,0,0,0}, + {4262,4260,4579 ,726,726,726 ,0,0,0}, {4271,4588,4272 ,726,726,726 ,0,0,0}, + {4265,4262,4581 ,726,726,726 ,0,0,0}, {4591,4274,4272 ,726,726,726 ,0,0,0}, + {4266,4265,4582 ,726,726,726 ,0,0,0}, {4593,4277,4274 ,726,726,726 ,0,0,0}, + {4268,4266,4585 ,726,726,726 ,0,0,0}, {3968,4538,3967 ,726,3295,3295 ,0,0,0}, + {4278,4277,4594 ,726,726,726 ,0,0,0}, {4587,4588,4271 ,726,726,726 ,0,0,0}, + {4280,4278,4597 ,726,726,726 ,0,0,0}, {4280,4597,4599 ,726,726,726 ,0,0,0}, + {3971,4542,4541 ,3295,3295,726 ,0,0,0}, {4591,4593,4274 ,726,726,726 ,0,0,0}, + {3974,4547,4544 ,3295,3295,3295 ,0,0,0}, {4600,4283,4599 ,726,726,726 ,0,0,0}, + {4593,4594,4277 ,726,726,726 ,0,0,0}, {4284,4600,4603 ,726,726,726 ,0,0,0}, + {4594,4597,4278 ,726,726,726 ,0,0,0}, {3980,4553,4550 ,3295,3294,3295 ,0,0,0}, + {4599,4283,4280 ,726,726,726 ,0,0,0}, {4603,4605,4286 ,726,726,726 ,0,0,0}, + {4284,4283,4600 ,726,726,726 ,0,0,0}, {4606,4289,4605 ,726,726,726 ,0,0,0}, + {3983,3985,4554 ,726,3295,3295 ,0,0,0}, {4609,4290,4606 ,726,726,726 ,0,0,0}, + {4286,4284,4603 ,726,726,726 ,0,0,0}, {3989,3991,4560 ,726,726,726 ,0,0,0}, + {4605,4289,4286 ,726,726,726 ,0,0,0}, {4292,4609,4611 ,726,726,726 ,0,0,0}, + {3992,3995,4565 ,726,3295,726 ,0,0,0}, {4606,4290,4289 ,726,726,726 ,0,0,0}, + {4295,4292,4611 ,3295,726,726 ,0,0,0}, {4296,4295,4612 ,726,3295,726 ,0,0,0}, + {3997,3998,4566 ,726,726,3295 ,0,0,0}, {4295,4611,4612 ,3295,726,726 ,0,0,0}, + {4573,4572,4296 ,3295,726,726 ,0,0,0}, {4572,4001,4296 ,726,726,726 ,0,0,0}, + {4612,4573,4296 ,726,3295,726 ,0,0,0}, {4609,4292,4290 ,726,726,726 ,0,0,0}, + {4159,4341,4305 ,3295,3295,3295 ,0,0,0}, {4157,4305,4308 ,3295,3295,3295 ,0,0,0}, + {4153,4308,4303 ,3295,3295,3295 ,0,0,0}, {4187,4303,4307 ,726,3295,726 ,0,0,0}, + {4307,4310,4189 ,726,3295,3295 ,0,0,0}, {4230,4619,4617 ,726,726,726 ,0,0,0}, + {4305,4157,4159 ,3295,3295,3295 ,0,0,0}, {4310,4313,4190 ,3295,3295,726 ,0,0,0}, + {4308,4153,4157 ,3295,3295,3295 ,0,0,0}, {4234,4237,4625 ,726,726,726 ,0,0,0}, + {4153,4303,4187 ,3295,3295,726 ,0,0,0}, {4314,4192,4313 ,726,726,3295 ,0,0,0}, + {4307,4189,4187 ,726,3295,726 ,0,0,0}, {4196,4318,4317 ,726,3295,3295 ,0,0,0}, + {4310,4190,4189 ,3295,726,3295 ,0,0,0}, {4198,4196,4317 ,3295,726,3295 ,0,0,0}, + {4313,4192,4190 ,3295,726,726 ,0,0,0}, {4321,4201,4198 ,726,3295,3295 ,0,0,0}, + {4314,4195,4192 ,726,3295,726 ,0,0,0}, {4325,4202,4201 ,726,726,3295 ,0,0,0}, + {4327,4204,4202 ,3295,726,726 ,0,0,0}, {4634,4244,4635 ,726,726,726 ,0,0,0}, + {4198,4317,4321 ,3295,3295,726 ,0,0,0}, {4322,4207,4204 ,726,3295,726 ,0,0,0}, + {4201,4321,4325 ,3295,726,726 ,0,0,0}, {4207,4328,4208 ,3295,726,3295 ,0,0,0}, + {4202,4325,4327 ,726,726,3295 ,0,0,0}, {4210,4208,4329 ,3295,3295,726 ,0,0,0}, + {4207,4322,4328 ,3295,726,726 ,0,0,0}, {4213,4335,4334 ,3295,726,3295 ,0,0,0}, + {4208,4328,4329 ,3295,726,726 ,0,0,0}, {4337,4214,4334 ,3295,3294,3295 ,0,0,0}, + {4210,4329,4335 ,3295,726,726 ,0,0,0}, {4337,4219,4216 ,3295,726,726 ,0,0,0}, + {4214,4213,4334 ,3294,3295,3295 ,0,0,0}, {4219,4297,4222 ,726,726,726 ,0,0,0}, + {4299,4222,4297 ,3295,726,726 ,0,0,0}, {4649,4259,4222 ,726,726,726 ,0,0,0}, + {4337,4339,4219 ,3295,726,726 ,0,0,0}, {4204,4327,4322 ,726,3295,726 ,0,0,0}, + {4166,4347,4165 ,3295,726,726 ,0,0,0}, {4177,4359,4356 ,726,3295,3295 ,0,0,0}, + {4175,4356,4354 ,3295,3295,726 ,0,0,0}, {4094,4421,4422 ,3295,726,3295 ,0,0,0}, + {4148,4371,4151 ,3295,3295,726 ,0,0,0}, {4109,4100,4434 ,3295,726,726 ,0,0,0}, + {4372,4371,4146 ,3294,3295,3295 ,0,0,0}, {4136,4139,4674 ,726,3295,3295 ,0,0,0}, + {4138,4372,4145 ,726,3294,3295 ,0,0,0}, {4675,4128,4127 ,3295,3295,726 ,0,0,0}, + {4119,3950,3931 ,726,726,726 ,0,0,0}, {4130,4676,4127 ,3295,726,726 ,0,0,0}, + {4119,3931,4672 ,726,726,726 ,0,0,0}, {4377,4107,4103 ,726,726,3295 ,0,0,0}, + {4099,4427,4428 ,3295,726,726 ,0,0,0}, {4661,4059,4047 ,3295,3295,3295 ,0,0,0}, + {4416,4419,4093 ,3295,3295,3295 ,0,0,0}, {4088,4409,4410 ,3294,3295,3294 ,0,0,0}, + {4397,4398,4071 ,3295,3295,726 ,0,0,0}, {4451,3939,4452 ,3295,3295,3295 ,0,0,0}, + {4074,4392,4395 ,3295,726,3295 ,0,0,0}, {4404,4087,4072 ,726,726,726 ,0,0,0}, + {4087,4404,4407 ,726,726,3295 ,0,0,0}, {4090,4413,4415 ,3295,3295,3295 ,0,0,0}, + {4425,4094,4422 ,726,3295,3295 ,0,0,0}, {4425,4096,4094 ,726,726,3295 ,0,0,0}, + {4100,4099,4431 ,726,3295,726 ,0,0,0}, {4434,4436,4109 ,726,726,3295 ,0,0,0}, + {4109,4378,4106 ,3295,3295,3295 ,0,0,0}, {4103,4102,4377 ,3295,3295,726 ,0,0,0}, + {4675,4677,4128 ,3295,726,3295 ,0,0,0}, {4678,4679,4142 ,726,3295,726 ,0,0,0}, + {4679,4680,4142 ,3295,726,726 ,0,0,0}, {4681,4674,4139 ,726,3295,3295 ,0,0,0}, + {4674,4682,4136 ,3295,726,726 ,0,0,0}, {4107,4377,4374 ,726,726,726 ,0,0,0}, + {4378,4377,4102 ,3295,726,3295 ,0,0,0}, {4378,4109,4436 ,3295,3295,726 ,0,0,0}, + {4434,4100,4433 ,726,726,726 ,0,0,0}, {4431,4099,4428 ,726,3295,726 ,0,0,0}, + {4427,4096,4425 ,726,726,726 ,0,0,0}, {4094,4093,4421 ,3295,3295,726 ,0,0,0}, + {4093,4090,4416 ,3295,3295,3295 ,0,0,0}, {4088,4410,4413 ,3294,3294,3295 ,0,0,0}, + {4087,4407,4409 ,726,3295,3295 ,0,0,0}, {4072,4403,4404 ,726,3295,726 ,0,0,0}, + {4071,4398,4401 ,726,3295,3295 ,0,0,0}, {4074,4395,4397 ,3295,3295,3295 ,0,0,0}, + {4074,4076,4392 ,3295,3295,726 ,0,0,0}, {4078,4389,4391 ,726,3295,3295 ,0,0,0}, + {4081,4385,4386 ,3295,726,726 ,0,0,0}, {4082,4379,4383 ,726,3295,726 ,0,0,0}, + {4083,4439,4437 ,726,3295,3295 ,0,0,0}, {4652,4442,4440 ,3295,726,726 ,0,0,0}, + {4653,4446,4445 ,3295,3295,3295 ,0,0,0}, {4656,4451,4448 ,726,3295,726 ,0,0,0}, + {3870,3937,3868 ,726,3295,3295 ,0,0,0}, {3874,3877,3935 ,3295,3295,3295 ,0,0,0}, + {4454,4452,3867 ,3295,3295,726 ,0,0,0}, {3934,3876,3874 ,3295,726,3295 ,0,0,0}, + {3880,3941,4068 ,3295,726,3295 ,0,0,0}, {4683,4668,4684 ,726,3295,3295 ,0,0,0}, + {4053,4685,4051 ,726,3295,3295 ,0,0,0}, {4686,4053,4054 ,726,726,3295 ,0,0,0}, + {4048,4660,4049 ,3295,3295,726 ,0,0,0}, {4048,4051,4687 ,3295,3295,726 ,0,0,0}, + {4688,4058,4667 ,726,726,3295 ,0,0,0}, {4689,4064,4063 ,3295,3295,3295 ,0,0,0}, + {4683,4659,4658 ,726,3295,3295 ,0,0,0}, {3890,4463,3888 ,3295,3295,3295 ,0,0,0}, + {3885,4460,4458 ,3295,3295,3295 ,0,0,0}, {3894,3896,4469 ,3295,3295,726 ,0,0,0}, + {3891,4466,4464 ,726,726,726 ,0,0,0}, {4475,3897,4655 ,3295,3295,726 ,0,0,0}, + {4655,4662,4475 ,726,3295,3295 ,0,0,0}, {4472,3897,4475 ,726,3295,3295 ,0,0,0}, + {4472,4470,3896 ,726,726,3295 ,0,0,0}, {4478,4476,4662 ,726,726,3295 ,0,0,0}, + {4663,4481,4651 ,3295,726,726 ,0,0,0}, {4651,4478,4662 ,726,726,3295 ,0,0,0}, + {4663,4484,4482 ,3295,726,3295 ,0,0,0}, {4664,4044,4487 ,3295,3295,3295 ,0,0,0}, + {4663,4664,4484 ,3295,3295,726 ,0,0,0}, {4488,4487,4044 ,726,3295,3295 ,0,0,0}, + {4488,4041,4490 ,726,3295,3295 ,0,0,0}, {4493,4041,4039 ,3295,3295,3295 ,0,0,0}, + {4113,3910,4115 ,726,3295,726 ,0,0,0}, {4672,4673,4123 ,726,3295,726 ,0,0,0}, + {3904,3901,3960 ,3295,726,726 ,0,0,0}, {4670,4120,4122 ,726,726,726 ,0,0,0}, + {4671,4120,4669 ,3295,726,726 ,0,0,0}, {4676,4130,4671 ,726,3295,3295 ,0,0,0}, + {4675,4127,4676 ,3295,726,726 ,0,0,0}, {4132,4128,4677 ,3295,3295,726 ,0,0,0}, + {4132,4690,4142 ,3295,3295,726 ,0,0,0}, {4690,4132,4677 ,3295,3295,726 ,0,0,0}, + {4690,4678,4142 ,3295,726,726 ,0,0,0}, {4139,4680,4681 ,3295,726,726 ,0,0,0}, + {4680,4139,4142 ,726,3295,726 ,0,0,0}, {4138,3917,4374 ,726,726,726 ,0,0,0}, + {4682,3917,4138 ,726,726,726 ,0,0,0}, {4682,4138,4136 ,726,726,726 ,0,0,0}, + {3917,3914,4374 ,726,3294,726 ,0,0,0}, {4112,3914,4113 ,3295,3294,726 ,0,0,0}, + {3914,4112,4374 ,3294,3295,726 ,0,0,0}, {3915,3910,4113 ,726,3295,726 ,0,0,0}, + {3908,3911,4115 ,726,726,726 ,0,0,0}, {3910,3908,4115 ,3295,726,726 ,0,0,0}, + {3911,3902,4118 ,726,726,726 ,0,0,0}, {3904,3960,4118 ,3295,726,726 ,0,0,0}, + {3958,3960,3900 ,3295,726,3295 ,0,0,0}, {3922,3957,3919 ,726,3295,726 ,0,0,0}, + {3919,3958,3900 ,726,3295,3295 ,0,0,0}, {3924,3955,3922 ,726,726,726 ,0,0,0}, + {3924,3925,3944 ,726,3295,3295 ,0,0,0}, {3924,3943,3955 ,726,726,726 ,0,0,0}, + {3947,3928,3948 ,726,726,3295 ,0,0,0}, {3944,3925,3947 ,3295,3295,726 ,0,0,0}, + {3950,3930,3931 ,726,3294,726 ,0,0,0}, {3948,3928,3930 ,3295,726,3294 ,0,0,0}, + {4064,4691,4066 ,3295,726,3295 ,0,0,0}, {4655,4654,4659 ,726,726,3295 ,0,0,0}, + {4068,4066,3883 ,3295,3295,3295 ,0,0,0}, {4683,4684,4659 ,726,3295,3295 ,0,0,0}, + {4668,4667,4684 ,3295,3295,3295 ,0,0,0}, {4688,4667,4666 ,726,3295,3295 ,0,0,0}, + {4657,4058,4688 ,3295,726,726 ,0,0,0}, {4686,4054,4657 ,726,3295,3295 ,0,0,0}, + {4685,4053,4686 ,3295,726,726 ,0,0,0}, {4687,4051,4685 ,726,3295,3295 ,0,0,0}, + {4660,4048,4687 ,3295,3295,726 ,0,0,0}, {4047,4049,4661 ,3295,726,3295 ,0,0,0}, + {4665,4059,4661 ,726,3295,3295 ,0,0,0}, {4689,4063,4665 ,3295,3295,726 ,0,0,0}, + {4691,4064,4689 ,726,3295,3295 ,0,0,0}, {3883,4066,4691 ,3295,3295,726 ,0,0,0}, + {3880,4068,3883 ,3295,3295,3295 ,0,0,0}, {3881,3941,3880 ,3295,726,3295 ,0,0,0}, + {3934,3881,3876 ,3295,3295,726 ,0,0,0}, {3881,3934,3941 ,3295,3295,726 ,0,0,0}, + {3874,3935,3934 ,3295,3295,3295 ,0,0,0}, {3939,3937,3870 ,3295,3295,726 ,0,0,0}, + {4454,3867,3866 ,3295,726,726 ,0,0,0}, {3867,4452,3939 ,726,3295,3295 ,0,0,0}, + {3885,4458,3866 ,3295,3295,726 ,0,0,0}, {4457,4454,3866 ,726,3295,726 ,0,0,0}, + {3888,4460,3885 ,3295,3295,3295 ,0,0,0}, {3890,4464,4463 ,3295,726,3295 ,0,0,0}, + {3888,4463,4460 ,3295,3295,3295 ,0,0,0}, {3891,3894,4466 ,726,3295,726 ,0,0,0}, + {3890,3891,4464 ,3295,726,726 ,0,0,0}, {4469,3896,4470 ,726,3295,726 ,0,0,0}, + {4466,3894,4469 ,726,3295,726 ,0,0,0}, {4472,3896,3897 ,726,3295,3295 ,0,0,0}, + {4220,4338,4336 ,730,730,730 ,0,0,0}, {4002,4498,3963 ,730,730,730 ,0,0,0}, + {4073,4406,4405 ,730,730,730 ,0,0,0}, {4332,4215,4333 ,730,730,730 ,0,0,0}, + {4206,4209,4324 ,730,730,730 ,0,0,0}, {4211,4212,4331 ,730,730,730 ,0,0,0}, + {4197,4199,4316 ,730,730,730 ,0,0,0}, {4200,4203,4320 ,730,730,730 ,0,0,0}, + {4301,4304,4155 ,730,730,730 ,0,0,0}, {4191,4193,4311 ,730,730,730 ,0,0,0}, + {4500,3964,3963 ,730,730,730 ,0,0,0}, {4345,4162,4343 ,730,730,730 ,0,0,0}, + {3972,4540,4543 ,730,730,730 ,0,0,0}, {4546,4549,3978 ,730,730,730 ,0,0,0}, + {4534,4537,3966 ,730,730,730 ,0,0,0}, {4540,3972,3970 ,730,730,730 ,0,0,0}, + {4003,4496,4495 ,730,730,730 ,0,0,0}, {3964,4500,4534 ,730,730,730 ,0,0,0}, + {4008,4009,4505 ,730,730,730 ,0,0,0}, {4578,4261,4580 ,730,730,730 ,0,0,0}, + {4506,4012,4509 ,730,730,730 ,0,0,0}, {4009,4506,4505 ,730,730,730 ,0,0,0}, + {4021,4520,4020 ,730,730,730 ,0,0,0}, {4014,4510,4509 ,730,730,730 ,0,0,0}, + {4527,4526,4032 ,730,730,730 ,0,0,0}, {4525,4524,4027 ,730,730,730 ,0,0,0}, + {4033,4036,4530 ,730,730,730 ,0,0,0}, {4692,4444,4447 ,730,730,730 ,0,0,0}, + {4079,4077,4388 ,730,730,730 ,0,0,0}, {3882,3942,3940 ,730,730,730 ,0,0,0}, + {3892,4467,4468 ,730,730,730 ,0,0,0}, {4042,4492,4494 ,730,730,730 ,0,0,0}, + {4532,4040,4494 ,730,730,730 ,0,0,0}, {4693,4694,4486 ,730,730,730 ,0,0,0}, + {3895,3893,4471 ,730,730,730 ,0,0,0}, {4693,4486,4489 ,730,730,730 ,0,0,0}, + {4483,4485,4694 ,730,730,730 ,0,0,0}, {4045,4695,4046 ,730,730,730 ,0,0,0}, + {4494,4040,4042 ,730,730,730 ,0,0,0}, {4406,4073,4086 ,730,730,730 ,0,0,0}, + {4696,4085,4443 ,730,730,730 ,0,0,0}, {4384,4382,4080 ,730,730,730 ,0,0,0}, + {3892,4468,3893 ,730,730,730 ,0,0,0}, {3938,4453,4455 ,730,730,730 ,0,0,0}, + {4036,4038,4532 ,730,730,730 ,0,0,0}, {3936,3869,3933 ,730,730,730 ,0,0,0}, + {3872,3873,3933 ,730,730,730 ,0,0,0}, {4697,4061,4062 ,730,730,730 ,0,0,0}, + {4693,4489,4043 ,730,730,730 ,0,0,0}, {4042,4043,4491 ,730,730,730 ,0,0,0}, + {4698,4483,4694 ,730,730,730 ,0,0,0}, {4479,4480,4699 ,730,730,730 ,0,0,0}, + {4699,4480,4698 ,730,730,730 ,0,0,0}, {4698,4480,4483 ,730,730,730 ,0,0,0}, + {4694,4485,4486 ,730,730,730 ,0,0,0}, {4700,4701,4702 ,730,730,730 ,0,0,0}, + {3951,3952,3929 ,730,730,730 ,0,0,0}, {4489,4491,4043 ,730,730,730 ,0,0,0}, + {4473,3895,4471 ,730,730,730 ,0,0,0}, {4492,4042,4491 ,730,730,730 ,0,0,0}, + {4703,4057,4055 ,730,730,730 ,0,0,0}, {4062,4065,4704 ,730,730,730 ,0,0,0}, + {4067,3942,3879 ,730,730,730 ,0,0,0}, {4065,4067,3878 ,730,730,730 ,0,0,0}, + {4532,4038,4040 ,730,730,730 ,0,0,0}, {4046,4705,4050 ,730,730,730 ,0,0,0}, + {4706,4060,4061 ,730,730,730 ,0,0,0}, {3938,4455,3865 ,730,730,730 ,0,0,0}, + {4050,4707,4052 ,730,730,730 ,0,0,0}, {3889,4467,3892 ,730,730,730 ,0,0,0}, + {4467,3889,4465 ,730,730,730 ,0,0,0}, {4380,4084,4381 ,730,730,730 ,0,0,0}, + {4396,4070,4399 ,730,730,730 ,0,0,0}, {4393,4390,4075 ,730,730,730 ,0,0,0}, + {4414,4412,4089 ,730,730,730 ,0,0,0}, {4402,4069,4073 ,730,730,730 ,0,0,0}, + {4414,4089,4091 ,730,730,730 ,0,0,0}, {4032,4033,4527 ,730,730,730 ,0,0,0}, + {4036,4532,4530 ,730,730,730 ,0,0,0}, {4530,4527,4033 ,730,730,730 ,0,0,0}, + {4546,3976,4545 ,730,730,730 ,0,0,0}, {4525,4027,4030 ,730,730,730 ,0,0,0}, + {4526,4030,4032 ,730,730,730 ,0,0,0}, {4026,4027,4524 ,730,730,730 ,0,0,0}, + {4525,4030,4526 ,730,730,730 ,0,0,0}, {4026,4518,4024 ,730,730,730 ,0,0,0}, + {4517,4021,4024 ,730,730,730 ,0,0,0}, {4524,4518,4026 ,730,730,730 ,0,0,0}, + {4021,4517,4520 ,730,730,730 ,0,0,0}, {4024,4518,4517 ,730,730,730 ,0,0,0}, + {4355,4174,4173 ,730,730,730 ,0,0,0}, {4514,4018,4020 ,730,730,730 ,0,0,0}, + {4018,4513,4015 ,730,730,730 ,0,0,0}, {4513,4510,4015 ,730,730,730 ,0,0,0}, + {4510,4014,4015 ,730,730,730 ,0,0,0}, {4509,4012,4014 ,730,730,730 ,0,0,0}, + {4506,4009,4012 ,730,730,730 ,0,0,0}, {4006,4503,4496 ,730,730,730 ,0,0,0}, + {4008,4505,4503 ,730,730,730 ,0,0,0}, {4003,4495,4002 ,730,730,730 ,0,0,0}, + {4498,4500,3963 ,730,730,730 ,0,0,0}, {3966,4537,3969 ,730,730,730 ,0,0,0}, + {3970,3969,4539 ,730,730,730 ,0,0,0}, {3972,4543,3975 ,730,730,730 ,0,0,0}, + {3970,4539,4540 ,730,730,730 ,0,0,0}, {3975,4545,3976 ,730,730,730 ,0,0,0}, + {3975,4543,4545 ,730,730,730 ,0,0,0}, {3981,4549,4551 ,730,730,730 ,0,0,0}, + {3978,3976,4546 ,730,730,730 ,0,0,0}, {3982,3981,4551 ,730,730,730 ,0,0,0}, + {3982,4551,4552 ,730,730,730 ,0,0,0}, {3984,4552,4555 ,730,730,730 ,0,0,0}, + {3982,4552,3984 ,730,730,730 ,0,0,0}, {4555,3987,3984 ,730,730,730 ,0,0,0}, + {4555,4557,3987 ,730,730,730 ,0,0,0}, {3987,4557,3988 ,730,730,730 ,0,0,0}, + {3969,4537,4539 ,730,730,730 ,0,0,0}, {3990,3988,4558 ,730,730,730 ,0,0,0}, + {3988,4557,4558 ,730,730,730 ,0,0,0}, {4561,3993,3990 ,730,730,730 ,0,0,0}, + {4561,3990,4558 ,730,730,730 ,0,0,0}, {3993,4563,3994 ,730,730,730 ,0,0,0}, + {3994,4564,3996 ,730,730,730 ,0,0,0}, {4564,3994,4563 ,730,730,730 ,0,0,0}, + {4564,4567,3999 ,730,730,730 ,0,0,0}, {4291,4610,4608 ,730,730,730 ,0,0,0}, + {4000,3999,4567 ,730,730,730 ,0,0,0}, {4570,4574,4294 ,730,730,730 ,0,0,0}, + {4293,4613,4610 ,730,730,730 ,0,0,0}, {3966,3964,4534 ,730,730,730 ,0,0,0}, + {4227,4614,4225 ,730,730,730 ,0,0,0}, {4613,4293,4294 ,730,730,730 ,0,0,0}, + {4495,4498,4002 ,730,730,730 ,0,0,0}, {4349,4167,4346 ,730,730,730 ,0,0,0}, + {4170,4168,4351 ,730,730,730 ,0,0,0}, {4168,4167,4349 ,730,730,730 ,0,0,0}, + {4164,4162,4345 ,730,730,730 ,0,0,0}, {4345,4346,4164 ,730,730,730 ,0,0,0}, + {4343,4161,4340 ,730,730,730 ,0,0,0}, {4343,4162,4161 ,730,730,730 ,0,0,0}, + {4306,4340,4158 ,730,730,730 ,0,0,0}, {4161,4158,4340 ,730,730,730 ,0,0,0}, + {4156,4304,4306 ,730,730,730 ,0,0,0}, {4306,4158,4156 ,730,730,730 ,0,0,0}, + {4302,4154,4188 ,730,730,730 ,0,0,0}, {4155,4304,4156 ,730,730,730 ,0,0,0}, + {4188,4191,4309 ,730,730,730 ,0,0,0}, {4154,4302,4301 ,730,730,730 ,0,0,0}, + {4302,4188,4309 ,730,730,730 ,0,0,0}, {4315,4312,4194 ,730,730,730 ,0,0,0}, + {4236,4626,4627 ,730,730,730 ,0,0,0}, {4197,4315,4194 ,730,730,730 ,0,0,0}, + {4193,4194,4312 ,730,730,730 ,0,0,0}, {4319,4200,4320 ,730,730,730 ,0,0,0}, + {4316,4315,4197 ,730,730,730 ,0,0,0}, {4203,4326,4320 ,730,730,730 ,0,0,0}, + {4200,4319,4199 ,730,730,730 ,0,0,0}, {4206,4323,4205 ,730,730,730 ,0,0,0}, + {4205,4323,4326 ,730,730,730 ,0,0,0}, {4330,4324,4209 ,730,730,730 ,0,0,0}, + {4324,4323,4206 ,730,730,730 ,0,0,0}, {4212,4332,4331 ,730,730,730 ,0,0,0}, + {4211,4331,4330 ,730,730,730 ,0,0,0}, {4336,4217,4218 ,730,730,730 ,0,0,0}, + {4217,4333,4215 ,730,730,730 ,0,0,0}, {4336,4218,4220 ,730,730,730 ,0,0,0}, + {4567,4569,4000 ,730,730,730 ,0,0,0}, {4570,4000,4569 ,730,730,730 ,0,0,0}, + {4288,4607,4287 ,730,730,730 ,0,0,0}, {3999,3996,4564 ,730,730,730 ,0,0,0}, + {4293,4610,4291 ,730,730,730 ,0,0,0}, {3993,4561,4563 ,730,730,730 ,0,0,0}, + {4285,4287,4604 ,730,730,730 ,0,0,0}, {4608,4607,4288 ,730,730,730 ,0,0,0}, + {4282,4285,4602 ,730,730,730 ,0,0,0}, {4607,4604,4287 ,730,730,730 ,0,0,0}, + {4601,4281,4282 ,730,730,730 ,0,0,0}, {4598,4279,4281 ,730,730,730 ,0,0,0}, + {4602,4285,4604 ,730,730,730 ,0,0,0}, {4596,4276,4279 ,730,730,730 ,0,0,0}, + {4601,4282,4602 ,730,730,730 ,0,0,0}, {3978,4549,3981 ,730,730,730 ,0,0,0}, + {4601,4598,4281 ,730,730,730 ,0,0,0}, {4595,4592,4275 ,730,730,730 ,0,0,0}, + {4598,4596,4279 ,730,730,730 ,0,0,0}, {4592,4590,4273 ,730,730,730 ,0,0,0}, + {4590,4589,4270 ,730,730,730 ,0,0,0}, {4589,4586,4269 ,730,730,730 ,0,0,0}, + {4276,4595,4275 ,730,730,730 ,0,0,0}, {4586,4584,4267 ,730,730,730 ,0,0,0}, + {4275,4592,4273 ,730,730,730 ,0,0,0}, {4583,4264,4584 ,730,730,730 ,0,0,0}, + {4273,4590,4270 ,730,730,730 ,0,0,0}, {4263,4583,4580 ,730,730,730 ,0,0,0}, + {4270,4589,4269 ,730,730,730 ,0,0,0}, {4261,4578,4226 ,730,730,730 ,0,0,0}, + {4269,4586,4267 ,730,730,730 ,0,0,0}, {4227,4226,4577 ,730,730,730 ,0,0,0}, + {4584,4264,4267 ,730,730,730 ,0,0,0}, {4225,4615,4229 ,730,730,730 ,0,0,0}, + {4263,4264,4583 ,730,730,730 ,0,0,0}, {4352,4170,4351 ,730,730,730 ,0,0,0}, + {4008,4503,4006 ,730,730,730 ,0,0,0}, {4006,4496,4003 ,730,730,730 ,0,0,0}, + {4226,4578,4577 ,730,730,730 ,0,0,0}, {4352,4355,4173 ,730,730,730 ,0,0,0}, + {4227,4577,4614 ,730,730,730 ,0,0,0}, {4355,4357,4174 ,730,730,730 ,0,0,0}, + {4225,4614,4615 ,730,730,730 ,0,0,0}, {4357,4358,4176 ,730,730,730 ,0,0,0}, + {4358,4361,4179 ,730,730,730 ,0,0,0}, {4349,4351,4168 ,730,730,730 ,0,0,0}, + {4361,4363,4180 ,730,730,730 ,0,0,0}, {4173,4170,4352 ,730,730,730 ,0,0,0}, + {4363,4364,4182 ,730,730,730 ,0,0,0}, {4020,4520,4514 ,730,730,730 ,0,0,0}, + {4018,4514,4513 ,730,730,730 ,0,0,0}, {4357,4176,4174 ,730,730,730 ,0,0,0}, + {4149,4367,4369 ,730,730,730 ,0,0,0}, {4358,4179,4176 ,730,730,730 ,0,0,0}, + {4141,4708,4709 ,730,730,730 ,0,0,0}, {4361,4180,4179 ,730,730,730 ,0,0,0}, + {3946,3949,3926 ,730,730,730 ,0,0,0}, {3920,3954,3921 ,730,730,730 ,0,0,0}, + {4185,4367,4150 ,730,730,730 ,0,0,0}, {4104,4373,4375 ,730,730,730 ,0,0,0}, + {4110,4108,4376 ,730,730,730 ,0,0,0}, {3923,3945,3946 ,730,730,730 ,0,0,0}, + {4098,4432,4430 ,730,730,730 ,0,0,0}, {4710,4124,4711 ,730,730,730 ,0,0,0}, + {4373,4104,4111 ,730,730,730 ,0,0,0}, {4092,4423,4420 ,730,730,730 ,0,0,0}, + {4474,3898,3895 ,730,730,730 ,0,0,0}, {4712,4477,4699 ,730,730,730 ,0,0,0}, + {4479,4699,4477 ,730,730,730 ,0,0,0}, {4477,4712,3898 ,730,730,730 ,0,0,0}, + {4713,4714,4715 ,730,730,730 ,0,0,0}, {4477,3898,4474 ,730,730,730 ,0,0,0}, + {4473,4474,3895 ,730,730,730 ,0,0,0}, {3875,3940,3873 ,730,730,730 ,0,0,0}, + {4706,4695,4060 ,730,730,730 ,0,0,0}, {4716,4717,4718 ,730,730,730 ,0,0,0}, + {4380,4438,4084 ,730,730,730 ,0,0,0}, {4070,4394,4075 ,730,730,730 ,0,0,0}, + {4411,4086,4089 ,730,730,730 ,0,0,0}, {4424,4095,4097 ,730,730,730 ,0,0,0}, + {4424,4423,4095 ,730,730,730 ,0,0,0}, {4426,4097,4429 ,730,730,730 ,0,0,0}, + {4420,4418,4092 ,730,730,730 ,0,0,0}, {4418,4417,4091 ,730,730,730 ,0,0,0}, + {4086,4411,4408 ,730,730,730 ,0,0,0}, {4402,4400,4069 ,730,730,730 ,0,0,0}, + {4069,4399,4070 ,730,730,730 ,0,0,0}, {4394,4393,4075 ,730,730,730 ,0,0,0}, + {4388,4387,4079 ,730,730,730 ,0,0,0}, {4384,4080,4079 ,730,730,730 ,0,0,0}, + {4429,4098,4430 ,730,730,730 ,0,0,0}, {4382,4381,4080 ,730,730,730 ,0,0,0}, + {4438,4085,4084 ,730,730,730 ,0,0,0}, {4441,4443,4085 ,730,730,730 ,0,0,0}, + {4449,4719,4692 ,730,730,730 ,0,0,0}, {4719,4449,4450 ,730,730,730 ,0,0,0}, + {3938,4719,4453 ,730,730,730 ,0,0,0}, {3884,4456,4459 ,730,730,730 ,0,0,0}, + {3887,3886,4462 ,730,730,730 ,0,0,0}, {3884,3865,4456 ,730,730,730 ,0,0,0}, + {4450,4453,4719 ,730,730,730 ,0,0,0}, {4447,4449,4692 ,730,730,730 ,0,0,0}, + {4443,4444,4696 ,730,730,730 ,0,0,0}, {4444,4692,4696 ,730,730,730 ,0,0,0}, + {4438,4441,4085 ,730,730,730 ,0,0,0}, {4381,4084,4080 ,730,730,730 ,0,0,0}, + {4384,4079,4387 ,730,730,730 ,0,0,0}, {4077,4075,4390 ,730,730,730 ,0,0,0}, + {4077,4390,4388 ,730,730,730 ,0,0,0}, {4070,4396,4394 ,730,730,730 ,0,0,0}, + {4069,4400,4399 ,730,730,730 ,0,0,0}, {4073,4405,4402 ,730,730,730 ,0,0,0}, + {4086,4408,4406 ,730,730,730 ,0,0,0}, {4089,4412,4411 ,730,730,730 ,0,0,0}, + {4091,4417,4414 ,730,730,730 ,0,0,0}, {4091,4092,4418 ,730,730,730 ,0,0,0}, + {4092,4095,4423 ,730,730,730 ,0,0,0}, {4097,4426,4424 ,730,730,730 ,0,0,0}, + {4097,4098,4429 ,730,730,730 ,0,0,0}, {4098,4110,4432 ,730,730,730 ,0,0,0}, + {4110,4376,4435 ,730,730,730 ,0,0,0}, {4432,4110,4435 ,730,730,730 ,0,0,0}, + {4376,4108,4105 ,730,730,730 ,0,0,0}, {4105,4101,4375 ,730,730,730 ,0,0,0}, + {4375,4376,4105 ,730,730,730 ,0,0,0}, {3927,3926,3949 ,730,730,730 ,0,0,0}, + {4104,4375,4101 ,730,730,730 ,0,0,0}, {3906,4116,4117 ,730,730,730 ,0,0,0}, + {3927,3949,3951 ,730,730,730 ,0,0,0}, {3952,4125,3932 ,730,730,730 ,0,0,0}, + {3951,3929,3927 ,730,730,730 ,0,0,0}, {3952,3932,3929 ,730,730,730 ,0,0,0}, + {4133,4720,4126 ,730,730,730 ,0,0,0}, {4129,4721,4121 ,730,730,730 ,0,0,0}, + {4722,4134,4723 ,730,730,730 ,0,0,0}, {4141,4724,4723 ,730,730,730 ,0,0,0}, + {3956,3918,3959 ,730,730,730 ,0,0,0}, {4725,4140,4726 ,730,730,730 ,0,0,0}, + {3920,3918,3956 ,730,730,730 ,0,0,0}, {4369,4144,4147 ,730,730,730 ,0,0,0}, + {4370,4143,4144 ,730,730,730 ,0,0,0}, {3909,4116,3907 ,730,730,730 ,0,0,0}, + {4117,3903,3906 ,730,730,730 ,0,0,0}, {3909,3916,4114 ,730,730,730 ,0,0,0}, + {4137,4143,4370 ,730,730,730 ,0,0,0}, {4137,4370,4373 ,730,730,730 ,0,0,0}, + {4144,4369,4370 ,730,730,730 ,0,0,0}, {4149,4369,4147 ,730,730,730 ,0,0,0}, + {4150,4367,4149 ,730,730,730 ,0,0,0}, {4364,4367,4185 ,730,730,730 ,0,0,0}, + {4182,4364,4185 ,730,730,730 ,0,0,0}, {4180,4363,4182 ,730,730,730 ,0,0,0}, + {4229,4618,4231 ,730,730,730 ,0,0,0}, {4621,4231,4620 ,730,730,730 ,0,0,0}, + {4164,4346,4167 ,730,730,730 ,0,0,0}, {4624,4232,4621 ,730,730,730 ,0,0,0}, + {4624,4235,4232 ,730,730,730 ,0,0,0}, {4626,4236,4235 ,730,730,730 ,0,0,0}, + {4618,4229,4615 ,730,730,730 ,0,0,0}, {4627,4242,4236 ,730,730,730 ,0,0,0}, + {4620,4231,4618 ,730,730,730 ,0,0,0}, {4154,4301,4155 ,730,730,730 ,0,0,0}, + {4238,4242,4630 ,730,730,730 ,0,0,0}, {4232,4231,4621 ,730,730,730 ,0,0,0}, + {4239,4238,4632 ,730,730,730 ,0,0,0}, {4624,4626,4235 ,730,730,730 ,0,0,0}, + {4245,4239,4633 ,730,730,730 ,0,0,0}, {4193,4312,4311 ,730,730,730 ,0,0,0}, + {4191,4311,4309 ,730,730,730 ,0,0,0}, {4242,4627,4630 ,730,730,730 ,0,0,0}, + {4246,4245,4636 ,730,730,730 ,0,0,0}, {4246,4636,4638 ,730,730,730 ,0,0,0}, + {4630,4632,4238 ,730,730,730 ,0,0,0}, {4199,4319,4316 ,730,730,730 ,0,0,0}, + {4239,4632,4633 ,730,730,730 ,0,0,0}, {4638,4639,4249 ,730,730,730 ,0,0,0}, + {4642,4255,4639 ,730,730,730 ,0,0,0}, {4633,4636,4245 ,730,730,730 ,0,0,0}, + {4249,4246,4638 ,730,730,730 ,0,0,0}, {4644,4253,4642 ,730,730,730 ,0,0,0}, + {4203,4205,4326 ,730,730,730 ,0,0,0}, {4645,4251,4644 ,730,730,730 ,0,0,0}, + {4255,4249,4639 ,730,730,730 ,0,0,0}, {4209,4211,4330 ,730,730,730 ,0,0,0}, + {4642,4253,4255 ,730,730,730 ,0,0,0}, {4645,4648,4256 ,730,730,730 ,0,0,0}, + {4212,4215,4332 ,730,730,730 ,0,0,0}, {4644,4251,4253 ,730,730,730 ,0,0,0}, + {4258,4256,4648 ,730,730,730 ,0,0,0}, {4258,4650,4221 ,730,730,730 ,0,0,0}, + {4333,4217,4336 ,730,730,730 ,0,0,0}, {4258,4648,4650 ,730,730,730 ,0,0,0}, + {4300,4220,4221 ,730,730,730 ,0,0,0}, {4338,4220,4300 ,730,730,730 ,0,0,0}, + {4650,4298,4221 ,730,730,730 ,0,0,0}, {4300,4221,4298 ,730,730,730 ,0,0,0}, + {4645,4256,4251 ,730,730,730 ,0,0,0}, {4261,4263,4580 ,730,730,730 ,0,0,0}, + {4595,4276,4596 ,730,730,730 ,0,0,0}, {4608,4288,4291 ,730,730,730 ,0,0,0}, + {4570,4294,4000 ,730,730,730 ,0,0,0}, {4574,4613,4294 ,730,730,730 ,0,0,0}, + {3921,3953,3923 ,730,730,730 ,0,0,0}, {4727,4129,4131 ,730,730,730 ,0,0,0}, + {4133,4722,4720 ,730,730,730 ,0,0,0}, {3923,3946,3926 ,730,730,730 ,0,0,0}, + {3923,3953,3945 ,730,730,730 ,0,0,0}, {3921,3954,3953 ,730,730,730 ,0,0,0}, + {3920,3956,3954 ,730,730,730 ,0,0,0}, {4135,4137,4728 ,730,730,730 ,0,0,0}, + {3899,3905,3959 ,730,730,730 ,0,0,0}, {3899,3959,3918 ,730,730,730 ,0,0,0}, + {4117,3905,3903 ,730,730,730 ,0,0,0}, {3905,4117,3959 ,730,730,730 ,0,0,0}, + {3912,4137,4373 ,730,730,730 ,0,0,0}, {3909,4114,4116 ,730,730,730 ,0,0,0}, + {3906,3907,4116 ,730,730,730 ,0,0,0}, {3913,4114,3916 ,730,730,730 ,0,0,0}, + {4373,3913,3912 ,730,730,730 ,0,0,0}, {4111,3913,4373 ,730,730,730 ,0,0,0}, + {3913,4111,4114 ,730,730,730 ,0,0,0}, {3912,4728,4137 ,730,730,730 ,0,0,0}, + {4135,4726,4140 ,730,730,730 ,0,0,0}, {4728,4726,4135 ,730,730,730 ,0,0,0}, + {4140,4708,4141 ,730,730,730 ,0,0,0}, {4725,4708,4140 ,730,730,730 ,0,0,0}, + {4709,4724,4141 ,730,730,730 ,0,0,0}, {4723,4134,4141 ,730,730,730 ,0,0,0}, + {4722,4133,4134 ,730,730,730 ,0,0,0}, {4729,4126,4720 ,730,730,730 ,0,0,0}, + {4131,4729,4727 ,730,730,730 ,0,0,0}, {4729,4131,4126 ,730,730,730 ,0,0,0}, + {4727,4730,4129 ,730,730,730 ,0,0,0}, {4721,4711,4121 ,730,730,730 ,0,0,0}, + {4730,4721,4129 ,730,730,730 ,0,0,0}, {4124,4710,4125 ,730,730,730 ,0,0,0}, + {4121,4711,4124 ,730,730,730 ,0,0,0}, {3932,4125,4710 ,730,730,730 ,0,0,0}, + {3936,3938,3871 ,730,730,730 ,0,0,0}, {4468,4471,3893 ,730,730,730 ,0,0,0}, + {4055,4052,4731 ,730,730,730 ,0,0,0}, {3887,4462,4465 ,730,730,730 ,0,0,0}, + {4465,3889,3887 ,730,730,730 ,0,0,0}, {4461,4462,3886 ,730,730,730 ,0,0,0}, + {4461,3884,4459 ,730,730,730 ,0,0,0}, {3884,4461,3886 ,730,730,730 ,0,0,0}, + {4456,3865,4455 ,730,730,730 ,0,0,0}, {3865,3871,3938 ,730,730,730 ,0,0,0}, + {3871,3869,3936 ,730,730,730 ,0,0,0}, {3869,3872,3933 ,730,730,730 ,0,0,0}, + {3873,3940,3933 ,730,730,730 ,0,0,0}, {3882,3940,3875 ,730,730,730 ,0,0,0}, + {3879,3942,3882 ,730,730,730 ,0,0,0}, {3878,4067,3879 ,730,730,730 ,0,0,0}, + {4704,4065,3878 ,730,730,730 ,0,0,0}, {4697,4062,4704 ,730,730,730 ,0,0,0}, + {4706,4061,4697 ,730,730,730 ,0,0,0}, {4045,4060,4695 ,730,730,730 ,0,0,0}, + {4705,4046,4695 ,730,730,730 ,0,0,0}, {4707,4050,4705 ,730,730,730 ,0,0,0}, + {4731,4052,4707 ,730,730,730 ,0,0,0}, {4732,4057,4703 ,730,730,730 ,0,0,0}, + {4703,4055,4731 ,730,730,730 ,0,0,0}, {4056,4732,4718 ,730,730,730 ,0,0,0}, + {4732,4056,4057 ,730,730,730 ,0,0,0}, {4716,4701,4717 ,730,730,730 ,0,0,0}, + {4056,4718,4717 ,730,730,730 ,0,0,0}, {4700,4702,4713 ,730,730,730 ,0,0,0}, + {4717,4701,4700 ,730,730,730 ,0,0,0}, {4713,4715,4712 ,730,730,730 ,0,0,0}, + {4713,4702,4714 ,730,730,730 ,0,0,0}, {3898,4712,4715 ,730,730,730 ,0,0,0}, + {4712,4699,4662 ,4036,4037,4038 ,0,0,0}, {4713,4655,4659 ,4039,4040,4041 ,0,0,0}, + {4655,4712,4662 ,4040,4036,4038 ,0,0,0}, {4712,4655,4713 ,4036,4040,4039 ,0,0,0}, + {4717,4684,4667 ,4042,4043,4044 ,0,0,0}, {4713,4659,4700 ,4039,4041,4045 ,0,0,0}, + {4717,4700,4684 ,4042,4045,4043 ,0,0,0}, {4667,4058,4056 ,4044,3474,3474 ,0,0,0}, + {4667,4056,4717 ,4044,3474,4042 ,0,0,0}, {4684,4700,4659 ,4043,4045,4041 ,0,0,0}, + {4699,4651,4662 ,4037,4046,4038 ,0,0,0}, {4663,4651,4698 ,4047,4046,4048 ,0,0,0}, + {4699,4698,4651 ,4037,4048,4046 ,0,0,0}, {4694,4664,4663 ,4049,4050,4047 ,0,0,0}, + {4663,4698,4694 ,4047,4048,4049 ,0,0,0}, {4664,4693,4044 ,4050,4051,3464 ,0,0,0}, + {4693,4664,4694 ,4051,4050,4049 ,0,0,0}, {4693,4043,4044 ,4051,3464,3464 ,0,0,0}, + {3939,4656,4719 ,3377,4052,4052 ,0,0,0}, {4652,4085,4696 ,4053,3500,4054 ,0,0,0}, + {4696,4692,4653 ,4054,4055,4055 ,0,0,0}, {4083,4085,4652 ,3500,3500,4053 ,0,0,0}, + {4656,4692,4719 ,4052,4055,4052 ,0,0,0}, {4692,4656,4653 ,4055,4052,4055 ,0,0,0}, + {4652,4696,4653 ,4053,4054,4055 ,0,0,0}, {4719,3938,3939 ,4052,3377,3377 ,0,0,0}, + {3917,4682,4728 ,2601,53,2600 ,0,0,0}, {4680,4708,4681 ,2596,2595,2597 ,0,0,0}, + {4725,4726,4674 ,2598,2599,139 ,0,0,0}, {4723,4690,4722 ,2590,2573,324 ,0,0,0}, + {4679,4678,4724 ,2594,2591,2592 ,0,0,0}, {4676,4727,4729 ,2575,2579,2576 ,0,0,0}, + {4675,4720,4677 ,2577,2578,2574 ,0,0,0}, {4669,4721,4730 ,2581,2582,2580 ,0,0,0}, + {4730,4727,4671 ,2580,2579,2584 ,0,0,0}, {4721,4670,4711 ,2582,2583,2588 ,0,0,0}, + {4670,4721,4669 ,2583,2582,2581 ,0,0,0}, {4710,4711,4673 ,2585,2588,2587 ,0,0,0}, + {4670,4673,4711 ,2583,2587,2588 ,0,0,0}, {4672,3932,4710 ,2586,126,2585 ,0,0,0}, + {4710,4673,4672 ,2585,2587,2586 ,0,0,0}, {3931,3932,4672 ,2589,126,2586 ,0,0,0}, + {4675,4676,4729 ,2577,2575,2576 ,0,0,0}, {4727,4676,4671 ,2579,2575,2584 ,0,0,0}, + {4669,4730,4671 ,2581,2580,2584 ,0,0,0}, {4675,4729,4720 ,2577,2576,2578 ,0,0,0}, + {4677,4720,4722 ,2574,2578,324 ,0,0,0}, {4690,4723,4678 ,2573,2590,2591 ,0,0,0}, + {4690,4677,4722 ,2573,2574,324 ,0,0,0}, {4679,4724,4709 ,2594,2592,2593 ,0,0,0}, + {4724,4678,4723 ,2592,2591,2590 ,0,0,0}, {4709,4708,4680 ,2593,2595,2596 ,0,0,0}, + {4709,4680,4679 ,2593,2596,2594 ,0,0,0}, {4674,4681,4725 ,139,2597,2598 ,0,0,0}, + {4708,4725,4681 ,2595,2598,2597 ,0,0,0}, {4726,4682,4674 ,2599,53,139 ,0,0,0}, + {3917,4728,3912 ,2601,2600,2602 ,0,0,0}, {4682,4726,4728 ,53,2599,2600 ,0,0,0}, + {3883,4691,4704 ,2630,2629,2628 ,0,0,0}, {4661,4695,4665 ,2626,2625,2627 ,0,0,0}, + {4706,4697,4689 ,2598,111,139 ,0,0,0}, {4731,4685,4703 ,2620,2603,324 ,0,0,0}, + {4660,4687,4707 ,2624,2621,2622 ,0,0,0}, {4688,4716,4718 ,2604,2608,2605 ,0,0,0}, + {4657,4732,4686 ,2606,2607,324 ,0,0,0}, {4668,4702,4701 ,2610,2611,2609 ,0,0,0}, + {4701,4716,4666 ,2609,2608,2613 ,0,0,0}, {4702,4683,4714 ,2611,2612,2618 ,0,0,0}, + {4683,4702,4668 ,2612,2611,2610 ,0,0,0}, {4715,4714,4658 ,2615,2618,2617 ,0,0,0}, + {4683,4658,4714 ,2612,2617,2618 ,0,0,0}, {4654,3898,4715 ,2616,2614,2615 ,0,0,0}, + {4715,4658,4654 ,2615,2617,2616 ,0,0,0}, {3897,3898,4654 ,2619,2614,2616 ,0,0,0}, + {4657,4688,4718 ,2606,2604,2605 ,0,0,0}, {4716,4688,4666 ,2608,2604,2613 ,0,0,0}, + {4668,4701,4666 ,2610,2609,2613 ,0,0,0}, {4657,4718,4732 ,2606,2605,2607 ,0,0,0}, + {4686,4732,4703 ,324,2607,324 ,0,0,0}, {4685,4731,4687 ,2603,2620,2621 ,0,0,0}, + {4685,4686,4703 ,2603,324,324 ,0,0,0}, {4660,4707,4705 ,2624,2622,2623 ,0,0,0}, + {4707,4687,4731 ,2622,2621,2620 ,0,0,0}, {4705,4695,4661 ,2623,2625,2626 ,0,0,0}, + {4705,4661,4660 ,2623,2626,2624 ,0,0,0}, {4689,4665,4706 ,139,2627,2598 ,0,0,0}, + {4695,4706,4665 ,2625,2598,2627 ,0,0,0}, {4697,4691,4689 ,111,2629,139 ,0,0,0}, + {3883,4704,3878 ,2630,2628,82 ,0,0,0}, {4691,4697,4704 ,2629,111,2628 ,0,0,0} +// MotorHacker.prt + , {4733,4734,4735 ,4056,4057,4058 ,0,0,0}, {4736,4737,4735 ,4059,4060,4058 ,0,0,0}, + {4733,4735,4737 ,4056,4058,4060 ,0,0,0}, {4738,4736,4739 ,4061,4059,4062 ,0,0,0}, + {4738,4737,4736 ,4061,4060,4059 ,0,0,0}, {4740,4739,4741 ,4063,4062,4064 ,0,0,0}, + {4736,4741,4739 ,4059,4064,4062 ,0,0,0}, {4742,4743,4740 ,4065,4066,4063 ,0,0,0}, + {4740,4741,4742 ,4063,4064,4065 ,0,0,0}, {4743,4744,4745 ,4066,4067,4068 ,0,0,0}, + {4744,4743,4742 ,4067,4066,4065 ,0,0,0}, {4746,4745,4747 ,4069,4068,4070 ,0,0,0}, + {4744,4747,4745 ,4067,4070,4068 ,0,0,0}, {4748,4749,4746 ,4071,4072,4069 ,0,0,0}, + {4746,4747,4748 ,4069,4070,4071 ,0,0,0}, {4750,4751,4749 ,4073,81,4072 ,0,0,0}, + {4750,4749,4748 ,4073,4072,4071 ,0,0,0}, {4751,4752,4749 ,81,81,4072 ,0,0,0}, + {4753,4734,4733 ,4074,4057,4056 ,0,0,0}, {4753,4754,4755 ,4074,4075,4076 ,0,0,0}, + {4755,4734,4753 ,4076,4057,4074 ,0,0,0}, {4756,4757,4754 ,4077,4078,4075 ,0,0,0}, + {4754,4757,4755 ,4075,4078,4076 ,0,0,0}, {4758,4759,4756 ,4079,4080,4077 ,0,0,0}, + {4756,4754,4758 ,4077,4075,4079 ,0,0,0}, {4759,4760,4761 ,4080,4081,4082 ,0,0,0}, + {4760,4759,4758 ,4081,4080,4079 ,0,0,0}, {4762,4761,4763 ,4083,4082,4084 ,0,0,0}, + {4760,4763,4761 ,4081,4084,4082 ,0,0,0}, {4764,4765,4762 ,4085,4086,4083 ,0,0,0}, + {4762,4763,4764 ,4083,4084,4085 ,0,0,0}, {4765,4766,4767 ,4086,4087,4088 ,0,0,0}, + {4766,4765,4764 ,4087,4086,4085 ,0,0,0}, {4767,4768,4769 ,4088,4089,4090 ,0,0,0}, + {4766,4768,4767 ,4087,4089,4088 ,0,0,0}, {4767,4769,4770 ,4088,4090,4091 ,0,0,0}, + {4771,4772,4773 ,2394,2394,4092 ,0,0,0}, {4774,4775,4773 ,4093,4094,4092 ,0,0,0}, + {4771,4773,4775 ,2394,4092,4094 ,0,0,0}, {4774,4776,4777 ,4093,4095,4096 ,0,0,0}, + {4777,4775,4774 ,4096,4094,4093 ,0,0,0}, {4778,4776,4779 ,4097,4095,4098 ,0,0,0}, + {4776,4778,4777 ,4095,4097,4096 ,0,0,0}, {4780,4781,4779 ,4099,4100,4098 ,0,0,0}, + {4778,4779,4781 ,4097,4098,4100 ,0,0,0}, {4780,4782,4783 ,4099,4101,4102 ,0,0,0}, + {4783,4781,4780 ,4102,4100,4099 ,0,0,0}, {4784,4782,4785 ,4103,4101,4104 ,0,0,0}, + {4782,4784,4783 ,4101,4103,4102 ,0,0,0}, {4786,4787,4785 ,4105,4106,4104 ,0,0,0}, + {4784,4785,4787 ,4103,4104,4106 ,0,0,0}, {4786,4788,4789 ,4105,4107,4108 ,0,0,0}, + {4789,4787,4786 ,4108,4106,4105 ,0,0,0}, {4790,4791,4788 ,4109,4110,4107 ,0,0,0}, + {4788,4791,4789 ,4107,4110,4108 ,0,0,0}, {4792,4793,4790 ,4111,4112,4109 ,0,0,0}, + {4790,4788,4792 ,4109,4107,4111 ,0,0,0}, {4793,4794,4795 ,4112,4113,4114 ,0,0,0}, + {4794,4793,4792 ,4113,4112,4111 ,0,0,0}, {4794,4796,4795 ,4113,4114,4114 ,0,0,0}, + {4797,4772,4771 ,4115,2394,2394 ,0,0,0}, {4797,4798,4799 ,4115,4116,4117 ,0,0,0}, + {4799,4772,4797 ,4117,2394,4115 ,0,0,0}, {4800,4798,4801 ,4118,4116,4119 ,0,0,0}, + {4798,4800,4799 ,4116,4118,4117 ,0,0,0}, {4802,4803,4801 ,4120,4121,4119 ,0,0,0}, + {4800,4801,4803 ,4118,4119,4121 ,0,0,0}, {4802,4804,4805 ,4120,4122,4123 ,0,0,0}, + {4805,4803,4802 ,4123,4121,4120 ,0,0,0}, {4806,4804,4807 ,4124,4122,4125 ,0,0,0}, + {4804,4806,4805 ,4122,4124,4123 ,0,0,0}, {4808,4809,4807 ,4126,4127,4125 ,0,0,0}, + {4806,4807,4809 ,4124,4125,4127 ,0,0,0}, {4808,4810,4811 ,4126,4128,4129 ,0,0,0}, + {4811,4809,4808 ,4129,4127,4126 ,0,0,0}, {4812,4810,4813 ,4130,4128,4131 ,0,0,0}, + {4810,4812,4811 ,4128,4130,4129 ,0,0,0}, {4813,4814,4815 ,4131,4132,4133 ,0,0,0}, + {4812,4813,4815 ,4130,4131,4133 ,0,0,0}, {4814,4816,4817 ,4132,4134,4135 ,0,0,0}, + {4816,4814,4813 ,4134,4132,4131 ,0,0,0}, {4818,4817,4819 ,126,4135,4136 ,0,0,0}, + {4816,4819,4817 ,4134,4136,4135 ,0,0,0}, {4818,4819,4820 ,126,4136,126 ,0,0,0}, + {4821,4822,4823 ,4137,4138,4139 ,0,0,0}, {4821,4824,4825 ,4137,4140,4141 ,0,0,0}, + {4824,4826,4825 ,4140,4142,4141 ,0,0,0}, {4823,4824,4821 ,4139,4140,4137 ,0,0,0}, + {4827,4828,4829 ,4143,4144,4145 ,0,0,0}, {4826,4827,4829 ,4142,4143,4145 ,0,0,0}, + {4828,4830,4831 ,4144,4146,4147 ,0,0,0}, {4830,4828,4827 ,4146,4144,4143 ,0,0,0}, + {4831,4830,4832 ,4147,4146,4148 ,0,0,0}, {4833,4831,4832 ,4149,4147,4148 ,0,0,0}, + {4833,4834,4835 ,4149,4150,4151 ,0,0,0}, {4833,4832,4834 ,4149,4148,4150 ,0,0,0}, + {4829,4825,4826 ,4145,4141,4142 ,0,0,0}, {4836,4837,4838 ,4152,1711,1711 ,0,0,0}, + {4836,4838,4835 ,4152,1711,4151 ,0,0,0}, {4834,4836,4835 ,4150,4152,4151 ,0,0,0}, + {4823,4822,4839 ,4139,4138,4153 ,0,0,0}, {4840,4839,4841 ,4154,4153,4155 ,0,0,0}, + {4822,4841,4839 ,4138,4155,4153 ,0,0,0}, {4842,4843,4840 ,4156,4157,4154 ,0,0,0}, + {4840,4841,4842 ,4154,4155,4156 ,0,0,0}, {4843,4844,4845 ,4157,4158,4159 ,0,0,0}, + {4844,4843,4842 ,4158,4157,4156 ,0,0,0}, {4846,4845,4847 ,4160,4159,4161 ,0,0,0}, + {4844,4847,4845 ,4158,4161,4159 ,0,0,0}, {4848,4849,4846 ,4162,4163,4160 ,0,0,0}, + {4846,4847,4848 ,4160,4161,4162 ,0,0,0}, {4849,4850,4851 ,4163,4164,1790 ,0,0,0}, + {4850,4849,4848 ,4164,4163,4162 ,0,0,0}, {4850,4852,4851 ,4164,1790,1790 ,0,0,0}, + {4853,4854,4855 ,4165,4166,4167 ,0,0,0}, {4856,4857,4858 ,4168,4169,4170 ,0,0,0}, + {4857,4853,4855 ,4169,4165,4167 ,0,0,0}, {4859,4856,4858 ,4171,4168,4170 ,0,0,0}, + {4857,4856,4853 ,4169,4168,4165 ,0,0,0}, {4859,4858,4860 ,4171,4170,4172 ,0,0,0}, + {4860,4861,4862 ,4172,4173,4174 ,0,0,0}, {4863,4862,4861 ,4175,4174,4173 ,0,0,0}, + {4864,4865,4866 ,4176,4177,4178 ,0,0,0}, {4861,4867,4863 ,4173,4179,4175 ,0,0,0}, + {4866,4868,4869 ,4178,4180,4181 ,0,0,0}, {4868,4867,4869 ,4180,4179,4181 ,0,0,0}, + {4863,4867,4868 ,4175,4179,4180 ,0,0,0}, {4866,4869,4864 ,4178,4181,4176 ,0,0,0}, + {4865,4864,4870 ,4177,4176,4182 ,0,0,0}, {4865,4870,4871 ,4177,4182,4183 ,0,0,0}, + {4872,4871,4870 ,4184,4183,4182 ,0,0,0}, {4873,4874,4875 ,4185,1711,4186 ,0,0,0}, + {4875,4871,4872 ,4186,4183,4184 ,0,0,0}, {4873,4875,4872 ,4185,4186,4184 ,0,0,0}, + {4873,4876,4874 ,4185,1711,1711 ,0,0,0}, {4859,4860,4862 ,4171,4172,4174 ,0,0,0}, + {4855,4854,4877 ,4167,4166,4187 ,0,0,0}, {4878,4877,4879 ,4188,4187,4189 ,0,0,0}, + {4854,4879,4877 ,4166,4189,4187 ,0,0,0}, {4880,4881,4878 ,4190,4191,4188 ,0,0,0}, + {4878,4879,4880 ,4188,4189,4190 ,0,0,0}, {4881,4882,4883 ,4191,4192,4193 ,0,0,0}, + {4882,4881,4880 ,4192,4191,4190 ,0,0,0}, {4884,4883,4885 ,4194,4193,4195 ,0,0,0}, + {4882,4885,4883 ,4192,4195,4193 ,0,0,0}, {4886,4887,4884 ,4196,4197,4194 ,0,0,0}, + {4884,4885,4886 ,4194,4195,4196 ,0,0,0}, {4887,4888,4889 ,4197,4198,4199 ,0,0,0}, + {4888,4887,4886 ,4198,4197,4196 ,0,0,0}, {4890,4889,4891 ,4200,4199,4201 ,0,0,0}, + {4888,4891,4889 ,4198,4201,4199 ,0,0,0}, {4892,4893,4890 ,4202,4203,4200 ,0,0,0}, + {4890,4891,4892 ,4200,4201,4202 ,0,0,0}, {4893,4894,4895 ,4203,4204,1790 ,0,0,0}, + {4894,4893,4892 ,4204,4203,4202 ,0,0,0}, {4894,4896,4895 ,4204,1790,1790 ,0,0,0}, + {4897,4898,4899 ,4205,4206,4207 ,0,0,0}, {4897,4900,4901 ,4205,4208,4209 ,0,0,0}, + {4900,4902,4901 ,4208,4210,4209 ,0,0,0}, {4899,4900,4897 ,4207,4208,4205 ,0,0,0}, + {4903,4904,4905 ,4211,4212,4213 ,0,0,0}, {4902,4903,4905 ,4210,4211,4213 ,0,0,0}, + {4904,4906,4907 ,4212,4214,4215 ,0,0,0}, {4906,4904,4903 ,4214,4212,4211 ,0,0,0}, + {4907,4906,4908 ,4215,4214,4216 ,0,0,0}, {4909,4907,4908 ,4217,4215,4216 ,0,0,0}, + {4909,4910,4911 ,4217,4218,4219 ,0,0,0}, {4909,4908,4910 ,4217,4216,4218 ,0,0,0}, + {4905,4901,4902 ,4213,4209,4210 ,0,0,0}, {4912,4913,4914 ,4220,1359,1359 ,0,0,0}, + {4912,4914,4911 ,4220,1359,4219 ,0,0,0}, {4910,4912,4911 ,4218,4220,4219 ,0,0,0}, + {4899,4898,4915 ,4207,4206,4221 ,0,0,0}, {4916,4915,4917 ,4222,4221,4223 ,0,0,0}, + {4898,4917,4915 ,4206,4223,4221 ,0,0,0}, {4918,4919,4916 ,4224,4225,4222 ,0,0,0}, + {4916,4917,4918 ,4222,4223,4224 ,0,0,0}, {4919,4920,4921 ,4225,4226,4227 ,0,0,0}, + {4920,4919,4918 ,4226,4225,4224 ,0,0,0}, {4922,4921,4923 ,4228,4227,4229 ,0,0,0}, + {4920,4923,4921 ,4226,4229,4227 ,0,0,0}, {4924,4925,4922 ,4230,4231,4228 ,0,0,0}, + {4922,4923,4924 ,4228,4229,4230 ,0,0,0}, {4925,4926,4927 ,4231,4232,1435 ,0,0,0}, + {4926,4925,4924 ,4232,4231,4230 ,0,0,0}, {4926,4928,4927 ,4232,1435,1435 ,0,0,0}, + {4929,4930,4931 ,4233,4234,4235 ,0,0,0}, {4932,4933,4934 ,4236,4237,4238 ,0,0,0}, + {4933,4929,4931 ,4237,4233,4235 ,0,0,0}, {4935,4932,4934 ,4239,4236,4238 ,0,0,0}, + {4933,4932,4929 ,4237,4236,4233 ,0,0,0}, {4935,4934,4936 ,4239,4238,4240 ,0,0,0}, + {4936,4937,4938 ,4240,4241,4242 ,0,0,0}, {4939,4938,4937 ,4243,4242,4241 ,0,0,0}, + {4940,4941,4942 ,4244,4245,4246 ,0,0,0}, {4937,4943,4939 ,4241,4247,4243 ,0,0,0}, + {4942,4944,4945 ,4246,4248,4249 ,0,0,0}, {4944,4943,4945 ,4248,4247,4249 ,0,0,0}, + {4939,4943,4944 ,4243,4247,4248 ,0,0,0}, {4942,4945,4940 ,4246,4249,4244 ,0,0,0}, + {4941,4940,4946 ,4245,4244,4250 ,0,0,0}, {4941,4946,4947 ,4245,4250,4251 ,0,0,0}, + {4948,4947,4946 ,4252,4251,4250 ,0,0,0}, {4949,4950,4951 ,4253,1359,4254 ,0,0,0}, + {4951,4947,4948 ,4254,4251,4252 ,0,0,0}, {4949,4951,4948 ,4253,4254,4252 ,0,0,0}, + {4949,4952,4950 ,4253,1359,1359 ,0,0,0}, {4935,4936,4938 ,4239,4240,4242 ,0,0,0}, + {4931,4930,4953 ,4235,4234,4255 ,0,0,0}, {4954,4953,4955 ,4256,4255,4257 ,0,0,0}, + {4930,4955,4953 ,4234,4257,4255 ,0,0,0}, {4956,4957,4954 ,4258,4259,4256 ,0,0,0}, + {4954,4955,4956 ,4256,4257,4258 ,0,0,0}, {4957,4958,4959 ,4259,4260,4261 ,0,0,0}, + {4958,4957,4956 ,4260,4259,4258 ,0,0,0}, {4960,4959,4961 ,4262,4261,4263 ,0,0,0}, + {4958,4961,4959 ,4260,4263,4261 ,0,0,0}, {4962,4963,4960 ,4264,4265,4262 ,0,0,0}, + {4960,4961,4962 ,4262,4263,4264 ,0,0,0}, {4963,4964,4965 ,4265,4266,4267 ,0,0,0}, + {4964,4963,4962 ,4266,4265,4264 ,0,0,0}, {4966,4965,4967 ,4268,4267,4269 ,0,0,0}, + {4964,4967,4965 ,4266,4269,4267 ,0,0,0}, {4968,4969,4966 ,4270,4271,4268 ,0,0,0}, + {4966,4967,4968 ,4268,4269,4270 ,0,0,0}, {4969,4970,4971 ,4271,4272,1435 ,0,0,0}, + {4970,4969,4968 ,4272,4271,4270 ,0,0,0}, {4970,4972,4971 ,4272,1435,1435 ,0,0,0}, + {4973,4974,4975 ,4273,4274,4275 ,0,0,0}, {4973,4976,4977 ,4273,4276,4277 ,0,0,0}, + {4976,4978,4977 ,4276,4278,4277 ,0,0,0}, {4975,4976,4973 ,4275,4276,4273 ,0,0,0}, + {4979,4980,4981 ,4279,4280,4281 ,0,0,0}, {4978,4979,4981 ,4278,4279,4281 ,0,0,0}, + {4980,4982,4983 ,4280,4282,4283 ,0,0,0}, {4982,4980,4979 ,4282,4280,4279 ,0,0,0}, + {4983,4982,4984 ,4283,4282,4284 ,0,0,0}, {4985,4983,4984 ,4285,4283,4284 ,0,0,0}, + {4985,4986,4987 ,4285,4286,4287 ,0,0,0}, {4985,4984,4986 ,4285,4284,4286 ,0,0,0}, + {4981,4977,4978 ,4281,4277,4278 ,0,0,0}, {4988,4989,4990 ,4288,126,4289 ,0,0,0}, + {4988,4990,4987 ,4288,4289,4287 ,0,0,0}, {4986,4988,4987 ,4286,4288,4287 ,0,0,0}, + {4975,4974,4991 ,4275,4274,4290 ,0,0,0}, {4992,4991,4993 ,4291,4290,4292 ,0,0,0}, + {4974,4993,4991 ,4274,4292,4290 ,0,0,0}, {4994,4995,4992 ,4293,4294,4291 ,0,0,0}, + {4992,4993,4994 ,4291,4292,4293 ,0,0,0}, {4995,4996,4997 ,4294,4295,4296 ,0,0,0}, + {4996,4995,4994 ,4295,4294,4293 ,0,0,0}, {4998,4997,4999 ,4297,4296,4298 ,0,0,0}, + {4996,4999,4997 ,4295,4298,4296 ,0,0,0}, {5000,5001,4998 ,4299,4300,4297 ,0,0,0}, + {4998,4999,5000 ,4297,4298,4299 ,0,0,0}, {5001,5002,5003 ,4300,4301,4302 ,0,0,0}, + {5002,5001,5000 ,4301,4300,4299 ,0,0,0}, {5002,5004,5003 ,4301,4303,4302 ,0,0,0}, + {5005,5006,5007 ,4304,4305,4306 ,0,0,0}, {5008,5009,5010 ,4307,4308,4309 ,0,0,0}, + {5009,5005,5007 ,4308,4304,4306 ,0,0,0}, {5011,5008,5010 ,4310,4307,4309 ,0,0,0}, + {5009,5008,5005 ,4308,4307,4304 ,0,0,0}, {5011,5010,5012 ,4310,4309,4311 ,0,0,0}, + {5012,5013,5014 ,4311,4312,4313 ,0,0,0}, {5015,5014,5013 ,4314,4313,4312 ,0,0,0}, + {5016,5017,5018 ,4315,4316,4317 ,0,0,0}, {5013,5019,5015 ,4312,4318,4314 ,0,0,0}, + {5018,5020,5021 ,4317,4319,4320 ,0,0,0}, {5020,5019,5021 ,4319,4318,4320 ,0,0,0}, + {5015,5019,5020 ,4314,4318,4319 ,0,0,0}, {5018,5021,5016 ,4317,4320,4315 ,0,0,0}, + {5017,5016,5022 ,4316,4315,4321 ,0,0,0}, {5017,5022,5023 ,4316,4321,4322 ,0,0,0}, + {5024,5023,5022 ,4323,4322,4321 ,0,0,0}, {5025,5026,5027 ,4324,126,4325 ,0,0,0}, + {5027,5023,5024 ,4325,4322,4323 ,0,0,0}, {5025,5027,5024 ,4324,4325,4323 ,0,0,0}, + {5025,5028,5026 ,4324,4326,126 ,0,0,0}, {5011,5012,5014 ,4310,4311,4313 ,0,0,0}, + {5007,5006,5029 ,4306,4305,4327 ,0,0,0}, {5030,5029,5031 ,4328,4327,4329 ,0,0,0}, + {5006,5031,5029 ,4305,4329,4327 ,0,0,0}, {5032,5033,5030 ,4330,4331,4328 ,0,0,0}, + {5030,5031,5032 ,4328,4329,4330 ,0,0,0}, {5033,5034,5035 ,4331,4332,4333 ,0,0,0}, + {5034,5033,5032 ,4332,4331,4330 ,0,0,0}, {5036,5035,5037 ,4334,4333,4335 ,0,0,0}, + {5034,5037,5035 ,4332,4335,4333 ,0,0,0}, {5038,5039,5036 ,4336,4337,4334 ,0,0,0}, + {5036,5037,5038 ,4334,4335,4336 ,0,0,0}, {5039,5040,5041 ,4337,4338,4339 ,0,0,0}, + {5040,5039,5038 ,4338,4337,4336 ,0,0,0}, {5042,5041,5043 ,4340,4339,4341 ,0,0,0}, + {5040,5043,5041 ,4338,4341,4339 ,0,0,0}, {5044,5045,5042 ,4342,4343,4340 ,0,0,0}, + {5042,5043,5044 ,4340,4341,4342 ,0,0,0}, {5045,5046,5047 ,4343,4344,4345 ,0,0,0}, + {5046,5045,5044 ,4344,4343,4342 ,0,0,0}, {5046,5048,5047 ,4344,4346,4345 ,0,0,0}, + {5049,5050,5051 ,4347,4348,4349 ,0,0,0}, {5049,5052,5053 ,4347,4350,4351 ,0,0,0}, + {5052,5054,5053 ,4350,4352,4351 ,0,0,0}, {5051,5052,5049 ,4349,4350,4347 ,0,0,0}, + {5055,5056,5057 ,4353,4354,4355 ,0,0,0}, {5054,5055,5057 ,4352,4353,4355 ,0,0,0}, + {5056,5058,5059 ,4354,4356,4357 ,0,0,0}, {5058,5056,5055 ,4356,4354,4353 ,0,0,0}, + {5059,5058,5060 ,4357,4356,4358 ,0,0,0}, {5061,5059,5060 ,4359,4357,4358 ,0,0,0}, + {5061,5062,5063 ,4359,4360,4361 ,0,0,0}, {5061,5060,5062 ,4359,4358,4360 ,0,0,0}, + {5057,5053,5054 ,4355,4351,4352 ,0,0,0}, {5064,5065,5066 ,4362,1790,1790 ,0,0,0}, + {5064,5066,5063 ,4362,1790,4361 ,0,0,0}, {5062,5064,5063 ,4360,4362,4361 ,0,0,0}, + {5051,5050,5067 ,4349,4348,4363 ,0,0,0}, {5068,5067,5069 ,4364,4363,4365 ,0,0,0}, + {5050,5069,5067 ,4348,4365,4363 ,0,0,0}, {5070,5071,5068 ,4366,4367,4364 ,0,0,0}, + {5068,5069,5070 ,4364,4365,4366 ,0,0,0}, {5071,5072,5073 ,4367,4368,4369 ,0,0,0}, + {5072,5071,5070 ,4368,4367,4366 ,0,0,0}, {5074,5073,5075 ,4370,4369,4371 ,0,0,0}, + {5072,5075,5073 ,4368,4371,4369 ,0,0,0}, {5076,5077,5074 ,4372,4373,4370 ,0,0,0}, + {5074,5075,5076 ,4370,4371,4372 ,0,0,0}, {5077,5078,5079 ,4373,4374,1711 ,0,0,0}, + {5078,5077,5076 ,4374,4373,4372 ,0,0,0}, {5078,5080,5079 ,4374,1711,1711 ,0,0,0}, + {5081,5082,5083 ,4375,4376,4377 ,0,0,0}, {5084,5085,5086 ,4378,4379,4380 ,0,0,0}, + {5085,5081,5083 ,4379,4375,4377 ,0,0,0}, {5087,5084,5086 ,4381,4378,4380 ,0,0,0}, + {5085,5084,5081 ,4379,4378,4375 ,0,0,0}, {5087,5086,5088 ,4381,4380,4382 ,0,0,0}, + {5088,5089,5090 ,4382,4383,4384 ,0,0,0}, {5091,5090,5089 ,4385,4384,4383 ,0,0,0}, + {5092,5093,5094 ,4386,4387,4388 ,0,0,0}, {5089,5095,5091 ,4383,4389,4385 ,0,0,0}, + {5094,5096,5097 ,4388,4390,4391 ,0,0,0}, {5096,5095,5097 ,4390,4389,4391 ,0,0,0}, + {5091,5095,5096 ,4385,4389,4390 ,0,0,0}, {5094,5097,5092 ,4388,4391,4386 ,0,0,0}, + {5093,5092,5098 ,4387,4386,4392 ,0,0,0}, {5093,5098,5099 ,4387,4392,4393 ,0,0,0}, + {5100,5099,5098 ,4394,4393,4392 ,0,0,0}, {5101,5102,5103 ,4395,1790,4396 ,0,0,0}, + {5103,5099,5100 ,4396,4393,4394 ,0,0,0}, {5101,5103,5100 ,4395,4396,4394 ,0,0,0}, + {5101,5104,5102 ,4395,1790,1790 ,0,0,0}, {5087,5088,5090 ,4381,4382,4384 ,0,0,0}, + {5083,5082,5105 ,4377,4376,4397 ,0,0,0}, {5106,5105,5107 ,4398,4397,4399 ,0,0,0}, + {5082,5107,5105 ,4376,4399,4397 ,0,0,0}, {5108,5109,5106 ,4400,4401,4398 ,0,0,0}, + {5106,5107,5108 ,4398,4399,4400 ,0,0,0}, {5109,5110,5111 ,4401,4402,4403 ,0,0,0}, + {5110,5109,5108 ,4402,4401,4400 ,0,0,0}, {5112,5111,5113 ,4404,4403,4405 ,0,0,0}, + {5110,5113,5111 ,4402,4405,4403 ,0,0,0}, {5114,5115,5112 ,4406,4407,4404 ,0,0,0}, + {5112,5113,5114 ,4404,4405,4406 ,0,0,0}, {5115,5116,5117 ,4407,4408,4409 ,0,0,0}, + {5116,5115,5114 ,4408,4407,4406 ,0,0,0}, {5118,5117,5119 ,4410,4409,4411 ,0,0,0}, + {5116,5119,5117 ,4408,4411,4409 ,0,0,0}, {5120,5121,5118 ,4412,4413,4410 ,0,0,0}, + {5118,5119,5120 ,4410,4411,4412 ,0,0,0}, {5121,5122,5123 ,4413,4414,1711 ,0,0,0}, + {5122,5121,5120 ,4414,4413,4412 ,0,0,0}, {5122,5124,5123 ,4414,1711,1711 ,0,0,0}, + {5125,5126,5127 ,4415,4416,4417 ,0,0,0}, {5125,5128,5129 ,4415,4418,4419 ,0,0,0}, + {5128,5130,5129 ,4418,4420,4419 ,0,0,0}, {5127,5128,5125 ,4417,4418,4415 ,0,0,0}, + {5131,5132,5133 ,4421,4422,4423 ,0,0,0}, {5130,5131,5133 ,4420,4421,4423 ,0,0,0}, + {5132,5134,5135 ,4422,4424,4425 ,0,0,0}, {5134,5132,5131 ,4424,4422,4421 ,0,0,0}, + {5135,5134,5136 ,4425,4424,4426 ,0,0,0}, {5137,5135,5136 ,4427,4425,4426 ,0,0,0}, + {5137,5138,5139 ,4427,4428,4429 ,0,0,0}, {5137,5136,5138 ,4427,4426,4428 ,0,0,0}, + {5133,5129,5130 ,4423,4419,4420 ,0,0,0}, {5140,5141,5142 ,4430,1435,1435 ,0,0,0}, + {5140,5142,5139 ,4430,1435,4429 ,0,0,0}, {5138,5140,5139 ,4428,4430,4429 ,0,0,0}, + {5127,5126,5143 ,4417,4416,4431 ,0,0,0}, {5144,5143,5145 ,4432,4431,4433 ,0,0,0}, + {5126,5145,5143 ,4416,4433,4431 ,0,0,0}, {5146,5147,5144 ,4434,4435,4432 ,0,0,0}, + {5144,5145,5146 ,4432,4433,4434 ,0,0,0}, {5147,5148,5149 ,4435,4436,4437 ,0,0,0}, + {5148,5147,5146 ,4436,4435,4434 ,0,0,0}, {5150,5149,5151 ,4438,4437,4439 ,0,0,0}, + {5148,5151,5149 ,4436,4439,4437 ,0,0,0}, {5152,5153,5150 ,4440,4441,4438 ,0,0,0}, + {5150,5151,5152 ,4438,4439,4440 ,0,0,0}, {5153,5154,5155 ,4441,4442,1359 ,0,0,0}, + {5154,5153,5152 ,4442,4441,4440 ,0,0,0}, {5154,5156,5155 ,4442,1359,1359 ,0,0,0}, + {5157,5158,5159 ,4443,4444,4445 ,0,0,0}, {5160,5161,5162 ,4446,4447,4448 ,0,0,0}, + {5161,5157,5159 ,4447,4443,4445 ,0,0,0}, {5163,5160,5162 ,4449,4446,4448 ,0,0,0}, + {5161,5160,5157 ,4447,4446,4443 ,0,0,0}, {5163,5162,5164 ,4449,4448,4450 ,0,0,0}, + {5164,5165,5166 ,4450,4451,4452 ,0,0,0}, {5167,5166,5165 ,4453,4452,4451 ,0,0,0}, + {5168,5169,5170 ,4454,4455,4456 ,0,0,0}, {5165,5171,5167 ,4451,4457,4453 ,0,0,0}, + {5170,5172,5173 ,4456,4458,4459 ,0,0,0}, {5172,5171,5173 ,4458,4457,4459 ,0,0,0}, + {5167,5171,5172 ,4453,4457,4458 ,0,0,0}, {5170,5173,5168 ,4456,4459,4454 ,0,0,0}, + {5169,5168,5174 ,4455,4454,4460 ,0,0,0}, {5169,5174,5175 ,4455,4460,4461 ,0,0,0}, + {5176,5175,5174 ,4462,4461,4460 ,0,0,0}, {5177,5178,5179 ,4463,1435,4464 ,0,0,0}, + {5179,5175,5176 ,4464,4461,4462 ,0,0,0}, {5177,5179,5176 ,4463,4464,4462 ,0,0,0}, + {5177,5180,5178 ,4463,1435,1435 ,0,0,0}, {5163,5164,5166 ,4449,4450,4452 ,0,0,0}, + {5159,5158,5181 ,4445,4444,4465 ,0,0,0}, {5182,5181,5183 ,4466,4465,4467 ,0,0,0}, + {5158,5183,5181 ,4444,4467,4465 ,0,0,0}, {5184,5185,5182 ,4468,4469,4466 ,0,0,0}, + {5182,5183,5184 ,4466,4467,4468 ,0,0,0}, {5185,5186,5187 ,4469,4470,4471 ,0,0,0}, + {5186,5185,5184 ,4470,4469,4468 ,0,0,0}, {5188,5187,5189 ,4472,4471,4473 ,0,0,0}, + {5186,5189,5187 ,4470,4473,4471 ,0,0,0}, {5190,5191,5188 ,4474,4475,4472 ,0,0,0}, + {5188,5189,5190 ,4472,4473,4474 ,0,0,0}, {5191,5192,5193 ,4475,4476,4477 ,0,0,0}, + {5192,5191,5190 ,4476,4475,4474 ,0,0,0}, {5194,5193,5195 ,4478,4477,4479 ,0,0,0}, + {5192,5195,5193 ,4476,4479,4477 ,0,0,0}, {5196,5197,5194 ,4480,4481,4478 ,0,0,0}, + {5194,5195,5196 ,4478,4479,4480 ,0,0,0}, {5197,5198,5199 ,4481,4482,1359 ,0,0,0}, + {5198,5197,5196 ,4482,4481,4480 ,0,0,0}, {5198,5200,5199 ,4482,1359,1359 ,0,0,0}, + {5201,5202,5203 ,4483,4484,4485 ,0,0,0}, {5201,5204,5205 ,4483,4486,4487 ,0,0,0}, + {5204,5206,5205 ,4486,4488,4487 ,0,0,0}, {5203,5204,5201 ,4485,4486,4483 ,0,0,0}, + {5207,5208,5209 ,4489,4490,4491 ,0,0,0}, {5206,5207,5209 ,4488,4489,4491 ,0,0,0}, + {5208,5210,5211 ,4490,4492,4493 ,0,0,0}, {5210,5208,5207 ,4492,4490,4489 ,0,0,0}, + {5211,5210,5212 ,4493,4492,4494 ,0,0,0}, {5213,5211,5212 ,4495,4493,4494 ,0,0,0}, + {5213,5214,5215 ,4495,4496,4497 ,0,0,0}, {5213,5212,5214 ,4495,4494,4496 ,0,0,0}, + {5209,5205,5206 ,4491,4487,4488 ,0,0,0}, {5216,5217,5218 ,4498,4499,82 ,0,0,0}, + {5216,5218,5215 ,4498,82,4497 ,0,0,0}, {5214,5216,5215 ,4496,4498,4497 ,0,0,0}, + {5203,5202,5219 ,4485,4484,4500 ,0,0,0}, {5220,5219,5221 ,4501,4500,4502 ,0,0,0}, + {5202,5221,5219 ,4484,4502,4500 ,0,0,0}, {5222,5223,5220 ,4503,4504,4501 ,0,0,0}, + {5220,5221,5222 ,4501,4502,4503 ,0,0,0}, {5223,5224,5225 ,4504,4505,4506 ,0,0,0}, + {5224,5223,5222 ,4505,4504,4503 ,0,0,0}, {5226,5225,5227 ,4507,4506,4508 ,0,0,0}, + {5224,5227,5225 ,4505,4508,4506 ,0,0,0}, {5228,5229,5226 ,4509,4510,4507 ,0,0,0}, + {5226,5227,5228 ,4507,4508,4509 ,0,0,0}, {5229,5230,5231 ,4510,4511,4512 ,0,0,0}, + {5230,5229,5228 ,4511,4510,4509 ,0,0,0}, {5230,5232,5231 ,4511,4513,4512 ,0,0,0}, + {5233,5234,5235 ,4514,4515,4516 ,0,0,0}, {5236,5237,5238 ,4517,4518,4519 ,0,0,0}, + {5237,5233,5235 ,4518,4514,4516 ,0,0,0}, {5239,5236,5238 ,4520,4517,4519 ,0,0,0}, + {5237,5236,5233 ,4518,4517,4514 ,0,0,0}, {5239,5238,5240 ,4520,4519,4521 ,0,0,0}, + {5240,5241,5242 ,4521,4522,4523 ,0,0,0}, {5243,5242,5241 ,4524,4523,4522 ,0,0,0}, + {5244,5245,5246 ,4525,4526,4527 ,0,0,0}, {5241,5247,5243 ,4522,4528,4524 ,0,0,0}, + {5246,5248,5249 ,4527,4529,4530 ,0,0,0}, {5248,5247,5249 ,4529,4528,4530 ,0,0,0}, + {5243,5247,5248 ,4524,4528,4529 ,0,0,0}, {5246,5249,5244 ,4527,4530,4525 ,0,0,0}, + {5245,5244,5250 ,4526,4525,4531 ,0,0,0}, {5245,5250,5251 ,4526,4531,4532 ,0,0,0}, + {5252,5251,5250 ,4533,4532,4531 ,0,0,0}, {5253,5254,5255 ,4534,4535,4536 ,0,0,0}, + {5255,5251,5252 ,4536,4532,4533 ,0,0,0}, {5253,5255,5252 ,4534,4536,4533 ,0,0,0}, + {5253,5256,5254 ,4534,4537,4535 ,0,0,0}, {5239,5240,5242 ,4520,4521,4523 ,0,0,0}, + {5235,5234,5257 ,4516,4515,4538 ,0,0,0}, {5258,5257,5259 ,4539,4538,4540 ,0,0,0}, + {5234,5259,5257 ,4515,4540,4538 ,0,0,0}, {5260,5261,5258 ,4541,4542,4539 ,0,0,0}, + {5258,5259,5260 ,4539,4540,4541 ,0,0,0}, {5261,5262,5263 ,4542,4543,4544 ,0,0,0}, + {5262,5261,5260 ,4543,4542,4541 ,0,0,0}, {5264,5263,5265 ,4545,4544,4546 ,0,0,0}, + {5262,5265,5263 ,4543,4546,4544 ,0,0,0}, {5266,5267,5264 ,4547,4548,4545 ,0,0,0}, + {5264,5265,5266 ,4545,4546,4547 ,0,0,0}, {5267,5268,5269 ,4548,4549,4550 ,0,0,0}, + {5268,5267,5266 ,4549,4548,4547 ,0,0,0}, {5270,5269,5271 ,4551,4550,4552 ,0,0,0}, + {5268,5271,5269 ,4549,4552,4550 ,0,0,0}, {5272,5273,5270 ,4553,4554,4551 ,0,0,0}, + {5270,5271,5272 ,4551,4552,4553 ,0,0,0}, {5273,5274,5275 ,4554,4555,4556 ,0,0,0}, + {5274,5273,5272 ,4555,4554,4553 ,0,0,0}, {5274,5276,5275 ,4555,126,4556 ,0,0,0}, + {5277,5278,5279 ,4557,4558,4559 ,0,0,0}, {5280,5281,5279 ,4560,4561,4559 ,0,0,0}, + {5277,5279,5281 ,4557,4559,4561 ,0,0,0}, {5282,5280,5283 ,4562,4560,4563 ,0,0,0}, + {5282,5281,5280 ,4562,4561,4560 ,0,0,0}, {5284,5283,5285 ,4564,4563,4565 ,0,0,0}, + {5280,5285,5283 ,4560,4565,4563 ,0,0,0}, {5286,5287,5284 ,4081,4566,4564 ,0,0,0}, + {5284,5285,5286 ,4564,4565,4081 ,0,0,0}, {5287,5288,5289 ,4566,4567,4568 ,0,0,0}, + {5288,5287,5286 ,4567,4566,4081 ,0,0,0}, {5290,5289,5291 ,4569,4568,4570 ,0,0,0}, + {5288,5291,5289 ,4567,4570,4568 ,0,0,0}, {5292,5293,5290 ,4571,4572,4569 ,0,0,0}, + {5290,5291,5292 ,4569,4570,4571 ,0,0,0}, {5294,5295,5293 ,4573,763,4572 ,0,0,0}, + {5294,5293,5292 ,4573,4572,4571 ,0,0,0}, {5295,5296,5293 ,763,763,4572 ,0,0,0}, + {5297,5278,5277 ,4574,4558,4557 ,0,0,0}, {5297,5298,5299 ,4574,4575,4576 ,0,0,0}, + {5299,5278,5297 ,4576,4558,4574 ,0,0,0}, {5300,5301,5298 ,4577,4578,4575 ,0,0,0}, + {5298,5301,5299 ,4575,4578,4576 ,0,0,0}, {5302,5303,5300 ,4579,4580,4577 ,0,0,0}, + {5300,5298,5302 ,4577,4575,4579 ,0,0,0}, {5303,5304,5305 ,4580,4065,4581 ,0,0,0}, + {5304,5303,5302 ,4065,4580,4579 ,0,0,0}, {5306,5305,5307 ,4582,4581,4583 ,0,0,0}, + {5304,5307,5305 ,4065,4583,4581 ,0,0,0}, {5308,5309,5306 ,4584,4585,4582 ,0,0,0}, + {5306,5307,5308 ,4582,4583,4584 ,0,0,0}, {5309,5310,5311 ,4585,4586,4587 ,0,0,0}, + {5310,5309,5308 ,4586,4585,4584 ,0,0,0}, {5311,5312,5313 ,4587,4588,54 ,0,0,0}, + {5310,5312,5311 ,4586,4588,4587 ,0,0,0}, {5311,5313,5314 ,4587,54,4589 ,0,0,0}, + {5315,5316,5317 ,4590,4591,4557 ,0,0,0}, {5318,5316,5319 ,4592,4591,4593 ,0,0,0}, + {5316,5318,5317 ,4591,4592,4557 ,0,0,0}, {5320,5321,5319 ,4594,4595,4593 ,0,0,0}, + {5318,5319,5321 ,4592,4593,4595 ,0,0,0}, {5320,5322,5323 ,4594,4596,4597 ,0,0,0}, + {5323,5321,5320 ,4597,4595,4594 ,0,0,0}, {5324,5322,5325 ,4598,4596,4599 ,0,0,0}, + {5322,5324,5323 ,4596,4598,4597 ,0,0,0}, {5326,5327,5325 ,4600,4601,4599 ,0,0,0}, + {5324,5325,5327 ,4598,4599,4601 ,0,0,0}, {5326,5328,5329 ,4600,4602,4603 ,0,0,0}, + {5329,5327,5326 ,4603,4601,4600 ,0,0,0}, {5330,5328,5331 ,4604,4602,4605 ,0,0,0}, + {5328,5330,5329 ,4602,4604,4603 ,0,0,0}, {5332,5333,5331 ,4606,4607,4605 ,0,0,0}, + {5330,5331,5333 ,4604,4605,4607 ,0,0,0}, {5332,5334,5335 ,4606,4608,4609 ,0,0,0}, + {5335,5333,5332 ,4609,4607,4606 ,0,0,0}, {5336,5334,5337 ,4610,4608,4611 ,0,0,0}, + {5334,5336,5335 ,4608,4610,4609 ,0,0,0}, {5338,5339,5337 ,4612,4613,4611 ,0,0,0}, + {5336,5337,5339 ,4610,4611,4613 ,0,0,0}, {5338,5340,5341 ,4612,4614,4615 ,0,0,0}, + {5341,5339,5338 ,4615,4613,4612 ,0,0,0}, {5342,5340,5343 ,4616,4614,4617 ,0,0,0}, + {5340,5342,5341 ,4614,4616,4615 ,0,0,0}, {5344,5345,5343 ,4618,4619,4617 ,0,0,0}, + {5342,5343,5345 ,4616,4617,4619 ,0,0,0}, {5344,5346,5347 ,4618,4620,4621 ,0,0,0}, + {5347,5345,5344 ,4621,4619,4618 ,0,0,0}, {5346,5348,5347 ,4620,4620,4621 ,0,0,0}, + {5349,5315,5317 ,4622,4590,4557 ,0,0,0}, {5350,5351,5349 ,4623,4624,4622 ,0,0,0}, + {5315,5349,5351 ,4590,4622,4624 ,0,0,0}, {5350,5352,5353 ,4623,4625,4626 ,0,0,0}, + {5353,5351,5350 ,4626,4624,4623 ,0,0,0}, {5354,5352,5355 ,4627,4625,4628 ,0,0,0}, + {5352,5354,5353 ,4625,4627,4626 ,0,0,0}, {5356,5357,5355 ,4629,4630,4628 ,0,0,0}, + {5354,5355,5357 ,4627,4628,4630 ,0,0,0}, {5356,5358,5359 ,4629,4631,4632 ,0,0,0}, + {5359,5357,5356 ,4632,4630,4629 ,0,0,0}, {5360,5358,5361 ,4633,4631,4634 ,0,0,0}, + {5358,5360,5359 ,4631,4633,4632 ,0,0,0}, {5362,5363,5361 ,4635,4636,4634 ,0,0,0}, + {5360,5361,5363 ,4633,4634,4636 ,0,0,0}, {5362,5364,5365 ,4635,4637,4638 ,0,0,0}, + {5365,5363,5362 ,4638,4636,4635 ,0,0,0}, {5366,5364,5367 ,4639,4637,4640 ,0,0,0}, + {5364,5366,5365 ,4637,4639,4638 ,0,0,0}, {5368,5369,5367 ,4641,4642,4640 ,0,0,0}, + {5366,5367,5369 ,4639,4640,4642 ,0,0,0}, {5368,5370,5371 ,4641,4643,4644 ,0,0,0}, + {5371,5369,5368 ,4644,4642,4641 ,0,0,0}, {5372,5370,5373 ,4645,4643,4646 ,0,0,0}, + {5370,5372,5371 ,4643,4645,4644 ,0,0,0}, {5374,5375,5373 ,4647,4648,4646 ,0,0,0}, + {5372,5373,5375 ,4645,4646,4648 ,0,0,0}, {5374,5376,5377 ,4647,4649,4650 ,0,0,0}, + {5377,5375,5374 ,4650,4648,4647 ,0,0,0}, {5378,5376,5379 ,4651,4649,82 ,0,0,0}, + {5376,5378,5377 ,4649,4651,4650 ,0,0,0}, {5378,5379,5380 ,4651,82,4652 ,0,0,0}, + {5381,5382,5383 ,4653,4654,4655 ,0,0,0}, {5384,5385,5386 ,4656,4657,4658 ,0,0,0}, + {5383,5386,5385 ,4655,4658,4657 ,0,0,0}, {5387,5388,5389 ,4659,4660,4661 ,0,0,0}, + {5390,5391,5384 ,4662,4663,4656 ,0,0,0}, {5387,5391,5390 ,4659,4663,4662 ,0,0,0}, + {5390,5388,5387 ,4662,4660,4659 ,0,0,0}, {5391,5385,5384 ,4663,4657,4656 ,0,0,0}, + {5392,5393,5394 ,4664,4665,4666 ,0,0,0}, {5393,5395,5394 ,4665,4667,4666 ,0,0,0}, + {5396,5397,5398 ,4668,4669,4670 ,0,0,0}, {5396,5398,5395 ,4668,4670,4667 ,0,0,0}, + {5393,5396,5395 ,4665,4668,4667 ,0,0,0}, {5388,5392,5389 ,4660,4664,4661 ,0,0,0}, + {5392,5394,5389 ,4664,4666,4661 ,0,0,0}, {5399,5400,5401 ,4671,4672,4673 ,0,0,0}, + {5402,5403,5404 ,4674,4675,4676 ,0,0,0}, {5401,5400,5402 ,4673,4672,4674 ,0,0,0}, + {5405,5406,5407 ,4677,4678,4679 ,0,0,0}, {5401,5402,5404 ,4673,4674,4676 ,0,0,0}, + {5407,5406,5403 ,4679,4678,4675 ,0,0,0}, {5406,5404,5403 ,4678,4676,4675 ,0,0,0}, + {5397,5400,5399 ,4669,4672,4671 ,0,0,0}, {5408,5405,5407 ,4677,4677,4679 ,0,0,0}, + {5398,5397,5399 ,4670,4669,4671 ,0,0,0}, {5382,5386,5383 ,4654,4658,4655 ,0,0,0}, + {5409,5382,5381 ,4680,4654,4653 ,0,0,0}, {5409,5410,5411 ,4680,4681,4682 ,0,0,0}, + {5410,5409,5381 ,4681,4680,4653 ,0,0,0}, {5412,5411,5413 ,4683,4682,4684 ,0,0,0}, + {5410,5413,5411 ,4681,4684,4682 ,0,0,0}, {5414,5415,5412 ,4685,4686,4683 ,0,0,0}, + {5412,5413,5414 ,4683,4684,4685 ,0,0,0}, {5415,5416,5417 ,4686,4687,4688 ,0,0,0}, + {5416,5415,5414 ,4687,4686,4685 ,0,0,0}, {5418,5417,5419 ,4689,4688,4690 ,0,0,0}, + {5416,5419,5417 ,4687,4690,4688 ,0,0,0}, {5420,5421,5418 ,4691,4692,4689 ,0,0,0}, + {5418,5419,5420 ,4689,4690,4691 ,0,0,0}, {5421,5422,5423 ,4692,4693,4694 ,0,0,0}, + {5422,5421,5420 ,4693,4692,4691 ,0,0,0}, {5424,5423,5425 ,4695,4694,4696 ,0,0,0}, + {5422,5425,5423 ,4693,4696,4694 ,0,0,0}, {5426,5427,5424 ,4697,4698,4695 ,0,0,0}, + {5424,5425,5426 ,4695,4696,4697 ,0,0,0}, {5427,5428,5429 ,4698,4699,4700 ,0,0,0}, + {5428,5427,5426 ,4699,4698,4697 ,0,0,0}, {5428,5430,5429 ,4699,4701,4700 ,0,0,0}, + {5431,5432,5433 ,4702,4703,4704 ,0,0,0}, {5434,5435,5436 ,4705,4706,4707 ,0,0,0}, + {5432,5436,5435 ,4703,4707,4706 ,0,0,0}, {5437,5438,5439 ,4708,4709,4710 ,0,0,0}, + {5440,5434,5441 ,4711,4705,4712 ,0,0,0}, {5437,5440,5441 ,4708,4711,4712 ,0,0,0}, + {5440,5437,5439 ,4711,4708,4710 ,0,0,0}, {5441,5434,5436 ,4712,4705,4707 ,0,0,0}, + {5442,5443,5444 ,4713,4714,4715 ,0,0,0}, {5444,5443,5445 ,4715,4714,4716 ,0,0,0}, + {5446,5447,5448 ,4717,4718,4719 ,0,0,0}, {5446,5445,5447 ,4717,4716,4718 ,0,0,0}, + {5444,5445,5446 ,4715,4716,4717 ,0,0,0}, {5439,5438,5442 ,4710,4709,4713 ,0,0,0}, + {5442,5438,5443 ,4713,4709,4714 ,0,0,0}, {5449,5450,5451 ,4720,4721,4722 ,0,0,0}, + {5452,5453,5454 ,4723,4724,4725 ,0,0,0}, {5450,5452,5451 ,4721,4723,4722 ,0,0,0}, + {5455,5456,5457 ,4726,4727,4728 ,0,0,0}, {5450,5453,5452 ,4721,4724,4723 ,0,0,0}, + {5456,5454,5457 ,4727,4725,4728 ,0,0,0}, {5457,5454,5453 ,4728,4725,4724 ,0,0,0}, + {5448,5449,5451 ,4719,4720,4722 ,0,0,0}, {5458,5456,5455 ,4726,4727,4726 ,0,0,0}, + {5447,5449,5448 ,4718,4720,4719 ,0,0,0}, {5433,5432,5435 ,4704,4703,4706 ,0,0,0}, + {5459,5431,5433 ,4729,4702,4704 ,0,0,0}, {5459,5460,5461 ,4729,4730,4731 ,0,0,0}, + {5461,5431,5459 ,4731,4702,4729 ,0,0,0}, {5462,5463,5460 ,4732,4733,4730 ,0,0,0}, + {5461,5460,5463 ,4731,4730,4733 ,0,0,0}, {5464,5462,5465 ,4734,4732,4735 ,0,0,0}, + {5462,5464,5463 ,4732,4734,4733 ,0,0,0}, {5465,5466,5467 ,4735,4736,4737 ,0,0,0}, + {5467,5464,5465 ,4737,4734,4735 ,0,0,0}, {5468,5469,5466 ,4738,4739,4736 ,0,0,0}, + {5467,5466,5469 ,4737,4736,4739 ,0,0,0}, {5470,5468,5471 ,4740,4738,4741 ,0,0,0}, + {5468,5470,5469 ,4738,4740,4739 ,0,0,0}, {5471,5472,5473 ,4741,4742,4743 ,0,0,0}, + {5473,5470,5471 ,4743,4740,4741 ,0,0,0}, {5474,5475,5472 ,4744,4745,4742 ,0,0,0}, + {5473,5472,5475 ,4743,4742,4745 ,0,0,0}, {5476,5474,5477 ,4746,4744,4747 ,0,0,0}, + {5474,5476,5475 ,4744,4746,4745 ,0,0,0}, {5477,5478,5479 ,4747,4748,4749 ,0,0,0}, + {5479,5476,5477 ,4749,4746,4747 ,0,0,0}, {5479,5478,5480 ,4749,4748,4750 ,0,0,0}, + {5481,5482,5483 ,4751,4752,4753 ,0,0,0}, {5484,5485,5486 ,4754,4755,4756 ,0,0,0}, + {5482,5486,5485 ,4752,4756,4755 ,0,0,0}, {5487,5488,5489 ,4757,4758,4759 ,0,0,0}, + {5490,5484,5491 ,4760,4754,4761 ,0,0,0}, {5490,5491,5487 ,4760,4761,4757 ,0,0,0}, + {5487,5489,5490 ,4757,4759,4760 ,0,0,0}, {5484,5486,5491 ,4754,4756,4761 ,0,0,0}, + {5492,5493,5494 ,4762,4763,4764 ,0,0,0}, {5495,5493,5492 ,4765,4763,4762 ,0,0,0}, + {5496,5497,5498 ,4766,4767,4768 ,0,0,0}, {5496,5498,5495 ,4766,4768,4765 ,0,0,0}, + {5495,5498,5493 ,4765,4768,4763 ,0,0,0}, {5488,5494,5489 ,4758,4764,4759 ,0,0,0}, + {5492,5494,5488 ,4762,4764,4758 ,0,0,0}, {5499,5500,5501 ,4769,4770,4771 ,0,0,0}, + {5502,5503,5504 ,4772,4773,4774 ,0,0,0}, {5501,5500,5504 ,4771,4770,4774 ,0,0,0}, + {5505,5506,5507 ,4775,4776,4777 ,0,0,0}, {5500,5502,5504 ,4770,4772,4774 ,0,0,0}, + {5505,5503,5506 ,4775,4773,4776 ,0,0,0}, {5503,5502,5506 ,4773,4772,4776 ,0,0,0}, + {5499,5501,5497 ,4769,4771,4767 ,0,0,0}, {5508,5505,5507 ,4777,4775,4777 ,0,0,0}, + {5496,5499,5497 ,4766,4769,4767 ,0,0,0}, {5482,5485,5483 ,4752,4755,4753 ,0,0,0}, + {5481,5483,5509 ,4751,4753,4778 ,0,0,0}, {5509,5510,5511 ,4778,4779,4780 ,0,0,0}, + {5511,5481,5509 ,4780,4751,4778 ,0,0,0}, {5512,5510,5513 ,4781,4779,4782 ,0,0,0}, + {5510,5512,5511 ,4779,4781,4780 ,0,0,0}, {5514,5515,5513 ,4783,4784,4782 ,0,0,0}, + {5512,5513,5515 ,4781,4782,4784 ,0,0,0}, {5514,5516,5517 ,4783,4785,4786 ,0,0,0}, + {5517,5515,5514 ,4786,4784,4783 ,0,0,0}, {5518,5516,5519 ,4787,4785,4788 ,0,0,0}, + {5516,5518,5517 ,4785,4787,4786 ,0,0,0}, {5520,5521,5519 ,4789,4790,4788 ,0,0,0}, + {5518,5519,5521 ,4787,4788,4790 ,0,0,0}, {5520,5522,5523 ,4789,4791,4792 ,0,0,0}, + {5523,5521,5520 ,4792,4790,4789 ,0,0,0}, {5524,5522,5525 ,4793,4791,4794 ,0,0,0}, + {5522,5524,5523 ,4791,4793,4792 ,0,0,0}, {5526,5527,5525 ,4795,4796,4794 ,0,0,0}, + {5524,5525,5527 ,4793,4794,4796 ,0,0,0}, {5526,5528,5529 ,4795,4797,4798 ,0,0,0}, + {5529,5527,5526 ,4798,4796,4795 ,0,0,0}, {5528,5530,5529 ,4797,4799,4798 ,0,0,0}, + {5528,5531,5530 ,4797,324,4799 ,0,0,0}, {5532,5533,5534 ,82,4800,4801 ,0,0,0}, + {5534,5535,5536 ,4801,4802,4803 ,0,0,0}, {5535,5537,5536 ,4802,4804,4803 ,0,0,0}, + {5534,5536,5532 ,4801,4803,82 ,0,0,0}, {5538,5539,5540 ,4805,4806,4807 ,0,0,0}, + {5540,5539,5537 ,4807,4806,4804 ,0,0,0}, {5538,5541,5542 ,4805,4808,4809 ,0,0,0}, + {5542,5539,5538 ,4809,4806,4805 ,0,0,0}, {5542,5541,5543 ,4809,4808,4810 ,0,0,0}, + {5543,5541,5544 ,4810,4808,4811 ,0,0,0}, {5544,5545,5546 ,4811,4812,4813 ,0,0,0}, + {5543,5544,5546 ,4810,4811,4813 ,0,0,0}, {5537,5535,5540 ,4804,4802,4807 ,0,0,0}, + {5547,5548,5549 ,4814,4815,4816 ,0,0,0}, {5547,5549,5545 ,4814,4816,4812 ,0,0,0}, + {5545,5549,5546 ,4812,4816,4813 ,0,0,0}, {5532,5550,5533 ,82,4817,4800 ,0,0,0}, + {5551,5550,5552 ,4818,4817,4819 ,0,0,0}, {5550,5551,5533 ,4817,4818,4800 ,0,0,0}, + {5553,5554,5552 ,4820,4821,4819 ,0,0,0}, {5551,5552,5554 ,4818,4819,4821 ,0,0,0}, + {5553,5555,5556 ,4820,4822,4823 ,0,0,0}, {5556,5554,5553 ,4823,4821,4820 ,0,0,0}, + {5557,5555,5558 ,4824,4822,4825 ,0,0,0}, {5555,5557,5556 ,4822,4824,4823 ,0,0,0}, + {5559,5560,5558 ,4826,4827,4825 ,0,0,0}, {5557,5558,5560 ,4824,4825,4827 ,0,0,0}, + {5559,5561,5562 ,4826,4828,4829 ,0,0,0}, {5562,5560,5559 ,4829,4827,4826 ,0,0,0}, + {5563,5561,5564 ,4830,4828,4831 ,0,0,0}, {5561,5563,5562 ,4828,4830,4829 ,0,0,0}, + {5559,5558,5565 ,4832,4833,4834 ,0,0,0}, {5565,5561,5559 ,4834,4835,4832 ,0,0,0}, + {5565,5564,5561 ,4834,4836,4835 ,0,0,0}, {5565,5555,5553 ,4834,4837,4838 ,0,0,0}, + {5558,5555,5565 ,4833,4837,4834 ,0,0,0}, {5565,5552,5550 ,4834,4839,4840 ,0,0,0}, + {5553,5552,5565 ,4838,4839,4834 ,0,0,0}, {5550,5532,5565 ,4840,4841,4834 ,0,0,0}, + {5537,5565,5536 ,4842,4834,4843 ,0,0,0}, {5565,5532,5536 ,4834,4841,4843 ,0,0,0}, + {5542,5565,5539 ,4844,4834,4845 ,0,0,0}, {5565,5537,5539 ,4834,4842,4845 ,0,0,0}, + {5546,5565,5543 ,4846,4834,4847 ,0,0,0}, {5565,5542,5543 ,4834,4844,4847 ,0,0,0}, + {5548,5565,5549 ,4848,4834,4849 ,0,0,0}, {5565,5546,5549 ,4834,4846,4849 ,0,0,0}, + {5566,5567,5568 ,82,4850,4851 ,0,0,0}, {5568,5569,5570 ,4851,4852,4853 ,0,0,0}, + {5569,5571,5570 ,4852,4854,4853 ,0,0,0}, {5568,5570,5566 ,4851,4853,82 ,0,0,0}, + {5572,5573,5574 ,4855,4856,4857 ,0,0,0}, {5574,5573,5571 ,4857,4856,4854 ,0,0,0}, + {5572,5575,5576 ,4855,4858,4859 ,0,0,0}, {5576,5573,5572 ,4859,4856,4855 ,0,0,0}, + {5576,5575,5577 ,4859,4858,4860 ,0,0,0}, {5577,5575,5578 ,4860,4858,4861 ,0,0,0}, + {5578,5579,5580 ,4861,4862,4863 ,0,0,0}, {5577,5578,5580 ,4860,4861,4863 ,0,0,0}, + {5571,5569,5574 ,4854,4852,4857 ,0,0,0}, {5581,5582,5583 ,4864,4865,4866 ,0,0,0}, + {5581,5583,5579 ,4864,4866,4862 ,0,0,0}, {5579,5583,5580 ,4862,4866,4863 ,0,0,0}, + {5566,5584,5567 ,82,4867,4850 ,0,0,0}, {5585,5584,5586 ,4868,4867,4869 ,0,0,0}, + {5584,5585,5567 ,4867,4868,4850 ,0,0,0}, {5587,5588,5586 ,4870,4871,4869 ,0,0,0}, + {5585,5586,5588 ,4868,4869,4871 ,0,0,0}, {5587,5589,5590 ,4870,4872,4873 ,0,0,0}, + {5590,5588,5587 ,4873,4871,4870 ,0,0,0}, {5591,5589,5592 ,4874,4872,4875 ,0,0,0}, + {5589,5591,5590 ,4872,4874,4873 ,0,0,0}, {5593,5594,5592 ,4876,4877,4875 ,0,0,0}, + {5591,5592,5594 ,4874,4875,4877 ,0,0,0}, {5593,5595,5596 ,4876,4878,4829 ,0,0,0}, + {5596,5594,5593 ,4829,4877,4876 ,0,0,0}, {5597,5595,5598 ,4879,4878,4831 ,0,0,0}, + {5595,5597,5596 ,4878,4879,4829 ,0,0,0}, {5593,5592,5599 ,4832,4833,4880 ,0,0,0}, + {5599,5595,5593 ,4880,4835,4832 ,0,0,0}, {5599,5598,5595 ,4880,4881,4835 ,0,0,0}, + {5599,5589,5587 ,4880,4837,4838 ,0,0,0}, {5592,5589,5599 ,4833,4837,4880 ,0,0,0}, + {5599,5586,5584 ,4880,4839,4840 ,0,0,0}, {5587,5586,5599 ,4838,4839,4880 ,0,0,0}, + {5584,5566,5599 ,4840,4882,4880 ,0,0,0}, {5571,5599,5570 ,4842,4880,4843 ,0,0,0}, + {5599,5566,5570 ,4880,4882,4843 ,0,0,0}, {5576,5599,5573 ,4844,4880,4845 ,0,0,0}, + {5599,5571,5573 ,4880,4842,4845 ,0,0,0}, {5580,5599,5577 ,4846,4880,4847 ,0,0,0}, + {5599,5576,5577 ,4880,4844,4847 ,0,0,0}, {5582,5599,5583 ,4883,4880,4849 ,0,0,0}, + {5599,5580,5583 ,4880,4846,4849 ,0,0,0}, {5600,5601,5602 ,4884,4885,4886 ,0,0,0}, + {5602,5603,5604 ,4886,4887,4888 ,0,0,0}, {5603,5605,5604 ,4887,4889,4888 ,0,0,0}, + {5602,5604,5600 ,4886,4888,4884 ,0,0,0}, {5606,5607,5608 ,4890,4891,4857 ,0,0,0}, + {5608,5607,5605 ,4857,4891,4889 ,0,0,0}, {5606,5609,5610 ,4890,4892,4893 ,0,0,0}, + {5610,5607,5606 ,4893,4891,4890 ,0,0,0}, {5610,5609,5611 ,4893,4892,4894 ,0,0,0}, + {5611,5609,5612 ,4894,4892,4895 ,0,0,0}, {5612,5613,5614 ,4895,4896,4897 ,0,0,0}, + {5611,5612,5614 ,4894,4895,4897 ,0,0,0}, {5605,5603,5608 ,4889,4887,4857 ,0,0,0}, + {5615,5616,5617 ,4898,4899,4900 ,0,0,0}, {5615,5617,5613 ,4898,4900,4896 ,0,0,0}, + {5613,5617,5614 ,4896,4900,4897 ,0,0,0}, {5600,5618,5601 ,4884,4901,4885 ,0,0,0}, + {5619,5618,5620 ,4868,4901,4902 ,0,0,0}, {5618,5619,5601 ,4901,4868,4885 ,0,0,0}, + {5621,5622,5620 ,4820,4903,4902 ,0,0,0}, {5619,5620,5622 ,4868,4902,4903 ,0,0,0}, + {5621,5623,5624 ,4820,4904,4905 ,0,0,0}, {5624,5622,5621 ,4905,4903,4820 ,0,0,0}, + {5625,5623,5626 ,4906,4904,4907 ,0,0,0}, {5623,5625,5624 ,4904,4906,4905 ,0,0,0}, + {5627,5628,5626 ,4826,4877,4907 ,0,0,0}, {5625,5626,5628 ,4906,4907,4877 ,0,0,0}, + {5627,5629,5630 ,4826,4828,4908 ,0,0,0}, {5630,5628,5627 ,4908,4877,4826 ,0,0,0}, + {5631,5629,5632 ,4909,4828,4910 ,0,0,0}, {5629,5631,5630 ,4828,4909,4908 ,0,0,0}, + {5627,5626,5633 ,4832,4833,4880 ,0,0,0}, {5633,5629,5627 ,4880,4835,4832 ,0,0,0}, + {5633,5632,5629 ,4880,4911,4835 ,0,0,0}, {5633,5623,5621 ,4880,4837,4838 ,0,0,0}, + {5626,5623,5633 ,4833,4837,4880 ,0,0,0}, {5633,5620,5618 ,4880,4839,4840 ,0,0,0}, + {5621,5620,5633 ,4838,4839,4880 ,0,0,0}, {5618,5600,5633 ,4840,4912,4880 ,0,0,0}, + {5605,5633,5604 ,4842,4880,4843 ,0,0,0}, {5633,5600,5604 ,4880,4912,4843 ,0,0,0}, + {5610,5633,5607 ,4844,4880,4845 ,0,0,0}, {5633,5605,5607 ,4880,4842,4845 ,0,0,0}, + {5614,5633,5611 ,4846,4880,4847 ,0,0,0}, {5633,5610,5611 ,4880,4844,4847 ,0,0,0}, + {5616,5633,5617 ,4913,4880,4849 ,0,0,0}, {5633,5614,5617 ,4880,4846,4849 ,0,0,0}, + {5634,5635,5636 ,4914,4915,4916 ,0,0,0}, {5636,5637,5638 ,4916,4917,4918 ,0,0,0}, + {5637,5639,5638 ,4917,4919,4918 ,0,0,0}, {5636,5638,5634 ,4916,4918,4914 ,0,0,0}, + {5640,5641,5642 ,4920,4921,4922 ,0,0,0}, {5642,5641,5639 ,4922,4921,4919 ,0,0,0}, + {5640,5643,5644 ,4920,4923,4924 ,0,0,0}, {5644,5641,5640 ,4924,4921,4920 ,0,0,0}, + {5644,5643,5645 ,4924,4923,4925 ,0,0,0}, {5645,5643,5646 ,4925,4923,4926 ,0,0,0}, + {5646,5647,5648 ,4926,4927,4928 ,0,0,0}, {5645,5646,5648 ,4925,4926,4928 ,0,0,0}, + {5639,5637,5642 ,4919,4917,4922 ,0,0,0}, {5649,5650,5651 ,4929,4815,4930 ,0,0,0}, + {5649,5651,5647 ,4929,4930,4927 ,0,0,0}, {5647,5651,5648 ,4927,4930,4928 ,0,0,0}, + {5634,5652,5635 ,4914,4931,4915 ,0,0,0}, {5653,5652,5654 ,4932,4931,4933 ,0,0,0}, + {5652,5653,5635 ,4931,4932,4915 ,0,0,0}, {5655,5656,5654 ,4934,4821,4933 ,0,0,0}, + {5653,5654,5656 ,4932,4933,4821 ,0,0,0}, {5655,5657,5658 ,4934,4935,4936 ,0,0,0}, + {5658,5656,5655 ,4936,4821,4934 ,0,0,0}, {5659,5657,5660 ,4937,4935,4938 ,0,0,0}, + {5657,5659,5658 ,4935,4937,4936 ,0,0,0}, {5661,5662,5660 ,4826,4877,4938 ,0,0,0}, + {5659,5660,5662 ,4937,4938,4877 ,0,0,0}, {5661,5663,5664 ,4826,4939,4940 ,0,0,0}, + {5664,5662,5661 ,4940,4877,4826 ,0,0,0}, {5665,5663,5666 ,4941,4939,4942 ,0,0,0}, + {5663,5665,5664 ,4939,4941,4940 ,0,0,0}, {5661,5660,5667 ,4832,4833,4943 ,0,0,0}, + {5667,5663,5661 ,4943,4835,4832 ,0,0,0}, {5667,5666,5663 ,4943,4944,4835 ,0,0,0}, + {5667,5657,5655 ,4943,4837,4838 ,0,0,0}, {5660,5657,5667 ,4833,4837,4943 ,0,0,0}, + {5667,5654,5652 ,4943,4839,4840 ,0,0,0}, {5655,5654,5667 ,4838,4839,4943 ,0,0,0}, + {5652,5634,5667 ,4840,4945,4943 ,0,0,0}, {5639,5667,5638 ,4842,4943,4843 ,0,0,0}, + {5667,5634,5638 ,4943,4945,4843 ,0,0,0}, {5644,5667,5641 ,4844,4943,4845 ,0,0,0}, + {5667,5639,5641 ,4943,4842,4845 ,0,0,0}, {5648,5667,5645 ,4846,4943,4847 ,0,0,0}, + {5667,5644,5645 ,4943,4844,4847 ,0,0,0}, {5650,5667,5651 ,4946,4943,4849 ,0,0,0}, + {5667,5648,5651 ,4943,4846,4849 ,0,0,0}, {5668,5669,5670 ,4947,4948,4949 ,0,0,0}, + {5671,5672,5673 ,4950,4951,4952 ,0,0,0}, {5670,5673,5672 ,4949,4952,4951 ,0,0,0}, + {5674,5675,5676 ,4953,4954,4955 ,0,0,0}, {5677,5678,5671 ,4956,4957,4950 ,0,0,0}, + {5674,5678,5677 ,4953,4957,4956 ,0,0,0}, {5677,5675,5674 ,4956,4954,4953 ,0,0,0}, + {5678,5672,5671 ,4957,4951,4950 ,0,0,0}, {5679,5680,5681 ,4958,4959,4960 ,0,0,0}, + {5680,5682,5681 ,4959,4961,4960 ,0,0,0}, {5683,5684,5685 ,4962,4963,4964 ,0,0,0}, + {5683,5685,5682 ,4962,4964,4961 ,0,0,0}, {5680,5683,5682 ,4959,4962,4961 ,0,0,0}, + {5675,5679,5676 ,4954,4958,4955 ,0,0,0}, {5679,5681,5676 ,4958,4960,4955 ,0,0,0}, + {5686,5687,5688 ,4965,4966,4967 ,0,0,0}, {5689,5690,5691 ,4968,4969,4970 ,0,0,0}, + {5688,5687,5689 ,4967,4966,4968 ,0,0,0}, {5692,5693,5694 ,4726,4971,4972 ,0,0,0}, + {5688,5689,5691 ,4967,4968,4970 ,0,0,0}, {5694,5693,5690 ,4972,4971,4969 ,0,0,0}, + {5693,5691,5690 ,4971,4970,4969 ,0,0,0}, {5684,5687,5686 ,4963,4966,4965 ,0,0,0}, + {5695,5692,5694 ,4726,4726,4972 ,0,0,0}, {5685,5684,5686 ,4964,4963,4965 ,0,0,0}, + {5669,5673,5670 ,4948,4952,4949 ,0,0,0}, {5696,5669,5668 ,4973,4948,4947 ,0,0,0}, + {5696,5697,5698 ,4973,4974,4975 ,0,0,0}, {5697,5696,5668 ,4974,4973,4947 ,0,0,0}, + {5699,5698,5700 ,4976,4975,4977 ,0,0,0}, {5697,5700,5698 ,4974,4977,4975 ,0,0,0}, + {5701,5702,5699 ,4978,4979,4976 ,0,0,0}, {5699,5700,5701 ,4976,4977,4978 ,0,0,0}, + {5702,5703,5704 ,4979,4980,4981 ,0,0,0}, {5703,5702,5701 ,4980,4979,4978 ,0,0,0}, + {5705,5704,5706 ,4982,4981,4983 ,0,0,0}, {5703,5706,5704 ,4980,4983,4981 ,0,0,0}, + {5707,5708,5705 ,4984,4985,4982 ,0,0,0}, {5705,5706,5707 ,4982,4983,4984 ,0,0,0}, + {5708,5709,5710 ,4985,4986,4987 ,0,0,0}, {5709,5708,5707 ,4986,4985,4984 ,0,0,0}, + {5711,5710,5712 ,4988,4987,4989 ,0,0,0}, {5709,5712,5710 ,4986,4989,4987 ,0,0,0}, + {5713,5714,5711 ,4990,4991,4988 ,0,0,0}, {5711,5712,5713 ,4988,4989,4990 ,0,0,0}, + {5714,5715,5716 ,4991,4992,4748 ,0,0,0}, {5715,5714,5713 ,4992,4991,4990 ,0,0,0}, + {5715,5717,5716 ,4992,4750,4748 ,0,0,0}, {5718,5719,5720 ,4993,4994,4995 ,0,0,0}, + {5721,5722,5723 ,4996,4997,4998 ,0,0,0}, {5719,5724,5725 ,4994,4999,5000 ,0,0,0}, + {5724,5719,5718 ,4999,4994,4993 ,0,0,0}, {5724,5726,5725 ,4999,5001,5000 ,0,0,0}, + {5720,5727,5718 ,4995,5002,4993 ,0,0,0}, {5721,5727,5728 ,4996,5002,5003 ,0,0,0}, + {5720,5728,5727 ,4995,5003,5002 ,0,0,0}, {5729,5730,5731 ,5004,5005,5006 ,0,0,0}, + {5721,5728,5722 ,4996,5003,4997 ,0,0,0}, {5732,5733,5734 ,5007,5008,5009 ,0,0,0}, + {5735,5736,5737 ,5010,5011,5012 ,0,0,0}, {5738,5739,5740 ,5013,5014,5015 ,0,0,0}, + {5741,5742,5743 ,5016,5017,5018 ,0,0,0}, {5744,5745,5746 ,5019,5020,5021 ,0,0,0}, + {5747,5748,5739 ,5022,5023,5014 ,0,0,0}, {5749,5750,5751 ,5024,5025,5026 ,0,0,0}, + {5750,5745,5752 ,5025,5020,5027 ,0,0,0}, {5753,5754,5755 ,5028,5029,5030 ,0,0,0}, + {5756,5757,5749 ,5031,5032,5024 ,0,0,0}, {5758,5759,5760 ,5033,5034,5035 ,0,0,0}, + {5761,5755,5762 ,5036,5030,5037 ,0,0,0}, {5763,5764,5765 ,5038,5039,5040 ,0,0,0}, + {5766,5764,5767 ,5041,5039,5042 ,0,0,0}, {5768,5769,5770 ,5043,5044,5045 ,0,0,0}, + {5765,5771,5768 ,5040,5046,5043 ,0,0,0}, {5772,5773,5774 ,5047,5048,5049 ,0,0,0}, + {5772,5775,5776 ,5047,5050,5051 ,0,0,0}, {5777,5778,5779 ,5052,5053,5054 ,0,0,0}, + {5780,5781,5779 ,5055,5056,5054 ,0,0,0}, {5782,5783,5784 ,5057,5058,5059 ,0,0,0}, + {5783,5777,5785 ,5058,5052,5060 ,0,0,0}, {5786,5787,5788 ,5061,5062,5063 ,0,0,0}, + {5782,5789,5786 ,5057,5064,5061 ,0,0,0}, {5790,5791,5792 ,5065,5066,5067 ,0,0,0}, + {5790,5793,5794 ,5065,5068,5069 ,0,0,0}, {5795,5796,5797 ,5070,5071,5072 ,0,0,0}, + {5795,5798,5791 ,5070,5073,5066 ,0,0,0}, {5799,5796,5800 ,5074,5071,5075 ,0,0,0}, + {5796,5799,5797 ,5071,5074,5072 ,0,0,0}, {5801,5802,5800 ,5076,5077,5075 ,0,0,0}, + {5799,5800,5802 ,5074,5075,5077 ,0,0,0}, {5803,5804,5802 ,5078,5079,5077 ,0,0,0}, + {5802,5801,5803 ,5077,5076,5078 ,0,0,0}, {5804,5805,5806 ,5079,5080,5081 ,0,0,0}, + {5805,5804,5803 ,5080,5079,5078 ,0,0,0}, {5807,5806,5808 ,5082,5081,5083 ,0,0,0}, + {5805,5808,5806 ,5080,5083,5081 ,0,0,0}, {5809,5810,5807 ,5084,5085,5082 ,0,0,0}, + {5807,5808,5809 ,5082,5083,5084 ,0,0,0}, {5810,5811,5812 ,5085,5086,5087 ,0,0,0}, + {5811,5810,5809 ,5086,5085,5084 ,0,0,0}, {5813,5812,5814 ,5088,5087,5089 ,0,0,0}, + {5811,5814,5812 ,5086,5089,5087 ,0,0,0}, {5815,5813,5816 ,5090,5088,5091 ,0,0,0}, + {5813,5814,5816 ,5088,5089,5091 ,0,0,0}, {5815,5817,5818 ,5090,5092,5093 ,0,0,0}, + {5818,5813,5815 ,5093,5088,5090 ,0,0,0}, {5819,5817,5820 ,5094,5092,5095 ,0,0,0}, + {5817,5819,5818 ,5092,5094,5093 ,0,0,0}, {5821,5822,5820 ,126,5096,5095 ,0,0,0}, + {5819,5820,5822 ,5094,5095,5096 ,0,0,0}, {5823,5822,5821 ,126,5096,126 ,0,0,0}, + {5792,5791,5798 ,5067,5066,5073 ,0,0,0}, {5795,5797,5798 ,5070,5072,5073 ,0,0,0}, + {5788,5793,5786 ,5063,5068,5061 ,0,0,0}, {5790,5792,5793 ,5065,5067,5068 ,0,0,0}, + {5788,5794,5793 ,5063,5069,5068 ,0,0,0}, {5784,5789,5782 ,5059,5064,5057 ,0,0,0}, + {5786,5789,5787 ,5061,5064,5062 ,0,0,0}, {5778,5777,5783 ,5053,5052,5058 ,0,0,0}, + {5783,5785,5784 ,5058,5060,5059 ,0,0,0}, {5780,5773,5781 ,5055,5048,5056 ,0,0,0}, + {5778,5780,5779 ,5053,5055,5054 ,0,0,0}, {5772,5774,5775 ,5047,5049,5050 ,0,0,0}, + {5773,5780,5774 ,5048,5055,5049 ,0,0,0}, {5769,5776,5770 ,5044,5051,5045 ,0,0,0}, + {5776,5775,5770 ,5051,5050,5045 ,0,0,0}, {5765,5768,5763 ,5040,5043,5038 ,0,0,0}, + {5771,5769,5768 ,5046,5044,5043 ,0,0,0}, {5758,5766,5759 ,5033,5041,5034 ,0,0,0}, + {5767,5764,5763 ,5042,5039,5038 ,0,0,0}, {5759,5766,5767 ,5034,5041,5042 ,0,0,0}, + {5760,5761,5762 ,5035,5036,5037 ,0,0,0}, {5759,5761,5760 ,5034,5036,5035 ,0,0,0}, + {5755,5757,5753 ,5030,5032,5028 ,0,0,0}, {5762,5755,5754 ,5037,5030,5029 ,0,0,0}, + {5824,5756,5749 ,5097,5031,5024 ,0,0,0}, {5756,5753,5757 ,5031,5028,5032 ,0,0,0}, + {5825,5750,5752 ,5098,5025,5027 ,0,0,0}, {5749,5751,5824 ,5024,5026,5097 ,0,0,0}, + {5750,5825,5751 ,5025,5098,5026 ,0,0,0}, {5746,5747,5744 ,5021,5022,5019 ,0,0,0}, + {5752,5745,5744 ,5027,5020,5019 ,0,0,0}, {5740,5743,5738 ,5015,5018,5013 ,0,0,0}, + {5747,5746,5748 ,5022,5021,5023 ,0,0,0}, {5739,5748,5740 ,5014,5023,5015 ,0,0,0}, + {5732,5741,5743 ,5007,5016,5018 ,0,0,0}, {5742,5738,5743 ,5017,5013,5018 ,0,0,0}, + {5733,5737,5734 ,5008,5012,5009 ,0,0,0}, {5732,5734,5741 ,5007,5009,5016 ,0,0,0}, + {5735,5729,5736 ,5010,5004,5011 ,0,0,0}, {5733,5735,5737 ,5008,5010,5012 ,0,0,0}, + {5731,5730,5723 ,5006,5005,4998 ,0,0,0}, {5736,5729,5731 ,5011,5004,5006 ,0,0,0}, + {5721,5723,5730 ,4996,4998,5005 ,0,0,0}, {5826,5827,5828 ,5099,5100,5101 ,0,0,0}, + {5829,5830,5831 ,5102,5103,5104 ,0,0,0}, {5832,5830,5829 ,5105,5103,5102 ,0,0,0}, + {5833,5829,5831 ,5106,5102,5104 ,0,0,0}, {5834,5835,5836 ,5107,5108,5109 ,0,0,0}, + {5837,5838,5833 ,5110,5108,5106 ,0,0,0}, {5835,5839,5836 ,5108,5111,5109 ,0,0,0}, + {5835,5838,5839 ,5108,5108,5111 ,0,0,0}, {5839,5840,5841 ,5111,5112,5113 ,0,0,0}, + {5840,5842,5841 ,5112,5114,5113 ,0,0,0}, {5841,5842,5843 ,5113,5114,5115 ,0,0,0}, + {5842,5844,5843 ,5114,5116,5115 ,0,0,0}, {5845,5846,5844 ,5117,5118,5116 ,0,0,0}, + {5845,5847,5848 ,5117,5119,5120 ,0,0,0}, {5849,5848,5847 ,5121,5120,5119 ,0,0,0}, + {5849,5847,5850 ,5121,5119,5122 ,0,0,0}, {5850,5851,5849 ,5122,5123,5121 ,0,0,0}, + {5846,5843,5844 ,5118,5115,5116 ,0,0,0}, {5848,5846,5845 ,5120,5118,5117 ,0,0,0}, + {5851,5852,5853 ,5123,5124,5125 ,0,0,0}, {5852,5851,5850 ,5124,5123,5122 ,0,0,0}, + {5430,5853,5852 ,5126,5125,5124 ,0,0,0}, {5832,5829,5854 ,5105,5102,5127 ,0,0,0}, + {5855,5856,5857 ,5128,5129,5130 ,0,0,0}, {5855,5854,5856 ,5128,5127,5129 ,0,0,0}, + {5856,5858,5857 ,5129,5131,5130 ,0,0,0}, {5858,5856,5859 ,5131,5129,5132 ,0,0,0}, + {5860,5861,5862 ,5133,5134,5135 ,0,0,0}, {5860,5859,5861 ,5133,5132,5134 ,0,0,0}, + {5863,5862,5861 ,5136,5135,5134 ,0,0,0}, {5862,5863,5864 ,5135,5136,5137 ,0,0,0}, + {5865,5866,5867 ,5138,5139,5140 ,0,0,0}, {5868,5869,5863 ,5141,5142,5136 ,0,0,0}, + {5870,5871,5868 ,5143,5144,5141 ,0,0,0}, {5871,5870,5872 ,5144,5143,5145 ,0,0,0}, + {5873,5874,5870 ,5146,5147,5143 ,0,0,0}, {5827,5826,5875 ,5100,5099,5148 ,0,0,0}, + {5876,5877,5873 ,5149,5150,5146 ,0,0,0}, {5878,5879,5880 ,5151,5152,5153 ,0,0,0}, + {5881,5882,5883 ,5154,5155,5156 ,0,0,0}, {5884,5885,5886 ,5157,5158,5159 ,0,0,0}, + {5887,5888,5889 ,5160,5161,5162 ,0,0,0}, {5890,5891,5892 ,5163,5164,5165 ,0,0,0}, + {5893,5894,5895 ,5166,5167,5168 ,0,0,0}, {5893,5896,5897 ,5166,5169,5170 ,0,0,0}, + {5898,5899,5900 ,5171,5172,5173 ,0,0,0}, {5901,5902,5903 ,5174,5175,5176 ,0,0,0}, + {5904,5905,5906 ,5177,5178,5179 ,0,0,0}, {5907,5899,5898 ,5180,5172,5171 ,0,0,0}, + {5908,5909,5910 ,5179,5181,5182 ,0,0,0}, {5908,5906,5905 ,5179,5179,5178 ,0,0,0}, + {5911,5912,5913 ,5183,5184,5185 ,0,0,0}, {5914,5911,5910 ,5186,5183,5182 ,0,0,0}, + {5915,5916,5917 ,5187,5188,5189 ,0,0,0}, {5918,5915,5913 ,5190,5187,5185 ,0,0,0}, + {5919,5920,5921 ,5191,5192,5193 ,0,0,0}, {5920,5919,5917 ,5192,5191,5189 ,0,0,0}, + {5922,5923,5921 ,5194,5195,5193 ,0,0,0}, {5919,5921,5923 ,5191,5193,5195 ,0,0,0}, + {5922,5924,5925 ,5194,5196,5197 ,0,0,0}, {5925,5923,5922 ,5197,5195,5194 ,0,0,0}, + {5918,5916,5915 ,5190,5188,5187 ,0,0,0}, {5916,5920,5917 ,5188,5192,5189 ,0,0,0}, + {5912,5918,5913 ,5184,5190,5185 ,0,0,0}, {5914,5912,5911 ,5186,5184,5183 ,0,0,0}, + {5909,5914,5910 ,5181,5186,5182 ,0,0,0}, {5909,5908,5905 ,5181,5179,5178 ,0,0,0}, + {5905,5926,5909 ,5178,5198,5181 ,0,0,0}, {5898,5926,5907 ,5171,5198,5180 ,0,0,0}, + {5926,5905,5907 ,5198,5178,5180 ,0,0,0}, {5927,5928,5929 ,5199,5200,5201 ,0,0,0}, + {5900,5899,5901 ,5173,5172,5174 ,0,0,0}, {5927,5930,5931 ,5199,5202,5203 ,0,0,0}, + {5931,5928,5927 ,5203,5200,5199 ,0,0,0}, {5932,5930,5933 ,5204,5202,5205 ,0,0,0}, + {5930,5932,5931 ,5202,5204,5203 ,0,0,0}, {5934,5528,5933 ,5206,5207,5205 ,0,0,0}, + {5932,5933,5528 ,5204,5205,5207 ,0,0,0}, {5531,5528,5934 ,5197,5207,5206 ,0,0,0}, + {5929,5928,5935 ,5201,5200,5208 ,0,0,0}, {5936,5937,5938 ,5209,5210,5211 ,0,0,0}, + {5929,5935,5938 ,5201,5208,5211 ,0,0,0}, {5936,5939,5937 ,5209,5212,5210 ,0,0,0}, + {5938,5935,5936 ,5211,5208,5209 ,0,0,0}, {5902,5894,5903 ,5175,5167,5176 ,0,0,0}, + {5939,5940,5937 ,5212,5213,5210 ,0,0,0}, {5906,5940,5904 ,5179,5213,5177 ,0,0,0}, + {5939,5904,5940 ,5212,5177,5213 ,0,0,0}, {5901,5903,5900 ,5174,5176,5173 ,0,0,0}, + {5892,5881,5890 ,5165,5154,5163 ,0,0,0}, {5893,5895,5896 ,5166,5168,5169 ,0,0,0}, + {5894,5902,5895 ,5167,5175,5168 ,0,0,0}, {5896,5889,5897 ,5169,5162,5170 ,0,0,0}, + {5891,5888,5887 ,5164,5161,5160 ,0,0,0}, {5888,5897,5889 ,5161,5170,5162 ,0,0,0}, + {5892,5891,5887 ,5165,5164,5160 ,0,0,0}, {5878,5885,5884 ,5151,5158,5157 ,0,0,0}, + {5881,5883,5890 ,5154,5156,5163 ,0,0,0}, {5882,5886,5883 ,5155,5159,5156 ,0,0,0}, + {5880,5885,5878 ,5153,5158,5151 ,0,0,0}, {5882,5884,5886 ,5155,5157,5159 ,0,0,0}, + {5828,5880,5879 ,5101,5153,5152 ,0,0,0}, {5879,5480,5876 ,5152,5214,5149 ,0,0,0}, + {5834,5941,5835 ,5107,5215,5108 ,0,0,0}, {5840,5839,5838 ,5112,5111,5108 ,0,0,0}, + {5837,5942,5838 ,5110,5216,5108 ,0,0,0}, {5840,5838,5942 ,5112,5108,5216 ,0,0,0}, + {5943,5941,5944 ,5217,5215,5218 ,0,0,0}, {5831,5837,5833 ,5104,5110,5106 ,0,0,0}, + {5945,5943,5946 ,5219,5217,5220 ,0,0,0}, {5945,5947,5943 ,5219,5221,5217 ,0,0,0}, + {5948,5947,5949 ,5222,5221,5223 ,0,0,0}, {5855,5832,5854 ,5128,5105,5127 ,0,0,0}, + {5950,5948,5951 ,5224,5222,5225 ,0,0,0}, {5950,5952,5948 ,5224,5226,5222 ,0,0,0}, + {5953,5952,5954 ,5227,5226,5228 ,0,0,0}, {5860,5858,5859 ,5133,5131,5132 ,0,0,0}, + {5955,5956,5953 ,5229,5230,5227 ,0,0,0}, {5957,5956,5955 ,5231,5230,5229 ,0,0,0}, + {5958,5956,5959 ,5232,5230,5233 ,0,0,0}, {5869,5864,5863 ,5142,5137,5136 ,0,0,0}, + {5867,5958,5865 ,5140,5232,5138 ,0,0,0}, {5871,5869,5868 ,5144,5142,5141 ,0,0,0}, + {5960,5867,5961 ,5234,5140,5235 ,0,0,0}, {5874,5872,5870 ,5147,5145,5143 ,0,0,0}, + {5826,5960,5875 ,5099,5234,5148 ,0,0,0}, {5877,5874,5873 ,5150,5147,5146 ,0,0,0}, + {5877,5876,5480 ,5150,5149,5214 ,0,0,0}, {5879,5876,5828 ,5152,5149,5101 ,0,0,0}, + {5828,5876,5826 ,5101,5149,5099 ,0,0,0}, {5961,5875,5960 ,5235,5148,5234 ,0,0,0}, + {5866,5961,5867 ,5139,5235,5140 ,0,0,0}, {5959,5865,5958 ,5233,5138,5232 ,0,0,0}, + {5957,5959,5956 ,5231,5233,5230 ,0,0,0}, {5954,5955,5953 ,5228,5229,5227 ,0,0,0}, + {5950,5954,5952 ,5224,5228,5226 ,0,0,0}, {5949,5951,5948 ,5223,5225,5222 ,0,0,0}, + {5945,5949,5947 ,5219,5223,5221 ,0,0,0}, {5944,5946,5943 ,5218,5220,5217 ,0,0,0}, + {5834,5944,5941 ,5107,5218,5215 ,0,0,0}, {5962,5963,5964 ,5236,5237,5238 ,0,0,0}, + {5965,5966,5964 ,5239,5240,5238 ,0,0,0}, {5962,5964,5966 ,5236,5238,5240 ,0,0,0}, + {5965,5967,5968 ,5239,5241,5242 ,0,0,0}, {5968,5966,5965 ,5242,5240,5239 ,0,0,0}, + {5969,5967,5970 ,5243,5241,5244 ,0,0,0}, {5967,5969,5968 ,5241,5243,5242 ,0,0,0}, + {5971,5972,5970 ,5245,5246,5244 ,0,0,0}, {5969,5970,5972 ,5243,5244,5246 ,0,0,0}, + {5971,5973,5974 ,5245,5247,5248 ,0,0,0}, {5974,5972,5971 ,5248,5246,5245 ,0,0,0}, + {5975,5973,5976 ,5249,5247,5250 ,0,0,0}, {5973,5975,5974 ,5247,5249,5248 ,0,0,0}, + {5977,5978,5976 ,5251,5252,5250 ,0,0,0}, {5975,5976,5978 ,5249,5250,5252 ,0,0,0}, + {5977,5979,5980 ,5251,5253,5254 ,0,0,0}, {5980,5978,5977 ,5254,5252,5251 ,0,0,0}, + {5981,5979,5982 ,5255,5253,5256 ,0,0,0}, {5979,5981,5980 ,5253,5255,5254 ,0,0,0}, + {5983,5984,5982 ,5257,5258,5256 ,0,0,0}, {5981,5982,5984 ,5255,5256,5258 ,0,0,0}, + {5983,5985,5986 ,5257,5259,5260 ,0,0,0}, {5986,5984,5983 ,5260,5258,5257 ,0,0,0}, + {5987,5985,5988 ,5261,5259,5262 ,0,0,0}, {5985,5987,5986 ,5259,5261,5260 ,0,0,0}, + {5989,5990,5988 ,5263,5264,5262 ,0,0,0}, {5987,5988,5990 ,5261,5262,5264 ,0,0,0}, + {5989,5991,5992 ,5263,5265,5266 ,0,0,0}, {5992,5990,5989 ,5266,5264,5263 ,0,0,0}, + {5993,5991,5994 ,5267,5265,5268 ,0,0,0}, {5991,5993,5992 ,5265,5267,5266 ,0,0,0}, + {5995,5996,5994 ,5269,5270,5268 ,0,0,0}, {5993,5994,5996 ,5267,5268,5270 ,0,0,0}, + {5995,5997,5998 ,5269,5271,5272 ,0,0,0}, {5998,5996,5995 ,5272,5270,5269 ,0,0,0}, + {5999,5997,6000 ,5273,5271,5274 ,0,0,0}, {5997,5999,5998 ,5271,5273,5272 ,0,0,0}, + {6001,6002,6000 ,5275,5276,5274 ,0,0,0}, {5999,6000,6002 ,5273,5274,5276 ,0,0,0}, + {6001,6003,6004 ,5275,5277,5278 ,0,0,0}, {6004,6002,6001 ,5278,5276,5275 ,0,0,0}, + {6005,6003,6006 ,5279,5277,5280 ,0,0,0}, {6003,6005,6004 ,5277,5279,5278 ,0,0,0}, + {6007,6008,6006 ,5281,5282,5280 ,0,0,0}, {6005,6006,6008 ,5279,5280,5282 ,0,0,0}, + {6009,6007,6010 ,5283,5281,5284 ,0,0,0}, {6009,6008,6007 ,5283,5282,5281 ,0,0,0}, + {6011,6010,6012 ,5285,5284,5286 ,0,0,0}, {6007,6012,6010 ,5281,5286,5284 ,0,0,0}, + {6013,6011,6014 ,5287,5285,5288 ,0,0,0}, {6011,6012,6014 ,5285,5286,5288 ,0,0,0}, + {6013,6015,6016 ,5287,5289,5290 ,0,0,0}, {6016,6011,6013 ,5290,5285,5287 ,0,0,0}, + {6015,6017,6016 ,5289,5291,5290 ,0,0,0}, {6018,5963,5962 ,5292,5237,5236 ,0,0,0}, + {6018,6019,6020 ,5292,5293,5294 ,0,0,0}, {6020,5963,6018 ,5294,5237,5292 ,0,0,0}, + {6021,6019,6022 ,5295,5293,5296 ,0,0,0}, {6019,6021,6020 ,5293,5295,5294 ,0,0,0}, + {6023,6024,6022 ,5297,5298,5296 ,0,0,0}, {6021,6022,6024 ,5295,5296,5298 ,0,0,0}, + {6023,6025,6026 ,5297,5299,5300 ,0,0,0}, {6026,6024,6023 ,5300,5298,5297 ,0,0,0}, + {6027,6025,6028 ,5301,5299,5302 ,0,0,0}, {6025,6027,6026 ,5299,5301,5300 ,0,0,0}, + {6029,6030,6028 ,5303,5304,5302 ,0,0,0}, {6027,6028,6030 ,5301,5302,5304 ,0,0,0}, + {6029,6031,6032 ,5303,5305,5306 ,0,0,0}, {6032,6030,6029 ,5306,5304,5303 ,0,0,0}, + {6033,6031,6034 ,5307,5305,5308 ,0,0,0}, {6031,6033,6032 ,5305,5307,5306 ,0,0,0}, + {6035,6036,6034 ,5309,5310,5308 ,0,0,0}, {6033,6034,6036 ,5307,5308,5310 ,0,0,0}, + {6035,6037,6038 ,5309,5311,5312 ,0,0,0}, {6038,6036,6035 ,5312,5310,5309 ,0,0,0}, + {6039,6037,6040 ,5313,5311,5314 ,0,0,0}, {6037,6039,6038 ,5311,5313,5312 ,0,0,0}, + {6041,6042,6040 ,5315,5316,5314 ,0,0,0}, {6039,6040,6042 ,5313,5314,5316 ,0,0,0}, + {6041,6043,6044 ,5315,5317,5318 ,0,0,0}, {6044,6042,6041 ,5318,5316,5315 ,0,0,0}, + {6045,6043,6046 ,5319,5317,5320 ,0,0,0}, {6043,6045,6044 ,5317,5319,5318 ,0,0,0}, + {6047,6048,6046 ,5321,5322,5320 ,0,0,0}, {6045,6046,6048 ,5319,5320,5322 ,0,0,0}, + {6047,6049,6050 ,5321,5323,5324 ,0,0,0}, {6050,6048,6047 ,5324,5322,5321 ,0,0,0}, + {6051,6049,6052 ,5325,5323,5326 ,0,0,0}, {6049,6051,6050 ,5323,5325,5324 ,0,0,0}, + {6053,6054,6052 ,5327,5328,5326 ,0,0,0}, {6051,6052,6054 ,5325,5326,5328 ,0,0,0}, + {6053,6055,6056 ,5327,5329,5330 ,0,0,0}, {6056,6054,6053 ,5330,5328,5327 ,0,0,0}, + {6057,6055,6058 ,5331,5329,5332 ,0,0,0}, {6055,6057,6056 ,5329,5331,5330 ,0,0,0}, + {6059,6060,6058 ,5333,5334,5332 ,0,0,0}, {6057,6058,6060 ,5331,5332,5334 ,0,0,0}, + {6059,6061,6062 ,5333,5335,5336 ,0,0,0}, {6062,6060,6059 ,5336,5334,5333 ,0,0,0}, + {6063,6064,6061 ,5337,5338,5335 ,0,0,0}, {6061,6064,6062 ,5335,5338,5336 ,0,0,0}, + {6065,6066,6063 ,5339,5340,5337 ,0,0,0}, {6063,6061,6065 ,5337,5335,5339 ,0,0,0}, + {6067,6068,6066 ,5341,5342,5340 ,0,0,0}, {6067,6066,6065 ,5341,5340,5339 ,0,0,0}, + {6069,6068,6070 ,5343,5342,5344 ,0,0,0}, {6068,6069,6066 ,5342,5343,5340 ,0,0,0}, + {6069,6070,6071 ,5343,5344,5345 ,0,0,0}, {6072,6073,6074 ,5346,5347,5348 ,0,0,0}, + {6075,6076,6074 ,5349,5350,5348 ,0,0,0}, {6072,6074,6076 ,5346,5348,5350 ,0,0,0}, + {6075,6077,6078 ,5349,5351,5352 ,0,0,0}, {6078,6076,6075 ,5352,5350,5349 ,0,0,0}, + {6079,6077,6080 ,5353,5351,5354 ,0,0,0}, {6077,6079,6078 ,5351,5353,5352 ,0,0,0}, + {6081,6082,6080 ,5355,5356,5354 ,0,0,0}, {6079,6080,6082 ,5353,5354,5356 ,0,0,0}, + {6081,6083,6084 ,5355,5357,5358 ,0,0,0}, {6084,6082,6081 ,5358,5356,5355 ,0,0,0}, + {6085,6083,6086 ,5359,5357,5360 ,0,0,0}, {6083,6085,6084 ,5357,5359,5358 ,0,0,0}, + {6087,6088,6086 ,5361,5362,5360 ,0,0,0}, {6085,6086,6088 ,5359,5360,5362 ,0,0,0}, + {6087,6089,6090 ,5361,5363,5364 ,0,0,0}, {6090,6088,6087 ,5364,5362,5361 ,0,0,0}, + {6091,6089,6092 ,5365,5363,5366 ,0,0,0}, {6089,6091,6090 ,5363,5365,5364 ,0,0,0}, + {6093,6094,6092 ,5367,5368,5366 ,0,0,0}, {6091,6092,6094 ,5365,5366,5368 ,0,0,0}, + {6093,6095,6096 ,5367,5369,5370 ,0,0,0}, {6096,6094,6093 ,5370,5368,5367 ,0,0,0}, + {6097,6095,6098 ,5371,5369,5372 ,0,0,0}, {6095,6097,6096 ,5369,5371,5370 ,0,0,0}, + {6099,6100,6098 ,5373,5374,5372 ,0,0,0}, {6097,6098,6100 ,5371,5372,5374 ,0,0,0}, + {6099,6101,6102 ,5373,5375,5376 ,0,0,0}, {6102,6100,6099 ,5376,5374,5373 ,0,0,0}, + {6103,6101,6104 ,5377,5375,5378 ,0,0,0}, {6101,6103,6102 ,5375,5377,5376 ,0,0,0}, + {6105,6106,6104 ,5379,5380,5378 ,0,0,0}, {6103,6104,6106 ,5377,5378,5380 ,0,0,0}, + {6105,6107,6108 ,5379,5381,5382 ,0,0,0}, {6108,6106,6105 ,5382,5380,5379 ,0,0,0}, + {6109,6107,6110 ,5383,5381,5384 ,0,0,0}, {6107,6109,6108 ,5381,5383,5382 ,0,0,0}, + {6111,6112,6110 ,5385,5386,5384 ,0,0,0}, {6109,6110,6112 ,5383,5384,5386 ,0,0,0}, + {6111,6113,6114 ,5385,5387,5388 ,0,0,0}, {6114,6112,6111 ,5388,5386,5385 ,0,0,0}, + {6115,6113,6116 ,5389,5387,5390 ,0,0,0}, {6113,6115,6114 ,5387,5389,5388 ,0,0,0}, + {6117,6118,6116 ,5391,5392,5390 ,0,0,0}, {6115,6116,6118 ,5389,5390,5392 ,0,0,0}, + {6117,6119,6120 ,5391,5393,5394 ,0,0,0}, {6120,6118,6117 ,5394,5392,5391 ,0,0,0}, + {6121,6119,6122 ,5395,5393,5396 ,0,0,0}, {6119,6121,6120 ,5393,5395,5394 ,0,0,0}, + {6123,6124,6122 ,5397,5398,5396 ,0,0,0}, {6121,6122,6124 ,5395,5396,5398 ,0,0,0}, + {6123,6125,6126 ,5397,5399,5400 ,0,0,0}, {6126,6124,6123 ,5400,5398,5397 ,0,0,0}, + {6127,6125,6128 ,5401,5399,5402 ,0,0,0}, {6125,6127,6126 ,5399,5401,5400 ,0,0,0}, + {6129,6130,6128 ,5403,5404,5402 ,0,0,0}, {6127,6128,6130 ,5401,5402,5404 ,0,0,0}, + {6129,6131,6132 ,5403,5405,5406 ,0,0,0}, {6132,6130,6129 ,5406,5404,5403 ,0,0,0}, + {6131,6133,6132 ,5405,5407,5406 ,0,0,0}, {6134,6073,6072 ,5408,5347,5346 ,0,0,0}, + {6134,6135,6136 ,5408,5409,5410 ,0,0,0}, {6136,6073,6134 ,5410,5347,5408 ,0,0,0}, + {6137,6135,6138 ,5411,5409,5412 ,0,0,0}, {6135,6137,6136 ,5409,5411,5410 ,0,0,0}, + {6139,6140,6138 ,5413,5414,5412 ,0,0,0}, {6137,6138,6140 ,5411,5412,5414 ,0,0,0}, + {6139,6141,6142 ,5413,5415,5416 ,0,0,0}, {6142,6140,6139 ,5416,5414,5413 ,0,0,0}, + {6143,6141,6144 ,5417,5415,5418 ,0,0,0}, {6141,6143,6142 ,5415,5417,5416 ,0,0,0}, + {6145,6146,6144 ,5419,5420,5418 ,0,0,0}, {6143,6144,6146 ,5417,5418,5420 ,0,0,0}, + {6145,6147,6148 ,5419,5421,5422 ,0,0,0}, {6148,6146,6145 ,5422,5420,5419 ,0,0,0}, + {6149,6147,6150 ,5423,5421,5424 ,0,0,0}, {6147,6149,6148 ,5421,5423,5422 ,0,0,0}, + {6151,6152,6150 ,5425,5426,5424 ,0,0,0}, {6149,6150,6152 ,5423,5424,5426 ,0,0,0}, + {6151,6153,6154 ,5425,5427,5428 ,0,0,0}, {6154,6152,6151 ,5428,5426,5425 ,0,0,0}, + {6155,6153,6156 ,5429,5427,5430 ,0,0,0}, {6153,6155,6154 ,5427,5429,5428 ,0,0,0}, + {6157,6158,6156 ,5431,5432,5430 ,0,0,0}, {6155,6156,6158 ,5429,5430,5432 ,0,0,0}, + {6157,6159,6160 ,5431,5433,5434 ,0,0,0}, {6160,6158,6157 ,5434,5432,5431 ,0,0,0}, + {6161,6159,6162 ,5435,5433,5436 ,0,0,0}, {6159,6161,6160 ,5433,5435,5434 ,0,0,0}, + {6163,6164,6162 ,5437,5438,5436 ,0,0,0}, {6161,6162,6164 ,5435,5436,5438 ,0,0,0}, + {6163,6165,6166 ,5437,5439,5440 ,0,0,0}, {6166,6164,6163 ,5440,5438,5437 ,0,0,0}, + {6167,6165,6168 ,5441,5439,5442 ,0,0,0}, {6165,6167,6166 ,5439,5441,5440 ,0,0,0}, + {6169,6170,6168 ,5443,5444,5442 ,0,0,0}, {6167,6168,6170 ,5441,5442,5444 ,0,0,0}, + {6169,6171,6172 ,5443,5445,5446 ,0,0,0}, {6172,6170,6169 ,5446,5444,5443 ,0,0,0}, + {6173,6171,6174 ,5447,5445,5448 ,0,0,0}, {6171,6173,6172 ,5445,5447,5446 ,0,0,0}, + {6175,6176,6174 ,5449,5450,5448 ,0,0,0}, {6173,6174,6176 ,5447,5448,5450 ,0,0,0}, + {6175,6177,6178 ,5449,5451,5452 ,0,0,0}, {6178,6176,6175 ,5452,5450,5449 ,0,0,0}, + {6179,6177,6180 ,5453,5451,5454 ,0,0,0}, {6177,6179,6178 ,5451,5453,5452 ,0,0,0}, + {6181,6182,6180 ,5455,5456,5454 ,0,0,0}, {6179,6180,6182 ,5453,5454,5456 ,0,0,0}, + {6181,6183,6184 ,5455,5457,5458 ,0,0,0}, {6184,6182,6181 ,5458,5456,5455 ,0,0,0}, + {6185,6183,6186 ,5459,5457,5460 ,0,0,0}, {6183,6185,6184 ,5457,5459,5458 ,0,0,0}, + {6187,6188,6186 ,5461,5462,5460 ,0,0,0}, {6185,6186,6188 ,5459,5460,5462 ,0,0,0}, + {6187,6189,6190 ,5461,5463,5464 ,0,0,0}, {6190,6188,6187 ,5464,5462,5461 ,0,0,0}, + {6191,6189,6192 ,5465,5463,5466 ,0,0,0}, {6189,6191,6190 ,5463,5465,5464 ,0,0,0}, + {6191,6192,6193 ,5465,5466,5467 ,0,0,0}, {6194,5228,5227 ,5468,5469,5469 ,0,0,0}, + {6195,6196,6197 ,726,726,726 ,0,0,0}, {6198,4961,4958 ,726,5470,726 ,0,0,0}, + {6199,6200,6201 ,5471,726,726 ,0,0,0}, {6202,6203,6204 ,726,726,726 ,0,0,0}, + {6205,5183,6206 ,5468,5471,5469 ,0,0,0}, {6207,6208,6209 ,5470,726,726 ,0,0,0}, + {6210,6211,6212 ,5471,5469,5469 ,0,0,0}, {6213,6212,5156 ,5468,5469,5469 ,0,0,0}, + {6214,6215,5262 ,5469,5472,5468 ,0,0,0}, {6216,6217,6218 ,5469,5468,5471 ,0,0,0}, + {6219,6220,6221 ,5473,5474,726 ,0,0,0}, {6222,6223,6224 ,5475,5476,5471 ,0,0,0}, + {6225,6226,6227 ,5477,5478,5469 ,0,0,0}, {6220,6219,6228 ,5474,5473,5479 ,0,0,0}, + {6229,6230,6231 ,5471,5469,726 ,0,0,0}, {6232,6233,5221 ,5468,5469,5471 ,0,0,0}, + {6234,6235,6236 ,726,5480,5481 ,0,0,0}, {6227,6237,6238 ,5469,726,5468 ,0,0,0}, + {6239,6240,6241 ,5475,5475,5482 ,0,0,0}, {6242,4896,6239 ,5468,5483,5475 ,0,0,0}, + {6241,6243,6244 ,5482,5482,5482 ,0,0,0}, {6240,6243,6241 ,5475,5482,5482 ,0,0,0}, + {6244,6245,6241 ,5482,5475,5482 ,0,0,0}, {6236,6230,6246 ,5481,5469,5475 ,0,0,0}, + {6247,5276,6248 ,726,5471,5484 ,0,0,0}, {6220,6228,6238 ,5474,5479,5468 ,0,0,0}, + {6249,6250,6251 ,5475,5485,5468 ,0,0,0}, {6252,6253,6254 ,5486,5483,5468 ,0,0,0}, + {6237,6220,6238 ,726,5474,5468 ,0,0,0}, {5221,6233,5222 ,5471,5469,726 ,0,0,0}, + {5228,6194,5230 ,5469,5468,726 ,0,0,0}, {5234,5233,6255 ,5471,5471,726 ,0,0,0}, + {5262,5232,6214 ,5468,5468,5469 ,0,0,0}, {5260,5232,5262 ,5471,5468,5468 ,0,0,0}, + {5234,6256,5259 ,5471,5471,5469 ,0,0,0}, {6257,5266,5265 ,5468,5478,726 ,0,0,0}, + {5233,6258,6255 ,5471,726,726 ,0,0,0}, {5189,6259,6260 ,5471,5468,726 ,0,0,0}, + {6261,5276,5274 ,5475,5471,726 ,0,0,0}, {6262,6263,6264 ,5469,5482,5483 ,0,0,0}, + {6265,6263,6266 ,5468,5482,5475 ,0,0,0}, {6267,6268,6269 ,726,5468,5468 ,0,0,0}, + {6270,6218,6271 ,726,5471,5469 ,0,0,0}, {6272,6273,6274 ,5475,5475,726 ,0,0,0}, + {6268,6267,6275 ,5468,726,5483 ,0,0,0}, {6276,6277,6278 ,5480,5487,5475 ,0,0,0}, + {6275,6279,6262 ,5483,5478,5469 ,0,0,0}, {6280,6281,6282 ,5475,5479,5474 ,0,0,0}, + {6282,6248,6280 ,5474,5484,5475 ,0,0,0}, {6283,6284,6282 ,5473,726,5474 ,0,0,0}, + {6283,6282,6281 ,5473,5474,5479 ,0,0,0}, {6265,6264,6263 ,5468,5483,5482 ,0,0,0}, + {6277,6272,6285 ,5487,5475,726 ,0,0,0}, {6263,6262,6279 ,5482,5469,5478 ,0,0,0}, + {6286,6287,6247 ,5486,5478,726 ,0,0,0}, {6270,6271,6269 ,726,5469,5468 ,0,0,0}, + {5186,6259,5189 ,726,5468,5471 ,0,0,0}, {6280,6248,5276 ,5475,5484,5471 ,0,0,0}, + {6288,6289,6290 ,726,726,726 ,0,0,0}, {6291,6292,5192 ,5468,5469,726 ,0,0,0}, + {6261,5274,6293 ,5475,726,5482 ,0,0,0}, {6294,5198,6295 ,726,726,5470 ,0,0,0}, + {5271,6296,6297 ,5475,5485,5475 ,0,0,0}, {6298,6299,5116 ,5471,726,5471 ,0,0,0}, + {5020,6300,5015 ,726,5470,726 ,0,0,0}, {6301,6302,6303 ,5470,5471,5471 ,0,0,0}, + {6304,6305,6306 ,726,726,5470 ,0,0,0}, {6306,6207,6304 ,5470,5470,726 ,0,0,0}, + {6288,6209,6289 ,726,726,726 ,0,0,0}, {6307,6308,6309 ,726,726,5470 ,0,0,0}, + {6201,6301,6303 ,726,5470,5471 ,0,0,0}, {6305,6310,6311 ,726,726,726 ,0,0,0}, + {5200,6312,6313 ,726,5470,726 ,0,0,0}, {6314,6315,6316 ,5470,726,726 ,0,0,0}, + {6289,6209,6208 ,726,726,726 ,0,0,0}, {6312,6317,6318 ,5470,726,5468 ,0,0,0}, + {6289,6319,6290 ,726,726,726 ,0,0,0}, {6318,6320,6321 ,5468,5468,726 ,0,0,0}, + {6317,6320,6318 ,726,5468,5468 ,0,0,0}, {6321,6322,6318 ,726,5471,5468 ,0,0,0}, + {6323,6324,6325 ,726,726,5471 ,0,0,0}, {5200,6317,6312 ,726,726,5470 ,0,0,0}, + {6313,6326,6327 ,726,726,726 ,0,0,0}, {6328,6329,6330 ,726,5488,5489 ,0,0,0}, + {5158,6331,6332 ,5471,5470,726 ,0,0,0}, {5186,6212,6259 ,726,5469,5468 ,0,0,0}, + {6333,5113,5110 ,726,726,5471 ,0,0,0}, {6334,5037,5034 ,726,726,726 ,0,0,0}, + {6335,4970,6336 ,726,5470,726 ,0,0,0}, {6337,5113,6333 ,726,726,726 ,0,0,0}, + {6338,6339,6340 ,726,726,726 ,0,0,0}, {6341,6342,6343 ,5489,726,726 ,0,0,0}, + {5107,6344,5108 ,726,5471,726 ,0,0,0}, {6345,6339,6346 ,726,726,726 ,0,0,0}, + {6347,6348,6349 ,726,726,5489 ,0,0,0}, {6350,6351,6352 ,726,726,726 ,0,0,0}, + {6353,6339,6345 ,726,726,726 ,0,0,0}, {6195,6197,6352 ,726,726,726 ,0,0,0}, + {6354,6355,6356 ,726,726,5489 ,0,0,0}, {6196,6338,6340 ,726,726,726 ,0,0,0}, + {6357,6358,6359 ,726,726,726 ,0,0,0}, {6355,6360,6357 ,726,5488,726 ,0,0,0}, + {6353,6340,6339 ,726,726,726 ,0,0,0}, {6204,6341,5124 ,726,5489,726 ,0,0,0}, + {6361,6362,6363 ,5489,726,726 ,0,0,0}, {6361,6364,6362 ,5489,5488,726 ,0,0,0}, + {6365,6366,6367 ,726,5471,726 ,0,0,0}, {6362,6364,6368 ,726,5488,726 ,0,0,0}, + {6369,6362,6368 ,726,726,726 ,0,0,0}, {6370,5082,6371 ,726,726,726 ,0,0,0}, + {5040,6372,6373 ,726,726,726 ,0,0,0}, {5198,5196,6295 ,726,726,5470 ,0,0,0}, + {6204,5120,6374 ,726,726,726 ,0,0,0}, {6366,6375,6376 ,5471,5471,726 ,0,0,0}, + {6377,4938,6378 ,726,5470,726 ,0,0,0}, {6367,6379,6365 ,726,5471,726 ,0,0,0}, + {5048,6380,6381 ,5489,726,726 ,0,0,0}, {6382,6383,6384 ,726,726,726 ,0,0,0}, + {6385,6386,6384 ,726,5471,726 ,0,0,0}, {6349,6348,6387 ,5489,726,5488 ,0,0,0}, + {6334,6388,5037 ,726,726,726 ,0,0,0}, {6342,6204,6363 ,726,726,726 ,0,0,0}, + {6389,6334,6387 ,726,726,5488 ,0,0,0}, {4964,6390,6391 ,726,5471,726 ,0,0,0}, + {6392,6393,6383 ,726,5488,726 ,0,0,0}, {6384,6394,6395 ,726,5471,726 ,0,0,0}, + {6396,6397,6398 ,726,726,5488 ,0,0,0}, {6399,6400,6396 ,726,726,726 ,0,0,0}, + {6401,6400,6402 ,726,726,726 ,0,0,0}, {6403,5048,6381 ,726,5489,726 ,0,0,0}, + {6404,6384,6405 ,726,726,726 ,0,0,0}, {6381,6380,6406 ,726,726,726 ,0,0,0}, + {6383,6407,6392 ,726,726,726 ,0,0,0}, {6408,6406,6380 ,726,726,726 ,0,0,0}, + {6383,6393,6384 ,726,5488,726 ,0,0,0}, {6408,6409,6406 ,726,5488,726 ,0,0,0}, + {6410,6407,6383 ,726,726,726 ,0,0,0}, {6406,6409,6411 ,726,5488,726 ,0,0,0}, + {6384,6412,6394 ,726,726,5471 ,0,0,0}, {5243,6413,5242 ,5469,5468,5468 ,0,0,0}, + {5243,5248,6414 ,5469,726,726 ,0,0,0}, {6415,4955,6416 ,726,5471,5471 ,0,0,0}, + {6417,4862,6418 ,5470,5468,5468 ,0,0,0}, {4972,6419,6420 ,5470,726,726 ,0,0,0}, + {6421,6422,6423 ,5468,726,5469 ,0,0,0}, {6424,6425,6426 ,5471,5468,726 ,0,0,0}, + {6427,6421,6428 ,5468,5468,726 ,0,0,0}, {6429,6430,6431 ,726,5470,5469 ,0,0,0}, + {6432,6433,6434 ,726,5469,726 ,0,0,0}, {6435,6436,6437 ,5471,5469,726 ,0,0,0}, + {6438,5259,6439 ,726,5469,5470 ,0,0,0}, {6403,6440,6441 ,726,5489,726 ,0,0,0}, + {6384,6386,6442 ,726,5471,726 ,0,0,0}, {6443,5146,5145 ,5468,726,5469 ,0,0,0}, + {6444,6445,6334 ,5470,5471,726 ,0,0,0}, {6198,6446,4961 ,726,726,5470 ,0,0,0}, + {6447,5006,5005 ,5471,726,726 ,0,0,0}, {6448,5248,5246 ,726,726,5468 ,0,0,0}, + {6449,6450,6451 ,726,5470,5471 ,0,0,0}, {6452,6453,6454 ,5471,726,5470 ,0,0,0}, + {6455,6456,6457 ,726,5470,726 ,0,0,0}, {6419,6458,6420 ,726,726,726 ,0,0,0}, + {6458,6419,6459 ,726,726,726 ,0,0,0}, {6420,6450,4972 ,726,5470,5470 ,0,0,0}, + {6458,6459,6460 ,726,726,726 ,0,0,0}, {6432,6426,6425 ,726,726,5468 ,0,0,0}, + {6458,6460,6461 ,726,726,726 ,0,0,0}, {6462,6463,6464 ,5471,5471,5468 ,0,0,0}, + {6430,6437,6431 ,5470,726,5469 ,0,0,0}, {6465,6429,6466 ,726,726,726 ,0,0,0}, + {6467,6468,6436 ,5468,5469,5469 ,0,0,0}, {6436,6435,6467 ,5469,5471,5468 ,0,0,0}, + {6469,6470,6467 ,5471,726,5468 ,0,0,0}, {6467,6470,6468 ,5468,726,5469 ,0,0,0}, + {5266,6471,5268 ,5478,5487,5468 ,0,0,0}, {5200,5198,6294 ,726,726,726 ,0,0,0}, + {6293,5274,5272 ,5482,726,5468 ,0,0,0}, {6292,5195,5192 ,5469,726,726 ,0,0,0}, + {6213,6210,6212 ,5468,5471,5469 ,0,0,0}, {6472,6211,6210 ,5468,5469,5471 ,0,0,0}, + {6217,6216,6473 ,5468,5469,5469 ,0,0,0}, {6211,6472,6474 ,5469,5468,5470 ,0,0,0}, + {6216,6218,6270 ,5469,5471,726 ,0,0,0}, {6473,6474,6475 ,5469,5470,5469 ,0,0,0}, + {6269,6271,6267 ,5468,5469,726 ,0,0,0}, {6275,6262,6268 ,5483,5469,5468 ,0,0,0}, + {6273,6279,6274 ,5475,5478,726 ,0,0,0}, {6279,6275,6274 ,5478,5483,726 ,0,0,0}, + {6286,6276,6287 ,5486,5480,5478 ,0,0,0}, {6277,6273,6272 ,5487,5475,5475 ,0,0,0}, + {6276,6278,6287 ,5480,5475,5478 ,0,0,0}, {6278,6277,6285 ,5475,5487,726 ,0,0,0}, + {6248,6286,6247 ,5484,5486,726 ,0,0,0}, {6261,6280,5276 ,5475,5475,5471 ,0,0,0}, + {6293,5272,6297 ,5482,5468,5475 ,0,0,0}, {6297,5272,5271 ,5475,5468,5475 ,0,0,0}, + {5268,6471,6296 ,5468,5487,5485 ,0,0,0}, {6296,5271,5268 ,5485,5475,5468 ,0,0,0}, + {6257,6471,5266 ,5468,5487,5478 ,0,0,0}, {6215,6257,5265 ,5472,5468,726 ,0,0,0}, + {6439,5259,6256 ,5470,5469,5471 ,0,0,0}, {5262,6215,5265 ,5468,5472,726 ,0,0,0}, + {6476,6477,5242 ,5471,5470,5468 ,0,0,0}, {5239,6477,6478 ,726,5470,726 ,0,0,0}, + {6224,6479,6222 ,5471,5468,5475 ,0,0,0}, {6233,6480,5222 ,5469,5469,726 ,0,0,0}, + {6481,6482,6242 ,5472,5482,5468 ,0,0,0}, {5205,4874,5201 ,5468,5468,5468 ,0,0,0}, + {4882,4880,6421 ,5471,726,5468 ,0,0,0}, {5137,4784,5135 ,5471,726,5469 ,0,0,0}, + {5148,6483,5151 ,5471,726,726 ,0,0,0}, {6333,5110,6199 ,726,5471,5471 ,0,0,0}, + {4804,6484,6485 ,726,726,5470 ,0,0,0}, {6486,6487,5046 ,726,726,726 ,0,0,0}, + {6488,5166,6489 ,726,726,5471 ,0,0,0}, {4781,6490,4778 ,5471,5471,5471 ,0,0,0}, + {4793,6491,6492 ,726,5469,5469 ,0,0,0}, {5132,5245,5251 ,5471,5469,5469 ,0,0,0}, + {5239,5242,6477 ,726,5468,5470 ,0,0,0}, {5255,5133,5251 ,5468,726,5469 ,0,0,0}, + {5245,4789,5246 ,5469,5471,5468 ,0,0,0}, {6448,6414,5248 ,726,726,726 ,0,0,0}, + {6414,6413,5243 ,726,5468,5469 ,0,0,0}, {6413,6476,5242 ,5468,5471,5468 ,0,0,0}, + {5236,5239,6478 ,726,726,726 ,0,0,0}, {5232,5260,6438 ,5468,5471,726 ,0,0,0}, + {5236,6258,5233 ,726,726,5471 ,0,0,0}, {6258,5236,6478 ,726,726,726 ,0,0,0}, + {6255,6256,5234 ,726,5471,5471 ,0,0,0}, {5259,6438,5260 ,5469,726,5471 ,0,0,0}, + {5230,6493,5232 ,726,5468,5468 ,0,0,0}, {6223,6214,6494 ,5476,5469,5468 ,0,0,0}, + {6493,6214,5232 ,5468,5469,5468 ,0,0,0}, {5222,6480,5224 ,726,5469,5470 ,0,0,0}, + {5227,5224,6495 ,5469,5470,726 ,0,0,0}, {6480,6495,5224 ,5469,726,5470 ,0,0,0}, + {6226,6225,6250 ,5478,5477,5485 ,0,0,0}, {5202,4874,6232 ,726,5468,5468 ,0,0,0}, + {5202,6232,5221 ,726,5468,5471 ,0,0,0}, {6496,6497,4894 ,5470,5470,5468 ,0,0,0}, + {4896,6240,6239 ,5483,5475,5475 ,0,0,0}, {6498,4880,4879 ,5468,726,5468 ,0,0,0}, + {6499,4854,6500 ,5469,5468,5471 ,0,0,0}, {4968,6336,4970 ,726,726,5470 ,0,0,0}, + {6501,6502,4930 ,5471,5471,5471 ,0,0,0}, {6503,5018,6504 ,726,726,5471 ,0,0,0}, + {6505,6506,6507 ,5471,5470,5471 ,0,0,0}, {5014,5015,6508 ,726,726,726 ,0,0,0}, + {4958,6375,6198 ,726,5471,726 ,0,0,0}, {6388,6334,6509 ,726,726,726 ,0,0,0}, + {5254,6510,5126 ,726,5468,5469 ,0,0,0}, {5151,6511,5152 ,726,726,5468 ,0,0,0}, + {5120,6204,5122 ,726,726,726 ,0,0,0}, {6299,5119,5116 ,726,5471,5471 ,0,0,0}, + {5080,6200,6199 ,726,726,5471 ,0,0,0}, {6201,6200,6301 ,726,726,5470 ,0,0,0}, + {6310,6323,6311 ,726,726,726 ,0,0,0}, {6325,6512,6302 ,5471,726,5471 ,0,0,0}, + {6303,6302,6512 ,5471,5471,726 ,0,0,0}, {6324,6323,6310 ,726,726,726 ,0,0,0}, + {6324,6512,6325 ,726,726,5471 ,0,0,0}, {6311,6306,6305 ,726,5470,726 ,0,0,0}, + {6207,6209,6304 ,5470,726,726 ,0,0,0}, {6308,6208,6309 ,726,726,5470 ,0,0,0}, + {6208,6207,6309 ,726,5470,5470 ,0,0,0}, {6315,6327,6326 ,726,726,726 ,0,0,0}, + {6307,6316,6513 ,726,726,5471 ,0,0,0}, {6513,6308,6307 ,5471,726,726 ,0,0,0}, + {6315,6314,6327 ,726,5470,726 ,0,0,0}, {6316,6315,6513 ,726,726,5471 ,0,0,0}, + {6312,6326,6313 ,5470,726,726 ,0,0,0}, {6294,6317,5200 ,726,726,726 ,0,0,0}, + {5186,5184,6212 ,726,726,5469 ,0,0,0}, {6295,5196,6514 ,5470,726,5470 ,0,0,0}, + {5195,6292,6514 ,726,5469,5470 ,0,0,0}, {6514,5196,5195 ,5470,726,726 ,0,0,0}, + {6291,5190,6260 ,5468,726,726 ,0,0,0}, {5190,6291,5192 ,726,5468,726 ,0,0,0}, + {5189,6260,5190 ,5471,726,726 ,0,0,0}, {6332,5183,5158 ,726,5471,5471 ,0,0,0}, + {5158,5157,6331 ,5471,5471,5470 ,0,0,0}, {6206,5183,6332 ,5469,5471,726 ,0,0,0}, + {6515,6516,5160 ,5470,5470,726 ,0,0,0}, {6488,5163,5166 ,726,5470,726 ,0,0,0}, + {6516,5157,5160 ,5470,5471,726 ,0,0,0}, {5167,5172,6517 ,726,726,726 ,0,0,0}, + {5167,6518,5166 ,726,5470,726 ,0,0,0}, {6519,5172,5170 ,726,726,5470 ,0,0,0}, + {5059,5061,4798 ,726,726,726 ,0,0,0}, {5175,5056,5169 ,726,726,5471 ,0,0,0}, + {5072,6520,5075 ,726,726,5470 ,0,0,0}, {5146,6521,5148 ,726,5471,5471 ,0,0,0}, + {6522,4904,4907 ,5471,5470,726 ,0,0,0}, {6523,4777,6524 ,726,726,5470 ,0,0,0}, + {5094,4808,6525 ,5471,5470,5470 ,0,0,0}, {6526,6527,5090 ,726,5471,726 ,0,0,0}, + {4784,5137,4783 ,726,5471,726 ,0,0,0}, {5255,5254,5129 ,5468,726,5471 ,0,0,0}, + {5179,5057,5175 ,5470,5471,726 ,0,0,0}, {5070,5069,6528 ,726,726,726 ,0,0,0}, + {4797,4771,5169 ,5470,5471,5471 ,0,0,0}, {6519,6517,5172 ,726,726,726 ,0,0,0}, + {6517,6518,5167 ,726,5470,726 ,0,0,0}, {6518,6489,5166 ,5470,5471,726 ,0,0,0}, + {5163,6515,5160 ,5470,5470,726 ,0,0,0}, {6515,5163,6488 ,5470,5470,726 ,0,0,0}, + {6213,5156,5154 ,5468,5469,726 ,0,0,0}, {6516,6331,5157 ,5470,5470,5471 ,0,0,0}, + {5184,5156,6212 ,726,5469,5469 ,0,0,0}, {6205,5184,5183 ,5468,726,5471 ,0,0,0}, + {6205,5156,5184 ,5468,5469,726 ,0,0,0}, {5154,5152,6511 ,726,5468,726 ,0,0,0}, + {5154,6511,6213 ,726,726,5468 ,0,0,0}, {5151,6483,6511 ,726,726,726 ,0,0,0}, + {5148,6521,6483 ,5471,5471,726 ,0,0,0}, {5145,6510,6443 ,5469,5468,5468 ,0,0,0}, + {5146,6443,6521 ,726,5468,5471 ,0,0,0}, {5126,5125,5254 ,5469,5468,726 ,0,0,0}, + {5145,5126,6510 ,5469,5469,5468 ,0,0,0}, {5129,5133,5255 ,5471,726,5468 ,0,0,0}, + {5125,5129,5254 ,5468,5471,726 ,0,0,0}, {5133,5132,5251 ,726,5471,5469 ,0,0,0}, + {4784,4787,5135 ,726,726,5469 ,0,0,0}, {4783,5137,5139 ,726,5471,5470 ,0,0,0}, + {6490,6524,4778 ,5471,5470,5471 ,0,0,0}, {4781,4783,5139 ,5471,726,5470 ,0,0,0}, + {6523,6519,4775 ,726,726,5470 ,0,0,0}, {5178,6529,5050 ,5470,5470,726 ,0,0,0}, + {5075,6530,5076 ,5470,5470,5470 ,0,0,0}, {6487,5048,5046 ,726,5489,726 ,0,0,0}, + {6373,5043,5040 ,726,726,726 ,0,0,0}, {6531,6387,6334 ,5489,5488,726 ,0,0,0}, + {6387,6531,6349 ,5488,5489,5489 ,0,0,0}, {6350,6328,6351 ,726,726,726 ,0,0,0}, + {6330,6532,6347 ,5489,726,726 ,0,0,0}, {6348,6347,6532 ,726,726,726 ,0,0,0}, + {6329,6328,6350 ,5488,726,726 ,0,0,0}, {6329,6532,6330 ,5488,726,5489 ,0,0,0}, + {6351,6195,6352 ,726,726,726 ,0,0,0}, {6196,6340,6197 ,726,726,726 ,0,0,0}, + {6356,6338,6354 ,5489,726,726 ,0,0,0}, {6338,6196,6354 ,726,726,726 ,0,0,0}, + {6342,6359,6343 ,726,726,726 ,0,0,0}, {6357,6356,6355 ,726,5489,726 ,0,0,0}, + {6359,6358,6343 ,726,726,726 ,0,0,0}, {6358,6357,6360 ,726,726,5488 ,0,0,0}, + {6342,6341,6204 ,726,5489,726 ,0,0,0}, {6363,6204,6361 ,726,726,5489 ,0,0,0}, + {5110,5108,6199 ,5471,726,5471 ,0,0,0}, {6204,6374,6202 ,726,726,726 ,0,0,0}, + {5119,6299,6374 ,5471,726,726 ,0,0,0}, {6374,5120,5119 ,726,726,5471 ,0,0,0}, + {6298,5114,6337 ,5471,726,726 ,0,0,0}, {5114,6298,5116 ,726,5471,5471 ,0,0,0}, + {5113,6337,5114 ,726,726,726 ,0,0,0}, {6533,5082,6370 ,5471,726,726 ,0,0,0}, + {5082,5081,6371 ,726,726,726 ,0,0,0}, {5107,5082,6533 ,726,726,5471 ,0,0,0}, + {6534,6535,5084 ,726,726,726 ,0,0,0}, {6527,5087,5090 ,5471,726,726 ,0,0,0}, + {6535,5081,5084 ,726,726,726 ,0,0,0}, {5091,5096,6536 ,726,726,726 ,0,0,0}, + {5091,6537,5090 ,726,5471,726 ,0,0,0}, {6525,5096,5094 ,5470,726,5471 ,0,0,0}, + {4813,4980,4983 ,5471,5471,726 ,0,0,0}, {5099,4980,5093 ,726,5471,726 ,0,0,0}, + {6538,4808,4807 ,5471,5470,726 ,0,0,0}, {5072,5070,6539 ,726,726,726 ,0,0,0}, + {4813,4810,5093 ,5471,726,726 ,0,0,0}, {4994,6540,4996 ,726,5470,726 ,0,0,0}, + {4901,5027,5026 ,5470,726,726 ,0,0,0}, {5014,6541,5011 ,726,726,5471 ,0,0,0}, + {5061,4801,4798 ,726,726,726 ,0,0,0}, {5179,5178,5053 ,5470,5470,726 ,0,0,0}, + {5103,4981,5099 ,5471,726,726 ,0,0,0}, {6503,5020,5018 ,726,726,726 ,0,0,0}, + {5093,4810,5094 ,726,726,5471 ,0,0,0}, {6525,6536,5096 ,5470,726,726 ,0,0,0}, + {6536,6537,5091 ,726,5471,726 ,0,0,0}, {6537,6526,5090 ,5471,726,726 ,0,0,0}, + {5087,6534,5084 ,726,726,726 ,0,0,0}, {6534,5087,6527 ,726,726,5471 ,0,0,0}, + {6542,5080,5078 ,5470,726,726 ,0,0,0}, {6535,6371,5081 ,726,726,726 ,0,0,0}, + {5108,5080,6199 ,726,726,5471 ,0,0,0}, {5080,5108,6344 ,726,726,5471 ,0,0,0}, + {6533,6344,5107 ,5471,5471,726 ,0,0,0}, {5080,6542,6200 ,726,5470,726 ,0,0,0}, + {5078,5076,6530 ,726,5470,5470 ,0,0,0}, {5078,6530,6542 ,726,5470,5470 ,0,0,0}, + {5075,6520,6530 ,5470,726,5470 ,0,0,0}, {5072,6539,6520 ,726,726,726 ,0,0,0}, + {5069,6529,6528 ,726,5470,726 ,0,0,0}, {5070,6528,6539 ,726,726,726 ,0,0,0}, + {5050,5049,5178 ,726,5470,5470 ,0,0,0}, {5069,5050,6529 ,726,726,5470 ,0,0,0}, + {5053,5057,5179 ,726,5471,5470 ,0,0,0}, {5049,5053,5178 ,5470,726,5470 ,0,0,0}, + {5057,5056,5175 ,5471,726,726 ,0,0,0}, {4798,4797,5059 ,726,5470,726 ,0,0,0}, + {4801,5063,4802 ,726,726,5471 ,0,0,0}, {4804,4802,6484 ,726,5471,726 ,0,0,0}, + {5061,5063,4801 ,726,726,726 ,0,0,0}, {6525,4808,6538 ,5470,5470,5471 ,0,0,0}, + {5044,6486,5046 ,5488,726,726 ,0,0,0}, {5246,4791,6448 ,5468,5470,726 ,0,0,0}, + {4970,6335,4972 ,5470,726,5470 ,0,0,0}, {6391,4967,4964 ,726,726,726 ,0,0,0}, + {6375,6543,6376 ,5471,726,726 ,0,0,0}, {6366,6376,6367 ,5471,726,726 ,0,0,0}, + {6412,6544,6379 ,726,5471,5471 ,0,0,0}, {6365,6379,6544 ,726,5471,5471 ,0,0,0}, + {6384,6442,6412 ,726,726,726 ,0,0,0}, {6442,6544,6412 ,726,5471,726 ,0,0,0}, + {6395,6405,6384 ,726,726,726 ,0,0,0}, {6545,6385,6384 ,726,726,726 ,0,0,0}, + {6382,6384,6397 ,726,726,726 ,0,0,0}, {6398,6397,6384 ,5488,726,726 ,0,0,0}, + {6440,6401,6441 ,5489,726,726 ,0,0,0}, {6400,6397,6396 ,726,726,726 ,0,0,0}, + {6401,6402,6441 ,726,726,726 ,0,0,0}, {6402,6400,6399 ,726,726,726 ,0,0,0}, + {6381,6440,6403 ,726,5489,726 ,0,0,0}, {6487,6380,5048 ,726,726,5489 ,0,0,0}, + {5032,5031,6334 ,726,5471,726 ,0,0,0}, {5043,6546,5044 ,726,726,5488 ,0,0,0}, + {6486,5044,6546 ,726,5488,726 ,0,0,0}, {6372,5038,6388 ,726,726,726 ,0,0,0}, + {6373,6546,5043 ,726,726,726 ,0,0,0}, {5038,6372,5040 ,726,726,726 ,0,0,0}, + {5037,6388,5038 ,726,726,726 ,0,0,0}, {6444,6334,6547 ,5470,726,5471 ,0,0,0}, + {6547,5006,6447 ,5471,726,5471 ,0,0,0}, {6547,6334,5006 ,5471,726,726 ,0,0,0}, + {5008,6548,5005 ,5471,726,726 ,0,0,0}, {5014,6549,6541 ,726,726,726 ,0,0,0}, + {5008,6550,6548 ,5471,726,726 ,0,0,0}, {6551,4999,4996 ,5471,726,726 ,0,0,0}, + {4999,6552,5000 ,726,726,726 ,0,0,0}, {6553,4994,4993 ,726,726,5471 ,0,0,0}, + {5102,6554,4974 ,5471,5471,5471 ,0,0,0}, {4977,5103,5102 ,726,5471,5471 ,0,0,0}, + {4813,5093,4980 ,5471,726,5471 ,0,0,0}, {6555,6556,6557 ,5470,726,726 ,0,0,0}, + {6558,4820,4990 ,726,5470,5471 ,0,0,0}, {5026,6559,4898 ,726,726,726 ,0,0,0}, + {6560,4924,4923 ,5471,5470,5471 ,0,0,0}, {4923,4920,6561 ,5471,726,726 ,0,0,0}, + {5023,4904,5017 ,726,5470,726 ,0,0,0}, {4816,4983,4985 ,5471,726,726 ,0,0,0}, + {5027,4905,5023 ,726,5471,726 ,0,0,0}, {4917,6562,4918 ,726,726,5471 ,0,0,0}, + {5017,6563,5018 ,726,726,726 ,0,0,0}, {6503,6300,5020 ,726,5470,726 ,0,0,0}, + {6300,6508,5015 ,5470,726,726 ,0,0,0}, {6508,6549,5014 ,726,726,726 ,0,0,0}, + {5011,6550,5008 ,5471,726,5471 ,0,0,0}, {6550,5011,6541 ,726,5471,726 ,0,0,0}, + {6552,6564,5002 ,726,726,726 ,0,0,0}, {5002,6564,6334 ,726,726,726 ,0,0,0}, + {6548,6447,5005 ,726,5471,726 ,0,0,0}, {5034,5032,6334 ,726,726,726 ,0,0,0}, + {6334,5031,5006 ,726,5471,726 ,0,0,0}, {5004,6334,6445 ,5471,726,5471 ,0,0,0}, + {6564,6531,6334 ,726,5489,726 ,0,0,0}, {5002,5000,6552 ,726,726,726 ,0,0,0}, + {4999,6551,6552 ,726,5471,726 ,0,0,0}, {4996,6540,6551 ,726,5470,5471 ,0,0,0}, + {4993,6554,6553 ,5471,5471,726 ,0,0,0}, {4994,6553,6540 ,726,726,5470 ,0,0,0}, + {4974,4973,5102 ,5471,726,5471 ,0,0,0}, {4993,4974,6554 ,5471,5471,5471 ,0,0,0}, + {4977,4981,5103 ,726,726,5471 ,0,0,0}, {4973,4977,5102 ,726,726,5471 ,0,0,0}, + {4981,4980,5099 ,726,5471,726 ,0,0,0}, {4816,4813,4983 ,5471,5471,726 ,0,0,0}, + {4816,4985,4819 ,5471,726,726 ,0,0,0}, {4987,4820,4819 ,726,5470,726 ,0,0,0}, + {4987,4819,4985 ,726,726,726 ,0,0,0}, {4987,4990,4820 ,726,5471,5470 ,0,0,0}, + {6565,4863,4868 ,5468,5469,5470 ,0,0,0}, {6421,6433,6428 ,5468,5469,726 ,0,0,0}, + {5208,4871,5209 ,5468,5471,5469 ,0,0,0}, {4891,4888,6421 ,5469,5471,5468 ,0,0,0}, + {4852,6434,6433 ,5469,726,5469 ,0,0,0}, {6432,6434,6426 ,726,726,726 ,0,0,0}, + {6466,6463,6465 ,726,5471,726 ,0,0,0}, {6462,6566,6424 ,5471,5468,5471 ,0,0,0}, + {6425,6424,6566 ,5468,5471,5468 ,0,0,0}, {6464,6463,6466 ,5468,5471,726 ,0,0,0}, + {6464,6566,6462 ,5468,5468,5471 ,0,0,0}, {6465,6430,6429 ,726,5470,726 ,0,0,0}, + {6437,6436,6431 ,726,5469,5469 ,0,0,0}, {6456,6435,6457 ,5470,5471,726 ,0,0,0}, + {6435,6437,6457 ,5471,726,726 ,0,0,0}, {6453,6449,6451 ,726,726,5471 ,0,0,0}, + {6455,6454,6567 ,726,5470,726 ,0,0,0}, {6567,6456,6455 ,726,5470,726 ,0,0,0}, + {6453,6452,6449 ,726,5471,726 ,0,0,0}, {6454,6453,6567 ,5470,726,726 ,0,0,0}, + {6420,6451,6450 ,726,5471,5470 ,0,0,0}, {6335,6419,4972 ,726,726,5470 ,0,0,0}, + {4958,4956,6375 ,726,5470,5471 ,0,0,0}, {4967,6568,4968 ,726,726,726 ,0,0,0}, + {6336,4968,6568 ,726,726,726 ,0,0,0}, {6390,4962,6446 ,5471,5470,726 ,0,0,0}, + {6391,6568,4967 ,726,726,726 ,0,0,0}, {4962,6390,4964 ,5470,5471,726 ,0,0,0}, + {4961,6446,4962 ,5470,726,5470 ,0,0,0}, {6502,4955,4930 ,5471,5471,5471 ,0,0,0}, + {4930,4929,6501 ,5471,726,5471 ,0,0,0}, {6416,4955,6502 ,5471,5471,5471 ,0,0,0}, + {6569,6570,4932 ,5471,726,726 ,0,0,0}, {6377,4935,4938 ,726,5470,5470 ,0,0,0}, + {6570,4929,4932 ,726,726,726 ,0,0,0}, {4939,4944,6571 ,5470,726,726 ,0,0,0}, + {4939,6572,4938 ,5470,726,5470 ,0,0,0}, {6573,4944,4942 ,726,726,726 ,0,0,0}, + {4831,4833,6574 ,726,5471,5471 ,0,0,0}, {4918,6575,4920 ,5471,726,726 ,0,0,0}, + {6576,6577,6578 ,5471,726,726 ,0,0,0}, {4866,6576,6579 ,5471,5471,5471 ,0,0,0}, + {6448,4791,6580 ,726,5470,5469 ,0,0,0}, {5208,5211,6581 ,5468,5468,5470 ,0,0,0}, + {4847,6582,4848 ,726,726,5471 ,0,0,0}, {4866,6579,4868 ,5471,5471,5470 ,0,0,0}, + {4947,4828,4941 ,726,5470,5470 ,0,0,0}, {4909,6583,6584 ,5470,5471,726 ,0,0,0}, + {4951,4829,4947 ,726,5471,726 ,0,0,0}, {6585,6574,4833 ,5471,5471,5471 ,0,0,0}, + {6586,6587,4941 ,726,5471,5470 ,0,0,0}, {6573,6571,4944 ,726,726,726 ,0,0,0}, + {6571,6572,4939 ,726,726,5470 ,0,0,0}, {6572,6378,4938 ,726,726,5470 ,0,0,0}, + {4935,6569,4932 ,5470,5471,726 ,0,0,0}, {6569,4935,6377 ,5471,5470,726 ,0,0,0}, + {4926,6560,6543 ,5471,5471,726 ,0,0,0}, {6543,4928,4926 ,726,726,5471 ,0,0,0}, + {6570,6501,4929 ,726,5471,726 ,0,0,0}, {4956,4928,6375 ,5470,726,5471 ,0,0,0}, + {6415,4956,4955 ,726,5470,5471 ,0,0,0}, {6415,4928,4956 ,726,726,5470 ,0,0,0}, + {6375,4928,6543 ,5471,726,726 ,0,0,0}, {4926,4924,6560 ,5471,5470,5471 ,0,0,0}, + {4923,6561,6560 ,5471,726,5471 ,0,0,0}, {4920,6575,6561 ,726,726,726 ,0,0,0}, + {4917,6559,6562 ,726,726,726 ,0,0,0}, {4918,6562,6575 ,5471,726,726 ,0,0,0}, + {4898,4897,5026 ,726,5471,726 ,0,0,0}, {4917,4898,6559 ,726,726,726 ,0,0,0}, + {4901,4905,5027 ,5470,5471,726 ,0,0,0}, {4897,4901,5026 ,5471,5470,726 ,0,0,0}, + {4905,4904,5023 ,5471,5470,726 ,0,0,0}, {6584,6522,4907 ,726,5471,726 ,0,0,0}, + {5017,4904,6522 ,726,5470,5471 ,0,0,0}, {4914,6588,6589 ,726,726,726 ,0,0,0}, + {6583,4911,6589 ,5471,726,726 ,0,0,0}, {6590,6591,6592 ,5470,5470,5471 ,0,0,0}, + {4894,6497,4896 ,5468,5470,5483 ,0,0,0}, {5202,5201,4874 ,726,5468,5468 ,0,0,0}, + {4894,4892,6496 ,5468,5469,5470 ,0,0,0}, {5230,6194,6493 ,726,5468,5468 ,0,0,0}, + {5227,6495,6194 ,5469,726,5468 ,0,0,0}, {6493,6494,6214 ,5468,5468,5469 ,0,0,0}, + {6223,6494,6224 ,5476,5468,5471 ,0,0,0}, {6251,6254,6249 ,5468,5468,5475 ,0,0,0}, + {6253,6593,6479 ,5483,726,5468 ,0,0,0}, {6222,6479,6593 ,5475,5468,726 ,0,0,0}, + {6252,6254,6251 ,5486,5468,5468 ,0,0,0}, {6252,6593,6253 ,5486,726,5483 ,0,0,0}, + {6249,6226,6250 ,5475,5478,5485 ,0,0,0}, {6227,6238,6225 ,5469,5468,5477 ,0,0,0}, + {6231,6237,6229 ,726,726,5471 ,0,0,0}, {6237,6227,6229 ,726,5469,5471 ,0,0,0}, + {6481,6235,6482 ,5472,5480,5482 ,0,0,0}, {6236,6231,6230 ,5481,726,5469 ,0,0,0}, + {6235,6234,6482 ,5480,726,5482 ,0,0,0}, {6234,6236,6246 ,726,5481,5475 ,0,0,0}, + {6239,6481,6242 ,5475,5472,5468 ,0,0,0}, {6497,6240,4896 ,5470,5475,5483 ,0,0,0}, + {6421,4880,6498 ,5468,726,5468 ,0,0,0}, {4891,6423,4892 ,5469,5469,5469 ,0,0,0}, + {6496,4892,6423 ,5470,5469,5469 ,0,0,0}, {6594,6422,6421 ,5468,726,5468 ,0,0,0}, + {6423,4891,6421 ,5469,5469,5468 ,0,0,0}, {6421,4888,4886 ,5468,5471,5470 ,0,0,0}, + {6421,4885,4882 ,5468,5469,5471 ,0,0,0}, {6595,4854,6499 ,5469,5468,5469 ,0,0,0}, + {4854,4853,6500 ,5468,5471,5471 ,0,0,0}, {4879,4854,6595 ,5468,5468,5469 ,0,0,0}, + {6596,6597,4856 ,5470,5471,5468 ,0,0,0}, {6417,4859,4862 ,5470,726,5468 ,0,0,0}, + {6597,4853,4856 ,5471,5471,5468 ,0,0,0}, {5211,5213,6598 ,5468,5468,5468 ,0,0,0}, + {4825,4951,4950 ,5471,726,726 ,0,0,0}, {4863,6599,4862 ,5469,5469,5468 ,0,0,0}, + {6600,4842,4841 ,726,5471,726 ,0,0,0}, {6601,4847,4844 ,726,726,5470 ,0,0,0}, + {6602,4822,4950 ,726,5470,726 ,0,0,0}, {6603,4844,4842 ,726,5470,5471 ,0,0,0}, + {5208,4865,4871 ,5468,5469,5471 ,0,0,0}, {5211,6598,6581 ,5468,5468,5470 ,0,0,0}, + {4871,4875,5209 ,5471,726,5469 ,0,0,0}, {4874,5205,4875 ,5468,5468,726 ,0,0,0}, + {5209,4875,5205 ,5469,726,5468 ,0,0,0}, {4790,6492,6580 ,5469,5469,5469 ,0,0,0}, + {5215,4795,6604 ,5471,5470,726 ,0,0,0}, {4795,6491,4793 ,5470,5469,726 ,0,0,0}, + {4865,6605,4866 ,5469,5471,5471 ,0,0,0}, {6579,6565,4868 ,5471,5468,5470 ,0,0,0}, + {6565,6599,4863 ,5468,5469,5469 ,0,0,0}, {6599,6418,4862 ,5469,5468,5468 ,0,0,0}, + {4859,6596,4856 ,726,5470,5468 ,0,0,0}, {6596,4859,6417 ,5470,726,5470 ,0,0,0}, + {4850,6582,6606 ,726,726,5471 ,0,0,0}, {6606,4852,4850 ,5471,5469,726 ,0,0,0}, + {6597,6500,4853 ,5471,5471,5471 ,0,0,0}, {4852,6433,6421 ,5469,5469,5468 ,0,0,0}, + {6421,6498,4852 ,5468,5468,5469 ,0,0,0}, {6595,6498,4879 ,5469,5468,5468 ,0,0,0}, + {4852,6606,6434 ,5469,5471,726 ,0,0,0}, {4850,4848,6582 ,726,5471,726 ,0,0,0}, + {4847,6601,6582 ,726,726,726 ,0,0,0}, {4844,6603,6601 ,5470,726,726 ,0,0,0}, + {4841,6602,6600 ,726,726,726 ,0,0,0}, {4842,6600,6603 ,5471,726,726 ,0,0,0}, + {4822,4821,4950 ,5470,726,726 ,0,0,0}, {4841,4822,6602 ,726,5470,726 ,0,0,0}, + {4825,4829,4951 ,5471,5471,726 ,0,0,0}, {4821,4825,4950 ,726,5471,726 ,0,0,0}, + {4829,4828,4947 ,5471,5470,726 ,0,0,0}, {6574,6586,4831 ,5471,726,726 ,0,0,0}, + {6585,4835,6607 ,5471,726,726 ,0,0,0}, {6505,6607,6506 ,5471,726,5470 ,0,0,0}, + {4833,4835,6585 ,5471,726,5471 ,0,0,0}, {6579,6576,6578 ,5471,5471,726 ,0,0,0}, + {6573,4942,6608 ,726,726,5471 ,0,0,0}, {6519,5170,4775 ,726,5470,5470 ,0,0,0}, + {6573,6608,6590 ,726,5471,5470 ,0,0,0}, {4810,4808,5094 ,726,5470,5471 ,0,0,0}, + {4804,6485,4807 ,726,5470,726 ,0,0,0}, {6538,4807,6485 ,5471,726,5470 ,0,0,0}, + {5170,5169,4771 ,5470,5471,5471 ,0,0,0}, {5066,4802,5063 ,726,5471,726 ,0,0,0}, + {5066,6484,4802 ,726,726,5471 ,0,0,0}, {4797,5169,5056 ,5470,5471,726 ,0,0,0}, + {5056,5059,4797 ,726,726,5470 ,0,0,0}, {5170,4771,4775 ,5470,5471,5470 ,0,0,0}, + {6523,4775,4777 ,726,5470,726 ,0,0,0}, {4789,5245,4787 ,5471,5469,726 ,0,0,0}, + {6524,4777,4778 ,5470,726,5471 ,0,0,0}, {5142,4781,5139 ,726,5471,5470 ,0,0,0}, + {5142,6490,4781 ,726,5471,5471 ,0,0,0}, {5245,5132,4787 ,5469,5471,726 ,0,0,0}, + {5132,5135,4787 ,5471,5469,726 ,0,0,0}, {4789,4791,5246 ,5471,5470,5468 ,0,0,0}, + {6580,4791,4790 ,5469,5470,5469 ,0,0,0}, {6605,4865,6581 ,5471,5469,5470 ,0,0,0}, + {6492,4790,4793 ,5469,5469,726 ,0,0,0}, {5218,4795,5215 ,5469,5470,5471 ,0,0,0}, + {5218,6491,4795 ,5469,5469,5470 ,0,0,0}, {6581,4865,5208 ,5470,5469,5468 ,0,0,0}, + {6604,6598,5213 ,726,5468,5468 ,0,0,0}, {6604,5213,5215 ,726,5468,5471 ,0,0,0}, + {6605,6576,4866 ,5471,5471,5471 ,0,0,0}, {6505,6507,6577 ,5471,5471,726 ,0,0,0}, + {6578,6577,6507 ,726,726,5471 ,0,0,0}, {4942,4941,6587 ,726,5470,5471 ,0,0,0}, + {4838,6607,4835 ,726,726,726 ,0,0,0}, {4838,6506,6607 ,726,5470,726 ,0,0,0}, + {6586,4941,4828 ,726,5470,5470 ,0,0,0}, {4828,4831,6586 ,5470,726,726 ,0,0,0}, + {4942,6587,6608 ,726,5471,5471 ,0,0,0}, {6592,6591,6609 ,5471,5470,726 ,0,0,0}, + {6590,6608,6591 ,5470,5471,5470 ,0,0,0}, {6609,6589,6588 ,726,726,726 ,0,0,0}, + {6588,6592,6609 ,726,5471,726 ,0,0,0}, {6589,4911,4914 ,726,726,726 ,0,0,0}, + {6583,4909,4911 ,5471,5470,726 ,0,0,0}, {6584,4907,4909 ,726,726,5470 ,0,0,0}, + {5017,6522,6563 ,726,5471,726 ,0,0,0}, {6504,6610,6503 ,5471,5471,726 ,0,0,0}, + {5018,6563,6504 ,726,726,5471 ,0,0,0}, {6556,6610,6557 ,726,5471,726 ,0,0,0}, + {6504,6557,6610 ,5471,726,5471 ,0,0,0}, {6556,6555,6558 ,726,5470,726 ,0,0,0}, + {4820,6558,6555 ,5470,726,5470 ,0,0,0}, {6594,6421,6427 ,5468,5468,5468 ,0,0,0}, + {4886,4885,6421 ,5470,5469,5468 ,0,0,0}, {6384,6404,6398 ,726,726,5488 ,0,0,0}, + {6393,6545,6384 ,5488,726,726 ,0,0,0}, {6334,5004,5002 ,726,5471,726 ,0,0,0}, + {6509,6334,6389 ,726,726,726 ,0,0,0}, {6475,6474,6472 ,5469,5470,5468 ,0,0,0}, + {6475,6217,6473 ,5469,5468,5469 ,0,0,0}, {6361,6204,6203 ,5489,726,726 ,0,0,0}, + {5124,5122,6204 ,726,726,726 ,0,0,0}, {6611,6612,6613 ,5490,5491,5492 ,0,0,0}, + {6614,6615,6616 ,5493,5494,5495 ,0,0,0}, {6617,6615,6618 ,5496,5494,5497 ,0,0,0}, + {6619,6620,6621 ,5498,5499,5500 ,0,0,0}, {6622,6623,6624 ,5501,5502,5503 ,0,0,0}, + {6625,6626,6627 ,5504,5505,5506 ,0,0,0}, {6628,6629,6630 ,5507,5508,5509 ,0,0,0}, + {6241,6245,6625 ,5510,5511,5504 ,0,0,0}, {6631,6632,6633 ,5512,5513,5514 ,0,0,0}, + {6622,6627,6626 ,5501,5506,5505 ,0,0,0}, {6634,6635,6632 ,5515,5516,5513 ,0,0,0}, + {6636,6634,6632 ,5517,5515,5513 ,0,0,0}, {6636,6637,6634 ,5517,5518,5515 ,0,0,0}, + {6637,6636,6638 ,5518,5517,5519 ,0,0,0}, {6639,6635,6640 ,5520,5516,5521 ,0,0,0}, + {6641,6642,6643 ,5522,5523,5524 ,0,0,0}, {6632,6635,6639 ,5513,5516,5520 ,0,0,0}, + {6643,6642,6638 ,5524,5523,5519 ,0,0,0}, {6644,6641,6645 ,5525,5522,5526 ,0,0,0}, + {6646,6647,6648 ,5527,5528,5529 ,0,0,0}, {6646,6639,6640 ,5527,5520,5521 ,0,0,0}, + {6649,6650,6651 ,5530,5531,5532 ,0,0,0}, {6646,6640,6647 ,5527,5521,5528 ,0,0,0}, + {6647,6649,6648 ,5528,5530,5529 ,0,0,0}, {6652,6653,6651 ,5533,5534,5532 ,0,0,0}, + {6629,6654,6630 ,5508,5535,5509 ,0,0,0}, {6651,6650,6652 ,5532,5531,5533 ,0,0,0}, + {6655,6614,6656 ,5536,5493,5537 ,0,0,0}, {6650,6657,6652 ,5531,5538,5533 ,0,0,0}, + {6629,6633,6654 ,5508,5514,5535 ,0,0,0}, {6658,6633,6639 ,5539,5514,5520 ,0,0,0}, + {6659,6660,6661 ,5540,5541,5542 ,0,0,0}, {6662,6659,6663 ,5543,5540,5544 ,0,0,0}, + {6220,6237,6612 ,5545,5546,5491 ,0,0,0}, {6664,6665,6666 ,5547,5548,5549 ,0,0,0}, + {6220,6611,6221 ,5545,5490,726 ,0,0,0}, {6667,6221,6611 ,5550,726,5490 ,0,0,0}, + {6668,6653,6669 ,5551,5534,5552 ,0,0,0}, {6649,6651,6648 ,5530,5532,5529 ,0,0,0}, + {6651,6653,6668 ,5532,5534,5551 ,0,0,0}, {6669,6670,6668 ,5552,5553,5551 ,0,0,0}, + {6671,6648,6668 ,5554,5529,5551 ,0,0,0}, {6633,6658,6654 ,5514,5539,5535 ,0,0,0}, + {6671,6658,6646 ,5554,5539,5527 ,0,0,0}, {6636,6672,6638 ,5517,5555,5519 ,0,0,0}, + {6646,6658,6639 ,5527,5539,5520 ,0,0,0}, {6673,6674,6643 ,5556,5557,5524 ,0,0,0}, + {6632,6639,6633 ,5513,5520,5514 ,0,0,0}, {6672,6636,6631 ,5555,5517,5512 ,0,0,0}, + {6641,6643,6645 ,5522,5524,5526 ,0,0,0}, {6637,6638,6642 ,5518,5519,5523 ,0,0,0}, + {6638,6672,6673 ,5519,5555,5556 ,0,0,0}, {6675,6645,6643 ,5558,5526,5524 ,0,0,0}, + {6651,6668,6648 ,5532,5551,5529 ,0,0,0}, {6676,6670,6669 ,5559,5553,5552 ,0,0,0}, + {6676,6663,6670 ,5559,5544,5553 ,0,0,0}, {6648,6671,6646 ,5529,5554,5527 ,0,0,0}, + {6670,6677,6671 ,5553,5560,5554 ,0,0,0}, {6629,6618,6631 ,5508,5497,5512 ,0,0,0}, + {6677,6654,6658 ,5560,5535,5539 ,0,0,0}, {6614,6674,6673 ,5493,5557,5556 ,0,0,0}, + {6655,6674,6614 ,5536,5557,5493 ,0,0,0}, {6632,6631,6636 ,5513,5512,5517 ,0,0,0}, + {6633,6629,6631 ,5514,5508,5512 ,0,0,0}, {6638,6673,6643 ,5519,5556,5524 ,0,0,0}, + {6618,6615,6672 ,5497,5494,5555 ,0,0,0}, {6643,6674,6675 ,5524,5557,5558 ,0,0,0}, + {6673,6615,6614 ,5556,5494,5493 ,0,0,0}, {6678,6675,6674 ,5561,5558,5557 ,0,0,0}, + {6668,6670,6671 ,5551,5553,5554 ,0,0,0}, {6662,6663,6676 ,5543,5544,5559 ,0,0,0}, + {6679,6661,6680 ,5562,5542,5563 ,0,0,0}, {6671,6677,6658 ,5554,5560,5539 ,0,0,0}, + {6681,6677,6663 ,5564,5560,5544 ,0,0,0}, {6618,6629,6628 ,5497,5508,5507 ,0,0,0}, + {6681,6630,6654 ,5564,5509,5535 ,0,0,0}, {6682,6656,6616 ,5565,5537,5495 ,0,0,0}, + {6672,6615,6673 ,5555,5494,5556 ,0,0,0}, {6631,6618,6672 ,5512,5497,5555 ,0,0,0}, + {6618,6628,6617 ,5497,5507,5496 ,0,0,0}, {6655,6656,6683 ,5536,5537,5566 ,0,0,0}, + {6617,6616,6615 ,5496,5495,5494 ,0,0,0}, {6674,6655,6678 ,5557,5536,5561 ,0,0,0}, + {6614,6616,6656 ,5493,5495,5537 ,0,0,0}, {6684,6678,6655 ,5567,5561,5536 ,0,0,0}, + {6670,6663,6677 ,5553,5544,5560 ,0,0,0}, {6660,6659,6662 ,5541,5540,5543 ,0,0,0}, + {6630,6685,6628 ,5509,5568,5507 ,0,0,0}, {6677,6681,6654 ,5560,5564,5535 ,0,0,0}, + {6686,6681,6659 ,5569,5564,5540 ,0,0,0}, {6628,6687,6617 ,5507,5570,5496 ,0,0,0}, + {6686,6685,6630 ,5569,5568,5509 ,0,0,0}, {6617,6688,6616 ,5496,5571,5495 ,0,0,0}, + {6687,6628,6685 ,5570,5507,5568 ,0,0,0}, {6656,6619,6683 ,5537,5498,5566 ,0,0,0}, + {6688,6617,6687 ,5571,5496,5570 ,0,0,0}, {6689,6683,6621 ,5572,5566,5500 ,0,0,0}, + {6682,6616,6688 ,5565,5495,5571 ,0,0,0}, {6655,6683,6684 ,5536,5566,5567 ,0,0,0}, + {6656,6682,6619 ,5537,5565,5498 ,0,0,0}, {6689,6684,6683 ,5572,5567,5566 ,0,0,0}, + {6663,6659,6681 ,5544,5540,5564 ,0,0,0}, {6680,6661,6660 ,5563,5542,5541 ,0,0,0}, + {6685,6665,6687 ,5568,5548,5570 ,0,0,0}, {6681,6686,6630 ,5564,5569,5509 ,0,0,0}, + {6661,6690,6686 ,5542,5573,5569 ,0,0,0}, {6687,6664,6688 ,5570,5547,5571 ,0,0,0}, + {6690,6665,6685 ,5573,5548,5568 ,0,0,0}, {6688,6691,6682 ,5571,5574,5565 ,0,0,0}, + {6665,6664,6687 ,5548,5547,5570 ,0,0,0}, {6692,6619,6682 ,5575,5498,5565 ,0,0,0}, + {6691,6688,6664 ,5574,5571,5547 ,0,0,0}, {6693,6621,6624 ,5576,5500,5503 ,0,0,0}, + {6682,6691,6692 ,5565,5574,5575 ,0,0,0}, {6692,6620,6619 ,5575,5499,5498 ,0,0,0}, + {6689,6621,6693 ,5572,5500,5576 ,0,0,0}, {6683,6619,6621 ,5566,5498,5500 ,0,0,0}, + {6659,6661,6686 ,5540,5542,5569 ,0,0,0}, {6694,6679,6680 ,5577,5562,5563 ,0,0,0}, + {6695,6691,6664 ,5578,5574,5547 ,0,0,0}, {6686,6690,6685 ,5569,5573,5568 ,0,0,0}, + {6679,6613,6690 ,5562,5492,5573 ,0,0,0}, {6696,6692,6691 ,5579,5575,5574 ,0,0,0}, + {6613,6666,6665 ,5492,5549,5548 ,0,0,0}, {6697,6620,6692 ,5580,5499,5575 ,0,0,0}, + {6666,6695,6664 ,5549,5578,5547 ,0,0,0}, {6627,6622,6698 ,5506,5501,5581 ,0,0,0}, + {6695,6696,6691 ,5578,5579,5574 ,0,0,0}, {6624,6620,6699 ,5503,5499,5582 ,0,0,0}, + {6697,6692,6696 ,5580,5575,5579 ,0,0,0}, {6699,6620,6697 ,5582,5499,5580 ,0,0,0}, + {6693,6624,6623 ,5576,5503,5502 ,0,0,0}, {6621,6620,6624 ,5500,5499,5503 ,0,0,0}, + {6661,6679,6690 ,5542,5562,5573 ,0,0,0}, {6611,6694,6667 ,5490,5577,5550 ,0,0,0}, + {6612,6700,6666 ,5491,5583,5549 ,0,0,0}, {6690,6613,6665 ,5573,5492,5548 ,0,0,0}, + {6612,6666,6613 ,5491,5549,5492 ,0,0,0}, {6700,6701,6695 ,5583,5584,5578 ,0,0,0}, + {6700,6695,6666 ,5583,5578,5549 ,0,0,0}, {6701,6702,6696 ,5584,5585,5579 ,0,0,0}, + {6701,6696,6695 ,5584,5579,5578 ,0,0,0}, {6702,6703,6697 ,5585,5586,5580 ,0,0,0}, + {6702,6697,6696 ,5585,5580,5579 ,0,0,0}, {6703,6698,6699 ,5586,5581,5582 ,0,0,0}, + {6699,6697,6703 ,5582,5580,5586 ,0,0,0}, {6698,6622,6699 ,5581,5501,5582 ,0,0,0}, + {6623,6622,6626 ,5502,5501,5505 ,0,0,0}, {6624,6699,6622 ,5503,5582,5501 ,0,0,0}, + {6694,6611,6679 ,5577,5490,5562 ,0,0,0}, {6613,6679,6611 ,5492,5562,5490 ,0,0,0}, + {6700,6237,6231 ,5583,5546,5587 ,0,0,0}, {6220,6612,6611 ,5545,5491,5490 ,0,0,0}, + {6701,6231,6236 ,5584,5587,5588 ,0,0,0}, {6237,6700,6612 ,5546,5583,5491 ,0,0,0}, + {6702,6236,6235 ,5585,5588,5589 ,0,0,0}, {6231,6701,6700 ,5587,5584,5583 ,0,0,0}, + {6703,6235,6481 ,5586,5589,5590 ,0,0,0}, {6236,6702,6701 ,5588,5585,5584 ,0,0,0}, + {6698,6481,6239 ,5581,5590,5591 ,0,0,0}, {6235,6703,6702 ,5589,5586,5585 ,0,0,0}, + {6627,6239,6241 ,5506,5591,5510 ,0,0,0}, {6481,6698,6703 ,5590,5581,5586 ,0,0,0}, + {6241,6625,6627 ,5510,5504,5506 ,0,0,0}, {6239,6627,6698 ,5591,5506,5581 ,0,0,0}, + {6704,6705,6706 ,5592,5593,5594 ,0,0,0}, {6707,6708,6709 ,5595,5596,5597 ,0,0,0}, + {6705,6710,6706 ,5593,5598,5594 ,0,0,0}, {6711,6709,6708 ,5599,5597,5596 ,0,0,0}, + {6712,6713,6714 ,5600,5601,5602 ,0,0,0}, {6715,6716,6713 ,5603,5604,5601 ,0,0,0}, + {6717,6718,6719 ,5605,5606,5607 ,0,0,0}, {6720,6716,6715 ,5608,5604,5603 ,0,0,0}, + {6716,6714,6713 ,5604,5602,5601 ,0,0,0}, {6721,6713,6707 ,5609,5601,5595 ,0,0,0}, + {6722,6723,6724 ,5610,5611,5612 ,0,0,0}, {6725,6726,6727 ,5613,5614,5615 ,0,0,0}, + {6728,6723,6729 ,5616,5611,5617 ,0,0,0}, {6730,6731,6704 ,5618,5619,5592 ,0,0,0}, + {6718,6467,6435 ,5606,5620,5621 ,0,0,0}, {6732,6733,6734 ,5622,5623,5624 ,0,0,0}, + {6735,6469,6717 ,5625,5626,5605 ,0,0,0}, {6467,6717,6469 ,5620,5605,5626 ,0,0,0}, + {6736,6737,6738 ,5627,5628,5629 ,0,0,0}, {6710,6739,6706 ,5598,5630,5594 ,0,0,0}, + {6740,6741,6742 ,5631,5632,5633 ,0,0,0}, {6743,6744,6745 ,5634,5635,5636 ,0,0,0}, + {6734,6737,6746 ,5624,5628,5637 ,0,0,0}, {6747,6748,6749 ,5638,5639,5640 ,0,0,0}, + {6750,6704,6751 ,5641,5592,5642 ,0,0,0}, {6748,6743,6749 ,5639,5634,5640 ,0,0,0}, + {6730,6711,6708 ,5618,5599,5596 ,0,0,0}, {6458,6461,6747 ,5643,5644,5638 ,0,0,0}, + {6711,6730,6752 ,5599,5618,5645 ,0,0,0}, {6752,6730,6750 ,5645,5618,5641 ,0,0,0}, + {6753,6754,6750 ,5646,5647,5641 ,0,0,0}, {6730,6708,6731 ,5618,5596,5619 ,0,0,0}, + {6753,6755,6756 ,5646,5648,5649 ,0,0,0}, {6756,6754,6753 ,5649,5647,5646 ,0,0,0}, + {6757,6758,6759 ,5650,5651,5652 ,0,0,0}, {6758,6757,6755 ,5651,5650,5648 ,0,0,0}, + {6715,6713,6721 ,5603,5601,5609 ,0,0,0}, {6760,6712,6714 ,5653,5600,5602 ,0,0,0}, + {6760,6761,6712 ,5653,5654,5600 ,0,0,0}, {6721,6707,6709 ,5609,5595,5597 ,0,0,0}, + {6762,6707,6712 ,5655,5595,5600 ,0,0,0}, {6704,6731,6705 ,5592,5619,5593 ,0,0,0}, + {6762,6731,6708 ,5655,5619,5596 ,0,0,0}, {6753,6763,6755 ,5646,5656,5648 ,0,0,0}, + {6764,6758,6765 ,5657,5651,5658 ,0,0,0}, {6752,6750,6754 ,5645,5641,5647 ,0,0,0}, + {6750,6730,6704 ,5641,5618,5592 ,0,0,0}, {6756,6755,6757 ,5649,5648,5650 ,0,0,0}, + {6751,6763,6753 ,5642,5656,5646 ,0,0,0}, {6758,6766,6759 ,5651,5659,5652 ,0,0,0}, + {6755,6763,6765 ,5648,5656,5658 ,0,0,0}, {6767,6766,6758 ,5660,5659,5651 ,0,0,0}, + {6713,6712,6707 ,5601,5600,5595 ,0,0,0}, {6768,6761,6760 ,5661,5654,5653 ,0,0,0}, + {6768,6724,6761 ,5661,5612,5654 ,0,0,0}, {6707,6762,6708 ,5595,5655,5596 ,0,0,0}, + {6761,6769,6762 ,5654,5662,5655 ,0,0,0}, {6706,6738,6751 ,5594,5629,5642 ,0,0,0}, + {6769,6705,6731 ,5662,5593,5619 ,0,0,0}, {6734,6764,6765 ,5624,5657,5658 ,0,0,0}, + {6733,6764,6734 ,5623,5657,5624 ,0,0,0}, {6750,6751,6753 ,5641,5642,5646 ,0,0,0}, + {6704,6706,6751 ,5592,5594,5642 ,0,0,0}, {6755,6765,6758 ,5648,5658,5651 ,0,0,0}, + {6738,6737,6763 ,5629,5628,5656 ,0,0,0}, {6758,6764,6767 ,5651,5657,5660 ,0,0,0}, + {6765,6737,6734 ,5658,5628,5624 ,0,0,0}, {6770,6767,6764 ,5663,5660,5657 ,0,0,0}, + {6712,6761,6762 ,5600,5654,5655 ,0,0,0}, {6722,6724,6768 ,5610,5612,5661 ,0,0,0}, + {6771,6728,6772 ,5664,5616,5665 ,0,0,0}, {6762,6769,6731 ,5655,5662,5619 ,0,0,0}, + {6773,6769,6724 ,5666,5662,5612 ,0,0,0}, {6738,6706,6739 ,5629,5594,5630 ,0,0,0}, + {6773,6710,6705 ,5666,5598,5593 ,0,0,0}, {6774,6732,6746 ,5667,5622,5637 ,0,0,0}, + {6763,6737,6765 ,5656,5628,5658 ,0,0,0}, {6751,6738,6763 ,5642,5629,5656 ,0,0,0}, + {6738,6739,6736 ,5629,5630,5627 ,0,0,0}, {6733,6732,6775 ,5623,5622,5668 ,0,0,0}, + {6736,6746,6737 ,5627,5637,5628 ,0,0,0}, {6764,6733,6770 ,5657,5623,5663 ,0,0,0}, + {6734,6746,6732 ,5624,5637,5622 ,0,0,0}, {6776,6770,6733 ,5669,5663,5623 ,0,0,0}, + {6761,6724,6769 ,5654,5612,5662 ,0,0,0}, {6729,6723,6722 ,5617,5611,5610 ,0,0,0}, + {6710,6777,6739 ,5598,5670,5630 ,0,0,0}, {6769,6773,6705 ,5662,5666,5593 ,0,0,0}, + {6778,6773,6723 ,5671,5666,5611 ,0,0,0}, {6739,6779,6736 ,5630,5672,5627 ,0,0,0}, + {6778,6777,6710 ,5671,5670,5598 ,0,0,0}, {6736,6780,6746 ,5627,5673,5637 ,0,0,0}, + {6779,6739,6777 ,5672,5630,5670 ,0,0,0}, {6732,6741,6775 ,5622,5632,5668 ,0,0,0}, + {6780,6736,6779 ,5673,5627,5672 ,0,0,0}, {6781,6775,6740 ,5674,5668,5631 ,0,0,0}, + {6774,6746,6780 ,5667,5637,5673 ,0,0,0}, {6733,6775,6776 ,5623,5668,5669 ,0,0,0}, + {6732,6774,6741 ,5622,5667,5632 ,0,0,0}, {6781,6776,6775 ,5674,5669,5668 ,0,0,0}, + {6724,6723,6773 ,5612,5611,5666 ,0,0,0}, {6772,6728,6729 ,5665,5616,5617 ,0,0,0}, + {6777,6725,6779 ,5670,5613,5672 ,0,0,0}, {6773,6778,6710 ,5666,5671,5598 ,0,0,0}, + {6728,6782,6778 ,5616,5675,5671 ,0,0,0}, {6779,6727,6780 ,5672,5615,5673 ,0,0,0}, + {6782,6725,6777 ,5675,5613,5670 ,0,0,0}, {6780,6783,6774 ,5673,5676,5667 ,0,0,0}, + {6725,6727,6779 ,5613,5615,5672 ,0,0,0}, {6784,6741,6774 ,5677,5632,5667 ,0,0,0}, + {6783,6780,6727 ,5676,5673,5615 ,0,0,0}, {6785,6740,6745 ,5678,5631,5636 ,0,0,0}, + {6774,6783,6784 ,5667,5676,5677 ,0,0,0}, {6784,6742,6741 ,5677,5633,5632 ,0,0,0}, + {6781,6740,6785 ,5674,5631,5678 ,0,0,0}, {6775,6741,6740 ,5668,5632,5631 ,0,0,0}, + {6723,6728,6778 ,5611,5616,5671 ,0,0,0}, {6786,6771,6772 ,5679,5664,5665 ,0,0,0}, + {6787,6783,6727 ,5680,5676,5615 ,0,0,0}, {6778,6782,6777 ,5671,5675,5670 ,0,0,0}, + {6771,6719,6782 ,5664,5607,5675 ,0,0,0}, {6788,6784,6783 ,5681,5677,5676 ,0,0,0}, + {6719,6726,6725 ,5607,5614,5613 ,0,0,0}, {6789,6742,6784 ,5682,5633,5677 ,0,0,0}, + {6726,6787,6727 ,5614,5680,5615 ,0,0,0}, {6749,6743,6790 ,5640,5634,5683 ,0,0,0}, + {6787,6788,6783 ,5680,5681,5676 ,0,0,0}, {6745,6742,6791 ,5636,5633,5684 ,0,0,0}, + {6789,6784,6788 ,5682,5677,5681 ,0,0,0}, {6791,6742,6789 ,5684,5633,5682 ,0,0,0}, + {6785,6745,6744 ,5678,5636,5635 ,0,0,0}, {6740,6742,6745 ,5631,5633,5636 ,0,0,0}, + {6728,6771,6782 ,5616,5664,5675 ,0,0,0}, {6717,6786,6735 ,5605,5679,5625 ,0,0,0}, + {6718,6792,6726 ,5606,5685,5614 ,0,0,0}, {6782,6719,6725 ,5675,5607,5613 ,0,0,0}, + {6718,6726,6719 ,5606,5614,5607 ,0,0,0}, {6792,6793,6787 ,5685,5686,5680 ,0,0,0}, + {6792,6787,6726 ,5685,5680,5614 ,0,0,0}, {6793,6794,6788 ,5686,5687,5681 ,0,0,0}, + {6793,6788,6787 ,5686,5681,5680 ,0,0,0}, {6794,6795,6789 ,5687,5688,5682 ,0,0,0}, + {6794,6789,6788 ,5687,5682,5681 ,0,0,0}, {6795,6790,6791 ,5688,5683,5684 ,0,0,0}, + {6791,6789,6795 ,5684,5682,5688 ,0,0,0}, {6790,6743,6791 ,5683,5634,5684 ,0,0,0}, + {6744,6743,6748 ,5635,5634,5639 ,0,0,0}, {6745,6791,6743 ,5636,5684,5634 ,0,0,0}, + {6786,6717,6771 ,5679,5605,5664 ,0,0,0}, {6719,6771,6717 ,5607,5664,5605 ,0,0,0}, + {6792,6435,6456 ,5685,5621,5689 ,0,0,0}, {6467,6718,6717 ,5620,5606,5605 ,0,0,0}, + {6793,6456,6567 ,5686,5689,5690 ,0,0,0}, {6435,6792,6718 ,5621,5685,5606 ,0,0,0}, + {6794,6567,6453 ,5687,5690,5691 ,0,0,0}, {6456,6793,6792 ,5689,5686,5685 ,0,0,0}, + {6795,6453,6451 ,5688,5691,5692 ,0,0,0}, {6567,6794,6793 ,5690,5687,5686 ,0,0,0}, + {6790,6451,6420 ,5683,5692,5693 ,0,0,0}, {6453,6795,6794 ,5691,5688,5687 ,0,0,0}, + {6749,6420,6458 ,5640,5693,5643 ,0,0,0}, {6451,6790,6795 ,5692,5683,5688 ,0,0,0}, + {6458,6747,6749 ,5643,5638,5640 ,0,0,0}, {6420,6749,6790 ,5693,5640,5683 ,0,0,0}, + {6796,6797,6798 ,5694,5695,5696 ,0,0,0}, {6799,6800,6801 ,5697,5698,5699 ,0,0,0}, + {6798,6802,6803 ,5696,5700,5701 ,0,0,0}, {6802,6804,6803 ,5700,5702,5701 ,0,0,0}, + {6805,6806,6807 ,5703,5704,5705 ,0,0,0}, {6807,6808,6805 ,5705,5706,5703 ,0,0,0}, + {6809,6810,6811 ,5707,5708,5709 ,0,0,0}, {6812,6806,6813 ,5710,5704,5711 ,0,0,0}, + {6812,6807,6806 ,5710,5705,5704 ,0,0,0}, {6813,6814,6812 ,5711,5712,5710 ,0,0,0}, + {6815,6801,6816 ,5713,5699,5714 ,0,0,0}, {6817,6818,6819 ,5715,5716,5717 ,0,0,0}, + {6809,6383,6382 ,5707,5718,5719 ,0,0,0}, {6820,6821,6822 ,5720,5721,5722 ,0,0,0}, + {6823,6410,6811 ,5723,5724,5709 ,0,0,0}, {6824,6825,6818 ,5725,5726,5716 ,0,0,0}, + {6383,6811,6410 ,5718,5709,5724 ,0,0,0}, {6826,6827,6828 ,5727,5728,5729 ,0,0,0}, + {6829,6803,6804 ,5730,5701,5702 ,0,0,0}, {6830,6831,6832 ,5731,5732,5733 ,0,0,0}, + {6833,6834,6798 ,5734,5735,5696 ,0,0,0}, {6835,6836,6837 ,5736,5737,5738 ,0,0,0}, + {6828,6838,6839 ,5729,5739,5740 ,0,0,0}, {6840,6838,6841 ,5741,5739,5742 ,0,0,0}, + {6842,6843,6844 ,5743,5744,5745 ,0,0,0}, {6796,6800,6799 ,5694,5698,5697 ,0,0,0}, + {6843,6830,6844 ,5744,5731,5745 ,0,0,0}, {6834,6845,6796 ,5735,5746,5694 ,0,0,0}, + {6406,6411,6842 ,5747,5748,5743 ,0,0,0}, {6846,6847,6834 ,5749,5750,5735 ,0,0,0}, + {6845,6800,6796 ,5746,5698,5694 ,0,0,0}, {6846,6848,6849 ,5749,5751,5752 ,0,0,0}, + {6834,6847,6845 ,5735,5750,5746 ,0,0,0}, {6850,6851,6852 ,5753,5754,5755 ,0,0,0}, + {6847,6846,6849 ,5750,5749,5752 ,0,0,0}, {6853,6852,6854 ,5756,5755,5757 ,0,0,0}, + {6851,6850,6848 ,5754,5753,5751 ,0,0,0}, {6816,6806,6815 ,5714,5704,5713 ,0,0,0}, + {6806,6816,6813 ,5704,5714,5711 ,0,0,0}, {6808,6855,6805 ,5706,5758,5703 ,0,0,0}, + {6815,6799,6801 ,5713,5697,5699 ,0,0,0}, {6856,6815,6805 ,5759,5713,5703 ,0,0,0}, + {6798,6797,6802 ,5696,5695,5700 ,0,0,0}, {6856,6797,6799 ,5759,5695,5697 ,0,0,0}, + {6846,6857,6848 ,5749,5760,5751 ,0,0,0}, {6799,6797,6796 ,5697,5695,5694 ,0,0,0}, + {6858,6859,6851 ,5761,5762,5754 ,0,0,0}, {6834,6796,6798 ,5735,5694,5696 ,0,0,0}, + {6857,6846,6833 ,5760,5749,5734 ,0,0,0}, {6852,6851,6854 ,5755,5754,5757 ,0,0,0}, + {6849,6848,6850 ,5752,5751,5753 ,0,0,0}, {6848,6857,6858 ,5751,5760,5761 ,0,0,0}, + {6860,6854,6851 ,5763,5757,5754 ,0,0,0}, {6806,6805,6815 ,5704,5703,5713 ,0,0,0}, + {6861,6855,6808 ,5764,5758,5706 ,0,0,0}, {6861,6824,6855 ,5764,5725,5758 ,0,0,0}, + {6815,6856,6799 ,5713,5759,5697 ,0,0,0}, {6855,6862,6856 ,5758,5765,5759 ,0,0,0}, + {6803,6841,6833 ,5701,5742,5734 ,0,0,0}, {6862,6802,6797 ,5765,5700,5695 ,0,0,0}, + {6828,6859,6858 ,5729,5762,5761 ,0,0,0}, {6827,6859,6828 ,5728,5762,5729 ,0,0,0}, + {6834,6833,6846 ,5735,5734,5749 ,0,0,0}, {6798,6803,6833 ,5696,5701,5734 ,0,0,0}, + {6848,6858,6851 ,5751,5761,5754 ,0,0,0}, {6841,6838,6857 ,5742,5739,5760 ,0,0,0}, + {6851,6859,6860 ,5754,5762,5763 ,0,0,0}, {6858,6838,6828 ,5761,5739,5729 ,0,0,0}, + {6863,6860,6859 ,5766,5763,5762 ,0,0,0}, {6805,6855,6856 ,5703,5758,5759 ,0,0,0}, + {6825,6824,6861 ,5726,5725,5764 ,0,0,0}, {6864,6817,6865 ,5767,5715,5768 ,0,0,0}, + {6856,6862,6797 ,5759,5765,5695 ,0,0,0}, {6866,6862,6824 ,5769,5765,5725 ,0,0,0}, + {6841,6803,6829 ,5742,5701,5730 ,0,0,0}, {6866,6804,6802 ,5769,5702,5700 ,0,0,0}, + {6867,6826,6839 ,5770,5727,5740 ,0,0,0}, {6857,6838,6858 ,5760,5739,5761 ,0,0,0}, + {6833,6841,6857 ,5734,5742,5760 ,0,0,0}, {6841,6829,6840 ,5742,5730,5741 ,0,0,0}, + {6827,6826,6868 ,5728,5727,5771 ,0,0,0}, {6840,6839,6838 ,5741,5740,5739 ,0,0,0}, + {6859,6827,6863 ,5762,5728,5766 ,0,0,0}, {6828,6839,6826 ,5729,5740,5727 ,0,0,0}, + {6869,6863,6827 ,5772,5766,5728 ,0,0,0}, {6855,6824,6862 ,5758,5725,5765 ,0,0,0}, + {6819,6818,6825 ,5717,5716,5726 ,0,0,0}, {6804,6870,6829 ,5702,5773,5730 ,0,0,0}, + {6862,6866,6802 ,5765,5769,5700 ,0,0,0}, {6871,6866,6818 ,5774,5769,5716 ,0,0,0}, + {6829,6872,6840 ,5730,5775,5741 ,0,0,0}, {6871,6870,6804 ,5774,5773,5702 ,0,0,0}, + {6840,6873,6839 ,5741,5776,5740 ,0,0,0}, {6872,6829,6870 ,5775,5730,5773 ,0,0,0}, + {6826,6836,6868 ,5727,5737,5771 ,0,0,0}, {6873,6840,6872 ,5776,5741,5775 ,0,0,0}, + {6874,6868,6835 ,5777,5771,5736 ,0,0,0}, {6867,6839,6873 ,5770,5740,5776 ,0,0,0}, + {6827,6868,6869 ,5728,5771,5772 ,0,0,0}, {6826,6867,6836 ,5727,5770,5737 ,0,0,0}, + {6874,6869,6868 ,5777,5772,5771 ,0,0,0}, {6824,6818,6866 ,5725,5716,5769 ,0,0,0}, + {6865,6817,6819 ,5768,5715,5717 ,0,0,0}, {6870,6821,6872 ,5773,5721,5775 ,0,0,0}, + {6866,6871,6804 ,5769,5774,5702 ,0,0,0}, {6817,6875,6871 ,5715,5778,5774 ,0,0,0}, + {6872,6820,6873 ,5775,5720,5776 ,0,0,0}, {6875,6821,6870 ,5778,5721,5773 ,0,0,0}, + {6873,6876,6867 ,5776,5779,5770 ,0,0,0}, {6821,6820,6872 ,5721,5720,5775 ,0,0,0}, + {6877,6836,6867 ,5780,5737,5770 ,0,0,0}, {6876,6873,6820 ,5779,5776,5720 ,0,0,0}, + {6878,6835,6832 ,5781,5736,5733 ,0,0,0}, {6867,6876,6877 ,5770,5779,5780 ,0,0,0}, + {6877,6837,6836 ,5780,5738,5737 ,0,0,0}, {6874,6835,6878 ,5777,5736,5781 ,0,0,0}, + {6868,6836,6835 ,5771,5737,5736 ,0,0,0}, {6818,6817,6871 ,5716,5715,5774 ,0,0,0}, + {6879,6864,6865 ,5782,5767,5768 ,0,0,0}, {6880,6876,6820 ,5783,5779,5720 ,0,0,0}, + {6871,6875,6870 ,5774,5778,5773 ,0,0,0}, {6864,6810,6875 ,5767,5708,5778 ,0,0,0}, + {6881,6877,6876 ,5784,5780,5779 ,0,0,0}, {6810,6822,6821 ,5708,5722,5721 ,0,0,0}, + {6882,6837,6877 ,5785,5738,5780 ,0,0,0}, {6822,6880,6820 ,5722,5783,5720 ,0,0,0}, + {6844,6830,6883 ,5745,5731,5786 ,0,0,0}, {6880,6881,6876 ,5783,5784,5779 ,0,0,0}, + {6832,6837,6884 ,5733,5738,5787 ,0,0,0}, {6882,6877,6881 ,5785,5780,5784 ,0,0,0}, + {6884,6837,6882 ,5787,5738,5785 ,0,0,0}, {6878,6832,6831 ,5781,5733,5732 ,0,0,0}, + {6835,6837,6832 ,5736,5738,5733 ,0,0,0}, {6817,6864,6875 ,5715,5767,5778 ,0,0,0}, + {6811,6879,6823 ,5709,5782,5723 ,0,0,0}, {6809,6885,6822 ,5707,5788,5722 ,0,0,0}, + {6875,6810,6821 ,5778,5708,5721 ,0,0,0}, {6809,6822,6810 ,5707,5722,5708 ,0,0,0}, + {6885,6886,6880 ,5788,5789,5783 ,0,0,0}, {6885,6880,6822 ,5788,5783,5722 ,0,0,0}, + {6886,6887,6881 ,5789,5790,5784 ,0,0,0}, {6886,6881,6880 ,5789,5784,5783 ,0,0,0}, + {6887,6888,6882 ,5790,5791,5785 ,0,0,0}, {6887,6882,6881 ,5790,5785,5784 ,0,0,0}, + {6888,6883,6884 ,5791,5786,5787 ,0,0,0}, {6884,6882,6888 ,5787,5785,5791 ,0,0,0}, + {6883,6830,6884 ,5786,5731,5787 ,0,0,0}, {6831,6830,6843 ,5732,5731,5744 ,0,0,0}, + {6832,6884,6830 ,5733,5787,5731 ,0,0,0}, {6879,6811,6864 ,5782,5709,5767 ,0,0,0}, + {6810,6864,6811 ,5708,5767,5709 ,0,0,0}, {6885,6382,6397 ,5788,5719,5792 ,0,0,0}, + {6383,6809,6811 ,5718,5707,5709 ,0,0,0}, {6886,6397,6400 ,5789,5792,5793 ,0,0,0}, + {6382,6885,6809 ,5719,5788,5707 ,0,0,0}, {6887,6400,6401 ,5790,5793,5794 ,0,0,0}, + {6397,6886,6885 ,5792,5789,5788 ,0,0,0}, {6888,6401,6440 ,5791,5794,5795 ,0,0,0}, + {6400,6887,6886 ,5793,5790,5789 ,0,0,0}, {6883,6440,6381 ,5786,5795,5796 ,0,0,0}, + {6401,6888,6887 ,5794,5791,5790 ,0,0,0}, {6844,6381,6406 ,5745,5796,5747 ,0,0,0}, + {6440,6883,6888 ,5795,5786,5791 ,0,0,0}, {6406,6842,6844 ,5747,5743,5745 ,0,0,0}, + {6381,6844,6883 ,5796,5745,5786 ,0,0,0}, {6889,6890,6891 ,5797,5798,5799 ,0,0,0}, + {6892,5806,5807 ,5800,5801,5802 ,0,0,0}, {6891,6893,6894 ,5799,5803,5804 ,0,0,0}, + {6893,6895,6894 ,5803,5805,5804 ,0,0,0}, {6896,6897,6898 ,5806,5807,5808 ,0,0,0}, + {6898,6899,6896 ,5808,5809,5806 ,0,0,0}, {6900,6901,6902 ,5810,5811,5812 ,0,0,0}, + {6903,6897,5812 ,5813,5807,5814 ,0,0,0}, {6903,6898,6897 ,5813,5808,5807 ,0,0,0}, + {5812,5813,6903 ,5814,5815,5813 ,0,0,0}, {6904,5807,5810 ,5816,5802,5817 ,0,0,0}, + {6905,6906,6907 ,5818,5819,5820 ,0,0,0}, {6900,6339,6338 ,5810,5821,5822 ,0,0,0}, + {6908,6909,6910 ,5823,5824,5825 ,0,0,0}, {6911,6346,6902 ,5826,5827,5812 ,0,0,0}, + {6912,6913,6906 ,5828,5829,5819 ,0,0,0}, {6339,6902,6346 ,5821,5812,5827 ,0,0,0}, + {6914,6915,6916 ,5830,5831,5832 ,0,0,0}, {6917,6894,6895 ,5833,5804,5805 ,0,0,0}, + {6918,6919,6920 ,5834,5835,5836 ,0,0,0}, {6921,6922,6891 ,5837,5838,5799 ,0,0,0}, + {6923,6924,6925 ,5839,5840,5841 ,0,0,0}, {6916,6926,6927 ,5832,5842,5843 ,0,0,0}, + {6928,6926,6929 ,5844,5842,5845 ,0,0,0}, {6930,6931,6932 ,5846,5847,5848 ,0,0,0}, + {6889,5806,6892 ,5797,5801,5800 ,0,0,0}, {6931,6918,6932 ,5847,5834,5848 ,0,0,0}, + {6922,5804,6889 ,5838,5849,5797 ,0,0,0}, {6362,6369,6930 ,5850,5851,5846 ,0,0,0}, + {6933,5802,6922 ,5852,5853,5838 ,0,0,0}, {5804,5806,6889 ,5849,5801,5797 ,0,0,0}, + {6933,6934,5799 ,5852,5854,5855 ,0,0,0}, {6922,5802,5804 ,5838,5853,5849 ,0,0,0}, + {5797,6935,5798 ,5856,5857,5858 ,0,0,0}, {5802,6933,5799 ,5853,5852,5855 ,0,0,0}, + {5792,5798,6936 ,5067,5858,5859 ,0,0,0}, {6935,5797,6934 ,5857,5856,5854 ,0,0,0}, + {5810,6897,6904 ,5817,5807,5816 ,0,0,0}, {6897,5810,5812 ,5807,5817,5814 ,0,0,0}, + {6899,6937,6896 ,5809,5860,5806 ,0,0,0}, {6904,6892,5807 ,5816,5800,5802 ,0,0,0}, + {6938,6904,6896 ,5861,5816,5806 ,0,0,0}, {6891,6890,6893 ,5799,5798,5803 ,0,0,0}, + {6938,6890,6892 ,5861,5798,5800 ,0,0,0}, {6933,6939,6934 ,5852,5862,5854 ,0,0,0}, + {6892,6890,6889 ,5800,5798,5797 ,0,0,0}, {6940,6941,6935 ,5863,5864,5857 ,0,0,0}, + {6922,6889,6891 ,5838,5797,5799 ,0,0,0}, {6939,6933,6921 ,5862,5852,5837 ,0,0,0}, + {5798,6935,6936 ,5858,5857,5859 ,0,0,0}, {5799,6934,5797 ,5855,5854,5856 ,0,0,0}, + {6934,6939,6940 ,5854,5862,5863 ,0,0,0}, {6942,6936,6935 ,5865,5859,5857 ,0,0,0}, + {6897,6896,6904 ,5807,5806,5816 ,0,0,0}, {6943,6937,6899 ,5866,5860,5809 ,0,0,0}, + {6943,6912,6937 ,5866,5828,5860 ,0,0,0}, {6904,6938,6892 ,5816,5861,5800 ,0,0,0}, + {6937,6944,6938 ,5860,5867,5861 ,0,0,0}, {6894,6929,6921 ,5804,5845,5837 ,0,0,0}, + {6944,6893,6890 ,5867,5803,5798 ,0,0,0}, {6916,6941,6940 ,5832,5864,5863 ,0,0,0}, + {6915,6941,6916 ,5831,5864,5832 ,0,0,0}, {6922,6921,6933 ,5838,5837,5852 ,0,0,0}, + {6891,6894,6921 ,5799,5804,5837 ,0,0,0}, {6934,6940,6935 ,5854,5863,5857 ,0,0,0}, + {6929,6926,6939 ,5845,5842,5862 ,0,0,0}, {6935,6941,6942 ,5857,5864,5865 ,0,0,0}, + {6940,6926,6916 ,5863,5842,5832 ,0,0,0}, {6945,6942,6941 ,5868,5865,5864 ,0,0,0}, + {6896,6937,6938 ,5806,5860,5861 ,0,0,0}, {6913,6912,6943 ,5829,5828,5866 ,0,0,0}, + {6946,6905,6947 ,5869,5818,5870 ,0,0,0}, {6938,6944,6890 ,5861,5867,5798 ,0,0,0}, + {6948,6944,6912 ,5871,5867,5828 ,0,0,0}, {6929,6894,6917 ,5845,5804,5833 ,0,0,0}, + {6948,6895,6893 ,5871,5805,5803 ,0,0,0}, {6949,6914,6927 ,5872,5830,5843 ,0,0,0}, + {6939,6926,6940 ,5862,5842,5863 ,0,0,0}, {6921,6929,6939 ,5837,5845,5862 ,0,0,0}, + {6929,6917,6928 ,5845,5833,5844 ,0,0,0}, {6915,6914,6950 ,5831,5830,5873 ,0,0,0}, + {6928,6927,6926 ,5844,5843,5842 ,0,0,0}, {6941,6915,6945 ,5864,5831,5868 ,0,0,0}, + {6916,6927,6914 ,5832,5843,5830 ,0,0,0}, {6951,6945,6915 ,5874,5868,5831 ,0,0,0}, + {6937,6912,6944 ,5860,5828,5867 ,0,0,0}, {6907,6906,6913 ,5820,5819,5829 ,0,0,0}, + {6895,6952,6917 ,5805,5875,5833 ,0,0,0}, {6944,6948,6893 ,5867,5871,5803 ,0,0,0}, + {6953,6948,6906 ,5876,5871,5819 ,0,0,0}, {6917,6954,6928 ,5833,5877,5844 ,0,0,0}, + {6953,6952,6895 ,5876,5875,5805 ,0,0,0}, {6928,6955,6927 ,5844,5878,5843 ,0,0,0}, + {6954,6917,6952 ,5877,5833,5875 ,0,0,0}, {6914,6924,6950 ,5830,5840,5873 ,0,0,0}, + {6955,6928,6954 ,5878,5844,5877 ,0,0,0}, {6956,6950,6923 ,5879,5873,5839 ,0,0,0}, + {6949,6927,6955 ,5872,5843,5878 ,0,0,0}, {6915,6950,6951 ,5831,5873,5874 ,0,0,0}, + {6914,6949,6924 ,5830,5872,5840 ,0,0,0}, {6956,6951,6950 ,5879,5874,5873 ,0,0,0}, + {6912,6906,6948 ,5828,5819,5871 ,0,0,0}, {6947,6905,6907 ,5870,5818,5820 ,0,0,0}, + {6952,6909,6954 ,5875,5824,5877 ,0,0,0}, {6948,6953,6895 ,5871,5876,5805 ,0,0,0}, + {6905,6957,6953 ,5818,5880,5876 ,0,0,0}, {6954,6908,6955 ,5877,5823,5878 ,0,0,0}, + {6957,6909,6952 ,5880,5824,5875 ,0,0,0}, {6955,6958,6949 ,5878,5881,5872 ,0,0,0}, + {6909,6908,6954 ,5824,5823,5877 ,0,0,0}, {6959,6924,6949 ,5882,5840,5872 ,0,0,0}, + {6958,6955,6908 ,5881,5878,5823 ,0,0,0}, {6960,6923,6920 ,5883,5839,5836 ,0,0,0}, + {6949,6958,6959 ,5872,5881,5882 ,0,0,0}, {6959,6925,6924 ,5882,5841,5840 ,0,0,0}, + {6956,6923,6960 ,5879,5839,5883 ,0,0,0}, {6950,6924,6923 ,5873,5840,5839 ,0,0,0}, + {6906,6905,6953 ,5819,5818,5876 ,0,0,0}, {6961,6946,6947 ,5884,5869,5870 ,0,0,0}, + {6962,6958,6908 ,5885,5881,5823 ,0,0,0}, {6953,6957,6952 ,5876,5880,5875 ,0,0,0}, + {6946,6901,6957 ,5869,5811,5880 ,0,0,0}, {6963,6959,6958 ,5886,5882,5881 ,0,0,0}, + {6901,6910,6909 ,5811,5825,5824 ,0,0,0}, {6964,6925,6959 ,5887,5841,5882 ,0,0,0}, + {6910,6962,6908 ,5825,5885,5823 ,0,0,0}, {6932,6918,6965 ,5848,5834,5888 ,0,0,0}, + {6962,6963,6958 ,5885,5886,5881 ,0,0,0}, {6920,6925,6966 ,5836,5841,5889 ,0,0,0}, + {6964,6959,6963 ,5887,5882,5886 ,0,0,0}, {6966,6925,6964 ,5889,5841,5887 ,0,0,0}, + {6960,6920,6919 ,5883,5836,5835 ,0,0,0}, {6923,6925,6920 ,5839,5841,5836 ,0,0,0}, + {6905,6946,6957 ,5818,5869,5880 ,0,0,0}, {6902,6961,6911 ,5812,5884,5826 ,0,0,0}, + {6900,6967,6910 ,5810,5890,5825 ,0,0,0}, {6957,6901,6909 ,5880,5811,5824 ,0,0,0}, + {6900,6910,6901 ,5810,5825,5811 ,0,0,0}, {6967,6968,6962 ,5890,5891,5885 ,0,0,0}, + {6967,6962,6910 ,5890,5885,5825 ,0,0,0}, {6968,6969,6963 ,5891,5892,5886 ,0,0,0}, + {6968,6963,6962 ,5891,5886,5885 ,0,0,0}, {6969,6970,6964 ,5892,5893,5887 ,0,0,0}, + {6969,6964,6963 ,5892,5887,5886 ,0,0,0}, {6970,6965,6966 ,5893,5888,5889 ,0,0,0}, + {6966,6964,6970 ,5889,5887,5893 ,0,0,0}, {6965,6918,6966 ,5888,5834,5889 ,0,0,0}, + {6919,6918,6931 ,5835,5834,5847 ,0,0,0}, {6920,6966,6918 ,5836,5889,5834 ,0,0,0}, + {6961,6902,6946 ,5884,5812,5869 ,0,0,0}, {6901,6946,6902 ,5811,5869,5812 ,0,0,0}, + {6967,6338,6356 ,5890,5822,5894 ,0,0,0}, {6339,6900,6902 ,5821,5810,5812 ,0,0,0}, + {6968,6356,6357 ,5891,5894,5895 ,0,0,0}, {6338,6967,6900 ,5822,5890,5810 ,0,0,0}, + {6969,6357,6359 ,5892,5895,5896 ,0,0,0}, {6356,6968,6967 ,5894,5891,5890 ,0,0,0}, + {6970,6359,6342 ,5893,5896,5897 ,0,0,0}, {6357,6969,6968 ,5895,5892,5891 ,0,0,0}, + {6965,6342,6363 ,5888,5897,5898 ,0,0,0}, {6359,6970,6969 ,5896,5893,5892 ,0,0,0}, + {6932,6363,6362 ,5848,5898,5850 ,0,0,0}, {6342,6965,6970 ,5897,5888,5893 ,0,0,0}, + {6362,6930,6932 ,5850,5846,5848 ,0,0,0}, {6363,6932,6965 ,5898,5848,5888 ,0,0,0}, + {6971,6972,6973 ,5899,5900,5901 ,0,0,0}, {6974,6975,5775 ,5902,5903,5904 ,0,0,0}, + {6972,6976,6973 ,5900,5905,5901 ,0,0,0}, {5770,5775,6975 ,5906,5904,5903 ,0,0,0}, + {6977,6978,6979 ,5907,5908,5909 ,0,0,0}, {5780,6980,6978 ,5910,5911,5908 ,0,0,0}, + {6981,6982,6983 ,5912,5913,5914 ,0,0,0}, {5778,6980,5780 ,5915,5911,5910 ,0,0,0}, + {6980,6979,6978 ,5911,5909,5908 ,0,0,0}, {5774,6978,6974 ,5916,5908,5902 ,0,0,0}, + {6984,6985,6986 ,5917,5918,5919 ,0,0,0}, {6987,6988,6989 ,5920,5921,5922 ,0,0,0}, + {6990,6985,6991 ,5923,5918,5924 ,0,0,0}, {6992,6993,6971 ,5925,5926,5899 ,0,0,0}, + {6982,6289,6208 ,5913,5927,5928 ,0,0,0}, {6994,6995,6996 ,5929,5930,5931 ,0,0,0}, + {6997,6319,6981 ,5932,5933,5912 ,0,0,0}, {6289,6981,6319 ,5927,5912,5933 ,0,0,0}, + {6998,6999,7000 ,5934,5935,5936 ,0,0,0}, {6976,7001,6973 ,5905,5937,5901 ,0,0,0}, + {7002,7003,7004 ,5938,5939,5940 ,0,0,0}, {7005,7006,7007 ,5941,5942,5943 ,0,0,0}, + {6996,6999,7008 ,5931,5935,5944 ,0,0,0}, {7009,7010,7011 ,5945,5946,5947 ,0,0,0}, + {7012,6971,7013 ,5948,5899,5949 ,0,0,0}, {7010,7005,7011 ,5946,5941,5947 ,0,0,0}, + {6992,5770,6975 ,5925,5906,5903 ,0,0,0}, {6318,6322,7009 ,5950,5951,5945 ,0,0,0}, + {5770,6992,5768 ,5906,5925,5952 ,0,0,0}, {5768,6992,7012 ,5952,5925,5948 ,0,0,0}, + {7014,5763,7012 ,5953,5954,5948 ,0,0,0}, {6992,6975,6993 ,5925,5903,5926 ,0,0,0}, + {7014,7015,5767 ,5953,5955,5956 ,0,0,0}, {5767,5763,7014 ,5956,5954,5953 ,0,0,0}, + {5759,7016,5761 ,5957,5958,5959 ,0,0,0}, {7016,5759,7015 ,5958,5957,5955 ,0,0,0}, + {5780,6978,5774 ,5910,5908,5916 ,0,0,0}, {7017,6977,6979 ,5960,5907,5909 ,0,0,0}, + {7017,7018,6977 ,5960,5961,5907 ,0,0,0}, {5774,6974,5775 ,5916,5902,5904 ,0,0,0}, + {7019,6974,6977 ,5962,5902,5907 ,0,0,0}, {6971,6993,6972 ,5899,5926,5900 ,0,0,0}, + {7019,6993,6975 ,5962,5926,5903 ,0,0,0}, {7014,7020,7015 ,5953,5963,5955 ,0,0,0}, + {7021,7016,7022 ,5964,5958,5965 ,0,0,0}, {5768,7012,5763 ,5952,5948,5954 ,0,0,0}, + {7012,6992,6971 ,5948,5925,5899 ,0,0,0}, {5767,7015,5759 ,5956,5955,5957 ,0,0,0}, + {7013,7020,7014 ,5949,5963,5953 ,0,0,0}, {7016,7023,5761 ,5958,5966,5959 ,0,0,0}, + {7015,7020,7022 ,5955,5963,5965 ,0,0,0}, {7024,7023,7016 ,5967,5966,5958 ,0,0,0}, + {6978,6977,6974 ,5908,5907,5902 ,0,0,0}, {7025,7018,7017 ,5968,5961,5960 ,0,0,0}, + {7025,6986,7018 ,5968,5919,5961 ,0,0,0}, {6974,7019,6975 ,5902,5962,5903 ,0,0,0}, + {7018,7026,7019 ,5961,5969,5962 ,0,0,0}, {6973,7000,7013 ,5901,5936,5949 ,0,0,0}, + {7026,6972,6993 ,5969,5900,5926 ,0,0,0}, {6996,7021,7022 ,5931,5964,5965 ,0,0,0}, + {6995,7021,6996 ,5930,5964,5931 ,0,0,0}, {7012,7013,7014 ,5948,5949,5953 ,0,0,0}, + {6971,6973,7013 ,5899,5901,5949 ,0,0,0}, {7015,7022,7016 ,5955,5965,5958 ,0,0,0}, + {7000,6999,7020 ,5936,5935,5963 ,0,0,0}, {7016,7021,7024 ,5958,5964,5967 ,0,0,0}, + {7022,6999,6996 ,5965,5935,5931 ,0,0,0}, {7027,7024,7021 ,5970,5967,5964 ,0,0,0}, + {6977,7018,7019 ,5907,5961,5962 ,0,0,0}, {6984,6986,7025 ,5917,5919,5968 ,0,0,0}, + {7028,6990,7029 ,5971,5923,5972 ,0,0,0}, {7019,7026,6993 ,5962,5969,5926 ,0,0,0}, + {7030,7026,6986 ,5973,5969,5919 ,0,0,0}, {7000,6973,7001 ,5936,5901,5937 ,0,0,0}, + {7030,6976,6972 ,5973,5905,5900 ,0,0,0}, {7031,6994,7008 ,5974,5929,5944 ,0,0,0}, + {7020,6999,7022 ,5963,5935,5965 ,0,0,0}, {7013,7000,7020 ,5949,5936,5963 ,0,0,0}, + {7000,7001,6998 ,5936,5937,5934 ,0,0,0}, {6995,6994,7032 ,5930,5929,5975 ,0,0,0}, + {6998,7008,6999 ,5934,5944,5935 ,0,0,0}, {7021,6995,7027 ,5964,5930,5970 ,0,0,0}, + {6996,7008,6994 ,5931,5944,5929 ,0,0,0}, {7033,7027,6995 ,5976,5970,5930 ,0,0,0}, + {7018,6986,7026 ,5961,5919,5969 ,0,0,0}, {6991,6985,6984 ,5924,5918,5917 ,0,0,0}, + {6976,7034,7001 ,5905,5977,5937 ,0,0,0}, {7026,7030,6972 ,5969,5973,5900 ,0,0,0}, + {7035,7030,6985 ,5978,5973,5918 ,0,0,0}, {7001,7036,6998 ,5937,5979,5934 ,0,0,0}, + {7035,7034,6976 ,5978,5977,5905 ,0,0,0}, {6998,7037,7008 ,5934,5980,5944 ,0,0,0}, + {7036,7001,7034 ,5979,5937,5977 ,0,0,0}, {6994,7003,7032 ,5929,5939,5975 ,0,0,0}, + {7037,6998,7036 ,5980,5934,5979 ,0,0,0}, {7038,7032,7002 ,5981,5975,5938 ,0,0,0}, + {7031,7008,7037 ,5974,5944,5980 ,0,0,0}, {6995,7032,7033 ,5930,5975,5976 ,0,0,0}, + {6994,7031,7003 ,5929,5974,5939 ,0,0,0}, {7038,7033,7032 ,5981,5976,5975 ,0,0,0}, + {6986,6985,7030 ,5919,5918,5973 ,0,0,0}, {7029,6990,6991 ,5972,5923,5924 ,0,0,0}, + {7034,6987,7036 ,5977,5920,5979 ,0,0,0}, {7030,7035,6976 ,5973,5978,5905 ,0,0,0}, + {6990,7039,7035 ,5923,5982,5978 ,0,0,0}, {7036,6989,7037 ,5979,5922,5980 ,0,0,0}, + {7039,6987,7034 ,5982,5920,5977 ,0,0,0}, {7037,7040,7031 ,5980,5983,5974 ,0,0,0}, + {6987,6989,7036 ,5920,5922,5979 ,0,0,0}, {7041,7003,7031 ,5984,5939,5974 ,0,0,0}, + {7040,7037,6989 ,5983,5980,5922 ,0,0,0}, {7042,7002,7007 ,5985,5938,5943 ,0,0,0}, + {7031,7040,7041 ,5974,5983,5984 ,0,0,0}, {7041,7004,7003 ,5984,5940,5939 ,0,0,0}, + {7038,7002,7042 ,5981,5938,5985 ,0,0,0}, {7032,7003,7002 ,5975,5939,5938 ,0,0,0}, + {6985,6990,7035 ,5918,5923,5978 ,0,0,0}, {7043,7028,7029 ,5986,5971,5972 ,0,0,0}, + {7044,7040,6989 ,5987,5983,5922 ,0,0,0}, {7035,7039,7034 ,5978,5982,5977 ,0,0,0}, + {7028,6983,7039 ,5971,5914,5982 ,0,0,0}, {7045,7041,7040 ,5988,5984,5983 ,0,0,0}, + {6983,6988,6987 ,5914,5921,5920 ,0,0,0}, {7046,7004,7041 ,5989,5940,5984 ,0,0,0}, + {6988,7044,6989 ,5921,5987,5922 ,0,0,0}, {7011,7005,7047 ,5947,5941,5990 ,0,0,0}, + {7044,7045,7040 ,5987,5988,5983 ,0,0,0}, {7007,7004,7048 ,5943,5940,5991 ,0,0,0}, + {7046,7041,7045 ,5989,5984,5988 ,0,0,0}, {7048,7004,7046 ,5991,5940,5989 ,0,0,0}, + {7042,7007,7006 ,5985,5943,5942 ,0,0,0}, {7002,7004,7007 ,5938,5940,5943 ,0,0,0}, + {6990,7028,7039 ,5923,5971,5982 ,0,0,0}, {6981,7043,6997 ,5912,5986,5932 ,0,0,0}, + {6982,7049,6988 ,5913,5992,5921 ,0,0,0}, {7039,6983,6987 ,5982,5914,5920 ,0,0,0}, + {6982,6988,6983 ,5913,5921,5914 ,0,0,0}, {7049,7050,7044 ,5992,5993,5987 ,0,0,0}, + {7049,7044,6988 ,5992,5987,5921 ,0,0,0}, {7050,7051,7045 ,5993,5994,5988 ,0,0,0}, + {7050,7045,7044 ,5993,5988,5987 ,0,0,0}, {7051,7052,7046 ,5994,5995,5989 ,0,0,0}, + {7051,7046,7045 ,5994,5989,5988 ,0,0,0}, {7052,7047,7048 ,5995,5990,5991 ,0,0,0}, + {7048,7046,7052 ,5991,5989,5995 ,0,0,0}, {7047,7005,7048 ,5990,5941,5991 ,0,0,0}, + {7006,7005,7010 ,5942,5941,5946 ,0,0,0}, {7007,7048,7005 ,5943,5991,5941 ,0,0,0}, + {7043,6981,7028 ,5986,5912,5971 ,0,0,0}, {6983,7028,6981 ,5914,5971,5912 ,0,0,0}, + {7049,6208,6308 ,5992,5928,5996 ,0,0,0}, {6289,6982,6981 ,5927,5913,5912 ,0,0,0}, + {7050,6308,6513 ,5993,5996,5997 ,0,0,0}, {6208,7049,6982 ,5928,5992,5913 ,0,0,0}, + {7051,6513,6315 ,5994,5997,5998 ,0,0,0}, {6308,7050,7049 ,5996,5993,5992 ,0,0,0}, + {7052,6315,6326 ,5995,5998,5999 ,0,0,0}, {6513,7051,7050 ,5997,5994,5993 ,0,0,0}, + {7047,6326,6312 ,5990,5999,6000 ,0,0,0}, {6315,7052,7051 ,5998,5995,5994 ,0,0,0}, + {7011,6312,6318 ,5947,6000,5950 ,0,0,0}, {6326,7047,7052 ,5999,5990,5995 ,0,0,0}, + {6318,7009,7011 ,5950,5945,5947 ,0,0,0}, {6312,7011,7047 ,6000,5947,5990 ,0,0,0}, + {7053,7054,7055 ,6001,6002,6003 ,0,0,0}, {7056,5743,5740 ,6004,6005,6006 ,0,0,0}, + {7055,7057,7058 ,6003,6007,6008 ,0,0,0}, {7057,7059,7058 ,6007,6009,6008 ,0,0,0}, + {7060,7061,7062 ,6010,6011,6012 ,0,0,0}, {7062,7063,7060 ,6012,6013,6010 ,0,0,0}, + {7064,7065,7066 ,6014,6015,6016 ,0,0,0}, {7067,7061,5746 ,6017,6011,6018 ,0,0,0}, + {7067,7062,7061 ,6017,6012,6011 ,0,0,0}, {5746,5745,7067 ,6018,5020,6017 ,0,0,0}, + {7068,5740,5748 ,6019,6006,6020 ,0,0,0}, {7069,7070,7071 ,6021,6022,6023 ,0,0,0}, + {7064,6263,6279 ,6014,6024,6025 ,0,0,0}, {7072,7073,7074 ,6026,6027,6028 ,0,0,0}, + {7075,6266,7066 ,6029,6030,6016 ,0,0,0}, {7076,7077,7070 ,6031,6032,6022 ,0,0,0}, + {6263,7066,6266 ,6024,6016,6030 ,0,0,0}, {7078,7079,7080 ,6033,6034,6035 ,0,0,0}, + {7081,7058,7059 ,6036,6008,6009 ,0,0,0}, {7082,7083,7084 ,6037,6038,6039 ,0,0,0}, + {7085,7086,7055 ,6040,6041,6003 ,0,0,0}, {7087,7088,7089 ,6042,6043,6044 ,0,0,0}, + {7080,7090,7091 ,6035,6045,6046 ,0,0,0}, {7092,7090,7093 ,6047,6045,6048 ,0,0,0}, + {7094,7095,7096 ,6049,6050,6051 ,0,0,0}, {7053,5743,7056 ,6001,6005,6004 ,0,0,0}, + {7095,7082,7096 ,6050,6037,6051 ,0,0,0}, {7086,5732,7053 ,6041,6052,6001 ,0,0,0}, + {6282,6284,7094 ,6053,6054,6049 ,0,0,0}, {7097,5733,7086 ,6055,6056,6041 ,0,0,0}, + {5732,5743,7053 ,6052,6005,6001 ,0,0,0}, {7097,7098,5735 ,6055,6057,6058 ,0,0,0}, + {7086,5733,5732 ,6041,6056,6052 ,0,0,0}, {5729,7099,5730 ,6059,6060,6061 ,0,0,0}, + {5733,7097,5735 ,6056,6055,6058 ,0,0,0}, {5721,5730,7100 ,6062,6061,6063 ,0,0,0}, + {7099,5729,7098 ,6060,6059,6057 ,0,0,0}, {5748,7061,7068 ,6020,6011,6019 ,0,0,0}, + {7061,5748,5746 ,6011,6020,6018 ,0,0,0}, {7063,7101,7060 ,6013,6064,6010 ,0,0,0}, + {7068,7056,5740 ,6019,6004,6006 ,0,0,0}, {7102,7068,7060 ,6065,6019,6010 ,0,0,0}, + {7055,7054,7057 ,6003,6002,6007 ,0,0,0}, {7102,7054,7056 ,6065,6002,6004 ,0,0,0}, + {7097,7103,7098 ,6055,6066,6057 ,0,0,0}, {7056,7054,7053 ,6004,6002,6001 ,0,0,0}, + {7104,7105,7099 ,6067,6068,6060 ,0,0,0}, {7086,7053,7055 ,6041,6001,6003 ,0,0,0}, + {7103,7097,7085 ,6066,6055,6040 ,0,0,0}, {5730,7099,7100 ,6061,6060,6063 ,0,0,0}, + {5735,7098,5729 ,6058,6057,6059 ,0,0,0}, {7098,7103,7104 ,6057,6066,6067 ,0,0,0}, + {7106,7100,7099 ,6069,6063,6060 ,0,0,0}, {7061,7060,7068 ,6011,6010,6019 ,0,0,0}, + {7107,7101,7063 ,6070,6064,6013 ,0,0,0}, {7107,7076,7101 ,6070,6031,6064 ,0,0,0}, + {7068,7102,7056 ,6019,6065,6004 ,0,0,0}, {7101,7108,7102 ,6064,6071,6065 ,0,0,0}, + {7058,7093,7085 ,6008,6048,6040 ,0,0,0}, {7108,7057,7054 ,6071,6007,6002 ,0,0,0}, + {7080,7105,7104 ,6035,6068,6067 ,0,0,0}, {7079,7105,7080 ,6034,6068,6035 ,0,0,0}, + {7086,7085,7097 ,6041,6040,6055 ,0,0,0}, {7055,7058,7085 ,6003,6008,6040 ,0,0,0}, + {7098,7104,7099 ,6057,6067,6060 ,0,0,0}, {7093,7090,7103 ,6048,6045,6066 ,0,0,0}, + {7099,7105,7106 ,6060,6068,6069 ,0,0,0}, {7104,7090,7080 ,6067,6045,6035 ,0,0,0}, + {7109,7106,7105 ,6072,6069,6068 ,0,0,0}, {7060,7101,7102 ,6010,6064,6065 ,0,0,0}, + {7077,7076,7107 ,6032,6031,6070 ,0,0,0}, {7110,7069,7111 ,6073,6021,6074 ,0,0,0}, + {7102,7108,7054 ,6065,6071,6002 ,0,0,0}, {7112,7108,7076 ,6075,6071,6031 ,0,0,0}, + {7093,7058,7081 ,6048,6008,6036 ,0,0,0}, {7112,7059,7057 ,6075,6009,6007 ,0,0,0}, + {7113,7078,7091 ,6076,6033,6046 ,0,0,0}, {7103,7090,7104 ,6066,6045,6067 ,0,0,0}, + {7085,7093,7103 ,6040,6048,6066 ,0,0,0}, {7093,7081,7092 ,6048,6036,6047 ,0,0,0}, + {7079,7078,7114 ,6034,6033,6077 ,0,0,0}, {7092,7091,7090 ,6047,6046,6045 ,0,0,0}, + {7105,7079,7109 ,6068,6034,6072 ,0,0,0}, {7080,7091,7078 ,6035,6046,6033 ,0,0,0}, + {7115,7109,7079 ,6078,6072,6034 ,0,0,0}, {7101,7076,7108 ,6064,6031,6071 ,0,0,0}, + {7071,7070,7077 ,6023,6022,6032 ,0,0,0}, {7059,7116,7081 ,6009,6079,6036 ,0,0,0}, + {7108,7112,7057 ,6071,6075,6007 ,0,0,0}, {7117,7112,7070 ,6080,6075,6022 ,0,0,0}, + {7081,7118,7092 ,6036,6081,6047 ,0,0,0}, {7117,7116,7059 ,6080,6079,6009 ,0,0,0}, + {7092,7119,7091 ,6047,6082,6046 ,0,0,0}, {7118,7081,7116 ,6081,6036,6079 ,0,0,0}, + {7078,7088,7114 ,6033,6043,6077 ,0,0,0}, {7119,7092,7118 ,6082,6047,6081 ,0,0,0}, + {7120,7114,7087 ,6083,6077,6042 ,0,0,0}, {7113,7091,7119 ,6076,6046,6082 ,0,0,0}, + {7079,7114,7115 ,6034,6077,6078 ,0,0,0}, {7078,7113,7088 ,6033,6076,6043 ,0,0,0}, + {7120,7115,7114 ,6083,6078,6077 ,0,0,0}, {7076,7070,7112 ,6031,6022,6075 ,0,0,0}, + {7111,7069,7071 ,6074,6021,6023 ,0,0,0}, {7116,7073,7118 ,6079,6027,6081 ,0,0,0}, + {7112,7117,7059 ,6075,6080,6009 ,0,0,0}, {7069,7121,7117 ,6021,6084,6080 ,0,0,0}, + {7118,7072,7119 ,6081,6026,6082 ,0,0,0}, {7121,7073,7116 ,6084,6027,6079 ,0,0,0}, + {7119,7122,7113 ,6082,6085,6076 ,0,0,0}, {7073,7072,7118 ,6027,6026,6081 ,0,0,0}, + {7123,7088,7113 ,6086,6043,6076 ,0,0,0}, {7122,7119,7072 ,6085,6082,6026 ,0,0,0}, + {7124,7087,7084 ,6087,6042,6039 ,0,0,0}, {7113,7122,7123 ,6076,6085,6086 ,0,0,0}, + {7123,7089,7088 ,6086,6044,6043 ,0,0,0}, {7120,7087,7124 ,6083,6042,6087 ,0,0,0}, + {7114,7088,7087 ,6077,6043,6042 ,0,0,0}, {7070,7069,7117 ,6022,6021,6080 ,0,0,0}, + {7125,7110,7111 ,6088,6073,6074 ,0,0,0}, {7126,7122,7072 ,6089,6085,6026 ,0,0,0}, + {7117,7121,7116 ,6080,6084,6079 ,0,0,0}, {7110,7065,7121 ,6073,6015,6084 ,0,0,0}, + {7127,7123,7122 ,6090,6086,6085 ,0,0,0}, {7065,7074,7073 ,6015,6028,6027 ,0,0,0}, + {7128,7089,7123 ,6091,6044,6086 ,0,0,0}, {7074,7126,7072 ,6028,6089,6026 ,0,0,0}, + {7096,7082,7129 ,6051,6037,6092 ,0,0,0}, {7126,7127,7122 ,6089,6090,6085 ,0,0,0}, + {7084,7089,7130 ,6039,6044,6093 ,0,0,0}, {7128,7123,7127 ,6091,6086,6090 ,0,0,0}, + {7130,7089,7128 ,6093,6044,6091 ,0,0,0}, {7124,7084,7083 ,6087,6039,6038 ,0,0,0}, + {7087,7089,7084 ,6042,6044,6039 ,0,0,0}, {7069,7110,7121 ,6021,6073,6084 ,0,0,0}, + {7066,7125,7075 ,6016,6088,6029 ,0,0,0}, {7064,7131,7074 ,6014,6094,6028 ,0,0,0}, + {7121,7065,7073 ,6084,6015,6027 ,0,0,0}, {7064,7074,7065 ,6014,6028,6015 ,0,0,0}, + {7131,7132,7126 ,6094,6095,6089 ,0,0,0}, {7131,7126,7074 ,6094,6089,6028 ,0,0,0}, + {7132,7133,7127 ,6095,6096,6090 ,0,0,0}, {7132,7127,7126 ,6095,6090,6089 ,0,0,0}, + {7133,7134,7128 ,6096,6097,6091 ,0,0,0}, {7133,7128,7127 ,6096,6091,6090 ,0,0,0}, + {7134,7129,7130 ,6097,6092,6093 ,0,0,0}, {7130,7128,7134 ,6093,6091,6097 ,0,0,0}, + {7129,7082,7130 ,6092,6037,6093 ,0,0,0}, {7083,7082,7095 ,6038,6037,6050 ,0,0,0}, + {7084,7130,7082 ,6039,6093,6037 ,0,0,0}, {7125,7066,7110 ,6088,6016,6073 ,0,0,0}, + {7065,7110,7066 ,6015,6073,6016 ,0,0,0}, {7131,6279,6273 ,6094,6025,6098 ,0,0,0}, + {6263,7064,7066 ,6024,6014,6016 ,0,0,0}, {7132,6273,6277 ,6095,6098,6099 ,0,0,0}, + {6279,7131,7064 ,6025,6094,6014 ,0,0,0}, {7133,6277,6276 ,6096,6099,6100 ,0,0,0}, + {6273,7132,7131 ,6098,6095,6094 ,0,0,0}, {7134,6276,6286 ,6097,6100,6101 ,0,0,0}, + {6277,7133,7132 ,6099,6096,6095 ,0,0,0}, {7129,6286,6248 ,6092,6101,6102 ,0,0,0}, + {6276,7134,7133 ,6100,6097,6096 ,0,0,0}, {7096,6248,6282 ,6051,6102,6053 ,0,0,0}, + {6286,7129,7134 ,6101,6092,6097 ,0,0,0}, {6282,7094,7096 ,6053,6049,6051 ,0,0,0}, + {6248,7096,7129 ,6102,6051,6092 ,0,0,0}, {7135,7136,7137 ,730,6103,6103 ,0,0,0}, + {5365,5307,5304 ,6103,730,730 ,0,0,0}, {7138,7136,7139 ,6104,6103,6105 ,0,0,0}, + {7138,7140,7141 ,6104,6106,6103 ,0,0,0}, {7142,7137,7143 ,6107,6103,6108 ,0,0,0}, + {7140,7144,7145 ,6106,6109,6110 ,0,0,0}, {7146,7147,7143 ,6103,6111,6108 ,0,0,0}, + {7145,7148,7149 ,6110,6112,6110 ,0,0,0}, {7150,7146,7151 ,6111,6103,6103 ,0,0,0}, + {7149,7152,7153 ,6110,6113,6112 ,0,0,0}, {7153,7154,7155 ,6112,6109,6110 ,0,0,0}, + {7155,7156,7157 ,6110,6106,6114 ,0,0,0}, {7151,7158,7159 ,6103,730,6115 ,0,0,0}, + {7160,7157,7161 ,6105,6114,6104 ,0,0,0}, {7162,7163,7164 ,6111,730,6111 ,0,0,0}, + {7165,7157,7160 ,6111,6114,6105 ,0,0,0}, {7164,7166,7167 ,6111,6110,6114 ,0,0,0}, + {7168,7169,7170 ,730,6114,6108 ,0,0,0}, {5313,5378,5380 ,6110,6111,6110 ,0,0,0}, + {7171,7172,7173 ,6115,730,6111 ,0,0,0}, {5377,5312,5375 ,730,730,6114 ,0,0,0}, + {7174,7175,5296 ,6111,6110,6110 ,0,0,0}, {5308,5371,5310 ,730,6114,6103 ,0,0,0}, + {5293,5343,5340 ,730,730,6114 ,0,0,0}, {5307,5366,5369 ,730,730,6103 ,0,0,0}, + {5337,5289,5338 ,6114,730,730 ,0,0,0}, {5363,5365,5304 ,730,6103,730 ,0,0,0}, + {5287,5331,5284 ,6103,6103,730 ,0,0,0}, {5357,5359,5298 ,730,730,730 ,0,0,0}, + {5325,5322,5283 ,730,730,730 ,0,0,0}, {5351,5297,5277 ,730,730,730 ,0,0,0}, + {5281,5320,5319 ,730,730,730 ,0,0,0}, {5281,5282,5320 ,730,730,730 ,0,0,0}, + {5283,5322,5282 ,730,730,730 ,0,0,0}, {5351,5277,5315 ,730,730,730 ,0,0,0}, + {5277,5281,5316 ,730,730,730 ,0,0,0}, {5326,5284,5328 ,6103,730,730 ,0,0,0}, + {5283,5284,5326 ,730,730,6103 ,0,0,0}, {5297,5354,5298 ,730,730,730 ,0,0,0}, + {5297,5353,5354 ,730,730,730 ,0,0,0}, {5287,5289,5334 ,6103,730,6103 ,0,0,0}, + {5287,5334,5332 ,6103,6103,730 ,0,0,0}, {5304,5302,5360 ,730,730,6103 ,0,0,0}, + {5359,5302,5298 ,730,730,730 ,0,0,0}, {5293,5340,5290 ,730,6114,6103 ,0,0,0}, + {5289,5290,5338 ,730,6103,730 ,0,0,0}, {5307,5365,5366 ,730,6103,730 ,0,0,0}, + {5346,5344,5296 ,6110,6111,6110 ,0,0,0}, {5293,5296,5344 ,730,6110,6111 ,0,0,0}, + {5308,5369,5371 ,730,6103,6114 ,0,0,0}, {5307,5369,5308 ,730,6103,730 ,0,0,0}, + {7173,7176,7174 ,6111,6111,6111 ,0,0,0}, {7177,7174,7176 ,6114,6111,6111 ,0,0,0}, + {5371,5372,5310 ,6114,730,6103 ,0,0,0}, {5310,5375,5312 ,6103,6114,730 ,0,0,0}, + {5372,5375,5310 ,730,6114,6103 ,0,0,0}, {5377,5378,5312 ,730,6111,730 ,0,0,0}, + {7178,7170,7169 ,6107,6108,6114 ,0,0,0}, {5313,5312,5378 ,6110,730,6111 ,0,0,0}, + {5380,7166,5313 ,6110,6110,6110 ,0,0,0}, {7169,7165,7179 ,6114,6111,730 ,0,0,0}, + {7180,7181,7168 ,6111,6110,730 ,0,0,0}, {7181,7171,7173 ,6110,6115,6111 ,0,0,0}, + {7154,7156,7155 ,6109,6106,6110 ,0,0,0}, {5363,5304,5360 ,730,730,6103 ,0,0,0}, + {5360,5302,5359 ,6103,730,730 ,0,0,0}, {5357,5298,5354 ,730,730,730 ,0,0,0}, + {5353,5297,5351 ,730,730,730 ,0,0,0}, {5315,5277,5316 ,730,730,730 ,0,0,0}, + {5316,5281,5319 ,730,730,730 ,0,0,0}, {5320,5282,5322 ,730,730,730 ,0,0,0}, + {5325,5283,5326 ,730,730,6103 ,0,0,0}, {5328,5284,5331 ,730,730,6103 ,0,0,0}, + {5331,5287,5332 ,6103,6103,730 ,0,0,0}, {5334,5289,5337 ,6103,730,6114 ,0,0,0}, + {5338,5290,5340 ,730,6103,6114 ,0,0,0}, {5343,5293,5344 ,730,730,6111 ,0,0,0}, + {5346,5296,7175 ,6110,6110,6110 ,0,0,0}, {7175,7174,7177 ,6110,6111,6114 ,0,0,0}, + {7176,7173,7172 ,6111,6111,730 ,0,0,0}, {7171,7181,7180 ,6115,6110,6111 ,0,0,0}, + {7182,7168,7170 ,6111,730,6108 ,0,0,0}, {7168,7182,7180 ,730,6111,6111 ,0,0,0}, + {7178,7169,7179 ,6107,6114,730 ,0,0,0}, {7179,7165,7160 ,730,6111,6105 ,0,0,0}, + {7161,7157,7156 ,6104,6114,6106 ,0,0,0}, {7155,7149,7153 ,6110,6110,6112 ,0,0,0}, + {7152,7149,7148 ,6113,6110,6112 ,0,0,0}, {7148,7145,7144 ,6112,6110,6109 ,0,0,0}, + {7140,7145,7141 ,6106,6110,6103 ,0,0,0}, {7138,7141,7136 ,6104,6103,6103 ,0,0,0}, + {7135,7139,7136 ,730,6105,6103 ,0,0,0}, {7142,7135,7137 ,6107,730,6103 ,0,0,0}, + {7146,7143,7137 ,6103,6108,6103 ,0,0,0}, {7146,7150,7147 ,6103,6111,6111 ,0,0,0}, + {7151,7159,7150 ,6103,6115,6111 ,0,0,0}, {7151,7163,7158 ,6103,730,730 ,0,0,0}, + {7162,7164,7167 ,6111,6111,6114 ,0,0,0}, {7158,7163,7162 ,730,730,6111 ,0,0,0}, + {7166,7164,5313 ,6110,6111,6110 ,0,0,0}, {5349,5317,7183 ,6116,6117,6118 ,0,0,0}, + {5352,7184,7185 ,6119,6120,6121 ,0,0,0}, {7186,7187,5504 ,6122,6123,6124 ,0,0,0}, + {5594,5364,5591 ,6125,6126,6127 ,0,0,0}, {5520,5519,5931 ,6128,6129,6130 ,0,0,0}, + {5450,5453,5374 ,6131,6132,6122 ,0,0,0}, {7188,5455,7189 ,6133,6134,6135 ,0,0,0}, + {7190,7191,7192 ,6136,6137,6138 ,0,0,0}, {5321,5401,5404 ,6122,6120,6139 ,0,0,0}, + {7187,5489,5494 ,6123,6140,6141 ,0,0,0}, {7193,5572,5574 ,6139,6142,6143 ,0,0,0}, + {5844,7194,5845 ,6144,6145,6146 ,0,0,0}, {5902,7195,5895 ,6147,6148,6149 ,0,0,0}, + {5422,7196,5425 ,6150,6144,6150 ,0,0,0}, {7197,5480,5879 ,6151,6134,6152 ,0,0,0}, + {7198,5381,7199 ,6145,6153,6154 ,0,0,0}, {7197,5879,7200 ,6151,6152,6155 ,0,0,0}, + {7201,5879,5878 ,6156,6152,6157 ,0,0,0}, {7202,7203,7204 ,6158,6144,6159 ,0,0,0}, + {7205,7206,7207 ,6160,6161,6162 ,0,0,0}, {5878,7208,7201 ,6157,6163,6156 ,0,0,0}, + {7209,7210,5878 ,6158,6164,6157 ,0,0,0}, {5884,7211,7209 ,6155,6165,6158 ,0,0,0}, + {7212,5889,7213 ,6166,6167,6116 ,0,0,0}, {5884,7209,5878 ,6155,6158,6157 ,0,0,0}, + {5896,7213,5889 ,6168,6116,6167 ,0,0,0}, {7204,7192,7191 ,6159,6138,6137 ,0,0,0}, + {7214,7215,7216 ,6122,6169,6170 ,0,0,0}, {7217,5884,5882 ,6171,6155,6172 ,0,0,0}, + {5882,7218,7217 ,6172,6118,6171 ,0,0,0}, {7219,7220,5892 ,6173,6174,6175 ,0,0,0}, + {5882,5881,7218 ,6172,6176,6118 ,0,0,0}, {5881,7220,7221 ,6176,6174,6177 ,0,0,0}, + {7222,5545,5544 ,6120,6146,6154 ,0,0,0}, {5881,5892,7220 ,6176,6175,6174 ,0,0,0}, + {7219,5892,5887 ,6173,6175,6178 ,0,0,0}, {7199,5383,7223 ,6154,6120,6145 ,0,0,0}, + {7224,7225,7226 ,6177,6179,6180 ,0,0,0}, {7227,7219,5887 ,6181,6173,6178 ,0,0,0}, + {7225,7228,7214 ,6179,6182,6122 ,0,0,0}, {7202,7229,7203 ,6158,6183,6144 ,0,0,0}, + {7216,7215,7230 ,6170,6169,6184 ,0,0,0}, {5896,5895,7231 ,6168,6149,6185 ,0,0,0}, + {7232,5329,7233 ,6186,6187,6119 ,0,0,0}, {5425,7234,5426 ,6150,6144,6188 ,0,0,0}, + {7235,5847,7236 ,6145,6144,6150 ,0,0,0}, {7229,5612,7237 ,6183,6189,6190 ,0,0,0}, + {5842,7238,7239 ,6154,6120,6127 ,0,0,0}, {5579,5578,5942 ,6191,6142,6192 ,0,0,0}, + {7184,5352,5350 ,6120,6119,6122 ,0,0,0}, {5936,5510,5509 ,6193,6194,6195 ,0,0,0}, + {5581,5837,5831 ,6196,6186,6197 ,0,0,0}, {5457,5379,5376 ,6196,6134,6138 ,0,0,0}, + {7187,5608,5603 ,6123,6198,6199 ,0,0,0}, {5374,5453,5376 ,6122,6132,6138 ,0,0,0}, + {5449,5450,5373 ,6157,6131,6137 ,0,0,0}, {5449,5373,5370 ,6157,6137,6131 ,0,0,0}, + {5368,5447,5370 ,6200,6143,6131 ,0,0,0}, {5356,5567,5585 ,6117,6201,6202 ,0,0,0}, + {7190,7240,7241 ,6136,6200,6156 ,0,0,0}, {5441,7242,5436 ,6118,6203,6132 ,0,0,0}, + {7243,5443,5445 ,6133,6204,6133 ,0,0,0}, {5373,5450,5374 ,6137,6131,6122 ,0,0,0}, + {5453,5457,5376 ,6132,6196,6138 ,0,0,0}, {5443,7244,5438 ,6204,6153,6201 ,0,0,0}, + {7245,5436,7242 ,6201,6132,6203 ,0,0,0}, {5358,5356,5585 ,6187,6117,6202 ,0,0,0}, + {5370,5447,5449 ,6131,6143,6157 ,0,0,0}, {5432,5862,5864 ,6132,6144,6205 ,0,0,0}, + {5445,5597,7243 ,6133,6201,6133 ,0,0,0}, {5368,5597,5447 ,6200,6201,6143 ,0,0,0}, + {5869,5431,5864 ,6206,6116,6205 ,0,0,0}, {5463,5869,5871 ,6207,6206,6204 ,0,0,0}, + {7246,7247,5437 ,6132,6119,6207 ,0,0,0}, {5862,5432,5436 ,6144,6132,6132 ,0,0,0}, + {5431,5869,5461 ,6116,6206,6121 ,0,0,0}, {5431,5432,5864 ,6116,6132,6205 ,0,0,0}, + {5872,5467,5871 ,6208,6207,6204 ,0,0,0}, {5463,5461,5869 ,6207,6121,6206 ,0,0,0}, + {5464,5463,5871 ,6209,6207,6204 ,0,0,0}, {5872,5874,5470 ,6208,6142,6196 ,0,0,0}, + {5467,5464,5871 ,6207,6209,6204 ,0,0,0}, {5469,5467,5872 ,6133,6207,6208 ,0,0,0}, + {5872,5470,5469 ,6208,6196,6133 ,0,0,0}, {5874,5473,5470 ,6142,6134,6196 ,0,0,0}, + {5877,5475,5874 ,6148,6131,6142 ,0,0,0}, {5874,5475,5473 ,6142,6131,6134 ,0,0,0}, + {5877,5476,5475 ,6148,6205,6131 ,0,0,0}, {5476,5877,5479 ,6205,6148,6204 ,0,0,0}, + {5877,5480,5479 ,6148,6134,6204 ,0,0,0}, {7201,7200,5879 ,6156,6155,6152 ,0,0,0}, + {7217,7211,5884 ,6171,6165,6155 ,0,0,0}, {7210,7208,5878 ,6164,6163,6157 ,0,0,0}, + {7218,5881,7221 ,6118,6176,6177 ,0,0,0}, {7212,7248,5887 ,6166,6210,6178 ,0,0,0}, + {7249,5901,7250 ,6157,6190,6211 ,0,0,0}, {7227,7251,7252 ,6181,6212,6182 ,0,0,0}, + {5493,7187,5494 ,6174,6123,6141 ,0,0,0}, {7253,7254,7187 ,6213,6214,6123 ,0,0,0}, + {5939,5936,5483 ,6215,6193,6216 ,0,0,0}, {5622,5624,5484 ,6217,6218,6219 ,0,0,0}, + {5509,5483,5936 ,6195,6216,6193 ,0,0,0}, {5514,5513,5928 ,6220,6221,6222 ,0,0,0}, + {5510,5935,5513 ,6194,6223,6221 ,0,0,0}, {5931,5519,5516 ,6130,6129,6181 ,0,0,0}, + {5516,5928,5931 ,6181,6222,6130 ,0,0,0}, {5525,5932,5526 ,6224,6225,6226 ,0,0,0}, + {5522,5931,5932 ,6227,6130,6225 ,0,0,0}, {5602,7187,5603 ,6212,6123,6199 ,0,0,0}, + {5533,7255,5534 ,6203,6228,6201 ,0,0,0}, {5624,5485,5484 ,6218,6229,6219 ,0,0,0}, + {7256,7257,7258 ,6230,6231,6232 ,0,0,0}, {5624,5625,5904 ,6218,6200,6233 ,0,0,0}, + {5525,5522,5932 ,6224,6227,6225 ,0,0,0}, {5932,5528,5526 ,6225,6234,6226 ,0,0,0}, + {5522,5520,5931 ,6227,6128,6130 ,0,0,0}, {5602,5601,7187 ,6212,6235,6123 ,0,0,0}, + {5514,5928,5516 ,6220,6222,6181 ,0,0,0}, {5935,5928,5513 ,6223,6222,6221 ,0,0,0}, + {5936,5935,5510 ,6193,6223,6194 ,0,0,0}, {5485,5939,5483 ,6229,6215,6216 ,0,0,0}, + {5939,5485,5904 ,6215,6229,6233 ,0,0,0}, {7254,5609,7187 ,6214,6236,6123 ,0,0,0}, + {5612,5609,7237 ,6189,6236,6190 ,0,0,0}, {7187,7259,7260 ,6123,6170,6214 ,0,0,0}, + {5501,7187,5497 ,6237,6123,6167 ,0,0,0}, {7186,7259,7187 ,6122,6170,6123 ,0,0,0}, + {5503,7261,7262 ,6238,6180,6179 ,0,0,0}, {7263,5540,7264 ,6197,6165,6196 ,0,0,0}, + {7265,5345,7266 ,6131,6122,6132 ,0,0,0}, {5508,7267,7261 ,6239,6240,6180 ,0,0,0}, + {7268,7269,7207 ,6171,6152,6162 ,0,0,0}, {5336,7270,5335 ,6204,6208,6126 ,0,0,0}, + {7271,7230,7272 ,6241,6184,6136 ,0,0,0}, {7273,5551,5554 ,6179,6179,6202 ,0,0,0}, + {5563,7270,5562 ,6127,6208,6242 ,0,0,0}, {5688,7274,7275 ,6156,6200,6136 ,0,0,0}, + {5691,5693,7276 ,6137,6135,6133 ,0,0,0}, {7277,7278,7279 ,6207,6133,6208 ,0,0,0}, + {5649,5682,5685 ,6196,6158,6159 ,0,0,0}, {5672,5642,5637 ,6181,6243,6139 ,0,0,0}, + {5656,5658,7280 ,6244,6245,6246 ,0,0,0}, {5635,7281,7282 ,6247,6190,6136 ,0,0,0}, + {7283,7257,7284 ,6248,6231,6170 ,0,0,0}, {7285,7286,5664 ,6152,6249,6250 ,0,0,0}, + {7287,7257,7283 ,6251,6231,6248 ,0,0,0}, {7288,7289,7290 ,6252,6253,6254 ,0,0,0}, + {7289,7256,7290 ,6253,6230,6254 ,0,0,0}, {7291,7292,7293 ,6255,6256,6257 ,0,0,0}, + {7294,7295,7296 ,6258,6259,6260 ,0,0,0}, {7289,7288,7296 ,6253,6252,6260 ,0,0,0}, + {7296,7295,7289 ,6260,6259,6253 ,0,0,0}, {7295,7294,7297 ,6259,6258,6261 ,0,0,0}, + {7298,7293,7299 ,6262,6257,6263 ,0,0,0}, {7297,7299,7295 ,6261,6263,6259 ,0,0,0}, + {7293,7292,7299 ,6257,6256,6263 ,0,0,0}, {7300,7301,7292 ,6264,6265,6256 ,0,0,0}, + {7297,7298,7299 ,6261,6262,6263 ,0,0,0}, {7291,7300,7292 ,6255,6264,6256 ,0,0,0}, + {7290,7256,7258 ,6254,6230,6232 ,0,0,0}, {7302,7303,5665 ,6138,6134,6266 ,0,0,0}, + {7258,7257,7287 ,6232,6231,6251 ,0,0,0}, {7284,7303,7302 ,6170,6134,6138 ,0,0,0}, + {7304,5658,5659 ,6267,6245,6268 ,0,0,0}, {5636,7282,7305 ,6167,6136,6199 ,0,0,0}, + {5653,5656,7281 ,6235,6244,6190 ,0,0,0}, {7306,5707,7307 ,6197,6164,6191 ,0,0,0}, + {5701,5700,7308 ,6171,6118,6269 ,0,0,0}, {5646,5643,5676 ,6270,6270,6174 ,0,0,0}, + {7306,5709,5707 ,6197,6163,6164 ,0,0,0}, {5681,5646,5676 ,6127,6270,6174 ,0,0,0}, + {7309,7241,7240 ,6137,6156,6200 ,0,0,0}, {7310,7311,7312 ,6213,6271,6169 ,0,0,0}, + {5670,5672,7313 ,6173,6181,6272 ,0,0,0}, {5712,5709,7306 ,6156,6163,6197 ,0,0,0}, + {7302,7314,7284 ,6138,6273,6170 ,0,0,0}, {7315,5713,5712 ,6201,6155,6156 ,0,0,0}, + {7315,5717,5715 ,6201,6134,6151 ,0,0,0}, {7316,7270,7317 ,6214,6208,6133 ,0,0,0}, + {7316,5330,5333 ,6214,6208,6117 ,0,0,0}, {7318,7319,7320 ,6190,6214,6199 ,0,0,0}, + {5707,5706,7307 ,6164,6158,6191 ,0,0,0}, {5701,7308,7307 ,6171,6269,6191 ,0,0,0}, + {7321,7322,7323 ,6274,6118,6183 ,0,0,0}, {7324,7325,7326 ,6149,6275,6214 ,0,0,0}, + {7327,7283,7314 ,6243,6248,6273 ,0,0,0}, {7327,7314,7328 ,6243,6273,6276 ,0,0,0}, + {7326,7216,7230 ,6214,6170,6184 ,0,0,0}, {7214,7228,7215 ,6122,6182,6169 ,0,0,0}, + {7226,7329,7224 ,6180,6244,6177 ,0,0,0}, {7225,7224,7228 ,6179,6177,6182 ,0,0,0}, + {7202,7330,5613 ,6158,6127,6249 ,0,0,0}, {5508,7329,7267 ,6239,6244,6240 ,0,0,0}, + {7226,7267,7329 ,6180,6240,6244 ,0,0,0}, {5508,7261,5505 ,6239,6180,6277 ,0,0,0}, + {7202,5613,5612 ,6158,6249,6189 ,0,0,0}, {5504,5503,7262 ,6124,6238,6179 ,0,0,0}, + {5503,5505,7261 ,6238,6277,6180 ,0,0,0}, {5631,5899,5907 ,6278,6279,6280 ,0,0,0}, + {5899,7250,5901 ,6279,6211,6190 ,0,0,0}, {7186,5504,7262 ,6122,6124,6179 ,0,0,0}, + {7331,7187,7260 ,6275,6123,6214 ,0,0,0}, {5504,7187,5501 ,6124,6123,6237 ,0,0,0}, + {5905,5628,5907 ,6281,6282,6280 ,0,0,0}, {5615,7330,7332 ,6283,6127,6174 ,0,0,0}, + {5613,7330,5615 ,6249,6127,6283 ,0,0,0}, {7203,7192,7204 ,6144,6138,6159 ,0,0,0}, + {7190,7241,7191 ,6136,6156,6137 ,0,0,0}, {7309,7188,7189 ,6137,6133,6135 ,0,0,0}, + {7188,7309,7240 ,6133,6137,6200 ,0,0,0}, {7188,5379,5455 ,6133,6134,6134 ,0,0,0}, + {5862,7245,5860 ,6144,6201,6209 ,0,0,0}, {5455,5379,5457 ,6134,6134,6196 ,0,0,0}, + {5597,5368,5596 ,6201,6200,6158 ,0,0,0}, {5361,5358,5588 ,6208,6187,6284 ,0,0,0}, + {5594,5596,5367 ,6125,6158,6204 ,0,0,0}, {7333,5857,5858 ,6191,6165,6179 ,0,0,0}, + {5855,7334,5832 ,6142,6172,6197 ,0,0,0}, {5579,5837,5581 ,6191,6186,6196 ,0,0,0}, + {5942,5837,5579 ,6192,6186,6191 ,0,0,0}, {5942,5578,5840 ,6192,6142,6285 ,0,0,0}, + {7335,5575,5572 ,6192,6228,6142 ,0,0,0}, {5401,5321,5323 ,6120,6122,6119 ,0,0,0}, + {5324,5399,5323 ,6171,6202,6119 ,0,0,0}, {7336,5852,5850 ,6150,6144,6150 ,0,0,0}, + {7196,5422,5420 ,6144,6150,6187 ,0,0,0}, {5428,5426,7234 ,6150,6188,6144 ,0,0,0}, + {5420,7337,7196 ,6187,6144,6144 ,0,0,0}, {5394,7232,7338 ,6165,6186,6286 ,0,0,0}, + {7337,5416,7339 ,6144,6192,6144 ,0,0,0}, {5414,5413,7339 ,6145,6145,6144 ,0,0,0}, + {7340,7341,7270 ,6143,6133,6208 ,0,0,0}, {7222,7342,5545 ,6120,6176,6146 ,0,0,0}, + {7265,5342,5345 ,6131,6137,6122 ,0,0,0}, {5348,5693,5692 ,6134,6135,6134 ,0,0,0}, + {7264,5535,5534 ,6196,6139,6201 ,0,0,0}, {7263,5541,5538 ,6197,6286,6165 ,0,0,0}, + {7273,5554,7343 ,6179,6202,6139 ,0,0,0}, {5557,7343,5556 ,6203,6139,6228 ,0,0,0}, + {5691,7276,7274 ,6137,6133,6200 ,0,0,0}, {7274,5688,5691 ,6200,6156,6137 ,0,0,0}, + {7344,7345,7346 ,6209,6207,6166 ,0,0,0}, {7347,5686,7275 ,6138,6137,6136 ,0,0,0}, + {7342,5547,5545 ,6176,6191,6146 ,0,0,0}, {7348,7349,7350 ,6186,6228,6287 ,0,0,0}, + {5541,7263,7222 ,6286,6197,6120 ,0,0,0}, {5541,7222,5544 ,6286,6120,6154 ,0,0,0}, + {5540,7263,5538 ,6165,6197,6165 ,0,0,0}, {5535,7264,5540 ,6139,6196,6165 ,0,0,0}, + {7255,5533,5551 ,6228,6203,6179 ,0,0,0}, {7255,7264,5534 ,6228,6196,6201 ,0,0,0}, + {5339,7270,5336 ,6200,6208,6204 ,0,0,0}, {7273,7255,5551 ,6179,6228,6179 ,0,0,0}, + {7351,7343,5557 ,6133,6139,6203 ,0,0,0}, {5556,7343,5554 ,6228,6139,6202 ,0,0,0}, + {5339,5341,7270 ,6200,6131,6208 ,0,0,0}, {7270,7352,5562 ,6208,6207,6242 ,0,0,0}, + {5347,5692,7353 ,6138,6134,6196 ,0,0,0}, {7270,5341,5342 ,6208,6131,6137 ,0,0,0}, + {7270,5333,5335 ,6208,6117,6126 ,0,0,0}, {5330,7316,7233 ,6208,6214,6119 ,0,0,0}, + {7270,7316,5333 ,6208,6214,6117 ,0,0,0}, {7198,5410,5381 ,6145,6120,6153 ,0,0,0}, + {7354,7355,5385 ,6201,6121,6288 ,0,0,0}, {5329,5330,7233 ,6187,6208,6119 ,0,0,0}, + {7356,5387,5389 ,6139,6192,6131 ,0,0,0}, {7223,5385,7355 ,6145,6288,6121 ,0,0,0}, + {5420,5419,7337 ,6187,6145,6144 ,0,0,0}, {5419,5416,7337 ,6145,6192,6144 ,0,0,0}, + {5413,5410,7198 ,6145,6120,6145 ,0,0,0}, {7355,7357,7223 ,6121,6289,6145 ,0,0,0}, + {7348,7357,7358 ,6186,6289,6191 ,0,0,0}, {7355,7358,7357 ,6121,6191,6289 ,0,0,0}, + {7348,7350,7342 ,6186,6287,6176 ,0,0,0}, {7348,7358,7349 ,6186,6191,6228 ,0,0,0}, + {5547,7342,7350 ,6191,6176,6287 ,0,0,0}, {7359,5350,5349 ,6202,6122,6116 ,0,0,0}, + {7360,7361,5830 ,6165,6191,6187 ,0,0,0}, {7362,5858,5860 ,6126,6179,6209 ,0,0,0}, + {7363,7238,5840 ,6154,6120,6285 ,0,0,0}, {5567,5356,7364 ,6201,6117,6120 ,0,0,0}, + {7365,7366,5569 ,6197,6201,6207 ,0,0,0}, {7185,7364,5355 ,6121,6120,6171 ,0,0,0}, + {5318,5406,5405 ,6116,6120,6201 ,0,0,0}, {7185,5355,5352 ,6121,6171,6119 ,0,0,0}, + {5358,5585,5588 ,6187,6202,6284 ,0,0,0}, {5588,5590,5361 ,6284,6140,6208 ,0,0,0}, + {5362,5590,5591 ,6117,6140,6127 ,0,0,0}, {5362,5591,5364 ,6117,6127,6126 ,0,0,0}, + {5364,5594,5367 ,6126,6125,6204 ,0,0,0}, {5368,5367,5596 ,6200,6204,6158 ,0,0,0}, + {5445,5447,5597 ,6133,6143,6201 ,0,0,0}, {5441,5437,7247 ,6118,6207,6119 ,0,0,0}, + {5443,7243,7244 ,6204,6133,6153 ,0,0,0}, {7246,5437,5438 ,6132,6207,6201 ,0,0,0}, + {7246,5438,7244 ,6132,6201,6153 ,0,0,0}, {7242,5441,7247 ,6203,6118,6119 ,0,0,0}, + {5436,7245,5862 ,6132,6201,6144 ,0,0,0}, {7362,5860,7245 ,6126,6209,6201 ,0,0,0}, + {7367,5857,7333 ,6242,6165,6191 ,0,0,0}, {7333,5858,7362 ,6191,6179,6126 ,0,0,0}, + {5855,7367,7368 ,6142,6242,6197 ,0,0,0}, {7367,5855,5857 ,6242,6142,6165 ,0,0,0}, + {7334,7360,5832 ,6172,6165,6197 ,0,0,0}, {7368,7334,5855 ,6197,6172,6142 ,0,0,0}, + {5830,7361,5831 ,6187,6191,6197 ,0,0,0}, {5832,7360,5830 ,6197,6165,6187 ,0,0,0}, + {5581,5831,7369 ,6196,6197,6202 ,0,0,0}, {5831,7361,7369 ,6197,6191,6202 ,0,0,0}, + {7229,7202,5612 ,6183,6158,6189 ,0,0,0}, {7332,7370,7371 ,6174,6118,6273 ,0,0,0}, + {5606,7187,5609 ,6290,6123,6236 ,0,0,0}, {7254,7237,5609 ,6214,6190,6236 ,0,0,0}, + {5606,5608,7187 ,6290,6198,6123 ,0,0,0}, {5498,7187,5493 ,6152,6123,6174 ,0,0,0}, + {5619,5622,5490 ,6124,6217,6291 ,0,0,0}, {5601,5489,7187 ,6235,6140,6123 ,0,0,0}, + {5619,5490,5489 ,6124,6291,6140 ,0,0,0}, {5619,5489,5601 ,6124,6140,6235 ,0,0,0}, + {5622,5484,5490 ,6217,6219,6291 ,0,0,0}, {5624,5904,5485 ,6218,6233,6229 ,0,0,0}, + {5625,5628,5905 ,6200,6282,6281 ,0,0,0}, {5625,5905,5904 ,6200,6281,6233 ,0,0,0}, + {5630,5631,5907 ,6269,6278,6280 ,0,0,0}, {5628,5630,5907 ,6282,6269,6280 ,0,0,0}, + {5899,5631,7372 ,6279,6278,6292 ,0,0,0}, {7372,7250,5899 ,6292,6211,6279 ,0,0,0}, + {7373,5901,7249 ,6293,6190,6157 ,0,0,0}, {5902,7373,7374 ,6147,6293,6266 ,0,0,0}, + {7373,5902,5901 ,6293,6147,6190 ,0,0,0}, {7195,7375,5895 ,6148,6273,6149 ,0,0,0}, + {7374,7195,5902 ,6266,6148,6147 ,0,0,0}, {7231,7376,5896 ,6185,6294,6168 ,0,0,0}, + {7375,7231,5895 ,6273,6185,6149 ,0,0,0}, {5887,5889,7212 ,6178,6167,6166 ,0,0,0}, + {7376,7213,5896 ,6294,6116,6168 ,0,0,0}, {7248,7227,5887 ,6210,6181,6178 ,0,0,0}, + {7252,7251,7370 ,6182,6212,6118 ,0,0,0}, {7248,7251,7227 ,6210,6212,6181 ,0,0,0}, + {7332,7371,5615 ,6174,6273,6283 ,0,0,0}, {7370,7251,7371 ,6118,6212,6273 ,0,0,0}, + {5637,7305,7313 ,6139,6199,6272 ,0,0,0}, {5668,7377,5697 ,6174,6295,6177 ,0,0,0}, + {7268,7327,7328 ,6171,6243,6276 ,0,0,0}, {5703,5701,7307 ,6165,6171,6191 ,0,0,0}, + {7377,5668,7378 ,6295,6174,6162 ,0,0,0}, {7313,5672,5637 ,6272,6181,6139 ,0,0,0}, + {5636,7305,5637 ,6167,6199,6139 ,0,0,0}, {5635,7282,5636 ,6247,6136,6167 ,0,0,0}, + {5653,7281,5635 ,6235,6190,6247 ,0,0,0}, {7280,7281,5656 ,6246,6190,6244 ,0,0,0}, + {7304,7280,5658 ,6267,6246,6245 ,0,0,0}, {5659,5662,7286 ,6268,6185,6249 ,0,0,0}, + {7286,7304,5659 ,6249,6267,6268 ,0,0,0}, {5665,7285,5664 ,6266,6152,6250 ,0,0,0}, + {5664,7286,5662 ,6250,6249,6185 ,0,0,0}, {5665,7303,7285 ,6266,6134,6152 ,0,0,0}, + {7283,7284,7314 ,6248,6170,6273 ,0,0,0}, {7271,7379,7230 ,6241,6296,6184 ,0,0,0}, + {7268,7328,7269 ,6171,6276,6152 ,0,0,0}, {7271,7272,7380 ,6241,6136,6200 ,0,0,0}, + {7380,7206,7205 ,6200,6161,6160 ,0,0,0}, {7205,7207,7269 ,6160,6162,6152 ,0,0,0}, + {7380,7272,7206 ,6200,6136,6161 ,0,0,0}, {7379,7324,7326 ,6296,6149,6214 ,0,0,0}, + {7326,7230,7379 ,6214,6184,6296 ,0,0,0}, {7311,7325,7324 ,6271,6275,6149 ,0,0,0}, + {7312,7319,7310 ,6169,6214,6213 ,0,0,0}, {7311,7310,7325 ,6271,6213,6275 ,0,0,0}, + {7320,7321,7318 ,6199,6274,6190 ,0,0,0}, {7312,7320,7319 ,6169,6199,6214 ,0,0,0}, + {7323,7322,7381 ,6183,6118,6144 ,0,0,0}, {7318,7321,7323 ,6190,6274,6183 ,0,0,0}, + {5649,7381,7322 ,6196,6144,6118 ,0,0,0}, {5324,5327,5398 ,6171,6117,6139 ,0,0,0}, + {7234,5430,5428 ,6144,6150,6150 ,0,0,0}, {7234,5425,7196 ,6144,6150,6144 ,0,0,0}, + {5395,5398,5327 ,6197,6139,6117 ,0,0,0}, {5329,7232,5395 ,6187,6186,6197 ,0,0,0}, + {7198,7339,5413 ,6145,6144,6145 ,0,0,0}, {5416,5414,7339 ,6192,6145,6144 ,0,0,0}, + {5383,5385,7223 ,6120,6288,6145 ,0,0,0}, {5381,5383,7199 ,6153,6120,6154 ,0,0,0}, + {5389,5394,7338 ,6131,6165,6286 ,0,0,0}, {5391,7382,7354 ,6144,6242,6201 ,0,0,0}, + {7354,5385,5391 ,6201,6288,6144 ,0,0,0}, {7338,7356,5389 ,6286,6139,6131 ,0,0,0}, + {5387,7356,7382 ,6192,6139,6242 ,0,0,0}, {5387,7382,5391 ,6192,6242,6144 ,0,0,0}, + {5394,5395,7232 ,6165,6197,6186 ,0,0,0}, {5327,5329,5395 ,6117,6187,6197 ,0,0,0}, + {5324,5398,5399 ,6171,6139,6202 ,0,0,0}, {5323,5399,5401 ,6119,6202,6120 ,0,0,0}, + {5406,5318,5404 ,6120,6116,6139 ,0,0,0}, {5321,5404,5318 ,6122,6139,6116 ,0,0,0}, + {5318,5405,5317 ,6116,6201,6117 ,0,0,0}, {5350,7359,7184 ,6122,6202,6120 ,0,0,0}, + {5317,5405,7183 ,6117,6201,6118 ,0,0,0}, {7359,5349,7183 ,6202,6116,6118 ,0,0,0}, + {7364,5356,5355 ,6120,6117,6171 ,0,0,0}, {7365,5568,7364 ,6197,6197,6120 ,0,0,0}, + {5567,7364,5568 ,6201,6120,6197 ,0,0,0}, {5575,7383,5578 ,6228,6145,6142 ,0,0,0}, + {5574,5569,7366 ,6143,6207,6201 ,0,0,0}, {5569,5568,7365 ,6207,6197,6197 ,0,0,0}, + {7335,5572,7193 ,6192,6142,6139 ,0,0,0}, {7193,5574,7366 ,6139,6143,6201 ,0,0,0}, + {5575,7335,7383 ,6228,6192,6145 ,0,0,0}, {7363,5840,5578 ,6154,6285,6142 ,0,0,0}, + {7363,5578,7383 ,6154,6142,6145 ,0,0,0}, {7238,5842,5840 ,6120,6154,6285 ,0,0,0}, + {5844,7239,7384 ,6144,6127,6187 ,0,0,0}, {7239,5844,5842 ,6127,6144,6154 ,0,0,0}, + {7384,7194,5844 ,6187,6145,6144 ,0,0,0}, {5845,7385,7236 ,6146,6145,6150 ,0,0,0}, + {7194,7385,5845 ,6145,6145,6146 ,0,0,0}, {5845,7236,5847 ,6146,6150,6144 ,0,0,0}, + {5850,5847,7386 ,6150,6144,6146 ,0,0,0}, {7235,7386,5847 ,6145,6146,6144 ,0,0,0}, + {5850,7387,7336 ,6150,6144,6150 ,0,0,0}, {5850,7386,7387 ,6150,6146,6144 ,0,0,0}, + {7388,5852,7389 ,6150,6144,6150 ,0,0,0}, {5852,7336,7389 ,6144,6150,6150 ,0,0,0}, + {5430,5852,7388 ,6150,6144,6150 ,0,0,0}, {7390,7391,7392 ,6131,6203,6207 ,0,0,0}, + {7347,7381,5685 ,6138,6144,6159 ,0,0,0}, {7315,5712,7306 ,6201,6156,6197 ,0,0,0}, + {7315,5715,5713 ,6201,6151,6155 ,0,0,0}, {7381,5649,5685 ,6144,6196,6159 ,0,0,0}, + {5670,7378,5668 ,6173,6162,6174 ,0,0,0}, {5697,7377,5700 ,6177,6295,6118 ,0,0,0}, + {5706,5703,7307 ,6158,6165,6191 ,0,0,0}, {7377,7308,5700 ,6295,6269,6118 ,0,0,0}, + {7378,5670,7313 ,6162,6173,6272 ,0,0,0}, {5672,5678,5642 ,6181,6182,6243 ,0,0,0}, + {5681,5682,5647 ,6127,6158,6297 ,0,0,0}, {5674,5640,5678 ,6118,6155,6182 ,0,0,0}, + {5642,5678,5640 ,6243,6182,6155 ,0,0,0}, {5674,5676,5643 ,6118,6174,6270 ,0,0,0}, + {5643,5640,5674 ,6270,6155,6118 ,0,0,0}, {5646,5681,5647 ,6270,6127,6297 ,0,0,0}, + {5649,5647,5682 ,6196,6297,6158 ,0,0,0}, {7347,5685,5686 ,6138,6159,6137 ,0,0,0}, + {7275,5686,5688 ,6136,6137,6156 ,0,0,0}, {7393,7394,7395 ,6205,6132,6116 ,0,0,0}, + {7394,7351,7396 ,6132,6133,6132 ,0,0,0}, {5342,7265,7270 ,6137,6131,6208 ,0,0,0}, + {7276,5693,5348 ,6133,6135,6134 ,0,0,0}, {5347,7353,7266 ,6138,6196,6132 ,0,0,0}, + {5347,5348,5692 ,6138,6134,6134 ,0,0,0}, {7266,5345,5347 ,6132,6122,6138 ,0,0,0}, + {7270,7265,7397 ,6208,6131,6157 ,0,0,0}, {7397,7340,7270 ,6157,6143,6208 ,0,0,0}, + {7396,5560,7398 ,6132,6172,6118 ,0,0,0}, {7399,7400,7270 ,6204,6201,6208 ,0,0,0}, + {7270,7401,7402 ,6208,6172,6214 ,0,0,0}, {7270,7400,7352 ,6208,6201,6207 ,0,0,0}, + {7401,7270,5563 ,6172,6208,6127 ,0,0,0}, {5562,7352,5560 ,6242,6207,6172 ,0,0,0}, + {7398,5560,7352 ,6118,6172,6207 ,0,0,0}, {7396,7351,5557 ,6132,6133,6203 ,0,0,0}, + {5557,5560,7396 ,6203,6172,6132 ,0,0,0}, {7394,7393,7351 ,6132,6205,6133 ,0,0,0}, + {7344,7395,7403 ,6209,6116,6121 ,0,0,0}, {7395,7344,7393 ,6116,6209,6205 ,0,0,0}, + {7403,7345,7344 ,6121,6207,6209 ,0,0,0}, {7346,7404,7277 ,6166,6209,6207 ,0,0,0}, + {7345,7404,7346 ,6207,6209,6166 ,0,0,0}, {7346,7277,7279 ,6166,6207,6208 ,0,0,0}, + {7392,7279,7405 ,6207,6208,6196 ,0,0,0}, {7278,7405,7279 ,6133,6196,6208 ,0,0,0}, + {7392,7406,7390 ,6207,6134,6131 ,0,0,0}, {7392,7405,7406 ,6207,6196,6134 ,0,0,0}, + {7407,7391,7408 ,6204,6203,6205 ,0,0,0}, {7391,7390,7408 ,6203,6131,6205 ,0,0,0}, + {5717,7391,7407 ,6134,6203,6204 ,0,0,0}, {7187,5498,5497 ,6123,6152,6167 ,0,0,0}, + {7187,7331,7253 ,6123,6275,6213 ,0,0,0}, {5590,5362,5361 ,6140,6117,6208 ,0,0,0}, + {7270,7341,7399 ,6208,6133,6204 ,0,0,0}, {7270,7402,7317 ,6208,6214,6133 ,0,0,0}, + {7409,6093,6092 ,6298,6299,6299 ,0,0,0}, {6098,7410,6099 ,6298,6298,6300 ,0,0,0}, + {7411,7412,5790 ,6301,6302,6302 ,0,0,0}, {6092,6089,7413 ,6299,6300,6303 ,0,0,0}, + {5787,7414,7415 ,6304,6304,6305 ,0,0,0}, {6083,7416,6086 ,6301,6299,6306 ,0,0,0}, + {5785,7417,7418 ,6305,6307,6308 ,0,0,0}, {7419,6080,6077 ,6298,6298,6309 ,0,0,0}, + {7420,5773,7421 ,6310,6311,6312 ,0,0,0}, {7422,7423,5779 ,6308,6313,6314 ,0,0,0}, + {5769,6193,7424 ,6315,6316,6317 ,0,0,0}, {7424,7425,5776 ,6317,6318,6319 ,0,0,0}, + {5764,6188,6190 ,6320,6321,6322 ,0,0,0}, {6148,5731,6146 ,6299,6303,6323 ,0,0,0}, + {6152,6154,5734 ,6324,6298,6306 ,0,0,0}, {5754,6178,6179 ,6325,6326,6327 ,0,0,0}, + {6155,6158,5742 ,6298,6328,6324 ,0,0,0}, {6170,6172,5751 ,6301,6329,6330 ,0,0,0}, + {6170,5825,6167 ,6301,6324,6331 ,0,0,0}, {5744,6164,6166 ,6332,6328,6333 ,0,0,0}, + {6164,5747,6161 ,6328,6334,6335 ,0,0,0}, {6173,5824,6172 ,6336,6298,6329 ,0,0,0}, + {6167,5752,6166 ,6331,6337,6333 ,0,0,0}, {5753,6176,6178 ,6338,6339,6326 ,0,0,0}, + {6173,6176,5756 ,6336,6339,6324 ,0,0,0}, {6158,6160,5738 ,6328,6328,6299 ,0,0,0}, + {6160,6161,5739 ,6328,6335,6340 ,0,0,0}, {5760,6182,6184 ,6341,6342,6343 ,0,0,0}, + {5762,6179,6182 ,6344,6327,6342 ,0,0,0}, {6184,6185,5758 ,6343,6345,6346 ,0,0,0}, + {6154,6155,5741 ,6298,6298,6347 ,0,0,0}, {6149,6152,5737 ,6348,6324,6316 ,0,0,0}, + {5766,6185,6188 ,6349,6345,6321 ,0,0,0}, {5765,6190,6191 ,6350,6322,6351 ,0,0,0}, + {5736,6149,5737 ,6324,6348,6316 ,0,0,0}, {5722,6143,5723 ,6300,6352,6353 ,0,0,0}, + {5771,6191,6193 ,6354,6351,6316 ,0,0,0}, {5719,6137,5720 ,6355,6299,6298 ,0,0,0}, + {6142,5728,6140 ,6299,6356,6357 ,0,0,0}, {7422,5781,7420 ,6308,6358,6310 ,0,0,0}, + {7425,7421,5772 ,6318,6312,6359 ,0,0,0}, {6075,6074,7426 ,6316,6306,6360 ,0,0,0}, + {7426,6074,5725 ,6360,6306,6299 ,0,0,0}, {7426,7427,6075 ,6360,6298,6316 ,0,0,0}, + {7423,7417,5777 ,6313,6307,6304 ,0,0,0}, {5784,7418,7428 ,6336,6308,6311 ,0,0,0}, + {5731,6148,5736 ,6303,6299,6324 ,0,0,0}, {7428,7414,5789 ,6311,6304,6314 ,0,0,0}, + {6083,6081,7429 ,6301,6300,6340 ,0,0,0}, {7430,6081,6080 ,6301,6300,6298 ,0,0,0}, + {7431,7411,5794 ,6301,6301,6333 ,0,0,0}, {5788,7415,7431 ,6361,6305,6301 ,0,0,0}, + {7432,6089,6087 ,6300,6300,6357 ,0,0,0}, {6086,7433,6087 ,6306,6355,6357 ,0,0,0}, + {7434,7435,5795 ,6353,6311,6301 ,0,0,0}, {5791,7412,7434 ,6362,6302,6353 ,0,0,0}, + {6095,6093,7436 ,6300,6299,6300 ,0,0,0}, {5796,7435,7437 ,6300,6311,6363 ,0,0,0}, + {5800,7437,7438 ,6301,6363,6353 ,0,0,0}, {5801,7438,7439 ,6300,6353,6328 ,0,0,0}, + {6095,7440,6098 ,6300,6300,6298 ,0,0,0}, {7441,5803,7439 ,6303,6352,6328 ,0,0,0}, + {7441,7442,5805 ,6303,6352,6340 ,0,0,0}, {7443,6101,6099 ,6299,6316,6300 ,0,0,0}, + {7444,5808,7442 ,6300,6340,6352 ,0,0,0}, {7445,6104,6101 ,6298,6364,6316 ,0,0,0}, + {5809,7444,7446 ,6316,6300,6306 ,0,0,0}, {7447,6105,6104 ,6364,6298,6364 ,0,0,0}, + {7446,7448,5811 ,6306,6340,6340 ,0,0,0}, {7449,6107,6105 ,6300,6300,6298 ,0,0,0}, + {7450,5814,7448 ,6323,6340,6340 ,0,0,0}, {7451,6110,6107 ,6298,6300,6300 ,0,0,0}, + {5816,7450,7452 ,6300,6323,6340 ,0,0,0}, {7453,6111,6110 ,6364,6300,6300 ,0,0,0}, + {7452,7454,5815 ,6340,6303,6303 ,0,0,0}, {7455,6113,6111 ,6300,6365,6300 ,0,0,0}, + {7456,5817,7454 ,6300,6300,6303 ,0,0,0}, {7457,6116,6113 ,6366,6300,6365 ,0,0,0}, + {5820,7456,7458 ,6300,6300,6316 ,0,0,0}, {7459,6117,6116 ,6367,6367,6300 ,0,0,0}, + {7458,7460,5821 ,6316,6300,6300 ,0,0,0}, {7461,6119,6117 ,6300,6300,6367 ,0,0,0}, + {7462,5821,7463 ,6301,6300,6300 ,0,0,0}, {7464,6122,6119 ,6368,6300,6300 ,0,0,0}, + {7465,7462,7466 ,6300,6301,6300 ,0,0,0}, {7467,6123,6122 ,6369,6367,6300 ,0,0,0}, + {7468,7465,7469 ,6316,6300,6300 ,0,0,0}, {6123,7470,6125 ,6367,6367,6300 ,0,0,0}, + {6128,6125,7471 ,6364,6300,6370 ,0,0,0}, {7472,6131,6129 ,6300,6316,6300 ,0,0,0}, + {7473,7468,7474 ,6300,6316,6316 ,0,0,0}, {7475,7476,7477 ,6300,6371,6300 ,0,0,0}, + {7478,7479,7480 ,6306,6300,6303 ,0,0,0}, {7481,7482,7483 ,6369,6300,6367 ,0,0,0}, + {7484,7485,7486 ,6301,6301,6300 ,0,0,0}, {7487,7488,7489 ,6300,6369,6367 ,0,0,0}, + {7490,7491,7492 ,6316,6316,6300 ,0,0,0}, {7493,7494,7495 ,6364,6300,6300 ,0,0,0}, + {7496,7487,7497 ,6364,6300,6316 ,0,0,0}, {7498,7499,7500 ,6300,6364,6316 ,0,0,0}, + {7495,7501,7500 ,6300,6316,6316 ,0,0,0}, {7502,7503,7504 ,6364,6372,6364 ,0,0,0}, + {7503,7496,7505 ,6372,6364,6300 ,0,0,0}, {7490,7499,7506 ,6316,6364,6367 ,0,0,0}, + {7507,7493,7502 ,6370,6364,6364 ,0,0,0}, {7483,7508,7509 ,6367,6367,6316 ,0,0,0}, + {7510,7488,7509 ,6316,6369,6316 ,0,0,0}, {7511,7484,7512 ,6306,6301,6303 ,0,0,0}, + {7512,7492,7513 ,6303,6300,6340 ,0,0,0}, {7514,7515,7477 ,6371,6300,6300 ,0,0,0}, + {7516,7481,7515 ,6300,6369,6300 ,0,0,0}, {7517,7478,7518 ,6300,6306,6300 ,0,0,0}, + {7517,7518,7486 ,6300,6300,6300 ,0,0,0}, {7519,7520,6131 ,6300,6300,6316 ,0,0,0}, + {7475,7520,7521 ,6300,6300,6316 ,0,0,0}, {7473,7522,7523 ,6300,6303,6301 ,0,0,0}, + {7479,7523,7524 ,6300,6301,6301 ,0,0,0}, {6129,6128,7525 ,6300,6364,6369 ,0,0,0}, + {6074,6073,5725 ,6306,6298,6299 ,0,0,0}, {5725,6073,6136 ,6299,6298,6340 ,0,0,0}, + {7427,7419,6077 ,6298,6298,6309 ,0,0,0}, {7427,6077,6075 ,6298,6309,6316 ,0,0,0}, + {7419,7430,6080 ,6298,6301,6298 ,0,0,0}, {7430,7429,6081 ,6301,6340,6300 ,0,0,0}, + {7429,7416,6083 ,6340,6299,6301 ,0,0,0}, {7416,7433,6086 ,6299,6355,6306 ,0,0,0}, + {7433,7432,6087 ,6355,6300,6357 ,0,0,0}, {7432,7413,6089 ,6300,6303,6300 ,0,0,0}, + {7413,7409,6092 ,6303,6298,6299 ,0,0,0}, {7409,7436,6093 ,6298,6300,6299 ,0,0,0}, + {7436,7440,6095 ,6300,6300,6300 ,0,0,0}, {7440,7410,6098 ,6300,6298,6298 ,0,0,0}, + {7410,7443,6099 ,6298,6299,6300 ,0,0,0}, {7443,7445,6101 ,6299,6298,6316 ,0,0,0}, + {7445,7447,6104 ,6298,6364,6364 ,0,0,0}, {7447,7449,6105 ,6364,6300,6298 ,0,0,0}, + {7449,7451,6107 ,6300,6298,6300 ,0,0,0}, {7451,7453,6110 ,6298,6364,6300 ,0,0,0}, + {7453,7455,6111 ,6364,6300,6300 ,0,0,0}, {7455,7457,6113 ,6300,6366,6365 ,0,0,0}, + {7457,7459,6116 ,6366,6367,6300 ,0,0,0}, {7459,7461,6117 ,6367,6300,6367 ,0,0,0}, + {7461,7464,6119 ,6300,6368,6300 ,0,0,0}, {7464,7467,6122 ,6368,6369,6300 ,0,0,0}, + {7467,7470,6123 ,6369,6367,6367 ,0,0,0}, {7470,7471,6125 ,6367,6370,6300 ,0,0,0}, + {7471,7525,6128 ,6370,6369,6364 ,0,0,0}, {7525,7472,6129 ,6369,6300,6300 ,0,0,0}, + {7472,7519,6131 ,6300,6300,6316 ,0,0,0}, {7519,7521,7520 ,6300,6316,6300 ,0,0,0}, + {7521,7476,7475 ,6316,6371,6300 ,0,0,0}, {7476,7514,7477 ,6371,6371,6300 ,0,0,0}, + {7514,7516,7515 ,6371,6300,6300 ,0,0,0}, {7516,7482,7481 ,6300,6300,6369 ,0,0,0}, + {7482,7508,7483 ,6300,6367,6367 ,0,0,0}, {7508,7510,7509 ,6367,6316,6316 ,0,0,0}, + {7510,7489,7488 ,6316,6367,6369 ,0,0,0}, {7489,7497,7487 ,6367,6316,6300 ,0,0,0}, + {7497,7505,7496 ,6316,6300,6364 ,0,0,0}, {7505,7504,7503 ,6300,6364,6372 ,0,0,0}, + {7504,7507,7502 ,6364,6370,6364 ,0,0,0}, {7507,7494,7493 ,6370,6300,6364 ,0,0,0}, + {7494,7501,7495 ,6300,6316,6300 ,0,0,0}, {7501,7498,7500 ,6316,6300,6316 ,0,0,0}, + {7498,7506,7499 ,6300,6367,6364 ,0,0,0}, {7506,7491,7490 ,6367,6316,6316 ,0,0,0}, + {7491,7513,7492 ,6316,6340,6300 ,0,0,0}, {7513,7511,7512 ,6340,6306,6303 ,0,0,0}, + {7511,7485,7484 ,6306,6301,6301 ,0,0,0}, {7485,7517,7486 ,6301,6300,6300 ,0,0,0}, + {7478,7480,7518 ,6306,6303,6300 ,0,0,0}, {7479,7524,7480 ,6300,6301,6303 ,0,0,0}, + {7523,7522,7524 ,6301,6303,6301 ,0,0,0}, {7473,7474,7522 ,6300,6316,6303 ,0,0,0}, + {7468,7469,7474 ,6316,6300,6316 ,0,0,0}, {7465,7466,7469 ,6300,6300,6300 ,0,0,0}, + {7462,7463,7466 ,6301,6300,6300 ,0,0,0}, {5821,7460,7463 ,6300,6300,6300 ,0,0,0}, + {5821,5820,7458 ,6300,6300,6316 ,0,0,0}, {5820,5817,7456 ,6300,6300,6300 ,0,0,0}, + {5817,5815,7454 ,6300,6303,6303 ,0,0,0}, {5815,5816,7452 ,6303,6300,6340 ,0,0,0}, + {5816,5814,7450 ,6300,6340,6323 ,0,0,0}, {5814,5811,7448 ,6340,6340,6340 ,0,0,0}, + {5811,5809,7446 ,6340,6316,6306 ,0,0,0}, {5809,5808,7444 ,6316,6340,6300 ,0,0,0}, + {5808,5805,7442 ,6340,6340,6352 ,0,0,0}, {5805,5803,7441 ,6340,6352,6303 ,0,0,0}, + {5803,5801,7439 ,6352,6300,6328 ,0,0,0}, {5801,5800,7438 ,6300,6301,6353 ,0,0,0}, + {5800,5796,7437 ,6301,6300,6363 ,0,0,0}, {5796,5795,7435 ,6300,6301,6311 ,0,0,0}, + {5795,5791,7434 ,6301,6362,6353 ,0,0,0}, {5791,5790,7412 ,6362,6302,6302 ,0,0,0}, + {5790,5794,7411 ,6302,6333,6301 ,0,0,0}, {5794,5788,7431 ,6333,6361,6301 ,0,0,0}, + {5788,5787,7415 ,6361,6304,6305 ,0,0,0}, {5787,5789,7414 ,6304,6314,6304 ,0,0,0}, + {5789,5784,7428 ,6314,6336,6311 ,0,0,0}, {5784,5785,7418 ,6336,6305,6308 ,0,0,0}, + {5785,5777,7417 ,6305,6304,6307 ,0,0,0}, {5777,5779,7423 ,6304,6314,6313 ,0,0,0}, + {5779,5781,7422 ,6314,6358,6308 ,0,0,0}, {5781,5773,7420 ,6358,6311,6310 ,0,0,0}, + {5773,5772,7421 ,6311,6359,6312 ,0,0,0}, {5772,5776,7425 ,6359,6319,6318 ,0,0,0}, + {5776,5769,7424 ,6319,6315,6317 ,0,0,0}, {5769,5771,6193 ,6315,6354,6316 ,0,0,0}, + {5771,5765,6191 ,6354,6350,6351 ,0,0,0}, {5765,5764,6190 ,6350,6320,6322 ,0,0,0}, + {5764,5766,6188 ,6320,6349,6321 ,0,0,0}, {5766,5758,6185 ,6349,6346,6345 ,0,0,0}, + {5758,5760,6184 ,6346,6341,6343 ,0,0,0}, {5760,5762,6182 ,6341,6344,6342 ,0,0,0}, + {5762,5754,6179 ,6344,6325,6327 ,0,0,0}, {5754,5753,6178 ,6325,6338,6326 ,0,0,0}, + {5753,5756,6176 ,6338,6324,6339 ,0,0,0}, {5756,5824,6173 ,6324,6298,6336 ,0,0,0}, + {5824,5751,6172 ,6298,6330,6329 ,0,0,0}, {5751,5825,6170 ,6330,6324,6301 ,0,0,0}, + {5825,5752,6167 ,6324,6337,6331 ,0,0,0}, {5752,5744,6166 ,6337,6332,6333 ,0,0,0}, + {5744,5747,6164 ,6332,6334,6328 ,0,0,0}, {5747,5739,6161 ,6334,6340,6335 ,0,0,0}, + {5739,5738,6160 ,6340,6299,6328 ,0,0,0}, {5738,5742,6158 ,6299,6324,6328 ,0,0,0}, + {5742,5741,6155 ,6324,6347,6298 ,0,0,0}, {5741,5734,6154 ,6347,6306,6298 ,0,0,0}, + {5734,5737,6152 ,6306,6316,6324 ,0,0,0}, {5736,6148,6149 ,6324,6299,6348 ,0,0,0}, + {5723,6146,5731 ,6353,6323,6303 ,0,0,0}, {5722,6142,6143 ,6300,6299,6352 ,0,0,0}, + {5723,6143,6146 ,6353,6352,6323 ,0,0,0}, {5728,5720,6140 ,6356,6298,6357 ,0,0,0}, + {5722,5728,6142 ,6300,6356,6299 ,0,0,0}, {6137,5719,6136 ,6299,6355,6340 ,0,0,0}, + {6140,5720,6137 ,6357,6298,6299 ,0,0,0}, {5725,6136,5719 ,6299,6340,6355 ,0,0,0}, + {7520,6133,6131 ,6373,6374,6375 ,0,0,0}, {7526,7527,7515 ,6376,6377,6378 ,0,0,0}, + {7477,7528,7475 ,6379,6380,6381 ,0,0,0}, {7509,7488,7529 ,6382,6383,6384 ,0,0,0}, + {7481,7483,7530 ,6385,6386,6387 ,0,0,0}, {7531,7532,7503 ,6388,6389,6390 ,0,0,0}, + {7533,7534,7487 ,6391,6392,6393 ,0,0,0}, {7495,7500,7535 ,6394,6395,6396 ,0,0,0}, + {7502,7493,7536 ,6397,6398,6399 ,0,0,0}, {7537,7538,7492 ,6400,6401,6402 ,0,0,0}, + {7539,7540,7499 ,6403,6404,6405 ,0,0,0}, {7486,7518,7541 ,6406,6407,6408 ,0,0,0}, + {7512,7484,7542 ,6409,6410,6411 ,0,0,0}, {7543,7544,7522 ,6412,6413,6414 ,0,0,0}, + {7545,7546,7480 ,6415,6416,6417 ,0,0,0}, {7547,7466,7548 ,6418,6419,6420 ,0,0,0}, + {7474,7469,7549 ,6421,6422,6423 ,0,0,0}, {7458,7550,7551 ,6424,6425,6426 ,0,0,0}, + {7460,7552,7463 ,6427,6428,6429 ,0,0,0}, {7553,7554,7452 ,6430,6431,6432 ,0,0,0}, + {7555,7456,7454 ,6433,6434,6435 ,0,0,0}, {7556,7448,7446 ,6436,6437,6438 ,0,0,0}, + {7450,7448,7557 ,6439,6437,6440 ,0,0,0}, {7558,7442,7559 ,6441,6442,6443 ,0,0,0}, + {7444,7558,7560 ,6444,6441,6445 ,0,0,0}, {7439,7438,7561 ,6446,6447,6448 ,0,0,0}, + {7441,7562,7559 ,6449,6450,6443 ,0,0,0}, {7437,7435,7563 ,6451,6452,6453 ,0,0,0}, + {7437,7564,7438 ,6451,6454,6447 ,0,0,0}, {7434,7412,7565 ,6455,6456,6457 ,0,0,0}, + {7434,7566,7435 ,6455,6458,6452 ,0,0,0}, {7567,7412,7411 ,6459,6456,6460 ,0,0,0}, + {7412,7567,7565 ,6456,6459,6457 ,0,0,0}, {7431,7568,7411 ,6461,6462,6460 ,0,0,0}, + {7567,7411,7568 ,6459,6460,6462 ,0,0,0}, {7431,7415,7569 ,6461,6463,6464 ,0,0,0}, + {7569,7568,7431 ,6464,6462,6461 ,0,0,0}, {7570,7415,7414 ,6465,6463,6466 ,0,0,0}, + {7415,7570,7569 ,6463,6465,6464 ,0,0,0}, {7428,7571,7414 ,6467,6468,6466 ,0,0,0}, + {7570,7414,7571 ,6465,6466,6468 ,0,0,0}, {7428,7418,7572 ,6467,6469,6470 ,0,0,0}, + {7572,7571,7428 ,6470,6468,6467 ,0,0,0}, {7573,7418,7417 ,6471,6469,6472 ,0,0,0}, + {7418,7573,7572 ,6469,6471,6470 ,0,0,0}, {7423,7574,7417 ,6473,6474,6472 ,0,0,0}, + {7573,7417,7574 ,6471,6472,6474 ,0,0,0}, {7423,7422,7575 ,6473,6475,6476 ,0,0,0}, + {7575,7574,7423 ,6476,6474,6473 ,0,0,0}, {7576,7422,7420 ,6477,6475,6478 ,0,0,0}, + {7422,7576,7575 ,6475,6477,6476 ,0,0,0}, {7421,7577,7420 ,6479,6480,6478 ,0,0,0}, + {7576,7420,7577 ,6477,6478,6480 ,0,0,0}, {7421,7425,7578 ,6479,6481,6482 ,0,0,0}, + {7578,7577,7421 ,6482,6480,6479 ,0,0,0}, {7579,7425,7424 ,6483,6481,6484 ,0,0,0}, + {7425,7579,7578 ,6481,6483,6482 ,0,0,0}, {6193,7580,7424 ,6485,6486,6484 ,0,0,0}, + {7579,7424,7580 ,6483,6484,6486 ,0,0,0}, {6192,7580,6193 ,6487,6486,6485 ,0,0,0}, + {7566,7563,7435 ,6458,6453,6452 ,0,0,0}, {7434,7565,7566 ,6455,6457,6458 ,0,0,0}, + {7564,7561,7438 ,6454,6448,6447 ,0,0,0}, {7437,7563,7564 ,6451,6453,6454 ,0,0,0}, + {7441,7439,7562 ,6449,6446,6450 ,0,0,0}, {7439,7561,7562 ,6446,6448,6450 ,0,0,0}, + {7442,7558,7444 ,6442,6441,6444 ,0,0,0}, {7442,7441,7559 ,6442,6449,6443 ,0,0,0}, + {7556,7446,7560 ,6436,6438,6445 ,0,0,0}, {7446,7444,7560 ,6438,6444,6445 ,0,0,0}, + {7450,7557,7553 ,6439,6440,6430 ,0,0,0}, {7557,7448,7556 ,6440,6437,6436 ,0,0,0}, + {7554,7454,7452 ,6431,6435,6432 ,0,0,0}, {7553,7452,7450 ,6430,6432,6439 ,0,0,0}, + {7555,7550,7456 ,6433,6425,6434 ,0,0,0}, {7554,7555,7454 ,6431,6433,6435 ,0,0,0}, + {7458,7551,7460 ,6424,6426,6427 ,0,0,0}, {7456,7550,7458 ,6434,6425,6424 ,0,0,0}, + {7463,7552,7548 ,6429,6428,6420 ,0,0,0}, {7460,7551,7552 ,6427,6426,6428 ,0,0,0}, + {7469,7466,7547 ,6422,6419,6418 ,0,0,0}, {7466,7463,7548 ,6419,6429,6420 ,0,0,0}, + {7543,7474,7549 ,6412,6421,6423 ,0,0,0}, {7549,7469,7547 ,6423,6422,6418 ,0,0,0}, + {7544,7524,7522 ,6413,6488,6414 ,0,0,0}, {7543,7522,7474 ,6412,6414,6421 ,0,0,0}, + {7480,7524,7545 ,6417,6488,6415 ,0,0,0}, {7544,7545,7524 ,6413,6415,6488 ,0,0,0}, + {7518,7546,7541 ,6407,6416,6408 ,0,0,0}, {7480,7546,7518 ,6417,6416,6407 ,0,0,0}, + {7484,7486,7581 ,6410,6406,6489 ,0,0,0}, {7486,7541,7581 ,6406,6408,6489 ,0,0,0}, + {7537,7512,7542 ,6400,6409,6411 ,0,0,0}, {7542,7484,7581 ,6411,6410,6489 ,0,0,0}, + {7538,7490,7492 ,6401,6490,6402 ,0,0,0}, {7537,7492,7512 ,6400,6402,6409 ,0,0,0}, + {7499,7490,7539 ,6405,6490,6403 ,0,0,0}, {7538,7539,7490 ,6401,6403,6490 ,0,0,0}, + {7500,7540,7535 ,6395,6404,6396 ,0,0,0}, {7499,7540,7500 ,6405,6404,6395 ,0,0,0}, + {7493,7495,7582 ,6398,6394,6491 ,0,0,0}, {7495,7535,7582 ,6394,6396,6491 ,0,0,0}, + {7531,7502,7536 ,6388,6397,6399 ,0,0,0}, {7536,7493,7582 ,6399,6398,6491 ,0,0,0}, + {7532,7496,7503 ,6389,6492,6390 ,0,0,0}, {7531,7503,7502 ,6388,6390,6397 ,0,0,0}, + {7487,7496,7533 ,6393,6492,6391 ,0,0,0}, {7532,7533,7496 ,6389,6391,6492 ,0,0,0}, + {7488,7534,7529 ,6383,6392,6384 ,0,0,0}, {7487,7534,7488 ,6393,6392,6383 ,0,0,0}, + {7483,7509,7583 ,6386,6382,6493 ,0,0,0}, {7509,7529,7583 ,6382,6384,6493 ,0,0,0}, + {7526,7481,7530 ,6376,6385,6387 ,0,0,0}, {7530,7483,7583 ,6387,6386,6493 ,0,0,0}, + {7527,7477,7515 ,6377,6379,6378 ,0,0,0}, {7526,7515,7481 ,6376,6378,6385 ,0,0,0}, + {7528,7584,7475 ,6380,6494,6381 ,0,0,0}, {7527,7528,7477 ,6377,6380,6379 ,0,0,0}, + {6133,7520,7584 ,6374,6373,6494 ,0,0,0}, {7475,7584,7520 ,6381,6494,6373 ,0,0,0}, + {6144,6030,6145 ,6495,6495,6496 ,0,0,0}, {6151,6150,6036 ,6497,6496,6496 ,0,0,0}, + {7539,7538,7585 ,6498,6499,6500 ,0,0,0}, {6027,6144,6141 ,6501,6495,6501 ,0,0,0}, + {7536,7582,7586 ,6502,6503,6503 ,0,0,0}, {6138,6021,6024 ,6496,6504,6501 ,0,0,0}, + {7587,7529,7534 ,6498,6505,6506 ,0,0,0}, {5963,6072,6076 ,6507,6495,6495 ,0,0,0}, + {5973,5971,6085 ,6508,6509,6504 ,0,0,0}, {7588,7527,7526 ,6510,6511,6512 ,0,0,0}, + {6132,6015,6013 ,6513,6500,6514 ,0,0,0}, {6133,6015,6132 ,6515,6500,6513 ,0,0,0}, + {6127,6130,6014 ,6516,6517,6518 ,0,0,0}, {6094,6096,5979 ,6519,6520,6497 ,0,0,0}, + {6100,6102,5985 ,6521,6522,6523 ,0,0,0}, {6124,6007,6006 ,6524,6525,6526 ,0,0,0}, + {6103,5989,5988 ,6527,6500,6498 ,0,0,0}, {6120,6001,6118 ,6528,6522,6529 ,0,0,0}, + {6118,6000,6115 ,6529,6530,6531 ,0,0,0}, {5995,6112,5997 ,6532,6533,6502 ,0,0,0}, + {6109,5995,5994 ,6534,6532,6495 ,0,0,0}, {6121,6003,6120 ,6535,6502,6528 ,0,0,0}, + {6114,6115,5997 ,6533,6531,6502 ,0,0,0}, {6124,6006,6121 ,6524,6526,6535 ,0,0,0}, + {6003,6121,6006 ,6502,6535,6526 ,0,0,0}, {6106,5991,5989 ,6503,6514,6500 ,0,0,0}, + {5994,5991,6108 ,6495,6514,6530 ,0,0,0}, {6012,6007,6126 ,6536,6525,6537 ,0,0,0}, + {6007,6124,6126 ,6525,6524,6537 ,0,0,0}, {6012,6126,6127 ,6536,6537,6516 ,0,0,0}, + {6103,5988,6102 ,6527,6498,6522 ,0,0,0}, {6100,5983,6097 ,6521,6501,6509 ,0,0,0}, + {6127,6014,6012 ,6516,6518,6536 ,0,0,0}, {6014,6130,6013 ,6518,6517,6514 ,0,0,0}, + {6097,5982,6096 ,6509,6500,6520 ,0,0,0}, {5977,6091,5979 ,6508,6509,6497 ,0,0,0}, + {6132,6013,6130 ,6513,6514,6517 ,0,0,0}, {5973,6088,5976 ,6508,6508,6495 ,0,0,0}, + {5976,6090,5977 ,6495,6530,6508 ,0,0,0}, {7589,7528,7590 ,6538,6539,6540 ,0,0,0}, + {7584,6015,6133 ,6541,6500,6515 ,0,0,0}, {6084,5970,6082 ,6495,6496,6542 ,0,0,0}, + {5971,5970,6084 ,6509,6496,6495 ,0,0,0}, {6078,6079,5965 ,6542,6504,6507 ,0,0,0}, + {7583,7529,7591 ,6543,6505,6500 ,0,0,0}, {7592,7533,7593 ,6503,6533,6500 ,0,0,0}, + {6076,6078,5964 ,6495,6542,6495 ,0,0,0}, {7594,7593,7531 ,6508,6500,6538 ,0,0,0}, + {6021,6135,6020 ,6504,6542,6501 ,0,0,0}, {5963,6020,6134 ,6507,6501,6495 ,0,0,0}, + {7540,7595,7596 ,6527,6530,6498 ,0,0,0}, {7582,7535,7597 ,6503,6527,6499 ,0,0,0}, + {6027,6141,6026 ,6501,6501,6544 ,0,0,0}, {6139,6024,6026 ,6504,6501,6544 ,0,0,0}, + {7542,7598,7599 ,6508,6530,6544 ,0,0,0}, {7600,7537,7599 ,6498,6500,6544 ,0,0,0}, + {6032,6147,6145 ,6495,6495,6496 ,0,0,0}, {7581,7541,7598 ,6523,6504,6530 ,0,0,0}, + {7546,7601,7541 ,6500,6504,6504 ,0,0,0}, {7546,7545,7602 ,6500,6522,6500 ,0,0,0}, + {6150,6147,6033 ,6496,6495,6496 ,0,0,0}, {7603,7545,7544 ,6515,6522,6504 ,0,0,0}, + {7543,7604,7544 ,6508,6500,6504 ,0,0,0}, {6153,6036,6038 ,6495,6496,6508 ,0,0,0}, + {7604,7543,7605 ,6500,6508,6498 ,0,0,0}, {6156,6038,6039 ,6504,6508,6507 ,0,0,0}, + {7606,7605,7549 ,6515,6498,6545 ,0,0,0}, {6157,6039,6042 ,6507,6507,6495 ,0,0,0}, + {7607,7606,7547 ,6498,6515,6504 ,0,0,0}, {6159,6042,6044 ,6504,6495,6495 ,0,0,0}, + {7608,7607,7548 ,6504,6498,6504 ,0,0,0}, {6044,6045,6162 ,6495,6504,6504 ,0,0,0}, + {7609,7608,7552 ,6504,6504,6498 ,0,0,0}, {6163,6162,6045 ,6504,6504,6504 ,0,0,0}, + {7609,7551,7550 ,6504,6504,6504 ,0,0,0}, {6165,6163,6048 ,6546,6504,6504 ,0,0,0}, + {7610,7550,7555 ,6508,6504,6504 ,0,0,0}, {6168,6165,6050 ,6507,6546,6504 ,0,0,0}, + {7611,7555,7554 ,6508,6504,6508 ,0,0,0}, {6169,6168,6051 ,6547,6507,6548 ,0,0,0}, + {7612,7554,7553 ,6498,6508,6498 ,0,0,0}, {6171,6169,6054 ,6546,6547,6548 ,0,0,0}, + {7613,7553,7557 ,6504,6498,6498 ,0,0,0}, {6056,6174,6054 ,6549,6547,6548 ,0,0,0}, + {7557,7614,7613 ,6498,6504,6504 ,0,0,0}, {6175,6056,6057 ,6549,6549,6550 ,0,0,0}, + {7614,7556,7615 ,6504,6504,6498 ,0,0,0}, {6057,6060,6177 ,6550,6549,6504 ,0,0,0}, + {6180,6060,6062 ,6549,6549,6545 ,0,0,0}, {6183,6181,6064 ,6549,6504,6504 ,0,0,0}, + {7615,7560,7616 ,6498,6504,6504 ,0,0,0}, {6189,6187,6069 ,6551,6504,6515 ,0,0,0}, + {7561,7617,7562 ,6504,6508,6515 ,0,0,0}, {7618,7579,7619 ,6504,6545,6515 ,0,0,0}, + {7620,7563,7566 ,6508,6552,6504 ,0,0,0}, {7576,7621,7622 ,6553,6504,6554 ,0,0,0}, + {7623,7624,7567 ,6555,6504,6515 ,0,0,0}, {7571,7572,7625 ,6504,6504,6504 ,0,0,0}, + {7576,7622,7575 ,6553,6554,6504 ,0,0,0}, {7569,7626,7627 ,6504,6504,6515 ,0,0,0}, + {7625,7626,7570 ,6504,6504,6515 ,0,0,0}, {7574,7628,7573 ,6548,6504,6504 ,0,0,0}, + {7574,7575,7629 ,6548,6504,6549 ,0,0,0}, {7623,7568,7627 ,6555,6504,6515 ,0,0,0}, + {7630,7572,7573 ,6504,6504,6504 ,0,0,0}, {7631,7578,7618 ,6504,6548,6504 ,0,0,0}, + {7621,7577,7631 ,6504,6548,6504 ,0,0,0}, {7565,7632,7566 ,6504,6544,6504 ,0,0,0}, + {7565,7624,7632 ,6504,6504,6544 ,0,0,0}, {6192,6189,6071 ,6515,6551,6554 ,0,0,0}, + {6071,7619,7580 ,6554,6515,6545 ,0,0,0}, {7564,7633,7561 ,6515,6504,6504 ,0,0,0}, + {7634,7564,7563 ,6508,6515,6552 ,0,0,0}, {6186,6183,6063 ,6504,6549,6549 ,0,0,0}, + {6066,6187,6186 ,6545,6504,6504 ,0,0,0}, {7558,7635,7616 ,6508,6498,6504 ,0,0,0}, + {7617,7635,7559 ,6508,6498,6498 ,0,0,0}, {6181,6062,6064 ,6504,6545,6504 ,0,0,0}, + {6079,6082,5967 ,6504,6542,6504 ,0,0,0}, {7636,7530,7637 ,6556,6557,6558 ,0,0,0}, + {7585,7538,7600 ,6500,6499,6498 ,0,0,0}, {6001,6120,6003 ,6522,6528,6502 ,0,0,0}, + {6000,6118,6001 ,6530,6529,6522 ,0,0,0}, {5997,6115,6000 ,6502,6531,6530 ,0,0,0}, + {5997,6112,6114 ,6502,6533,6533 ,0,0,0}, {5995,6109,6112 ,6532,6534,6533 ,0,0,0}, + {5994,6108,6109 ,6495,6530,6534 ,0,0,0}, {5991,6106,6108 ,6514,6503,6530 ,0,0,0}, + {5989,6103,6106 ,6500,6527,6503 ,0,0,0}, {5985,6102,5988 ,6523,6522,6498 ,0,0,0}, + {5983,6100,5985 ,6501,6521,6523 ,0,0,0}, {5982,6097,5983 ,6500,6509,6501 ,0,0,0}, + {5979,6096,5982 ,6497,6520,6500 ,0,0,0}, {5979,6091,6094 ,6497,6509,6519 ,0,0,0}, + {5977,6090,6091 ,6508,6530,6509 ,0,0,0}, {5976,6088,6090 ,6495,6508,6530 ,0,0,0}, + {5973,6085,6088 ,6508,6504,6508 ,0,0,0}, {5971,6084,6085 ,6509,6495,6504 ,0,0,0}, + {5967,6082,5970 ,6504,6542,6496 ,0,0,0}, {5965,6079,5967 ,6507,6504,6504 ,0,0,0}, + {5964,6078,5965 ,6495,6542,6507 ,0,0,0}, {5963,6076,5964 ,6507,6495,6495 ,0,0,0}, + {5963,6134,6072 ,6507,6495,6495 ,0,0,0}, {6020,6135,6134 ,6501,6542,6495 ,0,0,0}, + {6021,6138,6135 ,6504,6496,6542 ,0,0,0}, {6024,6139,6138 ,6501,6504,6496 ,0,0,0}, + {6026,6141,6139 ,6544,6501,6504 ,0,0,0}, {6030,6144,6027 ,6495,6495,6501 ,0,0,0}, + {6032,6145,6030 ,6495,6496,6495 ,0,0,0}, {6033,6147,6032 ,6496,6495,6495 ,0,0,0}, + {6036,6150,6033 ,6496,6496,6496 ,0,0,0}, {6036,6153,6151 ,6496,6495,6497 ,0,0,0}, + {6038,6156,6153 ,6508,6504,6495 ,0,0,0}, {6039,6157,6156 ,6507,6507,6504 ,0,0,0}, + {6042,6159,6157 ,6495,6504,6507 ,0,0,0}, {6044,6162,6159 ,6495,6504,6504 ,0,0,0}, + {6048,6163,6045 ,6504,6504,6504 ,0,0,0}, {6050,6165,6048 ,6504,6546,6504 ,0,0,0}, + {6051,6168,6050 ,6548,6507,6504 ,0,0,0}, {6054,6169,6051 ,6548,6547,6548 ,0,0,0}, + {6054,6174,6171 ,6548,6547,6546 ,0,0,0}, {6056,6175,6174 ,6549,6549,6547 ,0,0,0}, + {6057,6177,6175 ,6550,6504,6549 ,0,0,0}, {6060,6180,6177 ,6549,6549,6504 ,0,0,0}, + {6062,6181,6180 ,6545,6504,6549 ,0,0,0}, {6063,6183,6064 ,6549,6549,6504 ,0,0,0}, + {6066,6186,6063 ,6545,6504,6549 ,0,0,0}, {6069,6187,6066 ,6515,6504,6545 ,0,0,0}, + {6071,6189,6069 ,6554,6551,6515 ,0,0,0}, {6071,7580,6192 ,6554,6545,6515 ,0,0,0}, + {7619,7579,7580 ,6515,6545,6545 ,0,0,0}, {7618,7578,7579 ,6504,6548,6545 ,0,0,0}, + {7631,7577,7578 ,6504,6548,6548 ,0,0,0}, {7621,7576,7577 ,6504,6553,6548 ,0,0,0}, + {7629,7575,7622 ,6549,6504,6554 ,0,0,0}, {7628,7574,7629 ,6504,6548,6549 ,0,0,0}, + {7630,7573,7628 ,6504,6504,6504 ,0,0,0}, {7625,7572,7630 ,6504,6504,6504 ,0,0,0}, + {7625,7570,7571 ,6504,6515,6504 ,0,0,0}, {7626,7569,7570 ,6504,6504,6515 ,0,0,0}, + {7627,7568,7569 ,6515,6504,6504 ,0,0,0}, {7623,7567,7568 ,6555,6515,6504 ,0,0,0}, + {7624,7565,7567 ,6504,6504,6515 ,0,0,0}, {7620,7566,7632 ,6508,6504,6544 ,0,0,0}, + {7634,7563,7620 ,6508,6552,6508 ,0,0,0}, {7633,7564,7634 ,6504,6515,6508 ,0,0,0}, + {7617,7561,7633 ,6508,6504,6504 ,0,0,0}, {7617,7559,7562 ,6508,6498,6515 ,0,0,0}, + {7635,7558,7559 ,6498,6508,6498 ,0,0,0}, {7616,7560,7558 ,6504,6504,6508 ,0,0,0}, + {7615,7556,7560 ,6498,6504,6504 ,0,0,0}, {7614,7557,7556 ,6504,6498,6504 ,0,0,0}, + {7612,7553,7613 ,6498,6498,6504 ,0,0,0}, {7611,7554,7612 ,6508,6508,6498 ,0,0,0}, + {7610,7555,7611 ,6508,6504,6508 ,0,0,0}, {7609,7550,7610 ,6504,6504,6508 ,0,0,0}, + {7609,7552,7551 ,6504,6498,6504 ,0,0,0}, {7608,7548,7552 ,6504,6504,6498 ,0,0,0}, + {7607,7547,7548 ,6498,6504,6504 ,0,0,0}, {7606,7549,7547 ,6515,6545,6504 ,0,0,0}, + {7605,7543,7549 ,6498,6508,6545 ,0,0,0}, {7603,7544,7604 ,6515,6504,6500 ,0,0,0}, + {7602,7545,7603 ,6500,6522,6515 ,0,0,0}, {7601,7546,7602 ,6504,6500,6500 ,0,0,0}, + {7598,7541,7601 ,6530,6504,6504 ,0,0,0}, {7598,7542,7581 ,6530,6508,6523 ,0,0,0}, + {7599,7537,7542 ,6544,6500,6508 ,0,0,0}, {7600,7538,7537 ,6498,6499,6500 ,0,0,0}, + {7595,7539,7585 ,6530,6498,6500 ,0,0,0}, {7596,7535,7540 ,6498,6527,6527 ,0,0,0}, + {7595,7540,7539 ,6530,6527,6498 ,0,0,0}, {7597,7586,7582 ,6499,6503,6503 ,0,0,0}, + {7596,7597,7535 ,6498,6499,6527 ,0,0,0}, {7586,7594,7536 ,6503,6508,6502 ,0,0,0}, + {7531,7593,7532 ,6538,6500,6559 ,0,0,0}, {7536,7594,7531 ,6502,6508,6538 ,0,0,0}, + {7534,7533,7592 ,6506,6533,6503 ,0,0,0}, {7533,7532,7593 ,6533,6559,6500 ,0,0,0}, + {7591,7529,7587 ,6500,6505,6498 ,0,0,0}, {7587,7534,7592 ,6498,6506,6503 ,0,0,0}, + {7637,7583,7591 ,6558,6543,6500 ,0,0,0}, {7636,7526,7530 ,6556,6512,6557 ,0,0,0}, + {7637,7530,7583 ,6558,6557,6543 ,0,0,0}, {7588,7590,7527 ,6510,6540,6511 ,0,0,0}, + {7636,7588,7526 ,6556,6510,6512 ,0,0,0}, {7528,7589,7584 ,6539,6538,6541 ,0,0,0}, + {7527,7590,7528 ,6511,6540,6539 ,0,0,0}, {6015,7584,7589 ,6500,6541,6538 ,0,0,0}, + {7589,6017,6015 ,6560,6561,6562 ,0,0,0}, {7636,7638,7588 ,6563,6564,6565 ,0,0,0}, + {7590,7639,7640 ,6566,6567,6568 ,0,0,0}, {7587,7592,7641 ,6569,6570,6571 ,0,0,0}, + {7637,7591,7642 ,6572,6573,6574 ,0,0,0}, {7643,7644,7586 ,6575,6576,6577 ,0,0,0}, + {7645,7646,7593 ,6578,6579,6580 ,0,0,0}, {7595,7585,7647 ,6581,6582,6583 ,0,0,0}, + {7597,7596,7648 ,6584,6585,6586 ,0,0,0}, {7649,7650,7598 ,6587,6588,6589 ,0,0,0}, + {7651,7600,7599 ,6590,6591,6592 ,0,0,0}, {7603,7604,7652 ,6593,6594,6595 ,0,0,0}, + {7602,7653,7654 ,6596,6597,6598 ,0,0,0}, {7655,7656,7607 ,6599,6600,6601 ,0,0,0}, + {7657,7658,7605 ,6602,6603,6604 ,0,0,0}, {7659,7610,7660 ,6605,6606,6607 ,0,0,0}, + {7608,7609,7661 ,6608,6609,6610 ,0,0,0}, {7612,7613,7662 ,6611,6612,6613 ,0,0,0}, + {7612,7663,7611 ,6611,6614,6615 ,0,0,0}, {7616,7664,7615 ,6616,6617,6618 ,0,0,0}, + {7665,7666,7614 ,6619,6620,6621 ,0,0,0}, {7617,7667,7635 ,6622,6623,6624 ,0,0,0}, + {7668,7616,7635 ,6625,6616,6624 ,0,0,0}, {7669,7670,7634 ,6626,6627,6628 ,0,0,0}, + {7671,7633,7670 ,6629,6630,6627 ,0,0,0}, {7672,7673,7632 ,6631,6632,6633 ,0,0,0}, + {7669,7620,7673 ,6626,6634,6632 ,0,0,0}, {7623,7674,7624 ,6635,6636,6637 ,0,0,0}, + {7672,7624,7674 ,6631,6637,6636 ,0,0,0}, {7623,7627,7675 ,6635,6638,6639 ,0,0,0}, + {7675,7674,7623 ,6639,6636,6635 ,0,0,0}, {7676,7627,7626 ,6640,6638,6641 ,0,0,0}, + {7627,7676,7675 ,6638,6640,6639 ,0,0,0}, {7625,7677,7626 ,6642,6643,6641 ,0,0,0}, + {7676,7626,7677 ,6640,6641,6643 ,0,0,0}, {7625,7630,7678 ,6642,6644,6645 ,0,0,0}, + {7678,7677,7625 ,6645,6643,6642 ,0,0,0}, {7679,7630,7628 ,6646,6644,6647 ,0,0,0}, + {7630,7679,7678 ,6644,6646,6645 ,0,0,0}, {7629,7680,7628 ,6648,6649,6647 ,0,0,0}, + {7679,7628,7680 ,6646,6647,6649 ,0,0,0}, {7629,7622,7681 ,6648,6650,6651 ,0,0,0}, + {7681,7680,7629 ,6651,6649,6648 ,0,0,0}, {7682,7622,7621 ,6652,6650,6653 ,0,0,0}, + {7622,7682,7681 ,6650,6652,6651 ,0,0,0}, {7621,7683,7684 ,6653,6654,6655 ,0,0,0}, + {7682,7621,7684 ,6652,6653,6655 ,0,0,0}, {7683,7631,7685 ,6654,6656,6657 ,0,0,0}, + {7631,7683,7621 ,6656,6654,6653 ,0,0,0}, {7685,7618,7619 ,6657,6658,6659 ,0,0,0}, + {7631,7618,7685 ,6656,6658,6657 ,0,0,0}, {6071,7686,7619 ,6660,6661,6659 ,0,0,0}, + {7685,7619,7686 ,6657,6659,6661 ,0,0,0}, {6070,7686,6071 ,6660,6661,6660 ,0,0,0}, + {7620,7632,7673 ,6634,6633,6632 ,0,0,0}, {7672,7632,7624 ,6631,6633,6637 ,0,0,0}, + {7633,7634,7670 ,6630,6628,6627 ,0,0,0}, {7669,7634,7620 ,6626,6628,6634 ,0,0,0}, + {7671,7667,7617 ,6629,6623,6622 ,0,0,0}, {7671,7617,7633 ,6629,6622,6630 ,0,0,0}, + {7664,7616,7668 ,6617,6616,6625 ,0,0,0}, {7667,7668,7635 ,6623,6625,6624 ,0,0,0}, + {7615,7665,7614 ,6618,6619,6621 ,0,0,0}, {7664,7665,7615 ,6617,6619,6618 ,0,0,0}, + {7613,7666,7662 ,6612,6620,6613 ,0,0,0}, {7614,7666,7613 ,6621,6620,6612 ,0,0,0}, + {7663,7660,7611 ,6614,6607,6615 ,0,0,0}, {7612,7662,7663 ,6611,6613,6614 ,0,0,0}, + {7609,7610,7659 ,6609,6606,6605 ,0,0,0}, {7610,7611,7660 ,6606,6615,6607 ,0,0,0}, + {7655,7608,7661 ,6599,6608,6610 ,0,0,0}, {7661,7609,7659 ,6610,6609,6605 ,0,0,0}, + {7656,7606,7607 ,6600,6662,6601 ,0,0,0}, {7655,7607,7608 ,6599,6601,6608 ,0,0,0}, + {7605,7606,7657 ,6604,6662,6602 ,0,0,0}, {7656,7657,7606 ,6600,6602,6662 ,0,0,0}, + {7604,7658,7652 ,6594,6603,6595 ,0,0,0}, {7605,7658,7604 ,6604,6603,6594 ,0,0,0}, + {7602,7603,7653 ,6596,6593,6597 ,0,0,0}, {7603,7652,7653 ,6593,6595,6597 ,0,0,0}, + {7649,7601,7654 ,6587,6663,6598 ,0,0,0}, {7601,7602,7654 ,6663,6596,6598 ,0,0,0}, + {7650,7599,7598 ,6588,6592,6589 ,0,0,0}, {7649,7598,7601 ,6587,6589,6663 ,0,0,0}, + {7651,7687,7600 ,6590,6664,6591 ,0,0,0}, {7650,7651,7599 ,6588,6590,6592 ,0,0,0}, + {7647,7585,7687 ,6583,6582,6664 ,0,0,0}, {7600,7687,7585 ,6591,6664,6582 ,0,0,0}, + {7596,7595,7688 ,6585,6581,6665 ,0,0,0}, {7595,7647,7688 ,6581,6583,6665 ,0,0,0}, + {7643,7597,7648 ,6575,6584,6586 ,0,0,0}, {7648,7596,7688 ,6586,6585,6665 ,0,0,0}, + {7644,7594,7586 ,6576,6666,6577 ,0,0,0}, {7643,7586,7597 ,6575,6577,6584 ,0,0,0}, + {7593,7594,7645 ,6580,6666,6578 ,0,0,0}, {7644,7645,7594 ,6576,6578,6666 ,0,0,0}, + {7592,7646,7641 ,6570,6579,6571 ,0,0,0}, {7593,7646,7592 ,6580,6579,6570 ,0,0,0}, + {7591,7587,7689 ,6573,6569,6667 ,0,0,0}, {7587,7641,7689 ,6569,6571,6667 ,0,0,0}, + {7638,7637,7642 ,6564,6572,6574 ,0,0,0}, {7642,7591,7689 ,6574,6573,6667 ,0,0,0}, + {7638,7639,7588 ,6564,6567,6565 ,0,0,0}, {7638,7636,7637 ,6564,6563,6572 ,0,0,0}, + {7640,7690,7590 ,6568,6668,6566 ,0,0,0}, {7588,7639,7590 ,6565,6567,6566 ,0,0,0}, + {6017,7589,7690 ,6561,6560,6668 ,0,0,0}, {7590,7690,7589 ,6566,6668,6560 ,0,0,0}, + {5981,5984,5888 ,6669,6670,6671 ,0,0,0}, {7643,7648,7691 ,6672,6671,6671 ,0,0,0}, + {5894,5990,5903 ,6673,6674,6671 ,0,0,0}, {5984,5986,5897 ,6670,6669,6675 ,0,0,0}, + {5996,5926,5898 ,6670,6676,6677 ,0,0,0}, {7692,7693,7661 ,6324,6298,6672 ,0,0,0}, + {7694,7653,7652 ,6671,6672,6671 ,0,0,0}, {7695,7696,7657 ,6672,6671,6671 ,0,0,0}, + {6009,5920,5916 ,6678,6671,6679 ,0,0,0}, {7654,7653,7697 ,6671,6672,6680 ,0,0,0}, + {5922,6016,5924 ,6679,6671,6671 ,0,0,0}, {7698,7699,7651 ,6672,6672,6672 ,0,0,0}, + {7700,7701,7638 ,6672,6681,6672 ,0,0,0}, {7690,7640,7702 ,6671,6681,6672 ,0,0,0}, + {7703,7645,7644 ,6672,6672,6681 ,0,0,0}, {7641,7704,7705 ,6672,6672,6672 ,0,0,0}, + {7706,7689,7705 ,6672,6671,6672 ,0,0,0}, {7643,7707,7644 ,6672,6671,6681 ,0,0,0}, + {7646,7703,7704 ,6672,6672,6672 ,0,0,0}, {7700,7642,7706 ,6672,6672,6672 ,0,0,0}, + {7708,7709,7688 ,6671,6672,6672 ,0,0,0}, {7640,7639,7710 ,6681,6671,6671 ,0,0,0}, + {7647,7711,7708 ,6671,6681,6671 ,0,0,0}, {6017,7690,5924 ,6671,6671,6671 ,0,0,0}, + {7687,7699,7711 ,6672,6672,6681 ,0,0,0}, {5920,6010,5921 ,6671,6682,6672 ,0,0,0}, + {5922,5921,6011 ,6679,6672,6298 ,0,0,0}, {7654,7712,7649 ,6671,6671,6672 ,0,0,0}, + {7712,7698,7650 ,6671,6672,6672 ,0,0,0}, {6004,6005,5912 ,6672,6681,6670 ,0,0,0}, + {5916,5918,6008 ,6679,6669,6669 ,0,0,0}, {7696,7713,7658 ,6671,6672,6671 ,0,0,0}, + {6002,6004,5914 ,6671,6672,6681 ,0,0,0}, {5909,5926,5998 ,6669,6676,6298 ,0,0,0}, + {5909,5999,6002 ,6669,6669,6671 ,0,0,0}, {7714,7655,7693 ,6672,6671,6298 ,0,0,0}, + {7714,7695,7656 ,6672,6672,6672 ,0,0,0}, {5992,5900,5903 ,6683,6669,6671 ,0,0,0}, + {5898,5900,5993 ,6677,6669,6684 ,0,0,0}, {7663,7715,7660 ,6671,6685,6686 ,0,0,0}, + {7692,7659,7660 ,6324,6687,6686 ,0,0,0}, {7663,7662,7716 ,6671,6688,6688 ,0,0,0}, + {5986,5987,5893 ,6669,6689,6684 ,0,0,0}, {7717,7718,7665 ,6672,6690,6671 ,0,0,0}, + {7718,7719,7666 ,6690,6686,6690 ,0,0,0}, {7720,7717,7664 ,6691,6672,6691 ,0,0,0}, + {5888,5891,5980 ,6671,6692,6672 ,0,0,0}, {5890,5978,5891 ,6693,6673,6692 ,0,0,0}, + {5883,5975,5890 ,6672,6689,6693 ,0,0,0}, {7668,7721,7720 ,6686,6690,6691 ,0,0,0}, + {5974,5883,5886 ,6694,6672,6695 ,0,0,0}, {7667,7722,7721 ,6690,6691,6690 ,0,0,0}, + {5886,5885,5972 ,6695,6696,6697 ,0,0,0}, {7722,7671,7670 ,6691,6672,6688 ,0,0,0}, + {5880,5968,5969 ,6698,6699,6700 ,0,0,0}, {7723,7724,7669 ,6672,6688,6688 ,0,0,0}, + {7673,7672,7725 ,6688,6691,6701 ,0,0,0}, {7726,7674,7675 ,6686,6672,6671 ,0,0,0}, + {5966,5968,5828 ,6676,6699,6702 ,0,0,0}, {7676,7727,7728 ,6672,6671,6671 ,0,0,0}, + {5966,5827,5962 ,6676,6687,6703 ,0,0,0}, {7729,7677,7678 ,6686,6704,6672 ,0,0,0}, + {5827,5875,6018 ,6687,6705,6676 ,0,0,0}, {7680,7730,7679 ,6686,6706,6672 ,0,0,0}, + {5961,6019,5875 ,6698,6699,6705 ,0,0,0}, {6023,5866,5865 ,6697,6707,6708 ,0,0,0}, + {6022,5961,5866 ,6709,6698,6707 ,0,0,0}, {7731,7683,7685 ,6690,6671,6701 ,0,0,0}, + {5865,5959,6025 ,6708,6672,6694 ,0,0,0}, {7686,5853,7732 ,6690,6690,6686 ,0,0,0}, + {6029,6028,5957 ,6673,6689,6710 ,0,0,0}, {5851,5853,6068 ,6711,6690,6690 ,0,0,0}, + {6031,6029,5955 ,6686,6673,6692 ,0,0,0}, {6065,5849,6067 ,6712,6713,6685 ,0,0,0}, + {5950,5951,6037 ,6714,6684,6669 ,0,0,0}, {6061,5846,5848 ,6715,6716,6717 ,0,0,0}, + {5946,6043,5945 ,6718,6719,6691 ,0,0,0}, {6049,6047,5834 ,6298,6670,6676 ,0,0,0}, + {6055,5839,5841 ,6686,6704,6720 ,0,0,0}, {5841,5843,6058 ,6720,6669,6715 ,0,0,0}, + {6049,5836,6052 ,6298,6718,6669 ,0,0,0}, {5836,5839,6053 ,6718,6704,6691 ,0,0,0}, + {7724,7670,7669 ,6688,6688,6688 ,0,0,0}, {5944,6047,6046 ,6676,6670,6684 ,0,0,0}, + {6061,6059,5846 ,6715,6669,6716 ,0,0,0}, {5848,5849,6065 ,6717,6713,6712 ,0,0,0}, + {5848,6065,6061 ,6717,6712,6715 ,0,0,0}, {5949,6040,5951 ,6673,6721,6684 ,0,0,0}, + {5949,5945,6041 ,6673,6691,6670 ,0,0,0}, {5851,6068,6067 ,6711,6690,6685 ,0,0,0}, + {5851,6067,5849 ,6711,6685,6713 ,0,0,0}, {5954,6034,6031 ,6691,6669,6686 ,0,0,0}, + {6035,5954,5950 ,6720,6691,6714 ,0,0,0}, {6070,6068,5853 ,6671,6690,6690 ,0,0,0}, + {7684,7733,7734 ,6686,6722,6688 ,0,0,0}, {7681,7682,7735 ,6691,6723,6706 ,0,0,0}, + {6059,6058,5843 ,6669,6715,6669 ,0,0,0}, {6059,5843,5846 ,6669,6669,6716 ,0,0,0}, + {6058,6055,5841 ,6715,6686,6720 ,0,0,0}, {6055,6053,5839 ,6686,6691,6704 ,0,0,0}, + {6053,6052,5836 ,6691,6669,6718 ,0,0,0}, {6049,5834,5836 ,6298,6676,6718 ,0,0,0}, + {6047,5944,5834 ,6670,6676,6676 ,0,0,0}, {6046,6043,5946 ,6684,6719,6718 ,0,0,0}, + {6046,5946,5944 ,6684,6718,6676 ,0,0,0}, {6043,6041,5945 ,6719,6670,6691 ,0,0,0}, + {6041,6040,5949 ,6670,6721,6673 ,0,0,0}, {6040,6037,5951 ,6721,6669,6684 ,0,0,0}, + {6037,6035,5950 ,6669,6720,6714 ,0,0,0}, {6035,6034,5954 ,6720,6669,6691 ,0,0,0}, + {6031,5955,5954 ,6686,6692,6691 ,0,0,0}, {6029,5957,5955 ,6673,6710,6692 ,0,0,0}, + {6028,6025,5959 ,6689,6694,6672 ,0,0,0}, {6028,5959,5957 ,6689,6672,6710 ,0,0,0}, + {6025,6023,5865 ,6694,6697,6708 ,0,0,0}, {6023,6022,5866 ,6697,6709,6707 ,0,0,0}, + {6022,6019,5961 ,6709,6699,6698 ,0,0,0}, {6019,6018,5875 ,6699,6676,6705 ,0,0,0}, + {6018,5962,5827 ,6676,6703,6687 ,0,0,0}, {5966,5828,5827 ,6676,6702,6687 ,0,0,0}, + {5968,5880,5828 ,6699,6698,6702 ,0,0,0}, {5969,5972,5885 ,6700,6697,6696 ,0,0,0}, + {5969,5885,5880 ,6700,6696,6698 ,0,0,0}, {5972,5974,5886 ,6697,6694,6695 ,0,0,0}, + {5974,5975,5883 ,6694,6689,6672 ,0,0,0}, {5975,5978,5890 ,6689,6673,6693 ,0,0,0}, + {5978,5980,5891 ,6673,6672,6692 ,0,0,0}, {5980,5981,5888 ,6672,6669,6671 ,0,0,0}, + {5984,5897,5888 ,6670,6675,6671 ,0,0,0}, {5986,5893,5897 ,6669,6684,6675 ,0,0,0}, + {5987,5990,5894 ,6689,6674,6673 ,0,0,0}, {5987,5894,5893 ,6689,6673,6684 ,0,0,0}, + {5990,5992,5903 ,6674,6683,6671 ,0,0,0}, {5992,5993,5900 ,6683,6684,6669 ,0,0,0}, + {5993,5996,5898 ,6684,6670,6677 ,0,0,0}, {5996,5998,5926 ,6670,6298,6676 ,0,0,0}, + {5998,5999,5909 ,6298,6669,6669 ,0,0,0}, {6002,5914,5909 ,6671,6681,6669 ,0,0,0}, + {6004,5912,5914 ,6672,6670,6681 ,0,0,0}, {6005,6008,5918 ,6681,6669,6669 ,0,0,0}, + {6005,5918,5912 ,6681,6669,6670 ,0,0,0}, {6008,6009,5916 ,6669,6678,6679 ,0,0,0}, + {6009,6010,5920 ,6678,6682,6671 ,0,0,0}, {6010,6011,5921 ,6682,6298,6672 ,0,0,0}, + {6011,6016,5922 ,6298,6671,6679 ,0,0,0}, {6016,6017,5924 ,6671,6671,6671 ,0,0,0}, + {7690,7702,5924 ,6671,6672,6671 ,0,0,0}, {7640,7710,7702 ,6681,6671,6672 ,0,0,0}, + {7639,7638,7701 ,6671,6672,6681 ,0,0,0}, {7639,7701,7710 ,6671,6681,6671 ,0,0,0}, + {7638,7642,7700 ,6672,6672,6672 ,0,0,0}, {7642,7689,7706 ,6672,6671,6672 ,0,0,0}, + {7689,7641,7705 ,6671,6672,6672 ,0,0,0}, {7641,7646,7704 ,6672,6672,6672 ,0,0,0}, + {7646,7645,7703 ,6672,6672,6672 ,0,0,0}, {7644,7707,7703 ,6681,6671,6672 ,0,0,0}, + {7643,7691,7707 ,6672,6671,6671 ,0,0,0}, {7648,7688,7709 ,6671,6672,6672 ,0,0,0}, + {7648,7709,7691 ,6671,6672,6671 ,0,0,0}, {7688,7647,7708 ,6672,6671,6671 ,0,0,0}, + {7647,7687,7711 ,6671,6672,6681 ,0,0,0}, {7687,7651,7699 ,6672,6672,6672 ,0,0,0}, + {7651,7650,7698 ,6672,6672,6672 ,0,0,0}, {7650,7649,7712 ,6672,6672,6671 ,0,0,0}, + {7654,7697,7712 ,6671,6680,6671 ,0,0,0}, {7653,7694,7697 ,6672,6671,6680 ,0,0,0}, + {7652,7658,7713 ,6671,6671,6672 ,0,0,0}, {7652,7713,7694 ,6671,6672,6671 ,0,0,0}, + {7658,7657,7696 ,6671,6671,6671 ,0,0,0}, {7657,7656,7695 ,6671,6672,6672 ,0,0,0}, + {7656,7655,7714 ,6672,6671,6672 ,0,0,0}, {7655,7661,7693 ,6671,6672,6298 ,0,0,0}, + {7661,7659,7692 ,6672,6687,6324 ,0,0,0}, {7660,7715,7692 ,6686,6685,6324 ,0,0,0}, + {7663,7716,7715 ,6671,6688,6685 ,0,0,0}, {7662,7666,7719 ,6688,6690,6686 ,0,0,0}, + {7662,7719,7716 ,6688,6686,6688 ,0,0,0}, {7666,7665,7718 ,6690,6671,6690 ,0,0,0}, + {7665,7664,7717 ,6671,6691,6672 ,0,0,0}, {7664,7668,7720 ,6691,6686,6691 ,0,0,0}, + {7668,7667,7721 ,6686,6690,6690 ,0,0,0}, {7667,7671,7722 ,6690,6672,6691 ,0,0,0}, + {7670,7724,7722 ,6688,6688,6691 ,0,0,0}, {7673,7723,7669 ,6688,6672,6688 ,0,0,0}, + {7672,7736,7725 ,6691,6691,6701 ,0,0,0}, {7673,7725,7723 ,6688,6701,6672 ,0,0,0}, + {7726,7736,7674 ,6686,6691,6672 ,0,0,0}, {7672,7674,7736 ,6691,6672,6691 ,0,0,0}, + {7726,7675,7728 ,6686,6671,6671 ,0,0,0}, {7727,7676,7677 ,6671,6672,6704 ,0,0,0}, + {7728,7675,7676 ,6671,6671,6672 ,0,0,0}, {7729,7678,7679 ,6686,6672,6672 ,0,0,0}, + {7729,7727,7677 ,6686,6671,6704 ,0,0,0}, {7737,7730,7680 ,6688,6706,6686 ,0,0,0}, + {7730,7729,7679 ,6706,6686,6672 ,0,0,0}, {7737,7681,7735 ,6688,6691,6706 ,0,0,0}, + {7681,7737,7680 ,6691,6688,6686 ,0,0,0}, {7682,7734,7735 ,6723,6688,6706 ,0,0,0}, + {7684,7683,7733 ,6686,6671,6722 ,0,0,0}, {7682,7684,7734 ,6723,6686,6688 ,0,0,0}, + {7731,7685,7732 ,6690,6701,6686 ,0,0,0}, {7733,7683,7731 ,6722,6671,6690 ,0,0,0}, + {5853,7686,6070 ,6690,6690,6671 ,0,0,0}, {7732,7685,7686 ,6686,6701,6690 ,0,0,0}, + {7732,5430,7234 ,6724,6725,6726 ,0,0,0}, {7196,7733,7731 ,6727,6728,6729 ,0,0,0}, + {7735,7198,7737 ,6730,6731,6732 ,0,0,0}, {7339,7734,7337 ,6733,6734,6735 ,0,0,0}, + {7738,7348,7739 ,6736,6737,6738 ,0,0,0}, {7223,7738,7740 ,6739,6736,6736 ,0,0,0}, + {7264,7741,7742 ,6740,6741,6742 ,0,0,0}, {7263,7743,7222 ,6743,6744,6745 ,0,0,0}, + {7346,7744,7745 ,6746,6747,6748 ,0,0,0}, {7393,7746,7351 ,6749,6750,6751 ,0,0,0}, + {7747,7748,7391 ,6752,6753,6754 ,0,0,0}, {7744,7279,7392 ,6747,6755,6756 ,0,0,0}, + {7714,7315,7306 ,6757,6758,6759 ,0,0,0}, {5717,7315,7747 ,6760,6758,6752 ,0,0,0}, + {7696,7308,7713 ,6761,6762,6763 ,0,0,0}, {7307,7696,7695 ,6764,6761,6765 ,0,0,0}, + {7378,7313,7697 ,6766,6767,6768 ,0,0,0}, {7378,7694,7377 ,6766,6769,6770 ,0,0,0}, + {7712,7305,7698 ,6771,6772,6773 ,0,0,0}, {7305,7712,7313 ,6772,6771,6767 ,0,0,0}, + {7699,7698,7282 ,6774,6773,6775 ,0,0,0}, {7305,7282,7698 ,6772,6775,6773 ,0,0,0}, + {7280,7711,7281 ,6776,6777,6778 ,0,0,0}, {7699,7282,7281 ,6774,6775,6778 ,0,0,0}, + {7286,7709,7304 ,6779,6780,6781 ,0,0,0}, {7708,7280,7304 ,6782,6776,6781 ,0,0,0}, + {7285,7707,7691 ,6783,6784,6785 ,0,0,0}, {7704,7703,7749 ,6786,6787,6788 ,0,0,0}, + {7749,7303,7750 ,6788,6789,6788 ,0,0,0}, {7703,7707,7303 ,6787,6784,6789 ,0,0,0}, + {7751,7284,7257 ,6790,6791,6792 ,0,0,0}, {7284,7751,7750 ,6791,6790,6788 ,0,0,0}, + {7256,7752,7257 ,6793,6794,6792 ,0,0,0}, {7751,7257,7752 ,6790,6792,6794 ,0,0,0}, + {7256,7289,7753 ,6793,6795,6796 ,0,0,0}, {7753,7752,7256 ,6796,6794,6793 ,0,0,0}, + {7754,7289,7295 ,6797,6795,6798 ,0,0,0}, {7289,7754,7753 ,6795,6797,6796 ,0,0,0}, + {7299,7755,7295 ,6799,6800,6798 ,0,0,0}, {7754,7295,7755 ,6797,6798,6800 ,0,0,0}, + {7299,7292,7756 ,6799,6801,6802 ,0,0,0}, {7756,7755,7299 ,6802,6800,6799 ,0,0,0}, + {7757,7292,7301 ,6803,6801,6804 ,0,0,0}, {7292,7757,7756 ,6801,6803,6802 ,0,0,0}, + {5531,5934,7301 ,6805,6806,6804 ,0,0,0}, {7757,7301,5934 ,6803,6804,6806 ,0,0,0}, + {7701,7758,7759 ,6807,6808,6809 ,0,0,0}, {7703,7303,7749 ,6787,6789,6788 ,0,0,0}, + {7750,7303,7284 ,6788,6789,6791 ,0,0,0}, {7285,7303,7707 ,6783,6789,6784 ,0,0,0}, + {7286,7285,7691 ,6779,6783,6785 ,0,0,0}, {7691,7709,7286 ,6785,6780,6779 ,0,0,0}, + {7304,7709,7708 ,6781,6780,6782 ,0,0,0}, {7280,7708,7711 ,6776,6782,6777 ,0,0,0}, + {7711,7699,7281 ,6777,6774,6778 ,0,0,0}, {7749,7760,7704 ,6788,6810,6786 ,0,0,0}, + {7758,7701,7700 ,6808,6807,6811 ,0,0,0}, {7760,7705,7704 ,6810,6812,6786 ,0,0,0}, + {7759,7761,7710 ,6809,6813,6814 ,0,0,0}, {7710,7701,7759 ,6814,6807,6809 ,0,0,0}, + {7710,7762,7702 ,6814,6815,6816 ,0,0,0}, {7762,7710,7761 ,6815,6814,6813 ,0,0,0}, + {5924,7702,5925 ,6817,6816,6818 ,0,0,0}, {7762,5925,7702 ,6815,6818,6816 ,0,0,0}, + {7700,7763,7758 ,6811,6819,6808 ,0,0,0}, {7313,7712,7697 ,6767,6771,6768 ,0,0,0}, + {7763,7700,7706 ,6819,6811,6820 ,0,0,0}, {7764,7763,7706 ,6821,6819,6820 ,0,0,0}, + {7705,7760,7764 ,6812,6810,6821 ,0,0,0}, {7705,7764,7706 ,6812,6821,6820 ,0,0,0}, + {7697,7694,7378 ,6768,6769,6766 ,0,0,0}, {7344,7745,7746 ,6822,6748,6750 ,0,0,0}, + {7377,7713,7308 ,6770,6763,6762 ,0,0,0}, {7713,7377,7694 ,6763,6770,6769 ,0,0,0}, + {7696,7307,7308 ,6761,6764,6762 ,0,0,0}, {7306,7307,7695 ,6759,6764,6765 ,0,0,0}, + {7693,7315,7714 ,6823,6758,6757 ,0,0,0}, {7695,7714,7306 ,6765,6757,6759 ,0,0,0}, + {5717,7747,7391 ,6760,6752,6754 ,0,0,0}, {7693,7747,7315 ,6823,6752,6758 ,0,0,0}, + {7744,7346,7279 ,6747,6746,6755 ,0,0,0}, {7748,7744,7392 ,6753,6747,6756 ,0,0,0}, + {7746,7393,7344 ,6750,6749,6822 ,0,0,0}, {7765,7343,7766 ,6824,6825,6826 ,0,0,0}, + {7746,7766,7351 ,6750,6826,6751 ,0,0,0}, {7765,7741,7273 ,6824,6741,6827 ,0,0,0}, + {7343,7765,7273 ,6825,6824,6827 ,0,0,0}, {7742,7743,7263 ,6742,6744,6743 ,0,0,0}, + {7273,7741,7255 ,6827,6741,6828 ,0,0,0}, {7736,7726,7767 ,6829,6830,6831 ,0,0,0}, + {7727,7729,7740 ,6832,6833,6736 ,0,0,0}, {7743,7739,7342 ,6744,6738,6834 ,0,0,0}, + {7731,7234,7196 ,6729,6726,6727 ,0,0,0}, {7735,7734,7339 ,6730,6734,6733 ,0,0,0}, + {7199,7223,7730 ,6835,6739,6836 ,0,0,0}, {7357,7738,7223 ,6837,6736,6739 ,0,0,0}, + {7737,7199,7730 ,6732,6835,6836 ,0,0,0}, {7339,7198,7735 ,6733,6731,6730 ,0,0,0}, + {7737,7198,7199 ,6732,6731,6835 ,0,0,0}, {7733,7337,7734 ,6728,6735,6734 ,0,0,0}, + {7337,7733,7196 ,6735,6728,6727 ,0,0,0}, {7234,7731,7732 ,6726,6729,6724 ,0,0,0}, + {5430,7732,5853 ,6725,6724,6838 ,0,0,0}, {7715,7768,7692 ,6839,6840,6841 ,0,0,0}, + {7693,7692,7768 ,6823,6841,6840 ,0,0,0}, {7768,7715,7769 ,6840,6839,6842 ,0,0,0}, + {7693,7768,7747 ,6823,6840,6752 ,0,0,0}, {7770,7769,7716 ,6843,6842,6844 ,0,0,0}, + {7392,7391,7748 ,6756,6754,6753 ,0,0,0}, {7718,7770,7719 ,6845,6843,6846 ,0,0,0}, + {7718,7771,7770 ,6845,6847,6843 ,0,0,0}, {7772,7771,7717 ,6848,6847,6849 ,0,0,0}, + {7344,7346,7745 ,6822,6746,6748 ,0,0,0}, {7721,7772,7720 ,6850,6848,6851 ,0,0,0}, + {7721,7773,7772 ,6850,6852,6848 ,0,0,0}, {7774,7773,7722 ,6853,6852,6854 ,0,0,0}, + {7343,7351,7766 ,6825,6751,6826 ,0,0,0}, {7724,7775,7774 ,6855,6856,6853 ,0,0,0}, + {7723,7775,7724 ,6857,6856,6855 ,0,0,0}, {7776,7775,7725 ,6858,6856,6859 ,0,0,0}, + {7264,7255,7741 ,6740,6828,6741 ,0,0,0}, {7767,7776,7736 ,6831,6858,6829 ,0,0,0}, + {7263,7264,7742 ,6743,6740,6742 ,0,0,0}, {7777,7767,7728 ,6860,6831,6861 ,0,0,0}, + {7342,7222,7743 ,6834,6745,6744 ,0,0,0}, {7740,7777,7727 ,6736,6860,6832 ,0,0,0}, + {7348,7342,7739 ,6737,6834,6738 ,0,0,0}, {7730,7223,7740 ,6836,6739,6736 ,0,0,0}, + {7348,7738,7357 ,6737,6736,6837 ,0,0,0}, {7730,7740,7729 ,6836,6736,6833 ,0,0,0}, + {7728,7727,7777 ,6861,6832,6860 ,0,0,0}, {7726,7728,7767 ,6830,6861,6831 ,0,0,0}, + {7725,7736,7776 ,6859,6829,6858 ,0,0,0}, {7723,7725,7775 ,6857,6859,6856 ,0,0,0}, + {7722,7724,7774 ,6854,6855,6853 ,0,0,0}, {7721,7722,7773 ,6850,6854,6852 ,0,0,0}, + {7717,7720,7772 ,6849,6851,6848 ,0,0,0}, {7718,7717,7771 ,6845,6849,6847 ,0,0,0}, + {7716,7719,7770 ,6844,6846,6843 ,0,0,0}, {7715,7716,7769 ,6839,6844,6842 ,0,0,0}, + {7778,5725,5726 ,6862,6863,6864 ,0,0,0}, {7430,7419,6657 ,6865,6866,6867 ,0,0,0}, + {7779,7427,7426 ,6868,6869,6870 ,0,0,0}, {7429,6650,7416 ,6871,6872,6873 ,0,0,0}, + {6635,7409,7413 ,6874,6875,6876 ,0,0,0}, {6647,7432,7433 ,6877,6878,6879 ,0,0,0}, + {7443,6642,6641 ,6880,6881,6882 ,0,0,0}, {7440,6634,6637 ,6883,6884,6885 ,0,0,0}, + {7780,7453,7451 ,6886,6887,6888 ,0,0,0}, {7781,7447,6644 ,6889,6890,5525 ,0,0,0}, + {7464,7461,6720 ,6891,6892,6893 ,0,0,0}, {7457,7782,7783 ,6894,6895,6896 ,0,0,0}, + {7471,6709,7525 ,6897,6898,6899 ,0,0,0}, {7467,6715,7470 ,6900,6901,6902 ,0,0,0}, + {6756,7476,6754 ,6903,6904,6905 ,0,0,0}, {7519,7472,6752 ,6906,6907,6908 ,0,0,0}, + {7508,7784,7510 ,6909,6910,6911 ,0,0,0}, {7516,6757,7482 ,6912,6913,6914 ,0,0,0}, + {7785,7497,7489 ,6915,6916,6917 ,0,0,0}, {7507,7786,7494 ,6918,6919,6920 ,0,0,0}, + {7787,7504,7505 ,6921,6922,6923 ,0,0,0}, {6813,6816,7498 ,6924,6925,6926 ,0,0,0}, + {6813,7501,6814 ,6924,6927,5712 ,0,0,0}, {6801,6800,7491 ,6928,6929,6930 ,0,0,0}, + {6801,7506,6816 ,6928,6931,6925 ,0,0,0}, {7511,7513,6800 ,6932,6933,6929 ,0,0,0}, + {6800,7513,7491 ,6929,6933,6930 ,0,0,0}, {7511,6800,6845 ,6932,6929,6934 ,0,0,0}, + {6845,6847,7485 ,6934,6935,6936 ,0,0,0}, {7485,7511,6845 ,6936,6932,6934 ,0,0,0}, + {7517,6847,6849 ,6937,6935,6938 ,0,0,0}, {6847,7517,7485 ,6935,6937,6936 ,0,0,0}, + {7517,6849,7478 ,6937,6938,6939 ,0,0,0}, {6850,7479,7478 ,6940,6941,6939 ,0,0,0}, + {7478,6849,6850 ,6939,6938,6940 ,0,0,0}, {7479,6852,7523 ,6941,6942,6943 ,0,0,0}, + {6852,7479,6850 ,6942,6941,6940 ,0,0,0}, {7473,7523,6853 ,6944,6943,6945 ,0,0,0}, + {6852,6853,7523 ,6942,6945,6943 ,0,0,0}, {6853,7788,7468 ,6945,6946,6947 ,0,0,0}, + {7468,7473,6853 ,6947,6944,6945 ,0,0,0}, {7465,7788,7789 ,6948,6946,6949 ,0,0,0}, + {7788,7465,7468 ,6946,6948,6947 ,0,0,0}, {7790,7462,7789 ,6950,6951,6949 ,0,0,0}, + {7465,7789,7462 ,6948,6949,6951 ,0,0,0}, {7790,5823,5821 ,6950,126,3135 ,0,0,0}, + {5821,7462,7790 ,3135,6951,6950 ,0,0,0}, {6816,7506,7498 ,6925,6931,6926 ,0,0,0}, + {6801,7491,7506 ,6928,6930,6931 ,0,0,0}, {7501,7494,6814 ,6927,6920,5712 ,0,0,0}, + {6813,7498,7501 ,6924,6926,6927 ,0,0,0}, {7786,7507,7504 ,6919,6918,6922 ,0,0,0}, + {7786,6814,7494 ,6919,5712,6920 ,0,0,0}, {7787,7505,7497 ,6921,6923,6916 ,0,0,0}, + {7787,7786,7504 ,6921,6919,6922 ,0,0,0}, {7784,7785,7489 ,6910,6915,6917 ,0,0,0}, + {7785,7787,7497 ,6915,6921,6916 ,0,0,0}, {6759,7784,7508 ,6952,6910,6909 ,0,0,0}, + {7510,7784,7489 ,6911,6910,6917 ,0,0,0}, {6759,7482,6757 ,6952,6914,6913 ,0,0,0}, + {7482,6759,7508 ,6914,6952,6909 ,0,0,0}, {7514,6756,6757 ,6953,6903,6913 ,0,0,0}, + {7514,6757,7516 ,6953,6913,6912 ,0,0,0}, {7476,7521,6754 ,6904,6954,6905 ,0,0,0}, + {7514,7476,6756 ,6953,6904,6903 ,0,0,0}, {7519,6752,7521 ,6906,6908,6954 ,0,0,0}, + {6754,7521,6752 ,6905,6954,6908 ,0,0,0}, {6711,7472,7525 ,6955,6907,6899 ,0,0,0}, + {6752,7472,6711 ,6908,6907,6955 ,0,0,0}, {6721,6709,7471 ,6956,6898,6897 ,0,0,0}, + {6709,6711,7525 ,6898,6955,6899 ,0,0,0}, {6721,7470,6715 ,6956,6902,6901 ,0,0,0}, + {7470,6721,7471 ,6902,6956,6897 ,0,0,0}, {7464,6720,6715 ,6891,6893,6901 ,0,0,0}, + {7464,6715,7467 ,6891,6901,6900 ,0,0,0}, {7461,7459,7783 ,6892,6957,6896 ,0,0,0}, + {7461,7783,6720 ,6892,6896,6893 ,0,0,0}, {7457,7455,7782 ,6894,6958,6895 ,0,0,0}, + {7459,7457,7783 ,6957,6894,6896 ,0,0,0}, {7453,7780,7455 ,6887,6886,6958 ,0,0,0}, + {7782,7455,7780 ,6895,6958,6886 ,0,0,0}, {7781,7451,7449 ,6889,6888,6959 ,0,0,0}, + {7780,7451,7781 ,6886,6888,6889 ,0,0,0}, {6644,7447,7445 ,5525,6890,6960 ,0,0,0}, + {7781,7449,7447 ,6889,6959,6890 ,0,0,0}, {7445,7443,6641 ,6960,6880,6882 ,0,0,0}, + {6641,6644,7445 ,6882,5525,6960 ,0,0,0}, {7410,6637,6642 ,6961,6885,6881 ,0,0,0}, + {7410,6642,7443 ,6961,6881,6880 ,0,0,0}, {7440,7436,6634 ,6883,6962,6884 ,0,0,0}, + {7410,7440,6637 ,6961,6883,6885 ,0,0,0}, {6635,6634,7409 ,6874,6884,6875 ,0,0,0}, + {7436,7409,6634 ,6962,6875,6884 ,0,0,0}, {6640,7413,7432 ,6963,6876,6878 ,0,0,0}, + {6635,7413,6640 ,6874,6876,6963 ,0,0,0}, {6649,6647,7433 ,6964,6877,6879 ,0,0,0}, + {6647,6640,7432 ,6877,6963,6878 ,0,0,0}, {6649,7416,6650 ,6964,6873,6872 ,0,0,0}, + {7416,6649,7433 ,6873,6964,6879 ,0,0,0}, {7429,7430,6657 ,6871,6865,6867 ,0,0,0}, + {7429,6657,6650 ,6871,6867,6872 ,0,0,0}, {7419,7427,7791 ,6866,6869,6965 ,0,0,0}, + {7419,7791,6657 ,6866,6965,6867 ,0,0,0}, {7779,7426,7778 ,6868,6870,6862 ,0,0,0}, + {7791,7427,7779 ,6965,6869,6868 ,0,0,0}, {5725,7778,7426 ,6863,6862,6870 ,0,0,0}, + {5695,7792,7353 ,6966,6967,6968 ,0,0,0}, {7793,7397,7794 ,6969,6970,6971 ,0,0,0}, + {7265,7266,7795 ,6972,6973,6974 ,0,0,0}, {7399,7796,7400 ,6975,6976,6977 ,0,0,0}, + {7797,7798,7341 ,6978,6979,6980 ,0,0,0}, {7799,7396,7800 ,6981,6982,6983 ,0,0,0}, + {7398,7352,7801 ,6984,6985,6986 ,0,0,0}, {7403,7802,7803 ,6987,6988,6989 ,0,0,0}, + {7394,7804,7395 ,6990,6991,6992 ,0,0,0}, {7404,7805,7277 ,6993,6994,6995 ,0,0,0}, + {7806,7404,7345 ,6996,6993,6997 ,0,0,0}, {7278,7807,7405 ,6998,6999,7000 ,0,0,0}, + {7808,7278,7277 ,7001,6998,6995 ,0,0,0}, {7406,7405,7809 ,7002,7000,7003 ,0,0,0}, + {7807,7809,7405 ,6999,7003,7000 ,0,0,0}, {7810,7390,7406 ,7004,7005,7002 ,0,0,0}, + {7406,7809,7810 ,7002,7003,7004 ,0,0,0}, {7390,7811,7408 ,7005,7006,7007 ,0,0,0}, + {7811,7390,7810 ,7006,7005,7004 ,0,0,0}, {7407,7408,7812 ,7008,7007,7009 ,0,0,0}, + {7811,7812,7408 ,7006,7009,7007 ,0,0,0}, {7813,5717,7407 ,7010,82,7008 ,0,0,0}, + {7407,7812,7813 ,7008,7009,7010 ,0,0,0}, {5716,5717,7813 ,7011,82,7010 ,0,0,0}, + {7345,7803,7806 ,6997,6989,6996 ,0,0,0}, {7805,7808,7277 ,6994,7001,6995 ,0,0,0}, + {7808,7807,7278 ,7001,6999,6998 ,0,0,0}, {7805,7404,7806 ,6994,6993,6996 ,0,0,0}, + {7802,7403,7395 ,6988,6987,6992 ,0,0,0}, {7803,7345,7403 ,6989,6997,6987 ,0,0,0}, + {7395,7804,7802 ,6992,6991,6988 ,0,0,0}, {7799,7804,7394 ,6981,6991,6990 ,0,0,0}, + {7814,7400,7796 ,7012,6977,6976 ,0,0,0}, {7398,7800,7396 ,6984,6983,6982 ,0,0,0}, + {7394,7396,7799 ,6990,6982,6981 ,0,0,0}, {7352,7400,7814 ,6985,6977,7012 ,0,0,0}, + {7352,7814,7801 ,6985,7012,6986 ,0,0,0}, {7800,7398,7801 ,6983,6984,6986 ,0,0,0}, + {7397,7265,7794 ,6970,6972,6971 ,0,0,0}, {7796,7399,7798 ,6976,6975,6979 ,0,0,0}, + {7797,7341,7340 ,6978,6980,7013 ,0,0,0}, {7341,7798,7399 ,6980,6979,6975 ,0,0,0}, + {7340,7397,7793 ,7013,6970,6969 ,0,0,0}, {7340,7793,7797 ,7013,6969,6978 ,0,0,0}, + {7266,7792,7795 ,6973,6967,6974 ,0,0,0}, {7794,7265,7795 ,6971,6972,6974 ,0,0,0}, + {5695,7353,5692 ,6966,6968,7014 ,0,0,0}, {7792,7266,7353 ,6967,6973,6968 ,0,0,0}, + {7814,5710,7801 ,730,730,730 ,0,0,0}, {7809,7807,7805 ,730,730,730 ,0,0,0}, + {7807,7808,7805 ,730,730,730 ,0,0,0}, {7805,7806,7810 ,730,730,730 ,0,0,0}, + {7810,7809,7805 ,730,730,730 ,0,0,0}, {7811,7806,7803 ,730,730,730 ,0,0,0}, + {7806,7811,7810 ,730,730,730 ,0,0,0}, {7802,7812,7803 ,730,730,730 ,0,0,0}, + {7811,7803,7812 ,730,730,730 ,0,0,0}, {7813,7802,5716 ,730,730,730 ,0,0,0}, + {7813,7812,7802 ,730,730,730 ,0,0,0}, {7804,7799,5714 ,730,730,730 ,0,0,0}, + {7802,7804,5716 ,730,730,730 ,0,0,0}, {7796,5705,5708 ,730,730,7015 ,0,0,0}, + {5711,5714,7800 ,730,730,730 ,0,0,0}, {7793,5699,5702 ,7016,7015,7017 ,0,0,0}, + {7798,5702,5704 ,730,7017,7017 ,0,0,0}, {5696,5698,7795 ,730,730,730 ,0,0,0}, + {5695,5671,5673 ,730,730,730 ,0,0,0}, {5669,5696,7792 ,7015,730,730 ,0,0,0}, + {5675,5689,5687 ,730,730,7017 ,0,0,0}, {5671,5690,5677 ,730,7017,7015 ,0,0,0}, + {5683,5679,5684 ,730,730,730 ,0,0,0}, {5679,5687,5684 ,730,7017,730 ,0,0,0}, + {5680,5679,5683 ,730,730,730 ,0,0,0}, {5675,5677,5689 ,730,7015,730 ,0,0,0}, + {5679,5675,5687 ,730,730,7017 ,0,0,0}, {5690,5671,5694 ,7017,730,730 ,0,0,0}, + {5689,5677,5690 ,730,7015,7017 ,0,0,0}, {5695,5694,5671 ,730,730,730 ,0,0,0}, + {7792,5673,5669 ,730,730,7015 ,0,0,0}, {7792,5695,5673 ,730,730,730 ,0,0,0}, + {5698,7794,7795 ,730,7016,730 ,0,0,0}, {7795,7792,5696 ,730,730,730 ,0,0,0}, + {7793,7794,5699 ,7016,7016,7015 ,0,0,0}, {5698,5699,7794 ,730,7015,7016 ,0,0,0}, + {5702,7798,7797 ,7017,730,730 ,0,0,0}, {5702,7797,7793 ,7017,730,7016 ,0,0,0}, + {5704,5705,7796 ,7017,730,730 ,0,0,0}, {7798,5704,7796 ,730,7017,730 ,0,0,0}, + {5708,5710,7814 ,7015,730,730 ,0,0,0}, {7796,5708,7814 ,730,7015,730 ,0,0,0}, + {7801,5711,7800 ,730,730,730 ,0,0,0}, {7801,5710,5711 ,730,730,730 ,0,0,0}, + {7804,5714,5716 ,730,730,730 ,0,0,0}, {7799,7800,5714 ,730,730,730 ,0,0,0}, + {7815,7816,5667 ,7018,7019,7020 ,0,0,0}, {5667,7817,7815 ,7020,7021,7018 ,0,0,0}, + {5667,5650,7817 ,7020,7022,7021 ,0,0,0}, {5667,7818,7819 ,7020,7023,7024 ,0,0,0}, + {7816,7818,5667 ,7019,7023,7020 ,0,0,0}, {5667,7820,7821 ,7020,7025,7026 ,0,0,0}, + {7819,7820,5667 ,7024,7025,7020 ,0,0,0}, {7821,7822,5667 ,7026,7027,7020 ,0,0,0}, + {7823,5667,7824 ,7028,7020,7029 ,0,0,0}, {5667,7822,7824 ,7020,7027,7029 ,0,0,0}, + {7825,5667,7826 ,7030,7020,7031 ,0,0,0}, {5667,7823,7826 ,7020,7028,7031 ,0,0,0}, + {7827,5667,7828 ,7032,7020,7033 ,0,0,0}, {5667,7825,7828 ,7020,7030,7033 ,0,0,0}, + {5666,5667,7827 ,7034,7020,7032 ,0,0,0}, {5649,7322,7817 ,7035,7036,7037 ,0,0,0}, + {7819,7818,7312 ,7038,7039,7040 ,0,0,0}, {7816,7815,7321 ,7041,7042,7043 ,0,0,0}, + {7821,7379,7822 ,7044,7045,7046 ,0,0,0}, {7311,7324,7820 ,7047,7048,7049 ,0,0,0}, + {7380,7205,7823 ,7050,7051,7052 ,0,0,0}, {7380,7824,7271 ,7050,7053,7054 ,0,0,0}, + {7269,7328,7825 ,7055,7056,7057 ,0,0,0}, {7825,7826,7269 ,7057,7058,7055 ,0,0,0}, + {7828,7328,7314 ,7059,7056,7060 ,0,0,0}, {7328,7828,7825 ,7056,7059,7057 ,0,0,0}, + {7302,7827,7314 ,7061,7062,7060 ,0,0,0}, {7828,7314,7827 ,7059,7060,7062 ,0,0,0}, + {7302,5665,5666 ,7061,7063,4910 ,0,0,0}, {5666,7827,7302 ,4910,7062,7061 ,0,0,0}, + {7379,7821,7324 ,7045,7044,7048 ,0,0,0}, {7205,7826,7823 ,7051,7058,7052 ,0,0,0}, + {7269,7826,7205 ,7055,7058,7051 ,0,0,0}, {7312,7818,7320 ,7040,7039,7064 ,0,0,0}, + {7271,7824,7822 ,7054,7053,7046 ,0,0,0}, {7380,7823,7824 ,7050,7052,7053 ,0,0,0}, + {7379,7271,7822 ,7045,7054,7046 ,0,0,0}, {7820,7324,7821 ,7049,7048,7044 ,0,0,0}, + {7819,7312,7311 ,7038,7040,7047 ,0,0,0}, {7311,7820,7819 ,7047,7049,7038 ,0,0,0}, + {7815,7322,7321 ,7042,7036,7043 ,0,0,0}, {7320,7816,7321 ,7064,7041,7043 ,0,0,0}, + {7818,7816,7320 ,7039,7041,7064 ,0,0,0}, {5649,7817,5650 ,7035,7037,4929 ,0,0,0}, + {7322,7815,7817 ,7036,7042,7037 ,0,0,0}, {7829,7830,5633 ,7018,7019,7065 ,0,0,0}, + {5633,7831,7829 ,7065,7021,7018 ,0,0,0}, {5633,5616,7831 ,7065,7066,7021 ,0,0,0}, + {5633,7832,7833 ,7065,7023,7024 ,0,0,0}, {7830,7832,5633 ,7019,7023,7065 ,0,0,0}, + {5633,7834,7835 ,7065,7025,7026 ,0,0,0}, {7833,7834,5633 ,7024,7025,7065 ,0,0,0}, + {7835,7836,5633 ,7026,7027,7065 ,0,0,0}, {7837,5633,7838 ,7028,7065,7029 ,0,0,0}, + {5633,7836,7838 ,7065,7027,7029 ,0,0,0}, {7839,5633,7840 ,7030,7065,7031 ,0,0,0}, + {5633,7837,7840 ,7065,7028,7031 ,0,0,0}, {7841,5633,7842 ,7032,7065,7033 ,0,0,0}, + {5633,7839,7842 ,7065,7030,7033 ,0,0,0}, {5632,5633,7841 ,7067,7065,7032 ,0,0,0}, + {5615,7371,7831 ,7068,7069,7070 ,0,0,0}, {7833,7832,7212 ,7071,7072,7073 ,0,0,0}, + {7830,7829,7251 ,7074,7075,7076 ,0,0,0}, {7835,7231,7836 ,7077,7078,7079 ,0,0,0}, + {7213,7376,7834 ,7047,7080,7081 ,0,0,0}, {7195,7374,7837 ,7082,7083,7084 ,0,0,0}, + {7195,7838,7375 ,7082,7085,7086 ,0,0,0}, {7373,7249,7839 ,7087,7088,7089 ,0,0,0}, + {7839,7840,7373 ,7089,7090,7087 ,0,0,0}, {7842,7249,7250 ,7091,7088,7092 ,0,0,0}, + {7249,7842,7839 ,7088,7091,7089 ,0,0,0}, {7372,7841,7250 ,7093,7094,7092 ,0,0,0}, + {7842,7250,7841 ,7091,7092,7094 ,0,0,0}, {7372,5631,5632 ,7093,4831,4942 ,0,0,0}, + {5632,7841,7372 ,4942,7094,7093 ,0,0,0}, {7231,7835,7376 ,7078,7077,7080 ,0,0,0}, + {7374,7840,7837 ,7083,7090,7084 ,0,0,0}, {7373,7840,7374 ,7087,7090,7083 ,0,0,0}, + {7212,7832,7248 ,7073,7072,7095 ,0,0,0}, {7375,7838,7836 ,7086,7085,7079 ,0,0,0}, + {7195,7837,7838 ,7082,7084,7085 ,0,0,0}, {7231,7375,7836 ,7078,7086,7079 ,0,0,0}, + {7834,7376,7835 ,7081,7080,7077 ,0,0,0}, {7833,7212,7213 ,7071,7073,7047 ,0,0,0}, + {7213,7834,7833 ,7047,7081,7071 ,0,0,0}, {7829,7371,7251 ,7075,7069,7076 ,0,0,0}, + {7248,7830,7251 ,7095,7074,7076 ,0,0,0}, {7832,7830,7248 ,7072,7074,7095 ,0,0,0}, + {5615,7831,5616 ,7068,7070,4899 ,0,0,0}, {7371,7829,7831 ,7069,7075,7070 ,0,0,0}, + {7843,7844,5599 ,7018,7019,7065 ,0,0,0}, {5599,7845,7843 ,7065,7021,7018 ,0,0,0}, + {5599,5582,7845 ,7065,7096,7021 ,0,0,0}, {5599,7846,7847 ,7065,7023,7024 ,0,0,0}, + {7844,7846,5599 ,7019,7023,7065 ,0,0,0}, {5599,7848,7849 ,7065,7025,7026 ,0,0,0}, + {7847,7848,5599 ,7024,7025,7065 ,0,0,0}, {7849,7850,5599 ,7026,7027,7065 ,0,0,0}, + {7851,5599,7852 ,7028,7065,7029 ,0,0,0}, {5599,7850,7852 ,7065,7027,7029 ,0,0,0}, + {7853,5599,7854 ,7030,7065,7031 ,0,0,0}, {5599,7851,7854 ,7065,7028,7031 ,0,0,0}, + {7855,5599,7856 ,7032,7065,7033 ,0,0,0}, {5599,7853,7856 ,7065,7030,7033 ,0,0,0}, + {5598,5599,7855 ,7097,7065,7032 ,0,0,0}, {5581,7369,7845 ,7098,7099,7100 ,0,0,0}, + {7847,7846,7334 ,7101,7102,7103 ,0,0,0}, {7844,7843,7361 ,7104,7105,7076 ,0,0,0}, + {7849,7333,7850 ,7106,7107,7108 ,0,0,0}, {7368,7367,7848 ,7109,7110,7111 ,0,0,0}, + {7245,7242,7851 ,7112,7113,7114 ,0,0,0}, {7245,7852,7362 ,7112,7115,7116 ,0,0,0}, + {7247,7246,7853 ,7117,7118,7119 ,0,0,0}, {7853,7854,7247 ,7119,7120,7117 ,0,0,0}, + {7856,7246,7244 ,7121,7118,7122 ,0,0,0}, {7246,7856,7853 ,7118,7121,7119 ,0,0,0}, + {7243,7855,7244 ,7123,7124,7122 ,0,0,0}, {7856,7244,7855 ,7121,7122,7124 ,0,0,0}, + {7243,5597,5598 ,7123,4831,4831 ,0,0,0}, {5598,7855,7243 ,4831,7124,7123 ,0,0,0}, + {7333,7849,7367 ,7107,7106,7110 ,0,0,0}, {7242,7854,7851 ,7113,7120,7114 ,0,0,0}, + {7247,7854,7242 ,7117,7120,7113 ,0,0,0}, {7334,7846,7360 ,7103,7102,7125 ,0,0,0}, + {7362,7852,7850 ,7116,7115,7108 ,0,0,0}, {7245,7851,7852 ,7112,7114,7115 ,0,0,0}, + {7333,7362,7850 ,7107,7116,7108 ,0,0,0}, {7848,7367,7849 ,7111,7110,7106 ,0,0,0}, + {7847,7334,7368 ,7101,7103,7109 ,0,0,0}, {7368,7848,7847 ,7109,7111,7101 ,0,0,0}, + {7843,7369,7361 ,7105,7099,7076 ,0,0,0}, {7360,7844,7361 ,7125,7104,7076 ,0,0,0}, + {7846,7844,7360 ,7102,7104,7125 ,0,0,0}, {5581,7845,5582 ,7098,7100,4865 ,0,0,0}, + {7369,7843,7845 ,7099,7105,7100 ,0,0,0}, {7857,7858,5565 ,7018,7019,7126 ,0,0,0}, + {5565,7859,7857 ,7126,7021,7018 ,0,0,0}, {5565,5548,7859 ,7126,7127,7021 ,0,0,0}, + {5565,7860,7861 ,7126,7023,7024 ,0,0,0}, {7858,7860,5565 ,7019,7023,7126 ,0,0,0}, + {5565,7862,7863 ,7126,7025,7026 ,0,0,0}, {7861,7862,5565 ,7024,7025,7126 ,0,0,0}, + {7863,7864,5565 ,7026,7027,7126 ,0,0,0}, {7865,5565,7866 ,7028,7126,7029 ,0,0,0}, + {5565,7864,7866 ,7126,7027,7029 ,0,0,0}, {7867,5565,7868 ,7030,7126,7031 ,0,0,0}, + {5565,7865,7868 ,7126,7028,7031 ,0,0,0}, {7869,5565,7870 ,7032,7126,7033 ,0,0,0}, + {5565,7867,7870 ,7126,7030,7033 ,0,0,0}, {5564,5565,7869 ,7128,7126,7032 ,0,0,0}, + {5547,7350,7859 ,7129,7099,7130 ,0,0,0}, {7861,7860,7355 ,7131,7132,7133 ,0,0,0}, + {7858,7857,7349 ,7041,7075,7134 ,0,0,0}, {7863,7356,7864 ,7135,7107,7136 ,0,0,0}, + {7354,7382,7862 ,7137,7138,7139 ,0,0,0}, {7232,7233,7865 ,7140,7141,7142 ,0,0,0}, + {7232,7866,7338 ,7140,7143,7144 ,0,0,0}, {7316,7317,7867 ,7145,7146,7147 ,0,0,0}, + {7867,7868,7316 ,7147,7148,7145 ,0,0,0}, {7870,7317,7402 ,7149,7146,7150 ,0,0,0}, + {7317,7870,7867 ,7146,7149,7147 ,0,0,0}, {7401,7869,7402 ,7151,7152,7150 ,0,0,0}, + {7870,7402,7869 ,7149,7150,7152 ,0,0,0}, {7401,5563,5564 ,7151,7153,4831 ,0,0,0}, + {5564,7869,7401 ,4831,7152,7151 ,0,0,0}, {7356,7863,7382 ,7107,7135,7138 ,0,0,0}, + {7233,7868,7865 ,7141,7148,7142 ,0,0,0}, {7316,7868,7233 ,7145,7148,7141 ,0,0,0}, + {7355,7860,7358 ,7133,7132,7154 ,0,0,0}, {7338,7866,7864 ,7144,7143,7136 ,0,0,0}, + {7232,7865,7866 ,7140,7142,7143 ,0,0,0}, {7356,7338,7864 ,7107,7144,7136 ,0,0,0}, + {7862,7382,7863 ,7139,7138,7135 ,0,0,0}, {7861,7355,7354 ,7131,7133,7137 ,0,0,0}, + {7354,7862,7861 ,7137,7139,7131 ,0,0,0}, {7857,7350,7349 ,7075,7099,7134 ,0,0,0}, + {7358,7858,7349 ,7154,7041,7134 ,0,0,0}, {7860,7858,7358 ,7132,7041,7154 ,0,0,0}, + {5547,7859,5548 ,7129,7130,4929 ,0,0,0}, {7350,7857,7859 ,7099,7075,7130 ,0,0,0}, + {5508,5507,7871 ,4777,21,7155 ,0,0,0}, {7215,7228,7872 ,7156,7157,7158 ,0,0,0}, + {7224,7873,7874 ,7159,7160,7161 ,0,0,0}, {7875,7876,7206 ,7162,7163,7164 ,0,0,0}, + {7877,7272,7230 ,7165,7166,7167 ,0,0,0}, {7283,7327,7878 ,7168,7169,7170 ,0,0,0}, + {7268,7879,7880 ,7171,7172,7173 ,0,0,0}, {7258,7881,7290 ,7174,7175,7176 ,0,0,0}, + {7882,7883,7287 ,7177,7178,7179 ,0,0,0}, {7884,7885,7296 ,7180,7181,7182 ,0,0,0}, + {7886,7288,7290 ,7183,7184,7176 ,0,0,0}, {7887,7888,7297 ,7185,7186,7187 ,0,0,0}, + {7887,7294,7885 ,7185,7188,7181 ,0,0,0}, {7298,7888,7889 ,7189,7186,7190 ,0,0,0}, + {7888,7298,7297 ,7186,7189,7187 ,0,0,0}, {7890,7293,7889 ,7191,7192,7190 ,0,0,0}, + {7298,7889,7293 ,7189,7190,7192 ,0,0,0}, {7890,7891,7291 ,7191,7193,7194 ,0,0,0}, + {7291,7293,7890 ,7194,7192,7191 ,0,0,0}, {7300,7891,7892 ,7195,7193,7196 ,0,0,0}, + {7891,7300,7291 ,7193,7195,7194 ,0,0,0}, {5530,7301,7892 ,7197,7198,7196 ,0,0,0}, + {7300,7892,7301 ,7195,7196,7198 ,0,0,0}, {5531,7301,5530 ,7199,7198,7197 ,0,0,0}, + {7258,7883,7881 ,7174,7178,7175 ,0,0,0}, {7294,7296,7885 ,7188,7182,7181 ,0,0,0}, + {7887,7297,7294 ,7185,7187,7188 ,0,0,0}, {7288,7886,7884 ,7184,7183,7180 ,0,0,0}, + {7884,7296,7288 ,7180,7182,7184 ,0,0,0}, {7886,7290,7881 ,7183,7176,7175 ,0,0,0}, + {7883,7258,7287 ,7178,7174,7179 ,0,0,0}, {7283,7878,7882 ,7168,7170,7177 ,0,0,0}, + {7283,7882,7287 ,7168,7177,7179 ,0,0,0}, {7272,7875,7206 ,7166,7162,7164 ,0,0,0}, + {7880,7327,7268 ,7173,7169,7171 ,0,0,0}, {7327,7880,7878 ,7169,7173,7170 ,0,0,0}, + {7207,7206,7876 ,7200,7164,7163 ,0,0,0}, {7268,7207,7879 ,7171,7200,7172 ,0,0,0}, + {7879,7207,7876 ,7172,7200,7163 ,0,0,0}, {7877,7875,7272 ,7165,7162,7166 ,0,0,0}, + {7893,7877,7230 ,7201,7165,7167 ,0,0,0}, {7215,7872,7893 ,7156,7158,7201 ,0,0,0}, + {7215,7893,7230 ,7156,7201,7167 ,0,0,0}, {7329,7871,7873 ,7202,7155,7160 ,0,0,0}, + {7874,7228,7224 ,7161,7157,7159 ,0,0,0}, {7228,7874,7872 ,7157,7161,7158 ,0,0,0}, + {7329,7873,7224 ,7202,7160,7159 ,0,0,0}, {7871,7329,5508 ,7155,7202,4777 ,0,0,0}, + {5496,7884,5499 ,730,7015,730 ,0,0,0}, {7874,7873,7879 ,730,730,730 ,0,0,0}, + {5506,5502,7883 ,730,730,730 ,0,0,0}, {5500,7886,7881 ,730,730,7015 ,0,0,0}, + {7880,7879,7873 ,730,730,730 ,0,0,0}, {5507,7882,7871 ,730,730,730 ,0,0,0}, + {7877,7893,7872 ,730,730,730 ,0,0,0}, {7872,7874,7876 ,730,730,730 ,0,0,0}, + {7872,7876,7875 ,730,730,730 ,0,0,0}, {7877,7872,7875 ,730,730,730 ,0,0,0}, + {7873,7871,7880 ,730,730,730 ,0,0,0}, {7876,7874,7879 ,730,730,730 ,0,0,0}, + {7871,7878,7880 ,730,730,730 ,0,0,0}, {7882,5507,7883 ,730,730,730 ,0,0,0}, + {7878,7871,7882 ,730,730,730 ,0,0,0}, {7883,5502,7881 ,730,730,7015 ,0,0,0}, + {7883,5507,5506 ,730,730,730 ,0,0,0}, {7886,5500,5499 ,730,730,730 ,0,0,0}, + {7881,5502,5500 ,7015,730,730 ,0,0,0}, {7885,7884,5496 ,730,7015,730 ,0,0,0}, + {7884,7886,5499 ,7015,730,730 ,0,0,0}, {7887,5496,5495 ,7015,730,730 ,0,0,0}, + {5496,7887,7885 ,730,7015,730 ,0,0,0}, {7887,5495,7888 ,7015,730,730 ,0,0,0}, + {5488,7888,5492 ,730,730,730 ,0,0,0}, {7888,5495,5492 ,730,730,730 ,0,0,0}, + {5488,5487,7889 ,730,730,7015 ,0,0,0}, {7889,7888,5488 ,7015,730,730 ,0,0,0}, + {7889,5487,7890 ,7015,730,7015 ,0,0,0}, {5491,7891,7890 ,730,730,7015 ,0,0,0}, + {7890,5487,5491 ,7015,730,730 ,0,0,0}, {7891,5486,7892 ,730,730,7015 ,0,0,0}, + {5486,7891,5491 ,730,730,730 ,0,0,0}, {5482,5530,5486 ,730,7015,730 ,0,0,0}, + {7892,5486,5530 ,7015,730,7015 ,0,0,0}, {5529,5511,5527 ,7015,7015,730 ,0,0,0}, + {5482,5481,5529 ,730,730,7015 ,0,0,0}, {5523,5518,5521 ,7015,7015,7015 ,0,0,0}, + {5515,5524,5512 ,7015,7015,730 ,0,0,0}, {5523,5515,5517 ,7015,7015,7015 ,0,0,0}, + {5518,5523,5517 ,7015,7015,7015 ,0,0,0}, {5527,5512,5524 ,730,730,7015 ,0,0,0}, + {5524,5515,5523 ,7015,7015,7015 ,0,0,0}, {5529,5481,5511 ,7015,730,7015 ,0,0,0}, + {5527,5511,5512 ,730,7015,730 ,0,0,0}, {5529,5530,5482 ,7015,7015,730 ,0,0,0}, + {5458,7189,7894 ,126,7203,7204 ,0,0,0}, {7895,7896,7191 ,7205,7206,7207 ,0,0,0}, + {7241,7897,7309 ,7208,7209,7210 ,0,0,0}, {7330,7332,7898 ,7211,7212,7213 ,0,0,0}, + {7899,7202,7900 ,7214,7215,7216 ,0,0,0}, {7901,7902,7227 ,7217,7218,7219 ,0,0,0}, + {7252,7903,7370 ,7220,7221,7222 ,0,0,0}, {7221,7904,7905 ,7223,7224,7225 ,0,0,0}, + {7219,7220,7906 ,7226,7227,7228 ,0,0,0}, {7217,7211,7907 ,7229,7230,7231 ,0,0,0}, + {7908,7218,7217 ,7232,7233,7229 ,0,0,0}, {7209,7210,7909 ,7234,7235,7236 ,0,0,0}, + {7910,7211,7209 ,7237,7230,7234 ,0,0,0}, {7208,7911,7210 ,7238,7239,7235 ,0,0,0}, + {7909,7210,7911 ,7236,7235,7239 ,0,0,0}, {7912,7208,7201 ,7240,7238,7241 ,0,0,0}, + {7208,7912,7911 ,7238,7240,7239 ,0,0,0}, {7201,7200,7913 ,7241,7242,7243 ,0,0,0}, + {7913,7912,7201 ,7243,7240,7241 ,0,0,0}, {7197,7914,7200 ,7244,7245,7242 ,0,0,0}, + {7913,7200,7914 ,7243,7242,7245 ,0,0,0}, {7915,7197,5480 ,7246,7244,82 ,0,0,0}, + {7197,7915,7914 ,7244,7246,7245 ,0,0,0}, {5478,7915,5480 ,7011,7246,82 ,0,0,0}, + {7218,7908,7904 ,7233,7232,7224 ,0,0,0}, {7907,7211,7910 ,7231,7230,7237 ,0,0,0}, + {7910,7209,7909 ,7237,7234,7236 ,0,0,0}, {7907,7908,7217 ,7231,7232,7229 ,0,0,0}, + {7905,7220,7221 ,7225,7227,7223 ,0,0,0}, {7904,7221,7218 ,7224,7223,7233 ,0,0,0}, + {7220,7905,7906 ,7227,7225,7228 ,0,0,0}, {7901,7219,7906 ,7217,7226,7228 ,0,0,0}, + {7916,7898,7332 ,7247,7213,7212 ,0,0,0}, {7252,7227,7902 ,7220,7219,7218 ,0,0,0}, + {7219,7901,7227 ,7226,7217,7219 ,0,0,0}, {7370,7916,7332 ,7222,7247,7212 ,0,0,0}, + {7370,7903,7916 ,7222,7221,7247 ,0,0,0}, {7902,7903,7252 ,7218,7221,7220 ,0,0,0}, + {7191,7896,7241 ,7207,7206,7208 ,0,0,0}, {7898,7900,7330 ,7213,7216,7211 ,0,0,0}, + {7899,7204,7202 ,7214,7248,7215 ,0,0,0}, {7202,7330,7900 ,7215,7211,7216 ,0,0,0}, + {7204,7895,7191 ,7248,7205,7207 ,0,0,0}, {7204,7899,7895 ,7248,7214,7205 ,0,0,0}, + {7309,7897,7894 ,7210,7209,7204 ,0,0,0}, {7896,7897,7241 ,7206,7209,7208 ,0,0,0}, + {5458,5455,7189 ,126,4726,7203 ,0,0,0}, {7894,7189,7309 ,7204,7203,7210 ,0,0,0}, + {7909,7907,7910 ,7249,7250,7251 ,0,0,0}, {5460,7896,5462 ,726,726,7252 ,0,0,0}, + {7912,7907,7911 ,7253,7250,7253 ,0,0,0}, {7907,7909,7911 ,7250,7249,7253 ,0,0,0}, + {7908,7912,7913 ,7254,7253,7249 ,0,0,0}, {7912,7908,7907 ,7253,7254,7250 ,0,0,0}, + {7913,7914,7904 ,7249,7249,7255 ,0,0,0}, {7904,7908,7913 ,7255,7254,7249 ,0,0,0}, + {7914,7905,7904 ,7249,7256,7255 ,0,0,0}, {7915,5478,7905 ,7257,7257,7256 ,0,0,0}, + {7915,7905,7914 ,7257,7256,7249 ,0,0,0}, {7906,5477,7901 ,7258,726,7259 ,0,0,0}, + {7905,5478,7906 ,7256,7257,7258 ,0,0,0}, {7916,7903,5472 ,7260,7254,7257 ,0,0,0}, + {5474,7902,5477 ,7252,7261,726 ,0,0,0}, {5465,7900,5466 ,726,7262,7252 ,0,0,0}, + {5471,5468,7898 ,726,7252,7263 ,0,0,0}, {7897,5460,5459 ,7253,726,726 ,0,0,0}, + {7895,5465,5462 ,726,726,7252 ,0,0,0}, {5458,5435,5434 ,726,726,726 ,0,0,0}, + {5433,7894,5459 ,7264,7253,726 ,0,0,0}, {5439,5451,5452 ,726,7257,726 ,0,0,0}, + {5434,5440,5454 ,726,7264,726 ,0,0,0}, {5446,5448,5442 ,7257,726,7257 ,0,0,0}, + {5448,5451,5442 ,726,7257,7257 ,0,0,0}, {5446,5442,5444 ,7257,7257,7257 ,0,0,0}, + {5452,5440,5439 ,726,7264,726 ,0,0,0}, {5451,5439,5442 ,7257,726,7257 ,0,0,0}, + {5456,5434,5454 ,726,726,726 ,0,0,0}, {5454,5440,5452 ,726,7264,726 ,0,0,0}, + {5435,5458,7894 ,726,726,7253 ,0,0,0}, {5434,5456,5458 ,726,726,726 ,0,0,0}, + {5459,7894,7897 ,726,7253,7253 ,0,0,0}, {5435,7894,5433 ,726,7253,7264 ,0,0,0}, + {5462,7896,7895 ,7252,726,726 ,0,0,0}, {7896,5460,7897 ,726,726,7253 ,0,0,0}, + {7900,5465,7899 ,7262,726,7262 ,0,0,0}, {7899,5465,7895 ,7262,726,726 ,0,0,0}, + {5468,5466,7898 ,7252,7252,7263 ,0,0,0}, {5466,7900,7898 ,7252,7262,7263 ,0,0,0}, + {7898,7916,5471 ,7263,7260,726 ,0,0,0}, {5474,5472,7903 ,7252,7257,7254 ,0,0,0}, + {5472,5471,7916 ,7257,726,7260 ,0,0,0}, {5477,7902,7901 ,726,7261,7259 ,0,0,0}, + {5474,7903,7902 ,7252,7254,7261 ,0,0,0}, {5477,7906,5478 ,726,7258,7257 ,0,0,0}, + {5408,7917,7183 ,4799,7265,7266 ,0,0,0}, {7918,7185,7919 ,7267,7268,7269 ,0,0,0}, + {7184,7359,7920 ,7270,7271,7272 ,0,0,0}, {7366,7921,7193 ,7273,7274,7275 ,0,0,0}, + {7922,7923,7365 ,7276,7277,7278 ,0,0,0}, {7924,7363,7925 ,7279,7280,7281 ,0,0,0}, + {7383,7335,7926 ,7282,7283,7284 ,0,0,0}, {7384,7927,7928 ,7285,7286,7287 ,0,0,0}, + {7238,7929,7239 ,7288,7289,7290 ,0,0,0}, {7385,7930,7236 ,7291,7292,7293 ,0,0,0}, + {7931,7385,7194 ,7294,7291,7295 ,0,0,0}, {7235,7932,7386 ,7296,7297,7298 ,0,0,0}, + {7933,7235,7236 ,7299,7296,7293 ,0,0,0}, {7387,7386,7934 ,7300,7298,7301 ,0,0,0}, + {7932,7934,7386 ,7297,7301,7298 ,0,0,0}, {7935,7336,7387 ,7302,7303,7300 ,0,0,0}, + {7387,7934,7935 ,7300,7301,7302 ,0,0,0}, {7336,7936,7389 ,7303,7304,7305 ,0,0,0}, + {7936,7336,7935 ,7304,7303,7302 ,0,0,0}, {7388,7389,7937 ,7306,7305,7307 ,0,0,0}, + {7936,7937,7389 ,7304,7307,7305 ,0,0,0}, {7938,5430,7388 ,7308,21,7306 ,0,0,0}, + {7388,7937,7938 ,7306,7307,7308 ,0,0,0}, {5429,5430,7938 ,7309,21,7308 ,0,0,0}, + {7194,7928,7931 ,7295,7287,7294 ,0,0,0}, {7930,7933,7236 ,7292,7299,7293 ,0,0,0}, + {7933,7932,7235 ,7299,7297,7296 ,0,0,0}, {7930,7385,7931 ,7292,7291,7294 ,0,0,0}, + {7927,7384,7239 ,7286,7285,7290 ,0,0,0}, {7928,7194,7384 ,7287,7295,7285 ,0,0,0}, + {7239,7929,7927 ,7290,7289,7286 ,0,0,0}, {7924,7929,7238 ,7279,7289,7288 ,0,0,0}, + {7939,7193,7921 ,7310,7275,7274 ,0,0,0}, {7383,7925,7363 ,7282,7281,7280 ,0,0,0}, + {7238,7363,7924 ,7288,7280,7279 ,0,0,0}, {7335,7193,7939 ,7283,7275,7310 ,0,0,0}, + {7335,7939,7926 ,7283,7310,7284 ,0,0,0}, {7925,7383,7926 ,7281,7282,7284 ,0,0,0}, + {7185,7184,7919 ,7268,7270,7269 ,0,0,0}, {7921,7366,7923 ,7274,7273,7277 ,0,0,0}, + {7922,7365,7364 ,7276,7278,7311 ,0,0,0}, {7365,7923,7366 ,7278,7277,7273 ,0,0,0}, + {7364,7185,7918 ,7311,7268,7267 ,0,0,0}, {7364,7918,7922 ,7311,7267,7276 ,0,0,0}, + {7359,7917,7920 ,7271,7265,7272 ,0,0,0}, {7919,7184,7920 ,7269,7270,7272 ,0,0,0}, + {5408,7183,5405 ,4799,7266,7199 ,0,0,0}, {7917,7359,7183 ,7265,7271,7266 ,0,0,0}, + {7930,5400,5397 ,730,7312,6103 ,0,0,0}, {5393,7934,5396 ,7313,730,730 ,0,0,0}, + {5403,7927,5407 ,7314,7015,7315 ,0,0,0}, {7931,7928,5402 ,730,730,7316 ,0,0,0}, + {7926,7920,7925 ,730,7317,7313 ,0,0,0}, {7929,7917,5408 ,730,7318,7319 ,0,0,0}, + {7918,7919,7939 ,7320,7316,7316 ,0,0,0}, {7921,7923,7918 ,7320,6103,7320 ,0,0,0}, + {7922,7918,7923 ,6111,7320,6103 ,0,0,0}, {7926,7939,7919 ,730,7316,7316 ,0,0,0}, + {7939,7921,7918 ,7316,7320,7320 ,0,0,0}, {7917,7925,7920 ,7318,7313,7317 ,0,0,0}, + {7920,7926,7919 ,7317,730,7316 ,0,0,0}, {7929,7924,7917 ,730,7316,7318 ,0,0,0}, + {7917,7924,7925 ,7318,7316,7313 ,0,0,0}, {5407,7927,5408 ,7315,7015,7319 ,0,0,0}, + {5408,7927,7929 ,7319,7015,730 ,0,0,0}, {5402,7928,5403 ,7316,730,7314 ,0,0,0}, + {5403,7928,7927 ,7314,730,7015 ,0,0,0}, {7931,5402,5400 ,730,7316,7312 ,0,0,0}, + {5397,7933,7930 ,6103,7017,730 ,0,0,0}, {5400,7930,7931 ,7312,730,730 ,0,0,0}, + {7933,5397,7932 ,7017,6103,7017 ,0,0,0}, {5396,7934,7932 ,730,730,7017 ,0,0,0}, + {7932,5397,5396 ,7017,6103,730 ,0,0,0}, {7934,5393,5392 ,730,7313,730 ,0,0,0}, + {5392,5388,7935 ,730,7316,730 ,0,0,0}, {7935,7934,5392 ,730,730,730 ,0,0,0}, + {7936,5388,5390 ,7016,7316,7313 ,0,0,0}, {5388,7936,7935 ,7316,7016,730 ,0,0,0}, + {5384,7937,5390 ,7015,730,7313 ,0,0,0}, {7936,5390,7937 ,7016,7313,730 ,0,0,0}, + {7938,5384,5429 ,730,7015,730 ,0,0,0}, {7938,7937,5384 ,730,730,7015 ,0,0,0}, + {5384,5386,5429 ,7015,7015,730 ,0,0,0}, {5427,5409,5424 ,730,730,730 ,0,0,0}, + {5386,5382,5427 ,7015,730,730 ,0,0,0}, {5421,5417,5418 ,730,730,7017 ,0,0,0}, + {5412,5423,5411 ,7015,7016,730 ,0,0,0}, {5421,5412,5415 ,730,7015,730 ,0,0,0}, + {5417,5421,5415 ,730,730,730 ,0,0,0}, {5424,5411,5423 ,730,730,7016 ,0,0,0}, + {5423,5412,5421 ,7016,7015,730 ,0,0,0}, {5427,5382,5409 ,730,730,730 ,0,0,0}, + {5424,5409,5411 ,730,730,730 ,0,0,0}, {5427,5429,5386 ,730,730,7015 ,0,0,0}, + {5940,7940,7941 ,7321,1711,7322 ,0,0,0}, {5930,5927,7942 ,7323,7324,7325 ,0,0,0}, + {7943,5929,5938 ,7326,7327,7328 ,0,0,0}, {7756,7944,7755 ,7329,7330,7331 ,0,0,0}, + {7945,7946,5934 ,7332,7333,7334 ,0,0,0}, {7753,7947,7752 ,7335,7336,7337 ,0,0,0}, + {7947,7754,7948 ,7336,7338,7339 ,0,0,0}, {7751,7752,7949 ,7340,7337,7341 ,0,0,0}, + {7947,7949,7752 ,7336,7341,7337 ,0,0,0}, {7950,7750,7751 ,1359,1359,7340 ,0,0,0}, + {7751,7949,7950 ,7340,7341,1359 ,0,0,0}, {7948,7754,7755 ,7339,7338,7331 ,0,0,0}, + {7947,7753,7754 ,7336,7335,7338 ,0,0,0}, {7944,7756,7757 ,7330,7329,7342 ,0,0,0}, + {7944,7948,7755 ,7330,7339,7331 ,0,0,0}, {7757,5934,7946 ,7342,7334,7333 ,0,0,0}, + {7946,7944,7757 ,7333,7330,7342 ,0,0,0}, {5933,7942,7945 ,7343,7325,7332 ,0,0,0}, + {5933,7945,5934 ,7343,7332,7334 ,0,0,0}, {5927,7951,7942 ,7324,7344,7325 ,0,0,0}, + {5933,5930,7942 ,7343,7323,7325 ,0,0,0}, {7943,7951,5929 ,7326,7344,7327 ,0,0,0}, + {5927,5929,7951 ,7324,7327,7344 ,0,0,0}, {7943,5937,7941 ,7326,7345,7322 ,0,0,0}, + {5938,5937,7943 ,7328,7345,7326 ,0,0,0}, {7940,5940,5906 ,1711,7321,1711 ,0,0,0}, + {7941,5937,5940 ,7322,7345,7321 ,0,0,0}, {7940,5908,7952 ,2197,7346,7346 ,0,0,0}, + {5908,7940,5906 ,7346,2197,2197 ,0,0,0}, {7953,7954,7760 ,1435,7347,7348 ,0,0,0}, + {7761,7759,7955 ,7349,7350,7351 ,0,0,0}, {7758,7763,7956 ,7352,7353,7354 ,0,0,0}, + {5919,7957,5917 ,7355,7356,7357 ,0,0,0}, {7958,7959,5925 ,7358,7359,7360 ,0,0,0}, + {5913,7960,5911 ,7361,7362,7363 ,0,0,0}, {5913,5915,7960 ,7361,7364,7362 ,0,0,0}, + {5910,5911,7961 ,7365,7363,7366 ,0,0,0}, {7960,7961,5911 ,7362,7366,7363 ,0,0,0}, + {7952,5908,5910 ,1790,1790,7365 ,0,0,0}, {5910,7961,7952 ,7365,7366,1790 ,0,0,0}, + {5917,7962,5915 ,7357,7367,7364 ,0,0,0}, {7960,5915,7962 ,7362,7364,7367 ,0,0,0}, + {7758,7963,7759 ,7352,7368,7350 ,0,0,0}, {5919,5923,7957 ,7355,7369,7356 ,0,0,0}, + {7957,7962,5917 ,7356,7367,7357 ,0,0,0}, {5923,5925,7959 ,7369,7360,7359 ,0,0,0}, + {7959,7957,5923 ,7359,7356,7369 ,0,0,0}, {7958,5925,7762 ,7358,7360,7370 ,0,0,0}, + {7955,7762,7761 ,7351,7370,7349 ,0,0,0}, {7762,7955,7958 ,7370,7351,7358 ,0,0,0}, + {7963,7955,7759 ,7368,7351,7350 ,0,0,0}, {7956,7764,7954 ,7354,7371,7347 ,0,0,0}, + {7764,7956,7763 ,7371,7354,7353 ,0,0,0}, {7963,7758,7956 ,7368,7352,7354 ,0,0,0}, + {7953,7760,7749 ,1435,7348,1435 ,0,0,0}, {7954,7764,7760 ,7347,7371,7348 ,0,0,0}, + {7749,7950,7953 ,1398,7372,1398 ,0,0,0}, {7950,7749,7750 ,7372,1398,7372 ,0,0,0}, + {7950,7954,7953 ,7373,730,730 ,0,0,0}, {7951,7960,7962 ,730,730,730 ,0,0,0}, + {7948,7955,7963 ,7374,7375,7375 ,0,0,0}, {7963,7956,7947 ,7375,730,7373 ,0,0,0}, + {7946,7959,7958 ,7375,7375,7375 ,0,0,0}, {7958,7955,7944 ,7375,7375,730 ,0,0,0}, + {7962,7957,7942 ,730,730,7376 ,0,0,0}, {7957,7959,7945 ,730,7375,7375 ,0,0,0}, + {7941,7961,7943 ,730,730,730 ,0,0,0}, {7960,7943,7961 ,730,730,730 ,0,0,0}, + {7941,7940,7952 ,730,730,730 ,0,0,0}, {7952,7961,7941 ,730,730,730 ,0,0,0}, + {7962,7942,7951 ,730,7376,730 ,0,0,0}, {7960,7951,7943 ,730,730,730 ,0,0,0}, + {7957,7945,7942 ,730,7375,7376 ,0,0,0}, {7959,7946,7945 ,7375,7375,7375 ,0,0,0}, + {7958,7944,7946 ,7375,730,7375 ,0,0,0}, {7955,7948,7944 ,7375,7374,730 ,0,0,0}, + {7963,7947,7948 ,7375,7373,7374 ,0,0,0}, {7956,7949,7947 ,730,730,7373 ,0,0,0}, + {7950,7949,7954 ,7373,730,730 ,0,0,0}, {7956,7954,7949 ,730,730,730 ,0,0,0}, + {7964,5838,7965 ,7377,1435,1435 ,0,0,0}, {7966,5854,7967 ,7378,7379,7379 ,0,0,0}, + {7968,5829,5833 ,7380,7380,7377 ,0,0,0}, {5861,7969,7970 ,7381,7381,7382 ,0,0,0}, + {5856,7971,5859 ,7378,7383,7383 ,0,0,0}, {5868,7972,5870 ,7384,7385,7385 ,0,0,0}, + {7973,5868,5863 ,7384,7384,7382 ,0,0,0}, {5873,5870,7974 ,7386,7385,7386 ,0,0,0}, + {7972,7974,5870 ,7385,7386,7385 ,0,0,0}, {7975,5876,5873 ,7387,7388,7386 ,0,0,0}, + {5873,7974,7975 ,7386,7386,7387 ,0,0,0}, {7970,7973,5863 ,7382,7384,7382 ,0,0,0}, + {7973,7972,5868 ,7384,7385,7384 ,0,0,0}, {5859,7969,5861 ,7383,7381,7381 ,0,0,0}, + {5861,7970,5863 ,7381,7382,7382 ,0,0,0}, {5856,7966,7971 ,7378,7378,7383 ,0,0,0}, + {5859,7971,7969 ,7383,7383,7381 ,0,0,0}, {5854,5829,7967 ,7379,7380,7379 ,0,0,0}, + {5856,5854,7966 ,7378,7379,7378 ,0,0,0}, {7968,5833,7964 ,7380,7377,7377 ,0,0,0}, + {7967,5829,7968 ,7379,7380,7380 ,0,0,0}, {5838,7964,5833 ,1435,7377,7377 ,0,0,0}, + {7965,5835,7976 ,1398,1398,1398 ,0,0,0}, {5835,7965,5838 ,1398,1398,1398 ,0,0,0}, + {7977,7978,5960 ,7389,7390,7390 ,0,0,0}, {7979,5956,7980 ,7391,7391,7392 ,0,0,0}, + {5958,5867,7981 ,7392,7393,7393 ,0,0,0}, {5948,7982,7983 ,7394,7395,7394 ,0,0,0}, + {5953,7984,5952 ,7396,7396,7395 ,0,0,0}, {5943,7985,7986 ,7397,7398,7397 ,0,0,0}, + {7985,5943,5947 ,7398,7397,7398 ,0,0,0}, {7987,5941,7986 ,7399,7399,7397 ,0,0,0}, + {5943,7986,5941 ,7397,7397,7399 ,0,0,0}, {7987,7976,5835 ,7399,1359,1359 ,0,0,0}, + {5835,5941,7987 ,1359,7399,7399 ,0,0,0}, {7980,5958,7981 ,7392,7392,7393 ,0,0,0}, + {5947,5948,7983 ,7398,7394,7394 ,0,0,0}, {7983,7985,5947 ,7394,7398,7398 ,0,0,0}, + {7982,5948,5952 ,7395,7394,7395 ,0,0,0}, {7979,7984,5953 ,7391,7396,7396 ,0,0,0}, + {5952,7984,7982 ,7395,7396,7395 ,0,0,0}, {5958,7980,5956 ,7392,7392,7391 ,0,0,0}, + {5953,5956,7979 ,7396,7391,7391 ,0,0,0}, {5960,7978,5867 ,7390,7390,7393 ,0,0,0}, + {5867,7978,7981 ,7393,7390,7393 ,0,0,0}, {7977,5960,5826 ,7389,7390,7400 ,0,0,0}, + {7975,7977,5826 ,7401,7402,7402 ,0,0,0}, {7975,5826,5876 ,7401,7402,7401 ,0,0,0}, + {7987,7968,7964 ,7403,7403,7404 ,0,0,0}, {7973,7981,7972 ,7375,7375,730 ,0,0,0}, + {7969,7979,7970 ,7375,730,730 ,0,0,0}, {7980,7973,7970 ,730,7375,730 ,0,0,0}, + {7966,7982,7971 ,7373,7375,7373 ,0,0,0}, {7984,7969,7971 ,730,7375,7373 ,0,0,0}, + {7967,7986,7985 ,7405,7406,730 ,0,0,0}, {7983,7966,7967 ,7373,7373,7405 ,0,0,0}, + {7987,7986,7968 ,7403,7406,7403 ,0,0,0}, {7964,7965,7976 ,7404,730,7407 ,0,0,0}, + {7976,7987,7964 ,7407,7403,7404 ,0,0,0}, {7986,7967,7968 ,7406,7405,7403 ,0,0,0}, + {7983,7967,7985 ,7373,7405,730 ,0,0,0}, {7982,7966,7983 ,7375,7373,7373 ,0,0,0}, + {7984,7971,7982 ,730,7373,7375 ,0,0,0}, {7979,7969,7984 ,730,7375,730 ,0,0,0}, + {7980,7970,7979 ,730,730,730 ,0,0,0}, {7981,7973,7980 ,7375,7375,730 ,0,0,0}, + {7978,7972,7981 ,730,730,7375 ,0,0,0}, {7974,7978,7977 ,7373,730,730 ,0,0,0}, + {7978,7974,7972 ,730,7373,730 ,0,0,0}, {7974,7977,7975 ,7373,730,7405 ,0,0,0}, + {7988,7747,7989 ,7408,7409,7410 ,0,0,0}, {7990,7745,7991 ,7411,7412,7412 ,0,0,0}, + {7992,7744,7748 ,7413,7413,7408 ,0,0,0}, {7765,7993,7994 ,7414,7414,7415 ,0,0,0}, + {7746,7995,7766 ,7411,7416,7416 ,0,0,0}, {7742,7996,7743 ,7417,7418,7418 ,0,0,0}, + {7997,7742,7741 ,7417,7417,7415 ,0,0,0}, {7739,7743,7998 ,7419,7418,7419 ,0,0,0}, + {7996,7998,7743 ,7418,7419,7418 ,0,0,0}, {7999,7738,7739 ,1790,1790,7419 ,0,0,0}, + {7739,7998,7999 ,7419,7419,1790 ,0,0,0}, {7994,7997,7741 ,7415,7417,7415 ,0,0,0}, + {7997,7996,7742 ,7417,7418,7417 ,0,0,0}, {7766,7993,7765 ,7416,7414,7414 ,0,0,0}, + {7765,7994,7741 ,7414,7415,7415 ,0,0,0}, {7746,7990,7995 ,7411,7411,7416 ,0,0,0}, + {7766,7995,7993 ,7416,7416,7414 ,0,0,0}, {7745,7744,7991 ,7412,7413,7412 ,0,0,0}, + {7746,7745,7990 ,7411,7412,7411 ,0,0,0}, {7992,7748,7988 ,7413,7408,7408 ,0,0,0}, + {7991,7744,7992 ,7412,7413,7413 ,0,0,0}, {7747,7988,7748 ,7409,7408,7408 ,0,0,0}, + {7768,8000,7989 ,7420,7420,7421 ,0,0,0}, {7768,7989,7747 ,7420,7421,7421 ,0,0,0}, + {8001,8002,7777 ,1711,7422,7422 ,0,0,0}, {8003,7775,8004 ,7423,7423,7424 ,0,0,0}, + {7776,7767,8005 ,7424,7425,7425 ,0,0,0}, {7772,8006,8007 ,7426,7427,7426 ,0,0,0}, + {7774,8008,7773 ,7428,7428,7427 ,0,0,0}, {7770,8009,8010 ,7429,7430,7429 ,0,0,0}, + {8009,7770,7771 ,7430,7429,7430 ,0,0,0}, {8011,7769,8010 ,7431,7431,7429 ,0,0,0}, + {7770,8010,7769 ,7429,7429,7431 ,0,0,0}, {8011,8000,7768 ,7431,7432,82 ,0,0,0}, + {7768,7769,8011 ,82,7431,7431 ,0,0,0}, {8004,7776,8005 ,7424,7424,7425 ,0,0,0}, + {7771,7772,8007 ,7430,7426,7426 ,0,0,0}, {8007,8009,7771 ,7426,7430,7430 ,0,0,0}, + {8006,7772,7773 ,7427,7426,7427 ,0,0,0}, {8003,8008,7774 ,7423,7428,7428 ,0,0,0}, + {7773,8008,8006 ,7427,7428,7427 ,0,0,0}, {7776,8004,7775 ,7424,7424,7423 ,0,0,0}, + {7774,7775,8003 ,7428,7423,7423 ,0,0,0}, {7777,8002,7767 ,7422,7422,7425 ,0,0,0}, + {7767,8002,8005 ,7425,7422,7425 ,0,0,0}, {8001,7777,7740 ,1711,7422,1711 ,0,0,0}, + {7740,7999,8001 ,2197,2197,2197 ,0,0,0}, {7999,7740,7738 ,2197,2197,2197 ,0,0,0}, + {7999,8002,8001 ,7433,730,730 ,0,0,0}, {7990,7991,8007 ,7375,7375,730 ,0,0,0}, + {7994,8004,7997 ,730,730,730 ,0,0,0}, {8004,8005,7996 ,730,7376,730 ,0,0,0}, + {7995,8008,7993 ,730,730,7376 ,0,0,0}, {8003,7994,7993 ,730,730,7376 ,0,0,0}, + {8006,7995,7990 ,7376,730,7375 ,0,0,0}, {8010,7992,7988 ,7375,7376,7376 ,0,0,0}, + {7991,7992,8009 ,7375,7376,7375 ,0,0,0}, {7989,8011,7988 ,7374,7376,7376 ,0,0,0}, + {8010,7988,8011 ,7375,7376,7376 ,0,0,0}, {8000,8011,7989 ,730,7376,7374 ,0,0,0}, + {8009,7992,8010 ,7375,7376,7375 ,0,0,0}, {8007,7991,8009 ,730,7375,7375 ,0,0,0}, + {8006,7990,8007 ,7376,7375,730 ,0,0,0}, {8008,7995,8006 ,730,730,7376 ,0,0,0}, + {8003,7993,8008 ,730,7376,730 ,0,0,0}, {8004,7994,8003 ,730,730,730 ,0,0,0}, + {8004,7996,7997 ,730,730,730 ,0,0,0}, {8005,7998,7996 ,7376,7433,730 ,0,0,0}, + {7999,7998,8002 ,7433,7433,730 ,0,0,0}, {8005,8002,7998 ,7376,730,7433 ,0,0,0}, + {7175,5348,5346 ,7434,4326,7435 ,0,0,0}, {7347,7275,7172 ,7436,7437,7438 ,0,0,0}, + {7176,7274,7177 ,7439,7440,7441 ,0,0,0}, {7182,7170,7318 ,7442,7443,7444 ,0,0,0}, + {7180,7323,7381 ,7445,7446,7447 ,0,0,0}, {7326,7325,7160 ,7448,7449,7450 ,0,0,0}, + {7310,7178,7179 ,7451,7452,7453 ,0,0,0}, {7154,7153,7225 ,7454,7455,7456 ,0,0,0}, + {7156,7214,7216 ,7457,7458,7459 ,0,0,0}, {7144,7261,7148 ,7460,7461,7462 ,0,0,0}, + {7267,7226,7152 ,7463,7464,7465 ,0,0,0}, {7259,7186,7138 ,7466,7467,7468 ,0,0,0}, + {7262,7140,7186 ,7469,7470,7467 ,0,0,0}, {7331,7135,7142 ,7471,7472,7473 ,0,0,0}, + {7139,7135,7260 ,7474,7472,7475 ,0,0,0}, {7254,7143,7147 ,7476,7477,7478 ,0,0,0}, + {7142,7143,7253 ,7473,7477,7479 ,0,0,0}, {7150,7237,7147 ,7480,7481,7478 ,0,0,0}, + {7254,7147,7237 ,7476,7478,7481 ,0,0,0}, {7150,7159,7229 ,7480,7482,7483 ,0,0,0}, + {7229,7237,7150 ,7483,7481,7480 ,0,0,0}, {7203,7159,7158 ,7484,7482,7485 ,0,0,0}, + {7159,7203,7229 ,7482,7484,7483 ,0,0,0}, {7162,7192,7158 ,7486,7487,7485 ,0,0,0}, + {7203,7158,7192 ,7484,7485,7487 ,0,0,0}, {7162,7167,7190 ,7486,7488,7489 ,0,0,0}, + {7190,7192,7162 ,7489,7487,7486 ,0,0,0}, {7240,7167,7166 ,7490,7488,7491 ,0,0,0}, + {7167,7240,7190 ,7488,7490,7489 ,0,0,0}, {5380,7188,7166 ,82,7492,7491 ,0,0,0}, + {7240,7166,7188 ,7490,7491,7492 ,0,0,0}, {5379,7188,5380 ,82,7492,82 ,0,0,0}, + {7253,7331,7142 ,7479,7471,7473 ,0,0,0}, {7253,7143,7254 ,7479,7477,7476 ,0,0,0}, + {7139,7260,7259 ,7474,7475,7466 ,0,0,0}, {7260,7135,7331 ,7475,7472,7471 ,0,0,0}, + {7186,7140,7138 ,7467,7470,7468 ,0,0,0}, {7259,7138,7139 ,7466,7468,7474 ,0,0,0}, + {7262,7261,7144 ,7469,7461,7460 ,0,0,0}, {7262,7144,7140 ,7469,7460,7470 ,0,0,0}, + {7148,7267,7152 ,7462,7463,7465 ,0,0,0}, {7261,7267,7148 ,7461,7463,7462 ,0,0,0}, + {7153,7226,7225 ,7455,7464,7456 ,0,0,0}, {7152,7226,7153 ,7465,7464,7455 ,0,0,0}, + {7156,7154,7214 ,7457,7454,7458 ,0,0,0}, {7154,7225,7214 ,7454,7456,7458 ,0,0,0}, + {7326,7161,7216 ,7448,7493,7459 ,0,0,0}, {7161,7156,7216 ,7493,7457,7459 ,0,0,0}, + {7325,7179,7160 ,7449,7453,7450 ,0,0,0}, {7326,7160,7161 ,7448,7450,7493 ,0,0,0}, + {7310,7319,7178 ,7451,7494,7452 ,0,0,0}, {7325,7310,7179 ,7449,7451,7453 ,0,0,0}, + {7318,7170,7319 ,7444,7443,7494 ,0,0,0}, {7178,7319,7170 ,7452,7494,7443 ,0,0,0}, + {7180,7182,7323 ,7445,7442,7446 ,0,0,0}, {7182,7318,7323 ,7442,7444,7446 ,0,0,0}, + {7347,7171,7381 ,7436,7495,7447 ,0,0,0}, {7171,7180,7381 ,7495,7445,7447 ,0,0,0}, + {7275,7176,7172 ,7437,7439,7438 ,0,0,0}, {7347,7172,7171 ,7436,7438,7495 ,0,0,0}, + {7274,7276,7177 ,7440,7496,7441 ,0,0,0}, {7275,7274,7176 ,7437,7440,7439 ,0,0,0}, + {5348,7175,7276 ,4326,7434,7496 ,0,0,0}, {7177,7276,7175 ,7441,7496,7434 ,0,0,0}, + {8012,5296,5295 ,7497,763,7498 ,0,0,0}, {8013,7168,8014 ,7499,7500,7501 ,0,0,0}, + {8015,7181,7173 ,7502,7503,7504 ,0,0,0}, {8016,8017,7157 ,7505,7506,7507 ,0,0,0}, + {8018,8019,7165 ,7508,7509,7510 ,0,0,0}, {8020,7145,8021 ,7511,7512,7513 ,0,0,0}, + {7149,8022,8021 ,7514,7515,7513 ,0,0,0}, {8023,7137,8024 ,7516,7517,7518 ,0,0,0}, + {7136,8020,8024 ,7519,7511,7518 ,0,0,0}, {8025,7151,7146 ,7520,7521,7522 ,0,0,0}, + {7146,8023,8025 ,7522,7516,7520 ,0,0,0}, {7151,8026,7163 ,7521,7523,7524 ,0,0,0}, + {8026,7151,8025 ,7523,7521,7520 ,0,0,0}, {7164,7163,8027 ,7525,7524,7526 ,0,0,0}, + {8026,8027,7163 ,7523,7526,7524 ,0,0,0}, {5314,7164,8028 ,761,7525,7527 ,0,0,0}, + {7164,8027,8028 ,7525,7526,7527 ,0,0,0}, {5313,7164,5314 ,761,7525,761 ,0,0,0}, + {7136,8024,7137 ,7519,7518,7517 ,0,0,0}, {7146,7137,8023 ,7522,7517,7516 ,0,0,0}, + {7141,7145,8020 ,7528,7512,7511 ,0,0,0}, {7136,7141,8020 ,7519,7528,7511 ,0,0,0}, + {7155,8022,7149 ,7529,7515,7514 ,0,0,0}, {7145,7149,8021 ,7512,7514,7513 ,0,0,0}, + {7157,8017,7155 ,7507,7506,7529 ,0,0,0}, {8022,7155,8017 ,7515,7529,7506 ,0,0,0}, + {7165,8019,7157 ,7510,7509,7507 ,0,0,0}, {8019,8016,7157 ,7509,7505,7507 ,0,0,0}, + {7169,8013,8018 ,7530,7499,7508 ,0,0,0}, {7169,8018,7165 ,7530,7508,7510 ,0,0,0}, + {7168,7181,8014 ,7500,7503,7501 ,0,0,0}, {7169,7168,8013 ,7530,7500,7499 ,0,0,0}, + {8015,7173,8012 ,7502,7504,7497 ,0,0,0}, {8014,7181,8015 ,7501,7503,7502 ,0,0,0}, + {5296,8012,7174 ,763,7497,7531 ,0,0,0}, {8012,7173,7174 ,7497,7504,7531 ,0,0,0}, + {8027,8026,8025 ,7015,7532,7017 ,0,0,0}, {5300,8014,8015 ,7016,7015,7015 ,0,0,0}, + {8020,8023,8024 ,7533,7534,7535 ,0,0,0}, {8025,8020,8027 ,7017,7533,7015 ,0,0,0}, + {8027,8020,8028 ,7015,7533,7016 ,0,0,0}, {8020,8025,8023 ,7533,7017,7534 ,0,0,0}, + {8021,8028,8020 ,7536,7016,7533 ,0,0,0}, {8028,8022,5314 ,7016,730,7015 ,0,0,0}, + {8022,8028,8021 ,730,7016,7536 ,0,0,0}, {8019,5309,8016 ,7535,730,7320 ,0,0,0}, + {8022,8017,5314 ,730,6104,7015 ,0,0,0}, {8013,5303,8018 ,730,730,7534 ,0,0,0}, + {5306,8019,8018 ,7537,7535,7534 ,0,0,0}, {8012,5295,5299 ,7016,7015,730 ,0,0,0}, + {8015,5301,5300 ,7015,730,7016 ,0,0,0}, {5292,5280,5294 ,730,730,730 ,0,0,0}, + {5294,5278,5295 ,730,7016,7015 ,0,0,0}, {5291,5288,5292 ,730,730,730 ,0,0,0}, + {5280,5286,5285 ,730,7016,7016 ,0,0,0}, {5288,5280,5292 ,730,730,730 ,0,0,0}, + {5280,5279,5294 ,730,730,730 ,0,0,0}, {5280,5288,5286 ,730,730,7016 ,0,0,0}, + {5278,5299,5295 ,7016,730,7015 ,0,0,0}, {5279,5278,5294 ,730,7016,730 ,0,0,0}, + {5301,8015,5299 ,730,7015,730 ,0,0,0}, {5299,8015,8012 ,730,7015,7016 ,0,0,0}, + {5300,5303,8014 ,7016,730,7015 ,0,0,0}, {8018,5303,5305 ,7534,730,7537 ,0,0,0}, + {8014,5303,8013 ,7015,730,730 ,0,0,0}, {8018,5305,5306 ,7534,7537,7537 ,0,0,0}, + {5309,8017,8016 ,730,6104,7320 ,0,0,0}, {8019,5306,5309 ,7535,7537,730 ,0,0,0}, + {5314,8017,5311 ,7015,6104,730 ,0,0,0}, {5309,5311,8017 ,730,730,6104 ,0,0,0}, + {6223,6222,8029 ,7538,7539,7540 ,0,0,0}, {8030,6214,6223 ,7541,7542,7538 ,0,0,0}, + {8030,8031,6214 ,7541,82,7542 ,0,0,0}, {8029,8030,6223 ,7540,7541,7538 ,0,0,0}, + {6222,6593,8032 ,7539,7543,7544 ,0,0,0}, {6252,6251,8033 ,7545,7546,7547 ,0,0,0}, + {8034,8032,6593 ,7548,7544,7543 ,0,0,0}, {6593,6252,8034 ,7543,7545,7548 ,0,0,0}, + {8033,8034,6252 ,7547,7548,7545 ,0,0,0}, {6222,8032,8029 ,7539,7544,7540 ,0,0,0}, + {8033,6251,8035 ,7547,7546,7549 ,0,0,0}, {6250,8036,8035 ,7550,7551,7549 ,0,0,0}, + {8035,6251,6250 ,7549,7546,7550 ,0,0,0}, {8036,6250,6225 ,7551,7550,7552 ,0,0,0}, + {6238,8037,6225 ,7553,7554,7552 ,0,0,0}, {6238,6228,8038 ,7553,7555,7556 ,0,0,0}, + {6238,8038,8037 ,7553,7556,7554 ,0,0,0}, {8039,6219,8040 ,7557,7558,7559 ,0,0,0}, + {8038,6228,8039 ,7556,7555,7557 ,0,0,0}, {8039,6228,6219 ,7557,7555,7558 ,0,0,0}, + {6219,6221,8040 ,7558,7559,7559 ,0,0,0}, {8036,6225,8037 ,7551,7552,7554 ,0,0,0}, + {6215,8031,8041 ,7560,82,7561 ,0,0,0}, {8031,6215,6214 ,82,7560,7542 ,0,0,0}, + {8042,6257,8041 ,7562,7563,7561 ,0,0,0}, {6215,8041,6257 ,7560,7561,7563 ,0,0,0}, + {8042,8043,6471 ,7562,7564,7565 ,0,0,0}, {6471,6257,8042 ,7565,7563,7562 ,0,0,0}, + {6296,8043,8044 ,7566,7564,7567 ,0,0,0}, {8043,6296,6471 ,7564,7566,7565 ,0,0,0}, + {8045,6297,8044 ,7568,7569,7567 ,0,0,0}, {6296,8044,6297 ,7566,7567,7569 ,0,0,0}, + {8045,8046,6293 ,7568,7570,7571 ,0,0,0}, {6293,6297,8045 ,7571,7569,7568 ,0,0,0}, + {6261,8046,8047 ,7572,7570,7573 ,0,0,0}, {8046,6261,6293 ,7570,7572,7571 ,0,0,0}, + {8048,6280,8047 ,7574,7575,7573 ,0,0,0}, {6261,8047,6280 ,7572,7573,7575 ,0,0,0}, + {8048,8049,6281 ,7574,7576,7577 ,0,0,0}, {6281,6280,8048 ,7577,7575,7574 ,0,0,0}, + {6283,8049,8050 ,7578,7576,7579 ,0,0,0}, {8049,6283,6281 ,7576,7578,7577 ,0,0,0}, + {6283,8050,6284 ,7578,7579,7580 ,0,0,0}, {6284,8050,8051 ,7580,7579,7580 ,0,0,0}, + {7109,7115,8051 ,7581,7581,7581 ,0,0,0}, {8051,5721,7100 ,7581,7581,7581 ,0,0,0}, + {7100,7106,8051 ,7581,7581,7581 ,0,0,0}, {7120,8051,7115 ,7581,7581,7581 ,0,0,0}, + {7106,7109,8051 ,7581,7581,7581 ,0,0,0}, {7124,7083,8051 ,7581,7581,7581 ,0,0,0}, + {7124,8051,7120 ,7581,7581,7581 ,0,0,0}, {7083,7095,8051 ,7581,7581,7581 ,0,0,0}, + {6284,8051,7094 ,7581,7581,7581 ,0,0,0}, {7095,7094,8051 ,7581,7581,7581 ,0,0,0}, + {8040,6221,6667 ,7582,7582,7582 ,0,0,0}, {6667,6694,8040 ,7582,7582,7582 ,0,0,0}, + {8040,6680,6660 ,7582,7582,7582 ,0,0,0}, {6694,6680,8040 ,7582,7582,7582 ,0,0,0}, + {8040,6662,6676 ,7582,7582,7582 ,0,0,0}, {6660,6662,8040 ,7582,7582,7582 ,0,0,0}, + {8040,6669,6653 ,7582,7582,7582 ,0,0,0}, {6676,6669,8040 ,7582,7582,7582 ,0,0,0}, + {6657,8040,6652 ,7582,7582,7582 ,0,0,0}, {6653,6652,8040 ,7582,7582,7582 ,0,0,0}, + {8048,5726,5724 ,726,726,726 ,0,0,0}, {8041,8031,5726 ,726,726,726 ,0,0,0}, + {8050,8049,5724 ,726,726,726 ,0,0,0}, {5724,8049,8048 ,726,726,726 ,0,0,0}, + {5724,5718,8051 ,726,726,726 ,0,0,0}, {8051,8050,5724 ,726,726,726 ,0,0,0}, + {5727,5721,8051 ,7583,7583,726 ,0,0,0}, {5727,8051,5718 ,7583,726,726 ,0,0,0}, + {8048,8047,5726 ,726,726,726 ,0,0,0}, {5726,8046,8045 ,726,726,726 ,0,0,0}, + {8047,8046,5726 ,726,726,726 ,0,0,0}, {5726,8044,8043 ,726,726,726 ,0,0,0}, + {8045,8044,5726 ,726,726,726 ,0,0,0}, {5726,8042,8041 ,726,726,726 ,0,0,0}, + {8043,8042,5726 ,726,726,726 ,0,0,0}, {8030,5726,8031 ,726,726,726 ,0,0,0}, + {8029,8032,5726 ,726,726,726 ,0,0,0}, {8029,5726,8030 ,726,726,726 ,0,0,0}, + {8034,8033,5726 ,726,726,726 ,0,0,0}, {8034,5726,8032 ,726,726,726 ,0,0,0}, + {8035,8036,5726 ,726,726,726 ,0,0,0}, {8035,5726,8033 ,726,726,726 ,0,0,0}, + {8037,8038,5726 ,726,726,726 ,0,0,0}, {8037,5726,8036 ,726,726,726 ,0,0,0}, + {5726,8038,7778 ,726,726,726 ,0,0,0}, {8040,7778,8039 ,726,726,726 ,0,0,0}, + {7778,8038,8039 ,726,726,726 ,0,0,0}, {7779,7778,8040 ,726,726,726 ,0,0,0}, + {6657,7791,8040 ,7583,726,726 ,0,0,0}, {7779,8040,7791 ,726,726,726 ,0,0,0}, + {5256,8052,6510 ,7584,7585,7586 ,0,0,0}, {8053,6483,8054 ,7587,7588,7589 ,0,0,0}, + {6521,6443,8055 ,7590,7591,7592 ,0,0,0}, {6210,8056,6472 ,7593,7594,7595 ,0,0,0}, + {8057,8058,6213 ,4334,7596,7597 ,0,0,0}, {8059,6218,8060 ,7598,7599,7600 ,0,0,0}, + {6217,6475,8061 ,7601,7602,7603 ,0,0,0}, {6275,6267,8062 ,7604,7605,7606 ,0,0,0}, + {6271,8063,6267 ,7607,7608,7605 ,0,0,0}, {6272,8064,8065 ,7609,7610,7611 ,0,0,0}, + {6275,8066,6274 ,7604,7612,7613 ,0,0,0}, {8067,6285,8065 ,7614,7615,7611 ,0,0,0}, + {6272,8065,6285 ,7609,7611,7615 ,0,0,0}, {8067,8068,6278 ,7614,7616,7617 ,0,0,0}, + {6278,6285,8067 ,7617,7615,7614 ,0,0,0}, {6287,8068,8069 ,7618,7616,7619 ,0,0,0}, + {8068,6287,6278 ,7616,7618,7617 ,0,0,0}, {8070,6247,8069 ,7620,7621,7619 ,0,0,0}, + {6287,8069,6247 ,7618,7619,7621 ,0,0,0}, {8070,5275,5276 ,7620,7622,4289 ,0,0,0}, + {5276,6247,8070 ,4289,7621,7620 ,0,0,0}, {8062,6267,8063 ,7606,7605,7608 ,0,0,0}, + {8064,6274,8066 ,7610,7613,7612 ,0,0,0}, {6274,8064,6272 ,7613,7610,7609 ,0,0,0}, + {8062,8066,6275 ,7606,7612,7604 ,0,0,0}, {8059,8063,6271 ,7598,7608,7607 ,0,0,0}, + {6217,8061,8060 ,7601,7603,7600 ,0,0,0}, {6217,8060,6218 ,7601,7600,7599 ,0,0,0}, + {6271,6218,8059 ,7607,7599,7598 ,0,0,0}, {6475,8071,8061 ,7602,7623,7603 ,0,0,0}, + {8071,6475,6472 ,7623,7602,7595 ,0,0,0}, {8058,8056,6210 ,7596,7594,7593 ,0,0,0}, + {8056,8071,6472 ,7594,7623,7595 ,0,0,0}, {6213,8058,6210 ,7597,7596,7593 ,0,0,0}, + {6511,8053,8057 ,7624,7587,4334 ,0,0,0}, {6511,8057,6213 ,7624,4334,7597 ,0,0,0}, + {6483,6521,8054 ,7588,7590,7589 ,0,0,0}, {6511,6483,8053 ,7624,7588,7587 ,0,0,0}, + {6443,8052,8055 ,7591,7585,7592 ,0,0,0}, {8054,6521,8055 ,7589,7590,7592 ,0,0,0}, + {5256,6510,5254 ,7584,7586,4535 ,0,0,0}, {8052,6443,6510 ,7585,7591,7586 ,0,0,0}, + {8058,5267,8056 ,726,7625,726 ,0,0,0}, {8067,8065,8068 ,726,726,726 ,0,0,0}, + {8070,8069,8068 ,726,726,726 ,0,0,0}, {8066,8062,8064 ,726,726,726 ,0,0,0}, + {8068,8065,8062 ,726,726,726 ,0,0,0}, {8068,8062,8063 ,726,726,726 ,0,0,0}, + {8064,8062,8065 ,726,726,726 ,0,0,0}, {8063,8059,8070 ,726,726,726 ,0,0,0}, + {8070,8068,8063 ,726,726,726 ,0,0,0}, {8059,8060,5273 ,726,726,7626 ,0,0,0}, + {8059,5275,8070 ,726,726,726 ,0,0,0}, {8071,5269,5270 ,726,726,726 ,0,0,0}, + {5270,5273,8061 ,726,7626,726 ,0,0,0}, {8054,5258,5261 ,726,7627,726 ,0,0,0}, + {5263,5264,8057 ,726,7625,726 ,0,0,0}, {8055,5257,5258 ,7626,7627,7627 ,0,0,0}, + {5253,5238,5237 ,7626,7625,726 ,0,0,0}, {5256,5237,8052 ,726,726,726 ,0,0,0}, + {5249,5240,5250 ,726,7627,7625 ,0,0,0}, {5240,5249,5247 ,7627,726,726 ,0,0,0}, + {5249,5250,5244 ,726,7625,7627 ,0,0,0}, {5250,5253,5252 ,7625,7626,7628 ,0,0,0}, + {5240,5238,5250 ,7627,7625,7625 ,0,0,0}, {5240,5247,5241 ,7627,726,726 ,0,0,0}, + {5256,5253,5237 ,726,7626,726 ,0,0,0}, {5253,5250,5238 ,7626,7625,7625 ,0,0,0}, + {5235,8052,5237 ,726,726,726 ,0,0,0}, {8055,8052,5257 ,7626,726,7627 ,0,0,0}, + {5235,5257,8052 ,726,7627,726 ,0,0,0}, {8054,5261,8053 ,726,726,726 ,0,0,0}, + {5258,8054,8055 ,7627,726,7626 ,0,0,0}, {5263,8057,8053 ,726,726,726 ,0,0,0}, + {8053,5261,5263 ,726,726,726 ,0,0,0}, {5264,5267,8058 ,7625,7625,726 ,0,0,0}, + {8057,5264,8058 ,726,7625,726 ,0,0,0}, {8056,5269,8071 ,726,726,726 ,0,0,0}, + {8056,5267,5269 ,726,7625,726 ,0,0,0}, {5273,8060,8061 ,7626,726,726 ,0,0,0}, + {8061,8071,5270 ,726,726,726 ,0,0,0}, {5273,5275,8059 ,7626,726,726 ,0,0,0}, + {5217,8072,6491 ,4303,7629,7630 ,0,0,0}, {6414,6448,8073 ,7631,7632,7633 ,0,0,0}, + {6580,6492,8074 ,7634,7635,7636 ,0,0,0}, {6476,8075,6477 ,7637,7638,7639 ,0,0,0}, + {8076,8077,6413 ,7640,7641,7642 ,0,0,0}, {8078,8079,6258 ,7643,7644,7645 ,0,0,0}, + {8078,6478,8080 ,7643,7646,7647 ,0,0,0}, {8081,8082,6256 ,7648,7649,7650 ,0,0,0}, + {6256,6255,8081 ,7650,7651,7648 ,0,0,0}, {6439,8082,8083 ,7652,7649,7653 ,0,0,0}, + {8082,6439,6256 ,7649,7652,7650 ,0,0,0}, {8084,6438,8083 ,7654,7655,7653 ,0,0,0}, + {6439,8083,6438 ,7652,7653,7655 ,0,0,0}, {8084,5231,5232 ,7654,126,7656 ,0,0,0}, + {5232,6438,8084 ,7656,7655,7654 ,0,0,0}, {8075,6476,8077 ,7638,7637,7641 ,0,0,0}, + {8079,6255,6258 ,7644,7651,7645 ,0,0,0}, {8081,6255,8079 ,7648,7651,7644 ,0,0,0}, + {8073,6448,8085 ,7633,7632,7657 ,0,0,0}, {8080,6478,6477 ,7647,7646,7639 ,0,0,0}, + {8078,6258,6478 ,7643,7645,7646 ,0,0,0}, {8075,8080,6477 ,7638,7647,7639 ,0,0,0}, + {6413,8077,6476 ,7642,7641,7637 ,0,0,0}, {6414,8073,8076 ,7631,7633,7640 ,0,0,0}, + {8076,6413,6414 ,7640,7642,7631 ,0,0,0}, {6492,8072,8074 ,7635,7629,7636 ,0,0,0}, + {8085,6580,8074 ,7657,7634,7636 ,0,0,0}, {6448,6580,8085 ,7632,7634,7657 ,0,0,0}, + {5217,6491,5218 ,4303,7630,82 ,0,0,0}, {8072,6492,6491 ,7629,7635,7630 ,0,0,0}, + {8079,8078,5214 ,726,7658,7659 ,0,0,0}, {8072,8077,8073 ,7660,7661,726 ,0,0,0}, + {8072,8075,8077 ,7660,7661,7661 ,0,0,0}, {5216,8080,5217 ,7659,726,726 ,0,0,0}, + {8076,8073,8077 ,7661,726,7661 ,0,0,0}, {8074,8072,8073 ,7659,7660,726 ,0,0,0}, + {8075,8072,5217 ,7661,7660,726 ,0,0,0}, {8085,8074,8073 ,726,7659,726 ,0,0,0}, + {8075,5217,8080 ,7661,726,726 ,0,0,0}, {5214,8078,5216 ,7659,7658,7659 ,0,0,0}, + {5216,8078,8080 ,7659,7658,726 ,0,0,0}, {5212,8081,8079 ,726,5488,726 ,0,0,0}, + {5214,5212,8079 ,7659,726,726 ,0,0,0}, {5210,8081,5212 ,726,5488,726 ,0,0,0}, + {5210,8082,8081 ,726,7662,5488 ,0,0,0}, {8083,8082,5207 ,5471,7662,7661 ,0,0,0}, + {5210,5207,8082 ,726,7661,7662 ,0,0,0}, {5206,8083,5207 ,726,5471,7661 ,0,0,0}, + {8084,5206,5204 ,7663,726,7661 ,0,0,0}, {5206,8084,8083 ,726,7663,5471 ,0,0,0}, + {5203,5231,5204 ,7658,726,7661 ,0,0,0}, {8084,5204,5231 ,7663,7661,726 ,0,0,0}, + {5223,5219,5220 ,7658,7664,726 ,0,0,0}, {5223,5229,5219 ,7658,7665,7664 ,0,0,0}, + {5226,5223,5225 ,7666,7658,7667 ,0,0,0}, {5226,5229,5223 ,7666,7665,7658 ,0,0,0}, + {5231,5203,5229 ,726,7658,7665 ,0,0,0}, {5219,5229,5203 ,7664,7665,7658 ,0,0,0}, + {8086,5757,8087 ,726,726,726 ,0,0,0}, {5757,8088,8087 ,726,726,726 ,0,0,0}, + {8089,8090,5757 ,726,726,726 ,0,0,0}, {5757,8086,8089 ,726,726,726 ,0,0,0}, + {8091,8092,5757 ,726,726,726 ,0,0,0}, {8091,5757,8090 ,726,726,726 ,0,0,0}, + {5749,8093,8094 ,7583,726,7661 ,0,0,0}, {5757,8095,8096 ,726,726,726 ,0,0,0}, + {5749,8097,8098 ,7583,7658,7661 ,0,0,0}, {8099,5749,8100 ,726,7583,726 ,0,0,0}, + {8101,8102,5749 ,726,726,7583 ,0,0,0}, {8103,8100,5749 ,726,726,7583 ,0,0,0}, + {5749,8099,8104 ,7583,726,5489 ,0,0,0}, {8101,5749,8105 ,726,7583,7583 ,0,0,0}, + {5749,8102,8103 ,7583,726,726 ,0,0,0}, {5749,8106,8097 ,7583,726,7658 ,0,0,0}, + {8098,8105,5749 ,7661,7583,7583 ,0,0,0}, {8096,8093,5749 ,726,726,7583 ,0,0,0}, + {8106,5749,8094 ,726,7583,7661 ,0,0,0}, {5757,8092,8095 ,726,726,726 ,0,0,0}, + {5757,8096,5749 ,726,726,7583 ,0,0,0}, {5750,8104,5745 ,726,5489,7668 ,0,0,0}, + {8104,5750,5749 ,5489,726,7583 ,0,0,0}, {8088,5757,8107 ,726,726,726 ,0,0,0}, + {8108,5757,5755 ,726,726,726 ,0,0,0}, {5757,8108,8107 ,726,726,726 ,0,0,0}, + {8108,5755,5761 ,726,726,726 ,0,0,0}, {6211,6474,8106 ,7669,7670,7671 ,0,0,0}, + {8094,6212,6211 ,7672,7673,7669 ,0,0,0}, {8094,8093,6212 ,7672,7673,7673 ,0,0,0}, + {8106,8094,6211 ,7671,7672,7669 ,0,0,0}, {6474,6473,8097 ,7670,7674,7675 ,0,0,0}, + {6216,6270,8105 ,7676,7677,7678 ,0,0,0}, {8098,8097,6473 ,7679,7675,7674 ,0,0,0}, + {6473,6216,8098 ,7674,7676,7679 ,0,0,0}, {8105,8098,6216 ,7678,7679,7676 ,0,0,0}, + {6474,8097,8106 ,7670,7675,7671 ,0,0,0}, {8105,6270,8101 ,7678,7677,7680 ,0,0,0}, + {6269,8102,8101 ,7681,7682,7680 ,0,0,0}, {8101,6270,6269 ,7680,7677,7681 ,0,0,0}, + {8102,6269,6268 ,7682,7681,7683 ,0,0,0}, {6262,8103,6268 ,7684,7685,7683 ,0,0,0}, + {6262,6264,8100 ,7684,7686,7687 ,0,0,0}, {6262,8100,8103 ,7684,7687,7685 ,0,0,0}, + {8099,6265,8104 ,7688,7689,7690 ,0,0,0}, {8100,6264,8099 ,7687,7686,7688 ,0,0,0}, + {8099,6264,6265 ,7688,7686,7689 ,0,0,0}, {6265,6266,8104 ,7689,7690,7690 ,0,0,0}, + {8102,6268,8103 ,7682,7683,7685 ,0,0,0}, {6259,8093,8096 ,7691,7673,7692 ,0,0,0}, + {8093,6259,6212 ,7673,7691,7673 ,0,0,0}, {8095,6260,8096 ,7693,7694,7692 ,0,0,0}, + {6259,8096,6260 ,7691,7692,7694 ,0,0,0}, {8095,8092,6291 ,7693,7695,7696 ,0,0,0}, + {6291,6260,8095 ,7696,7694,7693 ,0,0,0}, {6292,8092,8091 ,7697,7695,7698 ,0,0,0}, + {8092,6292,6291 ,7695,7697,7696 ,0,0,0}, {8090,6514,8091 ,7699,7700,7698 ,0,0,0}, + {6292,8091,6514 ,7697,7698,7700 ,0,0,0}, {8090,8089,6295 ,7699,7701,7702 ,0,0,0}, + {6295,6514,8090 ,7702,7700,7699 ,0,0,0}, {6294,8089,8086 ,7703,7701,7704 ,0,0,0}, + {8089,6294,6295 ,7701,7703,7702 ,0,0,0}, {8087,6317,8086 ,7705,7706,7704 ,0,0,0}, + {6294,8086,6317 ,7703,7704,7706 ,0,0,0}, {8087,8088,6320 ,7705,7707,7708 ,0,0,0}, + {6320,6317,8087 ,7708,7706,7705 ,0,0,0}, {6321,8088,8107 ,7709,7707,7710 ,0,0,0}, + {8088,6321,6320 ,7707,7709,7708 ,0,0,0}, {6321,8107,6322 ,7709,7710,7711 ,0,0,0}, + {6322,8107,8108 ,7711,7710,7711 ,0,0,0}, {7023,8108,5761 ,7712,7712,7712 ,0,0,0}, + {8108,7024,7027 ,7712,7712,7712 ,0,0,0}, {7023,7024,8108 ,7712,7712,7712 ,0,0,0}, + {8108,7033,7038 ,7712,7712,7712 ,0,0,0}, {7027,7033,8108 ,7712,7712,7712 ,0,0,0}, + {8108,7042,7006 ,7712,7712,7712 ,0,0,0}, {7038,7042,8108 ,7712,7712,7712 ,0,0,0}, + {8108,7010,7009 ,7712,7712,7712 ,0,0,0}, {7006,7010,8108 ,7712,7712,7712 ,0,0,0}, + {8108,7009,6322 ,7712,7712,7712 ,0,0,0}, {7075,8104,6266 ,7713,7713,7713 ,0,0,0}, + {7075,7125,8104 ,7713,7713,7713 ,0,0,0}, {8104,7125,7111 ,7713,7713,7713 ,0,0,0}, + {7071,7077,8104 ,7713,7713,7713 ,0,0,0}, {7071,8104,7111 ,7713,7713,7713 ,0,0,0}, + {7077,7107,8104 ,7713,7713,7713 ,0,0,0}, {8104,7063,7062 ,7713,7713,7713 ,0,0,0}, + {7107,7063,8104 ,7713,7713,7713 ,0,0,0}, {5745,8104,7067 ,7713,7713,7713 ,0,0,0}, + {7062,7067,8104 ,7713,7713,7713 ,0,0,0}, {5180,8109,6529 ,1435,7714,7715 ,0,0,0}, + {8110,6520,8111 ,7716,7717,7718 ,0,0,0}, {6539,6528,8112 ,7719,7720,7721 ,0,0,0}, + {6200,8113,6301 ,7722,7723,7724 ,0,0,0}, {8114,8115,6542 ,7725,7726,7727 ,0,0,0}, + {8116,6323,8117 ,7728,7729,7730 ,0,0,0}, {6325,6302,8118 ,7731,7732,7733 ,0,0,0}, + {6207,6306,8119 ,7734,7735,7736 ,0,0,0}, {6311,8120,6306 ,7737,7738,7735 ,0,0,0}, + {6307,8121,8122 ,7739,7740,7741 ,0,0,0}, {6207,8123,6309 ,7734,7742,7743 ,0,0,0}, + {8124,6316,8122 ,7744,7745,7741 ,0,0,0}, {6307,8122,6316 ,7739,7741,7745 ,0,0,0}, + {8124,8125,6314 ,7744,7746,7747 ,0,0,0}, {6314,6316,8124 ,7747,7745,7744 ,0,0,0}, + {6327,8125,8126 ,7748,7746,7749 ,0,0,0}, {8125,6327,6314 ,7746,7748,7747 ,0,0,0}, + {8127,6313,8126 ,7750,7751,7749 ,0,0,0}, {6327,8126,6313 ,7748,7749,7751 ,0,0,0}, + {8127,5199,5200 ,7750,1359,1359 ,0,0,0}, {5200,6313,8127 ,1359,7751,7750 ,0,0,0}, + {8119,6306,8120 ,7736,7735,7738 ,0,0,0}, {8121,6309,8123 ,7740,7743,7742 ,0,0,0}, + {6309,8121,6307 ,7743,7740,7739 ,0,0,0}, {8119,8123,6207 ,7736,7742,7734 ,0,0,0}, + {8116,8120,6311 ,7728,7738,7737 ,0,0,0}, {6325,8118,8117 ,7731,7733,7730 ,0,0,0}, + {6325,8117,6323 ,7731,7730,7729 ,0,0,0}, {6311,6323,8116 ,7737,7729,7728 ,0,0,0}, + {6302,8128,8118 ,7732,7752,7733 ,0,0,0}, {8128,6302,6301 ,7752,7732,7724 ,0,0,0}, + {8115,8113,6200 ,7726,7723,7722 ,0,0,0}, {8113,8128,6301 ,7723,7752,7724 ,0,0,0}, + {6542,8115,6200 ,7727,7726,7722 ,0,0,0}, {6530,8110,8114 ,7753,7716,7725 ,0,0,0}, + {6530,8114,6542 ,7753,7725,7727 ,0,0,0}, {6520,6539,8111 ,7717,7719,7718 ,0,0,0}, + {6530,6520,8110 ,7753,7717,7716 ,0,0,0}, {6528,8109,8112 ,7720,7714,7721 ,0,0,0}, + {8111,6539,8112 ,7718,7719,7721 ,0,0,0}, {5180,6529,5178 ,1435,7715,1435 ,0,0,0}, + {8109,6528,6529 ,7714,7720,7715 ,0,0,0}, {8127,8126,8125 ,726,7628,7628 ,0,0,0}, + {5182,8122,5181 ,7627,7628,726 ,0,0,0}, {5161,5159,8123 ,7754,7625,7626 ,0,0,0}, + {8122,8121,5181 ,7628,726,726 ,0,0,0}, {5164,8116,5165 ,7755,726,7756 ,0,0,0}, + {5161,8123,8119 ,7754,7626,7626 ,0,0,0}, {8118,8128,5173 ,726,7628,7757 ,0,0,0}, + {8118,5171,8117 ,726,7758,7626 ,0,0,0}, {5174,5168,8113 ,7759,7760,7628 ,0,0,0}, + {8110,8111,8112 ,7625,7754,726 ,0,0,0}, {5177,5174,8115 ,7628,7759,7627 ,0,0,0}, + {5180,5177,8109 ,7628,7628,7761 ,0,0,0}, {8109,8110,8112 ,7761,7625,726 ,0,0,0}, + {5177,8114,8110 ,7628,7628,7625 ,0,0,0}, {8109,5177,8110 ,7761,7628,7625 ,0,0,0}, + {5177,5176,5174 ,7628,7762,7759 ,0,0,0}, {5177,8115,8114 ,7628,7627,7628 ,0,0,0}, + {5173,8113,5168 ,7757,7628,7760 ,0,0,0}, {8113,8115,5174 ,7628,7627,7759 ,0,0,0}, + {5173,8128,8113 ,7757,7628,7628 ,0,0,0}, {8117,5171,5165 ,7626,7758,7756 ,0,0,0}, + {5173,5171,8118 ,7757,7758,726 ,0,0,0}, {8120,8116,5164 ,7628,726,7755 ,0,0,0}, + {8116,8117,5165 ,726,7626,7756 ,0,0,0}, {8120,5162,8119 ,7628,7628,7626 ,0,0,0}, + {5162,8120,5164 ,7628,7628,7755 ,0,0,0}, {8121,8123,5159 ,726,7626,7625 ,0,0,0}, + {5162,5161,8119 ,7628,7754,7626 ,0,0,0}, {5185,8122,5182 ,7625,7628,7627 ,0,0,0}, + {5159,5181,8121 ,7625,726,726 ,0,0,0}, {8125,8124,5185 ,7628,7628,7625 ,0,0,0}, + {5185,8124,8122 ,7625,7628,7628 ,0,0,0}, {5187,8127,8125 ,7628,726,7628 ,0,0,0}, + {8125,5185,5187 ,7628,7625,7628 ,0,0,0}, {5187,5188,8127 ,7628,7628,726 ,0,0,0}, + {5191,5194,5197 ,7628,7628,7628 ,0,0,0}, {5188,5191,8127 ,7628,7628,726 ,0,0,0}, + {5197,8127,5191 ,7628,726,7628 ,0,0,0}, {5191,5193,5194 ,7628,726,7628 ,0,0,0}, + {8127,5197,5199 ,726,7628,7628 ,0,0,0}, {5141,8129,6490 ,1435,7763,7764 ,0,0,0}, + {6517,6519,8130 ,7765,7766,7767 ,0,0,0}, {6523,6524,8131 ,7768,7769,7770 ,0,0,0}, + {6489,8132,6488 ,7771,7772,7773 ,0,0,0}, {8133,8134,6518 ,7774,4221,7775 ,0,0,0}, + {8135,8136,6516 ,7776,7777,7778 ,0,0,0}, {8135,6515,8137 ,7776,7779,7780 ,0,0,0}, + {8138,8139,6332 ,7781,7782,7783 ,0,0,0}, {6332,6331,8138 ,7783,7784,7781 ,0,0,0}, + {6206,8139,8140 ,7785,7782,7786 ,0,0,0}, {8139,6206,6332 ,7782,7785,7783 ,0,0,0}, + {8141,6205,8140 ,7787,7788,7786 ,0,0,0}, {6206,8140,6205 ,7785,7786,7788 ,0,0,0}, + {8141,5155,5156 ,7787,1359,1359 ,0,0,0}, {5156,6205,8141 ,1359,7788,7787 ,0,0,0}, + {8132,6489,8134 ,7772,7771,4221 ,0,0,0}, {8136,6331,6516 ,7777,7784,7778 ,0,0,0}, + {8138,6331,8136 ,7781,7784,7777 ,0,0,0}, {8130,6519,8142 ,7767,7766,4227 ,0,0,0}, + {8137,6515,6488 ,7780,7779,7773 ,0,0,0}, {8135,6516,6515 ,7776,7778,7779 ,0,0,0}, + {8132,8137,6488 ,7772,7780,7773 ,0,0,0}, {6518,8134,6489 ,7775,4221,7771 ,0,0,0}, + {6517,8130,8133 ,7765,7767,7774 ,0,0,0}, {8133,6518,6517 ,7774,7775,7765 ,0,0,0}, + {6524,8129,8131 ,7769,7763,7770 ,0,0,0}, {8142,6523,8131 ,4227,7768,7770 ,0,0,0}, + {6519,6523,8142 ,7766,7768,4227 ,0,0,0}, {5141,6490,5142 ,1435,7764,1435 ,0,0,0}, + {8129,6524,6490 ,7763,7769,7764 ,0,0,0}, {5140,5149,5141 ,726,5471,7661 ,0,0,0}, + {8132,8135,8137 ,726,726,726 ,0,0,0}, {8138,8136,8135 ,7658,726,726 ,0,0,0}, + {8135,8132,8138 ,726,726,7658 ,0,0,0}, {8138,8134,8139 ,7658,726,7658 ,0,0,0}, + {8134,8138,8132 ,726,7658,726 ,0,0,0}, {8140,8139,8133 ,7658,7658,726 ,0,0,0}, + {8134,8133,8139 ,726,726,7658 ,0,0,0}, {8130,8141,8140 ,7658,7661,7658 ,0,0,0}, + {8140,8133,8130 ,7658,726,7658 ,0,0,0}, {8141,8142,5155 ,7661,7661,7664 ,0,0,0}, + {8142,8141,8130 ,7661,7661,7658 ,0,0,0}, {8142,8131,5155 ,7661,726,7664 ,0,0,0}, + {8131,8129,5153 ,726,726,7662 ,0,0,0}, {5147,5140,5138 ,7789,726,7658 ,0,0,0}, + {5128,5127,5134 ,5488,7668,7661 ,0,0,0}, {5144,5136,5143 ,7790,7664,7791 ,0,0,0}, + {5128,5134,5130 ,5488,7661,7792 ,0,0,0}, {5131,5130,5134 ,5488,7792,7661 ,0,0,0}, + {5136,5134,5143 ,7664,7661,7791 ,0,0,0}, {5143,5134,5127 ,7791,7661,7668 ,0,0,0}, + {5136,5144,5138 ,7664,7790,7658 ,0,0,0}, {5149,5140,5147 ,5471,726,7789 ,0,0,0}, + {5147,5138,5144 ,7789,7658,7790 ,0,0,0}, {5141,5150,8129 ,7661,7583,726 ,0,0,0}, + {5141,5149,5150 ,7661,5471,7583 ,0,0,0}, {8131,5153,5155 ,726,7662,7664 ,0,0,0}, + {5150,5153,8129 ,7583,7662,726 ,0,0,0}, {8143,5786,8144 ,7583,726,726 ,0,0,0}, + {8145,5782,8146 ,7668,726,5470 ,0,0,0}, {8145,8147,5782 ,7668,726,726 ,0,0,0}, + {5782,8148,8146 ,726,726,5470 ,0,0,0}, {8147,8149,5782 ,726,5489,726 ,0,0,0}, + {5782,8150,8151 ,726,7793,7794 ,0,0,0}, {8149,8150,5782 ,5489,7793,726 ,0,0,0}, + {5786,8152,5782 ,726,5470,726 ,0,0,0}, {8152,8148,5782 ,5470,726,726 ,0,0,0}, + {8153,8152,5786 ,726,5470,726 ,0,0,0}, {8154,5782,8151 ,7795,726,7794 ,0,0,0}, + {5786,8155,8153 ,726,5488,726 ,0,0,0}, {8154,8156,5782 ,7795,726,726 ,0,0,0}, + {8157,5782,8158 ,5485,726,7796 ,0,0,0}, {5782,8156,8158 ,726,726,7796 ,0,0,0}, + {5786,8159,8155 ,726,7583,5488 ,0,0,0}, {8160,5782,8157 ,7583,726,5485 ,0,0,0}, + {5786,8161,8159 ,726,726,7583 ,0,0,0}, {5786,8162,8163 ,726,5488,7583 ,0,0,0}, + {5786,8163,8161 ,726,7583,726 ,0,0,0}, {5783,8160,5778 ,5489,7583,7797 ,0,0,0}, + {5786,8143,8162 ,726,7583,5488 ,0,0,0}, {8160,5783,5782 ,7583,5489,726 ,0,0,0}, + {8144,5786,8164 ,726,726,7583 ,0,0,0}, {8165,5786,5793 ,726,726,726 ,0,0,0}, + {5786,8165,8164 ,726,726,7583 ,0,0,0}, {8165,5793,5792 ,726,726,726 ,0,0,0}, + {6201,6303,8145 ,7798,7799,7800 ,0,0,0}, {8146,6199,6201 ,7801,7802,7798 ,0,0,0}, + {8146,8148,6199 ,7801,7802,7802 ,0,0,0}, {8145,8146,6201 ,7800,7801,7798 ,0,0,0}, + {6303,6512,8147 ,7799,7803,7804 ,0,0,0}, {6324,6310,8150 ,7805,7806,7807 ,0,0,0}, + {8149,8147,6512 ,7808,7804,7803 ,0,0,0}, {6512,6324,8149 ,7803,7805,7808 ,0,0,0}, + {8150,8149,6324 ,7807,7808,7805 ,0,0,0}, {6303,8147,8145 ,7799,7804,7800 ,0,0,0}, + {8150,6310,8151 ,7807,7806,7809 ,0,0,0}, {6305,8154,8151 ,7810,7811,7809 ,0,0,0}, + {8151,6310,6305 ,7809,7806,7810 ,0,0,0}, {8154,6305,6304 ,7811,7810,7812 ,0,0,0}, + {6209,8156,6304 ,7813,7814,7812 ,0,0,0}, {6209,6288,8158 ,7813,7815,7816 ,0,0,0}, + {6209,8158,8156 ,7813,7816,7814 ,0,0,0}, {8157,6290,8160 ,7817,7818,7819 ,0,0,0}, + {8158,6288,8157 ,7816,7815,7817 ,0,0,0}, {8157,6288,6290 ,7817,7815,7818 ,0,0,0}, + {6290,6319,8160 ,7818,7819,7819 ,0,0,0}, {8154,6304,8156 ,7811,7812,7814 ,0,0,0}, + {6333,8148,8152 ,7820,7802,7821 ,0,0,0}, {8148,6333,6199 ,7802,7820,7802 ,0,0,0}, + {8153,6337,8152 ,7822,7823,7821 ,0,0,0}, {6333,8152,6337 ,7820,7821,7823 ,0,0,0}, + {8153,8155,6298 ,7822,7824,7825 ,0,0,0}, {6298,6337,8153 ,7825,7823,7822 ,0,0,0}, + {6299,8155,8159 ,7826,7824,7827 ,0,0,0}, {8155,6299,6298 ,7824,7826,7825 ,0,0,0}, + {8161,6374,8159 ,7828,7829,7827 ,0,0,0}, {6299,8159,6374 ,7826,7827,7829 ,0,0,0}, + {8161,8163,6202 ,7828,7830,7831 ,0,0,0}, {6202,6374,8161 ,7831,7829,7828 ,0,0,0}, + {6203,8163,8162 ,7832,7830,7833 ,0,0,0}, {8163,6203,6202 ,7830,7832,7831 ,0,0,0}, + {8143,6361,8162 ,7834,7835,7833 ,0,0,0}, {6203,8162,6361 ,7832,7833,7835 ,0,0,0}, + {8143,8144,6364 ,7834,7836,7837 ,0,0,0}, {6364,6361,8143 ,7837,7835,7834 ,0,0,0}, + {6368,8144,8164 ,7838,7836,7839 ,0,0,0}, {8144,6368,6364 ,7836,7838,7837 ,0,0,0}, + {6368,8164,6369 ,7838,7839,7840 ,0,0,0}, {6369,8164,8165 ,7840,7839,7840 ,0,0,0}, + {6936,8165,5792 ,7841,7841,7841 ,0,0,0}, {8165,6942,6945 ,7841,7841,7841 ,0,0,0}, + {6936,6942,8165 ,7841,7841,7841 ,0,0,0}, {8165,6951,6956 ,7841,7841,7841 ,0,0,0}, + {6945,6951,8165 ,7841,7841,7841 ,0,0,0}, {8165,6960,6919 ,7841,7841,7841 ,0,0,0}, + {6956,6960,8165 ,7841,7841,7841 ,0,0,0}, {8165,6931,6930 ,7841,7841,7841 ,0,0,0}, + {6919,6931,8165 ,7841,7841,7841 ,0,0,0}, {8165,6930,6369 ,7841,7841,7841 ,0,0,0}, + {6997,8160,6319 ,7842,7842,7842 ,0,0,0}, {6997,7043,8160 ,7842,7842,7842 ,0,0,0}, + {8160,7043,7029 ,7842,7842,7842 ,0,0,0}, {6991,6984,8160 ,7842,7842,7842 ,0,0,0}, + {6991,8160,7029 ,7842,7842,7842 ,0,0,0}, {6984,7025,8160 ,7842,7842,7842 ,0,0,0}, + {8160,7017,6979 ,7842,7842,7842 ,0,0,0}, {7025,7017,8160 ,7842,7842,7842 ,0,0,0}, + {5778,8160,6980 ,7842,7842,7842 ,0,0,0}, {6979,6980,8160 ,7842,7842,7842 ,0,0,0}, + {5104,8166,6554 ,1790,7843,4204 ,0,0,0}, {8167,6551,8168 ,7844,4198,4199 ,0,0,0}, + {6540,6553,8169 ,7845,7846,7847 ,0,0,0}, {6531,8170,6349 ,7848,7849,7850 ,0,0,0}, + {8171,8172,6564 ,7851,7852,7853 ,0,0,0}, {8173,6328,8174 ,7854,7855,7856 ,0,0,0}, + {6330,6347,8175 ,7857,7858,7859 ,0,0,0}, {6196,6195,8176 ,7860,7861,7862 ,0,0,0}, + {6351,8177,6195 ,7863,7864,7861 ,0,0,0}, {6355,8178,8179 ,7865,7866,7867 ,0,0,0}, + {6196,8180,6354 ,7860,7868,7869 ,0,0,0}, {8181,6360,8179 ,7870,7871,7867 ,0,0,0}, + {6355,8179,6360 ,7865,7867,7871 ,0,0,0}, {8181,8182,6358 ,7870,7872,7873 ,0,0,0}, + {6358,6360,8181 ,7873,7871,7870 ,0,0,0}, {6343,8182,8183 ,7874,7872,7875 ,0,0,0}, + {8182,6343,6358 ,7872,7874,7873 ,0,0,0}, {8184,6341,8183 ,7876,7877,7875 ,0,0,0}, + {6343,8183,6341 ,7874,7875,7877 ,0,0,0}, {8184,5123,5124 ,7876,1711,1711 ,0,0,0}, + {5124,6341,8184 ,1711,7877,7876 ,0,0,0}, {8176,6195,8177 ,7862,7861,7864 ,0,0,0}, + {8178,6354,8180 ,7866,7869,7868 ,0,0,0}, {6354,8178,6355 ,7869,7866,7865 ,0,0,0}, + {8176,8180,6196 ,7862,7868,7860 ,0,0,0}, {8173,8177,6351 ,7854,7864,7863 ,0,0,0}, + {6330,8175,8174 ,7857,7859,7856 ,0,0,0}, {6330,8174,6328 ,7857,7856,7855 ,0,0,0}, + {6351,6328,8173 ,7863,7855,7854 ,0,0,0}, {6347,8185,8175 ,7858,7878,7859 ,0,0,0}, + {8185,6347,6349 ,7878,7858,7850 ,0,0,0}, {8172,8170,6531 ,7852,7849,7848 ,0,0,0}, + {8170,8185,6349 ,7849,7878,7850 ,0,0,0}, {6564,8172,6531 ,7853,7852,7848 ,0,0,0}, + {6552,8167,8171 ,7879,7844,7851 ,0,0,0}, {6552,8171,6564 ,7879,7851,7853 ,0,0,0}, + {6551,6540,8168 ,4198,7845,4199 ,0,0,0}, {6552,6551,8167 ,7879,4198,7844 ,0,0,0}, + {6553,8166,8169 ,7846,7843,7847 ,0,0,0}, {8168,6540,8169 ,4199,7845,7847 ,0,0,0}, + {5104,6554,5102 ,1790,4204,1790 ,0,0,0}, {8166,6553,6554 ,7843,7846,4204 ,0,0,0}, + {8176,8177,8171 ,726,7880,7881 ,0,0,0}, {8166,8181,8179 ,7882,7627,7625 ,0,0,0}, + {8172,8173,8170 ,7883,7758,726 ,0,0,0}, {8185,8170,8173 ,7884,726,7758 ,0,0,0}, + {8174,8175,8185 ,7880,7761,7884 ,0,0,0}, {8173,8172,8177 ,7758,7883,7880 ,0,0,0}, + {8174,8185,8173 ,7880,7884,7758 ,0,0,0}, {8176,8171,8167 ,726,7881,7885 ,0,0,0}, + {8177,8172,8171 ,7880,7883,7881 ,0,0,0}, {8167,8168,8180 ,7885,7886,7758 ,0,0,0}, + {8180,8176,8167 ,7758,726,7885 ,0,0,0}, {8178,8168,8169 ,726,7886,7887 ,0,0,0}, + {8168,8178,8180 ,7886,726,7758 ,0,0,0}, {8179,8178,8169 ,7625,726,7887 ,0,0,0}, + {5104,8181,8166 ,7758,7627,7882 ,0,0,0}, {8166,8179,8169 ,7882,7625,7887 ,0,0,0}, + {8182,5104,5101 ,7627,7758,7755 ,0,0,0}, {5104,8182,8181 ,7758,7627,7627 ,0,0,0}, + {5100,8183,5101 ,7625,726,7755 ,0,0,0}, {8182,5101,8183 ,7627,7755,726 ,0,0,0}, + {5100,5098,8184 ,7625,7761,726 ,0,0,0}, {8184,8183,5100 ,726,726,7625 ,0,0,0}, + {5123,5098,5092 ,7627,7761,7625 ,0,0,0}, {5098,5123,8184 ,7761,7627,726 ,0,0,0}, + {5089,5117,5095 ,726,7627,7625 ,0,0,0}, {5097,5121,5092 ,7880,726,7625 ,0,0,0}, + {5115,5088,5112 ,7625,726,726 ,0,0,0}, {5109,5085,5106 ,7627,7625,7625 ,0,0,0}, + {5111,5112,5086 ,726,726,7625 ,0,0,0}, {5106,5083,5105 ,7625,7625,726 ,0,0,0}, + {5085,5109,5111 ,7625,7627,726 ,0,0,0}, {5086,5085,5111 ,7625,7625,726 ,0,0,0}, + {5106,5085,5083 ,7625,7625,7625 ,0,0,0}, {5089,5088,5115 ,726,726,7625 ,0,0,0}, + {5086,5112,5088 ,7625,726,726 ,0,0,0}, {5118,5095,5117 ,726,7625,7627 ,0,0,0}, + {5117,5089,5115 ,7627,726,7625 ,0,0,0}, {5097,5118,5121 ,7880,726,726 ,0,0,0}, + {5118,5097,5095 ,726,7880,7625 ,0,0,0}, {5121,5123,5092 ,726,7627,7625 ,0,0,0}, + {5065,8186,6484 ,1790,7888,7889 ,0,0,0}, {6536,6525,8187 ,7890,7891,7892 ,0,0,0}, + {6538,6485,8188 ,7893,7894,7895 ,0,0,0}, {6526,8189,6527 ,7896,7897,4137 ,0,0,0}, + {8190,8191,6537 ,7898,7899,7900 ,0,0,0}, {8192,8193,6535 ,7901,7902,7903 ,0,0,0}, + {8192,6534,8194 ,7901,7904,7905 ,0,0,0}, {8195,8196,6370 ,7906,7907,7908 ,0,0,0}, + {6370,6371,8195 ,7908,7909,7906 ,0,0,0}, {6533,8196,8197 ,7910,7907,7911 ,0,0,0}, + {8196,6533,6370 ,7907,7910,7908 ,0,0,0}, {8198,6344,8197 ,7912,7913,7911 ,0,0,0}, + {6533,8197,6344 ,7910,7911,7913 ,0,0,0}, {8198,5079,5080 ,7912,1711,1711 ,0,0,0}, + {5080,6344,8198 ,1711,7913,7912 ,0,0,0}, {8189,6526,8191 ,7897,7896,7899 ,0,0,0}, + {8193,6371,6535 ,7902,7909,7903 ,0,0,0}, {8195,6371,8193 ,7906,7909,7902 ,0,0,0}, + {8187,6525,8199 ,7892,7891,7914 ,0,0,0}, {8194,6534,6527 ,7905,7904,4137 ,0,0,0}, + {8192,6535,6534 ,7901,7903,7904 ,0,0,0}, {8189,8194,6527 ,7897,7905,4137 ,0,0,0}, + {6537,8191,6526 ,7900,7899,7896 ,0,0,0}, {6536,8187,8190 ,7890,7892,7898 ,0,0,0}, + {8190,6537,6536 ,7898,7900,7890 ,0,0,0}, {6485,8186,8188 ,7894,7888,7895 ,0,0,0}, + {8199,6538,8188 ,7914,7893,7895 ,0,0,0}, {6525,6538,8199 ,7891,7893,7914 ,0,0,0}, + {5065,6484,5066 ,1790,7889,1790 ,0,0,0}, {8186,6485,6484 ,7888,7894,7889 ,0,0,0}, + {8192,5073,8193 ,726,7658,726 ,0,0,0}, {8197,8196,5077 ,726,726,7660 ,0,0,0}, + {5079,8198,8197 ,726,7660,726 ,0,0,0}, {8192,8194,5071 ,726,726,7658 ,0,0,0}, + {5074,5077,8195 ,7660,7660,7659 ,0,0,0}, {8191,8190,5051 ,7659,726,7661 ,0,0,0}, + {8191,5067,8189 ,7659,726,726 ,0,0,0}, {5054,5052,8187 ,7915,7916,726 ,0,0,0}, + {8186,5060,5058 ,7658,7917,5475 ,0,0,0}, {8188,5055,8199 ,7658,726,7659 ,0,0,0}, + {5065,5064,5060 ,7918,7918,7917 ,0,0,0}, {5062,5060,5064 ,7661,7917,7918 ,0,0,0}, + {8188,8186,5058 ,7658,7658,5475 ,0,0,0}, {8186,5065,5060 ,7658,7918,7917 ,0,0,0}, + {5055,8188,5058 ,726,7658,5475 ,0,0,0}, {8199,5055,5054 ,7659,726,7915 ,0,0,0}, + {8187,5052,8190 ,726,7916,726 ,0,0,0}, {8199,5054,8187 ,7659,7915,726 ,0,0,0}, + {8191,5051,5067 ,7659,7661,726 ,0,0,0}, {8190,5052,5051 ,726,7916,7661 ,0,0,0}, + {5068,8194,8189 ,7664,726,726 ,0,0,0}, {5067,5068,8189 ,726,7664,726 ,0,0,0}, + {5073,8192,5071 ,7658,726,7658 ,0,0,0}, {5071,8194,5068 ,7658,726,7664 ,0,0,0}, + {8193,5074,8195 ,726,7660,7659 ,0,0,0}, {8193,5073,5074 ,726,7658,7660 ,0,0,0}, + {8197,5077,5079 ,726,7660,726 ,0,0,0}, {8196,8195,5077 ,726,7659,7660 ,0,0,0}, + {5823,8200,8201 ,726,5469,7919 ,0,0,0}, {8202,5823,8203 ,7920,726,7921 ,0,0,0}, + {5823,8202,8200 ,726,7920,5469 ,0,0,0}, {5823,8204,8203 ,726,726,7921 ,0,0,0}, + {8205,5823,8201 ,7922,726,7919 ,0,0,0}, {8204,5823,8206 ,726,726,7920 ,0,0,0}, + {8205,8207,5823 ,7922,7923,726 ,0,0,0}, {5823,8208,8209 ,726,7924,7925 ,0,0,0}, + {8209,8210,5823 ,7925,7926,726 ,0,0,0}, {8207,8208,5823 ,7923,7924,726 ,0,0,0}, + {8211,8212,5823 ,5472,7927,726 ,0,0,0}, {8211,5823,8210 ,5472,726,7926 ,0,0,0}, + {8213,8214,5823 ,7928,7929,726 ,0,0,0}, {8213,5823,8212 ,7928,726,7927 ,0,0,0}, + {8215,8216,5823 ,726,5489,726 ,0,0,0}, {8215,5823,8214 ,726,726,7929 ,0,0,0}, + {5823,8217,5822 ,726,5488,7583 ,0,0,0}, {8217,5823,8216 ,5488,726,5489 ,0,0,0}, + {5822,8218,8219 ,7583,5470,5489 ,0,0,0}, {8217,8218,5822 ,5488,5470,7583 ,0,0,0}, + {5818,5819,8219 ,5489,5488,5489 ,0,0,0}, {5822,8219,5819 ,7583,5489,5488 ,0,0,0}, + {5813,5818,8219 ,5489,5489,5489 ,0,0,0}, {5823,7790,8206 ,726,5489,7920 ,0,0,0}, + {7790,8220,8221 ,5489,5470,5488 ,0,0,0}, {8206,7790,8221 ,7920,5489,5488 ,0,0,0}, + {8222,7790,7789 ,5489,5489,726 ,0,0,0}, {7790,8222,8220 ,5489,5489,5470 ,0,0,0}, + {6853,8222,7788 ,5489,5489,7583 ,0,0,0}, {7789,7788,8222 ,726,7583,5489 ,0,0,0}, + {6387,6348,8210 ,7930,7931,7932 ,0,0,0}, {8209,6389,6387 ,7933,7934,7930 ,0,0,0}, + {8209,8208,6389 ,7933,7935,7934 ,0,0,0}, {8210,8209,6387 ,7932,7933,7930 ,0,0,0}, + {6348,6532,8211 ,7931,7936,7937 ,0,0,0}, {6329,6350,8213 ,7938,7939,7940 ,0,0,0}, + {8212,8211,6532 ,7941,7937,7936 ,0,0,0}, {6532,6329,8212 ,7936,7938,7941 ,0,0,0}, + {8213,8212,6329 ,7940,7941,7938 ,0,0,0}, {6348,8211,8210 ,7931,7937,7932 ,0,0,0}, + {8213,6350,8214 ,7940,7939,7942 ,0,0,0}, {6352,8215,8214 ,7943,7944,7942 ,0,0,0}, + {8214,6350,6352 ,7942,7939,7943 ,0,0,0}, {8215,6352,6197 ,7944,7943,7945 ,0,0,0}, + {6340,8216,6197 ,7946,7947,7945 ,0,0,0}, {6340,6353,8217 ,7946,7948,7949 ,0,0,0}, + {6340,8217,8216 ,7946,7949,7947 ,0,0,0}, {8218,6345,8219 ,7950,7951,7952 ,0,0,0}, + {8217,6353,8218 ,7949,7948,7950 ,0,0,0}, {8218,6353,6345 ,7950,7948,7951 ,0,0,0}, + {6345,6346,8219 ,7951,7952,7952 ,0,0,0}, {8215,6197,8216 ,7944,7945,7947 ,0,0,0}, + {6509,8208,8207 ,7953,7935,7954 ,0,0,0}, {8208,6509,6389 ,7935,7953,7934 ,0,0,0}, + {8205,6388,8207 ,7955,7956,7954 ,0,0,0}, {6509,8207,6388 ,7953,7954,7956 ,0,0,0}, + {8205,8201,6372 ,7955,7957,7958 ,0,0,0}, {6372,6388,8205 ,7958,7956,7955 ,0,0,0}, + {6373,8201,8200 ,7959,7957,7960 ,0,0,0}, {8201,6373,6372 ,7957,7959,7958 ,0,0,0}, + {8202,6546,8200 ,7961,7962,7960 ,0,0,0}, {6373,8200,6546 ,7959,7960,7962 ,0,0,0}, + {8202,8203,6486 ,7961,7963,7964 ,0,0,0}, {6486,6546,8202 ,7964,7962,7961 ,0,0,0}, + {6487,8203,8204 ,7965,7963,7966 ,0,0,0}, {8203,6487,6486 ,7963,7965,7964 ,0,0,0}, + {8206,6380,8204 ,7967,7968,7966 ,0,0,0}, {6487,8204,6380 ,7965,7966,7968 ,0,0,0}, + {8206,8221,6408 ,7967,7969,7970 ,0,0,0}, {6408,6380,8206 ,7970,7968,7967 ,0,0,0}, + {6409,8221,8220 ,7971,7969,7972 ,0,0,0}, {8221,6409,6408 ,7969,7971,7970 ,0,0,0}, + {6409,8220,6411 ,7971,7972,7973 ,0,0,0}, {6411,8220,8222 ,7973,7972,7973 ,0,0,0}, + {6863,6869,8222 ,7974,7974,7974 ,0,0,0}, {8222,6853,6854 ,7974,7974,7974 ,0,0,0}, + {6854,6860,8222 ,7974,7974,7974 ,0,0,0}, {6874,8222,6869 ,7974,7974,7974 ,0,0,0}, + {6860,6863,8222 ,7974,7974,7974 ,0,0,0}, {6878,6831,8222 ,7974,7974,7974 ,0,0,0}, + {6878,8222,6874 ,7974,7974,7974 ,0,0,0}, {6831,6843,8222 ,7974,7974,7974 ,0,0,0}, + {6411,8222,6842 ,7974,7974,7974 ,0,0,0}, {6843,6842,8222 ,7974,7974,7974 ,0,0,0}, + {8219,6346,6911 ,7975,7975,7975 ,0,0,0}, {6911,6961,8219 ,7975,7975,7975 ,0,0,0}, + {8219,6947,6907 ,7975,7975,7975 ,0,0,0}, {6961,6947,8219 ,7975,7975,7975 ,0,0,0}, + {8219,6913,6943 ,7975,7975,7975 ,0,0,0}, {6907,6913,8219 ,7975,7975,7975 ,0,0,0}, + {8219,6899,6898 ,7975,7975,7975 ,0,0,0}, {6943,6899,8219 ,7975,7975,7975 ,0,0,0}, + {5813,8219,6903 ,7975,7975,7975 ,0,0,0}, {6898,6903,8219 ,7975,7975,7975 ,0,0,0}, + {5028,8223,6559 ,126,7976,7977 ,0,0,0}, {8224,6561,8225 ,7978,7979,7980 ,0,0,0}, + {6575,6562,8226 ,7981,7982,7983 ,0,0,0}, {6376,8227,6367 ,7984,7985,7986 ,0,0,0}, + {8228,8229,6543 ,7987,7988,7989 ,0,0,0}, {8230,6394,8231 ,7990,7991,7992 ,0,0,0}, + {6412,6379,8232 ,7993,7994,7995 ,0,0,0}, {6404,6405,8233 ,7996,7997,7998 ,0,0,0}, + {6395,8234,6405 ,7999,8000,7997 ,0,0,0}, {6396,8235,8236 ,8001,8002,8003 ,0,0,0}, + {6404,8237,6398 ,7996,8004,8005 ,0,0,0}, {8238,6399,8236 ,8006,8007,8003 ,0,0,0}, + {6396,8236,6399 ,8001,8003,8007 ,0,0,0}, {8238,8239,6402 ,8006,8008,8009 ,0,0,0}, + {6402,6399,8238 ,8009,8007,8006 ,0,0,0}, {6441,8239,8240 ,8010,8008,8011 ,0,0,0}, + {8239,6441,6402 ,8008,8010,8009 ,0,0,0}, {8241,6403,8240 ,8012,8013,8011 ,0,0,0}, + {6441,8240,6403 ,8010,8011,8013 ,0,0,0}, {8241,5047,5048 ,8012,8014,4346 ,0,0,0}, + {5048,6403,8241 ,4346,8013,8012 ,0,0,0}, {8233,6405,8234 ,7998,7997,8000 ,0,0,0}, + {8235,6398,8237 ,8002,8005,8004 ,0,0,0}, {6398,8235,6396 ,8005,8002,8001 ,0,0,0}, + {8233,8237,6404 ,7998,8004,7996 ,0,0,0}, {8230,8234,6395 ,7990,8000,7999 ,0,0,0}, + {6412,8232,8231 ,7993,7995,7992 ,0,0,0}, {6412,8231,6394 ,7993,7992,7991 ,0,0,0}, + {6395,6394,8230 ,7999,7991,7990 ,0,0,0}, {6379,8242,8232 ,7994,8015,7995 ,0,0,0}, + {8242,6379,6367 ,8015,7994,7986 ,0,0,0}, {8229,8227,6376 ,7988,7985,7984 ,0,0,0}, + {8227,8242,6367 ,7985,8015,7986 ,0,0,0}, {6543,8229,6376 ,7989,7988,7984 ,0,0,0}, + {6560,8224,8228 ,8016,7978,7987 ,0,0,0}, {6560,8228,6543 ,8016,7987,7989 ,0,0,0}, + {6561,6575,8225 ,7979,7981,7980 ,0,0,0}, {6560,6561,8224 ,8016,7979,7978 ,0,0,0}, + {6562,8223,8226 ,7982,7976,7983 ,0,0,0}, {8225,6575,8226 ,7980,7981,7983 ,0,0,0}, + {5028,6559,5026 ,126,7977,4289 ,0,0,0}, {8223,6562,6559 ,7976,7982,7977 ,0,0,0}, + {8241,8240,8239 ,7625,7880,7758 ,0,0,0}, {5033,8224,8225 ,7626,7880,726 ,0,0,0}, + {8239,8236,8233 ,7758,8017,8018 ,0,0,0}, {8239,8238,8236 ,7758,7758,8017 ,0,0,0}, + {8235,8233,8236 ,8017,8018,8017 ,0,0,0}, {8235,8237,8233 ,8017,7758,8018 ,0,0,0}, + {8234,8239,8233 ,8019,7758,8018 ,0,0,0}, {8234,8230,8241 ,8019,7884,7625 ,0,0,0}, + {8241,8239,8234 ,7625,7758,8019 ,0,0,0}, {8230,8231,5045 ,7884,8020,7625 ,0,0,0}, + {8230,5047,8241 ,7884,7625,7625 ,0,0,0}, {8242,5041,5042 ,8021,7625,726 ,0,0,0}, + {5042,5045,8232 ,726,7625,7257 ,0,0,0}, {5035,5036,8228 ,726,726,8017 ,0,0,0}, + {5039,8227,8229 ,7625,8022,7761 ,0,0,0}, {5030,8226,5029 ,7626,726,7626 ,0,0,0}, + {8225,5030,5033 ,726,7626,7626 ,0,0,0}, {5025,5010,5009 ,7625,726,726 ,0,0,0}, + {5028,5009,8223 ,7625,726,7625 ,0,0,0}, {5021,5012,5022 ,726,726,7625 ,0,0,0}, + {5012,5021,5019 ,726,726,726 ,0,0,0}, {5016,5021,5022 ,7625,726,7625 ,0,0,0}, + {5024,5022,5025 ,7625,7625,7625 ,0,0,0}, {5022,5012,5010 ,7625,726,726 ,0,0,0}, + {5013,5012,5019 ,726,726,726 ,0,0,0}, {5009,5028,5025 ,726,7625,7625 ,0,0,0}, + {5010,5025,5022 ,726,7625,7625 ,0,0,0}, {8223,5007,5029 ,7625,726,7626 ,0,0,0}, + {5007,8223,5009 ,726,7625,726 ,0,0,0}, {8226,5030,8225 ,726,7626,726 ,0,0,0}, + {8223,5029,8226 ,7625,7626,726 ,0,0,0}, {5033,5035,8224 ,7626,726,7880 ,0,0,0}, + {8228,5036,8229 ,8017,726,7761 ,0,0,0}, {8224,5035,8228 ,7880,726,8017 ,0,0,0}, + {8229,5036,5039 ,7761,726,7625 ,0,0,0}, {8227,5041,8242 ,8022,7625,8021 ,0,0,0}, + {8227,5039,5041 ,8022,7625,7625 ,0,0,0}, {5045,8231,8232 ,7625,8020,7257 ,0,0,0}, + {8232,8242,5042 ,7257,8021,726 ,0,0,0}, {5045,5047,8230 ,7625,7625,7884 ,0,0,0}, + {4989,8243,6558 ,8023,8024,8025 ,0,0,0}, {6300,6503,8244 ,8026,8027,8028 ,0,0,0}, + {6610,6556,8245 ,8029,8030,8031 ,0,0,0}, {6549,8246,6541 ,8032,8033,8034 ,0,0,0}, + {8247,8248,6508 ,8035,8036,8037 ,0,0,0}, {8249,8250,6548 ,8038,8039,8040 ,0,0,0}, + {8249,6550,8251 ,8038,8041,8042 ,0,0,0}, {8252,8253,6547 ,8043,8044,8045 ,0,0,0}, + {6547,6447,8252 ,8045,8046,8043 ,0,0,0}, {6444,8253,8254 ,8047,8044,8048 ,0,0,0}, + {8253,6444,6547 ,8044,8047,8045 ,0,0,0}, {8255,6445,8254 ,8049,8050,8048 ,0,0,0}, + {6444,8254,6445 ,8047,8048,8050 ,0,0,0}, {8255,5003,5004 ,8049,82,82 ,0,0,0}, + {5004,6445,8255 ,82,8050,8049 ,0,0,0}, {8246,6549,8248 ,8033,8032,8036 ,0,0,0}, + {8250,6447,6548 ,8039,8046,8040 ,0,0,0}, {8252,6447,8250 ,8043,8046,8039 ,0,0,0}, + {8244,6503,8256 ,8028,8027,8051 ,0,0,0}, {8251,6550,6541 ,8042,8041,8034 ,0,0,0}, + {8249,6548,6550 ,8038,8040,8041 ,0,0,0}, {8246,8251,6541 ,8033,8042,8034 ,0,0,0}, + {6508,8248,6549 ,8037,8036,8032 ,0,0,0}, {6300,8244,8247 ,8026,8028,8035 ,0,0,0}, + {8247,6508,6300 ,8035,8037,8026 ,0,0,0}, {6556,8243,8245 ,8030,8024,8031 ,0,0,0}, + {8256,6610,8245 ,8051,8029,8031 ,0,0,0}, {6503,6610,8256 ,8027,8029,8051 ,0,0,0}, + {4989,6558,4990 ,8023,8025,8052 ,0,0,0}, {8243,6556,6558 ,8024,8030,8025 ,0,0,0}, + {8249,4986,8250 ,726,726,726 ,0,0,0}, {8253,4982,4979 ,726,7661,726 ,0,0,0}, + {8246,8248,8243 ,726,7660,726 ,0,0,0}, {8251,4989,4988 ,726,726,726 ,0,0,0}, + {8245,8243,8244 ,7661,726,726 ,0,0,0}, {8244,8256,8245 ,726,7658,7661 ,0,0,0}, + {8244,8248,8247 ,726,7660,726 ,0,0,0}, {8243,4989,8246 ,726,726,726 ,0,0,0}, + {8248,8244,8243 ,7660,726,726 ,0,0,0}, {8251,4988,8249 ,726,726,726 ,0,0,0}, + {8246,4989,8251 ,726,726,726 ,0,0,0}, {8249,4988,4986 ,726,726,726 ,0,0,0}, + {8250,4984,8252 ,726,7658,726 ,0,0,0}, {8250,4986,4984 ,726,726,7658 ,0,0,0}, + {8253,8252,4982 ,726,726,7661 ,0,0,0}, {4984,4982,8252 ,7658,7661,726 ,0,0,0}, + {8253,4979,8254 ,726,726,726 ,0,0,0}, {4978,8255,8254 ,726,726,726 ,0,0,0}, + {8254,4979,4978 ,726,726,726 ,0,0,0}, {8255,4976,5003 ,726,726,726 ,0,0,0}, + {4976,8255,4978 ,726,726,726 ,0,0,0}, {4976,4975,5003 ,726,726,726 ,0,0,0}, + {4995,4991,4992 ,7659,726,726 ,0,0,0}, {4995,5001,4991 ,7659,726,726 ,0,0,0}, + {4998,4995,4997 ,726,7659,726 ,0,0,0}, {4998,5001,4995 ,726,726,7659 ,0,0,0}, + {5003,4975,5001 ,726,726,726 ,0,0,0}, {4991,5001,4975 ,726,726,726 ,0,0,0}, + {8257,8258,7785 ,726,8053,7583 ,0,0,0}, {7787,8259,7786 ,726,726,726 ,0,0,0}, + {8258,8260,7785 ,8053,7922,7583 ,0,0,0}, {8257,7785,8261 ,726,7583,5472 ,0,0,0}, + {7785,8262,8263 ,7583,7664,5488 ,0,0,0}, {8260,8262,7785 ,7922,7664,7583 ,0,0,0}, + {8264,8265,7785 ,7920,726,7583 ,0,0,0}, {8263,8266,7785 ,5488,5471,7583 ,0,0,0}, + {8267,8268,7787 ,7664,7583,726 ,0,0,0}, {7787,8269,8270 ,726,5488,7664 ,0,0,0}, + {8271,7787,8272 ,726,726,726 ,0,0,0}, {8273,8274,7787 ,7664,7664,726 ,0,0,0}, + {8275,8272,7787 ,726,726,726 ,0,0,0}, {7787,8271,8259 ,726,726,726 ,0,0,0}, + {8273,7787,8276 ,7664,726,7664 ,0,0,0}, {7787,8274,8275 ,726,7664,726 ,0,0,0}, + {7787,8268,8276 ,726,7583,7664 ,0,0,0}, {7787,8270,8277 ,726,7664,726 ,0,0,0}, + {7787,8277,8267 ,726,726,7664 ,0,0,0}, {8265,7787,7785 ,726,726,7583 ,0,0,0}, + {8265,8269,7787 ,726,5488,726 ,0,0,0}, {7785,8266,8264 ,7583,5471,7920 ,0,0,0}, + {6814,7786,8259 ,726,726,726 ,0,0,0}, {8261,7785,8278 ,5472,7583,7793 ,0,0,0}, + {8279,7785,7784 ,5471,7583,7664 ,0,0,0}, {7785,8279,8278 ,7583,5471,7793 ,0,0,0}, + {8279,7784,6759 ,5471,7664,7920 ,0,0,0}, {6366,6365,8277 ,8054,8055,8056 ,0,0,0}, + {8270,6375,6366 ,8057,8058,8054 ,0,0,0}, {8270,8269,6375 ,8057,8058,8058 ,0,0,0}, + {8277,8270,6366 ,8056,8057,8054 ,0,0,0}, {6365,6544,8267 ,8055,8059,8060 ,0,0,0}, + {6442,6386,8276 ,8061,8062,8063 ,0,0,0}, {8268,8267,6544 ,8064,8060,8059 ,0,0,0}, + {6544,6442,8268 ,8059,8061,8064 ,0,0,0}, {8276,8268,6442 ,8063,8064,8061 ,0,0,0}, + {6365,8267,8277 ,8055,8060,8056 ,0,0,0}, {8276,6386,8273 ,8063,8062,8065 ,0,0,0}, + {6385,8274,8273 ,8066,8067,8065 ,0,0,0}, {8273,6386,6385 ,8065,8062,8066 ,0,0,0}, + {8274,6385,6545 ,8067,8066,8068 ,0,0,0}, {6393,8275,6545 ,8069,8070,8068 ,0,0,0}, + {6393,6392,8272 ,8069,8071,8072 ,0,0,0}, {6393,8272,8275 ,8069,8072,8070 ,0,0,0}, + {8271,6407,8259 ,8073,8074,8075 ,0,0,0}, {8272,6392,8271 ,8072,8071,8073 ,0,0,0}, + {8271,6392,6407 ,8073,8071,8074 ,0,0,0}, {6407,6410,8259 ,8074,8075,8075 ,0,0,0}, + {8274,6545,8275 ,8067,8068,8070 ,0,0,0}, {6198,8269,8265 ,8076,8058,8077 ,0,0,0}, + {8269,6198,6375 ,8058,8076,8058 ,0,0,0}, {8264,6446,8265 ,8078,8079,8077 ,0,0,0}, + {6198,8265,6446 ,8076,8077,8079 ,0,0,0}, {8264,8266,6390 ,8078,8080,8081 ,0,0,0}, + {6390,6446,8264 ,8081,8079,8078 ,0,0,0}, {6391,8266,8263 ,8082,8080,8083 ,0,0,0}, + {8266,6391,6390 ,8080,8082,8081 ,0,0,0}, {8262,6568,8263 ,8084,8085,8083 ,0,0,0}, + {6391,8263,6568 ,8082,8083,8085 ,0,0,0}, {8262,8260,6336 ,8084,8086,8087 ,0,0,0}, + {6336,6568,8262 ,8087,8085,8084 ,0,0,0}, {6335,8260,8258 ,8088,8086,8089 ,0,0,0}, + {8260,6335,6336 ,8086,8088,8087 ,0,0,0}, {8257,6419,8258 ,8090,8091,8089 ,0,0,0}, + {6335,8258,6419 ,8088,8089,8091 ,0,0,0}, {8257,8261,6459 ,8090,8092,8093 ,0,0,0}, + {6459,6419,8257 ,8093,8091,8090 ,0,0,0}, {6460,8261,8278 ,8094,8092,8095 ,0,0,0}, + {8261,6460,6459 ,8092,8094,8093 ,0,0,0}, {6460,8278,6461 ,8094,8095,8096 ,0,0,0}, + {6461,8278,8279 ,8096,8095,8096 ,0,0,0}, {6766,8279,6759 ,8097,8098,8097 ,0,0,0}, + {8279,6767,6770 ,8098,8097,8098 ,0,0,0}, {6766,6767,8279 ,8097,8097,8098 ,0,0,0}, + {8279,6776,6781 ,8098,8098,8097 ,0,0,0}, {6770,6776,8279 ,8098,8098,8098 ,0,0,0}, + {8279,6785,6744 ,8098,8098,8097 ,0,0,0}, {6781,6785,8279 ,8097,8098,8098 ,0,0,0}, + {8279,6748,6747 ,8098,8097,8097 ,0,0,0}, {6744,6748,8279 ,8097,8097,8098 ,0,0,0}, + {8279,6747,6461 ,8098,8097,8098 ,0,0,0}, {6823,8259,6410 ,8099,8099,8099 ,0,0,0}, + {6823,6879,8259 ,8099,8099,8099 ,0,0,0}, {8259,6879,6865 ,8099,8099,8099 ,0,0,0}, + {6819,6825,8259 ,8099,8099,8099 ,0,0,0}, {6819,8259,6865 ,8099,8099,8099 ,0,0,0}, + {6825,6861,8259 ,8099,8099,8099 ,0,0,0}, {8259,6808,6807 ,8099,8099,8099 ,0,0,0}, + {6861,6808,8259 ,8099,8099,8099 ,0,0,0}, {6814,8259,6812 ,8099,8099,8099 ,0,0,0}, + {6807,6812,8259 ,8099,8099,8099 ,0,0,0}, {4952,8280,6602 ,1359,8100,4482 ,0,0,0}, + {8281,6601,8282 ,4475,8101,8102 ,0,0,0}, {6603,6600,8283 ,8103,8104,4478 ,0,0,0}, + {6434,8284,6426 ,8105,8106,8107 ,0,0,0}, {8285,8286,6606 ,4472,8108,8109 ,0,0,0}, + {8287,6463,8288 ,8110,8111,8112 ,0,0,0}, {6462,6424,8289 ,8113,8114,8115 ,0,0,0}, + {6437,6430,8290 ,8116,8117,8118 ,0,0,0}, {6465,8291,6430 ,8119,8120,8117 ,0,0,0}, + {6455,8292,8293 ,8121,8122,8123 ,0,0,0}, {6437,8294,6457 ,8116,8124,8125 ,0,0,0}, + {8295,6454,8293 ,8126,8127,8123 ,0,0,0}, {6455,8293,6454 ,8121,8123,8127 ,0,0,0}, + {8295,8296,6452 ,8126,8128,8129 ,0,0,0}, {6452,6454,8295 ,8129,8127,8126 ,0,0,0}, + {6449,8296,8297 ,8130,8128,8131 ,0,0,0}, {8296,6449,6452 ,8128,8130,8129 ,0,0,0}, + {8298,6450,8297 ,8132,8133,8131 ,0,0,0}, {6449,8297,6450 ,8130,8131,8133 ,0,0,0}, + {8298,4971,4972 ,8132,1435,1435 ,0,0,0}, {4972,6450,8298 ,1435,8133,8132 ,0,0,0}, + {8290,6430,8291 ,8118,8117,8120 ,0,0,0}, {8292,6457,8294 ,8122,8125,8124 ,0,0,0}, + {6457,8292,6455 ,8125,8122,8121 ,0,0,0}, {8290,8294,6437 ,8118,8124,8116 ,0,0,0}, + {8287,8291,6465 ,8110,8120,8119 ,0,0,0}, {6462,8289,8288 ,8113,8115,8112 ,0,0,0}, + {6462,8288,6463 ,8113,8112,8111 ,0,0,0}, {6465,6463,8287 ,8119,8111,8110 ,0,0,0}, + {6424,8299,8289 ,8114,8134,8115 ,0,0,0}, {8299,6424,6426 ,8134,8114,8107 ,0,0,0}, + {8286,8284,6434 ,8108,8106,8105 ,0,0,0}, {8284,8299,6426 ,8106,8134,8107 ,0,0,0}, + {6606,8286,6434 ,8109,8108,8105 ,0,0,0}, {6582,8281,8285 ,4474,4475,4472 ,0,0,0}, + {6582,8285,6606 ,4474,4472,8109 ,0,0,0}, {6601,6603,8282 ,8101,8103,8102 ,0,0,0}, + {6582,6601,8281 ,4474,8101,4475 ,0,0,0}, {6600,8280,8283 ,8104,8100,4478 ,0,0,0}, + {8282,6603,8283 ,8102,8103,4478 ,0,0,0}, {4952,6602,4950 ,1359,4482,1359 ,0,0,0}, + {8280,6600,6602 ,8100,8104,4482 ,0,0,0}, {4946,8284,8286 ,726,726,726 ,0,0,0}, + {8292,4953,8293 ,726,7626,7758 ,0,0,0}, {8298,8297,8296 ,7625,7625,726 ,0,0,0}, + {8294,8290,4933 ,8135,7628,7626 ,0,0,0}, {4933,4931,8294 ,7626,7626,8135 ,0,0,0}, + {4943,8288,8289 ,726,7627,726 ,0,0,0}, {4936,8287,4937 ,726,7628,726 ,0,0,0}, + {4940,8284,4946 ,726,726,726 ,0,0,0}, {8289,8299,4945 ,726,726,726 ,0,0,0}, + {8281,8282,8283 ,7628,7628,726 ,0,0,0}, {4949,4946,8286 ,726,726,726 ,0,0,0}, + {4952,4949,8280 ,726,726,726 ,0,0,0}, {8280,8281,8283 ,726,7628,726 ,0,0,0}, + {8280,4949,8281 ,726,726,7628 ,0,0,0}, {8286,8285,4949 ,726,726,726 ,0,0,0}, + {4949,8285,8281 ,726,726,7628 ,0,0,0}, {8284,4940,4945 ,726,726,726 ,0,0,0}, + {4949,4948,4946 ,726,726,726 ,0,0,0}, {4945,4943,8289 ,726,726,726 ,0,0,0}, + {4945,8299,8284 ,726,726,726 ,0,0,0}, {8287,8288,4937 ,7628,7627,726 ,0,0,0}, + {4937,8288,4943 ,726,7627,726 ,0,0,0}, {4934,8291,4936 ,726,726,726 ,0,0,0}, + {4936,8291,8287 ,726,726,7628 ,0,0,0}, {4934,4933,8290 ,726,7626,7628 ,0,0,0}, + {8290,8291,4934 ,7628,726,726 ,0,0,0}, {4931,4953,8292 ,7626,7626,726 ,0,0,0}, + {4931,8292,8294 ,7626,726,8135 ,0,0,0}, {4954,8293,4953 ,7626,7758,7626 ,0,0,0}, + {8295,8293,4957 ,8135,7758,7628 ,0,0,0}, {4954,4957,8293 ,7626,7628,7758 ,0,0,0}, + {4957,4959,8296 ,7628,726,726 ,0,0,0}, {8296,8295,4957 ,726,8135,7628 ,0,0,0}, + {8298,4959,4960 ,7625,726,7626 ,0,0,0}, {4959,8298,8296 ,726,7625,726 ,0,0,0}, + {4963,4966,4969 ,7626,726,7626 ,0,0,0}, {4960,4963,8298 ,7626,7626,7625 ,0,0,0}, + {4969,8298,4963 ,7626,7625,7626 ,0,0,0}, {4963,4965,4966 ,7626,7627,726 ,0,0,0}, + {8298,4969,4971 ,7625,7626,8135 ,0,0,0}, {4913,8300,6588 ,1359,8136,8137 ,0,0,0}, + {6571,6573,8301 ,8138,8139,8140 ,0,0,0}, {6590,6592,8302 ,8141,8142,8143 ,0,0,0}, + {6378,8303,6377 ,8144,8145,8146 ,0,0,0}, {8304,8305,6572 ,8147,8148,8149 ,0,0,0}, + {8306,8307,6570 ,8150,8151,8152 ,0,0,0}, {8306,6569,8308 ,8150,8153,8154 ,0,0,0}, + {8309,8310,6502 ,8155,8156,8157 ,0,0,0}, {6502,6501,8309 ,8157,8158,8155 ,0,0,0}, + {6416,8310,8311 ,8159,8156,8160 ,0,0,0}, {8310,6416,6502 ,8156,8159,8157 ,0,0,0}, + {8312,6415,8311 ,8161,8162,8160 ,0,0,0}, {6416,8311,6415 ,8159,8160,8162 ,0,0,0}, + {8312,4927,4928 ,8161,1435,1435 ,0,0,0}, {4928,6415,8312 ,1435,8162,8161 ,0,0,0}, + {8303,6378,8305 ,8145,8144,8148 ,0,0,0}, {8307,6501,6570 ,8151,8158,8152 ,0,0,0}, + {8309,6501,8307 ,8155,8158,8151 ,0,0,0}, {8301,6573,8313 ,8140,8139,8163 ,0,0,0}, + {8308,6569,6377 ,8154,8153,8146 ,0,0,0}, {8306,6570,6569 ,8150,8152,8153 ,0,0,0}, + {8303,8308,6377 ,8145,8154,8146 ,0,0,0}, {6572,8305,6378 ,8149,8148,8144 ,0,0,0}, + {6571,8301,8304 ,8138,8140,8147 ,0,0,0}, {8304,6572,6571 ,8147,8149,8138 ,0,0,0}, + {6592,8300,8302 ,8142,8136,8143 ,0,0,0}, {8313,6590,8302 ,8163,8141,8143 ,0,0,0}, + {6573,6590,8313 ,8139,8141,8163 ,0,0,0}, {4913,6588,4914 ,1359,8137,1359 ,0,0,0}, + {8300,6592,6588 ,8136,8142,8137 ,0,0,0}, {8310,8305,8304 ,726,7661,7661 ,0,0,0}, + {8306,8308,8309 ,7661,7658,726 ,0,0,0}, {8309,8307,8306 ,726,726,7661 ,0,0,0}, + {8303,8305,8309 ,7658,7661,726 ,0,0,0}, {8303,8309,8308 ,7658,726,7658 ,0,0,0}, + {8304,8311,8310 ,7661,726,726 ,0,0,0}, {8305,8310,8309 ,7661,726,726 ,0,0,0}, + {8311,8304,8301 ,726,7661,7658 ,0,0,0}, {8301,8313,8312 ,7658,7661,726 ,0,0,0}, + {8312,8311,8301 ,726,726,7658 ,0,0,0}, {4927,8313,8302 ,726,7661,7658 ,0,0,0}, + {8313,4927,8312 ,7661,726,726 ,0,0,0}, {4912,4921,4913 ,7658,726,726 ,0,0,0}, + {8300,4925,8302 ,7658,7660,7658 ,0,0,0}, {4919,4912,4910 ,726,7658,726 ,0,0,0}, + {4900,4899,4906 ,726,726,726 ,0,0,0}, {4916,4908,4915 ,726,726,726 ,0,0,0}, + {4906,4903,4902 ,726,726,726 ,0,0,0}, {4906,4899,4915 ,726,726,726 ,0,0,0}, + {4900,4906,4902 ,726,726,726 ,0,0,0}, {4910,4908,4916 ,726,726,726 ,0,0,0}, + {4908,4906,4915 ,726,726,726 ,0,0,0}, {4921,4912,4919 ,726,7658,726 ,0,0,0}, + {4919,4910,4916 ,726,726,726 ,0,0,0}, {4913,4922,8300 ,726,726,7658 ,0,0,0}, + {4913,4921,4922 ,726,726,726 ,0,0,0}, {8302,4925,4927 ,7658,7660,726 ,0,0,0}, + {4922,4925,8300 ,726,7660,7658 ,0,0,0}, {8314,8315,7782 ,726,726,7664 ,0,0,0}, + {8316,8314,7782 ,726,726,7664 ,0,0,0}, {8316,7782,8317 ,726,7664,726 ,0,0,0}, + {8318,7782,8315 ,726,7664,726 ,0,0,0}, {8319,8320,7782 ,726,726,7664 ,0,0,0}, + {8319,7782,8318 ,726,7664,726 ,0,0,0}, {8321,7782,7780 ,726,7664,726 ,0,0,0}, + {8317,7782,8321 ,726,7664,726 ,0,0,0}, {8322,7782,8320 ,726,7664,726 ,0,0,0}, + {7782,8322,8323 ,7664,726,726 ,0,0,0}, {8321,7780,8324 ,726,726,726 ,0,0,0}, + {8325,7782,8323 ,726,7664,726 ,0,0,0}, {8326,8324,7780 ,7583,726,726 ,0,0,0}, + {7780,8327,8326 ,726,7664,7583 ,0,0,0}, {7782,8325,8328 ,7664,726,726 ,0,0,0}, + {7782,8328,8329 ,7664,726,726 ,0,0,0}, {8330,8327,7780 ,726,7664,726 ,0,0,0}, + {8331,8332,7780 ,726,726,726 ,0,0,0}, {8332,8330,7780 ,726,726,726 ,0,0,0}, + {8333,7780,8334 ,726,726,726 ,0,0,0}, {8333,8331,7780 ,726,726,726 ,0,0,0}, + {7783,8329,6720 ,7664,726,726 ,0,0,0}, {8329,7783,7782 ,726,7664,7664 ,0,0,0}, + {8334,7780,8335 ,726,726,726 ,0,0,0}, {8336,7780,7781 ,726,726,7664 ,0,0,0}, + {7780,8336,8335 ,726,726,726 ,0,0,0}, {8336,7781,6644 ,726,7664,5488 ,0,0,0}, + {6432,6425,8314 ,8164,8165,8166 ,0,0,0}, {8316,6433,6432 ,8167,8168,8164 ,0,0,0}, + {8316,8317,6433 ,8167,8168,8168 ,0,0,0}, {8314,8316,6432 ,8166,8167,8164 ,0,0,0}, + {6425,6566,8315 ,8165,8169,8170 ,0,0,0}, {6464,6466,8319 ,8171,8172,8173 ,0,0,0}, + {8318,8315,6566 ,8174,8170,8169 ,0,0,0}, {6566,6464,8318 ,8169,8171,8174 ,0,0,0}, + {8319,8318,6464 ,8173,8174,8171 ,0,0,0}, {6425,8315,8314 ,8165,8170,8166 ,0,0,0}, + {8319,6466,8320 ,8173,8172,8175 ,0,0,0}, {6429,8322,8320 ,8176,8177,8175 ,0,0,0}, + {8320,6466,6429 ,8175,8172,8176 ,0,0,0}, {8322,6429,6431 ,8177,8176,8178 ,0,0,0}, + {6436,8323,6431 ,8179,8180,8178 ,0,0,0}, {6436,6468,8325 ,8179,8181,8182 ,0,0,0}, + {6436,8325,8323 ,8179,8182,8180 ,0,0,0}, {8328,6470,8329 ,8183,8184,8185 ,0,0,0}, + {8325,6468,8328 ,8182,8181,8183 ,0,0,0}, {8328,6468,6470 ,8183,8181,8184 ,0,0,0}, + {6470,6469,8329 ,8184,8185,8185 ,0,0,0}, {8322,6431,8323 ,8177,8178,8180 ,0,0,0}, + {6428,8317,8321 ,8186,8168,8187 ,0,0,0}, {8317,6428,6433 ,8168,8186,8168 ,0,0,0}, + {8324,6427,8321 ,8188,8189,8187 ,0,0,0}, {6428,8321,6427 ,8186,8187,8189 ,0,0,0}, + {8324,8326,6594 ,8188,8190,8191 ,0,0,0}, {6594,6427,8324 ,8191,8189,8188 ,0,0,0}, + {6422,8326,8327 ,8192,8190,8193 ,0,0,0}, {8326,6422,6594 ,8190,8192,8191 ,0,0,0}, + {8330,6423,8327 ,8194,8195,8193 ,0,0,0}, {6422,8327,6423 ,8192,8193,8195 ,0,0,0}, + {8330,8332,6496 ,8194,8196,8197 ,0,0,0}, {6496,6423,8330 ,8197,8195,8194 ,0,0,0}, + {6497,8332,8331 ,8198,8196,8199 ,0,0,0}, {8332,6497,6496 ,8196,8198,8197 ,0,0,0}, + {8333,6240,8331 ,8200,8201,8199 ,0,0,0}, {6497,8331,6240 ,8198,8199,8201 ,0,0,0}, + {8333,8334,6243 ,8200,8202,8203 ,0,0,0}, {6243,6240,8333 ,8203,8201,8200 ,0,0,0}, + {6244,8334,8335 ,8204,8202,8205 ,0,0,0}, {8334,6244,6243 ,8202,8204,8203 ,0,0,0}, + {6244,8335,6245 ,8204,8205,8206 ,0,0,0}, {6245,8335,8336 ,8206,8205,8206 ,0,0,0}, + {6645,8336,6644 ,8207,8207,8207 ,0,0,0}, {8336,6675,6678 ,8207,8207,8207 ,0,0,0}, + {6645,6675,8336 ,8207,8207,8207 ,0,0,0}, {8336,6684,6689 ,8207,8207,8207 ,0,0,0}, + {6678,6684,8336 ,8207,8207,8207 ,0,0,0}, {8336,6693,6623 ,8207,8207,8207 ,0,0,0}, + {6689,6693,8336 ,8207,8207,8207 ,0,0,0}, {8336,6626,6625 ,8207,8207,8207 ,0,0,0}, + {6623,6626,8336 ,8207,8207,8207 ,0,0,0}, {8336,6625,6245 ,8207,8207,8207 ,0,0,0}, + {6735,8329,6469 ,8208,8208,8208 ,0,0,0}, {6735,6786,8329 ,8208,8208,8208 ,0,0,0}, + {8329,6786,6772 ,8208,8208,8208 ,0,0,0}, {6729,6722,8329 ,8208,8208,8208 ,0,0,0}, + {6729,8329,6772 ,8208,8208,8208 ,0,0,0}, {6722,6768,8329 ,8208,8208,8208 ,0,0,0}, + {8329,6760,6714 ,8208,8208,8208 ,0,0,0}, {6768,6760,8329 ,8208,8208,8208 ,0,0,0}, + {6720,8329,6716 ,8208,8208,8208 ,0,0,0}, {6714,6716,8329 ,8208,8208,8208 ,0,0,0}, + {4876,8337,6232 ,1711,8209,4414 ,0,0,0}, {8338,6495,8339 ,8210,8211,8212 ,0,0,0}, + {6480,6233,8340 ,8213,8214,4410 ,0,0,0}, {6494,8341,6224 ,4402,8215,8216 ,0,0,0}, + {8342,8343,6493 ,8217,8218,8219 ,0,0,0}, {8344,6254,8345 ,8220,8221,8222 ,0,0,0}, + {6253,6479,8346 ,8223,8224,8225 ,0,0,0}, {6227,6226,8347 ,8226,8227,8228 ,0,0,0}, + {6249,8348,6226 ,8229,8230,8227 ,0,0,0}, {6230,8349,8350 ,8231,8232,8233 ,0,0,0}, + {6227,8351,6229 ,8226,8234,8235 ,0,0,0}, {8352,6246,8350 ,8236,8237,8233 ,0,0,0}, + {6230,8350,6246 ,8231,8233,8237 ,0,0,0}, {8352,8353,6234 ,8236,8238,8239 ,0,0,0}, + {6234,6246,8352 ,8239,8237,8236 ,0,0,0}, {6482,8353,8354 ,8240,8238,8241 ,0,0,0}, + {8353,6482,6234 ,8238,8240,8239 ,0,0,0}, {8355,6242,8354 ,8242,8243,8241 ,0,0,0}, + {6482,8354,6242 ,8240,8241,8243 ,0,0,0}, {8355,4895,4896 ,8242,1790,1790 ,0,0,0}, + {4896,6242,8355 ,1790,8243,8242 ,0,0,0}, {8347,6226,8348 ,8228,8227,8230 ,0,0,0}, + {8349,6229,8351 ,8232,8235,8234 ,0,0,0}, {6229,8349,6230 ,8235,8232,8231 ,0,0,0}, + {8347,8351,6227 ,8228,8234,8226 ,0,0,0}, {8344,8348,6249 ,8220,8230,8229 ,0,0,0}, + {6253,8346,8345 ,8223,8225,8222 ,0,0,0}, {6253,8345,6254 ,8223,8222,8221 ,0,0,0}, + {6249,6254,8344 ,8229,8221,8220 ,0,0,0}, {6479,8356,8346 ,8224,8244,8225 ,0,0,0}, + {8356,6479,6224 ,8244,8224,8216 ,0,0,0}, {8343,8341,6494 ,8218,8215,4402 ,0,0,0}, + {8341,8356,6224 ,8215,8244,8216 ,0,0,0}, {6493,8343,6494 ,8219,8218,4402 ,0,0,0}, + {6194,8338,8342 ,8245,8210,8217 ,0,0,0}, {6194,8342,6493 ,8245,8217,8219 ,0,0,0}, + {6495,6480,8339 ,8211,8213,8212 ,0,0,0}, {6194,6495,8338 ,8245,8211,8210 ,0,0,0}, + {6233,8337,8340 ,8214,8209,4410 ,0,0,0}, {8339,6480,8340 ,8212,8213,4410 ,0,0,0}, + {4876,6232,4874 ,1711,4414,1711 ,0,0,0}, {8337,6233,6232 ,8209,8214,4414 ,0,0,0}, + {8342,8347,8348 ,726,726,7626 ,0,0,0}, {8356,8345,8346 ,726,726,726 ,0,0,0}, + {8344,8356,8341 ,726,726,726 ,0,0,0}, {8343,8344,8341 ,726,726,726 ,0,0,0}, + {8343,8348,8344 ,726,7626,726 ,0,0,0}, {8356,8344,8345 ,726,726,726 ,0,0,0}, + {8343,8342,8348 ,726,726,7626 ,0,0,0}, {8338,8351,8347 ,726,726,726 ,0,0,0}, + {8342,8338,8347 ,726,726,726 ,0,0,0}, {8351,8339,8349 ,726,726,7626 ,0,0,0}, + {8339,8351,8338 ,726,726,726 ,0,0,0}, {8350,8349,8340 ,7628,7626,726 ,0,0,0}, + {8339,8340,8349 ,726,726,7626 ,0,0,0}, {8337,8352,8350 ,726,726,7628 ,0,0,0}, + {8350,8340,8337 ,7628,726,726 ,0,0,0}, {8352,4876,8353 ,726,726,726 ,0,0,0}, + {4876,8352,8337 ,726,726,726 ,0,0,0}, {8354,8353,4873 ,7625,726,726 ,0,0,0}, + {4876,4873,8353 ,726,726,726 ,0,0,0}, {8354,4873,4872 ,7625,726,726 ,0,0,0}, + {8355,8354,4872 ,726,7625,726 ,0,0,0}, {4872,4870,8355 ,726,726,726 ,0,0,0}, + {4864,4895,4870 ,726,726,726 ,0,0,0}, {8355,4870,4895 ,726,726,726 ,0,0,0}, + {4867,4861,4889 ,726,726,7625 ,0,0,0}, {4864,4869,4893 ,726,726,726 ,0,0,0}, + {4858,4883,4884 ,7626,726,726 ,0,0,0}, {4884,4887,4860 ,726,726,726 ,0,0,0}, + {4883,4857,4881 ,726,7625,7625 ,0,0,0}, {4857,4878,4881 ,7625,726,7625 ,0,0,0}, + {4855,4878,4857 ,726,726,7625 ,0,0,0}, {4855,4877,4878 ,726,726,726 ,0,0,0}, + {4860,4858,4884 ,726,7626,726 ,0,0,0}, {4857,4883,4858 ,7625,726,7626 ,0,0,0}, + {4887,4889,4861 ,726,7625,726 ,0,0,0}, {4860,4887,4861 ,726,726,726 ,0,0,0}, + {4867,4890,4869 ,726,726,726 ,0,0,0}, {4867,4889,4890 ,726,7625,726 ,0,0,0}, + {4864,4893,4895 ,726,726,726 ,0,0,0}, {4890,4893,4869 ,726,726,726 ,0,0,0}, + {4837,8357,6506 ,1711,8246,8247 ,0,0,0}, {6565,6579,8358 ,8248,8249,8250 ,0,0,0}, + {6578,6507,8359 ,8251,8252,8253 ,0,0,0}, {6418,8360,6417 ,8254,8255,8256 ,0,0,0}, + {8361,8362,6599 ,8257,8258,8259 ,0,0,0}, {8363,8364,6597 ,8260,8261,8262 ,0,0,0}, + {8363,6596,8365 ,8260,8263,8264 ,0,0,0}, {8366,8367,6499 ,8265,8266,8267 ,0,0,0}, + {6499,6500,8366 ,8267,8268,8265 ,0,0,0}, {6595,8367,8368 ,8269,8266,8270 ,0,0,0}, + {8367,6595,6499 ,8266,8269,8267 ,0,0,0}, {8369,6498,8368 ,8271,8272,8270 ,0,0,0}, + {6595,8368,6498 ,8269,8270,8272 ,0,0,0}, {8369,4851,4852 ,8271,1790,1790 ,0,0,0}, + {4852,6498,8369 ,1790,8272,8271 ,0,0,0}, {8360,6418,8362 ,8255,8254,8258 ,0,0,0}, + {8364,6500,6597 ,8261,8268,8262 ,0,0,0}, {8366,6500,8364 ,8265,8268,8261 ,0,0,0}, + {8358,6579,8370 ,8250,8249,8273 ,0,0,0}, {8365,6596,6417 ,8264,8263,8256 ,0,0,0}, + {8363,6597,6596 ,8260,8262,8263 ,0,0,0}, {8360,8365,6417 ,8255,8264,8256 ,0,0,0}, + {6599,8362,6418 ,8259,8258,8254 ,0,0,0}, {6565,8358,8361 ,8248,8250,8257 ,0,0,0}, + {8361,6599,6565 ,8257,8259,8248 ,0,0,0}, {6507,8357,8359 ,8252,8246,8253 ,0,0,0}, + {8370,6578,8359 ,8273,8251,8253 ,0,0,0}, {6579,6578,8370 ,8249,8251,8273 ,0,0,0}, + {4837,6506,4838 ,1711,8247,1711 ,0,0,0}, {8357,6507,6506 ,8246,8252,8247 ,0,0,0}, + {4851,8369,8368 ,726,7658,726 ,0,0,0}, {8370,4826,8358 ,726,726,726 ,0,0,0}, + {4849,8368,8367 ,7660,726,7660 ,0,0,0}, {8363,4845,8364 ,7660,726,7660 ,0,0,0}, + {4846,4849,8366 ,7660,7660,7583 ,0,0,0}, {4839,8360,8362 ,7660,7661,7661 ,0,0,0}, + {4843,8363,8365 ,726,7660,7658 ,0,0,0}, {4824,8358,4826 ,726,726,726 ,0,0,0}, + {8362,8361,4823 ,7661,726,726 ,0,0,0}, {8357,4832,4830 ,726,726,726 ,0,0,0}, + {8359,4827,8370 ,726,726,726 ,0,0,0}, {4837,4836,4832 ,726,726,726 ,0,0,0}, + {4834,4832,4836 ,726,726,726 ,0,0,0}, {4832,8357,4837 ,726,726,726 ,0,0,0}, + {8359,4830,4827 ,726,726,726 ,0,0,0}, {8359,8357,4830 ,726,726,726 ,0,0,0}, + {8361,8358,4824 ,726,726,726 ,0,0,0}, {4826,8370,4827 ,726,726,726 ,0,0,0}, + {4823,4839,8362 ,726,7660,7661 ,0,0,0}, {4824,4823,8361 ,726,726,726 ,0,0,0}, + {8365,8360,4840 ,7658,7661,7659 ,0,0,0}, {4840,8360,4839 ,7659,7661,7660 ,0,0,0}, + {4843,8365,4840 ,726,7658,7659 ,0,0,0}, {4846,8364,4845 ,7660,7660,726 ,0,0,0}, + {8363,4843,4845 ,7660,726,726 ,0,0,0}, {4849,8367,8366 ,7660,7660,7583 ,0,0,0}, + {4846,8366,8364 ,7660,7583,7660 ,0,0,0}, {4849,4851,8368 ,7660,726,726 ,0,0,0}, + {6604,4796,8371 ,8274,8275,8276 ,0,0,0}, {6605,6581,8372 ,8277,8278,8279 ,0,0,0}, + {8373,6581,6598 ,8280,8278,8281 ,0,0,0}, {8374,8375,6505 ,8282,8283,8284 ,0,0,0}, + {8376,6577,6576 ,8285,8286,8287 ,0,0,0}, {6586,6574,8377 ,8288,8289,8290 ,0,0,0}, + {6585,8378,8379 ,8291,8292,8293 ,0,0,0}, {6608,8380,6591 ,8294,8295,8296 ,0,0,0}, + {8381,8382,6587 ,1631,8297,1631 ,0,0,0}, {8383,8384,6589 ,8298,8299,8300 ,0,0,0}, + {8383,6609,8385 ,8298,8301,8302 ,0,0,0}, {8386,8387,6584 ,8303,8304,8305 ,0,0,0}, + {8386,6583,8384 ,8303,8306,8299 ,0,0,0}, {6522,8387,8388 ,8307,8304,8308 ,0,0,0}, + {8387,6522,6584 ,8304,8307,8305 ,0,0,0}, {8389,6563,8388 ,8309,8310,8308 ,0,0,0}, + {6522,8388,6563 ,8307,8308,8310 ,0,0,0}, {6504,8389,6557 ,8311,8309,8312 ,0,0,0}, + {6504,6563,8389 ,8311,8310,8309 ,0,0,0}, {6555,6557,8390 ,8313,8312,8314 ,0,0,0}, + {8389,8390,6557 ,8309,8314,8312 ,0,0,0}, {8391,4820,6555 ,8315,126,8313 ,0,0,0}, + {6555,8390,8391 ,8313,8314,8315 ,0,0,0}, {4818,4820,8391 ,126,126,8315 ,0,0,0}, + {6583,6589,8384 ,8306,8300,8299 ,0,0,0}, {8386,6584,6583 ,8303,8305,8306 ,0,0,0}, + {6609,6591,8385 ,8301,8296,8302 ,0,0,0}, {8383,6589,6609 ,8298,8300,8301 ,0,0,0}, + {8382,8380,6608 ,8297,8295,8294 ,0,0,0}, {8380,8385,6591 ,8295,8302,8296 ,0,0,0}, + {6586,8381,6587 ,8288,1631,1631 ,0,0,0}, {6587,8382,6608 ,1631,8297,8294 ,0,0,0}, + {6574,8379,8377 ,8289,8293,8290 ,0,0,0}, {6586,8377,8381 ,8288,8290,1631 ,0,0,0}, + {6585,6607,8378 ,8291,8316,8292 ,0,0,0}, {6574,6585,8379 ,8289,8291,8293 ,0,0,0}, + {6505,8375,6607 ,8284,8283,8316 ,0,0,0}, {8378,6607,8375 ,8292,8316,8283 ,0,0,0}, + {8376,8374,6577 ,8285,8282,8286 ,0,0,0}, {8374,6505,6577 ,8282,8284,8286 ,0,0,0}, + {6605,8392,6576 ,8277,8317,8287 ,0,0,0}, {8392,8376,6576 ,8317,8285,8287 ,0,0,0}, + {6581,8393,8372 ,8278,8318,8279 ,0,0,0}, {6605,8372,8392 ,8277,8279,8317 ,0,0,0}, + {8373,6598,8371 ,8280,8281,8276 ,0,0,0}, {8393,6581,8373 ,8318,8278,8280 ,0,0,0}, + {4796,6604,4795 ,8275,8274,4114 ,0,0,0}, {8371,6598,6604 ,8276,8281,8274 ,0,0,0}, + {8383,8394,8384 ,726,726,726 ,0,0,0}, {8395,4769,8391 ,726,726,726 ,0,0,0}, + {8396,8387,8397 ,726,726,726 ,0,0,0}, {4800,4754,4753 ,726,726,7661 ,0,0,0}, + {4809,4811,4763 ,726,726,726 ,0,0,0}, {8398,8390,8389 ,726,726,726 ,0,0,0}, + {4814,4817,4768 ,726,726,726 ,0,0,0}, {4818,4769,4817 ,726,726,726 ,0,0,0}, + {4766,4764,4815 ,7658,726,726 ,0,0,0}, {4814,4768,4766 ,726,726,7658 ,0,0,0}, + {8398,8395,8390 ,726,726,726 ,0,0,0}, {4811,4812,4764 ,726,726,726 ,0,0,0}, + {4809,4763,4760 ,726,726,726 ,0,0,0}, {4805,4758,4803 ,726,726,726 ,0,0,0}, + {4806,4760,4758 ,726,726,726 ,0,0,0}, {4754,4800,4803 ,726,726,726 ,0,0,0}, + {8396,8389,8388 ,726,726,726 ,0,0,0}, {8384,8399,8386 ,726,7661,726 ,0,0,0}, + {8386,8399,8397 ,726,7661,726 ,0,0,0}, {4733,4773,4772 ,7658,726,7658 ,0,0,0}, + {4799,4753,4733 ,726,7661,7658 ,0,0,0}, {8400,8394,8385 ,726,726,726 ,0,0,0}, + {4773,4737,4774 ,726,7658,726 ,0,0,0}, {4776,4738,4739 ,7661,7658,726 ,0,0,0}, + {8380,8382,8401 ,726,7661,726 ,0,0,0}, {8380,8401,8400 ,726,726,726 ,0,0,0}, + {8382,8381,8402 ,7661,7658,7658 ,0,0,0}, {4780,4779,4739 ,726,726,726 ,0,0,0}, + {4743,4782,4740 ,726,7583,726 ,0,0,0}, {8403,8404,8379 ,726,726,726 ,0,0,0}, + {8404,8402,8377 ,726,7658,726 ,0,0,0}, {4792,4746,4749 ,7664,726,7664 ,0,0,0}, + {8403,8379,8378 ,726,726,7661 ,0,0,0}, {8405,8378,8375 ,726,7661,7664 ,0,0,0}, + {4752,4796,4794 ,726,726,7664 ,0,0,0}, {8406,8371,4752 ,7664,726,726 ,0,0,0}, + {8405,8374,8407 ,726,7583,726 ,0,0,0}, {8373,8408,8393 ,7664,7664,726 ,0,0,0}, + {4774,4737,4738 ,726,7658,7658 ,0,0,0}, {8372,8393,8409 ,7664,726,7664 ,0,0,0}, + {8408,8409,8393 ,7664,7664,726 ,0,0,0}, {8373,8371,8406 ,7664,726,7664 ,0,0,0}, + {8373,8406,8408 ,7664,7664,7664 ,0,0,0}, {8410,8407,8376 ,7664,726,7583 ,0,0,0}, + {8410,8376,8392 ,7664,7583,7664 ,0,0,0}, {4796,4752,8371 ,726,726,726 ,0,0,0}, + {4745,4746,4788 ,726,726,726 ,0,0,0}, {4743,4745,4785 ,726,726,7664 ,0,0,0}, + {8410,8392,8409 ,7664,7664,7664 ,0,0,0}, {8392,8372,8409 ,7664,7664,7664 ,0,0,0}, + {8374,8376,8407 ,7583,7583,726 ,0,0,0}, {8375,8374,8405 ,7664,7583,726 ,0,0,0}, + {8403,8378,8405 ,726,7661,726 ,0,0,0}, {8377,8379,8404 ,726,726,726 ,0,0,0}, + {8381,8377,8402 ,7658,726,7658 ,0,0,0}, {8401,8382,8402 ,726,7661,7658 ,0,0,0}, + {8385,8380,8400 ,726,726,726 ,0,0,0}, {8383,8385,8394 ,726,726,726 ,0,0,0}, + {8399,8384,8394 ,7661,726,726 ,0,0,0}, {8387,8386,8397 ,726,726,726 ,0,0,0}, + {8388,8387,8396 ,726,726,726 ,0,0,0}, {8398,8389,8396 ,726,726,726 ,0,0,0}, + {8391,8390,8395 ,726,726,726 ,0,0,0}, {4818,8391,4769 ,726,726,726 ,0,0,0}, + {4768,4817,4769 ,726,726,726 ,0,0,0}, {4815,4814,4766 ,726,726,7658 ,0,0,0}, + {4812,4815,4764 ,726,726,726 ,0,0,0}, {4763,4811,4764 ,726,726,726 ,0,0,0}, + {4806,4809,4760 ,726,726,726 ,0,0,0}, {4805,4806,4758 ,726,726,726 ,0,0,0}, + {4754,4803,4758 ,726,726,726 ,0,0,0}, {4799,4800,4753 ,726,726,7661 ,0,0,0}, + {4772,4799,4733 ,7658,726,7658 ,0,0,0}, {4737,4773,4733 ,7658,726,7658 ,0,0,0}, + {4779,4776,4739 ,726,7661,726 ,0,0,0}, {4776,4774,4738 ,7661,726,7658 ,0,0,0}, + {4740,4780,4739 ,726,726,726 ,0,0,0}, {4743,4785,4782 ,726,7664,7583 ,0,0,0}, + {4740,4782,4780 ,726,7583,726 ,0,0,0}, {4745,4786,4785 ,726,7664,7664 ,0,0,0}, + {4788,4746,4792 ,726,726,7664 ,0,0,0}, {4786,4745,4788 ,7664,726,726 ,0,0,0}, + {4792,4749,4794 ,7664,7664,7664 ,0,0,0}, {4752,4794,4749 ,726,7664,7664 ,0,0,0}, + {8411,8412,4736 ,726,726,726 ,0,0,0}, {4755,4757,4765 ,726,726,726 ,0,0,0}, + {4734,4755,4770 ,726,726,726 ,0,0,0}, {4736,4735,8411 ,726,726,726 ,0,0,0}, + {4761,4762,4765 ,726,726,726 ,0,0,0}, {4756,4759,4757 ,726,726,726 ,0,0,0}, + {4761,4765,4759 ,726,726,726 ,0,0,0}, {4757,4759,4765 ,726,726,726 ,0,0,0}, + {4765,4767,4755 ,726,726,726 ,0,0,0}, {8411,4734,4770 ,726,726,726 ,0,0,0}, + {4770,4755,4767 ,726,726,726 ,0,0,0}, {4736,8412,8413 ,726,726,726 ,0,0,0}, + {8411,4735,4734 ,726,726,726 ,0,0,0}, {4741,8413,8414 ,726,726,726 ,0,0,0}, + {8413,4741,4736 ,726,726,726 ,0,0,0}, {8414,4744,4742 ,726,726,7658 ,0,0,0}, + {4741,8414,4742 ,726,726,7658 ,0,0,0}, {8415,4744,8414 ,726,726,726 ,0,0,0}, + {4744,8416,4747 ,726,726,7661 ,0,0,0}, {8416,4744,8415 ,726,726,726 ,0,0,0}, + {8416,8417,4747 ,726,726,7661 ,0,0,0}, {4748,8417,4750 ,726,726,7661 ,0,0,0}, + {4748,4747,8417 ,726,7661,726 ,0,0,0}, {4750,8418,8419 ,7661,726,726 ,0,0,0}, + {8417,8418,4750 ,726,726,7661 ,0,0,0}, {8420,4751,8419 ,726,7658,726 ,0,0,0}, + {4750,8419,4751 ,7661,726,7658 ,0,0,0}, {8421,8422,8423 ,726,726,7660 ,0,0,0}, + {8423,8424,8421 ,7660,726,726 ,0,0,0}, {8422,8425,8426 ,726,726,7658 ,0,0,0}, + {8422,8420,8423 ,726,726,7660 ,0,0,0}, {8422,8427,8420 ,726,7661,726 ,0,0,0}, + {8422,8421,8425 ,726,726,726 ,0,0,0}, {8420,8427,4751 ,726,7661,7658 ,0,0,0}, + {8427,4752,4751 ,8319,81,8320 ,0,0,0}, {8425,8410,8426 ,8321,8322,8323 ,0,0,0}, + {8422,8409,8408 ,8324,8325,8326 ,0,0,0}, {8423,8420,8403 ,8327,8328,8329 ,0,0,0}, + {8421,8424,8405 ,8330,8331,8332 ,0,0,0}, {8417,8401,8418 ,8333,8334,8335 ,0,0,0}, + {8402,8419,8418 ,8336,8337,8335 ,0,0,0}, {8415,8399,8416 ,7530,8338,8339 ,0,0,0}, + {8394,8417,8416 ,8340,8333,8339 ,0,0,0}, {8414,8396,8397 ,8341,8342,8343 ,0,0,0}, + {8397,8415,8414 ,8343,7530,8341 ,0,0,0}, {8396,8413,8398 ,8342,8344,8345 ,0,0,0}, + {8413,8396,8414 ,8344,8342,8341 ,0,0,0}, {8395,8398,8412 ,8346,8345,8347 ,0,0,0}, + {8413,8412,8398 ,8344,8347,8345 ,0,0,0}, {4770,8395,8411 ,96,8346,8348 ,0,0,0}, + {8395,8412,8411 ,8346,8347,8348 ,0,0,0}, {4769,8395,4770 ,96,8346,96 ,0,0,0}, + {8394,8416,8399 ,8340,8339,8338 ,0,0,0}, {8397,8399,8415 ,8343,8338,7530 ,0,0,0}, + {8400,8401,8417 ,8349,8334,8333 ,0,0,0}, {8394,8400,8417 ,8340,8349,8333 ,0,0,0}, + {8404,8419,8402 ,8350,8337,8336 ,0,0,0}, {8401,8402,8418 ,8334,8336,8335 ,0,0,0}, + {8403,8420,8404 ,8329,8328,8350 ,0,0,0}, {8419,8404,8420 ,8337,8350,8328 ,0,0,0}, + {8405,8424,8403 ,8332,8331,8329 ,0,0,0}, {8424,8423,8403 ,8331,8327,8329 ,0,0,0}, + {8407,8425,8421 ,7516,8321,8330 ,0,0,0}, {8407,8421,8405 ,7516,8330,8332 ,0,0,0}, + {8410,8409,8426 ,8322,8325,8323 ,0,0,0}, {8407,8410,8425 ,7516,8322,8321 ,0,0,0}, + {8422,8408,8427 ,8324,8326,8319 ,0,0,0}, {8426,8409,8422 ,8323,8325,8324 ,0,0,0}, + {4752,8427,8406 ,81,8319,8351 ,0,0,0}, {8427,8408,8406 ,8319,8326,8351 ,0,0,0} +// MotorHacker.prt + , {8428,8429,8430 ,4056,4057,4058 ,0,0,0}, {8431,8432,8430 ,4059,4060,4058 ,0,0,0}, + {8428,8430,8432 ,4056,4058,4060 ,0,0,0}, {8433,8431,8434 ,4061,4059,4062 ,0,0,0}, + {8433,8432,8431 ,4061,4060,4059 ,0,0,0}, {8435,8434,8436 ,4063,4062,4064 ,0,0,0}, + {8431,8436,8434 ,4059,4064,4062 ,0,0,0}, {8437,8438,8435 ,4065,4066,4063 ,0,0,0}, + {8435,8436,8437 ,4063,4064,4065 ,0,0,0}, {8438,8439,8440 ,4066,4067,4068 ,0,0,0}, + {8439,8438,8437 ,4067,4066,4065 ,0,0,0}, {8441,8440,8442 ,4069,4068,4070 ,0,0,0}, + {8439,8442,8440 ,4067,4070,4068 ,0,0,0}, {8443,8444,8441 ,4071,4072,4069 ,0,0,0}, + {8441,8442,8443 ,4069,4070,4071 ,0,0,0}, {8445,8446,8444 ,4073,81,4072 ,0,0,0}, + {8445,8444,8443 ,4073,4072,4071 ,0,0,0}, {8446,8447,8444 ,81,81,4072 ,0,0,0}, + {8448,8429,8428 ,4074,4057,4056 ,0,0,0}, {8448,8449,8450 ,4074,4075,4076 ,0,0,0}, + {8450,8429,8448 ,4076,4057,4074 ,0,0,0}, {8451,8452,8449 ,4077,4078,4075 ,0,0,0}, + {8449,8452,8450 ,4075,4078,4076 ,0,0,0}, {8453,8454,8451 ,4079,4080,4077 ,0,0,0}, + {8451,8449,8453 ,4077,4075,4079 ,0,0,0}, {8454,8455,8456 ,4080,4081,4082 ,0,0,0}, + {8455,8454,8453 ,4081,4080,4079 ,0,0,0}, {8457,8456,8458 ,4083,4082,4084 ,0,0,0}, + {8455,8458,8456 ,4081,4084,4082 ,0,0,0}, {8459,8460,8457 ,4085,4086,4083 ,0,0,0}, + {8457,8458,8459 ,4083,4084,4085 ,0,0,0}, {8460,8461,8462 ,4086,4087,4088 ,0,0,0}, + {8461,8460,8459 ,4087,4086,4085 ,0,0,0}, {8462,8463,8464 ,4088,4089,4090 ,0,0,0}, + {8461,8463,8462 ,4087,4089,4088 ,0,0,0}, {8462,8464,8465 ,4088,4090,4091 ,0,0,0}, + {8466,8467,8468 ,2394,2394,4092 ,0,0,0}, {8469,8470,8468 ,4093,4094,4092 ,0,0,0}, + {8466,8468,8470 ,2394,4092,4094 ,0,0,0}, {8469,8471,8472 ,4093,4095,4096 ,0,0,0}, + {8472,8470,8469 ,4096,4094,4093 ,0,0,0}, {8473,8471,8474 ,4097,4095,4098 ,0,0,0}, + {8471,8473,8472 ,4095,4097,4096 ,0,0,0}, {8475,8476,8474 ,4099,4100,4098 ,0,0,0}, + {8473,8474,8476 ,4097,4098,4100 ,0,0,0}, {8475,8477,8478 ,4099,4101,4102 ,0,0,0}, + {8478,8476,8475 ,4102,4100,4099 ,0,0,0}, {8479,8477,8480 ,4103,4101,4104 ,0,0,0}, + {8477,8479,8478 ,4101,4103,4102 ,0,0,0}, {8481,8482,8480 ,4105,4106,4104 ,0,0,0}, + {8479,8480,8482 ,4103,4104,4106 ,0,0,0}, {8481,8483,8484 ,4105,4107,4108 ,0,0,0}, + {8484,8482,8481 ,4108,4106,4105 ,0,0,0}, {8485,8486,8483 ,4109,4110,4107 ,0,0,0}, + {8483,8486,8484 ,4107,4110,4108 ,0,0,0}, {8487,8488,8485 ,4111,4112,4109 ,0,0,0}, + {8485,8483,8487 ,4109,4107,4111 ,0,0,0}, {8488,8489,8490 ,4112,4113,4114 ,0,0,0}, + {8489,8488,8487 ,4113,4112,4111 ,0,0,0}, {8489,8491,8490 ,4113,4114,4114 ,0,0,0}, + {8492,8467,8466 ,4115,2394,2394 ,0,0,0}, {8492,8493,8494 ,4115,4116,4117 ,0,0,0}, + {8494,8467,8492 ,4117,2394,4115 ,0,0,0}, {8495,8493,8496 ,4118,4116,4119 ,0,0,0}, + {8493,8495,8494 ,4116,4118,4117 ,0,0,0}, {8497,8498,8496 ,4120,4121,4119 ,0,0,0}, + {8495,8496,8498 ,4118,4119,4121 ,0,0,0}, {8497,8499,8500 ,4120,4122,4123 ,0,0,0}, + {8500,8498,8497 ,4123,4121,4120 ,0,0,0}, {8501,8499,8502 ,4124,4122,4125 ,0,0,0}, + {8499,8501,8500 ,4122,4124,4123 ,0,0,0}, {8503,8504,8502 ,4126,4127,4125 ,0,0,0}, + {8501,8502,8504 ,4124,4125,4127 ,0,0,0}, {8503,8505,8506 ,4126,4128,4129 ,0,0,0}, + {8506,8504,8503 ,4129,4127,4126 ,0,0,0}, {8507,8505,8508 ,4130,4128,4131 ,0,0,0}, + {8505,8507,8506 ,4128,4130,4129 ,0,0,0}, {8508,8509,8510 ,4131,4132,4133 ,0,0,0}, + {8507,8508,8510 ,4130,4131,4133 ,0,0,0}, {8509,8511,8512 ,4132,4134,4135 ,0,0,0}, + {8511,8509,8508 ,4134,4132,4131 ,0,0,0}, {8513,8512,8514 ,126,4135,4136 ,0,0,0}, + {8511,8514,8512 ,4134,4136,4135 ,0,0,0}, {8513,8514,8515 ,126,4136,126 ,0,0,0}, + {8516,8517,8518 ,4137,4138,4139 ,0,0,0}, {8516,8519,8520 ,4137,4140,4141 ,0,0,0}, + {8519,8521,8520 ,4140,4142,4141 ,0,0,0}, {8518,8519,8516 ,4139,4140,4137 ,0,0,0}, + {8522,8523,8524 ,4143,4144,4145 ,0,0,0}, {8521,8522,8524 ,4142,4143,4145 ,0,0,0}, + {8523,8525,8526 ,4144,4146,4147 ,0,0,0}, {8525,8523,8522 ,4146,4144,4143 ,0,0,0}, + {8526,8525,8527 ,4147,4146,4148 ,0,0,0}, {8528,8526,8527 ,4149,4147,4148 ,0,0,0}, + {8528,8529,8530 ,4149,4150,4151 ,0,0,0}, {8528,8527,8529 ,4149,4148,4150 ,0,0,0}, + {8524,8520,8521 ,4145,4141,4142 ,0,0,0}, {8531,8532,8533 ,4152,1711,1711 ,0,0,0}, + {8531,8533,8530 ,4152,1711,4151 ,0,0,0}, {8529,8531,8530 ,4150,4152,4151 ,0,0,0}, + {8518,8517,8534 ,4139,4138,4153 ,0,0,0}, {8535,8534,8536 ,4154,4153,4155 ,0,0,0}, + {8517,8536,8534 ,4138,4155,4153 ,0,0,0}, {8537,8538,8535 ,4156,4157,4154 ,0,0,0}, + {8535,8536,8537 ,4154,4155,4156 ,0,0,0}, {8538,8539,8540 ,4157,4158,4159 ,0,0,0}, + {8539,8538,8537 ,4158,4157,4156 ,0,0,0}, {8541,8540,8542 ,4160,4159,4161 ,0,0,0}, + {8539,8542,8540 ,4158,4161,4159 ,0,0,0}, {8543,8544,8541 ,4162,4163,4160 ,0,0,0}, + {8541,8542,8543 ,4160,4161,4162 ,0,0,0}, {8544,8545,8546 ,4163,4164,1790 ,0,0,0}, + {8545,8544,8543 ,4164,4163,4162 ,0,0,0}, {8545,8547,8546 ,4164,1790,1790 ,0,0,0}, + {8548,8549,8550 ,4165,4166,4167 ,0,0,0}, {8551,8552,8553 ,4168,4169,4170 ,0,0,0}, + {8552,8548,8550 ,4169,4165,4167 ,0,0,0}, {8554,8551,8553 ,4171,4168,4170 ,0,0,0}, + {8552,8551,8548 ,4169,4168,4165 ,0,0,0}, {8554,8553,8555 ,4171,4170,4172 ,0,0,0}, + {8555,8556,8557 ,4172,4173,4174 ,0,0,0}, {8558,8557,8556 ,4175,4174,4173 ,0,0,0}, + {8559,8560,8561 ,4176,4177,4178 ,0,0,0}, {8556,8562,8558 ,4173,4179,4175 ,0,0,0}, + {8561,8563,8564 ,4178,4180,4181 ,0,0,0}, {8563,8562,8564 ,4180,4179,4181 ,0,0,0}, + {8558,8562,8563 ,4175,4179,4180 ,0,0,0}, {8561,8564,8559 ,4178,4181,4176 ,0,0,0}, + {8560,8559,8565 ,4177,4176,4182 ,0,0,0}, {8560,8565,8566 ,4177,4182,4183 ,0,0,0}, + {8567,8566,8565 ,4184,4183,4182 ,0,0,0}, {8568,8569,8570 ,4185,1711,4186 ,0,0,0}, + {8570,8566,8567 ,4186,4183,4184 ,0,0,0}, {8568,8570,8567 ,4185,4186,4184 ,0,0,0}, + {8568,8571,8569 ,4185,1711,1711 ,0,0,0}, {8554,8555,8557 ,4171,4172,4174 ,0,0,0}, + {8550,8549,8572 ,4167,4166,4187 ,0,0,0}, {8573,8572,8574 ,4188,4187,4189 ,0,0,0}, + {8549,8574,8572 ,4166,4189,4187 ,0,0,0}, {8575,8576,8573 ,4190,4191,4188 ,0,0,0}, + {8573,8574,8575 ,4188,4189,4190 ,0,0,0}, {8576,8577,8578 ,4191,4192,4193 ,0,0,0}, + {8577,8576,8575 ,4192,4191,4190 ,0,0,0}, {8579,8578,8580 ,4194,4193,4195 ,0,0,0}, + {8577,8580,8578 ,4192,4195,4193 ,0,0,0}, {8581,8582,8579 ,4196,4197,4194 ,0,0,0}, + {8579,8580,8581 ,4194,4195,4196 ,0,0,0}, {8582,8583,8584 ,4197,4198,4199 ,0,0,0}, + {8583,8582,8581 ,4198,4197,4196 ,0,0,0}, {8585,8584,8586 ,4200,4199,4201 ,0,0,0}, + {8583,8586,8584 ,4198,4201,4199 ,0,0,0}, {8587,8588,8585 ,4202,4203,4200 ,0,0,0}, + {8585,8586,8587 ,4200,4201,4202 ,0,0,0}, {8588,8589,8590 ,4203,4204,1790 ,0,0,0}, + {8589,8588,8587 ,4204,4203,4202 ,0,0,0}, {8589,8591,8590 ,4204,1790,1790 ,0,0,0}, + {8592,8593,8594 ,4205,4206,4207 ,0,0,0}, {8592,8595,8596 ,4205,4208,4209 ,0,0,0}, + {8595,8597,8596 ,4208,4210,4209 ,0,0,0}, {8594,8595,8592 ,4207,4208,4205 ,0,0,0}, + {8598,8599,8600 ,4211,4212,4213 ,0,0,0}, {8597,8598,8600 ,4210,4211,4213 ,0,0,0}, + {8599,8601,8602 ,4212,4214,4215 ,0,0,0}, {8601,8599,8598 ,4214,4212,4211 ,0,0,0}, + {8602,8601,8603 ,4215,4214,4216 ,0,0,0}, {8604,8602,8603 ,4217,4215,4216 ,0,0,0}, + {8604,8605,8606 ,4217,4218,4219 ,0,0,0}, {8604,8603,8605 ,4217,4216,4218 ,0,0,0}, + {8600,8596,8597 ,4213,4209,4210 ,0,0,0}, {8607,8608,8609 ,4220,1359,1359 ,0,0,0}, + {8607,8609,8606 ,4220,1359,4219 ,0,0,0}, {8605,8607,8606 ,4218,4220,4219 ,0,0,0}, + {8594,8593,8610 ,4207,4206,4221 ,0,0,0}, {8611,8610,8612 ,4222,4221,4223 ,0,0,0}, + {8593,8612,8610 ,4206,4223,4221 ,0,0,0}, {8613,8614,8611 ,4224,4225,4222 ,0,0,0}, + {8611,8612,8613 ,4222,4223,4224 ,0,0,0}, {8614,8615,8616 ,4225,4226,4227 ,0,0,0}, + {8615,8614,8613 ,4226,4225,4224 ,0,0,0}, {8617,8616,8618 ,4228,4227,4229 ,0,0,0}, + {8615,8618,8616 ,4226,4229,4227 ,0,0,0}, {8619,8620,8617 ,4230,4231,4228 ,0,0,0}, + {8617,8618,8619 ,4228,4229,4230 ,0,0,0}, {8620,8621,8622 ,4231,4232,1435 ,0,0,0}, + {8621,8620,8619 ,4232,4231,4230 ,0,0,0}, {8621,8623,8622 ,4232,1435,1435 ,0,0,0}, + {8624,8625,8626 ,4233,4234,4235 ,0,0,0}, {8627,8628,8629 ,4236,4237,4238 ,0,0,0}, + {8628,8624,8626 ,4237,4233,4235 ,0,0,0}, {8630,8627,8629 ,4239,4236,4238 ,0,0,0}, + {8628,8627,8624 ,4237,4236,4233 ,0,0,0}, {8630,8629,8631 ,4239,4238,4240 ,0,0,0}, + {8631,8632,8633 ,4240,4241,4242 ,0,0,0}, {8634,8633,8632 ,4243,4242,4241 ,0,0,0}, + {8635,8636,8637 ,4244,4245,4246 ,0,0,0}, {8632,8638,8634 ,4241,4247,4243 ,0,0,0}, + {8637,8639,8640 ,4246,4248,4249 ,0,0,0}, {8639,8638,8640 ,4248,4247,4249 ,0,0,0}, + {8634,8638,8639 ,4243,4247,4248 ,0,0,0}, {8637,8640,8635 ,4246,4249,4244 ,0,0,0}, + {8636,8635,8641 ,4245,4244,4250 ,0,0,0}, {8636,8641,8642 ,4245,4250,4251 ,0,0,0}, + {8643,8642,8641 ,4252,4251,4250 ,0,0,0}, {8644,8645,8646 ,4253,1359,4254 ,0,0,0}, + {8646,8642,8643 ,4254,4251,4252 ,0,0,0}, {8644,8646,8643 ,4253,4254,4252 ,0,0,0}, + {8644,8647,8645 ,4253,1359,1359 ,0,0,0}, {8630,8631,8633 ,4239,4240,4242 ,0,0,0}, + {8626,8625,8648 ,4235,4234,4255 ,0,0,0}, {8649,8648,8650 ,4256,4255,4257 ,0,0,0}, + {8625,8650,8648 ,4234,4257,4255 ,0,0,0}, {8651,8652,8649 ,4258,4259,4256 ,0,0,0}, + {8649,8650,8651 ,4256,4257,4258 ,0,0,0}, {8652,8653,8654 ,4259,4260,4261 ,0,0,0}, + {8653,8652,8651 ,4260,4259,4258 ,0,0,0}, {8655,8654,8656 ,4262,4261,4263 ,0,0,0}, + {8653,8656,8654 ,4260,4263,4261 ,0,0,0}, {8657,8658,8655 ,4264,4265,4262 ,0,0,0}, + {8655,8656,8657 ,4262,4263,4264 ,0,0,0}, {8658,8659,8660 ,4265,4266,4267 ,0,0,0}, + {8659,8658,8657 ,4266,4265,4264 ,0,0,0}, {8661,8660,8662 ,4268,4267,4269 ,0,0,0}, + {8659,8662,8660 ,4266,4269,4267 ,0,0,0}, {8663,8664,8661 ,4270,4271,4268 ,0,0,0}, + {8661,8662,8663 ,4268,4269,4270 ,0,0,0}, {8664,8665,8666 ,4271,4272,1435 ,0,0,0}, + {8665,8664,8663 ,4272,4271,4270 ,0,0,0}, {8665,8667,8666 ,4272,1435,1435 ,0,0,0}, + {8668,8669,8670 ,4273,4274,4275 ,0,0,0}, {8668,8671,8672 ,4273,4276,4277 ,0,0,0}, + {8671,8673,8672 ,4276,4278,4277 ,0,0,0}, {8670,8671,8668 ,4275,4276,4273 ,0,0,0}, + {8674,8675,8676 ,4279,4280,4281 ,0,0,0}, {8673,8674,8676 ,4278,4279,4281 ,0,0,0}, + {8675,8677,8678 ,4280,4282,4283 ,0,0,0}, {8677,8675,8674 ,4282,4280,4279 ,0,0,0}, + {8678,8677,8679 ,4283,4282,4284 ,0,0,0}, {8680,8678,8679 ,4285,4283,4284 ,0,0,0}, + {8680,8681,8682 ,4285,4286,4287 ,0,0,0}, {8680,8679,8681 ,4285,4284,4286 ,0,0,0}, + {8676,8672,8673 ,4281,4277,4278 ,0,0,0}, {8683,8684,8685 ,4288,126,4289 ,0,0,0}, + {8683,8685,8682 ,4288,4289,4287 ,0,0,0}, {8681,8683,8682 ,4286,4288,4287 ,0,0,0}, + {8670,8669,8686 ,4275,4274,4290 ,0,0,0}, {8687,8686,8688 ,4291,4290,4292 ,0,0,0}, + {8669,8688,8686 ,4274,4292,4290 ,0,0,0}, {8689,8690,8687 ,4293,4294,4291 ,0,0,0}, + {8687,8688,8689 ,4291,4292,4293 ,0,0,0}, {8690,8691,8692 ,4294,4295,4296 ,0,0,0}, + {8691,8690,8689 ,4295,4294,4293 ,0,0,0}, {8693,8692,8694 ,4297,4296,4298 ,0,0,0}, + {8691,8694,8692 ,4295,4298,4296 ,0,0,0}, {8695,8696,8693 ,4299,4300,4297 ,0,0,0}, + {8693,8694,8695 ,4297,4298,4299 ,0,0,0}, {8696,8697,8698 ,4300,4301,4302 ,0,0,0}, + {8697,8696,8695 ,4301,4300,4299 ,0,0,0}, {8697,8699,8698 ,4301,4303,4302 ,0,0,0}, + {8700,8701,8702 ,4304,4305,4306 ,0,0,0}, {8703,8704,8705 ,4307,4308,4309 ,0,0,0}, + {8704,8700,8702 ,4308,4304,4306 ,0,0,0}, {8706,8703,8705 ,4310,4307,4309 ,0,0,0}, + {8704,8703,8700 ,4308,4307,4304 ,0,0,0}, {8706,8705,8707 ,4310,4309,4311 ,0,0,0}, + {8707,8708,8709 ,4311,4312,4313 ,0,0,0}, {8710,8709,8708 ,4314,4313,4312 ,0,0,0}, + {8711,8712,8713 ,4315,4316,4317 ,0,0,0}, {8708,8714,8710 ,4312,4318,4314 ,0,0,0}, + {8713,8715,8716 ,4317,4319,4320 ,0,0,0}, {8715,8714,8716 ,4319,4318,4320 ,0,0,0}, + {8710,8714,8715 ,4314,4318,4319 ,0,0,0}, {8713,8716,8711 ,4317,4320,4315 ,0,0,0}, + {8712,8711,8717 ,4316,4315,4321 ,0,0,0}, {8712,8717,8718 ,4316,4321,4322 ,0,0,0}, + {8719,8718,8717 ,4323,4322,4321 ,0,0,0}, {8720,8721,8722 ,4324,126,4325 ,0,0,0}, + {8722,8718,8719 ,4325,4322,4323 ,0,0,0}, {8720,8722,8719 ,4324,4325,4323 ,0,0,0}, + {8720,8723,8721 ,4324,4326,126 ,0,0,0}, {8706,8707,8709 ,4310,4311,4313 ,0,0,0}, + {8702,8701,8724 ,4306,4305,4327 ,0,0,0}, {8725,8724,8726 ,4328,4327,4329 ,0,0,0}, + {8701,8726,8724 ,4305,4329,4327 ,0,0,0}, {8727,8728,8725 ,4330,4331,4328 ,0,0,0}, + {8725,8726,8727 ,4328,4329,4330 ,0,0,0}, {8728,8729,8730 ,4331,4332,4333 ,0,0,0}, + {8729,8728,8727 ,4332,4331,4330 ,0,0,0}, {8731,8730,8732 ,4334,4333,4335 ,0,0,0}, + {8729,8732,8730 ,4332,4335,4333 ,0,0,0}, {8733,8734,8731 ,4336,4337,4334 ,0,0,0}, + {8731,8732,8733 ,4334,4335,4336 ,0,0,0}, {8734,8735,8736 ,4337,4338,4339 ,0,0,0}, + {8735,8734,8733 ,4338,4337,4336 ,0,0,0}, {8737,8736,8738 ,4340,4339,4341 ,0,0,0}, + {8735,8738,8736 ,4338,4341,4339 ,0,0,0}, {8739,8740,8737 ,4342,4343,4340 ,0,0,0}, + {8737,8738,8739 ,4340,4341,4342 ,0,0,0}, {8740,8741,8742 ,4343,4344,4345 ,0,0,0}, + {8741,8740,8739 ,4344,4343,4342 ,0,0,0}, {8741,8743,8742 ,4344,4346,4345 ,0,0,0}, + {8744,8745,8746 ,4347,4348,4349 ,0,0,0}, {8744,8747,8748 ,4347,4350,4351 ,0,0,0}, + {8747,8749,8748 ,4350,4352,4351 ,0,0,0}, {8746,8747,8744 ,4349,4350,4347 ,0,0,0}, + {8750,8751,8752 ,4353,4354,4355 ,0,0,0}, {8749,8750,8752 ,4352,4353,4355 ,0,0,0}, + {8751,8753,8754 ,4354,4356,4357 ,0,0,0}, {8753,8751,8750 ,4356,4354,4353 ,0,0,0}, + {8754,8753,8755 ,4357,4356,4358 ,0,0,0}, {8756,8754,8755 ,4359,4357,4358 ,0,0,0}, + {8756,8757,8758 ,4359,4360,4361 ,0,0,0}, {8756,8755,8757 ,4359,4358,4360 ,0,0,0}, + {8752,8748,8749 ,4355,4351,4352 ,0,0,0}, {8759,8760,8761 ,4362,1790,1790 ,0,0,0}, + {8759,8761,8758 ,4362,1790,4361 ,0,0,0}, {8757,8759,8758 ,4360,4362,4361 ,0,0,0}, + {8746,8745,8762 ,4349,4348,4363 ,0,0,0}, {8763,8762,8764 ,4364,4363,4365 ,0,0,0}, + {8745,8764,8762 ,4348,4365,4363 ,0,0,0}, {8765,8766,8763 ,4366,4367,4364 ,0,0,0}, + {8763,8764,8765 ,4364,4365,4366 ,0,0,0}, {8766,8767,8768 ,4367,4368,4369 ,0,0,0}, + {8767,8766,8765 ,4368,4367,4366 ,0,0,0}, {8769,8768,8770 ,4370,4369,4371 ,0,0,0}, + {8767,8770,8768 ,4368,4371,4369 ,0,0,0}, {8771,8772,8769 ,4372,4373,4370 ,0,0,0}, + {8769,8770,8771 ,4370,4371,4372 ,0,0,0}, {8772,8773,8774 ,4373,4374,1711 ,0,0,0}, + {8773,8772,8771 ,4374,4373,4372 ,0,0,0}, {8773,8775,8774 ,4374,1711,1711 ,0,0,0}, + {8776,8777,8778 ,4375,4376,4377 ,0,0,0}, {8779,8780,8781 ,4378,4379,4380 ,0,0,0}, + {8780,8776,8778 ,4379,4375,4377 ,0,0,0}, {8782,8779,8781 ,4381,4378,4380 ,0,0,0}, + {8780,8779,8776 ,4379,4378,4375 ,0,0,0}, {8782,8781,8783 ,4381,4380,4382 ,0,0,0}, + {8783,8784,8785 ,4382,4383,4384 ,0,0,0}, {8786,8785,8784 ,4385,4384,4383 ,0,0,0}, + {8787,8788,8789 ,4386,4387,4388 ,0,0,0}, {8784,8790,8786 ,4383,4389,4385 ,0,0,0}, + {8789,8791,8792 ,4388,4390,4391 ,0,0,0}, {8791,8790,8792 ,4390,4389,4391 ,0,0,0}, + {8786,8790,8791 ,4385,4389,4390 ,0,0,0}, {8789,8792,8787 ,4388,4391,4386 ,0,0,0}, + {8788,8787,8793 ,4387,4386,4392 ,0,0,0}, {8788,8793,8794 ,4387,4392,4393 ,0,0,0}, + {8795,8794,8793 ,4394,4393,4392 ,0,0,0}, {8796,8797,8798 ,4395,1790,4396 ,0,0,0}, + {8798,8794,8795 ,4396,4393,4394 ,0,0,0}, {8796,8798,8795 ,4395,4396,4394 ,0,0,0}, + {8796,8799,8797 ,4395,1790,1790 ,0,0,0}, {8782,8783,8785 ,4381,4382,4384 ,0,0,0}, + {8778,8777,8800 ,4377,4376,4397 ,0,0,0}, {8801,8800,8802 ,4398,4397,4399 ,0,0,0}, + {8777,8802,8800 ,4376,4399,4397 ,0,0,0}, {8803,8804,8801 ,4400,4401,4398 ,0,0,0}, + {8801,8802,8803 ,4398,4399,4400 ,0,0,0}, {8804,8805,8806 ,4401,4402,4403 ,0,0,0}, + {8805,8804,8803 ,4402,4401,4400 ,0,0,0}, {8807,8806,8808 ,4404,4403,4405 ,0,0,0}, + {8805,8808,8806 ,4402,4405,4403 ,0,0,0}, {8809,8810,8807 ,4406,4407,4404 ,0,0,0}, + {8807,8808,8809 ,4404,4405,4406 ,0,0,0}, {8810,8811,8812 ,4407,4408,4409 ,0,0,0}, + {8811,8810,8809 ,4408,4407,4406 ,0,0,0}, {8813,8812,8814 ,4410,4409,4411 ,0,0,0}, + {8811,8814,8812 ,4408,4411,4409 ,0,0,0}, {8815,8816,8813 ,4412,4413,4410 ,0,0,0}, + {8813,8814,8815 ,4410,4411,4412 ,0,0,0}, {8816,8817,8818 ,4413,4414,1711 ,0,0,0}, + {8817,8816,8815 ,4414,4413,4412 ,0,0,0}, {8817,8819,8818 ,4414,1711,1711 ,0,0,0}, + {8820,8821,8822 ,4415,4416,4417 ,0,0,0}, {8820,8823,8824 ,4415,4418,4419 ,0,0,0}, + {8823,8825,8824 ,4418,4420,4419 ,0,0,0}, {8822,8823,8820 ,4417,4418,4415 ,0,0,0}, + {8826,8827,8828 ,4421,4422,4423 ,0,0,0}, {8825,8826,8828 ,4420,4421,4423 ,0,0,0}, + {8827,8829,8830 ,4422,4424,4425 ,0,0,0}, {8829,8827,8826 ,4424,4422,4421 ,0,0,0}, + {8830,8829,8831 ,4425,4424,4426 ,0,0,0}, {8832,8830,8831 ,4427,4425,4426 ,0,0,0}, + {8832,8833,8834 ,4427,4428,4429 ,0,0,0}, {8832,8831,8833 ,4427,4426,4428 ,0,0,0}, + {8828,8824,8825 ,4423,4419,4420 ,0,0,0}, {8835,8836,8837 ,4430,1435,1435 ,0,0,0}, + {8835,8837,8834 ,4430,1435,4429 ,0,0,0}, {8833,8835,8834 ,4428,4430,4429 ,0,0,0}, + {8822,8821,8838 ,4417,4416,4431 ,0,0,0}, {8839,8838,8840 ,4432,4431,4433 ,0,0,0}, + {8821,8840,8838 ,4416,4433,4431 ,0,0,0}, {8841,8842,8839 ,4434,4435,4432 ,0,0,0}, + {8839,8840,8841 ,4432,4433,4434 ,0,0,0}, {8842,8843,8844 ,4435,4436,4437 ,0,0,0}, + {8843,8842,8841 ,4436,4435,4434 ,0,0,0}, {8845,8844,8846 ,4438,4437,4439 ,0,0,0}, + {8843,8846,8844 ,4436,4439,4437 ,0,0,0}, {8847,8848,8845 ,4440,4441,4438 ,0,0,0}, + {8845,8846,8847 ,4438,4439,4440 ,0,0,0}, {8848,8849,8850 ,4441,4442,1359 ,0,0,0}, + {8849,8848,8847 ,4442,4441,4440 ,0,0,0}, {8849,8851,8850 ,4442,1359,1359 ,0,0,0}, + {8852,8853,8854 ,4443,4444,4445 ,0,0,0}, {8855,8856,8857 ,4446,4447,4448 ,0,0,0}, + {8856,8852,8854 ,4447,4443,4445 ,0,0,0}, {8858,8855,8857 ,4449,4446,4448 ,0,0,0}, + {8856,8855,8852 ,4447,4446,4443 ,0,0,0}, {8858,8857,8859 ,4449,4448,4450 ,0,0,0}, + {8859,8860,8861 ,4450,4451,4452 ,0,0,0}, {8862,8861,8860 ,4453,4452,4451 ,0,0,0}, + {8863,8864,8865 ,4454,4455,4456 ,0,0,0}, {8860,8866,8862 ,4451,4457,4453 ,0,0,0}, + {8865,8867,8868 ,4456,4458,4459 ,0,0,0}, {8867,8866,8868 ,4458,4457,4459 ,0,0,0}, + {8862,8866,8867 ,4453,4457,4458 ,0,0,0}, {8865,8868,8863 ,4456,4459,4454 ,0,0,0}, + {8864,8863,8869 ,4455,4454,4460 ,0,0,0}, {8864,8869,8870 ,4455,4460,4461 ,0,0,0}, + {8871,8870,8869 ,4462,4461,4460 ,0,0,0}, {8872,8873,8874 ,4463,1435,4464 ,0,0,0}, + {8874,8870,8871 ,4464,4461,4462 ,0,0,0}, {8872,8874,8871 ,4463,4464,4462 ,0,0,0}, + {8872,8875,8873 ,4463,1435,1435 ,0,0,0}, {8858,8859,8861 ,4449,4450,4452 ,0,0,0}, + {8854,8853,8876 ,4445,4444,4465 ,0,0,0}, {8877,8876,8878 ,4466,4465,4467 ,0,0,0}, + {8853,8878,8876 ,4444,4467,4465 ,0,0,0}, {8879,8880,8877 ,4468,4469,4466 ,0,0,0}, + {8877,8878,8879 ,4466,4467,4468 ,0,0,0}, {8880,8881,8882 ,4469,4470,4471 ,0,0,0}, + {8881,8880,8879 ,4470,4469,4468 ,0,0,0}, {8883,8882,8884 ,4472,4471,4473 ,0,0,0}, + {8881,8884,8882 ,4470,4473,4471 ,0,0,0}, {8885,8886,8883 ,4474,4475,4472 ,0,0,0}, + {8883,8884,8885 ,4472,4473,4474 ,0,0,0}, {8886,8887,8888 ,4475,4476,4477 ,0,0,0}, + {8887,8886,8885 ,4476,4475,4474 ,0,0,0}, {8889,8888,8890 ,4478,4477,4479 ,0,0,0}, + {8887,8890,8888 ,4476,4479,4477 ,0,0,0}, {8891,8892,8889 ,4480,4481,4478 ,0,0,0}, + {8889,8890,8891 ,4478,4479,4480 ,0,0,0}, {8892,8893,8894 ,4481,4482,1359 ,0,0,0}, + {8893,8892,8891 ,4482,4481,4480 ,0,0,0}, {8893,8895,8894 ,4482,1359,1359 ,0,0,0}, + {8896,8897,8898 ,4483,4484,4485 ,0,0,0}, {8896,8899,8900 ,4483,4486,4487 ,0,0,0}, + {8899,8901,8900 ,4486,4488,4487 ,0,0,0}, {8898,8899,8896 ,4485,4486,4483 ,0,0,0}, + {8902,8903,8904 ,4489,4490,4491 ,0,0,0}, {8901,8902,8904 ,4488,4489,4491 ,0,0,0}, + {8903,8905,8906 ,4490,4492,4493 ,0,0,0}, {8905,8903,8902 ,4492,4490,4489 ,0,0,0}, + {8906,8905,8907 ,4493,4492,4494 ,0,0,0}, {8908,8906,8907 ,4495,4493,4494 ,0,0,0}, + {8908,8909,8910 ,4495,4496,4497 ,0,0,0}, {8908,8907,8909 ,4495,4494,4496 ,0,0,0}, + {8904,8900,8901 ,4491,4487,4488 ,0,0,0}, {8911,8912,8913 ,4498,4499,82 ,0,0,0}, + {8911,8913,8910 ,4498,82,4497 ,0,0,0}, {8909,8911,8910 ,4496,4498,4497 ,0,0,0}, + {8898,8897,8914 ,4485,4484,4500 ,0,0,0}, {8915,8914,8916 ,4501,4500,4502 ,0,0,0}, + {8897,8916,8914 ,4484,4502,4500 ,0,0,0}, {8917,8918,8915 ,4503,4504,4501 ,0,0,0}, + {8915,8916,8917 ,4501,4502,4503 ,0,0,0}, {8918,8919,8920 ,4504,4505,4506 ,0,0,0}, + {8919,8918,8917 ,4505,4504,4503 ,0,0,0}, {8921,8920,8922 ,4507,4506,4508 ,0,0,0}, + {8919,8922,8920 ,4505,4508,4506 ,0,0,0}, {8923,8924,8921 ,4509,4510,4507 ,0,0,0}, + {8921,8922,8923 ,4507,4508,4509 ,0,0,0}, {8924,8925,8926 ,4510,4511,4512 ,0,0,0}, + {8925,8924,8923 ,4511,4510,4509 ,0,0,0}, {8925,8927,8926 ,4511,4513,4512 ,0,0,0}, + {8928,8929,8930 ,4514,4515,4516 ,0,0,0}, {8931,8932,8933 ,4517,4518,4519 ,0,0,0}, + {8932,8928,8930 ,4518,4514,4516 ,0,0,0}, {8934,8931,8933 ,4520,4517,4519 ,0,0,0}, + {8932,8931,8928 ,4518,4517,4514 ,0,0,0}, {8934,8933,8935 ,4520,4519,4521 ,0,0,0}, + {8935,8936,8937 ,4521,4522,4523 ,0,0,0}, {8938,8937,8936 ,4524,4523,4522 ,0,0,0}, + {8939,8940,8941 ,4525,4526,4527 ,0,0,0}, {8936,8942,8938 ,4522,4528,4524 ,0,0,0}, + {8941,8943,8944 ,4527,4529,4530 ,0,0,0}, {8943,8942,8944 ,4529,4528,4530 ,0,0,0}, + {8938,8942,8943 ,4524,4528,4529 ,0,0,0}, {8941,8944,8939 ,4527,4530,4525 ,0,0,0}, + {8940,8939,8945 ,4526,4525,4531 ,0,0,0}, {8940,8945,8946 ,4526,4531,4532 ,0,0,0}, + {8947,8946,8945 ,4533,4532,4531 ,0,0,0}, {8948,8949,8950 ,4534,4535,4536 ,0,0,0}, + {8950,8946,8947 ,4536,4532,4533 ,0,0,0}, {8948,8950,8947 ,4534,4536,4533 ,0,0,0}, + {8948,8951,8949 ,4534,4537,4535 ,0,0,0}, {8934,8935,8937 ,4520,4521,4523 ,0,0,0}, + {8930,8929,8952 ,4516,4515,4538 ,0,0,0}, {8953,8952,8954 ,4539,4538,4540 ,0,0,0}, + {8929,8954,8952 ,4515,4540,4538 ,0,0,0}, {8955,8956,8953 ,4541,4542,4539 ,0,0,0}, + {8953,8954,8955 ,4539,4540,4541 ,0,0,0}, {8956,8957,8958 ,4542,4543,4544 ,0,0,0}, + {8957,8956,8955 ,4543,4542,4541 ,0,0,0}, {8959,8958,8960 ,4545,4544,4546 ,0,0,0}, + {8957,8960,8958 ,4543,4546,4544 ,0,0,0}, {8961,8962,8959 ,4547,4548,4545 ,0,0,0}, + {8959,8960,8961 ,4545,4546,4547 ,0,0,0}, {8962,8963,8964 ,4548,4549,4550 ,0,0,0}, + {8963,8962,8961 ,4549,4548,4547 ,0,0,0}, {8965,8964,8966 ,4551,4550,4552 ,0,0,0}, + {8963,8966,8964 ,4549,4552,4550 ,0,0,0}, {8967,8968,8965 ,4553,4554,4551 ,0,0,0}, + {8965,8966,8967 ,4551,4552,4553 ,0,0,0}, {8968,8969,8970 ,4554,4555,4556 ,0,0,0}, + {8969,8968,8967 ,4555,4554,4553 ,0,0,0}, {8969,8971,8970 ,4555,126,4556 ,0,0,0}, + {8972,8973,8974 ,4557,4558,4559 ,0,0,0}, {8975,8976,8974 ,4560,4561,4559 ,0,0,0}, + {8972,8974,8976 ,4557,4559,4561 ,0,0,0}, {8977,8975,8978 ,4562,4560,4563 ,0,0,0}, + {8977,8976,8975 ,4562,4561,4560 ,0,0,0}, {8979,8978,8980 ,4564,4563,4565 ,0,0,0}, + {8975,8980,8978 ,4560,4565,4563 ,0,0,0}, {8981,8982,8979 ,4081,4566,4564 ,0,0,0}, + {8979,8980,8981 ,4564,4565,4081 ,0,0,0}, {8982,8983,8984 ,4566,4567,4568 ,0,0,0}, + {8983,8982,8981 ,4567,4566,4081 ,0,0,0}, {8985,8984,8986 ,4569,4568,4570 ,0,0,0}, + {8983,8986,8984 ,4567,4570,4568 ,0,0,0}, {8987,8988,8985 ,4571,4572,4569 ,0,0,0}, + {8985,8986,8987 ,4569,4570,4571 ,0,0,0}, {8989,8990,8988 ,4573,763,4572 ,0,0,0}, + {8989,8988,8987 ,4573,4572,4571 ,0,0,0}, {8990,8991,8988 ,763,763,4572 ,0,0,0}, + {8992,8973,8972 ,4574,4558,4557 ,0,0,0}, {8992,8993,8994 ,4574,4575,4576 ,0,0,0}, + {8994,8973,8992 ,4576,4558,4574 ,0,0,0}, {8995,8996,8993 ,4577,4578,4575 ,0,0,0}, + {8993,8996,8994 ,4575,4578,4576 ,0,0,0}, {8997,8998,8995 ,4579,4580,4577 ,0,0,0}, + {8995,8993,8997 ,4577,4575,4579 ,0,0,0}, {8998,8999,9000 ,4580,4065,4581 ,0,0,0}, + {8999,8998,8997 ,4065,4580,4579 ,0,0,0}, {9001,9000,9002 ,4582,4581,4583 ,0,0,0}, + {8999,9002,9000 ,4065,4583,4581 ,0,0,0}, {9003,9004,9001 ,4584,4585,4582 ,0,0,0}, + {9001,9002,9003 ,4582,4583,4584 ,0,0,0}, {9004,9005,9006 ,4585,4586,4587 ,0,0,0}, + {9005,9004,9003 ,4586,4585,4584 ,0,0,0}, {9006,9007,9008 ,4587,4588,54 ,0,0,0}, + {9005,9007,9006 ,4586,4588,4587 ,0,0,0}, {9006,9008,9009 ,4587,54,4589 ,0,0,0}, + {9010,9011,9012 ,4590,4591,4557 ,0,0,0}, {9013,9011,9014 ,4592,4591,4593 ,0,0,0}, + {9011,9013,9012 ,4591,4592,4557 ,0,0,0}, {9015,9016,9014 ,4594,4595,4593 ,0,0,0}, + {9013,9014,9016 ,4592,4593,4595 ,0,0,0}, {9015,9017,9018 ,4594,4596,4597 ,0,0,0}, + {9018,9016,9015 ,4597,4595,4594 ,0,0,0}, {9019,9017,9020 ,4598,4596,4599 ,0,0,0}, + {9017,9019,9018 ,4596,4598,4597 ,0,0,0}, {9021,9022,9020 ,4600,4601,4599 ,0,0,0}, + {9019,9020,9022 ,4598,4599,4601 ,0,0,0}, {9021,9023,9024 ,4600,4602,4603 ,0,0,0}, + {9024,9022,9021 ,4603,4601,4600 ,0,0,0}, {9025,9023,9026 ,4604,4602,4605 ,0,0,0}, + {9023,9025,9024 ,4602,4604,4603 ,0,0,0}, {9027,9028,9026 ,4606,4607,4605 ,0,0,0}, + {9025,9026,9028 ,4604,4605,4607 ,0,0,0}, {9027,9029,9030 ,4606,4608,4609 ,0,0,0}, + {9030,9028,9027 ,4609,4607,4606 ,0,0,0}, {9031,9029,9032 ,4610,4608,4611 ,0,0,0}, + {9029,9031,9030 ,4608,4610,4609 ,0,0,0}, {9033,9034,9032 ,4612,4613,4611 ,0,0,0}, + {9031,9032,9034 ,4610,4611,4613 ,0,0,0}, {9033,9035,9036 ,4612,4614,4615 ,0,0,0}, + {9036,9034,9033 ,4615,4613,4612 ,0,0,0}, {9037,9035,9038 ,4616,4614,4617 ,0,0,0}, + {9035,9037,9036 ,4614,4616,4615 ,0,0,0}, {9039,9040,9038 ,4618,4619,4617 ,0,0,0}, + {9037,9038,9040 ,4616,4617,4619 ,0,0,0}, {9039,9041,9042 ,4618,4620,4621 ,0,0,0}, + {9042,9040,9039 ,4621,4619,4618 ,0,0,0}, {9041,9043,9042 ,4620,4620,4621 ,0,0,0}, + {9044,9010,9012 ,4622,4590,4557 ,0,0,0}, {9045,9046,9044 ,4623,4624,4622 ,0,0,0}, + {9010,9044,9046 ,4590,4622,4624 ,0,0,0}, {9045,9047,9048 ,4623,4625,4626 ,0,0,0}, + {9048,9046,9045 ,4626,4624,4623 ,0,0,0}, {9049,9047,9050 ,4627,4625,4628 ,0,0,0}, + {9047,9049,9048 ,4625,4627,4626 ,0,0,0}, {9051,9052,9050 ,4629,4630,4628 ,0,0,0}, + {9049,9050,9052 ,4627,4628,4630 ,0,0,0}, {9051,9053,9054 ,4629,4631,4632 ,0,0,0}, + {9054,9052,9051 ,4632,4630,4629 ,0,0,0}, {9055,9053,9056 ,4633,4631,4634 ,0,0,0}, + {9053,9055,9054 ,4631,4633,4632 ,0,0,0}, {9057,9058,9056 ,4635,4636,4634 ,0,0,0}, + {9055,9056,9058 ,4633,4634,4636 ,0,0,0}, {9057,9059,9060 ,4635,4637,4638 ,0,0,0}, + {9060,9058,9057 ,4638,4636,4635 ,0,0,0}, {9061,9059,9062 ,4639,4637,4640 ,0,0,0}, + {9059,9061,9060 ,4637,4639,4638 ,0,0,0}, {9063,9064,9062 ,4641,4642,4640 ,0,0,0}, + {9061,9062,9064 ,4639,4640,4642 ,0,0,0}, {9063,9065,9066 ,4641,4643,4644 ,0,0,0}, + {9066,9064,9063 ,4644,4642,4641 ,0,0,0}, {9067,9065,9068 ,4645,4643,4646 ,0,0,0}, + {9065,9067,9066 ,4643,4645,4644 ,0,0,0}, {9069,9070,9068 ,4647,4648,4646 ,0,0,0}, + {9067,9068,9070 ,4645,4646,4648 ,0,0,0}, {9069,9071,9072 ,4647,4649,4650 ,0,0,0}, + {9072,9070,9069 ,4650,4648,4647 ,0,0,0}, {9073,9071,9074 ,4651,4649,82 ,0,0,0}, + {9071,9073,9072 ,4649,4651,4650 ,0,0,0}, {9073,9074,9075 ,4651,82,4652 ,0,0,0}, + {9076,9077,9078 ,4653,4654,4655 ,0,0,0}, {9079,9080,9081 ,4656,4657,4658 ,0,0,0}, + {9078,9081,9080 ,4655,4658,4657 ,0,0,0}, {9082,9083,9084 ,4659,4660,4661 ,0,0,0}, + {9085,9086,9079 ,4662,4663,4656 ,0,0,0}, {9082,9086,9085 ,4659,4663,4662 ,0,0,0}, + {9085,9083,9082 ,4662,4660,4659 ,0,0,0}, {9086,9080,9079 ,4663,4657,4656 ,0,0,0}, + {9087,9088,9089 ,4664,4665,4666 ,0,0,0}, {9088,9090,9089 ,4665,4667,4666 ,0,0,0}, + {9091,9092,9093 ,4668,4669,4670 ,0,0,0}, {9091,9093,9090 ,4668,4670,4667 ,0,0,0}, + {9088,9091,9090 ,4665,4668,4667 ,0,0,0}, {9083,9087,9084 ,4660,4664,4661 ,0,0,0}, + {9087,9089,9084 ,4664,4666,4661 ,0,0,0}, {9094,9095,9096 ,4671,4672,4673 ,0,0,0}, + {9097,9098,9099 ,4674,4675,4676 ,0,0,0}, {9096,9095,9097 ,4673,4672,4674 ,0,0,0}, + {9100,9101,9102 ,4677,4678,4679 ,0,0,0}, {9096,9097,9099 ,4673,4674,4676 ,0,0,0}, + {9102,9101,9098 ,4679,4678,4675 ,0,0,0}, {9101,9099,9098 ,4678,4676,4675 ,0,0,0}, + {9092,9095,9094 ,4669,4672,4671 ,0,0,0}, {9103,9100,9102 ,4677,4677,4679 ,0,0,0}, + {9093,9092,9094 ,4670,4669,4671 ,0,0,0}, {9077,9081,9078 ,4654,4658,4655 ,0,0,0}, + {9104,9077,9076 ,4680,4654,4653 ,0,0,0}, {9104,9105,9106 ,4680,4681,4682 ,0,0,0}, + {9105,9104,9076 ,4681,4680,4653 ,0,0,0}, {9107,9106,9108 ,4683,4682,4684 ,0,0,0}, + {9105,9108,9106 ,4681,4684,4682 ,0,0,0}, {9109,9110,9107 ,4685,4686,4683 ,0,0,0}, + {9107,9108,9109 ,4683,4684,4685 ,0,0,0}, {9110,9111,9112 ,4686,4687,4688 ,0,0,0}, + {9111,9110,9109 ,4687,4686,4685 ,0,0,0}, {9113,9112,9114 ,4689,4688,4690 ,0,0,0}, + {9111,9114,9112 ,4687,4690,4688 ,0,0,0}, {9115,9116,9113 ,4691,4692,4689 ,0,0,0}, + {9113,9114,9115 ,4689,4690,4691 ,0,0,0}, {9116,9117,9118 ,4692,4693,4694 ,0,0,0}, + {9117,9116,9115 ,4693,4692,4691 ,0,0,0}, {9119,9118,9120 ,4695,4694,4696 ,0,0,0}, + {9117,9120,9118 ,4693,4696,4694 ,0,0,0}, {9121,9122,9119 ,4697,4698,4695 ,0,0,0}, + {9119,9120,9121 ,4695,4696,4697 ,0,0,0}, {9122,9123,9124 ,4698,4699,4700 ,0,0,0}, + {9123,9122,9121 ,4699,4698,4697 ,0,0,0}, {9123,9125,9124 ,4699,4701,4700 ,0,0,0}, + {9126,9127,9128 ,4702,4703,4704 ,0,0,0}, {9129,9130,9131 ,4705,4706,4707 ,0,0,0}, + {9127,9131,9130 ,4703,4707,4706 ,0,0,0}, {9132,9133,9134 ,4708,4709,4710 ,0,0,0}, + {9135,9129,9136 ,4711,4705,4712 ,0,0,0}, {9132,9135,9136 ,4708,4711,4712 ,0,0,0}, + {9135,9132,9134 ,4711,4708,4710 ,0,0,0}, {9136,9129,9131 ,4712,4705,4707 ,0,0,0}, + {9137,9138,9139 ,4713,4714,4715 ,0,0,0}, {9139,9138,9140 ,4715,4714,4716 ,0,0,0}, + {9141,9142,9143 ,4717,4718,4719 ,0,0,0}, {9141,9140,9142 ,4717,4716,4718 ,0,0,0}, + {9139,9140,9141 ,4715,4716,4717 ,0,0,0}, {9134,9133,9137 ,4710,4709,4713 ,0,0,0}, + {9137,9133,9138 ,4713,4709,4714 ,0,0,0}, {9144,9145,9146 ,4720,4721,4722 ,0,0,0}, + {9147,9148,9149 ,4723,4724,4725 ,0,0,0}, {9145,9147,9146 ,4721,4723,4722 ,0,0,0}, + {9150,9151,9152 ,4726,4727,4728 ,0,0,0}, {9145,9148,9147 ,4721,4724,4723 ,0,0,0}, + {9151,9149,9152 ,4727,4725,4728 ,0,0,0}, {9152,9149,9148 ,4728,4725,4724 ,0,0,0}, + {9143,9144,9146 ,4719,4720,4722 ,0,0,0}, {9153,9151,9150 ,4726,4727,4726 ,0,0,0}, + {9142,9144,9143 ,4718,4720,4719 ,0,0,0}, {9128,9127,9130 ,4704,4703,4706 ,0,0,0}, + {9154,9126,9128 ,4729,4702,4704 ,0,0,0}, {9154,9155,9156 ,4729,4730,4731 ,0,0,0}, + {9156,9126,9154 ,4731,4702,4729 ,0,0,0}, {9157,9158,9155 ,4732,4733,4730 ,0,0,0}, + {9156,9155,9158 ,4731,4730,4733 ,0,0,0}, {9159,9157,9160 ,4734,4732,4735 ,0,0,0}, + {9157,9159,9158 ,4732,4734,4733 ,0,0,0}, {9160,9161,9162 ,4735,4736,4737 ,0,0,0}, + {9162,9159,9160 ,4737,4734,4735 ,0,0,0}, {9163,9164,9161 ,4738,4739,4736 ,0,0,0}, + {9162,9161,9164 ,4737,4736,4739 ,0,0,0}, {9165,9163,9166 ,4740,4738,4741 ,0,0,0}, + {9163,9165,9164 ,4738,4740,4739 ,0,0,0}, {9166,9167,9168 ,4741,4742,4743 ,0,0,0}, + {9168,9165,9166 ,4743,4740,4741 ,0,0,0}, {9169,9170,9167 ,4744,4745,4742 ,0,0,0}, + {9168,9167,9170 ,4743,4742,4745 ,0,0,0}, {9171,9169,9172 ,4746,4744,4747 ,0,0,0}, + {9169,9171,9170 ,4744,4746,4745 ,0,0,0}, {9172,9173,9174 ,4747,4748,4749 ,0,0,0}, + {9174,9171,9172 ,4749,4746,4747 ,0,0,0}, {9174,9173,9175 ,4749,4748,4750 ,0,0,0}, + {9176,9177,9178 ,4751,4752,4753 ,0,0,0}, {9179,9180,9181 ,4754,4755,4756 ,0,0,0}, + {9177,9181,9180 ,4752,4756,4755 ,0,0,0}, {9182,9183,9184 ,4757,4758,4759 ,0,0,0}, + {9185,9179,9186 ,4760,4754,4761 ,0,0,0}, {9185,9186,9182 ,4760,4761,4757 ,0,0,0}, + {9182,9184,9185 ,4757,4759,4760 ,0,0,0}, {9179,9181,9186 ,4754,4756,4761 ,0,0,0}, + {9187,9188,9189 ,4762,4763,4764 ,0,0,0}, {9190,9188,9187 ,4765,4763,4762 ,0,0,0}, + {9191,9192,9193 ,4766,4767,4768 ,0,0,0}, {9191,9193,9190 ,4766,4768,4765 ,0,0,0}, + {9190,9193,9188 ,4765,4768,4763 ,0,0,0}, {9183,9189,9184 ,4758,4764,4759 ,0,0,0}, + {9187,9189,9183 ,4762,4764,4758 ,0,0,0}, {9194,9195,9196 ,4769,4770,4771 ,0,0,0}, + {9197,9198,9199 ,4772,4773,4774 ,0,0,0}, {9196,9195,9199 ,4771,4770,4774 ,0,0,0}, + {9200,9201,9202 ,4775,4776,4777 ,0,0,0}, {9195,9197,9199 ,4770,4772,4774 ,0,0,0}, + {9200,9198,9201 ,4775,4773,4776 ,0,0,0}, {9198,9197,9201 ,4773,4772,4776 ,0,0,0}, + {9194,9196,9192 ,4769,4771,4767 ,0,0,0}, {9203,9200,9202 ,4777,4775,4777 ,0,0,0}, + {9191,9194,9192 ,4766,4769,4767 ,0,0,0}, {9177,9180,9178 ,4752,4755,4753 ,0,0,0}, + {9176,9178,9204 ,4751,4753,4778 ,0,0,0}, {9204,9205,9206 ,4778,4779,4780 ,0,0,0}, + {9206,9176,9204 ,4780,4751,4778 ,0,0,0}, {9207,9205,9208 ,4781,4779,4782 ,0,0,0}, + {9205,9207,9206 ,4779,4781,4780 ,0,0,0}, {9209,9210,9208 ,4783,4784,4782 ,0,0,0}, + {9207,9208,9210 ,4781,4782,4784 ,0,0,0}, {9209,9211,9212 ,4783,4785,4786 ,0,0,0}, + {9212,9210,9209 ,4786,4784,4783 ,0,0,0}, {9213,9211,9214 ,4787,4785,4788 ,0,0,0}, + {9211,9213,9212 ,4785,4787,4786 ,0,0,0}, {9215,9216,9214 ,4789,4790,4788 ,0,0,0}, + {9213,9214,9216 ,4787,4788,4790 ,0,0,0}, {9215,9217,9218 ,4789,4791,4792 ,0,0,0}, + {9218,9216,9215 ,4792,4790,4789 ,0,0,0}, {9219,9217,9220 ,4793,4791,4794 ,0,0,0}, + {9217,9219,9218 ,4791,4793,4792 ,0,0,0}, {9221,9222,9220 ,4795,4796,4794 ,0,0,0}, + {9219,9220,9222 ,4793,4794,4796 ,0,0,0}, {9221,9223,9224 ,4795,4797,4798 ,0,0,0}, + {9224,9222,9221 ,4798,4796,4795 ,0,0,0}, {9223,9225,9224 ,4797,4799,4798 ,0,0,0}, + {9223,9226,9225 ,4797,324,4799 ,0,0,0}, {9227,9228,9229 ,82,4800,4801 ,0,0,0}, + {9229,9230,9231 ,4801,4802,4803 ,0,0,0}, {9230,9232,9231 ,4802,4804,4803 ,0,0,0}, + {9229,9231,9227 ,4801,4803,82 ,0,0,0}, {9233,9234,9235 ,4805,4806,4807 ,0,0,0}, + {9235,9234,9232 ,4807,4806,4804 ,0,0,0}, {9233,9236,9237 ,4805,4808,4809 ,0,0,0}, + {9237,9234,9233 ,4809,4806,4805 ,0,0,0}, {9237,9236,9238 ,4809,4808,4810 ,0,0,0}, + {9238,9236,9239 ,4810,4808,4811 ,0,0,0}, {9239,9240,9241 ,4811,4812,4813 ,0,0,0}, + {9238,9239,9241 ,4810,4811,4813 ,0,0,0}, {9232,9230,9235 ,4804,4802,4807 ,0,0,0}, + {9242,9243,9244 ,4814,4815,4816 ,0,0,0}, {9242,9244,9240 ,4814,4816,4812 ,0,0,0}, + {9240,9244,9241 ,4812,4816,4813 ,0,0,0}, {9227,9245,9228 ,82,4817,4800 ,0,0,0}, + {9246,9245,9247 ,4818,4817,4819 ,0,0,0}, {9245,9246,9228 ,4817,4818,4800 ,0,0,0}, + {9248,9249,9247 ,4820,4821,4819 ,0,0,0}, {9246,9247,9249 ,4818,4819,4821 ,0,0,0}, + {9248,9250,9251 ,4820,4822,4823 ,0,0,0}, {9251,9249,9248 ,4823,4821,4820 ,0,0,0}, + {9252,9250,9253 ,4824,4822,4825 ,0,0,0}, {9250,9252,9251 ,4822,4824,4823 ,0,0,0}, + {9254,9255,9253 ,4826,4827,4825 ,0,0,0}, {9252,9253,9255 ,4824,4825,4827 ,0,0,0}, + {9254,9256,9257 ,4826,4828,4829 ,0,0,0}, {9257,9255,9254 ,4829,4827,4826 ,0,0,0}, + {9258,9256,9259 ,4830,4828,4831 ,0,0,0}, {9256,9258,9257 ,4828,4830,4829 ,0,0,0}, + {9254,9253,9260 ,4832,4833,4834 ,0,0,0}, {9260,9256,9254 ,4834,4835,4832 ,0,0,0}, + {9260,9259,9256 ,4834,4836,4835 ,0,0,0}, {9260,9250,9248 ,4834,4837,4838 ,0,0,0}, + {9253,9250,9260 ,4833,4837,4834 ,0,0,0}, {9260,9247,9245 ,4834,4839,4840 ,0,0,0}, + {9248,9247,9260 ,4838,4839,4834 ,0,0,0}, {9245,9227,9260 ,4840,4841,4834 ,0,0,0}, + {9232,9260,9231 ,4842,4834,4843 ,0,0,0}, {9260,9227,9231 ,4834,4841,4843 ,0,0,0}, + {9237,9260,9234 ,4844,4834,4845 ,0,0,0}, {9260,9232,9234 ,4834,4842,4845 ,0,0,0}, + {9241,9260,9238 ,4846,4834,4847 ,0,0,0}, {9260,9237,9238 ,4834,4844,4847 ,0,0,0}, + {9243,9260,9244 ,4848,4834,4849 ,0,0,0}, {9260,9241,9244 ,4834,4846,4849 ,0,0,0}, + {9261,9262,9263 ,82,4850,4851 ,0,0,0}, {9263,9264,9265 ,4851,4852,4853 ,0,0,0}, + {9264,9266,9265 ,4852,4854,4853 ,0,0,0}, {9263,9265,9261 ,4851,4853,82 ,0,0,0}, + {9267,9268,9269 ,4855,4856,4857 ,0,0,0}, {9269,9268,9266 ,4857,4856,4854 ,0,0,0}, + {9267,9270,9271 ,4855,4858,4859 ,0,0,0}, {9271,9268,9267 ,4859,4856,4855 ,0,0,0}, + {9271,9270,9272 ,4859,4858,4860 ,0,0,0}, {9272,9270,9273 ,4860,4858,4861 ,0,0,0}, + {9273,9274,9275 ,4861,4862,4863 ,0,0,0}, {9272,9273,9275 ,4860,4861,4863 ,0,0,0}, + {9266,9264,9269 ,4854,4852,4857 ,0,0,0}, {9276,9277,9278 ,4864,4865,4866 ,0,0,0}, + {9276,9278,9274 ,4864,4866,4862 ,0,0,0}, {9274,9278,9275 ,4862,4866,4863 ,0,0,0}, + {9261,9279,9262 ,82,4867,4850 ,0,0,0}, {9280,9279,9281 ,4868,4867,4869 ,0,0,0}, + {9279,9280,9262 ,4867,4868,4850 ,0,0,0}, {9282,9283,9281 ,4870,4871,4869 ,0,0,0}, + {9280,9281,9283 ,4868,4869,4871 ,0,0,0}, {9282,9284,9285 ,4870,4872,4873 ,0,0,0}, + {9285,9283,9282 ,4873,4871,4870 ,0,0,0}, {9286,9284,9287 ,4874,4872,4875 ,0,0,0}, + {9284,9286,9285 ,4872,4874,4873 ,0,0,0}, {9288,9289,9287 ,4876,4877,4875 ,0,0,0}, + {9286,9287,9289 ,4874,4875,4877 ,0,0,0}, {9288,9290,9291 ,4876,4878,4829 ,0,0,0}, + {9291,9289,9288 ,4829,4877,4876 ,0,0,0}, {9292,9290,9293 ,4879,4878,4831 ,0,0,0}, + {9290,9292,9291 ,4878,4879,4829 ,0,0,0}, {9288,9287,9294 ,4832,4833,4880 ,0,0,0}, + {9294,9290,9288 ,4880,4835,4832 ,0,0,0}, {9294,9293,9290 ,4880,4881,4835 ,0,0,0}, + {9294,9284,9282 ,4880,4837,4838 ,0,0,0}, {9287,9284,9294 ,4833,4837,4880 ,0,0,0}, + {9294,9281,9279 ,4880,4839,4840 ,0,0,0}, {9282,9281,9294 ,4838,4839,4880 ,0,0,0}, + {9279,9261,9294 ,4840,4882,4880 ,0,0,0}, {9266,9294,9265 ,4842,4880,4843 ,0,0,0}, + {9294,9261,9265 ,4880,4882,4843 ,0,0,0}, {9271,9294,9268 ,4844,4880,4845 ,0,0,0}, + {9294,9266,9268 ,4880,4842,4845 ,0,0,0}, {9275,9294,9272 ,4846,4880,4847 ,0,0,0}, + {9294,9271,9272 ,4880,4844,4847 ,0,0,0}, {9277,9294,9278 ,4883,4880,4849 ,0,0,0}, + {9294,9275,9278 ,4880,4846,4849 ,0,0,0}, {9295,9296,9297 ,4884,4885,4886 ,0,0,0}, + {9297,9298,9299 ,4886,4887,4888 ,0,0,0}, {9298,9300,9299 ,4887,4889,4888 ,0,0,0}, + {9297,9299,9295 ,4886,4888,4884 ,0,0,0}, {9301,9302,9303 ,4890,4891,4857 ,0,0,0}, + {9303,9302,9300 ,4857,4891,4889 ,0,0,0}, {9301,9304,9305 ,4890,4892,4893 ,0,0,0}, + {9305,9302,9301 ,4893,4891,4890 ,0,0,0}, {9305,9304,9306 ,4893,4892,4894 ,0,0,0}, + {9306,9304,9307 ,4894,4892,4895 ,0,0,0}, {9307,9308,9309 ,4895,4896,4897 ,0,0,0}, + {9306,9307,9309 ,4894,4895,4897 ,0,0,0}, {9300,9298,9303 ,4889,4887,4857 ,0,0,0}, + {9310,9311,9312 ,4898,4899,4900 ,0,0,0}, {9310,9312,9308 ,4898,4900,4896 ,0,0,0}, + {9308,9312,9309 ,4896,4900,4897 ,0,0,0}, {9295,9313,9296 ,4884,4901,4885 ,0,0,0}, + {9314,9313,9315 ,4868,4901,4902 ,0,0,0}, {9313,9314,9296 ,4901,4868,4885 ,0,0,0}, + {9316,9317,9315 ,4820,4903,4902 ,0,0,0}, {9314,9315,9317 ,4868,4902,4903 ,0,0,0}, + {9316,9318,9319 ,4820,4904,4905 ,0,0,0}, {9319,9317,9316 ,4905,4903,4820 ,0,0,0}, + {9320,9318,9321 ,4906,4904,4907 ,0,0,0}, {9318,9320,9319 ,4904,4906,4905 ,0,0,0}, + {9322,9323,9321 ,4826,4877,4907 ,0,0,0}, {9320,9321,9323 ,4906,4907,4877 ,0,0,0}, + {9322,9324,9325 ,4826,4828,4908 ,0,0,0}, {9325,9323,9322 ,4908,4877,4826 ,0,0,0}, + {9326,9324,9327 ,4909,4828,4910 ,0,0,0}, {9324,9326,9325 ,4828,4909,4908 ,0,0,0}, + {9322,9321,9328 ,4832,4833,4880 ,0,0,0}, {9328,9324,9322 ,4880,4835,4832 ,0,0,0}, + {9328,9327,9324 ,4880,4911,4835 ,0,0,0}, {9328,9318,9316 ,4880,4837,4838 ,0,0,0}, + {9321,9318,9328 ,4833,4837,4880 ,0,0,0}, {9328,9315,9313 ,4880,4839,4840 ,0,0,0}, + {9316,9315,9328 ,4838,4839,4880 ,0,0,0}, {9313,9295,9328 ,4840,4912,4880 ,0,0,0}, + {9300,9328,9299 ,4842,4880,4843 ,0,0,0}, {9328,9295,9299 ,4880,4912,4843 ,0,0,0}, + {9305,9328,9302 ,4844,4880,4845 ,0,0,0}, {9328,9300,9302 ,4880,4842,4845 ,0,0,0}, + {9309,9328,9306 ,4846,4880,4847 ,0,0,0}, {9328,9305,9306 ,4880,4844,4847 ,0,0,0}, + {9311,9328,9312 ,4913,4880,4849 ,0,0,0}, {9328,9309,9312 ,4880,4846,4849 ,0,0,0}, + {9329,9330,9331 ,4914,4915,4916 ,0,0,0}, {9331,9332,9333 ,4916,4917,4918 ,0,0,0}, + {9332,9334,9333 ,4917,4919,4918 ,0,0,0}, {9331,9333,9329 ,4916,4918,4914 ,0,0,0}, + {9335,9336,9337 ,4920,4921,4922 ,0,0,0}, {9337,9336,9334 ,4922,4921,4919 ,0,0,0}, + {9335,9338,9339 ,4920,4923,4924 ,0,0,0}, {9339,9336,9335 ,4924,4921,4920 ,0,0,0}, + {9339,9338,9340 ,4924,4923,4925 ,0,0,0}, {9340,9338,9341 ,4925,4923,4926 ,0,0,0}, + {9341,9342,9343 ,4926,4927,4928 ,0,0,0}, {9340,9341,9343 ,4925,4926,4928 ,0,0,0}, + {9334,9332,9337 ,4919,4917,4922 ,0,0,0}, {9344,9345,9346 ,4929,4815,4930 ,0,0,0}, + {9344,9346,9342 ,4929,4930,4927 ,0,0,0}, {9342,9346,9343 ,4927,4930,4928 ,0,0,0}, + {9329,9347,9330 ,4914,4931,4915 ,0,0,0}, {9348,9347,9349 ,4932,4931,4933 ,0,0,0}, + {9347,9348,9330 ,4931,4932,4915 ,0,0,0}, {9350,9351,9349 ,4934,4821,4933 ,0,0,0}, + {9348,9349,9351 ,4932,4933,4821 ,0,0,0}, {9350,9352,9353 ,4934,4935,4936 ,0,0,0}, + {9353,9351,9350 ,4936,4821,4934 ,0,0,0}, {9354,9352,9355 ,4937,4935,4938 ,0,0,0}, + {9352,9354,9353 ,4935,4937,4936 ,0,0,0}, {9356,9357,9355 ,4826,4877,4938 ,0,0,0}, + {9354,9355,9357 ,4937,4938,4877 ,0,0,0}, {9356,9358,9359 ,4826,4939,4940 ,0,0,0}, + {9359,9357,9356 ,4940,4877,4826 ,0,0,0}, {9360,9358,9361 ,4941,4939,4942 ,0,0,0}, + {9358,9360,9359 ,4939,4941,4940 ,0,0,0}, {9356,9355,9362 ,4832,4833,4943 ,0,0,0}, + {9362,9358,9356 ,4943,4835,4832 ,0,0,0}, {9362,9361,9358 ,4943,4944,4835 ,0,0,0}, + {9362,9352,9350 ,4943,4837,4838 ,0,0,0}, {9355,9352,9362 ,4833,4837,4943 ,0,0,0}, + {9362,9349,9347 ,4943,4839,4840 ,0,0,0}, {9350,9349,9362 ,4838,4839,4943 ,0,0,0}, + {9347,9329,9362 ,4840,4945,4943 ,0,0,0}, {9334,9362,9333 ,4842,4943,4843 ,0,0,0}, + {9362,9329,9333 ,4943,4945,4843 ,0,0,0}, {9339,9362,9336 ,4844,4943,4845 ,0,0,0}, + {9362,9334,9336 ,4943,4842,4845 ,0,0,0}, {9343,9362,9340 ,4846,4943,4847 ,0,0,0}, + {9362,9339,9340 ,4943,4844,4847 ,0,0,0}, {9345,9362,9346 ,4946,4943,4849 ,0,0,0}, + {9362,9343,9346 ,4943,4846,4849 ,0,0,0}, {9363,9364,9365 ,4947,4948,4949 ,0,0,0}, + {9366,9367,9368 ,4950,4951,4952 ,0,0,0}, {9365,9368,9367 ,4949,4952,4951 ,0,0,0}, + {9369,9370,9371 ,4953,4954,4955 ,0,0,0}, {9372,9373,9366 ,4956,4957,4950 ,0,0,0}, + {9369,9373,9372 ,4953,4957,4956 ,0,0,0}, {9372,9370,9369 ,4956,4954,4953 ,0,0,0}, + {9373,9367,9366 ,4957,4951,4950 ,0,0,0}, {9374,9375,9376 ,4958,4959,4960 ,0,0,0}, + {9375,9377,9376 ,4959,4961,4960 ,0,0,0}, {9378,9379,9380 ,4962,4963,4964 ,0,0,0}, + {9378,9380,9377 ,4962,4964,4961 ,0,0,0}, {9375,9378,9377 ,4959,4962,4961 ,0,0,0}, + {9370,9374,9371 ,4954,4958,4955 ,0,0,0}, {9374,9376,9371 ,4958,4960,4955 ,0,0,0}, + {9381,9382,9383 ,4965,4966,4967 ,0,0,0}, {9384,9385,9386 ,4968,4969,4970 ,0,0,0}, + {9383,9382,9384 ,4967,4966,4968 ,0,0,0}, {9387,9388,9389 ,4726,4971,4972 ,0,0,0}, + {9383,9384,9386 ,4967,4968,4970 ,0,0,0}, {9389,9388,9385 ,4972,4971,4969 ,0,0,0}, + {9388,9386,9385 ,4971,4970,4969 ,0,0,0}, {9379,9382,9381 ,4963,4966,4965 ,0,0,0}, + {9390,9387,9389 ,4726,4726,4972 ,0,0,0}, {9380,9379,9381 ,4964,4963,4965 ,0,0,0}, + {9364,9368,9365 ,4948,4952,4949 ,0,0,0}, {9391,9364,9363 ,4973,4948,4947 ,0,0,0}, + {9391,9392,9393 ,4973,4974,4975 ,0,0,0}, {9392,9391,9363 ,4974,4973,4947 ,0,0,0}, + {9394,9393,9395 ,4976,4975,4977 ,0,0,0}, {9392,9395,9393 ,4974,4977,4975 ,0,0,0}, + {9396,9397,9394 ,4978,4979,4976 ,0,0,0}, {9394,9395,9396 ,4976,4977,4978 ,0,0,0}, + {9397,9398,9399 ,4979,4980,4981 ,0,0,0}, {9398,9397,9396 ,4980,4979,4978 ,0,0,0}, + {9400,9399,9401 ,4982,4981,4983 ,0,0,0}, {9398,9401,9399 ,4980,4983,4981 ,0,0,0}, + {9402,9403,9400 ,4984,4985,4982 ,0,0,0}, {9400,9401,9402 ,4982,4983,4984 ,0,0,0}, + {9403,9404,9405 ,4985,4986,4987 ,0,0,0}, {9404,9403,9402 ,4986,4985,4984 ,0,0,0}, + {9406,9405,9407 ,4988,4987,4989 ,0,0,0}, {9404,9407,9405 ,4986,4989,4987 ,0,0,0}, + {9408,9409,9406 ,4990,4991,4988 ,0,0,0}, {9406,9407,9408 ,4988,4989,4990 ,0,0,0}, + {9409,9410,9411 ,4991,4992,4748 ,0,0,0}, {9410,9409,9408 ,4992,4991,4990 ,0,0,0}, + {9410,9412,9411 ,4992,4750,4748 ,0,0,0}, {9413,9414,9415 ,4993,4994,4995 ,0,0,0}, + {9416,9417,9418 ,4996,4997,4998 ,0,0,0}, {9414,9419,9420 ,4994,4999,5000 ,0,0,0}, + {9419,9414,9413 ,4999,4994,4993 ,0,0,0}, {9419,9421,9420 ,4999,5001,5000 ,0,0,0}, + {9415,9422,9413 ,4995,5002,4993 ,0,0,0}, {9416,9422,9423 ,4996,5002,5003 ,0,0,0}, + {9415,9423,9422 ,4995,5003,5002 ,0,0,0}, {9424,9425,9426 ,5004,5005,5006 ,0,0,0}, + {9416,9423,9417 ,4996,5003,4997 ,0,0,0}, {9427,9428,9429 ,5007,5008,5009 ,0,0,0}, + {9430,9431,9432 ,5010,5011,5012 ,0,0,0}, {9433,9434,9435 ,5013,5014,5015 ,0,0,0}, + {9436,9437,9438 ,5016,5017,5018 ,0,0,0}, {9439,9440,9441 ,5019,5020,5021 ,0,0,0}, + {9442,9443,9434 ,5022,5023,5014 ,0,0,0}, {9444,9445,9446 ,5024,5025,5026 ,0,0,0}, + {9445,9440,9447 ,5025,5020,5027 ,0,0,0}, {9448,9449,9450 ,5028,5029,5030 ,0,0,0}, + {9451,9452,9444 ,5031,5032,5024 ,0,0,0}, {9453,9454,9455 ,5033,5034,5035 ,0,0,0}, + {9456,9450,9457 ,5036,5030,5037 ,0,0,0}, {9458,9459,9460 ,5038,5039,5040 ,0,0,0}, + {9461,9459,9462 ,5041,5039,5042 ,0,0,0}, {9463,9464,9465 ,5043,5044,5045 ,0,0,0}, + {9460,9466,9463 ,5040,5046,5043 ,0,0,0}, {9467,9468,9469 ,5047,5048,5049 ,0,0,0}, + {9467,9470,9471 ,5047,5050,5051 ,0,0,0}, {9472,9473,9474 ,5052,5053,5054 ,0,0,0}, + {9475,9476,9474 ,5055,5056,5054 ,0,0,0}, {9477,9478,9479 ,5057,5058,5059 ,0,0,0}, + {9478,9472,9480 ,5058,5052,5060 ,0,0,0}, {9481,9482,9483 ,5061,5062,5063 ,0,0,0}, + {9477,9484,9481 ,5057,5064,5061 ,0,0,0}, {9485,9486,9487 ,5065,5066,5067 ,0,0,0}, + {9485,9488,9489 ,5065,5068,5069 ,0,0,0}, {9490,9491,9492 ,5070,5071,5072 ,0,0,0}, + {9490,9493,9486 ,5070,5073,5066 ,0,0,0}, {9494,9491,9495 ,5074,5071,5075 ,0,0,0}, + {9491,9494,9492 ,5071,5074,5072 ,0,0,0}, {9496,9497,9495 ,5076,5077,5075 ,0,0,0}, + {9494,9495,9497 ,5074,5075,5077 ,0,0,0}, {9498,9499,9497 ,5078,5079,5077 ,0,0,0}, + {9497,9496,9498 ,5077,5076,5078 ,0,0,0}, {9499,9500,9501 ,5079,5080,5081 ,0,0,0}, + {9500,9499,9498 ,5080,5079,5078 ,0,0,0}, {9502,9501,9503 ,5082,5081,5083 ,0,0,0}, + {9500,9503,9501 ,5080,5083,5081 ,0,0,0}, {9504,9505,9502 ,5084,5085,5082 ,0,0,0}, + {9502,9503,9504 ,5082,5083,5084 ,0,0,0}, {9505,9506,9507 ,5085,5086,5087 ,0,0,0}, + {9506,9505,9504 ,5086,5085,5084 ,0,0,0}, {9508,9507,9509 ,5088,5087,5089 ,0,0,0}, + {9506,9509,9507 ,5086,5089,5087 ,0,0,0}, {9510,9508,9511 ,5090,5088,5091 ,0,0,0}, + {9508,9509,9511 ,5088,5089,5091 ,0,0,0}, {9510,9512,9513 ,5090,5092,5093 ,0,0,0}, + {9513,9508,9510 ,5093,5088,5090 ,0,0,0}, {9514,9512,9515 ,5094,5092,5095 ,0,0,0}, + {9512,9514,9513 ,5092,5094,5093 ,0,0,0}, {9516,9517,9515 ,126,5096,5095 ,0,0,0}, + {9514,9515,9517 ,5094,5095,5096 ,0,0,0}, {9518,9517,9516 ,126,5096,126 ,0,0,0}, + {9487,9486,9493 ,5067,5066,5073 ,0,0,0}, {9490,9492,9493 ,5070,5072,5073 ,0,0,0}, + {9483,9488,9481 ,5063,5068,5061 ,0,0,0}, {9485,9487,9488 ,5065,5067,5068 ,0,0,0}, + {9483,9489,9488 ,5063,5069,5068 ,0,0,0}, {9479,9484,9477 ,5059,5064,5057 ,0,0,0}, + {9481,9484,9482 ,5061,5064,5062 ,0,0,0}, {9473,9472,9478 ,5053,5052,5058 ,0,0,0}, + {9478,9480,9479 ,5058,5060,5059 ,0,0,0}, {9475,9468,9476 ,5055,5048,5056 ,0,0,0}, + {9473,9475,9474 ,5053,5055,5054 ,0,0,0}, {9467,9469,9470 ,5047,5049,5050 ,0,0,0}, + {9468,9475,9469 ,5048,5055,5049 ,0,0,0}, {9464,9471,9465 ,5044,5051,5045 ,0,0,0}, + {9471,9470,9465 ,5051,5050,5045 ,0,0,0}, {9460,9463,9458 ,5040,5043,5038 ,0,0,0}, + {9466,9464,9463 ,5046,5044,5043 ,0,0,0}, {9453,9461,9454 ,5033,5041,5034 ,0,0,0}, + {9462,9459,9458 ,5042,5039,5038 ,0,0,0}, {9454,9461,9462 ,5034,5041,5042 ,0,0,0}, + {9455,9456,9457 ,5035,5036,5037 ,0,0,0}, {9454,9456,9455 ,5034,5036,5035 ,0,0,0}, + {9450,9452,9448 ,5030,5032,5028 ,0,0,0}, {9457,9450,9449 ,5037,5030,5029 ,0,0,0}, + {9519,9451,9444 ,5097,5031,5024 ,0,0,0}, {9451,9448,9452 ,5031,5028,5032 ,0,0,0}, + {9520,9445,9447 ,5098,5025,5027 ,0,0,0}, {9444,9446,9519 ,5024,5026,5097 ,0,0,0}, + {9445,9520,9446 ,5025,5098,5026 ,0,0,0}, {9441,9442,9439 ,5021,5022,5019 ,0,0,0}, + {9447,9440,9439 ,5027,5020,5019 ,0,0,0}, {9435,9438,9433 ,5015,5018,5013 ,0,0,0}, + {9442,9441,9443 ,5022,5021,5023 ,0,0,0}, {9434,9443,9435 ,5014,5023,5015 ,0,0,0}, + {9427,9436,9438 ,5007,5016,5018 ,0,0,0}, {9437,9433,9438 ,5017,5013,5018 ,0,0,0}, + {9428,9432,9429 ,5008,5012,5009 ,0,0,0}, {9427,9429,9436 ,5007,5009,5016 ,0,0,0}, + {9430,9424,9431 ,5010,5004,5011 ,0,0,0}, {9428,9430,9432 ,5008,5010,5012 ,0,0,0}, + {9426,9425,9418 ,5006,5005,4998 ,0,0,0}, {9431,9424,9426 ,5011,5004,5006 ,0,0,0}, + {9416,9418,9425 ,4996,4998,5005 ,0,0,0}, {9521,9522,9523 ,5099,5100,5101 ,0,0,0}, + {9524,9525,9526 ,5102,5103,5104 ,0,0,0}, {9527,9525,9524 ,5105,5103,5102 ,0,0,0}, + {9528,9524,9526 ,5106,5102,5104 ,0,0,0}, {9529,9530,9531 ,5107,5108,5109 ,0,0,0}, + {9532,9533,9528 ,5110,5108,5106 ,0,0,0}, {9530,9534,9531 ,5108,5111,5109 ,0,0,0}, + {9530,9533,9534 ,5108,5108,5111 ,0,0,0}, {9534,9535,9536 ,5111,5112,5113 ,0,0,0}, + {9535,9537,9536 ,5112,5114,5113 ,0,0,0}, {9536,9537,9538 ,5113,5114,5115 ,0,0,0}, + {9537,9539,9538 ,5114,5116,5115 ,0,0,0}, {9540,9541,9539 ,5117,5118,5116 ,0,0,0}, + {9540,9542,9543 ,5117,5119,5120 ,0,0,0}, {9544,9543,9542 ,5121,5120,5119 ,0,0,0}, + {9544,9542,9545 ,5121,5119,5122 ,0,0,0}, {9545,9546,9544 ,5122,5123,5121 ,0,0,0}, + {9541,9538,9539 ,5118,5115,5116 ,0,0,0}, {9543,9541,9540 ,5120,5118,5117 ,0,0,0}, + {9546,9547,9548 ,5123,5124,5125 ,0,0,0}, {9547,9546,9545 ,5124,5123,5122 ,0,0,0}, + {9125,9548,9547 ,5126,5125,5124 ,0,0,0}, {9527,9524,9549 ,5105,5102,5127 ,0,0,0}, + {9550,9551,9552 ,5128,5129,5130 ,0,0,0}, {9550,9549,9551 ,5128,5127,5129 ,0,0,0}, + {9551,9553,9552 ,5129,5131,5130 ,0,0,0}, {9553,9551,9554 ,5131,5129,5132 ,0,0,0}, + {9555,9556,9557 ,5133,5134,5135 ,0,0,0}, {9555,9554,9556 ,5133,5132,5134 ,0,0,0}, + {9558,9557,9556 ,5136,5135,5134 ,0,0,0}, {9557,9558,9559 ,5135,5136,5137 ,0,0,0}, + {9560,9561,9562 ,5138,5139,5140 ,0,0,0}, {9563,9564,9558 ,5141,5142,5136 ,0,0,0}, + {9565,9566,9563 ,5143,5144,5141 ,0,0,0}, {9566,9565,9567 ,5144,5143,5145 ,0,0,0}, + {9568,9569,9565 ,5146,5147,5143 ,0,0,0}, {9522,9521,9570 ,5100,5099,5148 ,0,0,0}, + {9571,9572,9568 ,5149,5150,5146 ,0,0,0}, {9573,9574,9575 ,5151,5152,5153 ,0,0,0}, + {9576,9577,9578 ,5154,5155,5156 ,0,0,0}, {9579,9580,9581 ,5157,5158,5159 ,0,0,0}, + {9582,9583,9584 ,5160,5161,5162 ,0,0,0}, {9585,9586,9587 ,5163,5164,5165 ,0,0,0}, + {9588,9589,9590 ,5166,5167,5168 ,0,0,0}, {9588,9591,9592 ,5166,5169,5170 ,0,0,0}, + {9593,9594,9595 ,5171,5172,5173 ,0,0,0}, {9596,9597,9598 ,5174,5175,5176 ,0,0,0}, + {9599,9600,9601 ,5177,5178,5179 ,0,0,0}, {9602,9594,9593 ,5180,5172,5171 ,0,0,0}, + {9603,9604,9605 ,5179,5181,5182 ,0,0,0}, {9603,9601,9600 ,5179,5179,5178 ,0,0,0}, + {9606,9607,9608 ,5183,5184,5185 ,0,0,0}, {9609,9606,9605 ,5186,5183,5182 ,0,0,0}, + {9610,9611,9612 ,5187,5188,5189 ,0,0,0}, {9613,9610,9608 ,5190,5187,5185 ,0,0,0}, + {9614,9615,9616 ,5191,5192,5193 ,0,0,0}, {9615,9614,9612 ,5192,5191,5189 ,0,0,0}, + {9617,9618,9616 ,5194,5195,5193 ,0,0,0}, {9614,9616,9618 ,5191,5193,5195 ,0,0,0}, + {9617,9619,9620 ,5194,5196,5197 ,0,0,0}, {9620,9618,9617 ,5197,5195,5194 ,0,0,0}, + {9613,9611,9610 ,5190,5188,5187 ,0,0,0}, {9611,9615,9612 ,5188,5192,5189 ,0,0,0}, + {9607,9613,9608 ,5184,5190,5185 ,0,0,0}, {9609,9607,9606 ,5186,5184,5183 ,0,0,0}, + {9604,9609,9605 ,5181,5186,5182 ,0,0,0}, {9604,9603,9600 ,5181,5179,5178 ,0,0,0}, + {9600,9621,9604 ,5178,5198,5181 ,0,0,0}, {9593,9621,9602 ,5171,5198,5180 ,0,0,0}, + {9621,9600,9602 ,5198,5178,5180 ,0,0,0}, {9622,9623,9624 ,5199,5200,5201 ,0,0,0}, + {9595,9594,9596 ,5173,5172,5174 ,0,0,0}, {9622,9625,9626 ,5199,5202,5203 ,0,0,0}, + {9626,9623,9622 ,5203,5200,5199 ,0,0,0}, {9627,9625,9628 ,5204,5202,5205 ,0,0,0}, + {9625,9627,9626 ,5202,5204,5203 ,0,0,0}, {9629,9223,9628 ,5206,5207,5205 ,0,0,0}, + {9627,9628,9223 ,5204,5205,5207 ,0,0,0}, {9226,9223,9629 ,5197,5207,5206 ,0,0,0}, + {9624,9623,9630 ,5201,5200,5208 ,0,0,0}, {9631,9632,9633 ,5209,5210,5211 ,0,0,0}, + {9624,9630,9633 ,5201,5208,5211 ,0,0,0}, {9631,9634,9632 ,5209,5212,5210 ,0,0,0}, + {9633,9630,9631 ,5211,5208,5209 ,0,0,0}, {9597,9589,9598 ,5175,5167,5176 ,0,0,0}, + {9634,9635,9632 ,5212,5213,5210 ,0,0,0}, {9601,9635,9599 ,5179,5213,5177 ,0,0,0}, + {9634,9599,9635 ,5212,5177,5213 ,0,0,0}, {9596,9598,9595 ,5174,5176,5173 ,0,0,0}, + {9587,9576,9585 ,5165,5154,5163 ,0,0,0}, {9588,9590,9591 ,5166,5168,5169 ,0,0,0}, + {9589,9597,9590 ,5167,5175,5168 ,0,0,0}, {9591,9584,9592 ,5169,5162,5170 ,0,0,0}, + {9586,9583,9582 ,5164,5161,5160 ,0,0,0}, {9583,9592,9584 ,5161,5170,5162 ,0,0,0}, + {9587,9586,9582 ,5165,5164,5160 ,0,0,0}, {9573,9580,9579 ,5151,5158,5157 ,0,0,0}, + {9576,9578,9585 ,5154,5156,5163 ,0,0,0}, {9577,9581,9578 ,5155,5159,5156 ,0,0,0}, + {9575,9580,9573 ,5153,5158,5151 ,0,0,0}, {9577,9579,9581 ,5155,5157,5159 ,0,0,0}, + {9523,9575,9574 ,5101,5153,5152 ,0,0,0}, {9574,9175,9571 ,5152,5214,5149 ,0,0,0}, + {9529,9636,9530 ,5107,5215,5108 ,0,0,0}, {9535,9534,9533 ,5112,5111,5108 ,0,0,0}, + {9532,9637,9533 ,5110,5216,5108 ,0,0,0}, {9535,9533,9637 ,5112,5108,5216 ,0,0,0}, + {9638,9636,9639 ,5217,5215,5218 ,0,0,0}, {9526,9532,9528 ,5104,5110,5106 ,0,0,0}, + {9640,9638,9641 ,5219,5217,5220 ,0,0,0}, {9640,9642,9638 ,5219,5221,5217 ,0,0,0}, + {9643,9642,9644 ,5222,5221,5223 ,0,0,0}, {9550,9527,9549 ,5128,5105,5127 ,0,0,0}, + {9645,9643,9646 ,5224,5222,5225 ,0,0,0}, {9645,9647,9643 ,5224,5226,5222 ,0,0,0}, + {9648,9647,9649 ,5227,5226,5228 ,0,0,0}, {9555,9553,9554 ,5133,5131,5132 ,0,0,0}, + {9650,9651,9648 ,5229,5230,5227 ,0,0,0}, {9652,9651,9650 ,5231,5230,5229 ,0,0,0}, + {9653,9651,9654 ,5232,5230,5233 ,0,0,0}, {9564,9559,9558 ,5142,5137,5136 ,0,0,0}, + {9562,9653,9560 ,5140,5232,5138 ,0,0,0}, {9566,9564,9563 ,5144,5142,5141 ,0,0,0}, + {9655,9562,9656 ,5234,5140,5235 ,0,0,0}, {9569,9567,9565 ,5147,5145,5143 ,0,0,0}, + {9521,9655,9570 ,5099,5234,5148 ,0,0,0}, {9572,9569,9568 ,5150,5147,5146 ,0,0,0}, + {9572,9571,9175 ,5150,5149,5214 ,0,0,0}, {9574,9571,9523 ,5152,5149,5101 ,0,0,0}, + {9523,9571,9521 ,5101,5149,5099 ,0,0,0}, {9656,9570,9655 ,5235,5148,5234 ,0,0,0}, + {9561,9656,9562 ,5139,5235,5140 ,0,0,0}, {9654,9560,9653 ,5233,5138,5232 ,0,0,0}, + {9652,9654,9651 ,5231,5233,5230 ,0,0,0}, {9649,9650,9648 ,5228,5229,5227 ,0,0,0}, + {9645,9649,9647 ,5224,5228,5226 ,0,0,0}, {9644,9646,9643 ,5223,5225,5222 ,0,0,0}, + {9640,9644,9642 ,5219,5223,5221 ,0,0,0}, {9639,9641,9638 ,5218,5220,5217 ,0,0,0}, + {9529,9639,9636 ,5107,5218,5215 ,0,0,0}, {9657,9658,9659 ,5236,5237,5238 ,0,0,0}, + {9660,9661,9659 ,5239,5240,5238 ,0,0,0}, {9657,9659,9661 ,5236,5238,5240 ,0,0,0}, + {9660,9662,9663 ,5239,5241,5242 ,0,0,0}, {9663,9661,9660 ,5242,5240,5239 ,0,0,0}, + {9664,9662,9665 ,5243,5241,5244 ,0,0,0}, {9662,9664,9663 ,5241,5243,5242 ,0,0,0}, + {9666,9667,9665 ,5245,5246,5244 ,0,0,0}, {9664,9665,9667 ,5243,5244,5246 ,0,0,0}, + {9666,9668,9669 ,5245,5247,5248 ,0,0,0}, {9669,9667,9666 ,5248,5246,5245 ,0,0,0}, + {9670,9668,9671 ,5249,5247,5250 ,0,0,0}, {9668,9670,9669 ,5247,5249,5248 ,0,0,0}, + {9672,9673,9671 ,5251,5252,5250 ,0,0,0}, {9670,9671,9673 ,5249,5250,5252 ,0,0,0}, + {9672,9674,9675 ,5251,5253,5254 ,0,0,0}, {9675,9673,9672 ,5254,5252,5251 ,0,0,0}, + {9676,9674,9677 ,5255,5253,5256 ,0,0,0}, {9674,9676,9675 ,5253,5255,5254 ,0,0,0}, + {9678,9679,9677 ,5257,5258,5256 ,0,0,0}, {9676,9677,9679 ,5255,5256,5258 ,0,0,0}, + {9678,9680,9681 ,5257,5259,5260 ,0,0,0}, {9681,9679,9678 ,5260,5258,5257 ,0,0,0}, + {9682,9680,9683 ,5261,5259,5262 ,0,0,0}, {9680,9682,9681 ,5259,5261,5260 ,0,0,0}, + {9684,9685,9683 ,5263,5264,5262 ,0,0,0}, {9682,9683,9685 ,5261,5262,5264 ,0,0,0}, + {9684,9686,9687 ,5263,5265,5266 ,0,0,0}, {9687,9685,9684 ,5266,5264,5263 ,0,0,0}, + {9688,9686,9689 ,5267,5265,5268 ,0,0,0}, {9686,9688,9687 ,5265,5267,5266 ,0,0,0}, + {9690,9691,9689 ,5269,5270,5268 ,0,0,0}, {9688,9689,9691 ,5267,5268,5270 ,0,0,0}, + {9690,9692,9693 ,5269,5271,5272 ,0,0,0}, {9693,9691,9690 ,5272,5270,5269 ,0,0,0}, + {9694,9692,9695 ,5273,5271,5274 ,0,0,0}, {9692,9694,9693 ,5271,5273,5272 ,0,0,0}, + {9696,9697,9695 ,5275,5276,5274 ,0,0,0}, {9694,9695,9697 ,5273,5274,5276 ,0,0,0}, + {9696,9698,9699 ,5275,5277,5278 ,0,0,0}, {9699,9697,9696 ,5278,5276,5275 ,0,0,0}, + {9700,9698,9701 ,5279,5277,5280 ,0,0,0}, {9698,9700,9699 ,5277,5279,5278 ,0,0,0}, + {9702,9703,9701 ,5281,5282,5280 ,0,0,0}, {9700,9701,9703 ,5279,5280,5282 ,0,0,0}, + {9704,9702,9705 ,5283,5281,5284 ,0,0,0}, {9704,9703,9702 ,5283,5282,5281 ,0,0,0}, + {9706,9705,9707 ,5285,5284,5286 ,0,0,0}, {9702,9707,9705 ,5281,5286,5284 ,0,0,0}, + {9708,9706,9709 ,5287,5285,5288 ,0,0,0}, {9706,9707,9709 ,5285,5286,5288 ,0,0,0}, + {9708,9710,9711 ,5287,5289,5290 ,0,0,0}, {9711,9706,9708 ,5290,5285,5287 ,0,0,0}, + {9710,9712,9711 ,5289,5291,5290 ,0,0,0}, {9713,9658,9657 ,5292,5237,5236 ,0,0,0}, + {9713,9714,9715 ,5292,5293,5294 ,0,0,0}, {9715,9658,9713 ,5294,5237,5292 ,0,0,0}, + {9716,9714,9717 ,5295,5293,5296 ,0,0,0}, {9714,9716,9715 ,5293,5295,5294 ,0,0,0}, + {9718,9719,9717 ,5297,5298,5296 ,0,0,0}, {9716,9717,9719 ,5295,5296,5298 ,0,0,0}, + {9718,9720,9721 ,5297,5299,5300 ,0,0,0}, {9721,9719,9718 ,5300,5298,5297 ,0,0,0}, + {9722,9720,9723 ,5301,5299,5302 ,0,0,0}, {9720,9722,9721 ,5299,5301,5300 ,0,0,0}, + {9724,9725,9723 ,5303,5304,5302 ,0,0,0}, {9722,9723,9725 ,5301,5302,5304 ,0,0,0}, + {9724,9726,9727 ,5303,5305,5306 ,0,0,0}, {9727,9725,9724 ,5306,5304,5303 ,0,0,0}, + {9728,9726,9729 ,5307,5305,5308 ,0,0,0}, {9726,9728,9727 ,5305,5307,5306 ,0,0,0}, + {9730,9731,9729 ,5309,5310,5308 ,0,0,0}, {9728,9729,9731 ,5307,5308,5310 ,0,0,0}, + {9730,9732,9733 ,5309,5311,5312 ,0,0,0}, {9733,9731,9730 ,5312,5310,5309 ,0,0,0}, + {9734,9732,9735 ,5313,5311,5314 ,0,0,0}, {9732,9734,9733 ,5311,5313,5312 ,0,0,0}, + {9736,9737,9735 ,5315,5316,5314 ,0,0,0}, {9734,9735,9737 ,5313,5314,5316 ,0,0,0}, + {9736,9738,9739 ,5315,5317,5318 ,0,0,0}, {9739,9737,9736 ,5318,5316,5315 ,0,0,0}, + {9740,9738,9741 ,5319,5317,5320 ,0,0,0}, {9738,9740,9739 ,5317,5319,5318 ,0,0,0}, + {9742,9743,9741 ,5321,5322,5320 ,0,0,0}, {9740,9741,9743 ,5319,5320,5322 ,0,0,0}, + {9742,9744,9745 ,5321,5323,5324 ,0,0,0}, {9745,9743,9742 ,5324,5322,5321 ,0,0,0}, + {9746,9744,9747 ,5325,5323,5326 ,0,0,0}, {9744,9746,9745 ,5323,5325,5324 ,0,0,0}, + {9748,9749,9747 ,5327,5328,5326 ,0,0,0}, {9746,9747,9749 ,5325,5326,5328 ,0,0,0}, + {9748,9750,9751 ,5327,5329,5330 ,0,0,0}, {9751,9749,9748 ,5330,5328,5327 ,0,0,0}, + {9752,9750,9753 ,5331,5329,5332 ,0,0,0}, {9750,9752,9751 ,5329,5331,5330 ,0,0,0}, + {9754,9755,9753 ,5333,5334,5332 ,0,0,0}, {9752,9753,9755 ,5331,5332,5334 ,0,0,0}, + {9754,9756,9757 ,5333,5335,5336 ,0,0,0}, {9757,9755,9754 ,5336,5334,5333 ,0,0,0}, + {9758,9759,9756 ,5337,5338,5335 ,0,0,0}, {9756,9759,9757 ,5335,5338,5336 ,0,0,0}, + {9760,9761,9758 ,5339,5340,5337 ,0,0,0}, {9758,9756,9760 ,5337,5335,5339 ,0,0,0}, + {9762,9763,9761 ,5341,5342,5340 ,0,0,0}, {9762,9761,9760 ,5341,5340,5339 ,0,0,0}, + {9764,9763,9765 ,5343,5342,5344 ,0,0,0}, {9763,9764,9761 ,5342,5343,5340 ,0,0,0}, + {9764,9765,9766 ,5343,5344,5345 ,0,0,0}, {9767,9768,9769 ,5346,5347,5348 ,0,0,0}, + {9770,9771,9769 ,5349,5350,5348 ,0,0,0}, {9767,9769,9771 ,5346,5348,5350 ,0,0,0}, + {9770,9772,9773 ,5349,5351,5352 ,0,0,0}, {9773,9771,9770 ,5352,5350,5349 ,0,0,0}, + {9774,9772,9775 ,5353,5351,5354 ,0,0,0}, {9772,9774,9773 ,5351,5353,5352 ,0,0,0}, + {9776,9777,9775 ,5355,5356,5354 ,0,0,0}, {9774,9775,9777 ,5353,5354,5356 ,0,0,0}, + {9776,9778,9779 ,5355,5357,5358 ,0,0,0}, {9779,9777,9776 ,5358,5356,5355 ,0,0,0}, + {9780,9778,9781 ,5359,5357,5360 ,0,0,0}, {9778,9780,9779 ,5357,5359,5358 ,0,0,0}, + {9782,9783,9781 ,5361,5362,5360 ,0,0,0}, {9780,9781,9783 ,5359,5360,5362 ,0,0,0}, + {9782,9784,9785 ,5361,5363,5364 ,0,0,0}, {9785,9783,9782 ,5364,5362,5361 ,0,0,0}, + {9786,9784,9787 ,5365,5363,5366 ,0,0,0}, {9784,9786,9785 ,5363,5365,5364 ,0,0,0}, + {9788,9789,9787 ,5367,5368,5366 ,0,0,0}, {9786,9787,9789 ,5365,5366,5368 ,0,0,0}, + {9788,9790,9791 ,5367,5369,5370 ,0,0,0}, {9791,9789,9788 ,5370,5368,5367 ,0,0,0}, + {9792,9790,9793 ,5371,5369,5372 ,0,0,0}, {9790,9792,9791 ,5369,5371,5370 ,0,0,0}, + {9794,9795,9793 ,5373,5374,5372 ,0,0,0}, {9792,9793,9795 ,5371,5372,5374 ,0,0,0}, + {9794,9796,9797 ,5373,5375,5376 ,0,0,0}, {9797,9795,9794 ,5376,5374,5373 ,0,0,0}, + {9798,9796,9799 ,5377,5375,5378 ,0,0,0}, {9796,9798,9797 ,5375,5377,5376 ,0,0,0}, + {9800,9801,9799 ,5379,5380,5378 ,0,0,0}, {9798,9799,9801 ,5377,5378,5380 ,0,0,0}, + {9800,9802,9803 ,5379,5381,5382 ,0,0,0}, {9803,9801,9800 ,5382,5380,5379 ,0,0,0}, + {9804,9802,9805 ,5383,5381,5384 ,0,0,0}, {9802,9804,9803 ,5381,5383,5382 ,0,0,0}, + {9806,9807,9805 ,5385,5386,5384 ,0,0,0}, {9804,9805,9807 ,5383,5384,5386 ,0,0,0}, + {9806,9808,9809 ,5385,5387,5388 ,0,0,0}, {9809,9807,9806 ,5388,5386,5385 ,0,0,0}, + {9810,9808,9811 ,5389,5387,5390 ,0,0,0}, {9808,9810,9809 ,5387,5389,5388 ,0,0,0}, + {9812,9813,9811 ,5391,5392,5390 ,0,0,0}, {9810,9811,9813 ,5389,5390,5392 ,0,0,0}, + {9812,9814,9815 ,5391,5393,5394 ,0,0,0}, {9815,9813,9812 ,5394,5392,5391 ,0,0,0}, + {9816,9814,9817 ,5395,5393,5396 ,0,0,0}, {9814,9816,9815 ,5393,5395,5394 ,0,0,0}, + {9818,9819,9817 ,5397,5398,5396 ,0,0,0}, {9816,9817,9819 ,5395,5396,5398 ,0,0,0}, + {9818,9820,9821 ,5397,5399,5400 ,0,0,0}, {9821,9819,9818 ,5400,5398,5397 ,0,0,0}, + {9822,9820,9823 ,5401,5399,5402 ,0,0,0}, {9820,9822,9821 ,5399,5401,5400 ,0,0,0}, + {9824,9825,9823 ,5403,5404,5402 ,0,0,0}, {9822,9823,9825 ,5401,5402,5404 ,0,0,0}, + {9824,9826,9827 ,5403,5405,5406 ,0,0,0}, {9827,9825,9824 ,5406,5404,5403 ,0,0,0}, + {9826,9828,9827 ,5405,5407,5406 ,0,0,0}, {9829,9768,9767 ,5408,5347,5346 ,0,0,0}, + {9829,9830,9831 ,5408,5409,5410 ,0,0,0}, {9831,9768,9829 ,5410,5347,5408 ,0,0,0}, + {9832,9830,9833 ,5411,5409,5412 ,0,0,0}, {9830,9832,9831 ,5409,5411,5410 ,0,0,0}, + {9834,9835,9833 ,5413,5414,5412 ,0,0,0}, {9832,9833,9835 ,5411,5412,5414 ,0,0,0}, + {9834,9836,9837 ,5413,5415,5416 ,0,0,0}, {9837,9835,9834 ,5416,5414,5413 ,0,0,0}, + {9838,9836,9839 ,5417,5415,5418 ,0,0,0}, {9836,9838,9837 ,5415,5417,5416 ,0,0,0}, + {9840,9841,9839 ,5419,5420,5418 ,0,0,0}, {9838,9839,9841 ,5417,5418,5420 ,0,0,0}, + {9840,9842,9843 ,5419,5421,5422 ,0,0,0}, {9843,9841,9840 ,5422,5420,5419 ,0,0,0}, + {9844,9842,9845 ,5423,5421,5424 ,0,0,0}, {9842,9844,9843 ,5421,5423,5422 ,0,0,0}, + {9846,9847,9845 ,5425,5426,5424 ,0,0,0}, {9844,9845,9847 ,5423,5424,5426 ,0,0,0}, + {9846,9848,9849 ,5425,5427,5428 ,0,0,0}, {9849,9847,9846 ,5428,5426,5425 ,0,0,0}, + {9850,9848,9851 ,5429,5427,5430 ,0,0,0}, {9848,9850,9849 ,5427,5429,5428 ,0,0,0}, + {9852,9853,9851 ,5431,5432,5430 ,0,0,0}, {9850,9851,9853 ,5429,5430,5432 ,0,0,0}, + {9852,9854,9855 ,5431,5433,5434 ,0,0,0}, {9855,9853,9852 ,5434,5432,5431 ,0,0,0}, + {9856,9854,9857 ,5435,5433,5436 ,0,0,0}, {9854,9856,9855 ,5433,5435,5434 ,0,0,0}, + {9858,9859,9857 ,5437,5438,5436 ,0,0,0}, {9856,9857,9859 ,5435,5436,5438 ,0,0,0}, + {9858,9860,9861 ,5437,5439,5440 ,0,0,0}, {9861,9859,9858 ,5440,5438,5437 ,0,0,0}, + {9862,9860,9863 ,5441,5439,5442 ,0,0,0}, {9860,9862,9861 ,5439,5441,5440 ,0,0,0}, + {9864,9865,9863 ,5443,5444,5442 ,0,0,0}, {9862,9863,9865 ,5441,5442,5444 ,0,0,0}, + {9864,9866,9867 ,5443,5445,5446 ,0,0,0}, {9867,9865,9864 ,5446,5444,5443 ,0,0,0}, + {9868,9866,9869 ,5447,5445,5448 ,0,0,0}, {9866,9868,9867 ,5445,5447,5446 ,0,0,0}, + {9870,9871,9869 ,5449,5450,5448 ,0,0,0}, {9868,9869,9871 ,5447,5448,5450 ,0,0,0}, + {9870,9872,9873 ,5449,5451,5452 ,0,0,0}, {9873,9871,9870 ,5452,5450,5449 ,0,0,0}, + {9874,9872,9875 ,5453,5451,5454 ,0,0,0}, {9872,9874,9873 ,5451,5453,5452 ,0,0,0}, + {9876,9877,9875 ,5455,5456,5454 ,0,0,0}, {9874,9875,9877 ,5453,5454,5456 ,0,0,0}, + {9876,9878,9879 ,5455,5457,5458 ,0,0,0}, {9879,9877,9876 ,5458,5456,5455 ,0,0,0}, + {9880,9878,9881 ,5459,5457,5460 ,0,0,0}, {9878,9880,9879 ,5457,5459,5458 ,0,0,0}, + {9882,9883,9881 ,5461,5462,5460 ,0,0,0}, {9880,9881,9883 ,5459,5460,5462 ,0,0,0}, + {9882,9884,9885 ,5461,5463,5464 ,0,0,0}, {9885,9883,9882 ,5464,5462,5461 ,0,0,0}, + {9886,9884,9887 ,5465,5463,5466 ,0,0,0}, {9884,9886,9885 ,5463,5465,5464 ,0,0,0}, + {9886,9887,9888 ,5465,5466,5467 ,0,0,0}, {9889,8923,8922 ,5468,5469,5469 ,0,0,0}, + {9890,9891,9892 ,726,726,726 ,0,0,0}, {9893,8656,8653 ,726,5470,726 ,0,0,0}, + {9894,9895,9896 ,5471,726,726 ,0,0,0}, {9897,9898,9899 ,726,726,726 ,0,0,0}, + {9900,8878,9901 ,5468,5471,5469 ,0,0,0}, {9902,9903,9904 ,5470,726,726 ,0,0,0}, + {9905,9906,9907 ,5471,5469,5469 ,0,0,0}, {9908,9907,8851 ,5468,5469,5469 ,0,0,0}, + {9909,9910,8957 ,5469,5472,5468 ,0,0,0}, {9911,9912,9913 ,5469,5468,5471 ,0,0,0}, + {9914,9915,9916 ,5473,5474,726 ,0,0,0}, {9917,9918,9919 ,5475,5476,5471 ,0,0,0}, + {9920,9921,9922 ,5477,5478,5469 ,0,0,0}, {9915,9914,9923 ,5474,5473,5479 ,0,0,0}, + {9924,9925,9926 ,5471,5469,726 ,0,0,0}, {9927,9928,8916 ,5468,5469,5471 ,0,0,0}, + {9929,9930,9931 ,726,5480,5481 ,0,0,0}, {9922,9932,9933 ,5469,726,5468 ,0,0,0}, + {9934,9935,9936 ,5475,5475,5482 ,0,0,0}, {9937,8591,9934 ,5468,5483,5475 ,0,0,0}, + {9936,9938,9939 ,5482,5482,5482 ,0,0,0}, {9935,9938,9936 ,5475,5482,5482 ,0,0,0}, + {9939,9940,9936 ,5482,5475,5482 ,0,0,0}, {9931,9925,9941 ,5481,5469,5475 ,0,0,0}, + {9942,8971,9943 ,726,5471,5484 ,0,0,0}, {9915,9923,9933 ,5474,5479,5468 ,0,0,0}, + {9944,9945,9946 ,5475,5485,5468 ,0,0,0}, {9947,9948,9949 ,5486,5483,5468 ,0,0,0}, + {9932,9915,9933 ,726,5474,5468 ,0,0,0}, {8916,9928,8917 ,5471,5469,726 ,0,0,0}, + {8923,9889,8925 ,5469,5468,726 ,0,0,0}, {8929,8928,9950 ,5471,5471,726 ,0,0,0}, + {8957,8927,9909 ,5468,5468,5469 ,0,0,0}, {8955,8927,8957 ,5471,5468,5468 ,0,0,0}, + {8929,9951,8954 ,5471,5471,5469 ,0,0,0}, {9952,8961,8960 ,5468,5478,726 ,0,0,0}, + {8928,9953,9950 ,5471,726,726 ,0,0,0}, {8884,9954,9955 ,5471,5468,726 ,0,0,0}, + {9956,8971,8969 ,5475,5471,726 ,0,0,0}, {9957,9958,9959 ,5469,5482,5483 ,0,0,0}, + {9960,9958,9961 ,5468,5482,5475 ,0,0,0}, {9962,9963,9964 ,726,5468,5468 ,0,0,0}, + {9965,9913,9966 ,726,5471,5469 ,0,0,0}, {9967,9968,9969 ,5475,5475,726 ,0,0,0}, + {9963,9962,9970 ,5468,726,5483 ,0,0,0}, {9971,9972,9973 ,5480,5487,5475 ,0,0,0}, + {9970,9974,9957 ,5483,5478,5469 ,0,0,0}, {9975,9976,9977 ,5475,5479,5474 ,0,0,0}, + {9977,9943,9975 ,5474,5484,5475 ,0,0,0}, {9978,9979,9977 ,5473,726,5474 ,0,0,0}, + {9978,9977,9976 ,5473,5474,5479 ,0,0,0}, {9960,9959,9958 ,5468,5483,5482 ,0,0,0}, + {9972,9967,9980 ,5487,5475,726 ,0,0,0}, {9958,9957,9974 ,5482,5469,5478 ,0,0,0}, + {9981,9982,9942 ,5486,5478,726 ,0,0,0}, {9965,9966,9964 ,726,5469,5468 ,0,0,0}, + {8881,9954,8884 ,726,5468,5471 ,0,0,0}, {9975,9943,8971 ,5475,5484,5471 ,0,0,0}, + {9983,9984,9985 ,726,726,726 ,0,0,0}, {9986,9987,8887 ,5468,5469,726 ,0,0,0}, + {9956,8969,9988 ,5475,726,5482 ,0,0,0}, {9989,8893,9990 ,726,726,5470 ,0,0,0}, + {8966,9991,9992 ,5475,5485,5475 ,0,0,0}, {9993,9994,8811 ,5471,726,5471 ,0,0,0}, + {8715,9995,8710 ,726,5470,726 ,0,0,0}, {9996,9997,9998 ,5470,5471,5471 ,0,0,0}, + {9999,10000,10001 ,726,726,5470 ,0,0,0}, {10001,9902,9999 ,5470,5470,726 ,0,0,0}, + {9983,9904,9984 ,726,726,726 ,0,0,0}, {10002,10003,10004 ,726,726,5470 ,0,0,0}, + {9896,9996,9998 ,726,5470,5471 ,0,0,0}, {10000,10005,10006 ,726,726,726 ,0,0,0}, + {8895,10007,10008 ,726,5470,726 ,0,0,0}, {10009,10010,10011 ,5470,726,726 ,0,0,0}, + {9984,9904,9903 ,726,726,726 ,0,0,0}, {10007,10012,10013 ,5470,726,5468 ,0,0,0}, + {9984,10014,9985 ,726,726,726 ,0,0,0}, {10013,10015,10016 ,5468,5468,726 ,0,0,0}, + {10012,10015,10013 ,726,5468,5468 ,0,0,0}, {10016,10017,10013 ,726,5471,5468 ,0,0,0}, + {10018,10019,10020 ,726,726,5471 ,0,0,0}, {8895,10012,10007 ,726,726,5470 ,0,0,0}, + {10008,10021,10022 ,726,726,726 ,0,0,0}, {10023,10024,10025 ,726,5488,5489 ,0,0,0}, + {8853,10026,10027 ,5471,5470,726 ,0,0,0}, {8881,9907,9954 ,726,5469,5468 ,0,0,0}, + {10028,8808,8805 ,726,726,5471 ,0,0,0}, {10029,8732,8729 ,726,726,726 ,0,0,0}, + {10030,8665,10031 ,726,5470,726 ,0,0,0}, {10032,8808,10028 ,726,726,726 ,0,0,0}, + {10033,10034,10035 ,726,726,726 ,0,0,0}, {10036,10037,10038 ,5489,726,726 ,0,0,0}, + {8802,10039,8803 ,726,5471,726 ,0,0,0}, {10040,10034,10041 ,726,726,726 ,0,0,0}, + {10042,10043,10044 ,726,726,5489 ,0,0,0}, {10045,10046,10047 ,726,726,726 ,0,0,0}, + {10048,10034,10040 ,726,726,726 ,0,0,0}, {9890,9892,10047 ,726,726,726 ,0,0,0}, + {10049,10050,10051 ,726,726,5489 ,0,0,0}, {9891,10033,10035 ,726,726,726 ,0,0,0}, + {10052,10053,10054 ,726,726,726 ,0,0,0}, {10050,10055,10052 ,726,5488,726 ,0,0,0}, + {10048,10035,10034 ,726,726,726 ,0,0,0}, {9899,10036,8819 ,726,5489,726 ,0,0,0}, + {10056,10057,10058 ,5489,726,726 ,0,0,0}, {10056,10059,10057 ,5489,5488,726 ,0,0,0}, + {10060,10061,10062 ,726,5471,726 ,0,0,0}, {10057,10059,10063 ,726,5488,726 ,0,0,0}, + {10064,10057,10063 ,726,726,726 ,0,0,0}, {10065,8777,10066 ,726,726,726 ,0,0,0}, + {8735,10067,10068 ,726,726,726 ,0,0,0}, {8893,8891,9990 ,726,726,5470 ,0,0,0}, + {9899,8815,10069 ,726,726,726 ,0,0,0}, {10061,10070,10071 ,5471,5471,726 ,0,0,0}, + {10072,8633,10073 ,726,5470,726 ,0,0,0}, {10062,10074,10060 ,726,5471,726 ,0,0,0}, + {8743,10075,10076 ,5489,726,726 ,0,0,0}, {10077,10078,10079 ,726,726,726 ,0,0,0}, + {10080,10081,10079 ,726,5471,726 ,0,0,0}, {10044,10043,10082 ,5489,726,5488 ,0,0,0}, + {10029,10083,8732 ,726,726,726 ,0,0,0}, {10037,9899,10058 ,726,726,726 ,0,0,0}, + {10084,10029,10082 ,726,726,5488 ,0,0,0}, {8659,10085,10086 ,726,5471,726 ,0,0,0}, + {10087,10088,10078 ,726,5488,726 ,0,0,0}, {10079,10089,10090 ,726,5471,726 ,0,0,0}, + {10091,10092,10093 ,726,726,5488 ,0,0,0}, {10094,10095,10091 ,726,726,726 ,0,0,0}, + {10096,10095,10097 ,726,726,726 ,0,0,0}, {10098,8743,10076 ,726,5489,726 ,0,0,0}, + {10099,10079,10100 ,726,726,726 ,0,0,0}, {10076,10075,10101 ,726,726,726 ,0,0,0}, + {10078,10102,10087 ,726,726,726 ,0,0,0}, {10103,10101,10075 ,726,726,726 ,0,0,0}, + {10078,10088,10079 ,726,5488,726 ,0,0,0}, {10103,10104,10101 ,726,5488,726 ,0,0,0}, + {10105,10102,10078 ,726,726,726 ,0,0,0}, {10101,10104,10106 ,726,5488,726 ,0,0,0}, + {10079,10107,10089 ,726,726,5471 ,0,0,0}, {8938,10108,8937 ,5469,5468,5468 ,0,0,0}, + {8938,8943,10109 ,5469,726,726 ,0,0,0}, {10110,8650,10111 ,726,5471,5471 ,0,0,0}, + {10112,8557,10113 ,5470,5468,5468 ,0,0,0}, {8667,10114,10115 ,5470,726,726 ,0,0,0}, + {10116,10117,10118 ,5468,726,5469 ,0,0,0}, {10119,10120,10121 ,5471,5468,726 ,0,0,0}, + {10122,10116,10123 ,5468,5468,726 ,0,0,0}, {10124,10125,10126 ,726,5470,5469 ,0,0,0}, + {10127,10128,10129 ,726,5469,726 ,0,0,0}, {10130,10131,10132 ,5471,5469,726 ,0,0,0}, + {10133,8954,10134 ,726,5469,5470 ,0,0,0}, {10098,10135,10136 ,726,5489,726 ,0,0,0}, + {10079,10081,10137 ,726,5471,726 ,0,0,0}, {10138,8841,8840 ,5468,726,5469 ,0,0,0}, + {10139,10140,10029 ,5470,5471,726 ,0,0,0}, {9893,10141,8656 ,726,726,5470 ,0,0,0}, + {10142,8701,8700 ,5471,726,726 ,0,0,0}, {10143,8943,8941 ,726,726,5468 ,0,0,0}, + {10144,10145,10146 ,726,5470,5471 ,0,0,0}, {10147,10148,10149 ,5471,726,5470 ,0,0,0}, + {10150,10151,10152 ,726,5470,726 ,0,0,0}, {10114,10153,10115 ,726,726,726 ,0,0,0}, + {10153,10114,10154 ,726,726,726 ,0,0,0}, {10115,10145,8667 ,726,5470,5470 ,0,0,0}, + {10153,10154,10155 ,726,726,726 ,0,0,0}, {10127,10121,10120 ,726,726,5468 ,0,0,0}, + {10153,10155,10156 ,726,726,726 ,0,0,0}, {10157,10158,10159 ,5471,5471,5468 ,0,0,0}, + {10125,10132,10126 ,5470,726,5469 ,0,0,0}, {10160,10124,10161 ,726,726,726 ,0,0,0}, + {10162,10163,10131 ,5468,5469,5469 ,0,0,0}, {10131,10130,10162 ,5469,5471,5468 ,0,0,0}, + {10164,10165,10162 ,5471,726,5468 ,0,0,0}, {10162,10165,10163 ,5468,726,5469 ,0,0,0}, + {8961,10166,8963 ,5478,5487,5468 ,0,0,0}, {8895,8893,9989 ,726,726,726 ,0,0,0}, + {9988,8969,8967 ,5482,726,5468 ,0,0,0}, {9987,8890,8887 ,5469,726,726 ,0,0,0}, + {9908,9905,9907 ,5468,5471,5469 ,0,0,0}, {10167,9906,9905 ,5468,5469,5471 ,0,0,0}, + {9912,9911,10168 ,5468,5469,5469 ,0,0,0}, {9906,10167,10169 ,5469,5468,5470 ,0,0,0}, + {9911,9913,9965 ,5469,5471,726 ,0,0,0}, {10168,10169,10170 ,5469,5470,5469 ,0,0,0}, + {9964,9966,9962 ,5468,5469,726 ,0,0,0}, {9970,9957,9963 ,5483,5469,5468 ,0,0,0}, + {9968,9974,9969 ,5475,5478,726 ,0,0,0}, {9974,9970,9969 ,5478,5483,726 ,0,0,0}, + {9981,9971,9982 ,5486,5480,5478 ,0,0,0}, {9972,9968,9967 ,5487,5475,5475 ,0,0,0}, + {9971,9973,9982 ,5480,5475,5478 ,0,0,0}, {9973,9972,9980 ,5475,5487,726 ,0,0,0}, + {9943,9981,9942 ,5484,5486,726 ,0,0,0}, {9956,9975,8971 ,5475,5475,5471 ,0,0,0}, + {9988,8967,9992 ,5482,5468,5475 ,0,0,0}, {9992,8967,8966 ,5475,5468,5475 ,0,0,0}, + {8963,10166,9991 ,5468,5487,5485 ,0,0,0}, {9991,8966,8963 ,5485,5475,5468 ,0,0,0}, + {9952,10166,8961 ,5468,5487,5478 ,0,0,0}, {9910,9952,8960 ,5472,5468,726 ,0,0,0}, + {10134,8954,9951 ,5470,5469,5471 ,0,0,0}, {8957,9910,8960 ,5468,5472,726 ,0,0,0}, + {10171,10172,8937 ,5471,5470,5468 ,0,0,0}, {8934,10172,10173 ,726,5470,726 ,0,0,0}, + {9919,10174,9917 ,5471,5468,5475 ,0,0,0}, {9928,10175,8917 ,5469,5469,726 ,0,0,0}, + {10176,10177,9937 ,5472,5482,5468 ,0,0,0}, {8900,8569,8896 ,5468,5468,5468 ,0,0,0}, + {8577,8575,10116 ,5471,726,5468 ,0,0,0}, {8832,8479,8830 ,5471,726,5469 ,0,0,0}, + {8843,10178,8846 ,5471,726,726 ,0,0,0}, {10028,8805,9894 ,726,5471,5471 ,0,0,0}, + {8499,10179,10180 ,726,726,5470 ,0,0,0}, {10181,10182,8741 ,726,726,726 ,0,0,0}, + {10183,8861,10184 ,726,726,5471 ,0,0,0}, {8476,10185,8473 ,5471,5471,5471 ,0,0,0}, + {8488,10186,10187 ,726,5469,5469 ,0,0,0}, {8827,8940,8946 ,5471,5469,5469 ,0,0,0}, + {8934,8937,10172 ,726,5468,5470 ,0,0,0}, {8950,8828,8946 ,5468,726,5469 ,0,0,0}, + {8940,8484,8941 ,5469,5471,5468 ,0,0,0}, {10143,10109,8943 ,726,726,726 ,0,0,0}, + {10109,10108,8938 ,726,5468,5469 ,0,0,0}, {10108,10171,8937 ,5468,5471,5468 ,0,0,0}, + {8931,8934,10173 ,726,726,726 ,0,0,0}, {8927,8955,10133 ,5468,5471,726 ,0,0,0}, + {8931,9953,8928 ,726,726,5471 ,0,0,0}, {9953,8931,10173 ,726,726,726 ,0,0,0}, + {9950,9951,8929 ,726,5471,5471 ,0,0,0}, {8954,10133,8955 ,5469,726,5471 ,0,0,0}, + {8925,10188,8927 ,726,5468,5468 ,0,0,0}, {9918,9909,10189 ,5476,5469,5468 ,0,0,0}, + {10188,9909,8927 ,5468,5469,5468 ,0,0,0}, {8917,10175,8919 ,726,5469,5470 ,0,0,0}, + {8922,8919,10190 ,5469,5470,726 ,0,0,0}, {10175,10190,8919 ,5469,726,5470 ,0,0,0}, + {9921,9920,9945 ,5478,5477,5485 ,0,0,0}, {8897,8569,9927 ,726,5468,5468 ,0,0,0}, + {8897,9927,8916 ,726,5468,5471 ,0,0,0}, {10191,10192,8589 ,5470,5470,5468 ,0,0,0}, + {8591,9935,9934 ,5483,5475,5475 ,0,0,0}, {10193,8575,8574 ,5468,726,5468 ,0,0,0}, + {10194,8549,10195 ,5469,5468,5471 ,0,0,0}, {8663,10031,8665 ,726,726,5470 ,0,0,0}, + {10196,10197,8625 ,5471,5471,5471 ,0,0,0}, {10198,8713,10199 ,726,726,5471 ,0,0,0}, + {10200,10201,10202 ,5471,5470,5471 ,0,0,0}, {8709,8710,10203 ,726,726,726 ,0,0,0}, + {8653,10070,9893 ,726,5471,726 ,0,0,0}, {10083,10029,10204 ,726,726,726 ,0,0,0}, + {8949,10205,8821 ,726,5468,5469 ,0,0,0}, {8846,10206,8847 ,726,726,5468 ,0,0,0}, + {8815,9899,8817 ,726,726,726 ,0,0,0}, {9994,8814,8811 ,726,5471,5471 ,0,0,0}, + {8775,9895,9894 ,726,726,5471 ,0,0,0}, {9896,9895,9996 ,726,726,5470 ,0,0,0}, + {10005,10018,10006 ,726,726,726 ,0,0,0}, {10020,10207,9997 ,5471,726,5471 ,0,0,0}, + {9998,9997,10207 ,5471,5471,726 ,0,0,0}, {10019,10018,10005 ,726,726,726 ,0,0,0}, + {10019,10207,10020 ,726,726,5471 ,0,0,0}, {10006,10001,10000 ,726,5470,726 ,0,0,0}, + {9902,9904,9999 ,5470,726,726 ,0,0,0}, {10003,9903,10004 ,726,726,5470 ,0,0,0}, + {9903,9902,10004 ,726,5470,5470 ,0,0,0}, {10010,10022,10021 ,726,726,726 ,0,0,0}, + {10002,10011,10208 ,726,726,5471 ,0,0,0}, {10208,10003,10002 ,5471,726,726 ,0,0,0}, + {10010,10009,10022 ,726,5470,726 ,0,0,0}, {10011,10010,10208 ,726,726,5471 ,0,0,0}, + {10007,10021,10008 ,5470,726,726 ,0,0,0}, {9989,10012,8895 ,726,726,726 ,0,0,0}, + {8881,8879,9907 ,726,726,5469 ,0,0,0}, {9990,8891,10209 ,5470,726,5470 ,0,0,0}, + {8890,9987,10209 ,726,5469,5470 ,0,0,0}, {10209,8891,8890 ,5470,726,726 ,0,0,0}, + {9986,8885,9955 ,5468,726,726 ,0,0,0}, {8885,9986,8887 ,726,5468,726 ,0,0,0}, + {8884,9955,8885 ,5471,726,726 ,0,0,0}, {10027,8878,8853 ,726,5471,5471 ,0,0,0}, + {8853,8852,10026 ,5471,5471,5470 ,0,0,0}, {9901,8878,10027 ,5469,5471,726 ,0,0,0}, + {10210,10211,8855 ,5470,5470,726 ,0,0,0}, {10183,8858,8861 ,726,5470,726 ,0,0,0}, + {10211,8852,8855 ,5470,5471,726 ,0,0,0}, {8862,8867,10212 ,726,726,726 ,0,0,0}, + {8862,10213,8861 ,726,5470,726 ,0,0,0}, {10214,8867,8865 ,726,726,5470 ,0,0,0}, + {8754,8756,8493 ,726,726,726 ,0,0,0}, {8870,8751,8864 ,726,726,5471 ,0,0,0}, + {8767,10215,8770 ,726,726,5470 ,0,0,0}, {8841,10216,8843 ,726,5471,5471 ,0,0,0}, + {10217,8599,8602 ,5471,5470,726 ,0,0,0}, {10218,8472,10219 ,726,726,5470 ,0,0,0}, + {8789,8503,10220 ,5471,5470,5470 ,0,0,0}, {10221,10222,8785 ,726,5471,726 ,0,0,0}, + {8479,8832,8478 ,726,5471,726 ,0,0,0}, {8950,8949,8824 ,5468,726,5471 ,0,0,0}, + {8874,8752,8870 ,5470,5471,726 ,0,0,0}, {8765,8764,10223 ,726,726,726 ,0,0,0}, + {8492,8466,8864 ,5470,5471,5471 ,0,0,0}, {10214,10212,8867 ,726,726,726 ,0,0,0}, + {10212,10213,8862 ,726,5470,726 ,0,0,0}, {10213,10184,8861 ,5470,5471,726 ,0,0,0}, + {8858,10210,8855 ,5470,5470,726 ,0,0,0}, {10210,8858,10183 ,5470,5470,726 ,0,0,0}, + {9908,8851,8849 ,5468,5469,726 ,0,0,0}, {10211,10026,8852 ,5470,5470,5471 ,0,0,0}, + {8879,8851,9907 ,726,5469,5469 ,0,0,0}, {9900,8879,8878 ,5468,726,5471 ,0,0,0}, + {9900,8851,8879 ,5468,5469,726 ,0,0,0}, {8849,8847,10206 ,726,5468,726 ,0,0,0}, + {8849,10206,9908 ,726,726,5468 ,0,0,0}, {8846,10178,10206 ,726,726,726 ,0,0,0}, + {8843,10216,10178 ,5471,5471,726 ,0,0,0}, {8840,10205,10138 ,5469,5468,5468 ,0,0,0}, + {8841,10138,10216 ,726,5468,5471 ,0,0,0}, {8821,8820,8949 ,5469,5468,726 ,0,0,0}, + {8840,8821,10205 ,5469,5469,5468 ,0,0,0}, {8824,8828,8950 ,5471,726,5468 ,0,0,0}, + {8820,8824,8949 ,5468,5471,726 ,0,0,0}, {8828,8827,8946 ,726,5471,5469 ,0,0,0}, + {8479,8482,8830 ,726,726,5469 ,0,0,0}, {8478,8832,8834 ,726,5471,5470 ,0,0,0}, + {10185,10219,8473 ,5471,5470,5471 ,0,0,0}, {8476,8478,8834 ,5471,726,5470 ,0,0,0}, + {10218,10214,8470 ,726,726,5470 ,0,0,0}, {8873,10224,8745 ,5470,5470,726 ,0,0,0}, + {8770,10225,8771 ,5470,5470,5470 ,0,0,0}, {10182,8743,8741 ,726,5489,726 ,0,0,0}, + {10068,8738,8735 ,726,726,726 ,0,0,0}, {10226,10082,10029 ,5489,5488,726 ,0,0,0}, + {10082,10226,10044 ,5488,5489,5489 ,0,0,0}, {10045,10023,10046 ,726,726,726 ,0,0,0}, + {10025,10227,10042 ,5489,726,726 ,0,0,0}, {10043,10042,10227 ,726,726,726 ,0,0,0}, + {10024,10023,10045 ,5488,726,726 ,0,0,0}, {10024,10227,10025 ,5488,726,5489 ,0,0,0}, + {10046,9890,10047 ,726,726,726 ,0,0,0}, {9891,10035,9892 ,726,726,726 ,0,0,0}, + {10051,10033,10049 ,5489,726,726 ,0,0,0}, {10033,9891,10049 ,726,726,726 ,0,0,0}, + {10037,10054,10038 ,726,726,726 ,0,0,0}, {10052,10051,10050 ,726,5489,726 ,0,0,0}, + {10054,10053,10038 ,726,726,726 ,0,0,0}, {10053,10052,10055 ,726,726,5488 ,0,0,0}, + {10037,10036,9899 ,726,5489,726 ,0,0,0}, {10058,9899,10056 ,726,726,5489 ,0,0,0}, + {8805,8803,9894 ,5471,726,5471 ,0,0,0}, {9899,10069,9897 ,726,726,726 ,0,0,0}, + {8814,9994,10069 ,5471,726,726 ,0,0,0}, {10069,8815,8814 ,726,726,5471 ,0,0,0}, + {9993,8809,10032 ,5471,726,726 ,0,0,0}, {8809,9993,8811 ,726,5471,5471 ,0,0,0}, + {8808,10032,8809 ,726,726,726 ,0,0,0}, {10228,8777,10065 ,5471,726,726 ,0,0,0}, + {8777,8776,10066 ,726,726,726 ,0,0,0}, {8802,8777,10228 ,726,726,5471 ,0,0,0}, + {10229,10230,8779 ,726,726,726 ,0,0,0}, {10222,8782,8785 ,5471,726,726 ,0,0,0}, + {10230,8776,8779 ,726,726,726 ,0,0,0}, {8786,8791,10231 ,726,726,726 ,0,0,0}, + {8786,10232,8785 ,726,5471,726 ,0,0,0}, {10220,8791,8789 ,5470,726,5471 ,0,0,0}, + {8508,8675,8678 ,5471,5471,726 ,0,0,0}, {8794,8675,8788 ,726,5471,726 ,0,0,0}, + {10233,8503,8502 ,5471,5470,726 ,0,0,0}, {8767,8765,10234 ,726,726,726 ,0,0,0}, + {8508,8505,8788 ,5471,726,726 ,0,0,0}, {8689,10235,8691 ,726,5470,726 ,0,0,0}, + {8596,8722,8721 ,5470,726,726 ,0,0,0}, {8709,10236,8706 ,726,726,5471 ,0,0,0}, + {8756,8496,8493 ,726,726,726 ,0,0,0}, {8874,8873,8748 ,5470,5470,726 ,0,0,0}, + {8798,8676,8794 ,5471,726,726 ,0,0,0}, {10198,8715,8713 ,726,726,726 ,0,0,0}, + {8788,8505,8789 ,726,726,5471 ,0,0,0}, {10220,10231,8791 ,5470,726,726 ,0,0,0}, + {10231,10232,8786 ,726,5471,726 ,0,0,0}, {10232,10221,8785 ,5471,726,726 ,0,0,0}, + {8782,10229,8779 ,726,726,726 ,0,0,0}, {10229,8782,10222 ,726,726,5471 ,0,0,0}, + {10237,8775,8773 ,5470,726,726 ,0,0,0}, {10230,10066,8776 ,726,726,726 ,0,0,0}, + {8803,8775,9894 ,726,726,5471 ,0,0,0}, {8775,8803,10039 ,726,726,5471 ,0,0,0}, + {10228,10039,8802 ,5471,5471,726 ,0,0,0}, {8775,10237,9895 ,726,5470,726 ,0,0,0}, + {8773,8771,10225 ,726,5470,5470 ,0,0,0}, {8773,10225,10237 ,726,5470,5470 ,0,0,0}, + {8770,10215,10225 ,5470,726,5470 ,0,0,0}, {8767,10234,10215 ,726,726,726 ,0,0,0}, + {8764,10224,10223 ,726,5470,726 ,0,0,0}, {8765,10223,10234 ,726,726,726 ,0,0,0}, + {8745,8744,8873 ,726,5470,5470 ,0,0,0}, {8764,8745,10224 ,726,726,5470 ,0,0,0}, + {8748,8752,8874 ,726,5471,5470 ,0,0,0}, {8744,8748,8873 ,5470,726,5470 ,0,0,0}, + {8752,8751,8870 ,5471,726,726 ,0,0,0}, {8493,8492,8754 ,726,5470,726 ,0,0,0}, + {8496,8758,8497 ,726,726,5471 ,0,0,0}, {8499,8497,10179 ,726,5471,726 ,0,0,0}, + {8756,8758,8496 ,726,726,726 ,0,0,0}, {10220,8503,10233 ,5470,5470,5471 ,0,0,0}, + {8739,10181,8741 ,5488,726,726 ,0,0,0}, {8941,8486,10143 ,5468,5470,726 ,0,0,0}, + {8665,10030,8667 ,5470,726,5470 ,0,0,0}, {10086,8662,8659 ,726,726,726 ,0,0,0}, + {10070,10238,10071 ,5471,726,726 ,0,0,0}, {10061,10071,10062 ,5471,726,726 ,0,0,0}, + {10107,10239,10074 ,726,5471,5471 ,0,0,0}, {10060,10074,10239 ,726,5471,5471 ,0,0,0}, + {10079,10137,10107 ,726,726,726 ,0,0,0}, {10137,10239,10107 ,726,5471,726 ,0,0,0}, + {10090,10100,10079 ,726,726,726 ,0,0,0}, {10240,10080,10079 ,726,726,726 ,0,0,0}, + {10077,10079,10092 ,726,726,726 ,0,0,0}, {10093,10092,10079 ,5488,726,726 ,0,0,0}, + {10135,10096,10136 ,5489,726,726 ,0,0,0}, {10095,10092,10091 ,726,726,726 ,0,0,0}, + {10096,10097,10136 ,726,726,726 ,0,0,0}, {10097,10095,10094 ,726,726,726 ,0,0,0}, + {10076,10135,10098 ,726,5489,726 ,0,0,0}, {10182,10075,8743 ,726,726,5489 ,0,0,0}, + {8727,8726,10029 ,726,5471,726 ,0,0,0}, {8738,10241,8739 ,726,726,5488 ,0,0,0}, + {10181,8739,10241 ,726,5488,726 ,0,0,0}, {10067,8733,10083 ,726,726,726 ,0,0,0}, + {10068,10241,8738 ,726,726,726 ,0,0,0}, {8733,10067,8735 ,726,726,726 ,0,0,0}, + {8732,10083,8733 ,726,726,726 ,0,0,0}, {10139,10029,10242 ,5470,726,5471 ,0,0,0}, + {10242,8701,10142 ,5471,726,5471 ,0,0,0}, {10242,10029,8701 ,5471,726,726 ,0,0,0}, + {8703,10243,8700 ,5471,726,726 ,0,0,0}, {8709,10244,10236 ,726,726,726 ,0,0,0}, + {8703,10245,10243 ,5471,726,726 ,0,0,0}, {10246,8694,8691 ,5471,726,726 ,0,0,0}, + {8694,10247,8695 ,726,726,726 ,0,0,0}, {10248,8689,8688 ,726,726,5471 ,0,0,0}, + {8797,10249,8669 ,5471,5471,5471 ,0,0,0}, {8672,8798,8797 ,726,5471,5471 ,0,0,0}, + {8508,8788,8675 ,5471,726,5471 ,0,0,0}, {10250,10251,10252 ,5470,726,726 ,0,0,0}, + {10253,8515,8685 ,726,5470,5471 ,0,0,0}, {8721,10254,8593 ,726,726,726 ,0,0,0}, + {10255,8619,8618 ,5471,5470,5471 ,0,0,0}, {8618,8615,10256 ,5471,726,726 ,0,0,0}, + {8718,8599,8712 ,726,5470,726 ,0,0,0}, {8511,8678,8680 ,5471,726,726 ,0,0,0}, + {8722,8600,8718 ,726,5471,726 ,0,0,0}, {8612,10257,8613 ,726,726,5471 ,0,0,0}, + {8712,10258,8713 ,726,726,726 ,0,0,0}, {10198,9995,8715 ,726,5470,726 ,0,0,0}, + {9995,10203,8710 ,5470,726,726 ,0,0,0}, {10203,10244,8709 ,726,726,726 ,0,0,0}, + {8706,10245,8703 ,5471,726,5471 ,0,0,0}, {10245,8706,10236 ,726,5471,726 ,0,0,0}, + {10247,10259,8697 ,726,726,726 ,0,0,0}, {8697,10259,10029 ,726,726,726 ,0,0,0}, + {10243,10142,8700 ,726,5471,726 ,0,0,0}, {8729,8727,10029 ,726,726,726 ,0,0,0}, + {10029,8726,8701 ,726,5471,726 ,0,0,0}, {8699,10029,10140 ,5471,726,5471 ,0,0,0}, + {10259,10226,10029 ,726,5489,726 ,0,0,0}, {8697,8695,10247 ,726,726,726 ,0,0,0}, + {8694,10246,10247 ,726,5471,726 ,0,0,0}, {8691,10235,10246 ,726,5470,5471 ,0,0,0}, + {8688,10249,10248 ,5471,5471,726 ,0,0,0}, {8689,10248,10235 ,726,726,5470 ,0,0,0}, + {8669,8668,8797 ,5471,726,5471 ,0,0,0}, {8688,8669,10249 ,5471,5471,5471 ,0,0,0}, + {8672,8676,8798 ,726,726,5471 ,0,0,0}, {8668,8672,8797 ,726,726,5471 ,0,0,0}, + {8676,8675,8794 ,726,5471,726 ,0,0,0}, {8511,8508,8678 ,5471,5471,726 ,0,0,0}, + {8511,8680,8514 ,5471,726,726 ,0,0,0}, {8682,8515,8514 ,726,5470,726 ,0,0,0}, + {8682,8514,8680 ,726,726,726 ,0,0,0}, {8682,8685,8515 ,726,5471,5470 ,0,0,0}, + {10260,8558,8563 ,5468,5469,5470 ,0,0,0}, {10116,10128,10123 ,5468,5469,726 ,0,0,0}, + {8903,8566,8904 ,5468,5471,5469 ,0,0,0}, {8586,8583,10116 ,5469,5471,5468 ,0,0,0}, + {8547,10129,10128 ,5469,726,5469 ,0,0,0}, {10127,10129,10121 ,726,726,726 ,0,0,0}, + {10161,10158,10160 ,726,5471,726 ,0,0,0}, {10157,10261,10119 ,5471,5468,5471 ,0,0,0}, + {10120,10119,10261 ,5468,5471,5468 ,0,0,0}, {10159,10158,10161 ,5468,5471,726 ,0,0,0}, + {10159,10261,10157 ,5468,5468,5471 ,0,0,0}, {10160,10125,10124 ,726,5470,726 ,0,0,0}, + {10132,10131,10126 ,726,5469,5469 ,0,0,0}, {10151,10130,10152 ,5470,5471,726 ,0,0,0}, + {10130,10132,10152 ,5471,726,726 ,0,0,0}, {10148,10144,10146 ,726,726,5471 ,0,0,0}, + {10150,10149,10262 ,726,5470,726 ,0,0,0}, {10262,10151,10150 ,726,5470,726 ,0,0,0}, + {10148,10147,10144 ,726,5471,726 ,0,0,0}, {10149,10148,10262 ,5470,726,726 ,0,0,0}, + {10115,10146,10145 ,726,5471,5470 ,0,0,0}, {10030,10114,8667 ,726,726,5470 ,0,0,0}, + {8653,8651,10070 ,726,5470,5471 ,0,0,0}, {8662,10263,8663 ,726,726,726 ,0,0,0}, + {10031,8663,10263 ,726,726,726 ,0,0,0}, {10085,8657,10141 ,5471,5470,726 ,0,0,0}, + {10086,10263,8662 ,726,726,726 ,0,0,0}, {8657,10085,8659 ,5470,5471,726 ,0,0,0}, + {8656,10141,8657 ,5470,726,5470 ,0,0,0}, {10197,8650,8625 ,5471,5471,5471 ,0,0,0}, + {8625,8624,10196 ,5471,726,5471 ,0,0,0}, {10111,8650,10197 ,5471,5471,5471 ,0,0,0}, + {10264,10265,8627 ,5471,726,726 ,0,0,0}, {10072,8630,8633 ,726,5470,5470 ,0,0,0}, + {10265,8624,8627 ,726,726,726 ,0,0,0}, {8634,8639,10266 ,5470,726,726 ,0,0,0}, + {8634,10267,8633 ,5470,726,5470 ,0,0,0}, {10268,8639,8637 ,726,726,726 ,0,0,0}, + {8526,8528,10269 ,726,5471,5471 ,0,0,0}, {8613,10270,8615 ,5471,726,726 ,0,0,0}, + {10271,10272,10273 ,5471,726,726 ,0,0,0}, {8561,10271,10274 ,5471,5471,5471 ,0,0,0}, + {10143,8486,10275 ,726,5470,5469 ,0,0,0}, {8903,8906,10276 ,5468,5468,5470 ,0,0,0}, + {8542,10277,8543 ,726,726,5471 ,0,0,0}, {8561,10274,8563 ,5471,5471,5470 ,0,0,0}, + {8642,8523,8636 ,726,5470,5470 ,0,0,0}, {8604,10278,10279 ,5470,5471,726 ,0,0,0}, + {8646,8524,8642 ,726,5471,726 ,0,0,0}, {10280,10269,8528 ,5471,5471,5471 ,0,0,0}, + {10281,10282,8636 ,726,5471,5470 ,0,0,0}, {10268,10266,8639 ,726,726,726 ,0,0,0}, + {10266,10267,8634 ,726,726,5470 ,0,0,0}, {10267,10073,8633 ,726,726,5470 ,0,0,0}, + {8630,10264,8627 ,5470,5471,726 ,0,0,0}, {10264,8630,10072 ,5471,5470,726 ,0,0,0}, + {8621,10255,10238 ,5471,5471,726 ,0,0,0}, {10238,8623,8621 ,726,726,5471 ,0,0,0}, + {10265,10196,8624 ,726,5471,726 ,0,0,0}, {8651,8623,10070 ,5470,726,5471 ,0,0,0}, + {10110,8651,8650 ,726,5470,5471 ,0,0,0}, {10110,8623,8651 ,726,726,5470 ,0,0,0}, + {10070,8623,10238 ,5471,726,726 ,0,0,0}, {8621,8619,10255 ,5471,5470,5471 ,0,0,0}, + {8618,10256,10255 ,5471,726,5471 ,0,0,0}, {8615,10270,10256 ,726,726,726 ,0,0,0}, + {8612,10254,10257 ,726,726,726 ,0,0,0}, {8613,10257,10270 ,5471,726,726 ,0,0,0}, + {8593,8592,8721 ,726,5471,726 ,0,0,0}, {8612,8593,10254 ,726,726,726 ,0,0,0}, + {8596,8600,8722 ,5470,5471,726 ,0,0,0}, {8592,8596,8721 ,5471,5470,726 ,0,0,0}, + {8600,8599,8718 ,5471,5470,726 ,0,0,0}, {10279,10217,8602 ,726,5471,726 ,0,0,0}, + {8712,8599,10217 ,726,5470,5471 ,0,0,0}, {8609,10283,10284 ,726,726,726 ,0,0,0}, + {10278,8606,10284 ,5471,726,726 ,0,0,0}, {10285,10286,10287 ,5470,5470,5471 ,0,0,0}, + {8589,10192,8591 ,5468,5470,5483 ,0,0,0}, {8897,8896,8569 ,726,5468,5468 ,0,0,0}, + {8589,8587,10191 ,5468,5469,5470 ,0,0,0}, {8925,9889,10188 ,726,5468,5468 ,0,0,0}, + {8922,10190,9889 ,5469,726,5468 ,0,0,0}, {10188,10189,9909 ,5468,5468,5469 ,0,0,0}, + {9918,10189,9919 ,5476,5468,5471 ,0,0,0}, {9946,9949,9944 ,5468,5468,5475 ,0,0,0}, + {9948,10288,10174 ,5483,726,5468 ,0,0,0}, {9917,10174,10288 ,5475,5468,726 ,0,0,0}, + {9947,9949,9946 ,5486,5468,5468 ,0,0,0}, {9947,10288,9948 ,5486,726,5483 ,0,0,0}, + {9944,9921,9945 ,5475,5478,5485 ,0,0,0}, {9922,9933,9920 ,5469,5468,5477 ,0,0,0}, + {9926,9932,9924 ,726,726,5471 ,0,0,0}, {9932,9922,9924 ,726,5469,5471 ,0,0,0}, + {10176,9930,10177 ,5472,5480,5482 ,0,0,0}, {9931,9926,9925 ,5481,726,5469 ,0,0,0}, + {9930,9929,10177 ,5480,726,5482 ,0,0,0}, {9929,9931,9941 ,726,5481,5475 ,0,0,0}, + {9934,10176,9937 ,5475,5472,5468 ,0,0,0}, {10192,9935,8591 ,5470,5475,5483 ,0,0,0}, + {10116,8575,10193 ,5468,726,5468 ,0,0,0}, {8586,10118,8587 ,5469,5469,5469 ,0,0,0}, + {10191,8587,10118 ,5470,5469,5469 ,0,0,0}, {10289,10117,10116 ,5468,726,5468 ,0,0,0}, + {10118,8586,10116 ,5469,5469,5468 ,0,0,0}, {10116,8583,8581 ,5468,5471,5470 ,0,0,0}, + {10116,8580,8577 ,5468,5469,5471 ,0,0,0}, {10290,8549,10194 ,5469,5468,5469 ,0,0,0}, + {8549,8548,10195 ,5468,5471,5471 ,0,0,0}, {8574,8549,10290 ,5468,5468,5469 ,0,0,0}, + {10291,10292,8551 ,5470,5471,5468 ,0,0,0}, {10112,8554,8557 ,5470,726,5468 ,0,0,0}, + {10292,8548,8551 ,5471,5471,5468 ,0,0,0}, {8906,8908,10293 ,5468,5468,5468 ,0,0,0}, + {8520,8646,8645 ,5471,726,726 ,0,0,0}, {8558,10294,8557 ,5469,5469,5468 ,0,0,0}, + {10295,8537,8536 ,726,5471,726 ,0,0,0}, {10296,8542,8539 ,726,726,5470 ,0,0,0}, + {10297,8517,8645 ,726,5470,726 ,0,0,0}, {10298,8539,8537 ,726,5470,5471 ,0,0,0}, + {8903,8560,8566 ,5468,5469,5471 ,0,0,0}, {8906,10293,10276 ,5468,5468,5470 ,0,0,0}, + {8566,8570,8904 ,5471,726,5469 ,0,0,0}, {8569,8900,8570 ,5468,5468,726 ,0,0,0}, + {8904,8570,8900 ,5469,726,5468 ,0,0,0}, {8485,10187,10275 ,5469,5469,5469 ,0,0,0}, + {8910,8490,10299 ,5471,5470,726 ,0,0,0}, {8490,10186,8488 ,5470,5469,726 ,0,0,0}, + {8560,10300,8561 ,5469,5471,5471 ,0,0,0}, {10274,10260,8563 ,5471,5468,5470 ,0,0,0}, + {10260,10294,8558 ,5468,5469,5469 ,0,0,0}, {10294,10113,8557 ,5469,5468,5468 ,0,0,0}, + {8554,10291,8551 ,726,5470,5468 ,0,0,0}, {10291,8554,10112 ,5470,726,5470 ,0,0,0}, + {8545,10277,10301 ,726,726,5471 ,0,0,0}, {10301,8547,8545 ,5471,5469,726 ,0,0,0}, + {10292,10195,8548 ,5471,5471,5471 ,0,0,0}, {8547,10128,10116 ,5469,5469,5468 ,0,0,0}, + {10116,10193,8547 ,5468,5468,5469 ,0,0,0}, {10290,10193,8574 ,5469,5468,5468 ,0,0,0}, + {8547,10301,10129 ,5469,5471,726 ,0,0,0}, {8545,8543,10277 ,726,5471,726 ,0,0,0}, + {8542,10296,10277 ,726,726,726 ,0,0,0}, {8539,10298,10296 ,5470,726,726 ,0,0,0}, + {8536,10297,10295 ,726,726,726 ,0,0,0}, {8537,10295,10298 ,5471,726,726 ,0,0,0}, + {8517,8516,8645 ,5470,726,726 ,0,0,0}, {8536,8517,10297 ,726,5470,726 ,0,0,0}, + {8520,8524,8646 ,5471,5471,726 ,0,0,0}, {8516,8520,8645 ,726,5471,726 ,0,0,0}, + {8524,8523,8642 ,5471,5470,726 ,0,0,0}, {10269,10281,8526 ,5471,726,726 ,0,0,0}, + {10280,8530,10302 ,5471,726,726 ,0,0,0}, {10200,10302,10201 ,5471,726,5470 ,0,0,0}, + {8528,8530,10280 ,5471,726,5471 ,0,0,0}, {10274,10271,10273 ,5471,5471,726 ,0,0,0}, + {10268,8637,10303 ,726,726,5471 ,0,0,0}, {10214,8865,8470 ,726,5470,5470 ,0,0,0}, + {10268,10303,10285 ,726,5471,5470 ,0,0,0}, {8505,8503,8789 ,726,5470,5471 ,0,0,0}, + {8499,10180,8502 ,726,5470,726 ,0,0,0}, {10233,8502,10180 ,5471,726,5470 ,0,0,0}, + {8865,8864,8466 ,5470,5471,5471 ,0,0,0}, {8761,8497,8758 ,726,5471,726 ,0,0,0}, + {8761,10179,8497 ,726,726,5471 ,0,0,0}, {8492,8864,8751 ,5470,5471,726 ,0,0,0}, + {8751,8754,8492 ,726,726,5470 ,0,0,0}, {8865,8466,8470 ,5470,5471,5470 ,0,0,0}, + {10218,8470,8472 ,726,5470,726 ,0,0,0}, {8484,8940,8482 ,5471,5469,726 ,0,0,0}, + {10219,8472,8473 ,5470,726,5471 ,0,0,0}, {8837,8476,8834 ,726,5471,5470 ,0,0,0}, + {8837,10185,8476 ,726,5471,5471 ,0,0,0}, {8940,8827,8482 ,5469,5471,726 ,0,0,0}, + {8827,8830,8482 ,5471,5469,726 ,0,0,0}, {8484,8486,8941 ,5471,5470,5468 ,0,0,0}, + {10275,8486,8485 ,5469,5470,5469 ,0,0,0}, {10300,8560,10276 ,5471,5469,5470 ,0,0,0}, + {10187,8485,8488 ,5469,5469,726 ,0,0,0}, {8913,8490,8910 ,5469,5470,5471 ,0,0,0}, + {8913,10186,8490 ,5469,5469,5470 ,0,0,0}, {10276,8560,8903 ,5470,5469,5468 ,0,0,0}, + {10299,10293,8908 ,726,5468,5468 ,0,0,0}, {10299,8908,8910 ,726,5468,5471 ,0,0,0}, + {10300,10271,8561 ,5471,5471,5471 ,0,0,0}, {10200,10202,10272 ,5471,5471,726 ,0,0,0}, + {10273,10272,10202 ,726,726,5471 ,0,0,0}, {8637,8636,10282 ,726,5470,5471 ,0,0,0}, + {8533,10302,8530 ,726,726,726 ,0,0,0}, {8533,10201,10302 ,726,5470,726 ,0,0,0}, + {10281,8636,8523 ,726,5470,5470 ,0,0,0}, {8523,8526,10281 ,5470,726,726 ,0,0,0}, + {8637,10282,10303 ,726,5471,5471 ,0,0,0}, {10287,10286,10304 ,5471,5470,726 ,0,0,0}, + {10285,10303,10286 ,5470,5471,5470 ,0,0,0}, {10304,10284,10283 ,726,726,726 ,0,0,0}, + {10283,10287,10304 ,726,5471,726 ,0,0,0}, {10284,8606,8609 ,726,726,726 ,0,0,0}, + {10278,8604,8606 ,5471,5470,726 ,0,0,0}, {10279,8602,8604 ,726,726,5470 ,0,0,0}, + {8712,10217,10258 ,726,5471,726 ,0,0,0}, {10199,10305,10198 ,5471,5471,726 ,0,0,0}, + {8713,10258,10199 ,726,726,5471 ,0,0,0}, {10251,10305,10252 ,726,5471,726 ,0,0,0}, + {10199,10252,10305 ,5471,726,5471 ,0,0,0}, {10251,10250,10253 ,726,5470,726 ,0,0,0}, + {8515,10253,10250 ,5470,726,5470 ,0,0,0}, {10289,10116,10122 ,5468,5468,5468 ,0,0,0}, + {8581,8580,10116 ,5470,5469,5468 ,0,0,0}, {10079,10099,10093 ,726,726,5488 ,0,0,0}, + {10088,10240,10079 ,5488,726,726 ,0,0,0}, {10029,8699,8697 ,726,5471,726 ,0,0,0}, + {10204,10029,10084 ,726,726,726 ,0,0,0}, {10170,10169,10167 ,5469,5470,5468 ,0,0,0}, + {10170,9912,10168 ,5469,5468,5469 ,0,0,0}, {10056,9899,9898 ,5489,726,726 ,0,0,0}, + {8819,8817,9899 ,726,726,726 ,0,0,0}, {10306,10307,10308 ,5490,5491,5492 ,0,0,0}, + {10309,10310,10311 ,5493,5494,5495 ,0,0,0}, {10312,10310,10313 ,5496,5494,5497 ,0,0,0}, + {10314,10315,10316 ,5498,5499,5500 ,0,0,0}, {10317,10318,10319 ,5501,5502,5503 ,0,0,0}, + {10320,10321,10322 ,5504,5505,5506 ,0,0,0}, {10323,10324,10325 ,5507,5508,5509 ,0,0,0}, + {9936,9940,10320 ,5510,5511,5504 ,0,0,0}, {10326,10327,10328 ,5512,5513,5514 ,0,0,0}, + {10317,10322,10321 ,5501,5506,5505 ,0,0,0}, {10329,10330,10327 ,5515,5516,5513 ,0,0,0}, + {10331,10329,10327 ,5517,5515,5513 ,0,0,0}, {10331,10332,10329 ,5517,5518,5515 ,0,0,0}, + {10332,10331,10333 ,5518,5517,5519 ,0,0,0}, {10334,10330,10335 ,5520,5516,5521 ,0,0,0}, + {10336,10337,10338 ,5522,5523,5524 ,0,0,0}, {10327,10330,10334 ,5513,5516,5520 ,0,0,0}, + {10338,10337,10333 ,5524,5523,5519 ,0,0,0}, {10339,10336,10340 ,5525,5522,5526 ,0,0,0}, + {10341,10342,10343 ,5527,5528,5529 ,0,0,0}, {10341,10334,10335 ,5527,5520,5521 ,0,0,0}, + {10344,10345,10346 ,5530,5531,5532 ,0,0,0}, {10341,10335,10342 ,5527,5521,5528 ,0,0,0}, + {10342,10344,10343 ,5528,5530,5529 ,0,0,0}, {10347,10348,10346 ,5533,5534,5532 ,0,0,0}, + {10324,10349,10325 ,5508,5535,5509 ,0,0,0}, {10346,10345,10347 ,5532,5531,5533 ,0,0,0}, + {10350,10309,10351 ,5536,5493,5537 ,0,0,0}, {10345,10352,10347 ,5531,5538,5533 ,0,0,0}, + {10324,10328,10349 ,5508,5514,5535 ,0,0,0}, {10353,10328,10334 ,5539,5514,5520 ,0,0,0}, + {10354,10355,10356 ,5540,5541,5542 ,0,0,0}, {10357,10354,10358 ,5543,5540,5544 ,0,0,0}, + {9915,9932,10307 ,5545,5546,5491 ,0,0,0}, {10359,10360,10361 ,5547,5548,5549 ,0,0,0}, + {9915,10306,9916 ,5545,5490,726 ,0,0,0}, {10362,9916,10306 ,5550,726,5490 ,0,0,0}, + {10363,10348,10364 ,5551,5534,5552 ,0,0,0}, {10344,10346,10343 ,5530,5532,5529 ,0,0,0}, + {10346,10348,10363 ,5532,5534,5551 ,0,0,0}, {10364,10365,10363 ,5552,5553,5551 ,0,0,0}, + {10366,10343,10363 ,5554,5529,5551 ,0,0,0}, {10328,10353,10349 ,5514,5539,5535 ,0,0,0}, + {10366,10353,10341 ,5554,5539,5527 ,0,0,0}, {10331,10367,10333 ,5517,5555,5519 ,0,0,0}, + {10341,10353,10334 ,5527,5539,5520 ,0,0,0}, {10368,10369,10338 ,5556,5557,5524 ,0,0,0}, + {10327,10334,10328 ,5513,5520,5514 ,0,0,0}, {10367,10331,10326 ,5555,5517,5512 ,0,0,0}, + {10336,10338,10340 ,5522,5524,5526 ,0,0,0}, {10332,10333,10337 ,5518,5519,5523 ,0,0,0}, + {10333,10367,10368 ,5519,5555,5556 ,0,0,0}, {10370,10340,10338 ,5558,5526,5524 ,0,0,0}, + {10346,10363,10343 ,5532,5551,5529 ,0,0,0}, {10371,10365,10364 ,5559,5553,5552 ,0,0,0}, + {10371,10358,10365 ,5559,5544,5553 ,0,0,0}, {10343,10366,10341 ,5529,5554,5527 ,0,0,0}, + {10365,10372,10366 ,5553,5560,5554 ,0,0,0}, {10324,10313,10326 ,5508,5497,5512 ,0,0,0}, + {10372,10349,10353 ,5560,5535,5539 ,0,0,0}, {10309,10369,10368 ,5493,5557,5556 ,0,0,0}, + {10350,10369,10309 ,5536,5557,5493 ,0,0,0}, {10327,10326,10331 ,5513,5512,5517 ,0,0,0}, + {10328,10324,10326 ,5514,5508,5512 ,0,0,0}, {10333,10368,10338 ,5519,5556,5524 ,0,0,0}, + {10313,10310,10367 ,5497,5494,5555 ,0,0,0}, {10338,10369,10370 ,5524,5557,5558 ,0,0,0}, + {10368,10310,10309 ,5556,5494,5493 ,0,0,0}, {10373,10370,10369 ,5561,5558,5557 ,0,0,0}, + {10363,10365,10366 ,5551,5553,5554 ,0,0,0}, {10357,10358,10371 ,5543,5544,5559 ,0,0,0}, + {10374,10356,10375 ,5562,5542,5563 ,0,0,0}, {10366,10372,10353 ,5554,5560,5539 ,0,0,0}, + {10376,10372,10358 ,5564,5560,5544 ,0,0,0}, {10313,10324,10323 ,5497,5508,5507 ,0,0,0}, + {10376,10325,10349 ,5564,5509,5535 ,0,0,0}, {10377,10351,10311 ,5565,5537,5495 ,0,0,0}, + {10367,10310,10368 ,5555,5494,5556 ,0,0,0}, {10326,10313,10367 ,5512,5497,5555 ,0,0,0}, + {10313,10323,10312 ,5497,5507,5496 ,0,0,0}, {10350,10351,10378 ,5536,5537,5566 ,0,0,0}, + {10312,10311,10310 ,5496,5495,5494 ,0,0,0}, {10369,10350,10373 ,5557,5536,5561 ,0,0,0}, + {10309,10311,10351 ,5493,5495,5537 ,0,0,0}, {10379,10373,10350 ,5567,5561,5536 ,0,0,0}, + {10365,10358,10372 ,5553,5544,5560 ,0,0,0}, {10355,10354,10357 ,5541,5540,5543 ,0,0,0}, + {10325,10380,10323 ,5509,5568,5507 ,0,0,0}, {10372,10376,10349 ,5560,5564,5535 ,0,0,0}, + {10381,10376,10354 ,5569,5564,5540 ,0,0,0}, {10323,10382,10312 ,5507,5570,5496 ,0,0,0}, + {10381,10380,10325 ,5569,5568,5509 ,0,0,0}, {10312,10383,10311 ,5496,5571,5495 ,0,0,0}, + {10382,10323,10380 ,5570,5507,5568 ,0,0,0}, {10351,10314,10378 ,5537,5498,5566 ,0,0,0}, + {10383,10312,10382 ,5571,5496,5570 ,0,0,0}, {10384,10378,10316 ,5572,5566,5500 ,0,0,0}, + {10377,10311,10383 ,5565,5495,5571 ,0,0,0}, {10350,10378,10379 ,5536,5566,5567 ,0,0,0}, + {10351,10377,10314 ,5537,5565,5498 ,0,0,0}, {10384,10379,10378 ,5572,5567,5566 ,0,0,0}, + {10358,10354,10376 ,5544,5540,5564 ,0,0,0}, {10375,10356,10355 ,5563,5542,5541 ,0,0,0}, + {10380,10360,10382 ,5568,5548,5570 ,0,0,0}, {10376,10381,10325 ,5564,5569,5509 ,0,0,0}, + {10356,10385,10381 ,5542,5573,5569 ,0,0,0}, {10382,10359,10383 ,5570,5547,5571 ,0,0,0}, + {10385,10360,10380 ,5573,5548,5568 ,0,0,0}, {10383,10386,10377 ,5571,5574,5565 ,0,0,0}, + {10360,10359,10382 ,5548,5547,5570 ,0,0,0}, {10387,10314,10377 ,5575,5498,5565 ,0,0,0}, + {10386,10383,10359 ,5574,5571,5547 ,0,0,0}, {10388,10316,10319 ,5576,5500,5503 ,0,0,0}, + {10377,10386,10387 ,5565,5574,5575 ,0,0,0}, {10387,10315,10314 ,5575,5499,5498 ,0,0,0}, + {10384,10316,10388 ,5572,5500,5576 ,0,0,0}, {10378,10314,10316 ,5566,5498,5500 ,0,0,0}, + {10354,10356,10381 ,5540,5542,5569 ,0,0,0}, {10389,10374,10375 ,5577,5562,5563 ,0,0,0}, + {10390,10386,10359 ,5578,5574,5547 ,0,0,0}, {10381,10385,10380 ,5569,5573,5568 ,0,0,0}, + {10374,10308,10385 ,5562,5492,5573 ,0,0,0}, {10391,10387,10386 ,5579,5575,5574 ,0,0,0}, + {10308,10361,10360 ,5492,5549,5548 ,0,0,0}, {10392,10315,10387 ,5580,5499,5575 ,0,0,0}, + {10361,10390,10359 ,5549,5578,5547 ,0,0,0}, {10322,10317,10393 ,5506,5501,5581 ,0,0,0}, + {10390,10391,10386 ,5578,5579,5574 ,0,0,0}, {10319,10315,10394 ,5503,5499,5582 ,0,0,0}, + {10392,10387,10391 ,5580,5575,5579 ,0,0,0}, {10394,10315,10392 ,5582,5499,5580 ,0,0,0}, + {10388,10319,10318 ,5576,5503,5502 ,0,0,0}, {10316,10315,10319 ,5500,5499,5503 ,0,0,0}, + {10356,10374,10385 ,5542,5562,5573 ,0,0,0}, {10306,10389,10362 ,5490,5577,5550 ,0,0,0}, + {10307,10395,10361 ,5491,5583,5549 ,0,0,0}, {10385,10308,10360 ,5573,5492,5548 ,0,0,0}, + {10307,10361,10308 ,5491,5549,5492 ,0,0,0}, {10395,10396,10390 ,5583,5584,5578 ,0,0,0}, + {10395,10390,10361 ,5583,5578,5549 ,0,0,0}, {10396,10397,10391 ,5584,5585,5579 ,0,0,0}, + {10396,10391,10390 ,5584,5579,5578 ,0,0,0}, {10397,10398,10392 ,5585,5586,5580 ,0,0,0}, + {10397,10392,10391 ,5585,5580,5579 ,0,0,0}, {10398,10393,10394 ,5586,5581,5582 ,0,0,0}, + {10394,10392,10398 ,5582,5580,5586 ,0,0,0}, {10393,10317,10394 ,5581,5501,5582 ,0,0,0}, + {10318,10317,10321 ,5502,5501,5505 ,0,0,0}, {10319,10394,10317 ,5503,5582,5501 ,0,0,0}, + {10389,10306,10374 ,5577,5490,5562 ,0,0,0}, {10308,10374,10306 ,5492,5562,5490 ,0,0,0}, + {10395,9932,9926 ,5583,5546,5587 ,0,0,0}, {9915,10307,10306 ,5545,5491,5490 ,0,0,0}, + {10396,9926,9931 ,5584,5587,5588 ,0,0,0}, {9932,10395,10307 ,5546,5583,5491 ,0,0,0}, + {10397,9931,9930 ,5585,5588,5589 ,0,0,0}, {9926,10396,10395 ,5587,5584,5583 ,0,0,0}, + {10398,9930,10176 ,5586,5589,5590 ,0,0,0}, {9931,10397,10396 ,5588,5585,5584 ,0,0,0}, + {10393,10176,9934 ,5581,5590,5591 ,0,0,0}, {9930,10398,10397 ,5589,5586,5585 ,0,0,0}, + {10322,9934,9936 ,5506,5591,5510 ,0,0,0}, {10176,10393,10398 ,5590,5581,5586 ,0,0,0}, + {9936,10320,10322 ,5510,5504,5506 ,0,0,0}, {9934,10322,10393 ,5591,5506,5581 ,0,0,0}, + {10399,10400,10401 ,5592,5593,5594 ,0,0,0}, {10402,10403,10404 ,5595,5596,5597 ,0,0,0}, + {10400,10405,10401 ,5593,5598,5594 ,0,0,0}, {10406,10404,10403 ,5599,5597,5596 ,0,0,0}, + {10407,10408,10409 ,5600,5601,5602 ,0,0,0}, {10410,10411,10408 ,5603,5604,5601 ,0,0,0}, + {10412,10413,10414 ,5605,5606,5607 ,0,0,0}, {10415,10411,10410 ,5608,5604,5603 ,0,0,0}, + {10411,10409,10408 ,5604,5602,5601 ,0,0,0}, {10416,10408,10402 ,5609,5601,5595 ,0,0,0}, + {10417,10418,10419 ,5610,5611,5612 ,0,0,0}, {10420,10421,10422 ,5613,5614,5615 ,0,0,0}, + {10423,10418,10424 ,5616,5611,5617 ,0,0,0}, {10425,10426,10399 ,5618,5619,5592 ,0,0,0}, + {10413,10162,10130 ,5606,5620,5621 ,0,0,0}, {10427,10428,10429 ,5622,5623,5624 ,0,0,0}, + {10430,10164,10412 ,5625,5626,5605 ,0,0,0}, {10162,10412,10164 ,5620,5605,5626 ,0,0,0}, + {10431,10432,10433 ,5627,5628,5629 ,0,0,0}, {10405,10434,10401 ,5598,5630,5594 ,0,0,0}, + {10435,10436,10437 ,5631,5632,5633 ,0,0,0}, {10438,10439,10440 ,5634,5635,5636 ,0,0,0}, + {10429,10432,10441 ,5624,5628,5637 ,0,0,0}, {10442,10443,10444 ,5638,5639,5640 ,0,0,0}, + {10445,10399,10446 ,5641,5592,5642 ,0,0,0}, {10443,10438,10444 ,5639,5634,5640 ,0,0,0}, + {10425,10406,10403 ,5618,5599,5596 ,0,0,0}, {10153,10156,10442 ,5643,5644,5638 ,0,0,0}, + {10406,10425,10447 ,5599,5618,5645 ,0,0,0}, {10447,10425,10445 ,5645,5618,5641 ,0,0,0}, + {10448,10449,10445 ,5646,5647,5641 ,0,0,0}, {10425,10403,10426 ,5618,5596,5619 ,0,0,0}, + {10448,10450,10451 ,5646,5648,5649 ,0,0,0}, {10451,10449,10448 ,5649,5647,5646 ,0,0,0}, + {10452,10453,10454 ,5650,5651,5652 ,0,0,0}, {10453,10452,10450 ,5651,5650,5648 ,0,0,0}, + {10410,10408,10416 ,5603,5601,5609 ,0,0,0}, {10455,10407,10409 ,5653,5600,5602 ,0,0,0}, + {10455,10456,10407 ,5653,5654,5600 ,0,0,0}, {10416,10402,10404 ,5609,5595,5597 ,0,0,0}, + {10457,10402,10407 ,5655,5595,5600 ,0,0,0}, {10399,10426,10400 ,5592,5619,5593 ,0,0,0}, + {10457,10426,10403 ,5655,5619,5596 ,0,0,0}, {10448,10458,10450 ,5646,5656,5648 ,0,0,0}, + {10459,10453,10460 ,5657,5651,5658 ,0,0,0}, {10447,10445,10449 ,5645,5641,5647 ,0,0,0}, + {10445,10425,10399 ,5641,5618,5592 ,0,0,0}, {10451,10450,10452 ,5649,5648,5650 ,0,0,0}, + {10446,10458,10448 ,5642,5656,5646 ,0,0,0}, {10453,10461,10454 ,5651,5659,5652 ,0,0,0}, + {10450,10458,10460 ,5648,5656,5658 ,0,0,0}, {10462,10461,10453 ,5660,5659,5651 ,0,0,0}, + {10408,10407,10402 ,5601,5600,5595 ,0,0,0}, {10463,10456,10455 ,5661,5654,5653 ,0,0,0}, + {10463,10419,10456 ,5661,5612,5654 ,0,0,0}, {10402,10457,10403 ,5595,5655,5596 ,0,0,0}, + {10456,10464,10457 ,5654,5662,5655 ,0,0,0}, {10401,10433,10446 ,5594,5629,5642 ,0,0,0}, + {10464,10400,10426 ,5662,5593,5619 ,0,0,0}, {10429,10459,10460 ,5624,5657,5658 ,0,0,0}, + {10428,10459,10429 ,5623,5657,5624 ,0,0,0}, {10445,10446,10448 ,5641,5642,5646 ,0,0,0}, + {10399,10401,10446 ,5592,5594,5642 ,0,0,0}, {10450,10460,10453 ,5648,5658,5651 ,0,0,0}, + {10433,10432,10458 ,5629,5628,5656 ,0,0,0}, {10453,10459,10462 ,5651,5657,5660 ,0,0,0}, + {10460,10432,10429 ,5658,5628,5624 ,0,0,0}, {10465,10462,10459 ,5663,5660,5657 ,0,0,0}, + {10407,10456,10457 ,5600,5654,5655 ,0,0,0}, {10417,10419,10463 ,5610,5612,5661 ,0,0,0}, + {10466,10423,10467 ,5664,5616,5665 ,0,0,0}, {10457,10464,10426 ,5655,5662,5619 ,0,0,0}, + {10468,10464,10419 ,5666,5662,5612 ,0,0,0}, {10433,10401,10434 ,5629,5594,5630 ,0,0,0}, + {10468,10405,10400 ,5666,5598,5593 ,0,0,0}, {10469,10427,10441 ,5667,5622,5637 ,0,0,0}, + {10458,10432,10460 ,5656,5628,5658 ,0,0,0}, {10446,10433,10458 ,5642,5629,5656 ,0,0,0}, + {10433,10434,10431 ,5629,5630,5627 ,0,0,0}, {10428,10427,10470 ,5623,5622,5668 ,0,0,0}, + {10431,10441,10432 ,5627,5637,5628 ,0,0,0}, {10459,10428,10465 ,5657,5623,5663 ,0,0,0}, + {10429,10441,10427 ,5624,5637,5622 ,0,0,0}, {10471,10465,10428 ,5669,5663,5623 ,0,0,0}, + {10456,10419,10464 ,5654,5612,5662 ,0,0,0}, {10424,10418,10417 ,5617,5611,5610 ,0,0,0}, + {10405,10472,10434 ,5598,5670,5630 ,0,0,0}, {10464,10468,10400 ,5662,5666,5593 ,0,0,0}, + {10473,10468,10418 ,5671,5666,5611 ,0,0,0}, {10434,10474,10431 ,5630,5672,5627 ,0,0,0}, + {10473,10472,10405 ,5671,5670,5598 ,0,0,0}, {10431,10475,10441 ,5627,5673,5637 ,0,0,0}, + {10474,10434,10472 ,5672,5630,5670 ,0,0,0}, {10427,10436,10470 ,5622,5632,5668 ,0,0,0}, + {10475,10431,10474 ,5673,5627,5672 ,0,0,0}, {10476,10470,10435 ,5674,5668,5631 ,0,0,0}, + {10469,10441,10475 ,5667,5637,5673 ,0,0,0}, {10428,10470,10471 ,5623,5668,5669 ,0,0,0}, + {10427,10469,10436 ,5622,5667,5632 ,0,0,0}, {10476,10471,10470 ,5674,5669,5668 ,0,0,0}, + {10419,10418,10468 ,5612,5611,5666 ,0,0,0}, {10467,10423,10424 ,5665,5616,5617 ,0,0,0}, + {10472,10420,10474 ,5670,5613,5672 ,0,0,0}, {10468,10473,10405 ,5666,5671,5598 ,0,0,0}, + {10423,10477,10473 ,5616,5675,5671 ,0,0,0}, {10474,10422,10475 ,5672,5615,5673 ,0,0,0}, + {10477,10420,10472 ,5675,5613,5670 ,0,0,0}, {10475,10478,10469 ,5673,5676,5667 ,0,0,0}, + {10420,10422,10474 ,5613,5615,5672 ,0,0,0}, {10479,10436,10469 ,5677,5632,5667 ,0,0,0}, + {10478,10475,10422 ,5676,5673,5615 ,0,0,0}, {10480,10435,10440 ,5678,5631,5636 ,0,0,0}, + {10469,10478,10479 ,5667,5676,5677 ,0,0,0}, {10479,10437,10436 ,5677,5633,5632 ,0,0,0}, + {10476,10435,10480 ,5674,5631,5678 ,0,0,0}, {10470,10436,10435 ,5668,5632,5631 ,0,0,0}, + {10418,10423,10473 ,5611,5616,5671 ,0,0,0}, {10481,10466,10467 ,5679,5664,5665 ,0,0,0}, + {10482,10478,10422 ,5680,5676,5615 ,0,0,0}, {10473,10477,10472 ,5671,5675,5670 ,0,0,0}, + {10466,10414,10477 ,5664,5607,5675 ,0,0,0}, {10483,10479,10478 ,5681,5677,5676 ,0,0,0}, + {10414,10421,10420 ,5607,5614,5613 ,0,0,0}, {10484,10437,10479 ,5682,5633,5677 ,0,0,0}, + {10421,10482,10422 ,5614,5680,5615 ,0,0,0}, {10444,10438,10485 ,5640,5634,5683 ,0,0,0}, + {10482,10483,10478 ,5680,5681,5676 ,0,0,0}, {10440,10437,10486 ,5636,5633,5684 ,0,0,0}, + {10484,10479,10483 ,5682,5677,5681 ,0,0,0}, {10486,10437,10484 ,5684,5633,5682 ,0,0,0}, + {10480,10440,10439 ,5678,5636,5635 ,0,0,0}, {10435,10437,10440 ,5631,5633,5636 ,0,0,0}, + {10423,10466,10477 ,5616,5664,5675 ,0,0,0}, {10412,10481,10430 ,5605,5679,5625 ,0,0,0}, + {10413,10487,10421 ,5606,5685,5614 ,0,0,0}, {10477,10414,10420 ,5675,5607,5613 ,0,0,0}, + {10413,10421,10414 ,5606,5614,5607 ,0,0,0}, {10487,10488,10482 ,5685,5686,5680 ,0,0,0}, + {10487,10482,10421 ,5685,5680,5614 ,0,0,0}, {10488,10489,10483 ,5686,5687,5681 ,0,0,0}, + {10488,10483,10482 ,5686,5681,5680 ,0,0,0}, {10489,10490,10484 ,5687,5688,5682 ,0,0,0}, + {10489,10484,10483 ,5687,5682,5681 ,0,0,0}, {10490,10485,10486 ,5688,5683,5684 ,0,0,0}, + {10486,10484,10490 ,5684,5682,5688 ,0,0,0}, {10485,10438,10486 ,5683,5634,5684 ,0,0,0}, + {10439,10438,10443 ,5635,5634,5639 ,0,0,0}, {10440,10486,10438 ,5636,5684,5634 ,0,0,0}, + {10481,10412,10466 ,5679,5605,5664 ,0,0,0}, {10414,10466,10412 ,5607,5664,5605 ,0,0,0}, + {10487,10130,10151 ,5685,5621,5689 ,0,0,0}, {10162,10413,10412 ,5620,5606,5605 ,0,0,0}, + {10488,10151,10262 ,5686,5689,5690 ,0,0,0}, {10130,10487,10413 ,5621,5685,5606 ,0,0,0}, + {10489,10262,10148 ,5687,5690,5691 ,0,0,0}, {10151,10488,10487 ,5689,5686,5685 ,0,0,0}, + {10490,10148,10146 ,5688,5691,5692 ,0,0,0}, {10262,10489,10488 ,5690,5687,5686 ,0,0,0}, + {10485,10146,10115 ,5683,5692,5693 ,0,0,0}, {10148,10490,10489 ,5691,5688,5687 ,0,0,0}, + {10444,10115,10153 ,5640,5693,5643 ,0,0,0}, {10146,10485,10490 ,5692,5683,5688 ,0,0,0}, + {10153,10442,10444 ,5643,5638,5640 ,0,0,0}, {10115,10444,10485 ,5693,5640,5683 ,0,0,0}, + {10491,10492,10493 ,5694,5695,5696 ,0,0,0}, {10494,10495,10496 ,5697,5698,5699 ,0,0,0}, + {10493,10497,10498 ,5696,5700,5701 ,0,0,0}, {10497,10499,10498 ,5700,5702,5701 ,0,0,0}, + {10500,10501,10502 ,5703,5704,5705 ,0,0,0}, {10502,10503,10500 ,5705,5706,5703 ,0,0,0}, + {10504,10505,10506 ,5707,5708,5709 ,0,0,0}, {10507,10501,10508 ,5710,5704,5711 ,0,0,0}, + {10507,10502,10501 ,5710,5705,5704 ,0,0,0}, {10508,10509,10507 ,5711,5712,5710 ,0,0,0}, + {10510,10496,10511 ,5713,5699,5714 ,0,0,0}, {10512,10513,10514 ,5715,5716,5717 ,0,0,0}, + {10504,10078,10077 ,5707,5718,5719 ,0,0,0}, {10515,10516,10517 ,5720,5721,5722 ,0,0,0}, + {10518,10105,10506 ,5723,5724,5709 ,0,0,0}, {10519,10520,10513 ,5725,5726,5716 ,0,0,0}, + {10078,10506,10105 ,5718,5709,5724 ,0,0,0}, {10521,10522,10523 ,5727,5728,5729 ,0,0,0}, + {10524,10498,10499 ,5730,5701,5702 ,0,0,0}, {10525,10526,10527 ,5731,5732,5733 ,0,0,0}, + {10528,10529,10493 ,5734,5735,5696 ,0,0,0}, {10530,10531,10532 ,5736,5737,5738 ,0,0,0}, + {10523,10533,10534 ,5729,5739,5740 ,0,0,0}, {10535,10533,10536 ,5741,5739,5742 ,0,0,0}, + {10537,10538,10539 ,5743,5744,5745 ,0,0,0}, {10491,10495,10494 ,5694,5698,5697 ,0,0,0}, + {10538,10525,10539 ,5744,5731,5745 ,0,0,0}, {10529,10540,10491 ,5735,5746,5694 ,0,0,0}, + {10101,10106,10537 ,5747,5748,5743 ,0,0,0}, {10541,10542,10529 ,5749,5750,5735 ,0,0,0}, + {10540,10495,10491 ,5746,5698,5694 ,0,0,0}, {10541,10543,10544 ,5749,5751,5752 ,0,0,0}, + {10529,10542,10540 ,5735,5750,5746 ,0,0,0}, {10545,10546,10547 ,5753,5754,5755 ,0,0,0}, + {10542,10541,10544 ,5750,5749,5752 ,0,0,0}, {10548,10547,10549 ,5756,5755,5757 ,0,0,0}, + {10546,10545,10543 ,5754,5753,5751 ,0,0,0}, {10511,10501,10510 ,5714,5704,5713 ,0,0,0}, + {10501,10511,10508 ,5704,5714,5711 ,0,0,0}, {10503,10550,10500 ,5706,5758,5703 ,0,0,0}, + {10510,10494,10496 ,5713,5697,5699 ,0,0,0}, {10551,10510,10500 ,5759,5713,5703 ,0,0,0}, + {10493,10492,10497 ,5696,5695,5700 ,0,0,0}, {10551,10492,10494 ,5759,5695,5697 ,0,0,0}, + {10541,10552,10543 ,5749,5760,5751 ,0,0,0}, {10494,10492,10491 ,5697,5695,5694 ,0,0,0}, + {10553,10554,10546 ,5761,5762,5754 ,0,0,0}, {10529,10491,10493 ,5735,5694,5696 ,0,0,0}, + {10552,10541,10528 ,5760,5749,5734 ,0,0,0}, {10547,10546,10549 ,5755,5754,5757 ,0,0,0}, + {10544,10543,10545 ,5752,5751,5753 ,0,0,0}, {10543,10552,10553 ,5751,5760,5761 ,0,0,0}, + {10555,10549,10546 ,5763,5757,5754 ,0,0,0}, {10501,10500,10510 ,5704,5703,5713 ,0,0,0}, + {10556,10550,10503 ,5764,5758,5706 ,0,0,0}, {10556,10519,10550 ,5764,5725,5758 ,0,0,0}, + {10510,10551,10494 ,5713,5759,5697 ,0,0,0}, {10550,10557,10551 ,5758,5765,5759 ,0,0,0}, + {10498,10536,10528 ,5701,5742,5734 ,0,0,0}, {10557,10497,10492 ,5765,5700,5695 ,0,0,0}, + {10523,10554,10553 ,5729,5762,5761 ,0,0,0}, {10522,10554,10523 ,5728,5762,5729 ,0,0,0}, + {10529,10528,10541 ,5735,5734,5749 ,0,0,0}, {10493,10498,10528 ,5696,5701,5734 ,0,0,0}, + {10543,10553,10546 ,5751,5761,5754 ,0,0,0}, {10536,10533,10552 ,5742,5739,5760 ,0,0,0}, + {10546,10554,10555 ,5754,5762,5763 ,0,0,0}, {10553,10533,10523 ,5761,5739,5729 ,0,0,0}, + {10558,10555,10554 ,5766,5763,5762 ,0,0,0}, {10500,10550,10551 ,5703,5758,5759 ,0,0,0}, + {10520,10519,10556 ,5726,5725,5764 ,0,0,0}, {10559,10512,10560 ,5767,5715,5768 ,0,0,0}, + {10551,10557,10492 ,5759,5765,5695 ,0,0,0}, {10561,10557,10519 ,5769,5765,5725 ,0,0,0}, + {10536,10498,10524 ,5742,5701,5730 ,0,0,0}, {10561,10499,10497 ,5769,5702,5700 ,0,0,0}, + {10562,10521,10534 ,5770,5727,5740 ,0,0,0}, {10552,10533,10553 ,5760,5739,5761 ,0,0,0}, + {10528,10536,10552 ,5734,5742,5760 ,0,0,0}, {10536,10524,10535 ,5742,5730,5741 ,0,0,0}, + {10522,10521,10563 ,5728,5727,5771 ,0,0,0}, {10535,10534,10533 ,5741,5740,5739 ,0,0,0}, + {10554,10522,10558 ,5762,5728,5766 ,0,0,0}, {10523,10534,10521 ,5729,5740,5727 ,0,0,0}, + {10564,10558,10522 ,5772,5766,5728 ,0,0,0}, {10550,10519,10557 ,5758,5725,5765 ,0,0,0}, + {10514,10513,10520 ,5717,5716,5726 ,0,0,0}, {10499,10565,10524 ,5702,5773,5730 ,0,0,0}, + {10557,10561,10497 ,5765,5769,5700 ,0,0,0}, {10566,10561,10513 ,5774,5769,5716 ,0,0,0}, + {10524,10567,10535 ,5730,5775,5741 ,0,0,0}, {10566,10565,10499 ,5774,5773,5702 ,0,0,0}, + {10535,10568,10534 ,5741,5776,5740 ,0,0,0}, {10567,10524,10565 ,5775,5730,5773 ,0,0,0}, + {10521,10531,10563 ,5727,5737,5771 ,0,0,0}, {10568,10535,10567 ,5776,5741,5775 ,0,0,0}, + {10569,10563,10530 ,5777,5771,5736 ,0,0,0}, {10562,10534,10568 ,5770,5740,5776 ,0,0,0}, + {10522,10563,10564 ,5728,5771,5772 ,0,0,0}, {10521,10562,10531 ,5727,5770,5737 ,0,0,0}, + {10569,10564,10563 ,5777,5772,5771 ,0,0,0}, {10519,10513,10561 ,5725,5716,5769 ,0,0,0}, + {10560,10512,10514 ,5768,5715,5717 ,0,0,0}, {10565,10516,10567 ,5773,5721,5775 ,0,0,0}, + {10561,10566,10499 ,5769,5774,5702 ,0,0,0}, {10512,10570,10566 ,5715,5778,5774 ,0,0,0}, + {10567,10515,10568 ,5775,5720,5776 ,0,0,0}, {10570,10516,10565 ,5778,5721,5773 ,0,0,0}, + {10568,10571,10562 ,5776,5779,5770 ,0,0,0}, {10516,10515,10567 ,5721,5720,5775 ,0,0,0}, + {10572,10531,10562 ,5780,5737,5770 ,0,0,0}, {10571,10568,10515 ,5779,5776,5720 ,0,0,0}, + {10573,10530,10527 ,5781,5736,5733 ,0,0,0}, {10562,10571,10572 ,5770,5779,5780 ,0,0,0}, + {10572,10532,10531 ,5780,5738,5737 ,0,0,0}, {10569,10530,10573 ,5777,5736,5781 ,0,0,0}, + {10563,10531,10530 ,5771,5737,5736 ,0,0,0}, {10513,10512,10566 ,5716,5715,5774 ,0,0,0}, + {10574,10559,10560 ,5782,5767,5768 ,0,0,0}, {10575,10571,10515 ,5783,5779,5720 ,0,0,0}, + {10566,10570,10565 ,5774,5778,5773 ,0,0,0}, {10559,10505,10570 ,5767,5708,5778 ,0,0,0}, + {10576,10572,10571 ,5784,5780,5779 ,0,0,0}, {10505,10517,10516 ,5708,5722,5721 ,0,0,0}, + {10577,10532,10572 ,5785,5738,5780 ,0,0,0}, {10517,10575,10515 ,5722,5783,5720 ,0,0,0}, + {10539,10525,10578 ,5745,5731,5786 ,0,0,0}, {10575,10576,10571 ,5783,5784,5779 ,0,0,0}, + {10527,10532,10579 ,5733,5738,5787 ,0,0,0}, {10577,10572,10576 ,5785,5780,5784 ,0,0,0}, + {10579,10532,10577 ,5787,5738,5785 ,0,0,0}, {10573,10527,10526 ,5781,5733,5732 ,0,0,0}, + {10530,10532,10527 ,5736,5738,5733 ,0,0,0}, {10512,10559,10570 ,5715,5767,5778 ,0,0,0}, + {10506,10574,10518 ,5709,5782,5723 ,0,0,0}, {10504,10580,10517 ,5707,5788,5722 ,0,0,0}, + {10570,10505,10516 ,5778,5708,5721 ,0,0,0}, {10504,10517,10505 ,5707,5722,5708 ,0,0,0}, + {10580,10581,10575 ,5788,5789,5783 ,0,0,0}, {10580,10575,10517 ,5788,5783,5722 ,0,0,0}, + {10581,10582,10576 ,5789,5790,5784 ,0,0,0}, {10581,10576,10575 ,5789,5784,5783 ,0,0,0}, + {10582,10583,10577 ,5790,5791,5785 ,0,0,0}, {10582,10577,10576 ,5790,5785,5784 ,0,0,0}, + {10583,10578,10579 ,5791,5786,5787 ,0,0,0}, {10579,10577,10583 ,5787,5785,5791 ,0,0,0}, + {10578,10525,10579 ,5786,5731,5787 ,0,0,0}, {10526,10525,10538 ,5732,5731,5744 ,0,0,0}, + {10527,10579,10525 ,5733,5787,5731 ,0,0,0}, {10574,10506,10559 ,5782,5709,5767 ,0,0,0}, + {10505,10559,10506 ,5708,5767,5709 ,0,0,0}, {10580,10077,10092 ,5788,5719,5792 ,0,0,0}, + {10078,10504,10506 ,5718,5707,5709 ,0,0,0}, {10581,10092,10095 ,5789,5792,5793 ,0,0,0}, + {10077,10580,10504 ,5719,5788,5707 ,0,0,0}, {10582,10095,10096 ,5790,5793,5794 ,0,0,0}, + {10092,10581,10580 ,5792,5789,5788 ,0,0,0}, {10583,10096,10135 ,5791,5794,5795 ,0,0,0}, + {10095,10582,10581 ,5793,5790,5789 ,0,0,0}, {10578,10135,10076 ,5786,5795,5796 ,0,0,0}, + {10096,10583,10582 ,5794,5791,5790 ,0,0,0}, {10539,10076,10101 ,5745,5796,5747 ,0,0,0}, + {10135,10578,10583 ,5795,5786,5791 ,0,0,0}, {10101,10537,10539 ,5747,5743,5745 ,0,0,0}, + {10076,10539,10578 ,5796,5745,5786 ,0,0,0}, {10584,10585,10586 ,5797,5798,5799 ,0,0,0}, + {10587,9501,9502 ,5800,5801,5802 ,0,0,0}, {10586,10588,10589 ,5799,5803,5804 ,0,0,0}, + {10588,10590,10589 ,5803,5805,5804 ,0,0,0}, {10591,10592,10593 ,5806,5807,5808 ,0,0,0}, + {10593,10594,10591 ,5808,5809,5806 ,0,0,0}, {10595,10596,10597 ,5810,5811,5812 ,0,0,0}, + {10598,10592,9507 ,5813,5807,5814 ,0,0,0}, {10598,10593,10592 ,5813,5808,5807 ,0,0,0}, + {9507,9508,10598 ,5814,5815,5813 ,0,0,0}, {10599,9502,9505 ,5816,5802,5817 ,0,0,0}, + {10600,10601,10602 ,5818,5819,5820 ,0,0,0}, {10595,10034,10033 ,5810,5821,5822 ,0,0,0}, + {10603,10604,10605 ,5823,5824,5825 ,0,0,0}, {10606,10041,10597 ,5826,5827,5812 ,0,0,0}, + {10607,10608,10601 ,5828,5829,5819 ,0,0,0}, {10034,10597,10041 ,5821,5812,5827 ,0,0,0}, + {10609,10610,10611 ,5830,5831,5832 ,0,0,0}, {10612,10589,10590 ,5833,5804,5805 ,0,0,0}, + {10613,10614,10615 ,5834,5835,5836 ,0,0,0}, {10616,10617,10586 ,5837,5838,5799 ,0,0,0}, + {10618,10619,10620 ,5839,5840,5841 ,0,0,0}, {10611,10621,10622 ,5832,5842,5843 ,0,0,0}, + {10623,10621,10624 ,5844,5842,5845 ,0,0,0}, {10625,10626,10627 ,5846,5847,5848 ,0,0,0}, + {10584,9501,10587 ,5797,5801,5800 ,0,0,0}, {10626,10613,10627 ,5847,5834,5848 ,0,0,0}, + {10617,9499,10584 ,5838,5849,5797 ,0,0,0}, {10057,10064,10625 ,5850,5851,5846 ,0,0,0}, + {10628,9497,10617 ,5852,5853,5838 ,0,0,0}, {9499,9501,10584 ,5849,5801,5797 ,0,0,0}, + {10628,10629,9494 ,5852,5854,5855 ,0,0,0}, {10617,9497,9499 ,5838,5853,5849 ,0,0,0}, + {9492,10630,9493 ,5856,5857,5858 ,0,0,0}, {9497,10628,9494 ,5853,5852,5855 ,0,0,0}, + {9487,9493,10631 ,5067,5858,5859 ,0,0,0}, {10630,9492,10629 ,5857,5856,5854 ,0,0,0}, + {9505,10592,10599 ,5817,5807,5816 ,0,0,0}, {10592,9505,9507 ,5807,5817,5814 ,0,0,0}, + {10594,10632,10591 ,5809,5860,5806 ,0,0,0}, {10599,10587,9502 ,5816,5800,5802 ,0,0,0}, + {10633,10599,10591 ,5861,5816,5806 ,0,0,0}, {10586,10585,10588 ,5799,5798,5803 ,0,0,0}, + {10633,10585,10587 ,5861,5798,5800 ,0,0,0}, {10628,10634,10629 ,5852,5862,5854 ,0,0,0}, + {10587,10585,10584 ,5800,5798,5797 ,0,0,0}, {10635,10636,10630 ,5863,5864,5857 ,0,0,0}, + {10617,10584,10586 ,5838,5797,5799 ,0,0,0}, {10634,10628,10616 ,5862,5852,5837 ,0,0,0}, + {9493,10630,10631 ,5858,5857,5859 ,0,0,0}, {9494,10629,9492 ,5855,5854,5856 ,0,0,0}, + {10629,10634,10635 ,5854,5862,5863 ,0,0,0}, {10637,10631,10630 ,5865,5859,5857 ,0,0,0}, + {10592,10591,10599 ,5807,5806,5816 ,0,0,0}, {10638,10632,10594 ,5866,5860,5809 ,0,0,0}, + {10638,10607,10632 ,5866,5828,5860 ,0,0,0}, {10599,10633,10587 ,5816,5861,5800 ,0,0,0}, + {10632,10639,10633 ,5860,5867,5861 ,0,0,0}, {10589,10624,10616 ,5804,5845,5837 ,0,0,0}, + {10639,10588,10585 ,5867,5803,5798 ,0,0,0}, {10611,10636,10635 ,5832,5864,5863 ,0,0,0}, + {10610,10636,10611 ,5831,5864,5832 ,0,0,0}, {10617,10616,10628 ,5838,5837,5852 ,0,0,0}, + {10586,10589,10616 ,5799,5804,5837 ,0,0,0}, {10629,10635,10630 ,5854,5863,5857 ,0,0,0}, + {10624,10621,10634 ,5845,5842,5862 ,0,0,0}, {10630,10636,10637 ,5857,5864,5865 ,0,0,0}, + {10635,10621,10611 ,5863,5842,5832 ,0,0,0}, {10640,10637,10636 ,5868,5865,5864 ,0,0,0}, + {10591,10632,10633 ,5806,5860,5861 ,0,0,0}, {10608,10607,10638 ,5829,5828,5866 ,0,0,0}, + {10641,10600,10642 ,5869,5818,5870 ,0,0,0}, {10633,10639,10585 ,5861,5867,5798 ,0,0,0}, + {10643,10639,10607 ,5871,5867,5828 ,0,0,0}, {10624,10589,10612 ,5845,5804,5833 ,0,0,0}, + {10643,10590,10588 ,5871,5805,5803 ,0,0,0}, {10644,10609,10622 ,5872,5830,5843 ,0,0,0}, + {10634,10621,10635 ,5862,5842,5863 ,0,0,0}, {10616,10624,10634 ,5837,5845,5862 ,0,0,0}, + {10624,10612,10623 ,5845,5833,5844 ,0,0,0}, {10610,10609,10645 ,5831,5830,5873 ,0,0,0}, + {10623,10622,10621 ,5844,5843,5842 ,0,0,0}, {10636,10610,10640 ,5864,5831,5868 ,0,0,0}, + {10611,10622,10609 ,5832,5843,5830 ,0,0,0}, {10646,10640,10610 ,5874,5868,5831 ,0,0,0}, + {10632,10607,10639 ,5860,5828,5867 ,0,0,0}, {10602,10601,10608 ,5820,5819,5829 ,0,0,0}, + {10590,10647,10612 ,5805,5875,5833 ,0,0,0}, {10639,10643,10588 ,5867,5871,5803 ,0,0,0}, + {10648,10643,10601 ,5876,5871,5819 ,0,0,0}, {10612,10649,10623 ,5833,5877,5844 ,0,0,0}, + {10648,10647,10590 ,5876,5875,5805 ,0,0,0}, {10623,10650,10622 ,5844,5878,5843 ,0,0,0}, + {10649,10612,10647 ,5877,5833,5875 ,0,0,0}, {10609,10619,10645 ,5830,5840,5873 ,0,0,0}, + {10650,10623,10649 ,5878,5844,5877 ,0,0,0}, {10651,10645,10618 ,5879,5873,5839 ,0,0,0}, + {10644,10622,10650 ,5872,5843,5878 ,0,0,0}, {10610,10645,10646 ,5831,5873,5874 ,0,0,0}, + {10609,10644,10619 ,5830,5872,5840 ,0,0,0}, {10651,10646,10645 ,5879,5874,5873 ,0,0,0}, + {10607,10601,10643 ,5828,5819,5871 ,0,0,0}, {10642,10600,10602 ,5870,5818,5820 ,0,0,0}, + {10647,10604,10649 ,5875,5824,5877 ,0,0,0}, {10643,10648,10590 ,5871,5876,5805 ,0,0,0}, + {10600,10652,10648 ,5818,5880,5876 ,0,0,0}, {10649,10603,10650 ,5877,5823,5878 ,0,0,0}, + {10652,10604,10647 ,5880,5824,5875 ,0,0,0}, {10650,10653,10644 ,5878,5881,5872 ,0,0,0}, + {10604,10603,10649 ,5824,5823,5877 ,0,0,0}, {10654,10619,10644 ,5882,5840,5872 ,0,0,0}, + {10653,10650,10603 ,5881,5878,5823 ,0,0,0}, {10655,10618,10615 ,5883,5839,5836 ,0,0,0}, + {10644,10653,10654 ,5872,5881,5882 ,0,0,0}, {10654,10620,10619 ,5882,5841,5840 ,0,0,0}, + {10651,10618,10655 ,5879,5839,5883 ,0,0,0}, {10645,10619,10618 ,5873,5840,5839 ,0,0,0}, + {10601,10600,10648 ,5819,5818,5876 ,0,0,0}, {10656,10641,10642 ,5884,5869,5870 ,0,0,0}, + {10657,10653,10603 ,5885,5881,5823 ,0,0,0}, {10648,10652,10647 ,5876,5880,5875 ,0,0,0}, + {10641,10596,10652 ,5869,5811,5880 ,0,0,0}, {10658,10654,10653 ,5886,5882,5881 ,0,0,0}, + {10596,10605,10604 ,5811,5825,5824 ,0,0,0}, {10659,10620,10654 ,5887,5841,5882 ,0,0,0}, + {10605,10657,10603 ,5825,5885,5823 ,0,0,0}, {10627,10613,10660 ,5848,5834,5888 ,0,0,0}, + {10657,10658,10653 ,5885,5886,5881 ,0,0,0}, {10615,10620,10661 ,5836,5841,5889 ,0,0,0}, + {10659,10654,10658 ,5887,5882,5886 ,0,0,0}, {10661,10620,10659 ,5889,5841,5887 ,0,0,0}, + {10655,10615,10614 ,5883,5836,5835 ,0,0,0}, {10618,10620,10615 ,5839,5841,5836 ,0,0,0}, + {10600,10641,10652 ,5818,5869,5880 ,0,0,0}, {10597,10656,10606 ,5812,5884,5826 ,0,0,0}, + {10595,10662,10605 ,5810,5890,5825 ,0,0,0}, {10652,10596,10604 ,5880,5811,5824 ,0,0,0}, + {10595,10605,10596 ,5810,5825,5811 ,0,0,0}, {10662,10663,10657 ,5890,5891,5885 ,0,0,0}, + {10662,10657,10605 ,5890,5885,5825 ,0,0,0}, {10663,10664,10658 ,5891,5892,5886 ,0,0,0}, + {10663,10658,10657 ,5891,5886,5885 ,0,0,0}, {10664,10665,10659 ,5892,5893,5887 ,0,0,0}, + {10664,10659,10658 ,5892,5887,5886 ,0,0,0}, {10665,10660,10661 ,5893,5888,5889 ,0,0,0}, + {10661,10659,10665 ,5889,5887,5893 ,0,0,0}, {10660,10613,10661 ,5888,5834,5889 ,0,0,0}, + {10614,10613,10626 ,5835,5834,5847 ,0,0,0}, {10615,10661,10613 ,5836,5889,5834 ,0,0,0}, + {10656,10597,10641 ,5884,5812,5869 ,0,0,0}, {10596,10641,10597 ,5811,5869,5812 ,0,0,0}, + {10662,10033,10051 ,5890,5822,5894 ,0,0,0}, {10034,10595,10597 ,5821,5810,5812 ,0,0,0}, + {10663,10051,10052 ,5891,5894,5895 ,0,0,0}, {10033,10662,10595 ,5822,5890,5810 ,0,0,0}, + {10664,10052,10054 ,5892,5895,5896 ,0,0,0}, {10051,10663,10662 ,5894,5891,5890 ,0,0,0}, + {10665,10054,10037 ,5893,5896,5897 ,0,0,0}, {10052,10664,10663 ,5895,5892,5891 ,0,0,0}, + {10660,10037,10058 ,5888,5897,5898 ,0,0,0}, {10054,10665,10664 ,5896,5893,5892 ,0,0,0}, + {10627,10058,10057 ,5848,5898,5850 ,0,0,0}, {10037,10660,10665 ,5897,5888,5893 ,0,0,0}, + {10057,10625,10627 ,5850,5846,5848 ,0,0,0}, {10058,10627,10660 ,5898,5848,5888 ,0,0,0}, + {10666,10667,10668 ,5899,5900,5901 ,0,0,0}, {10669,10670,9470 ,5902,5903,5904 ,0,0,0}, + {10667,10671,10668 ,5900,5905,5901 ,0,0,0}, {9465,9470,10670 ,5906,5904,5903 ,0,0,0}, + {10672,10673,10674 ,5907,5908,5909 ,0,0,0}, {9475,10675,10673 ,5910,5911,5908 ,0,0,0}, + {10676,10677,10678 ,5912,5913,5914 ,0,0,0}, {9473,10675,9475 ,5915,5911,5910 ,0,0,0}, + {10675,10674,10673 ,5911,5909,5908 ,0,0,0}, {9469,10673,10669 ,5916,5908,5902 ,0,0,0}, + {10679,10680,10681 ,5917,5918,5919 ,0,0,0}, {10682,10683,10684 ,5920,5921,5922 ,0,0,0}, + {10685,10680,10686 ,5923,5918,5924 ,0,0,0}, {10687,10688,10666 ,5925,5926,5899 ,0,0,0}, + {10677,9984,9903 ,5913,5927,5928 ,0,0,0}, {10689,10690,10691 ,5929,5930,5931 ,0,0,0}, + {10692,10014,10676 ,5932,5933,5912 ,0,0,0}, {9984,10676,10014 ,5927,5912,5933 ,0,0,0}, + {10693,10694,10695 ,5934,5935,5936 ,0,0,0}, {10671,10696,10668 ,5905,5937,5901 ,0,0,0}, + {10697,10698,10699 ,5938,5939,5940 ,0,0,0}, {10700,10701,10702 ,5941,5942,5943 ,0,0,0}, + {10691,10694,10703 ,5931,5935,5944 ,0,0,0}, {10704,10705,10706 ,5945,5946,5947 ,0,0,0}, + {10707,10666,10708 ,5948,5899,5949 ,0,0,0}, {10705,10700,10706 ,5946,5941,5947 ,0,0,0}, + {10687,9465,10670 ,5925,5906,5903 ,0,0,0}, {10013,10017,10704 ,5950,5951,5945 ,0,0,0}, + {9465,10687,9463 ,5906,5925,5952 ,0,0,0}, {9463,10687,10707 ,5952,5925,5948 ,0,0,0}, + {10709,9458,10707 ,5953,5954,5948 ,0,0,0}, {10687,10670,10688 ,5925,5903,5926 ,0,0,0}, + {10709,10710,9462 ,5953,5955,5956 ,0,0,0}, {9462,9458,10709 ,5956,5954,5953 ,0,0,0}, + {9454,10711,9456 ,5957,5958,5959 ,0,0,0}, {10711,9454,10710 ,5958,5957,5955 ,0,0,0}, + {9475,10673,9469 ,5910,5908,5916 ,0,0,0}, {10712,10672,10674 ,5960,5907,5909 ,0,0,0}, + {10712,10713,10672 ,5960,5961,5907 ,0,0,0}, {9469,10669,9470 ,5916,5902,5904 ,0,0,0}, + {10714,10669,10672 ,5962,5902,5907 ,0,0,0}, {10666,10688,10667 ,5899,5926,5900 ,0,0,0}, + {10714,10688,10670 ,5962,5926,5903 ,0,0,0}, {10709,10715,10710 ,5953,5963,5955 ,0,0,0}, + {10716,10711,10717 ,5964,5958,5965 ,0,0,0}, {9463,10707,9458 ,5952,5948,5954 ,0,0,0}, + {10707,10687,10666 ,5948,5925,5899 ,0,0,0}, {9462,10710,9454 ,5956,5955,5957 ,0,0,0}, + {10708,10715,10709 ,5949,5963,5953 ,0,0,0}, {10711,10718,9456 ,5958,5966,5959 ,0,0,0}, + {10710,10715,10717 ,5955,5963,5965 ,0,0,0}, {10719,10718,10711 ,5967,5966,5958 ,0,0,0}, + {10673,10672,10669 ,5908,5907,5902 ,0,0,0}, {10720,10713,10712 ,5968,5961,5960 ,0,0,0}, + {10720,10681,10713 ,5968,5919,5961 ,0,0,0}, {10669,10714,10670 ,5902,5962,5903 ,0,0,0}, + {10713,10721,10714 ,5961,5969,5962 ,0,0,0}, {10668,10695,10708 ,5901,5936,5949 ,0,0,0}, + {10721,10667,10688 ,5969,5900,5926 ,0,0,0}, {10691,10716,10717 ,5931,5964,5965 ,0,0,0}, + {10690,10716,10691 ,5930,5964,5931 ,0,0,0}, {10707,10708,10709 ,5948,5949,5953 ,0,0,0}, + {10666,10668,10708 ,5899,5901,5949 ,0,0,0}, {10710,10717,10711 ,5955,5965,5958 ,0,0,0}, + {10695,10694,10715 ,5936,5935,5963 ,0,0,0}, {10711,10716,10719 ,5958,5964,5967 ,0,0,0}, + {10717,10694,10691 ,5965,5935,5931 ,0,0,0}, {10722,10719,10716 ,5970,5967,5964 ,0,0,0}, + {10672,10713,10714 ,5907,5961,5962 ,0,0,0}, {10679,10681,10720 ,5917,5919,5968 ,0,0,0}, + {10723,10685,10724 ,5971,5923,5972 ,0,0,0}, {10714,10721,10688 ,5962,5969,5926 ,0,0,0}, + {10725,10721,10681 ,5973,5969,5919 ,0,0,0}, {10695,10668,10696 ,5936,5901,5937 ,0,0,0}, + {10725,10671,10667 ,5973,5905,5900 ,0,0,0}, {10726,10689,10703 ,5974,5929,5944 ,0,0,0}, + {10715,10694,10717 ,5963,5935,5965 ,0,0,0}, {10708,10695,10715 ,5949,5936,5963 ,0,0,0}, + {10695,10696,10693 ,5936,5937,5934 ,0,0,0}, {10690,10689,10727 ,5930,5929,5975 ,0,0,0}, + {10693,10703,10694 ,5934,5944,5935 ,0,0,0}, {10716,10690,10722 ,5964,5930,5970 ,0,0,0}, + {10691,10703,10689 ,5931,5944,5929 ,0,0,0}, {10728,10722,10690 ,5976,5970,5930 ,0,0,0}, + {10713,10681,10721 ,5961,5919,5969 ,0,0,0}, {10686,10680,10679 ,5924,5918,5917 ,0,0,0}, + {10671,10729,10696 ,5905,5977,5937 ,0,0,0}, {10721,10725,10667 ,5969,5973,5900 ,0,0,0}, + {10730,10725,10680 ,5978,5973,5918 ,0,0,0}, {10696,10731,10693 ,5937,5979,5934 ,0,0,0}, + {10730,10729,10671 ,5978,5977,5905 ,0,0,0}, {10693,10732,10703 ,5934,5980,5944 ,0,0,0}, + {10731,10696,10729 ,5979,5937,5977 ,0,0,0}, {10689,10698,10727 ,5929,5939,5975 ,0,0,0}, + {10732,10693,10731 ,5980,5934,5979 ,0,0,0}, {10733,10727,10697 ,5981,5975,5938 ,0,0,0}, + {10726,10703,10732 ,5974,5944,5980 ,0,0,0}, {10690,10727,10728 ,5930,5975,5976 ,0,0,0}, + {10689,10726,10698 ,5929,5974,5939 ,0,0,0}, {10733,10728,10727 ,5981,5976,5975 ,0,0,0}, + {10681,10680,10725 ,5919,5918,5973 ,0,0,0}, {10724,10685,10686 ,5972,5923,5924 ,0,0,0}, + {10729,10682,10731 ,5977,5920,5979 ,0,0,0}, {10725,10730,10671 ,5973,5978,5905 ,0,0,0}, + {10685,10734,10730 ,5923,5982,5978 ,0,0,0}, {10731,10684,10732 ,5979,5922,5980 ,0,0,0}, + {10734,10682,10729 ,5982,5920,5977 ,0,0,0}, {10732,10735,10726 ,5980,5983,5974 ,0,0,0}, + {10682,10684,10731 ,5920,5922,5979 ,0,0,0}, {10736,10698,10726 ,5984,5939,5974 ,0,0,0}, + {10735,10732,10684 ,5983,5980,5922 ,0,0,0}, {10737,10697,10702 ,5985,5938,5943 ,0,0,0}, + {10726,10735,10736 ,5974,5983,5984 ,0,0,0}, {10736,10699,10698 ,5984,5940,5939 ,0,0,0}, + {10733,10697,10737 ,5981,5938,5985 ,0,0,0}, {10727,10698,10697 ,5975,5939,5938 ,0,0,0}, + {10680,10685,10730 ,5918,5923,5978 ,0,0,0}, {10738,10723,10724 ,5986,5971,5972 ,0,0,0}, + {10739,10735,10684 ,5987,5983,5922 ,0,0,0}, {10730,10734,10729 ,5978,5982,5977 ,0,0,0}, + {10723,10678,10734 ,5971,5914,5982 ,0,0,0}, {10740,10736,10735 ,5988,5984,5983 ,0,0,0}, + {10678,10683,10682 ,5914,5921,5920 ,0,0,0}, {10741,10699,10736 ,5989,5940,5984 ,0,0,0}, + {10683,10739,10684 ,5921,5987,5922 ,0,0,0}, {10706,10700,10742 ,5947,5941,5990 ,0,0,0}, + {10739,10740,10735 ,5987,5988,5983 ,0,0,0}, {10702,10699,10743 ,5943,5940,5991 ,0,0,0}, + {10741,10736,10740 ,5989,5984,5988 ,0,0,0}, {10743,10699,10741 ,5991,5940,5989 ,0,0,0}, + {10737,10702,10701 ,5985,5943,5942 ,0,0,0}, {10697,10699,10702 ,5938,5940,5943 ,0,0,0}, + {10685,10723,10734 ,5923,5971,5982 ,0,0,0}, {10676,10738,10692 ,5912,5986,5932 ,0,0,0}, + {10677,10744,10683 ,5913,5992,5921 ,0,0,0}, {10734,10678,10682 ,5982,5914,5920 ,0,0,0}, + {10677,10683,10678 ,5913,5921,5914 ,0,0,0}, {10744,10745,10739 ,5992,5993,5987 ,0,0,0}, + {10744,10739,10683 ,5992,5987,5921 ,0,0,0}, {10745,10746,10740 ,5993,5994,5988 ,0,0,0}, + {10745,10740,10739 ,5993,5988,5987 ,0,0,0}, {10746,10747,10741 ,5994,5995,5989 ,0,0,0}, + {10746,10741,10740 ,5994,5989,5988 ,0,0,0}, {10747,10742,10743 ,5995,5990,5991 ,0,0,0}, + {10743,10741,10747 ,5991,5989,5995 ,0,0,0}, {10742,10700,10743 ,5990,5941,5991 ,0,0,0}, + {10701,10700,10705 ,5942,5941,5946 ,0,0,0}, {10702,10743,10700 ,5943,5991,5941 ,0,0,0}, + {10738,10676,10723 ,5986,5912,5971 ,0,0,0}, {10678,10723,10676 ,5914,5971,5912 ,0,0,0}, + {10744,9903,10003 ,5992,5928,5996 ,0,0,0}, {9984,10677,10676 ,5927,5913,5912 ,0,0,0}, + {10745,10003,10208 ,5993,5996,5997 ,0,0,0}, {9903,10744,10677 ,5928,5992,5913 ,0,0,0}, + {10746,10208,10010 ,5994,5997,5998 ,0,0,0}, {10003,10745,10744 ,5996,5993,5992 ,0,0,0}, + {10747,10010,10021 ,5995,5998,5999 ,0,0,0}, {10208,10746,10745 ,5997,5994,5993 ,0,0,0}, + {10742,10021,10007 ,5990,5999,6000 ,0,0,0}, {10010,10747,10746 ,5998,5995,5994 ,0,0,0}, + {10706,10007,10013 ,5947,6000,5950 ,0,0,0}, {10021,10742,10747 ,5999,5990,5995 ,0,0,0}, + {10013,10704,10706 ,5950,5945,5947 ,0,0,0}, {10007,10706,10742 ,6000,5947,5990 ,0,0,0}, + {10748,10749,10750 ,6001,6002,6003 ,0,0,0}, {10751,9438,9435 ,6004,6005,6006 ,0,0,0}, + {10750,10752,10753 ,6003,6007,6008 ,0,0,0}, {10752,10754,10753 ,6007,6009,6008 ,0,0,0}, + {10755,10756,10757 ,6010,6011,6012 ,0,0,0}, {10757,10758,10755 ,6012,6013,6010 ,0,0,0}, + {10759,10760,10761 ,6014,6015,6016 ,0,0,0}, {10762,10756,9441 ,6017,6011,6018 ,0,0,0}, + {10762,10757,10756 ,6017,6012,6011 ,0,0,0}, {9441,9440,10762 ,6018,5020,6017 ,0,0,0}, + {10763,9435,9443 ,6019,6006,6020 ,0,0,0}, {10764,10765,10766 ,6021,6022,6023 ,0,0,0}, + {10759,9958,9974 ,6014,6024,6025 ,0,0,0}, {10767,10768,10769 ,6026,6027,6028 ,0,0,0}, + {10770,9961,10761 ,6029,6030,6016 ,0,0,0}, {10771,10772,10765 ,6031,6032,6022 ,0,0,0}, + {9958,10761,9961 ,6024,6016,6030 ,0,0,0}, {10773,10774,10775 ,6033,6034,6035 ,0,0,0}, + {10776,10753,10754 ,6036,6008,6009 ,0,0,0}, {10777,10778,10779 ,6037,6038,6039 ,0,0,0}, + {10780,10781,10750 ,6040,6041,6003 ,0,0,0}, {10782,10783,10784 ,6042,6043,6044 ,0,0,0}, + {10775,10785,10786 ,6035,6045,6046 ,0,0,0}, {10787,10785,10788 ,6047,6045,6048 ,0,0,0}, + {10789,10790,10791 ,6049,6050,6051 ,0,0,0}, {10748,9438,10751 ,6001,6005,6004 ,0,0,0}, + {10790,10777,10791 ,6050,6037,6051 ,0,0,0}, {10781,9427,10748 ,6041,6052,6001 ,0,0,0}, + {9977,9979,10789 ,6053,6054,6049 ,0,0,0}, {10792,9428,10781 ,6055,6056,6041 ,0,0,0}, + {9427,9438,10748 ,6052,6005,6001 ,0,0,0}, {10792,10793,9430 ,6055,6057,6058 ,0,0,0}, + {10781,9428,9427 ,6041,6056,6052 ,0,0,0}, {9424,10794,9425 ,6059,6060,6061 ,0,0,0}, + {9428,10792,9430 ,6056,6055,6058 ,0,0,0}, {9416,9425,10795 ,6062,6061,6063 ,0,0,0}, + {10794,9424,10793 ,6060,6059,6057 ,0,0,0}, {9443,10756,10763 ,6020,6011,6019 ,0,0,0}, + {10756,9443,9441 ,6011,6020,6018 ,0,0,0}, {10758,10796,10755 ,6013,6064,6010 ,0,0,0}, + {10763,10751,9435 ,6019,6004,6006 ,0,0,0}, {10797,10763,10755 ,6065,6019,6010 ,0,0,0}, + {10750,10749,10752 ,6003,6002,6007 ,0,0,0}, {10797,10749,10751 ,6065,6002,6004 ,0,0,0}, + {10792,10798,10793 ,6055,6066,6057 ,0,0,0}, {10751,10749,10748 ,6004,6002,6001 ,0,0,0}, + {10799,10800,10794 ,6067,6068,6060 ,0,0,0}, {10781,10748,10750 ,6041,6001,6003 ,0,0,0}, + {10798,10792,10780 ,6066,6055,6040 ,0,0,0}, {9425,10794,10795 ,6061,6060,6063 ,0,0,0}, + {9430,10793,9424 ,6058,6057,6059 ,0,0,0}, {10793,10798,10799 ,6057,6066,6067 ,0,0,0}, + {10801,10795,10794 ,6069,6063,6060 ,0,0,0}, {10756,10755,10763 ,6011,6010,6019 ,0,0,0}, + {10802,10796,10758 ,6070,6064,6013 ,0,0,0}, {10802,10771,10796 ,6070,6031,6064 ,0,0,0}, + {10763,10797,10751 ,6019,6065,6004 ,0,0,0}, {10796,10803,10797 ,6064,6071,6065 ,0,0,0}, + {10753,10788,10780 ,6008,6048,6040 ,0,0,0}, {10803,10752,10749 ,6071,6007,6002 ,0,0,0}, + {10775,10800,10799 ,6035,6068,6067 ,0,0,0}, {10774,10800,10775 ,6034,6068,6035 ,0,0,0}, + {10781,10780,10792 ,6041,6040,6055 ,0,0,0}, {10750,10753,10780 ,6003,6008,6040 ,0,0,0}, + {10793,10799,10794 ,6057,6067,6060 ,0,0,0}, {10788,10785,10798 ,6048,6045,6066 ,0,0,0}, + {10794,10800,10801 ,6060,6068,6069 ,0,0,0}, {10799,10785,10775 ,6067,6045,6035 ,0,0,0}, + {10804,10801,10800 ,6072,6069,6068 ,0,0,0}, {10755,10796,10797 ,6010,6064,6065 ,0,0,0}, + {10772,10771,10802 ,6032,6031,6070 ,0,0,0}, {10805,10764,10806 ,6073,6021,6074 ,0,0,0}, + {10797,10803,10749 ,6065,6071,6002 ,0,0,0}, {10807,10803,10771 ,6075,6071,6031 ,0,0,0}, + {10788,10753,10776 ,6048,6008,6036 ,0,0,0}, {10807,10754,10752 ,6075,6009,6007 ,0,0,0}, + {10808,10773,10786 ,6076,6033,6046 ,0,0,0}, {10798,10785,10799 ,6066,6045,6067 ,0,0,0}, + {10780,10788,10798 ,6040,6048,6066 ,0,0,0}, {10788,10776,10787 ,6048,6036,6047 ,0,0,0}, + {10774,10773,10809 ,6034,6033,6077 ,0,0,0}, {10787,10786,10785 ,6047,6046,6045 ,0,0,0}, + {10800,10774,10804 ,6068,6034,6072 ,0,0,0}, {10775,10786,10773 ,6035,6046,6033 ,0,0,0}, + {10810,10804,10774 ,6078,6072,6034 ,0,0,0}, {10796,10771,10803 ,6064,6031,6071 ,0,0,0}, + {10766,10765,10772 ,6023,6022,6032 ,0,0,0}, {10754,10811,10776 ,6009,6079,6036 ,0,0,0}, + {10803,10807,10752 ,6071,6075,6007 ,0,0,0}, {10812,10807,10765 ,6080,6075,6022 ,0,0,0}, + {10776,10813,10787 ,6036,6081,6047 ,0,0,0}, {10812,10811,10754 ,6080,6079,6009 ,0,0,0}, + {10787,10814,10786 ,6047,6082,6046 ,0,0,0}, {10813,10776,10811 ,6081,6036,6079 ,0,0,0}, + {10773,10783,10809 ,6033,6043,6077 ,0,0,0}, {10814,10787,10813 ,6082,6047,6081 ,0,0,0}, + {10815,10809,10782 ,6083,6077,6042 ,0,0,0}, {10808,10786,10814 ,6076,6046,6082 ,0,0,0}, + {10774,10809,10810 ,6034,6077,6078 ,0,0,0}, {10773,10808,10783 ,6033,6076,6043 ,0,0,0}, + {10815,10810,10809 ,6083,6078,6077 ,0,0,0}, {10771,10765,10807 ,6031,6022,6075 ,0,0,0}, + {10806,10764,10766 ,6074,6021,6023 ,0,0,0}, {10811,10768,10813 ,6079,6027,6081 ,0,0,0}, + {10807,10812,10754 ,6075,6080,6009 ,0,0,0}, {10764,10816,10812 ,6021,6084,6080 ,0,0,0}, + {10813,10767,10814 ,6081,6026,6082 ,0,0,0}, {10816,10768,10811 ,6084,6027,6079 ,0,0,0}, + {10814,10817,10808 ,6082,6085,6076 ,0,0,0}, {10768,10767,10813 ,6027,6026,6081 ,0,0,0}, + {10818,10783,10808 ,6086,6043,6076 ,0,0,0}, {10817,10814,10767 ,6085,6082,6026 ,0,0,0}, + {10819,10782,10779 ,6087,6042,6039 ,0,0,0}, {10808,10817,10818 ,6076,6085,6086 ,0,0,0}, + {10818,10784,10783 ,6086,6044,6043 ,0,0,0}, {10815,10782,10819 ,6083,6042,6087 ,0,0,0}, + {10809,10783,10782 ,6077,6043,6042 ,0,0,0}, {10765,10764,10812 ,6022,6021,6080 ,0,0,0}, + {10820,10805,10806 ,6088,6073,6074 ,0,0,0}, {10821,10817,10767 ,6089,6085,6026 ,0,0,0}, + {10812,10816,10811 ,6080,6084,6079 ,0,0,0}, {10805,10760,10816 ,6073,6015,6084 ,0,0,0}, + {10822,10818,10817 ,6090,6086,6085 ,0,0,0}, {10760,10769,10768 ,6015,6028,6027 ,0,0,0}, + {10823,10784,10818 ,6091,6044,6086 ,0,0,0}, {10769,10821,10767 ,6028,6089,6026 ,0,0,0}, + {10791,10777,10824 ,6051,6037,6092 ,0,0,0}, {10821,10822,10817 ,6089,6090,6085 ,0,0,0}, + {10779,10784,10825 ,6039,6044,6093 ,0,0,0}, {10823,10818,10822 ,6091,6086,6090 ,0,0,0}, + {10825,10784,10823 ,6093,6044,6091 ,0,0,0}, {10819,10779,10778 ,6087,6039,6038 ,0,0,0}, + {10782,10784,10779 ,6042,6044,6039 ,0,0,0}, {10764,10805,10816 ,6021,6073,6084 ,0,0,0}, + {10761,10820,10770 ,6016,6088,6029 ,0,0,0}, {10759,10826,10769 ,6014,6094,6028 ,0,0,0}, + {10816,10760,10768 ,6084,6015,6027 ,0,0,0}, {10759,10769,10760 ,6014,6028,6015 ,0,0,0}, + {10826,10827,10821 ,6094,6095,6089 ,0,0,0}, {10826,10821,10769 ,6094,6089,6028 ,0,0,0}, + {10827,10828,10822 ,6095,6096,6090 ,0,0,0}, {10827,10822,10821 ,6095,6090,6089 ,0,0,0}, + {10828,10829,10823 ,6096,6097,6091 ,0,0,0}, {10828,10823,10822 ,6096,6091,6090 ,0,0,0}, + {10829,10824,10825 ,6097,6092,6093 ,0,0,0}, {10825,10823,10829 ,6093,6091,6097 ,0,0,0}, + {10824,10777,10825 ,6092,6037,6093 ,0,0,0}, {10778,10777,10790 ,6038,6037,6050 ,0,0,0}, + {10779,10825,10777 ,6039,6093,6037 ,0,0,0}, {10820,10761,10805 ,6088,6016,6073 ,0,0,0}, + {10760,10805,10761 ,6015,6073,6016 ,0,0,0}, {10826,9974,9968 ,6094,6025,6098 ,0,0,0}, + {9958,10759,10761 ,6024,6014,6016 ,0,0,0}, {10827,9968,9972 ,6095,6098,6099 ,0,0,0}, + {9974,10826,10759 ,6025,6094,6014 ,0,0,0}, {10828,9972,9971 ,6096,6099,6100 ,0,0,0}, + {9968,10827,10826 ,6098,6095,6094 ,0,0,0}, {10829,9971,9981 ,6097,6100,6101 ,0,0,0}, + {9972,10828,10827 ,6099,6096,6095 ,0,0,0}, {10824,9981,9943 ,6092,6101,6102 ,0,0,0}, + {9971,10829,10828 ,6100,6097,6096 ,0,0,0}, {10791,9943,9977 ,6051,6102,6053 ,0,0,0}, + {9981,10824,10829 ,6101,6092,6097 ,0,0,0}, {9977,10789,10791 ,6053,6049,6051 ,0,0,0}, + {9943,10791,10824 ,6102,6051,6092 ,0,0,0}, {10830,10831,10832 ,730,6103,6103 ,0,0,0}, + {9060,9002,8999 ,6103,730,730 ,0,0,0}, {10833,10831,10834 ,6104,6103,6105 ,0,0,0}, + {10833,10835,10836 ,6104,6106,6103 ,0,0,0}, {10837,10832,10838 ,6107,6103,6108 ,0,0,0}, + {10835,10839,10840 ,6106,6109,6110 ,0,0,0}, {10841,10842,10838 ,6103,6111,6108 ,0,0,0}, + {10840,10843,10844 ,6110,6112,6110 ,0,0,0}, {10845,10841,10846 ,6111,6103,6103 ,0,0,0}, + {10844,10847,10848 ,6110,6113,6112 ,0,0,0}, {10848,10849,10850 ,6112,6109,6110 ,0,0,0}, + {10850,10851,10852 ,6110,6106,6114 ,0,0,0}, {10846,10853,10854 ,6103,730,6115 ,0,0,0}, + {10855,10852,10856 ,6105,6114,6104 ,0,0,0}, {10857,10858,10859 ,6111,730,6111 ,0,0,0}, + {10860,10852,10855 ,6111,6114,6105 ,0,0,0}, {10859,10861,10862 ,6111,6110,6114 ,0,0,0}, + {10863,10864,10865 ,730,6114,6108 ,0,0,0}, {9008,9073,9075 ,6110,6111,6110 ,0,0,0}, + {10866,10867,10868 ,6115,730,6111 ,0,0,0}, {9072,9007,9070 ,730,730,6114 ,0,0,0}, + {10869,10870,8991 ,6111,6110,6110 ,0,0,0}, {9003,9066,9005 ,730,6114,6103 ,0,0,0}, + {8988,9038,9035 ,730,730,6114 ,0,0,0}, {9002,9061,9064 ,730,730,6103 ,0,0,0}, + {9032,8984,9033 ,6114,730,730 ,0,0,0}, {9058,9060,8999 ,730,6103,730 ,0,0,0}, + {8982,9026,8979 ,6103,6103,730 ,0,0,0}, {9052,9054,8993 ,730,730,730 ,0,0,0}, + {9020,9017,8978 ,730,730,730 ,0,0,0}, {9046,8992,8972 ,730,730,730 ,0,0,0}, + {8976,9015,9014 ,730,730,730 ,0,0,0}, {8976,8977,9015 ,730,730,730 ,0,0,0}, + {8978,9017,8977 ,730,730,730 ,0,0,0}, {9046,8972,9010 ,730,730,730 ,0,0,0}, + {8972,8976,9011 ,730,730,730 ,0,0,0}, {9021,8979,9023 ,6103,730,730 ,0,0,0}, + {8978,8979,9021 ,730,730,6103 ,0,0,0}, {8992,9049,8993 ,730,730,730 ,0,0,0}, + {8992,9048,9049 ,730,730,730 ,0,0,0}, {8982,8984,9029 ,6103,730,6103 ,0,0,0}, + {8982,9029,9027 ,6103,6103,730 ,0,0,0}, {8999,8997,9055 ,730,730,6103 ,0,0,0}, + {9054,8997,8993 ,730,730,730 ,0,0,0}, {8988,9035,8985 ,730,6114,6103 ,0,0,0}, + {8984,8985,9033 ,730,6103,730 ,0,0,0}, {9002,9060,9061 ,730,6103,730 ,0,0,0}, + {9041,9039,8991 ,6110,6111,6110 ,0,0,0}, {8988,8991,9039 ,730,6110,6111 ,0,0,0}, + {9003,9064,9066 ,730,6103,6114 ,0,0,0}, {9002,9064,9003 ,730,6103,730 ,0,0,0}, + {10868,10871,10869 ,6111,6111,6111 ,0,0,0}, {10872,10869,10871 ,6114,6111,6111 ,0,0,0}, + {9066,9067,9005 ,6114,730,6103 ,0,0,0}, {9005,9070,9007 ,6103,6114,730 ,0,0,0}, + {9067,9070,9005 ,730,6114,6103 ,0,0,0}, {9072,9073,9007 ,730,6111,730 ,0,0,0}, + {10873,10865,10864 ,6107,6108,6114 ,0,0,0}, {9008,9007,9073 ,6110,730,6111 ,0,0,0}, + {9075,10861,9008 ,6110,6110,6110 ,0,0,0}, {10864,10860,10874 ,6114,6111,730 ,0,0,0}, + {10875,10876,10863 ,6111,6110,730 ,0,0,0}, {10876,10866,10868 ,6110,6115,6111 ,0,0,0}, + {10849,10851,10850 ,6109,6106,6110 ,0,0,0}, {9058,8999,9055 ,730,730,6103 ,0,0,0}, + {9055,8997,9054 ,6103,730,730 ,0,0,0}, {9052,8993,9049 ,730,730,730 ,0,0,0}, + {9048,8992,9046 ,730,730,730 ,0,0,0}, {9010,8972,9011 ,730,730,730 ,0,0,0}, + {9011,8976,9014 ,730,730,730 ,0,0,0}, {9015,8977,9017 ,730,730,730 ,0,0,0}, + {9020,8978,9021 ,730,730,6103 ,0,0,0}, {9023,8979,9026 ,730,730,6103 ,0,0,0}, + {9026,8982,9027 ,6103,6103,730 ,0,0,0}, {9029,8984,9032 ,6103,730,6114 ,0,0,0}, + {9033,8985,9035 ,730,6103,6114 ,0,0,0}, {9038,8988,9039 ,730,730,6111 ,0,0,0}, + {9041,8991,10870 ,6110,6110,6110 ,0,0,0}, {10870,10869,10872 ,6110,6111,6114 ,0,0,0}, + {10871,10868,10867 ,6111,6111,730 ,0,0,0}, {10866,10876,10875 ,6115,6110,6111 ,0,0,0}, + {10877,10863,10865 ,6111,730,6108 ,0,0,0}, {10863,10877,10875 ,730,6111,6111 ,0,0,0}, + {10873,10864,10874 ,6107,6114,730 ,0,0,0}, {10874,10860,10855 ,730,6111,6105 ,0,0,0}, + {10856,10852,10851 ,6104,6114,6106 ,0,0,0}, {10850,10844,10848 ,6110,6110,6112 ,0,0,0}, + {10847,10844,10843 ,6113,6110,6112 ,0,0,0}, {10843,10840,10839 ,6112,6110,6109 ,0,0,0}, + {10835,10840,10836 ,6106,6110,6103 ,0,0,0}, {10833,10836,10831 ,6104,6103,6103 ,0,0,0}, + {10830,10834,10831 ,730,6105,6103 ,0,0,0}, {10837,10830,10832 ,6107,730,6103 ,0,0,0}, + {10841,10838,10832 ,6103,6108,6103 ,0,0,0}, {10841,10845,10842 ,6103,6111,6111 ,0,0,0}, + {10846,10854,10845 ,6103,6115,6111 ,0,0,0}, {10846,10858,10853 ,6103,730,730 ,0,0,0}, + {10857,10859,10862 ,6111,6111,6114 ,0,0,0}, {10853,10858,10857 ,730,730,6111 ,0,0,0}, + {10861,10859,9008 ,6110,6111,6110 ,0,0,0}, {9044,9012,10878 ,6116,6117,6118 ,0,0,0}, + {9047,10879,10880 ,6119,6120,6121 ,0,0,0}, {10881,10882,9199 ,6122,6123,6124 ,0,0,0}, + {9289,9059,9286 ,6125,6126,6127 ,0,0,0}, {9215,9214,9626 ,6128,6129,6130 ,0,0,0}, + {9145,9148,9069 ,6131,6132,6122 ,0,0,0}, {10883,9150,10884 ,6133,6134,6135 ,0,0,0}, + {10885,10886,10887 ,6136,6137,6138 ,0,0,0}, {9016,9096,9099 ,6122,6120,6139 ,0,0,0}, + {10882,9184,9189 ,6123,6140,6141 ,0,0,0}, {10888,9267,9269 ,6139,6142,6143 ,0,0,0}, + {9539,10889,9540 ,6144,6145,6146 ,0,0,0}, {9597,10890,9590 ,6147,6148,6149 ,0,0,0}, + {9117,10891,9120 ,6150,6144,6150 ,0,0,0}, {10892,9175,9574 ,6151,6134,6152 ,0,0,0}, + {10893,9076,10894 ,6145,6153,6154 ,0,0,0}, {10892,9574,10895 ,6151,6152,6155 ,0,0,0}, + {10896,9574,9573 ,6156,6152,6157 ,0,0,0}, {10897,10898,10899 ,6158,6144,6159 ,0,0,0}, + {10900,10901,10902 ,6160,6161,6162 ,0,0,0}, {9573,10903,10896 ,6157,6163,6156 ,0,0,0}, + {10904,10905,9573 ,6158,6164,6157 ,0,0,0}, {9579,10906,10904 ,6155,6165,6158 ,0,0,0}, + {10907,9584,10908 ,6166,6167,6116 ,0,0,0}, {9579,10904,9573 ,6155,6158,6157 ,0,0,0}, + {9591,10908,9584 ,6168,6116,6167 ,0,0,0}, {10899,10887,10886 ,6159,6138,6137 ,0,0,0}, + {10909,10910,10911 ,6122,6169,6170 ,0,0,0}, {10912,9579,9577 ,6171,6155,6172 ,0,0,0}, + {9577,10913,10912 ,6172,6118,6171 ,0,0,0}, {10914,10915,9587 ,6173,6174,6175 ,0,0,0}, + {9577,9576,10913 ,6172,6176,6118 ,0,0,0}, {9576,10915,10916 ,6176,6174,6177 ,0,0,0}, + {10917,9240,9239 ,6120,6146,6154 ,0,0,0}, {9576,9587,10915 ,6176,6175,6174 ,0,0,0}, + {10914,9587,9582 ,6173,6175,6178 ,0,0,0}, {10894,9078,10918 ,6154,6120,6145 ,0,0,0}, + {10919,10920,10921 ,6177,6179,6180 ,0,0,0}, {10922,10914,9582 ,6181,6173,6178 ,0,0,0}, + {10920,10923,10909 ,6179,6182,6122 ,0,0,0}, {10897,10924,10898 ,6158,6183,6144 ,0,0,0}, + {10911,10910,10925 ,6170,6169,6184 ,0,0,0}, {9591,9590,10926 ,6168,6149,6185 ,0,0,0}, + {10927,9024,10928 ,6186,6187,6119 ,0,0,0}, {9120,10929,9121 ,6150,6144,6188 ,0,0,0}, + {10930,9542,10931 ,6145,6144,6150 ,0,0,0}, {10924,9307,10932 ,6183,6189,6190 ,0,0,0}, + {9537,10933,10934 ,6154,6120,6127 ,0,0,0}, {9274,9273,9637 ,6191,6142,6192 ,0,0,0}, + {10879,9047,9045 ,6120,6119,6122 ,0,0,0}, {9631,9205,9204 ,6193,6194,6195 ,0,0,0}, + {9276,9532,9526 ,6196,6186,6197 ,0,0,0}, {9152,9074,9071 ,6196,6134,6138 ,0,0,0}, + {10882,9303,9298 ,6123,6198,6199 ,0,0,0}, {9069,9148,9071 ,6122,6132,6138 ,0,0,0}, + {9144,9145,9068 ,6157,6131,6137 ,0,0,0}, {9144,9068,9065 ,6157,6137,6131 ,0,0,0}, + {9063,9142,9065 ,6200,6143,6131 ,0,0,0}, {9051,9262,9280 ,6117,6201,6202 ,0,0,0}, + {10885,10935,10936 ,6136,6200,6156 ,0,0,0}, {9136,10937,9131 ,6118,6203,6132 ,0,0,0}, + {10938,9138,9140 ,6133,6204,6133 ,0,0,0}, {9068,9145,9069 ,6137,6131,6122 ,0,0,0}, + {9148,9152,9071 ,6132,6196,6138 ,0,0,0}, {9138,10939,9133 ,6204,6153,6201 ,0,0,0}, + {10940,9131,10937 ,6201,6132,6203 ,0,0,0}, {9053,9051,9280 ,6187,6117,6202 ,0,0,0}, + {9065,9142,9144 ,6131,6143,6157 ,0,0,0}, {9127,9557,9559 ,6132,6144,6205 ,0,0,0}, + {9140,9292,10938 ,6133,6201,6133 ,0,0,0}, {9063,9292,9142 ,6200,6201,6143 ,0,0,0}, + {9564,9126,9559 ,6206,6116,6205 ,0,0,0}, {9158,9564,9566 ,6207,6206,6204 ,0,0,0}, + {10941,10942,9132 ,6132,6119,6207 ,0,0,0}, {9557,9127,9131 ,6144,6132,6132 ,0,0,0}, + {9126,9564,9156 ,6116,6206,6121 ,0,0,0}, {9126,9127,9559 ,6116,6132,6205 ,0,0,0}, + {9567,9162,9566 ,6208,6207,6204 ,0,0,0}, {9158,9156,9564 ,6207,6121,6206 ,0,0,0}, + {9159,9158,9566 ,6209,6207,6204 ,0,0,0}, {9567,9569,9165 ,6208,6142,6196 ,0,0,0}, + {9162,9159,9566 ,6207,6209,6204 ,0,0,0}, {9164,9162,9567 ,6133,6207,6208 ,0,0,0}, + {9567,9165,9164 ,6208,6196,6133 ,0,0,0}, {9569,9168,9165 ,6142,6134,6196 ,0,0,0}, + {9572,9170,9569 ,6148,6131,6142 ,0,0,0}, {9569,9170,9168 ,6142,6131,6134 ,0,0,0}, + {9572,9171,9170 ,6148,6205,6131 ,0,0,0}, {9171,9572,9174 ,6205,6148,6204 ,0,0,0}, + {9572,9175,9174 ,6148,6134,6204 ,0,0,0}, {10896,10895,9574 ,6156,6155,6152 ,0,0,0}, + {10912,10906,9579 ,6171,6165,6155 ,0,0,0}, {10905,10903,9573 ,6164,6163,6157 ,0,0,0}, + {10913,9576,10916 ,6118,6176,6177 ,0,0,0}, {10907,10943,9582 ,6166,6210,6178 ,0,0,0}, + {10944,9596,10945 ,6157,6190,6211 ,0,0,0}, {10922,10946,10947 ,6181,6212,6182 ,0,0,0}, + {9188,10882,9189 ,6174,6123,6141 ,0,0,0}, {10948,10949,10882 ,6213,6214,6123 ,0,0,0}, + {9634,9631,9178 ,6215,6193,6216 ,0,0,0}, {9317,9319,9179 ,6217,6218,6219 ,0,0,0}, + {9204,9178,9631 ,6195,6216,6193 ,0,0,0}, {9209,9208,9623 ,6220,6221,6222 ,0,0,0}, + {9205,9630,9208 ,6194,6223,6221 ,0,0,0}, {9626,9214,9211 ,6130,6129,6181 ,0,0,0}, + {9211,9623,9626 ,6181,6222,6130 ,0,0,0}, {9220,9627,9221 ,6224,6225,6226 ,0,0,0}, + {9217,9626,9627 ,6227,6130,6225 ,0,0,0}, {9297,10882,9298 ,6212,6123,6199 ,0,0,0}, + {9228,10950,9229 ,6203,6228,6201 ,0,0,0}, {9319,9180,9179 ,6218,6229,6219 ,0,0,0}, + {10951,10952,10953 ,6230,6231,6232 ,0,0,0}, {9319,9320,9599 ,6218,6200,6233 ,0,0,0}, + {9220,9217,9627 ,6224,6227,6225 ,0,0,0}, {9627,9223,9221 ,6225,6234,6226 ,0,0,0}, + {9217,9215,9626 ,6227,6128,6130 ,0,0,0}, {9297,9296,10882 ,6212,6235,6123 ,0,0,0}, + {9209,9623,9211 ,6220,6222,6181 ,0,0,0}, {9630,9623,9208 ,6223,6222,6221 ,0,0,0}, + {9631,9630,9205 ,6193,6223,6194 ,0,0,0}, {9180,9634,9178 ,6229,6215,6216 ,0,0,0}, + {9634,9180,9599 ,6215,6229,6233 ,0,0,0}, {10949,9304,10882 ,6214,6236,6123 ,0,0,0}, + {9307,9304,10932 ,6189,6236,6190 ,0,0,0}, {10882,10954,10955 ,6123,6170,6214 ,0,0,0}, + {9196,10882,9192 ,6237,6123,6167 ,0,0,0}, {10881,10954,10882 ,6122,6170,6123 ,0,0,0}, + {9198,10956,10957 ,6238,6180,6179 ,0,0,0}, {10958,9235,10959 ,6197,6165,6196 ,0,0,0}, + {10960,9040,10961 ,6131,6122,6132 ,0,0,0}, {9203,10962,10956 ,6239,6240,6180 ,0,0,0}, + {10963,10964,10902 ,6171,6152,6162 ,0,0,0}, {9031,10965,9030 ,6204,6208,6126 ,0,0,0}, + {10966,10925,10967 ,6241,6184,6136 ,0,0,0}, {10968,9246,9249 ,6179,6179,6202 ,0,0,0}, + {9258,10965,9257 ,6127,6208,6242 ,0,0,0}, {9383,10969,10970 ,6156,6200,6136 ,0,0,0}, + {9386,9388,10971 ,6137,6135,6133 ,0,0,0}, {10972,10973,10974 ,6207,6133,6208 ,0,0,0}, + {9344,9377,9380 ,6196,6158,6159 ,0,0,0}, {9367,9337,9332 ,6181,6243,6139 ,0,0,0}, + {9351,9353,10975 ,6244,6245,6246 ,0,0,0}, {9330,10976,10977 ,6247,6190,6136 ,0,0,0}, + {10978,10952,10979 ,6248,6231,6170 ,0,0,0}, {10980,10981,9359 ,6152,6249,6250 ,0,0,0}, + {10982,10952,10978 ,6251,6231,6248 ,0,0,0}, {10983,10984,10985 ,6252,6253,6254 ,0,0,0}, + {10984,10951,10985 ,6253,6230,6254 ,0,0,0}, {10986,10987,10988 ,6255,6256,6257 ,0,0,0}, + {10989,10990,10991 ,6258,6259,6260 ,0,0,0}, {10984,10983,10991 ,6253,6252,6260 ,0,0,0}, + {10991,10990,10984 ,6260,6259,6253 ,0,0,0}, {10990,10989,10992 ,6259,6258,6261 ,0,0,0}, + {10993,10988,10994 ,6262,6257,6263 ,0,0,0}, {10992,10994,10990 ,6261,6263,6259 ,0,0,0}, + {10988,10987,10994 ,6257,6256,6263 ,0,0,0}, {10995,10996,10987 ,6264,6265,6256 ,0,0,0}, + {10992,10993,10994 ,6261,6262,6263 ,0,0,0}, {10986,10995,10987 ,6255,6264,6256 ,0,0,0}, + {10985,10951,10953 ,6254,6230,6232 ,0,0,0}, {10997,10998,9360 ,6138,6134,6266 ,0,0,0}, + {10953,10952,10982 ,6232,6231,6251 ,0,0,0}, {10979,10998,10997 ,6170,6134,6138 ,0,0,0}, + {10999,9353,9354 ,6267,6245,6268 ,0,0,0}, {9331,10977,11000 ,6167,6136,6199 ,0,0,0}, + {9348,9351,10976 ,6235,6244,6190 ,0,0,0}, {11001,9402,11002 ,6197,6164,6191 ,0,0,0}, + {9396,9395,11003 ,6171,6118,6269 ,0,0,0}, {9341,9338,9371 ,6270,6270,6174 ,0,0,0}, + {11001,9404,9402 ,6197,6163,6164 ,0,0,0}, {9376,9341,9371 ,6127,6270,6174 ,0,0,0}, + {11004,10936,10935 ,6137,6156,6200 ,0,0,0}, {11005,11006,11007 ,6213,6271,6169 ,0,0,0}, + {9365,9367,11008 ,6173,6181,6272 ,0,0,0}, {9407,9404,11001 ,6156,6163,6197 ,0,0,0}, + {10997,11009,10979 ,6138,6273,6170 ,0,0,0}, {11010,9408,9407 ,6201,6155,6156 ,0,0,0}, + {11010,9412,9410 ,6201,6134,6151 ,0,0,0}, {11011,10965,11012 ,6214,6208,6133 ,0,0,0}, + {11011,9025,9028 ,6214,6208,6117 ,0,0,0}, {11013,11014,11015 ,6190,6214,6199 ,0,0,0}, + {9402,9401,11002 ,6164,6158,6191 ,0,0,0}, {9396,11003,11002 ,6171,6269,6191 ,0,0,0}, + {11016,11017,11018 ,6274,6118,6183 ,0,0,0}, {11019,11020,11021 ,6149,6275,6214 ,0,0,0}, + {11022,10978,11009 ,6243,6248,6273 ,0,0,0}, {11022,11009,11023 ,6243,6273,6276 ,0,0,0}, + {11021,10911,10925 ,6214,6170,6184 ,0,0,0}, {10909,10923,10910 ,6122,6182,6169 ,0,0,0}, + {10921,11024,10919 ,6180,6244,6177 ,0,0,0}, {10920,10919,10923 ,6179,6177,6182 ,0,0,0}, + {10897,11025,9308 ,6158,6127,6249 ,0,0,0}, {9203,11024,10962 ,6239,6244,6240 ,0,0,0}, + {10921,10962,11024 ,6180,6240,6244 ,0,0,0}, {9203,10956,9200 ,6239,6180,6277 ,0,0,0}, + {10897,9308,9307 ,6158,6249,6189 ,0,0,0}, {9199,9198,10957 ,6124,6238,6179 ,0,0,0}, + {9198,9200,10956 ,6238,6277,6180 ,0,0,0}, {9326,9594,9602 ,6278,6279,6280 ,0,0,0}, + {9594,10945,9596 ,6279,6211,6190 ,0,0,0}, {10881,9199,10957 ,6122,6124,6179 ,0,0,0}, + {11026,10882,10955 ,6275,6123,6214 ,0,0,0}, {9199,10882,9196 ,6124,6123,6237 ,0,0,0}, + {9600,9323,9602 ,6281,6282,6280 ,0,0,0}, {9310,11025,11027 ,6283,6127,6174 ,0,0,0}, + {9308,11025,9310 ,6249,6127,6283 ,0,0,0}, {10898,10887,10899 ,6144,6138,6159 ,0,0,0}, + {10885,10936,10886 ,6136,6156,6137 ,0,0,0}, {11004,10883,10884 ,6137,6133,6135 ,0,0,0}, + {10883,11004,10935 ,6133,6137,6200 ,0,0,0}, {10883,9074,9150 ,6133,6134,6134 ,0,0,0}, + {9557,10940,9555 ,6144,6201,6209 ,0,0,0}, {9150,9074,9152 ,6134,6134,6196 ,0,0,0}, + {9292,9063,9291 ,6201,6200,6158 ,0,0,0}, {9056,9053,9283 ,6208,6187,6284 ,0,0,0}, + {9289,9291,9062 ,6125,6158,6204 ,0,0,0}, {11028,9552,9553 ,6191,6165,6179 ,0,0,0}, + {9550,11029,9527 ,6142,6172,6197 ,0,0,0}, {9274,9532,9276 ,6191,6186,6196 ,0,0,0}, + {9637,9532,9274 ,6192,6186,6191 ,0,0,0}, {9637,9273,9535 ,6192,6142,6285 ,0,0,0}, + {11030,9270,9267 ,6192,6228,6142 ,0,0,0}, {9096,9016,9018 ,6120,6122,6119 ,0,0,0}, + {9019,9094,9018 ,6171,6202,6119 ,0,0,0}, {11031,9547,9545 ,6150,6144,6150 ,0,0,0}, + {10891,9117,9115 ,6144,6150,6187 ,0,0,0}, {9123,9121,10929 ,6150,6188,6144 ,0,0,0}, + {9115,11032,10891 ,6187,6144,6144 ,0,0,0}, {9089,10927,11033 ,6165,6186,6286 ,0,0,0}, + {11032,9111,11034 ,6144,6192,6144 ,0,0,0}, {9109,9108,11034 ,6145,6145,6144 ,0,0,0}, + {11035,11036,10965 ,6143,6133,6208 ,0,0,0}, {10917,11037,9240 ,6120,6176,6146 ,0,0,0}, + {10960,9037,9040 ,6131,6137,6122 ,0,0,0}, {9043,9388,9387 ,6134,6135,6134 ,0,0,0}, + {10959,9230,9229 ,6196,6139,6201 ,0,0,0}, {10958,9236,9233 ,6197,6286,6165 ,0,0,0}, + {10968,9249,11038 ,6179,6202,6139 ,0,0,0}, {9252,11038,9251 ,6203,6139,6228 ,0,0,0}, + {9386,10971,10969 ,6137,6133,6200 ,0,0,0}, {10969,9383,9386 ,6200,6156,6137 ,0,0,0}, + {11039,11040,11041 ,6209,6207,6166 ,0,0,0}, {11042,9381,10970 ,6138,6137,6136 ,0,0,0}, + {11037,9242,9240 ,6176,6191,6146 ,0,0,0}, {11043,11044,11045 ,6186,6228,6287 ,0,0,0}, + {9236,10958,10917 ,6286,6197,6120 ,0,0,0}, {9236,10917,9239 ,6286,6120,6154 ,0,0,0}, + {9235,10958,9233 ,6165,6197,6165 ,0,0,0}, {9230,10959,9235 ,6139,6196,6165 ,0,0,0}, + {10950,9228,9246 ,6228,6203,6179 ,0,0,0}, {10950,10959,9229 ,6228,6196,6201 ,0,0,0}, + {9034,10965,9031 ,6200,6208,6204 ,0,0,0}, {10968,10950,9246 ,6179,6228,6179 ,0,0,0}, + {11046,11038,9252 ,6133,6139,6203 ,0,0,0}, {9251,11038,9249 ,6228,6139,6202 ,0,0,0}, + {9034,9036,10965 ,6200,6131,6208 ,0,0,0}, {10965,11047,9257 ,6208,6207,6242 ,0,0,0}, + {9042,9387,11048 ,6138,6134,6196 ,0,0,0}, {10965,9036,9037 ,6208,6131,6137 ,0,0,0}, + {10965,9028,9030 ,6208,6117,6126 ,0,0,0}, {9025,11011,10928 ,6208,6214,6119 ,0,0,0}, + {10965,11011,9028 ,6208,6214,6117 ,0,0,0}, {10893,9105,9076 ,6145,6120,6153 ,0,0,0}, + {11049,11050,9080 ,6201,6121,6288 ,0,0,0}, {9024,9025,10928 ,6187,6208,6119 ,0,0,0}, + {11051,9082,9084 ,6139,6192,6131 ,0,0,0}, {10918,9080,11050 ,6145,6288,6121 ,0,0,0}, + {9115,9114,11032 ,6187,6145,6144 ,0,0,0}, {9114,9111,11032 ,6145,6192,6144 ,0,0,0}, + {9108,9105,10893 ,6145,6120,6145 ,0,0,0}, {11050,11052,10918 ,6121,6289,6145 ,0,0,0}, + {11043,11052,11053 ,6186,6289,6191 ,0,0,0}, {11050,11053,11052 ,6121,6191,6289 ,0,0,0}, + {11043,11045,11037 ,6186,6287,6176 ,0,0,0}, {11043,11053,11044 ,6186,6191,6228 ,0,0,0}, + {9242,11037,11045 ,6191,6176,6287 ,0,0,0}, {11054,9045,9044 ,6202,6122,6116 ,0,0,0}, + {11055,11056,9525 ,6165,6191,6187 ,0,0,0}, {11057,9553,9555 ,6126,6179,6209 ,0,0,0}, + {11058,10933,9535 ,6154,6120,6285 ,0,0,0}, {9262,9051,11059 ,6201,6117,6120 ,0,0,0}, + {11060,11061,9264 ,6197,6201,6207 ,0,0,0}, {10880,11059,9050 ,6121,6120,6171 ,0,0,0}, + {9013,9101,9100 ,6116,6120,6201 ,0,0,0}, {10880,9050,9047 ,6121,6171,6119 ,0,0,0}, + {9053,9280,9283 ,6187,6202,6284 ,0,0,0}, {9283,9285,9056 ,6284,6140,6208 ,0,0,0}, + {9057,9285,9286 ,6117,6140,6127 ,0,0,0}, {9057,9286,9059 ,6117,6127,6126 ,0,0,0}, + {9059,9289,9062 ,6126,6125,6204 ,0,0,0}, {9063,9062,9291 ,6200,6204,6158 ,0,0,0}, + {9140,9142,9292 ,6133,6143,6201 ,0,0,0}, {9136,9132,10942 ,6118,6207,6119 ,0,0,0}, + {9138,10938,10939 ,6204,6133,6153 ,0,0,0}, {10941,9132,9133 ,6132,6207,6201 ,0,0,0}, + {10941,9133,10939 ,6132,6201,6153 ,0,0,0}, {10937,9136,10942 ,6203,6118,6119 ,0,0,0}, + {9131,10940,9557 ,6132,6201,6144 ,0,0,0}, {11057,9555,10940 ,6126,6209,6201 ,0,0,0}, + {11062,9552,11028 ,6242,6165,6191 ,0,0,0}, {11028,9553,11057 ,6191,6179,6126 ,0,0,0}, + {9550,11062,11063 ,6142,6242,6197 ,0,0,0}, {11062,9550,9552 ,6242,6142,6165 ,0,0,0}, + {11029,11055,9527 ,6172,6165,6197 ,0,0,0}, {11063,11029,9550 ,6197,6172,6142 ,0,0,0}, + {9525,11056,9526 ,6187,6191,6197 ,0,0,0}, {9527,11055,9525 ,6197,6165,6187 ,0,0,0}, + {9276,9526,11064 ,6196,6197,6202 ,0,0,0}, {9526,11056,11064 ,6197,6191,6202 ,0,0,0}, + {10924,10897,9307 ,6183,6158,6189 ,0,0,0}, {11027,11065,11066 ,6174,6118,6273 ,0,0,0}, + {9301,10882,9304 ,6290,6123,6236 ,0,0,0}, {10949,10932,9304 ,6214,6190,6236 ,0,0,0}, + {9301,9303,10882 ,6290,6198,6123 ,0,0,0}, {9193,10882,9188 ,6152,6123,6174 ,0,0,0}, + {9314,9317,9185 ,6124,6217,6291 ,0,0,0}, {9296,9184,10882 ,6235,6140,6123 ,0,0,0}, + {9314,9185,9184 ,6124,6291,6140 ,0,0,0}, {9314,9184,9296 ,6124,6140,6235 ,0,0,0}, + {9317,9179,9185 ,6217,6219,6291 ,0,0,0}, {9319,9599,9180 ,6218,6233,6229 ,0,0,0}, + {9320,9323,9600 ,6200,6282,6281 ,0,0,0}, {9320,9600,9599 ,6200,6281,6233 ,0,0,0}, + {9325,9326,9602 ,6269,6278,6280 ,0,0,0}, {9323,9325,9602 ,6282,6269,6280 ,0,0,0}, + {9594,9326,11067 ,6279,6278,6292 ,0,0,0}, {11067,10945,9594 ,6292,6211,6279 ,0,0,0}, + {11068,9596,10944 ,6293,6190,6157 ,0,0,0}, {9597,11068,11069 ,6147,6293,6266 ,0,0,0}, + {11068,9597,9596 ,6293,6147,6190 ,0,0,0}, {10890,11070,9590 ,6148,6273,6149 ,0,0,0}, + {11069,10890,9597 ,6266,6148,6147 ,0,0,0}, {10926,11071,9591 ,6185,6294,6168 ,0,0,0}, + {11070,10926,9590 ,6273,6185,6149 ,0,0,0}, {9582,9584,10907 ,6178,6167,6166 ,0,0,0}, + {11071,10908,9591 ,6294,6116,6168 ,0,0,0}, {10943,10922,9582 ,6210,6181,6178 ,0,0,0}, + {10947,10946,11065 ,6182,6212,6118 ,0,0,0}, {10943,10946,10922 ,6210,6212,6181 ,0,0,0}, + {11027,11066,9310 ,6174,6273,6283 ,0,0,0}, {11065,10946,11066 ,6118,6212,6273 ,0,0,0}, + {9332,11000,11008 ,6139,6199,6272 ,0,0,0}, {9363,11072,9392 ,6174,6295,6177 ,0,0,0}, + {10963,11022,11023 ,6171,6243,6276 ,0,0,0}, {9398,9396,11002 ,6165,6171,6191 ,0,0,0}, + {11072,9363,11073 ,6295,6174,6162 ,0,0,0}, {11008,9367,9332 ,6272,6181,6139 ,0,0,0}, + {9331,11000,9332 ,6167,6199,6139 ,0,0,0}, {9330,10977,9331 ,6247,6136,6167 ,0,0,0}, + {9348,10976,9330 ,6235,6190,6247 ,0,0,0}, {10975,10976,9351 ,6246,6190,6244 ,0,0,0}, + {10999,10975,9353 ,6267,6246,6245 ,0,0,0}, {9354,9357,10981 ,6268,6185,6249 ,0,0,0}, + {10981,10999,9354 ,6249,6267,6268 ,0,0,0}, {9360,10980,9359 ,6266,6152,6250 ,0,0,0}, + {9359,10981,9357 ,6250,6249,6185 ,0,0,0}, {9360,10998,10980 ,6266,6134,6152 ,0,0,0}, + {10978,10979,11009 ,6248,6170,6273 ,0,0,0}, {10966,11074,10925 ,6241,6296,6184 ,0,0,0}, + {10963,11023,10964 ,6171,6276,6152 ,0,0,0}, {10966,10967,11075 ,6241,6136,6200 ,0,0,0}, + {11075,10901,10900 ,6200,6161,6160 ,0,0,0}, {10900,10902,10964 ,6160,6162,6152 ,0,0,0}, + {11075,10967,10901 ,6200,6136,6161 ,0,0,0}, {11074,11019,11021 ,6296,6149,6214 ,0,0,0}, + {11021,10925,11074 ,6214,6184,6296 ,0,0,0}, {11006,11020,11019 ,6271,6275,6149 ,0,0,0}, + {11007,11014,11005 ,6169,6214,6213 ,0,0,0}, {11006,11005,11020 ,6271,6213,6275 ,0,0,0}, + {11015,11016,11013 ,6199,6274,6190 ,0,0,0}, {11007,11015,11014 ,6169,6199,6214 ,0,0,0}, + {11018,11017,11076 ,6183,6118,6144 ,0,0,0}, {11013,11016,11018 ,6190,6274,6183 ,0,0,0}, + {9344,11076,11017 ,6196,6144,6118 ,0,0,0}, {9019,9022,9093 ,6171,6117,6139 ,0,0,0}, + {10929,9125,9123 ,6144,6150,6150 ,0,0,0}, {10929,9120,10891 ,6144,6150,6144 ,0,0,0}, + {9090,9093,9022 ,6197,6139,6117 ,0,0,0}, {9024,10927,9090 ,6187,6186,6197 ,0,0,0}, + {10893,11034,9108 ,6145,6144,6145 ,0,0,0}, {9111,9109,11034 ,6192,6145,6144 ,0,0,0}, + {9078,9080,10918 ,6120,6288,6145 ,0,0,0}, {9076,9078,10894 ,6153,6120,6154 ,0,0,0}, + {9084,9089,11033 ,6131,6165,6286 ,0,0,0}, {9086,11077,11049 ,6144,6242,6201 ,0,0,0}, + {11049,9080,9086 ,6201,6288,6144 ,0,0,0}, {11033,11051,9084 ,6286,6139,6131 ,0,0,0}, + {9082,11051,11077 ,6192,6139,6242 ,0,0,0}, {9082,11077,9086 ,6192,6242,6144 ,0,0,0}, + {9089,9090,10927 ,6165,6197,6186 ,0,0,0}, {9022,9024,9090 ,6117,6187,6197 ,0,0,0}, + {9019,9093,9094 ,6171,6139,6202 ,0,0,0}, {9018,9094,9096 ,6119,6202,6120 ,0,0,0}, + {9101,9013,9099 ,6120,6116,6139 ,0,0,0}, {9016,9099,9013 ,6122,6139,6116 ,0,0,0}, + {9013,9100,9012 ,6116,6201,6117 ,0,0,0}, {9045,11054,10879 ,6122,6202,6120 ,0,0,0}, + {9012,9100,10878 ,6117,6201,6118 ,0,0,0}, {11054,9044,10878 ,6202,6116,6118 ,0,0,0}, + {11059,9051,9050 ,6120,6117,6171 ,0,0,0}, {11060,9263,11059 ,6197,6197,6120 ,0,0,0}, + {9262,11059,9263 ,6201,6120,6197 ,0,0,0}, {9270,11078,9273 ,6228,6145,6142 ,0,0,0}, + {9269,9264,11061 ,6143,6207,6201 ,0,0,0}, {9264,9263,11060 ,6207,6197,6197 ,0,0,0}, + {11030,9267,10888 ,6192,6142,6139 ,0,0,0}, {10888,9269,11061 ,6139,6143,6201 ,0,0,0}, + {9270,11030,11078 ,6228,6192,6145 ,0,0,0}, {11058,9535,9273 ,6154,6285,6142 ,0,0,0}, + {11058,9273,11078 ,6154,6142,6145 ,0,0,0}, {10933,9537,9535 ,6120,6154,6285 ,0,0,0}, + {9539,10934,11079 ,6144,6127,6187 ,0,0,0}, {10934,9539,9537 ,6127,6144,6154 ,0,0,0}, + {11079,10889,9539 ,6187,6145,6144 ,0,0,0}, {9540,11080,10931 ,6146,6145,6150 ,0,0,0}, + {10889,11080,9540 ,6145,6145,6146 ,0,0,0}, {9540,10931,9542 ,6146,6150,6144 ,0,0,0}, + {9545,9542,11081 ,6150,6144,6146 ,0,0,0}, {10930,11081,9542 ,6145,6146,6144 ,0,0,0}, + {9545,11082,11031 ,6150,6144,6150 ,0,0,0}, {9545,11081,11082 ,6150,6146,6144 ,0,0,0}, + {11083,9547,11084 ,6150,6144,6150 ,0,0,0}, {9547,11031,11084 ,6144,6150,6150 ,0,0,0}, + {9125,9547,11083 ,6150,6144,6150 ,0,0,0}, {11085,11086,11087 ,6131,6203,6207 ,0,0,0}, + {11042,11076,9380 ,6138,6144,6159 ,0,0,0}, {11010,9407,11001 ,6201,6156,6197 ,0,0,0}, + {11010,9410,9408 ,6201,6151,6155 ,0,0,0}, {11076,9344,9380 ,6144,6196,6159 ,0,0,0}, + {9365,11073,9363 ,6173,6162,6174 ,0,0,0}, {9392,11072,9395 ,6177,6295,6118 ,0,0,0}, + {9401,9398,11002 ,6158,6165,6191 ,0,0,0}, {11072,11003,9395 ,6295,6269,6118 ,0,0,0}, + {11073,9365,11008 ,6162,6173,6272 ,0,0,0}, {9367,9373,9337 ,6181,6182,6243 ,0,0,0}, + {9376,9377,9342 ,6127,6158,6297 ,0,0,0}, {9369,9335,9373 ,6118,6155,6182 ,0,0,0}, + {9337,9373,9335 ,6243,6182,6155 ,0,0,0}, {9369,9371,9338 ,6118,6174,6270 ,0,0,0}, + {9338,9335,9369 ,6270,6155,6118 ,0,0,0}, {9341,9376,9342 ,6270,6127,6297 ,0,0,0}, + {9344,9342,9377 ,6196,6297,6158 ,0,0,0}, {11042,9380,9381 ,6138,6159,6137 ,0,0,0}, + {10970,9381,9383 ,6136,6137,6156 ,0,0,0}, {11088,11089,11090 ,6205,6132,6116 ,0,0,0}, + {11089,11046,11091 ,6132,6133,6132 ,0,0,0}, {9037,10960,10965 ,6137,6131,6208 ,0,0,0}, + {10971,9388,9043 ,6133,6135,6134 ,0,0,0}, {9042,11048,10961 ,6138,6196,6132 ,0,0,0}, + {9042,9043,9387 ,6138,6134,6134 ,0,0,0}, {10961,9040,9042 ,6132,6122,6138 ,0,0,0}, + {10965,10960,11092 ,6208,6131,6157 ,0,0,0}, {11092,11035,10965 ,6157,6143,6208 ,0,0,0}, + {11091,9255,11093 ,6132,6172,6118 ,0,0,0}, {11094,11095,10965 ,6204,6201,6208 ,0,0,0}, + {10965,11096,11097 ,6208,6172,6214 ,0,0,0}, {10965,11095,11047 ,6208,6201,6207 ,0,0,0}, + {11096,10965,9258 ,6172,6208,6127 ,0,0,0}, {9257,11047,9255 ,6242,6207,6172 ,0,0,0}, + {11093,9255,11047 ,6118,6172,6207 ,0,0,0}, {11091,11046,9252 ,6132,6133,6203 ,0,0,0}, + {9252,9255,11091 ,6203,6172,6132 ,0,0,0}, {11089,11088,11046 ,6132,6205,6133 ,0,0,0}, + {11039,11090,11098 ,6209,6116,6121 ,0,0,0}, {11090,11039,11088 ,6116,6209,6205 ,0,0,0}, + {11098,11040,11039 ,6121,6207,6209 ,0,0,0}, {11041,11099,10972 ,6166,6209,6207 ,0,0,0}, + {11040,11099,11041 ,6207,6209,6166 ,0,0,0}, {11041,10972,10974 ,6166,6207,6208 ,0,0,0}, + {11087,10974,11100 ,6207,6208,6196 ,0,0,0}, {10973,11100,10974 ,6133,6196,6208 ,0,0,0}, + {11087,11101,11085 ,6207,6134,6131 ,0,0,0}, {11087,11100,11101 ,6207,6196,6134 ,0,0,0}, + {11102,11086,11103 ,6204,6203,6205 ,0,0,0}, {11086,11085,11103 ,6203,6131,6205 ,0,0,0}, + {9412,11086,11102 ,6134,6203,6204 ,0,0,0}, {10882,9193,9192 ,6123,6152,6167 ,0,0,0}, + {10882,11026,10948 ,6123,6275,6213 ,0,0,0}, {9285,9057,9056 ,6140,6117,6208 ,0,0,0}, + {10965,11036,11094 ,6208,6133,6204 ,0,0,0}, {10965,11097,11012 ,6208,6214,6133 ,0,0,0}, + {11104,9788,9787 ,6298,6299,6299 ,0,0,0}, {9793,11105,9794 ,6298,6298,6300 ,0,0,0}, + {11106,11107,9485 ,6301,6302,6302 ,0,0,0}, {9787,9784,11108 ,6299,6300,6303 ,0,0,0}, + {9482,11109,11110 ,6304,6304,6305 ,0,0,0}, {9778,11111,9781 ,6301,6299,6306 ,0,0,0}, + {9480,11112,11113 ,6305,6307,6308 ,0,0,0}, {11114,9775,9772 ,6298,6298,6309 ,0,0,0}, + {11115,9468,11116 ,6310,6311,6312 ,0,0,0}, {11117,11118,9474 ,6308,6313,6314 ,0,0,0}, + {9464,9888,11119 ,6315,6316,6317 ,0,0,0}, {11119,11120,9471 ,6317,6318,6319 ,0,0,0}, + {9459,9883,9885 ,6320,6321,6322 ,0,0,0}, {9843,9426,9841 ,6299,6303,6323 ,0,0,0}, + {9847,9849,9429 ,6324,6298,6306 ,0,0,0}, {9449,9873,9874 ,6325,6326,6327 ,0,0,0}, + {9850,9853,9437 ,6298,6328,6324 ,0,0,0}, {9865,9867,9446 ,6301,6329,6330 ,0,0,0}, + {9865,9520,9862 ,6301,6324,6331 ,0,0,0}, {9439,9859,9861 ,6332,6328,6333 ,0,0,0}, + {9859,9442,9856 ,6328,6334,6335 ,0,0,0}, {9868,9519,9867 ,6336,6298,6329 ,0,0,0}, + {9862,9447,9861 ,6331,6337,6333 ,0,0,0}, {9448,9871,9873 ,6338,6339,6326 ,0,0,0}, + {9868,9871,9451 ,6336,6339,6324 ,0,0,0}, {9853,9855,9433 ,6328,6328,6299 ,0,0,0}, + {9855,9856,9434 ,6328,6335,6340 ,0,0,0}, {9455,9877,9879 ,6341,6342,6343 ,0,0,0}, + {9457,9874,9877 ,6344,6327,6342 ,0,0,0}, {9879,9880,9453 ,6343,6345,6346 ,0,0,0}, + {9849,9850,9436 ,6298,6298,6347 ,0,0,0}, {9844,9847,9432 ,6348,6324,6316 ,0,0,0}, + {9461,9880,9883 ,6349,6345,6321 ,0,0,0}, {9460,9885,9886 ,6350,6322,6351 ,0,0,0}, + {9431,9844,9432 ,6324,6348,6316 ,0,0,0}, {9417,9838,9418 ,6300,6352,6353 ,0,0,0}, + {9466,9886,9888 ,6354,6351,6316 ,0,0,0}, {9414,9832,9415 ,6355,6299,6298 ,0,0,0}, + {9837,9423,9835 ,6299,6356,6357 ,0,0,0}, {11117,9476,11115 ,6308,6358,6310 ,0,0,0}, + {11120,11116,9467 ,6318,6312,6359 ,0,0,0}, {9770,9769,11121 ,6316,6306,6360 ,0,0,0}, + {11121,9769,9420 ,6360,6306,6299 ,0,0,0}, {11121,11122,9770 ,6360,6298,6316 ,0,0,0}, + {11118,11112,9472 ,6313,6307,6304 ,0,0,0}, {9479,11113,11123 ,6336,6308,6311 ,0,0,0}, + {9426,9843,9431 ,6303,6299,6324 ,0,0,0}, {11123,11109,9484 ,6311,6304,6314 ,0,0,0}, + {9778,9776,11124 ,6301,6300,6340 ,0,0,0}, {11125,9776,9775 ,6301,6300,6298 ,0,0,0}, + {11126,11106,9489 ,6301,6301,6333 ,0,0,0}, {9483,11110,11126 ,6361,6305,6301 ,0,0,0}, + {11127,9784,9782 ,6300,6300,6357 ,0,0,0}, {9781,11128,9782 ,6306,6355,6357 ,0,0,0}, + {11129,11130,9490 ,6353,6311,6301 ,0,0,0}, {9486,11107,11129 ,6362,6302,6353 ,0,0,0}, + {9790,9788,11131 ,6300,6299,6300 ,0,0,0}, {9491,11130,11132 ,6300,6311,6363 ,0,0,0}, + {9495,11132,11133 ,6301,6363,6353 ,0,0,0}, {9496,11133,11134 ,6300,6353,6328 ,0,0,0}, + {9790,11135,9793 ,6300,6300,6298 ,0,0,0}, {11136,9498,11134 ,6303,6352,6328 ,0,0,0}, + {11136,11137,9500 ,6303,6352,6340 ,0,0,0}, {11138,9796,9794 ,6299,6316,6300 ,0,0,0}, + {11139,9503,11137 ,6300,6340,6352 ,0,0,0}, {11140,9799,9796 ,6298,6364,6316 ,0,0,0}, + {9504,11139,11141 ,6316,6300,6306 ,0,0,0}, {11142,9800,9799 ,6364,6298,6364 ,0,0,0}, + {11141,11143,9506 ,6306,6340,6340 ,0,0,0}, {11144,9802,9800 ,6300,6300,6298 ,0,0,0}, + {11145,9509,11143 ,6323,6340,6340 ,0,0,0}, {11146,9805,9802 ,6298,6300,6300 ,0,0,0}, + {9511,11145,11147 ,6300,6323,6340 ,0,0,0}, {11148,9806,9805 ,6364,6300,6300 ,0,0,0}, + {11147,11149,9510 ,6340,6303,6303 ,0,0,0}, {11150,9808,9806 ,6300,6365,6300 ,0,0,0}, + {11151,9512,11149 ,6300,6300,6303 ,0,0,0}, {11152,9811,9808 ,6366,6300,6365 ,0,0,0}, + {9515,11151,11153 ,6300,6300,6316 ,0,0,0}, {11154,9812,9811 ,6367,6367,6300 ,0,0,0}, + {11153,11155,9516 ,6316,6300,6300 ,0,0,0}, {11156,9814,9812 ,6300,6300,6367 ,0,0,0}, + {11157,9516,11158 ,6301,6300,6300 ,0,0,0}, {11159,9817,9814 ,6368,6300,6300 ,0,0,0}, + {11160,11157,11161 ,6300,6301,6300 ,0,0,0}, {11162,9818,9817 ,6369,6367,6300 ,0,0,0}, + {11163,11160,11164 ,6316,6300,6300 ,0,0,0}, {9818,11165,9820 ,6367,6367,6300 ,0,0,0}, + {9823,9820,11166 ,6364,6300,6370 ,0,0,0}, {11167,9826,9824 ,6300,6316,6300 ,0,0,0}, + {11168,11163,11169 ,6300,6316,6316 ,0,0,0}, {11170,11171,11172 ,6300,6371,6300 ,0,0,0}, + {11173,11174,11175 ,6306,6300,6303 ,0,0,0}, {11176,11177,11178 ,6369,6300,6367 ,0,0,0}, + {11179,11180,11181 ,6301,6301,6300 ,0,0,0}, {11182,11183,11184 ,6300,6369,6367 ,0,0,0}, + {11185,11186,11187 ,6316,6316,6300 ,0,0,0}, {11188,11189,11190 ,6364,6300,6300 ,0,0,0}, + {11191,11182,11192 ,6364,6300,6316 ,0,0,0}, {11193,11194,11195 ,6300,6364,6316 ,0,0,0}, + {11190,11196,11195 ,6300,6316,6316 ,0,0,0}, {11197,11198,11199 ,6364,6372,6364 ,0,0,0}, + {11198,11191,11200 ,6372,6364,6300 ,0,0,0}, {11185,11194,11201 ,6316,6364,6367 ,0,0,0}, + {11202,11188,11197 ,6370,6364,6364 ,0,0,0}, {11178,11203,11204 ,6367,6367,6316 ,0,0,0}, + {11205,11183,11204 ,6316,6369,6316 ,0,0,0}, {11206,11179,11207 ,6306,6301,6303 ,0,0,0}, + {11207,11187,11208 ,6303,6300,6340 ,0,0,0}, {11209,11210,11172 ,6371,6300,6300 ,0,0,0}, + {11211,11176,11210 ,6300,6369,6300 ,0,0,0}, {11212,11173,11213 ,6300,6306,6300 ,0,0,0}, + {11212,11213,11181 ,6300,6300,6300 ,0,0,0}, {11214,11215,9826 ,6300,6300,6316 ,0,0,0}, + {11170,11215,11216 ,6300,6300,6316 ,0,0,0}, {11168,11217,11218 ,6300,6303,6301 ,0,0,0}, + {11174,11218,11219 ,6300,6301,6301 ,0,0,0}, {9824,9823,11220 ,6300,6364,6369 ,0,0,0}, + {9769,9768,9420 ,6306,6298,6299 ,0,0,0}, {9420,9768,9831 ,6299,6298,6340 ,0,0,0}, + {11122,11114,9772 ,6298,6298,6309 ,0,0,0}, {11122,9772,9770 ,6298,6309,6316 ,0,0,0}, + {11114,11125,9775 ,6298,6301,6298 ,0,0,0}, {11125,11124,9776 ,6301,6340,6300 ,0,0,0}, + {11124,11111,9778 ,6340,6299,6301 ,0,0,0}, {11111,11128,9781 ,6299,6355,6306 ,0,0,0}, + {11128,11127,9782 ,6355,6300,6357 ,0,0,0}, {11127,11108,9784 ,6300,6303,6300 ,0,0,0}, + {11108,11104,9787 ,6303,6298,6299 ,0,0,0}, {11104,11131,9788 ,6298,6300,6299 ,0,0,0}, + {11131,11135,9790 ,6300,6300,6300 ,0,0,0}, {11135,11105,9793 ,6300,6298,6298 ,0,0,0}, + {11105,11138,9794 ,6298,6299,6300 ,0,0,0}, {11138,11140,9796 ,6299,6298,6316 ,0,0,0}, + {11140,11142,9799 ,6298,6364,6364 ,0,0,0}, {11142,11144,9800 ,6364,6300,6298 ,0,0,0}, + {11144,11146,9802 ,6300,6298,6300 ,0,0,0}, {11146,11148,9805 ,6298,6364,6300 ,0,0,0}, + {11148,11150,9806 ,6364,6300,6300 ,0,0,0}, {11150,11152,9808 ,6300,6366,6365 ,0,0,0}, + {11152,11154,9811 ,6366,6367,6300 ,0,0,0}, {11154,11156,9812 ,6367,6300,6367 ,0,0,0}, + {11156,11159,9814 ,6300,6368,6300 ,0,0,0}, {11159,11162,9817 ,6368,6369,6300 ,0,0,0}, + {11162,11165,9818 ,6369,6367,6367 ,0,0,0}, {11165,11166,9820 ,6367,6370,6300 ,0,0,0}, + {11166,11220,9823 ,6370,6369,6364 ,0,0,0}, {11220,11167,9824 ,6369,6300,6300 ,0,0,0}, + {11167,11214,9826 ,6300,6300,6316 ,0,0,0}, {11214,11216,11215 ,6300,6316,6300 ,0,0,0}, + {11216,11171,11170 ,6316,6371,6300 ,0,0,0}, {11171,11209,11172 ,6371,6371,6300 ,0,0,0}, + {11209,11211,11210 ,6371,6300,6300 ,0,0,0}, {11211,11177,11176 ,6300,6300,6369 ,0,0,0}, + {11177,11203,11178 ,6300,6367,6367 ,0,0,0}, {11203,11205,11204 ,6367,6316,6316 ,0,0,0}, + {11205,11184,11183 ,6316,6367,6369 ,0,0,0}, {11184,11192,11182 ,6367,6316,6300 ,0,0,0}, + {11192,11200,11191 ,6316,6300,6364 ,0,0,0}, {11200,11199,11198 ,6300,6364,6372 ,0,0,0}, + {11199,11202,11197 ,6364,6370,6364 ,0,0,0}, {11202,11189,11188 ,6370,6300,6364 ,0,0,0}, + {11189,11196,11190 ,6300,6316,6300 ,0,0,0}, {11196,11193,11195 ,6316,6300,6316 ,0,0,0}, + {11193,11201,11194 ,6300,6367,6364 ,0,0,0}, {11201,11186,11185 ,6367,6316,6316 ,0,0,0}, + {11186,11208,11187 ,6316,6340,6300 ,0,0,0}, {11208,11206,11207 ,6340,6306,6303 ,0,0,0}, + {11206,11180,11179 ,6306,6301,6301 ,0,0,0}, {11180,11212,11181 ,6301,6300,6300 ,0,0,0}, + {11173,11175,11213 ,6306,6303,6300 ,0,0,0}, {11174,11219,11175 ,6300,6301,6303 ,0,0,0}, + {11218,11217,11219 ,6301,6303,6301 ,0,0,0}, {11168,11169,11217 ,6300,6316,6303 ,0,0,0}, + {11163,11164,11169 ,6316,6300,6316 ,0,0,0}, {11160,11161,11164 ,6300,6300,6300 ,0,0,0}, + {11157,11158,11161 ,6301,6300,6300 ,0,0,0}, {9516,11155,11158 ,6300,6300,6300 ,0,0,0}, + {9516,9515,11153 ,6300,6300,6316 ,0,0,0}, {9515,9512,11151 ,6300,6300,6300 ,0,0,0}, + {9512,9510,11149 ,6300,6303,6303 ,0,0,0}, {9510,9511,11147 ,6303,6300,6340 ,0,0,0}, + {9511,9509,11145 ,6300,6340,6323 ,0,0,0}, {9509,9506,11143 ,6340,6340,6340 ,0,0,0}, + {9506,9504,11141 ,6340,6316,6306 ,0,0,0}, {9504,9503,11139 ,6316,6340,6300 ,0,0,0}, + {9503,9500,11137 ,6340,6340,6352 ,0,0,0}, {9500,9498,11136 ,6340,6352,6303 ,0,0,0}, + {9498,9496,11134 ,6352,6300,6328 ,0,0,0}, {9496,9495,11133 ,6300,6301,6353 ,0,0,0}, + {9495,9491,11132 ,6301,6300,6363 ,0,0,0}, {9491,9490,11130 ,6300,6301,6311 ,0,0,0}, + {9490,9486,11129 ,6301,6362,6353 ,0,0,0}, {9486,9485,11107 ,6362,6302,6302 ,0,0,0}, + {9485,9489,11106 ,6302,6333,6301 ,0,0,0}, {9489,9483,11126 ,6333,6361,6301 ,0,0,0}, + {9483,9482,11110 ,6361,6304,6305 ,0,0,0}, {9482,9484,11109 ,6304,6314,6304 ,0,0,0}, + {9484,9479,11123 ,6314,6336,6311 ,0,0,0}, {9479,9480,11113 ,6336,6305,6308 ,0,0,0}, + {9480,9472,11112 ,6305,6304,6307 ,0,0,0}, {9472,9474,11118 ,6304,6314,6313 ,0,0,0}, + {9474,9476,11117 ,6314,6358,6308 ,0,0,0}, {9476,9468,11115 ,6358,6311,6310 ,0,0,0}, + {9468,9467,11116 ,6311,6359,6312 ,0,0,0}, {9467,9471,11120 ,6359,6319,6318 ,0,0,0}, + {9471,9464,11119 ,6319,6315,6317 ,0,0,0}, {9464,9466,9888 ,6315,6354,6316 ,0,0,0}, + {9466,9460,9886 ,6354,6350,6351 ,0,0,0}, {9460,9459,9885 ,6350,6320,6322 ,0,0,0}, + {9459,9461,9883 ,6320,6349,6321 ,0,0,0}, {9461,9453,9880 ,6349,6346,6345 ,0,0,0}, + {9453,9455,9879 ,6346,6341,6343 ,0,0,0}, {9455,9457,9877 ,6341,6344,6342 ,0,0,0}, + {9457,9449,9874 ,6344,6325,6327 ,0,0,0}, {9449,9448,9873 ,6325,6338,6326 ,0,0,0}, + {9448,9451,9871 ,6338,6324,6339 ,0,0,0}, {9451,9519,9868 ,6324,6298,6336 ,0,0,0}, + {9519,9446,9867 ,6298,6330,6329 ,0,0,0}, {9446,9520,9865 ,6330,6324,6301 ,0,0,0}, + {9520,9447,9862 ,6324,6337,6331 ,0,0,0}, {9447,9439,9861 ,6337,6332,6333 ,0,0,0}, + {9439,9442,9859 ,6332,6334,6328 ,0,0,0}, {9442,9434,9856 ,6334,6340,6335 ,0,0,0}, + {9434,9433,9855 ,6340,6299,6328 ,0,0,0}, {9433,9437,9853 ,6299,6324,6328 ,0,0,0}, + {9437,9436,9850 ,6324,6347,6298 ,0,0,0}, {9436,9429,9849 ,6347,6306,6298 ,0,0,0}, + {9429,9432,9847 ,6306,6316,6324 ,0,0,0}, {9431,9843,9844 ,6324,6299,6348 ,0,0,0}, + {9418,9841,9426 ,6353,6323,6303 ,0,0,0}, {9417,9837,9838 ,6300,6299,6352 ,0,0,0}, + {9418,9838,9841 ,6353,6352,6323 ,0,0,0}, {9423,9415,9835 ,6356,6298,6357 ,0,0,0}, + {9417,9423,9837 ,6300,6356,6299 ,0,0,0}, {9832,9414,9831 ,6299,6355,6340 ,0,0,0}, + {9835,9415,9832 ,6357,6298,6299 ,0,0,0}, {9420,9831,9414 ,6299,6340,6355 ,0,0,0}, + {11215,9828,9826 ,6373,6374,6375 ,0,0,0}, {11221,11222,11210 ,6376,6377,6378 ,0,0,0}, + {11172,11223,11170 ,6379,6380,6381 ,0,0,0}, {11204,11183,11224 ,6382,6383,6384 ,0,0,0}, + {11176,11178,11225 ,6385,6386,6387 ,0,0,0}, {11226,11227,11198 ,6388,6389,6390 ,0,0,0}, + {11228,11229,11182 ,6391,6392,6393 ,0,0,0}, {11190,11195,11230 ,6394,6395,6396 ,0,0,0}, + {11197,11188,11231 ,6397,6398,6399 ,0,0,0}, {11232,11233,11187 ,6400,6401,6402 ,0,0,0}, + {11234,11235,11194 ,6403,6404,6405 ,0,0,0}, {11181,11213,11236 ,6406,6407,6408 ,0,0,0}, + {11207,11179,11237 ,6409,6410,6411 ,0,0,0}, {11238,11239,11217 ,6412,6413,6414 ,0,0,0}, + {11240,11241,11175 ,6415,6416,6417 ,0,0,0}, {11242,11161,11243 ,6418,6419,6420 ,0,0,0}, + {11169,11164,11244 ,6421,6422,6423 ,0,0,0}, {11153,11245,11246 ,6424,6425,6426 ,0,0,0}, + {11155,11247,11158 ,6427,6428,6429 ,0,0,0}, {11248,11249,11147 ,6430,6431,6432 ,0,0,0}, + {11250,11151,11149 ,6433,6434,6435 ,0,0,0}, {11251,11143,11141 ,6436,6437,6438 ,0,0,0}, + {11145,11143,11252 ,6439,6437,6440 ,0,0,0}, {11253,11137,11254 ,6441,6442,6443 ,0,0,0}, + {11139,11253,11255 ,6444,6441,6445 ,0,0,0}, {11134,11133,11256 ,6446,6447,6448 ,0,0,0}, + {11136,11257,11254 ,6449,6450,6443 ,0,0,0}, {11132,11130,11258 ,6451,6452,6453 ,0,0,0}, + {11132,11259,11133 ,6451,6454,6447 ,0,0,0}, {11129,11107,11260 ,6455,6456,6457 ,0,0,0}, + {11129,11261,11130 ,6455,6458,6452 ,0,0,0}, {11262,11107,11106 ,6459,6456,6460 ,0,0,0}, + {11107,11262,11260 ,6456,6459,6457 ,0,0,0}, {11126,11263,11106 ,6461,6462,6460 ,0,0,0}, + {11262,11106,11263 ,6459,6460,6462 ,0,0,0}, {11126,11110,11264 ,6461,6463,6464 ,0,0,0}, + {11264,11263,11126 ,6464,6462,6461 ,0,0,0}, {11265,11110,11109 ,6465,6463,6466 ,0,0,0}, + {11110,11265,11264 ,6463,6465,6464 ,0,0,0}, {11123,11266,11109 ,6467,6468,6466 ,0,0,0}, + {11265,11109,11266 ,6465,6466,6468 ,0,0,0}, {11123,11113,11267 ,6467,6469,6470 ,0,0,0}, + {11267,11266,11123 ,6470,6468,6467 ,0,0,0}, {11268,11113,11112 ,6471,6469,6472 ,0,0,0}, + {11113,11268,11267 ,6469,6471,6470 ,0,0,0}, {11118,11269,11112 ,6473,6474,6472 ,0,0,0}, + {11268,11112,11269 ,6471,6472,6474 ,0,0,0}, {11118,11117,11270 ,6473,6475,6476 ,0,0,0}, + {11270,11269,11118 ,6476,6474,6473 ,0,0,0}, {11271,11117,11115 ,6477,6475,6478 ,0,0,0}, + {11117,11271,11270 ,6475,6477,6476 ,0,0,0}, {11116,11272,11115 ,6479,6480,6478 ,0,0,0}, + {11271,11115,11272 ,6477,6478,6480 ,0,0,0}, {11116,11120,11273 ,6479,6481,6482 ,0,0,0}, + {11273,11272,11116 ,6482,6480,6479 ,0,0,0}, {11274,11120,11119 ,6483,6481,6484 ,0,0,0}, + {11120,11274,11273 ,6481,6483,6482 ,0,0,0}, {9888,11275,11119 ,6485,6486,6484 ,0,0,0}, + {11274,11119,11275 ,6483,6484,6486 ,0,0,0}, {9887,11275,9888 ,6487,6486,6485 ,0,0,0}, + {11261,11258,11130 ,6458,6453,6452 ,0,0,0}, {11129,11260,11261 ,6455,6457,6458 ,0,0,0}, + {11259,11256,11133 ,6454,6448,6447 ,0,0,0}, {11132,11258,11259 ,6451,6453,6454 ,0,0,0}, + {11136,11134,11257 ,6449,6446,6450 ,0,0,0}, {11134,11256,11257 ,6446,6448,6450 ,0,0,0}, + {11137,11253,11139 ,6442,6441,6444 ,0,0,0}, {11137,11136,11254 ,6442,6449,6443 ,0,0,0}, + {11251,11141,11255 ,6436,6438,6445 ,0,0,0}, {11141,11139,11255 ,6438,6444,6445 ,0,0,0}, + {11145,11252,11248 ,6439,6440,6430 ,0,0,0}, {11252,11143,11251 ,6440,6437,6436 ,0,0,0}, + {11249,11149,11147 ,6431,6435,6432 ,0,0,0}, {11248,11147,11145 ,6430,6432,6439 ,0,0,0}, + {11250,11245,11151 ,6433,6425,6434 ,0,0,0}, {11249,11250,11149 ,6431,6433,6435 ,0,0,0}, + {11153,11246,11155 ,6424,6426,6427 ,0,0,0}, {11151,11245,11153 ,6434,6425,6424 ,0,0,0}, + {11158,11247,11243 ,6429,6428,6420 ,0,0,0}, {11155,11246,11247 ,6427,6426,6428 ,0,0,0}, + {11164,11161,11242 ,6422,6419,6418 ,0,0,0}, {11161,11158,11243 ,6419,6429,6420 ,0,0,0}, + {11238,11169,11244 ,6412,6421,6423 ,0,0,0}, {11244,11164,11242 ,6423,6422,6418 ,0,0,0}, + {11239,11219,11217 ,6413,6488,6414 ,0,0,0}, {11238,11217,11169 ,6412,6414,6421 ,0,0,0}, + {11175,11219,11240 ,6417,6488,6415 ,0,0,0}, {11239,11240,11219 ,6413,6415,6488 ,0,0,0}, + {11213,11241,11236 ,6407,6416,6408 ,0,0,0}, {11175,11241,11213 ,6417,6416,6407 ,0,0,0}, + {11179,11181,11276 ,6410,6406,6489 ,0,0,0}, {11181,11236,11276 ,6406,6408,6489 ,0,0,0}, + {11232,11207,11237 ,6400,6409,6411 ,0,0,0}, {11237,11179,11276 ,6411,6410,6489 ,0,0,0}, + {11233,11185,11187 ,6401,6490,6402 ,0,0,0}, {11232,11187,11207 ,6400,6402,6409 ,0,0,0}, + {11194,11185,11234 ,6405,6490,6403 ,0,0,0}, {11233,11234,11185 ,6401,6403,6490 ,0,0,0}, + {11195,11235,11230 ,6395,6404,6396 ,0,0,0}, {11194,11235,11195 ,6405,6404,6395 ,0,0,0}, + {11188,11190,11277 ,6398,6394,6491 ,0,0,0}, {11190,11230,11277 ,6394,6396,6491 ,0,0,0}, + {11226,11197,11231 ,6388,6397,6399 ,0,0,0}, {11231,11188,11277 ,6399,6398,6491 ,0,0,0}, + {11227,11191,11198 ,6389,6492,6390 ,0,0,0}, {11226,11198,11197 ,6388,6390,6397 ,0,0,0}, + {11182,11191,11228 ,6393,6492,6391 ,0,0,0}, {11227,11228,11191 ,6389,6391,6492 ,0,0,0}, + {11183,11229,11224 ,6383,6392,6384 ,0,0,0}, {11182,11229,11183 ,6393,6392,6383 ,0,0,0}, + {11178,11204,11278 ,6386,6382,6493 ,0,0,0}, {11204,11224,11278 ,6382,6384,6493 ,0,0,0}, + {11221,11176,11225 ,6376,6385,6387 ,0,0,0}, {11225,11178,11278 ,6387,6386,6493 ,0,0,0}, + {11222,11172,11210 ,6377,6379,6378 ,0,0,0}, {11221,11210,11176 ,6376,6378,6385 ,0,0,0}, + {11223,11279,11170 ,6380,6494,6381 ,0,0,0}, {11222,11223,11172 ,6377,6380,6379 ,0,0,0}, + {9828,11215,11279 ,6374,6373,6494 ,0,0,0}, {11170,11279,11215 ,6381,6494,6373 ,0,0,0}, + {9839,9725,9840 ,6495,6495,6496 ,0,0,0}, {9846,9845,9731 ,6497,6496,6496 ,0,0,0}, + {11234,11233,11280 ,6498,6499,6500 ,0,0,0}, {9722,9839,9836 ,6501,6495,6501 ,0,0,0}, + {11231,11277,11281 ,6502,6503,6503 ,0,0,0}, {9833,9716,9719 ,6496,6504,6501 ,0,0,0}, + {11282,11224,11229 ,6498,6505,6506 ,0,0,0}, {9658,9767,9771 ,6507,6495,6495 ,0,0,0}, + {9668,9666,9780 ,6508,6509,6504 ,0,0,0}, {11283,11222,11221 ,6510,6511,6512 ,0,0,0}, + {9827,9710,9708 ,6513,6500,6514 ,0,0,0}, {9828,9710,9827 ,6515,6500,6513 ,0,0,0}, + {9822,9825,9709 ,6516,6517,6518 ,0,0,0}, {9789,9791,9674 ,6519,6520,6497 ,0,0,0}, + {9795,9797,9680 ,6521,6522,6523 ,0,0,0}, {9819,9702,9701 ,6524,6525,6526 ,0,0,0}, + {9798,9684,9683 ,6527,6500,6498 ,0,0,0}, {9815,9696,9813 ,6528,6522,6529 ,0,0,0}, + {9813,9695,9810 ,6529,6530,6531 ,0,0,0}, {9690,9807,9692 ,6532,6533,6502 ,0,0,0}, + {9804,9690,9689 ,6534,6532,6495 ,0,0,0}, {9816,9698,9815 ,6535,6502,6528 ,0,0,0}, + {9809,9810,9692 ,6533,6531,6502 ,0,0,0}, {9819,9701,9816 ,6524,6526,6535 ,0,0,0}, + {9698,9816,9701 ,6502,6535,6526 ,0,0,0}, {9801,9686,9684 ,6503,6514,6500 ,0,0,0}, + {9689,9686,9803 ,6495,6514,6530 ,0,0,0}, {9707,9702,9821 ,6536,6525,6537 ,0,0,0}, + {9702,9819,9821 ,6525,6524,6537 ,0,0,0}, {9707,9821,9822 ,6536,6537,6516 ,0,0,0}, + {9798,9683,9797 ,6527,6498,6522 ,0,0,0}, {9795,9678,9792 ,6521,6501,6509 ,0,0,0}, + {9822,9709,9707 ,6516,6518,6536 ,0,0,0}, {9709,9825,9708 ,6518,6517,6514 ,0,0,0}, + {9792,9677,9791 ,6509,6500,6520 ,0,0,0}, {9672,9786,9674 ,6508,6509,6497 ,0,0,0}, + {9827,9708,9825 ,6513,6514,6517 ,0,0,0}, {9668,9783,9671 ,6508,6508,6495 ,0,0,0}, + {9671,9785,9672 ,6495,6530,6508 ,0,0,0}, {11284,11223,11285 ,6538,6539,6540 ,0,0,0}, + {11279,9710,9828 ,6541,6500,6515 ,0,0,0}, {9779,9665,9777 ,6495,6496,6542 ,0,0,0}, + {9666,9665,9779 ,6509,6496,6495 ,0,0,0}, {9773,9774,9660 ,6542,6504,6507 ,0,0,0}, + {11278,11224,11286 ,6543,6505,6500 ,0,0,0}, {11287,11228,11288 ,6503,6533,6500 ,0,0,0}, + {9771,9773,9659 ,6495,6542,6495 ,0,0,0}, {11289,11288,11226 ,6508,6500,6538 ,0,0,0}, + {9716,9830,9715 ,6504,6542,6501 ,0,0,0}, {9658,9715,9829 ,6507,6501,6495 ,0,0,0}, + {11235,11290,11291 ,6527,6530,6498 ,0,0,0}, {11277,11230,11292 ,6503,6527,6499 ,0,0,0}, + {9722,9836,9721 ,6501,6501,6544 ,0,0,0}, {9834,9719,9721 ,6504,6501,6544 ,0,0,0}, + {11237,11293,11294 ,6508,6530,6544 ,0,0,0}, {11295,11232,11294 ,6498,6500,6544 ,0,0,0}, + {9727,9842,9840 ,6495,6495,6496 ,0,0,0}, {11276,11236,11293 ,6523,6504,6530 ,0,0,0}, + {11241,11296,11236 ,6500,6504,6504 ,0,0,0}, {11241,11240,11297 ,6500,6522,6500 ,0,0,0}, + {9845,9842,9728 ,6496,6495,6496 ,0,0,0}, {11298,11240,11239 ,6515,6522,6504 ,0,0,0}, + {11238,11299,11239 ,6508,6500,6504 ,0,0,0}, {9848,9731,9733 ,6495,6496,6508 ,0,0,0}, + {11299,11238,11300 ,6500,6508,6498 ,0,0,0}, {9851,9733,9734 ,6504,6508,6507 ,0,0,0}, + {11301,11300,11244 ,6515,6498,6545 ,0,0,0}, {9852,9734,9737 ,6507,6507,6495 ,0,0,0}, + {11302,11301,11242 ,6498,6515,6504 ,0,0,0}, {9854,9737,9739 ,6504,6495,6495 ,0,0,0}, + {11303,11302,11243 ,6504,6498,6504 ,0,0,0}, {9739,9740,9857 ,6495,6504,6504 ,0,0,0}, + {11304,11303,11247 ,6504,6504,6498 ,0,0,0}, {9858,9857,9740 ,6504,6504,6504 ,0,0,0}, + {11304,11246,11245 ,6504,6504,6504 ,0,0,0}, {9860,9858,9743 ,6546,6504,6504 ,0,0,0}, + {11305,11245,11250 ,6508,6504,6504 ,0,0,0}, {9863,9860,9745 ,6507,6546,6504 ,0,0,0}, + {11306,11250,11249 ,6508,6504,6508 ,0,0,0}, {9864,9863,9746 ,6547,6507,6548 ,0,0,0}, + {11307,11249,11248 ,6498,6508,6498 ,0,0,0}, {9866,9864,9749 ,6546,6547,6548 ,0,0,0}, + {11308,11248,11252 ,6504,6498,6498 ,0,0,0}, {9751,9869,9749 ,6549,6547,6548 ,0,0,0}, + {11252,11309,11308 ,6498,6504,6504 ,0,0,0}, {9870,9751,9752 ,6549,6549,6550 ,0,0,0}, + {11309,11251,11310 ,6504,6504,6498 ,0,0,0}, {9752,9755,9872 ,6550,6549,6504 ,0,0,0}, + {9875,9755,9757 ,6549,6549,6545 ,0,0,0}, {9878,9876,9759 ,6549,6504,6504 ,0,0,0}, + {11310,11255,11311 ,6498,6504,6504 ,0,0,0}, {9884,9882,9764 ,6551,6504,6515 ,0,0,0}, + {11256,11312,11257 ,6504,6508,6515 ,0,0,0}, {11313,11274,11314 ,6504,6545,6515 ,0,0,0}, + {11315,11258,11261 ,6508,6552,6504 ,0,0,0}, {11271,11316,11317 ,6553,6504,6554 ,0,0,0}, + {11318,11319,11262 ,6555,6504,6515 ,0,0,0}, {11266,11267,11320 ,6504,6504,6504 ,0,0,0}, + {11271,11317,11270 ,6553,6554,6504 ,0,0,0}, {11264,11321,11322 ,6504,6504,6515 ,0,0,0}, + {11320,11321,11265 ,6504,6504,6515 ,0,0,0}, {11269,11323,11268 ,6548,6504,6504 ,0,0,0}, + {11269,11270,11324 ,6548,6504,6549 ,0,0,0}, {11318,11263,11322 ,6555,6504,6515 ,0,0,0}, + {11325,11267,11268 ,6504,6504,6504 ,0,0,0}, {11326,11273,11313 ,6504,6548,6504 ,0,0,0}, + {11316,11272,11326 ,6504,6548,6504 ,0,0,0}, {11260,11327,11261 ,6504,6544,6504 ,0,0,0}, + {11260,11319,11327 ,6504,6504,6544 ,0,0,0}, {9887,9884,9766 ,6515,6551,6554 ,0,0,0}, + {9766,11314,11275 ,6554,6515,6545 ,0,0,0}, {11259,11328,11256 ,6515,6504,6504 ,0,0,0}, + {11329,11259,11258 ,6508,6515,6552 ,0,0,0}, {9881,9878,9758 ,6504,6549,6549 ,0,0,0}, + {9761,9882,9881 ,6545,6504,6504 ,0,0,0}, {11253,11330,11311 ,6508,6498,6504 ,0,0,0}, + {11312,11330,11254 ,6508,6498,6498 ,0,0,0}, {9876,9757,9759 ,6504,6545,6504 ,0,0,0}, + {9774,9777,9662 ,6504,6542,6504 ,0,0,0}, {11331,11225,11332 ,6556,6557,6558 ,0,0,0}, + {11280,11233,11295 ,6500,6499,6498 ,0,0,0}, {9696,9815,9698 ,6522,6528,6502 ,0,0,0}, + {9695,9813,9696 ,6530,6529,6522 ,0,0,0}, {9692,9810,9695 ,6502,6531,6530 ,0,0,0}, + {9692,9807,9809 ,6502,6533,6533 ,0,0,0}, {9690,9804,9807 ,6532,6534,6533 ,0,0,0}, + {9689,9803,9804 ,6495,6530,6534 ,0,0,0}, {9686,9801,9803 ,6514,6503,6530 ,0,0,0}, + {9684,9798,9801 ,6500,6527,6503 ,0,0,0}, {9680,9797,9683 ,6523,6522,6498 ,0,0,0}, + {9678,9795,9680 ,6501,6521,6523 ,0,0,0}, {9677,9792,9678 ,6500,6509,6501 ,0,0,0}, + {9674,9791,9677 ,6497,6520,6500 ,0,0,0}, {9674,9786,9789 ,6497,6509,6519 ,0,0,0}, + {9672,9785,9786 ,6508,6530,6509 ,0,0,0}, {9671,9783,9785 ,6495,6508,6530 ,0,0,0}, + {9668,9780,9783 ,6508,6504,6508 ,0,0,0}, {9666,9779,9780 ,6509,6495,6504 ,0,0,0}, + {9662,9777,9665 ,6504,6542,6496 ,0,0,0}, {9660,9774,9662 ,6507,6504,6504 ,0,0,0}, + {9659,9773,9660 ,6495,6542,6507 ,0,0,0}, {9658,9771,9659 ,6507,6495,6495 ,0,0,0}, + {9658,9829,9767 ,6507,6495,6495 ,0,0,0}, {9715,9830,9829 ,6501,6542,6495 ,0,0,0}, + {9716,9833,9830 ,6504,6496,6542 ,0,0,0}, {9719,9834,9833 ,6501,6504,6496 ,0,0,0}, + {9721,9836,9834 ,6544,6501,6504 ,0,0,0}, {9725,9839,9722 ,6495,6495,6501 ,0,0,0}, + {9727,9840,9725 ,6495,6496,6495 ,0,0,0}, {9728,9842,9727 ,6496,6495,6495 ,0,0,0}, + {9731,9845,9728 ,6496,6496,6496 ,0,0,0}, {9731,9848,9846 ,6496,6495,6497 ,0,0,0}, + {9733,9851,9848 ,6508,6504,6495 ,0,0,0}, {9734,9852,9851 ,6507,6507,6504 ,0,0,0}, + {9737,9854,9852 ,6495,6504,6507 ,0,0,0}, {9739,9857,9854 ,6495,6504,6504 ,0,0,0}, + {9743,9858,9740 ,6504,6504,6504 ,0,0,0}, {9745,9860,9743 ,6504,6546,6504 ,0,0,0}, + {9746,9863,9745 ,6548,6507,6504 ,0,0,0}, {9749,9864,9746 ,6548,6547,6548 ,0,0,0}, + {9749,9869,9866 ,6548,6547,6546 ,0,0,0}, {9751,9870,9869 ,6549,6549,6547 ,0,0,0}, + {9752,9872,9870 ,6550,6504,6549 ,0,0,0}, {9755,9875,9872 ,6549,6549,6504 ,0,0,0}, + {9757,9876,9875 ,6545,6504,6549 ,0,0,0}, {9758,9878,9759 ,6549,6549,6504 ,0,0,0}, + {9761,9881,9758 ,6545,6504,6549 ,0,0,0}, {9764,9882,9761 ,6515,6504,6545 ,0,0,0}, + {9766,9884,9764 ,6554,6551,6515 ,0,0,0}, {9766,11275,9887 ,6554,6545,6515 ,0,0,0}, + {11314,11274,11275 ,6515,6545,6545 ,0,0,0}, {11313,11273,11274 ,6504,6548,6545 ,0,0,0}, + {11326,11272,11273 ,6504,6548,6548 ,0,0,0}, {11316,11271,11272 ,6504,6553,6548 ,0,0,0}, + {11324,11270,11317 ,6549,6504,6554 ,0,0,0}, {11323,11269,11324 ,6504,6548,6549 ,0,0,0}, + {11325,11268,11323 ,6504,6504,6504 ,0,0,0}, {11320,11267,11325 ,6504,6504,6504 ,0,0,0}, + {11320,11265,11266 ,6504,6515,6504 ,0,0,0}, {11321,11264,11265 ,6504,6504,6515 ,0,0,0}, + {11322,11263,11264 ,6515,6504,6504 ,0,0,0}, {11318,11262,11263 ,6555,6515,6504 ,0,0,0}, + {11319,11260,11262 ,6504,6504,6515 ,0,0,0}, {11315,11261,11327 ,6508,6504,6544 ,0,0,0}, + {11329,11258,11315 ,6508,6552,6508 ,0,0,0}, {11328,11259,11329 ,6504,6515,6508 ,0,0,0}, + {11312,11256,11328 ,6508,6504,6504 ,0,0,0}, {11312,11254,11257 ,6508,6498,6515 ,0,0,0}, + {11330,11253,11254 ,6498,6508,6498 ,0,0,0}, {11311,11255,11253 ,6504,6504,6508 ,0,0,0}, + {11310,11251,11255 ,6498,6504,6504 ,0,0,0}, {11309,11252,11251 ,6504,6498,6504 ,0,0,0}, + {11307,11248,11308 ,6498,6498,6504 ,0,0,0}, {11306,11249,11307 ,6508,6508,6498 ,0,0,0}, + {11305,11250,11306 ,6508,6504,6508 ,0,0,0}, {11304,11245,11305 ,6504,6504,6508 ,0,0,0}, + {11304,11247,11246 ,6504,6498,6504 ,0,0,0}, {11303,11243,11247 ,6504,6504,6498 ,0,0,0}, + {11302,11242,11243 ,6498,6504,6504 ,0,0,0}, {11301,11244,11242 ,6515,6545,6504 ,0,0,0}, + {11300,11238,11244 ,6498,6508,6545 ,0,0,0}, {11298,11239,11299 ,6515,6504,6500 ,0,0,0}, + {11297,11240,11298 ,6500,6522,6515 ,0,0,0}, {11296,11241,11297 ,6504,6500,6500 ,0,0,0}, + {11293,11236,11296 ,6530,6504,6504 ,0,0,0}, {11293,11237,11276 ,6530,6508,6523 ,0,0,0}, + {11294,11232,11237 ,6544,6500,6508 ,0,0,0}, {11295,11233,11232 ,6498,6499,6500 ,0,0,0}, + {11290,11234,11280 ,6530,6498,6500 ,0,0,0}, {11291,11230,11235 ,6498,6527,6527 ,0,0,0}, + {11290,11235,11234 ,6530,6527,6498 ,0,0,0}, {11292,11281,11277 ,6499,6503,6503 ,0,0,0}, + {11291,11292,11230 ,6498,6499,6527 ,0,0,0}, {11281,11289,11231 ,6503,6508,6502 ,0,0,0}, + {11226,11288,11227 ,6538,6500,6559 ,0,0,0}, {11231,11289,11226 ,6502,6508,6538 ,0,0,0}, + {11229,11228,11287 ,6506,6533,6503 ,0,0,0}, {11228,11227,11288 ,6533,6559,6500 ,0,0,0}, + {11286,11224,11282 ,6500,6505,6498 ,0,0,0}, {11282,11229,11287 ,6498,6506,6503 ,0,0,0}, + {11332,11278,11286 ,6558,6543,6500 ,0,0,0}, {11331,11221,11225 ,6556,6512,6557 ,0,0,0}, + {11332,11225,11278 ,6558,6557,6543 ,0,0,0}, {11283,11285,11222 ,6510,6540,6511 ,0,0,0}, + {11331,11283,11221 ,6556,6510,6512 ,0,0,0}, {11223,11284,11279 ,6539,6538,6541 ,0,0,0}, + {11222,11285,11223 ,6511,6540,6539 ,0,0,0}, {9710,11279,11284 ,6500,6541,6538 ,0,0,0}, + {11284,9712,9710 ,6560,6561,6562 ,0,0,0}, {11331,11333,11283 ,6563,6564,6565 ,0,0,0}, + {11285,11334,11335 ,6566,6567,6568 ,0,0,0}, {11282,11287,11336 ,6569,6570,6571 ,0,0,0}, + {11332,11286,11337 ,6572,6573,6574 ,0,0,0}, {11338,11339,11281 ,6575,6576,6577 ,0,0,0}, + {11340,11341,11288 ,6578,6579,6580 ,0,0,0}, {11290,11280,11342 ,6581,6582,6583 ,0,0,0}, + {11292,11291,11343 ,6584,6585,6586 ,0,0,0}, {11344,11345,11293 ,6587,6588,6589 ,0,0,0}, + {11346,11295,11294 ,6590,6591,6592 ,0,0,0}, {11298,11299,11347 ,6593,6594,6595 ,0,0,0}, + {11297,11348,11349 ,6596,6597,6598 ,0,0,0}, {11350,11351,11302 ,6599,6600,6601 ,0,0,0}, + {11352,11353,11300 ,6602,6603,6604 ,0,0,0}, {11354,11305,11355 ,6605,6606,6607 ,0,0,0}, + {11303,11304,11356 ,6608,6609,6610 ,0,0,0}, {11307,11308,11357 ,6611,6612,6613 ,0,0,0}, + {11307,11358,11306 ,6611,6614,6615 ,0,0,0}, {11311,11359,11310 ,6616,6617,6618 ,0,0,0}, + {11360,11361,11309 ,6619,6620,6621 ,0,0,0}, {11312,11362,11330 ,6622,6623,6624 ,0,0,0}, + {11363,11311,11330 ,6625,6616,6624 ,0,0,0}, {11364,11365,11329 ,6626,6627,6628 ,0,0,0}, + {11366,11328,11365 ,6629,6630,6627 ,0,0,0}, {11367,11368,11327 ,6631,6632,6633 ,0,0,0}, + {11364,11315,11368 ,6626,6634,6632 ,0,0,0}, {11318,11369,11319 ,6635,6636,6637 ,0,0,0}, + {11367,11319,11369 ,6631,6637,6636 ,0,0,0}, {11318,11322,11370 ,6635,6638,6639 ,0,0,0}, + {11370,11369,11318 ,6639,6636,6635 ,0,0,0}, {11371,11322,11321 ,6640,6638,6641 ,0,0,0}, + {11322,11371,11370 ,6638,6640,6639 ,0,0,0}, {11320,11372,11321 ,6642,6643,6641 ,0,0,0}, + {11371,11321,11372 ,6640,6641,6643 ,0,0,0}, {11320,11325,11373 ,6642,6644,6645 ,0,0,0}, + {11373,11372,11320 ,6645,6643,6642 ,0,0,0}, {11374,11325,11323 ,6646,6644,6647 ,0,0,0}, + {11325,11374,11373 ,6644,6646,6645 ,0,0,0}, {11324,11375,11323 ,6648,6649,6647 ,0,0,0}, + {11374,11323,11375 ,6646,6647,6649 ,0,0,0}, {11324,11317,11376 ,6648,6650,6651 ,0,0,0}, + {11376,11375,11324 ,6651,6649,6648 ,0,0,0}, {11377,11317,11316 ,6652,6650,6653 ,0,0,0}, + {11317,11377,11376 ,6650,6652,6651 ,0,0,0}, {11316,11378,11379 ,6653,6654,6655 ,0,0,0}, + {11377,11316,11379 ,6652,6653,6655 ,0,0,0}, {11378,11326,11380 ,6654,6656,6657 ,0,0,0}, + {11326,11378,11316 ,6656,6654,6653 ,0,0,0}, {11380,11313,11314 ,6657,6658,6659 ,0,0,0}, + {11326,11313,11380 ,6656,6658,6657 ,0,0,0}, {9766,11381,11314 ,6660,6661,6659 ,0,0,0}, + {11380,11314,11381 ,6657,6659,6661 ,0,0,0}, {9765,11381,9766 ,6660,6661,6660 ,0,0,0}, + {11315,11327,11368 ,6634,6633,6632 ,0,0,0}, {11367,11327,11319 ,6631,6633,6637 ,0,0,0}, + {11328,11329,11365 ,6630,6628,6627 ,0,0,0}, {11364,11329,11315 ,6626,6628,6634 ,0,0,0}, + {11366,11362,11312 ,6629,6623,6622 ,0,0,0}, {11366,11312,11328 ,6629,6622,6630 ,0,0,0}, + {11359,11311,11363 ,6617,6616,6625 ,0,0,0}, {11362,11363,11330 ,6623,6625,6624 ,0,0,0}, + {11310,11360,11309 ,6618,6619,6621 ,0,0,0}, {11359,11360,11310 ,6617,6619,6618 ,0,0,0}, + {11308,11361,11357 ,6612,6620,6613 ,0,0,0}, {11309,11361,11308 ,6621,6620,6612 ,0,0,0}, + {11358,11355,11306 ,6614,6607,6615 ,0,0,0}, {11307,11357,11358 ,6611,6613,6614 ,0,0,0}, + {11304,11305,11354 ,6609,6606,6605 ,0,0,0}, {11305,11306,11355 ,6606,6615,6607 ,0,0,0}, + {11350,11303,11356 ,6599,6608,6610 ,0,0,0}, {11356,11304,11354 ,6610,6609,6605 ,0,0,0}, + {11351,11301,11302 ,6600,6662,6601 ,0,0,0}, {11350,11302,11303 ,6599,6601,6608 ,0,0,0}, + {11300,11301,11352 ,6604,6662,6602 ,0,0,0}, {11351,11352,11301 ,6600,6602,6662 ,0,0,0}, + {11299,11353,11347 ,6594,6603,6595 ,0,0,0}, {11300,11353,11299 ,6604,6603,6594 ,0,0,0}, + {11297,11298,11348 ,6596,6593,6597 ,0,0,0}, {11298,11347,11348 ,6593,6595,6597 ,0,0,0}, + {11344,11296,11349 ,6587,6663,6598 ,0,0,0}, {11296,11297,11349 ,6663,6596,6598 ,0,0,0}, + {11345,11294,11293 ,6588,6592,6589 ,0,0,0}, {11344,11293,11296 ,6587,6589,6663 ,0,0,0}, + {11346,11382,11295 ,6590,6664,6591 ,0,0,0}, {11345,11346,11294 ,6588,6590,6592 ,0,0,0}, + {11342,11280,11382 ,6583,6582,6664 ,0,0,0}, {11295,11382,11280 ,6591,6664,6582 ,0,0,0}, + {11291,11290,11383 ,6585,6581,6665 ,0,0,0}, {11290,11342,11383 ,6581,6583,6665 ,0,0,0}, + {11338,11292,11343 ,6575,6584,6586 ,0,0,0}, {11343,11291,11383 ,6586,6585,6665 ,0,0,0}, + {11339,11289,11281 ,6576,6666,6577 ,0,0,0}, {11338,11281,11292 ,6575,6577,6584 ,0,0,0}, + {11288,11289,11340 ,6580,6666,6578 ,0,0,0}, {11339,11340,11289 ,6576,6578,6666 ,0,0,0}, + {11287,11341,11336 ,6570,6579,6571 ,0,0,0}, {11288,11341,11287 ,6580,6579,6570 ,0,0,0}, + {11286,11282,11384 ,6573,6569,6667 ,0,0,0}, {11282,11336,11384 ,6569,6571,6667 ,0,0,0}, + {11333,11332,11337 ,6564,6572,6574 ,0,0,0}, {11337,11286,11384 ,6574,6573,6667 ,0,0,0}, + {11333,11334,11283 ,6564,6567,6565 ,0,0,0}, {11333,11331,11332 ,6564,6563,6572 ,0,0,0}, + {11335,11385,11285 ,6568,6668,6566 ,0,0,0}, {11283,11334,11285 ,6565,6567,6566 ,0,0,0}, + {9712,11284,11385 ,6561,6560,6668 ,0,0,0}, {11285,11385,11284 ,6566,6668,6560 ,0,0,0}, + {9676,9679,9583 ,6669,6670,6671 ,0,0,0}, {11338,11343,11386 ,6672,6671,6671 ,0,0,0}, + {9589,9685,9598 ,6673,6674,6671 ,0,0,0}, {9679,9681,9592 ,6670,6669,6675 ,0,0,0}, + {9691,9621,9593 ,6670,6676,6677 ,0,0,0}, {11387,11388,11356 ,6324,6298,6672 ,0,0,0}, + {11389,11348,11347 ,6671,6672,6671 ,0,0,0}, {11390,11391,11352 ,6672,6671,6671 ,0,0,0}, + {9704,9615,9611 ,6678,6671,6679 ,0,0,0}, {11349,11348,11392 ,6671,6672,6680 ,0,0,0}, + {9617,9711,9619 ,6679,6671,6671 ,0,0,0}, {11393,11394,11346 ,6672,6672,6672 ,0,0,0}, + {11395,11396,11333 ,6672,6681,6672 ,0,0,0}, {11385,11335,11397 ,6671,6681,6672 ,0,0,0}, + {11398,11340,11339 ,6672,6672,6681 ,0,0,0}, {11336,11399,11400 ,6672,6672,6672 ,0,0,0}, + {11401,11384,11400 ,6672,6671,6672 ,0,0,0}, {11338,11402,11339 ,6672,6671,6681 ,0,0,0}, + {11341,11398,11399 ,6672,6672,6672 ,0,0,0}, {11395,11337,11401 ,6672,6672,6672 ,0,0,0}, + {11403,11404,11383 ,6671,6672,6672 ,0,0,0}, {11335,11334,11405 ,6681,6671,6671 ,0,0,0}, + {11342,11406,11403 ,6671,6681,6671 ,0,0,0}, {9712,11385,9619 ,6671,6671,6671 ,0,0,0}, + {11382,11394,11406 ,6672,6672,6681 ,0,0,0}, {9615,9705,9616 ,6671,6682,6672 ,0,0,0}, + {9617,9616,9706 ,6679,6672,6298 ,0,0,0}, {11349,11407,11344 ,6671,6671,6672 ,0,0,0}, + {11407,11393,11345 ,6671,6672,6672 ,0,0,0}, {9699,9700,9607 ,6672,6681,6670 ,0,0,0}, + {9611,9613,9703 ,6679,6669,6669 ,0,0,0}, {11391,11408,11353 ,6671,6672,6671 ,0,0,0}, + {9697,9699,9609 ,6671,6672,6681 ,0,0,0}, {9604,9621,9693 ,6669,6676,6298 ,0,0,0}, + {9604,9694,9697 ,6669,6669,6671 ,0,0,0}, {11409,11350,11388 ,6672,6671,6298 ,0,0,0}, + {11409,11390,11351 ,6672,6672,6672 ,0,0,0}, {9687,9595,9598 ,6683,6669,6671 ,0,0,0}, + {9593,9595,9688 ,6677,6669,6684 ,0,0,0}, {11358,11410,11355 ,6671,6685,6686 ,0,0,0}, + {11387,11354,11355 ,6324,6687,6686 ,0,0,0}, {11358,11357,11411 ,6671,6688,6688 ,0,0,0}, + {9681,9682,9588 ,6669,6689,6684 ,0,0,0}, {11412,11413,11360 ,6672,6690,6671 ,0,0,0}, + {11413,11414,11361 ,6690,6686,6690 ,0,0,0}, {11415,11412,11359 ,6691,6672,6691 ,0,0,0}, + {9583,9586,9675 ,6671,6692,6672 ,0,0,0}, {9585,9673,9586 ,6693,6673,6692 ,0,0,0}, + {9578,9670,9585 ,6672,6689,6693 ,0,0,0}, {11363,11416,11415 ,6686,6690,6691 ,0,0,0}, + {9669,9578,9581 ,6694,6672,6695 ,0,0,0}, {11362,11417,11416 ,6690,6691,6690 ,0,0,0}, + {9581,9580,9667 ,6695,6696,6697 ,0,0,0}, {11417,11366,11365 ,6691,6672,6688 ,0,0,0}, + {9575,9663,9664 ,6698,6699,6700 ,0,0,0}, {11418,11419,11364 ,6672,6688,6688 ,0,0,0}, + {11368,11367,11420 ,6688,6691,6701 ,0,0,0}, {11421,11369,11370 ,6686,6672,6671 ,0,0,0}, + {9661,9663,9523 ,6676,6699,6702 ,0,0,0}, {11371,11422,11423 ,6672,6671,6671 ,0,0,0}, + {9661,9522,9657 ,6676,6687,6703 ,0,0,0}, {11424,11372,11373 ,6686,6704,6672 ,0,0,0}, + {9522,9570,9713 ,6687,6705,6676 ,0,0,0}, {11375,11425,11374 ,6686,6706,6672 ,0,0,0}, + {9656,9714,9570 ,6698,6699,6705 ,0,0,0}, {9718,9561,9560 ,6697,6707,6708 ,0,0,0}, + {9717,9656,9561 ,6709,6698,6707 ,0,0,0}, {11426,11378,11380 ,6690,6671,6701 ,0,0,0}, + {9560,9654,9720 ,6708,6672,6694 ,0,0,0}, {11381,9548,11427 ,6690,6690,6686 ,0,0,0}, + {9724,9723,9652 ,6673,6689,6710 ,0,0,0}, {9546,9548,9763 ,6711,6690,6690 ,0,0,0}, + {9726,9724,9650 ,6686,6673,6692 ,0,0,0}, {9760,9544,9762 ,6712,6713,6685 ,0,0,0}, + {9645,9646,9732 ,6714,6684,6669 ,0,0,0}, {9756,9541,9543 ,6715,6716,6717 ,0,0,0}, + {9641,9738,9640 ,6718,6719,6691 ,0,0,0}, {9744,9742,9529 ,6298,6670,6676 ,0,0,0}, + {9750,9534,9536 ,6686,6704,6720 ,0,0,0}, {9536,9538,9753 ,6720,6669,6715 ,0,0,0}, + {9744,9531,9747 ,6298,6718,6669 ,0,0,0}, {9531,9534,9748 ,6718,6704,6691 ,0,0,0}, + {11419,11365,11364 ,6688,6688,6688 ,0,0,0}, {9639,9742,9741 ,6676,6670,6684 ,0,0,0}, + {9756,9754,9541 ,6715,6669,6716 ,0,0,0}, {9543,9544,9760 ,6717,6713,6712 ,0,0,0}, + {9543,9760,9756 ,6717,6712,6715 ,0,0,0}, {9644,9735,9646 ,6673,6721,6684 ,0,0,0}, + {9644,9640,9736 ,6673,6691,6670 ,0,0,0}, {9546,9763,9762 ,6711,6690,6685 ,0,0,0}, + {9546,9762,9544 ,6711,6685,6713 ,0,0,0}, {9649,9729,9726 ,6691,6669,6686 ,0,0,0}, + {9730,9649,9645 ,6720,6691,6714 ,0,0,0}, {9765,9763,9548 ,6671,6690,6690 ,0,0,0}, + {11379,11428,11429 ,6686,6722,6688 ,0,0,0}, {11376,11377,11430 ,6691,6723,6706 ,0,0,0}, + {9754,9753,9538 ,6669,6715,6669 ,0,0,0}, {9754,9538,9541 ,6669,6669,6716 ,0,0,0}, + {9753,9750,9536 ,6715,6686,6720 ,0,0,0}, {9750,9748,9534 ,6686,6691,6704 ,0,0,0}, + {9748,9747,9531 ,6691,6669,6718 ,0,0,0}, {9744,9529,9531 ,6298,6676,6718 ,0,0,0}, + {9742,9639,9529 ,6670,6676,6676 ,0,0,0}, {9741,9738,9641 ,6684,6719,6718 ,0,0,0}, + {9741,9641,9639 ,6684,6718,6676 ,0,0,0}, {9738,9736,9640 ,6719,6670,6691 ,0,0,0}, + {9736,9735,9644 ,6670,6721,6673 ,0,0,0}, {9735,9732,9646 ,6721,6669,6684 ,0,0,0}, + {9732,9730,9645 ,6669,6720,6714 ,0,0,0}, {9730,9729,9649 ,6720,6669,6691 ,0,0,0}, + {9726,9650,9649 ,6686,6692,6691 ,0,0,0}, {9724,9652,9650 ,6673,6710,6692 ,0,0,0}, + {9723,9720,9654 ,6689,6694,6672 ,0,0,0}, {9723,9654,9652 ,6689,6672,6710 ,0,0,0}, + {9720,9718,9560 ,6694,6697,6708 ,0,0,0}, {9718,9717,9561 ,6697,6709,6707 ,0,0,0}, + {9717,9714,9656 ,6709,6699,6698 ,0,0,0}, {9714,9713,9570 ,6699,6676,6705 ,0,0,0}, + {9713,9657,9522 ,6676,6703,6687 ,0,0,0}, {9661,9523,9522 ,6676,6702,6687 ,0,0,0}, + {9663,9575,9523 ,6699,6698,6702 ,0,0,0}, {9664,9667,9580 ,6700,6697,6696 ,0,0,0}, + {9664,9580,9575 ,6700,6696,6698 ,0,0,0}, {9667,9669,9581 ,6697,6694,6695 ,0,0,0}, + {9669,9670,9578 ,6694,6689,6672 ,0,0,0}, {9670,9673,9585 ,6689,6673,6693 ,0,0,0}, + {9673,9675,9586 ,6673,6672,6692 ,0,0,0}, {9675,9676,9583 ,6672,6669,6671 ,0,0,0}, + {9679,9592,9583 ,6670,6675,6671 ,0,0,0}, {9681,9588,9592 ,6669,6684,6675 ,0,0,0}, + {9682,9685,9589 ,6689,6674,6673 ,0,0,0}, {9682,9589,9588 ,6689,6673,6684 ,0,0,0}, + {9685,9687,9598 ,6674,6683,6671 ,0,0,0}, {9687,9688,9595 ,6683,6684,6669 ,0,0,0}, + {9688,9691,9593 ,6684,6670,6677 ,0,0,0}, {9691,9693,9621 ,6670,6298,6676 ,0,0,0}, + {9693,9694,9604 ,6298,6669,6669 ,0,0,0}, {9697,9609,9604 ,6671,6681,6669 ,0,0,0}, + {9699,9607,9609 ,6672,6670,6681 ,0,0,0}, {9700,9703,9613 ,6681,6669,6669 ,0,0,0}, + {9700,9613,9607 ,6681,6669,6670 ,0,0,0}, {9703,9704,9611 ,6669,6678,6679 ,0,0,0}, + {9704,9705,9615 ,6678,6682,6671 ,0,0,0}, {9705,9706,9616 ,6682,6298,6672 ,0,0,0}, + {9706,9711,9617 ,6298,6671,6679 ,0,0,0}, {9711,9712,9619 ,6671,6671,6671 ,0,0,0}, + {11385,11397,9619 ,6671,6672,6671 ,0,0,0}, {11335,11405,11397 ,6681,6671,6672 ,0,0,0}, + {11334,11333,11396 ,6671,6672,6681 ,0,0,0}, {11334,11396,11405 ,6671,6681,6671 ,0,0,0}, + {11333,11337,11395 ,6672,6672,6672 ,0,0,0}, {11337,11384,11401 ,6672,6671,6672 ,0,0,0}, + {11384,11336,11400 ,6671,6672,6672 ,0,0,0}, {11336,11341,11399 ,6672,6672,6672 ,0,0,0}, + {11341,11340,11398 ,6672,6672,6672 ,0,0,0}, {11339,11402,11398 ,6681,6671,6672 ,0,0,0}, + {11338,11386,11402 ,6672,6671,6671 ,0,0,0}, {11343,11383,11404 ,6671,6672,6672 ,0,0,0}, + {11343,11404,11386 ,6671,6672,6671 ,0,0,0}, {11383,11342,11403 ,6672,6671,6671 ,0,0,0}, + {11342,11382,11406 ,6671,6672,6681 ,0,0,0}, {11382,11346,11394 ,6672,6672,6672 ,0,0,0}, + {11346,11345,11393 ,6672,6672,6672 ,0,0,0}, {11345,11344,11407 ,6672,6672,6671 ,0,0,0}, + {11349,11392,11407 ,6671,6680,6671 ,0,0,0}, {11348,11389,11392 ,6672,6671,6680 ,0,0,0}, + {11347,11353,11408 ,6671,6671,6672 ,0,0,0}, {11347,11408,11389 ,6671,6672,6671 ,0,0,0}, + {11353,11352,11391 ,6671,6671,6671 ,0,0,0}, {11352,11351,11390 ,6671,6672,6672 ,0,0,0}, + {11351,11350,11409 ,6672,6671,6672 ,0,0,0}, {11350,11356,11388 ,6671,6672,6298 ,0,0,0}, + {11356,11354,11387 ,6672,6687,6324 ,0,0,0}, {11355,11410,11387 ,6686,6685,6324 ,0,0,0}, + {11358,11411,11410 ,6671,6688,6685 ,0,0,0}, {11357,11361,11414 ,6688,6690,6686 ,0,0,0}, + {11357,11414,11411 ,6688,6686,6688 ,0,0,0}, {11361,11360,11413 ,6690,6671,6690 ,0,0,0}, + {11360,11359,11412 ,6671,6691,6672 ,0,0,0}, {11359,11363,11415 ,6691,6686,6691 ,0,0,0}, + {11363,11362,11416 ,6686,6690,6690 ,0,0,0}, {11362,11366,11417 ,6690,6672,6691 ,0,0,0}, + {11365,11419,11417 ,6688,6688,6691 ,0,0,0}, {11368,11418,11364 ,6688,6672,6688 ,0,0,0}, + {11367,11431,11420 ,6691,6691,6701 ,0,0,0}, {11368,11420,11418 ,6688,6701,6672 ,0,0,0}, + {11421,11431,11369 ,6686,6691,6672 ,0,0,0}, {11367,11369,11431 ,6691,6672,6691 ,0,0,0}, + {11421,11370,11423 ,6686,6671,6671 ,0,0,0}, {11422,11371,11372 ,6671,6672,6704 ,0,0,0}, + {11423,11370,11371 ,6671,6671,6672 ,0,0,0}, {11424,11373,11374 ,6686,6672,6672 ,0,0,0}, + {11424,11422,11372 ,6686,6671,6704 ,0,0,0}, {11432,11425,11375 ,6688,6706,6686 ,0,0,0}, + {11425,11424,11374 ,6706,6686,6672 ,0,0,0}, {11432,11376,11430 ,6688,6691,6706 ,0,0,0}, + {11376,11432,11375 ,6691,6688,6686 ,0,0,0}, {11377,11429,11430 ,6723,6688,6706 ,0,0,0}, + {11379,11378,11428 ,6686,6671,6722 ,0,0,0}, {11377,11379,11429 ,6723,6686,6688 ,0,0,0}, + {11426,11380,11427 ,6690,6701,6686 ,0,0,0}, {11428,11378,11426 ,6722,6671,6690 ,0,0,0}, + {9548,11381,9765 ,6690,6690,6671 ,0,0,0}, {11427,11380,11381 ,6686,6701,6690 ,0,0,0}, + {11427,9125,10929 ,6724,6725,6726 ,0,0,0}, {10891,11428,11426 ,6727,6728,6729 ,0,0,0}, + {11430,10893,11432 ,6730,6731,6732 ,0,0,0}, {11034,11429,11032 ,6733,6734,6735 ,0,0,0}, + {11433,11043,11434 ,6736,6737,6738 ,0,0,0}, {10918,11433,11435 ,6739,6736,6736 ,0,0,0}, + {10959,11436,11437 ,6740,6741,6742 ,0,0,0}, {10958,11438,10917 ,6743,6744,6745 ,0,0,0}, + {11041,11439,11440 ,6746,6747,6748 ,0,0,0}, {11088,11441,11046 ,6749,6750,6751 ,0,0,0}, + {11442,11443,11086 ,6752,6753,6754 ,0,0,0}, {11439,10974,11087 ,6747,6755,6756 ,0,0,0}, + {11409,11010,11001 ,6757,6758,6759 ,0,0,0}, {9412,11010,11442 ,6760,6758,6752 ,0,0,0}, + {11391,11003,11408 ,6761,6762,6763 ,0,0,0}, {11002,11391,11390 ,6764,6761,6765 ,0,0,0}, + {11073,11008,11392 ,6766,6767,6768 ,0,0,0}, {11073,11389,11072 ,6766,6769,6770 ,0,0,0}, + {11407,11000,11393 ,6771,6772,6773 ,0,0,0}, {11000,11407,11008 ,6772,6771,6767 ,0,0,0}, + {11394,11393,10977 ,6774,6773,6775 ,0,0,0}, {11000,10977,11393 ,6772,6775,6773 ,0,0,0}, + {10975,11406,10976 ,6776,6777,6778 ,0,0,0}, {11394,10977,10976 ,6774,6775,6778 ,0,0,0}, + {10981,11404,10999 ,6779,6780,6781 ,0,0,0}, {11403,10975,10999 ,6782,6776,6781 ,0,0,0}, + {10980,11402,11386 ,6783,6784,6785 ,0,0,0}, {11399,11398,11444 ,6786,6787,6788 ,0,0,0}, + {11444,10998,11445 ,6788,6789,6788 ,0,0,0}, {11398,11402,10998 ,6787,6784,6789 ,0,0,0}, + {11446,10979,10952 ,6790,6791,6792 ,0,0,0}, {10979,11446,11445 ,6791,6790,6788 ,0,0,0}, + {10951,11447,10952 ,6793,6794,6792 ,0,0,0}, {11446,10952,11447 ,6790,6792,6794 ,0,0,0}, + {10951,10984,11448 ,6793,6795,6796 ,0,0,0}, {11448,11447,10951 ,6796,6794,6793 ,0,0,0}, + {11449,10984,10990 ,6797,6795,6798 ,0,0,0}, {10984,11449,11448 ,6795,6797,6796 ,0,0,0}, + {10994,11450,10990 ,6799,6800,6798 ,0,0,0}, {11449,10990,11450 ,6797,6798,6800 ,0,0,0}, + {10994,10987,11451 ,6799,6801,6802 ,0,0,0}, {11451,11450,10994 ,6802,6800,6799 ,0,0,0}, + {11452,10987,10996 ,6803,6801,6804 ,0,0,0}, {10987,11452,11451 ,6801,6803,6802 ,0,0,0}, + {9226,9629,10996 ,6805,6806,6804 ,0,0,0}, {11452,10996,9629 ,6803,6804,6806 ,0,0,0}, + {11396,11453,11454 ,6807,6808,6809 ,0,0,0}, {11398,10998,11444 ,6787,6789,6788 ,0,0,0}, + {11445,10998,10979 ,6788,6789,6791 ,0,0,0}, {10980,10998,11402 ,6783,6789,6784 ,0,0,0}, + {10981,10980,11386 ,6779,6783,6785 ,0,0,0}, {11386,11404,10981 ,6785,6780,6779 ,0,0,0}, + {10999,11404,11403 ,6781,6780,6782 ,0,0,0}, {10975,11403,11406 ,6776,6782,6777 ,0,0,0}, + {11406,11394,10976 ,6777,6774,6778 ,0,0,0}, {11444,11455,11399 ,6788,6810,6786 ,0,0,0}, + {11453,11396,11395 ,6808,6807,6811 ,0,0,0}, {11455,11400,11399 ,6810,6812,6786 ,0,0,0}, + {11454,11456,11405 ,6809,6813,6814 ,0,0,0}, {11405,11396,11454 ,6814,6807,6809 ,0,0,0}, + {11405,11457,11397 ,6814,6815,6816 ,0,0,0}, {11457,11405,11456 ,6815,6814,6813 ,0,0,0}, + {9619,11397,9620 ,6817,6816,6818 ,0,0,0}, {11457,9620,11397 ,6815,6818,6816 ,0,0,0}, + {11395,11458,11453 ,6811,6819,6808 ,0,0,0}, {11008,11407,11392 ,6767,6771,6768 ,0,0,0}, + {11458,11395,11401 ,6819,6811,6820 ,0,0,0}, {11459,11458,11401 ,6821,6819,6820 ,0,0,0}, + {11400,11455,11459 ,6812,6810,6821 ,0,0,0}, {11400,11459,11401 ,6812,6821,6820 ,0,0,0}, + {11392,11389,11073 ,6768,6769,6766 ,0,0,0}, {11039,11440,11441 ,6822,6748,6750 ,0,0,0}, + {11072,11408,11003 ,6770,6763,6762 ,0,0,0}, {11408,11072,11389 ,6763,6770,6769 ,0,0,0}, + {11391,11002,11003 ,6761,6764,6762 ,0,0,0}, {11001,11002,11390 ,6759,6764,6765 ,0,0,0}, + {11388,11010,11409 ,6823,6758,6757 ,0,0,0}, {11390,11409,11001 ,6765,6757,6759 ,0,0,0}, + {9412,11442,11086 ,6760,6752,6754 ,0,0,0}, {11388,11442,11010 ,6823,6752,6758 ,0,0,0}, + {11439,11041,10974 ,6747,6746,6755 ,0,0,0}, {11443,11439,11087 ,6753,6747,6756 ,0,0,0}, + {11441,11088,11039 ,6750,6749,6822 ,0,0,0}, {11460,11038,11461 ,6824,6825,6826 ,0,0,0}, + {11441,11461,11046 ,6750,6826,6751 ,0,0,0}, {11460,11436,10968 ,6824,6741,6827 ,0,0,0}, + {11038,11460,10968 ,6825,6824,6827 ,0,0,0}, {11437,11438,10958 ,6742,6744,6743 ,0,0,0}, + {10968,11436,10950 ,6827,6741,6828 ,0,0,0}, {11431,11421,11462 ,6829,6830,6831 ,0,0,0}, + {11422,11424,11435 ,6832,6833,6736 ,0,0,0}, {11438,11434,11037 ,6744,6738,6834 ,0,0,0}, + {11426,10929,10891 ,6729,6726,6727 ,0,0,0}, {11430,11429,11034 ,6730,6734,6733 ,0,0,0}, + {10894,10918,11425 ,6835,6739,6836 ,0,0,0}, {11052,11433,10918 ,6837,6736,6739 ,0,0,0}, + {11432,10894,11425 ,6732,6835,6836 ,0,0,0}, {11034,10893,11430 ,6733,6731,6730 ,0,0,0}, + {11432,10893,10894 ,6732,6731,6835 ,0,0,0}, {11428,11032,11429 ,6728,6735,6734 ,0,0,0}, + {11032,11428,10891 ,6735,6728,6727 ,0,0,0}, {10929,11426,11427 ,6726,6729,6724 ,0,0,0}, + {9125,11427,9548 ,6725,6724,6838 ,0,0,0}, {11410,11463,11387 ,6839,6840,6841 ,0,0,0}, + {11388,11387,11463 ,6823,6841,6840 ,0,0,0}, {11463,11410,11464 ,6840,6839,6842 ,0,0,0}, + {11388,11463,11442 ,6823,6840,6752 ,0,0,0}, {11465,11464,11411 ,6843,6842,6844 ,0,0,0}, + {11087,11086,11443 ,6756,6754,6753 ,0,0,0}, {11413,11465,11414 ,6845,6843,6846 ,0,0,0}, + {11413,11466,11465 ,6845,6847,6843 ,0,0,0}, {11467,11466,11412 ,6848,6847,6849 ,0,0,0}, + {11039,11041,11440 ,6822,6746,6748 ,0,0,0}, {11416,11467,11415 ,6850,6848,6851 ,0,0,0}, + {11416,11468,11467 ,6850,6852,6848 ,0,0,0}, {11469,11468,11417 ,6853,6852,6854 ,0,0,0}, + {11038,11046,11461 ,6825,6751,6826 ,0,0,0}, {11419,11470,11469 ,6855,6856,6853 ,0,0,0}, + {11418,11470,11419 ,6857,6856,6855 ,0,0,0}, {11471,11470,11420 ,6858,6856,6859 ,0,0,0}, + {10959,10950,11436 ,6740,6828,6741 ,0,0,0}, {11462,11471,11431 ,6831,6858,6829 ,0,0,0}, + {10958,10959,11437 ,6743,6740,6742 ,0,0,0}, {11472,11462,11423 ,6860,6831,6861 ,0,0,0}, + {11037,10917,11438 ,6834,6745,6744 ,0,0,0}, {11435,11472,11422 ,6736,6860,6832 ,0,0,0}, + {11043,11037,11434 ,6737,6834,6738 ,0,0,0}, {11425,10918,11435 ,6836,6739,6736 ,0,0,0}, + {11043,11433,11052 ,6737,6736,6837 ,0,0,0}, {11425,11435,11424 ,6836,6736,6833 ,0,0,0}, + {11423,11422,11472 ,6861,6832,6860 ,0,0,0}, {11421,11423,11462 ,6830,6861,6831 ,0,0,0}, + {11420,11431,11471 ,6859,6829,6858 ,0,0,0}, {11418,11420,11470 ,6857,6859,6856 ,0,0,0}, + {11417,11419,11469 ,6854,6855,6853 ,0,0,0}, {11416,11417,11468 ,6850,6854,6852 ,0,0,0}, + {11412,11415,11467 ,6849,6851,6848 ,0,0,0}, {11413,11412,11466 ,6845,6849,6847 ,0,0,0}, + {11411,11414,11465 ,6844,6846,6843 ,0,0,0}, {11410,11411,11464 ,6839,6844,6842 ,0,0,0}, + {11473,9420,9421 ,6862,6863,6864 ,0,0,0}, {11125,11114,10352 ,6865,6866,6867 ,0,0,0}, + {11474,11122,11121 ,6868,6869,6870 ,0,0,0}, {11124,10345,11111 ,6871,6872,6873 ,0,0,0}, + {10330,11104,11108 ,6874,6875,6876 ,0,0,0}, {10342,11127,11128 ,6877,6878,6879 ,0,0,0}, + {11138,10337,10336 ,6880,6881,6882 ,0,0,0}, {11135,10329,10332 ,6883,6884,6885 ,0,0,0}, + {11475,11148,11146 ,6886,6887,6888 ,0,0,0}, {11476,11142,10339 ,6889,6890,5525 ,0,0,0}, + {11159,11156,10415 ,6891,6892,6893 ,0,0,0}, {11152,11477,11478 ,6894,6895,6896 ,0,0,0}, + {11166,10404,11220 ,6897,6898,6899 ,0,0,0}, {11162,10410,11165 ,6900,6901,6902 ,0,0,0}, + {10451,11171,10449 ,6903,6904,6905 ,0,0,0}, {11214,11167,10447 ,6906,6907,6908 ,0,0,0}, + {11203,11479,11205 ,6909,6910,6911 ,0,0,0}, {11211,10452,11177 ,6912,6913,6914 ,0,0,0}, + {11480,11192,11184 ,6915,6916,6917 ,0,0,0}, {11202,11481,11189 ,6918,6919,6920 ,0,0,0}, + {11482,11199,11200 ,6921,6922,6923 ,0,0,0}, {10508,10511,11193 ,6924,6925,6926 ,0,0,0}, + {10508,11196,10509 ,6924,6927,5712 ,0,0,0}, {10496,10495,11186 ,6928,6929,6930 ,0,0,0}, + {10496,11201,10511 ,6928,6931,6925 ,0,0,0}, {11206,11208,10495 ,6932,6933,6929 ,0,0,0}, + {10495,11208,11186 ,6929,6933,6930 ,0,0,0}, {11206,10495,10540 ,6932,6929,6934 ,0,0,0}, + {10540,10542,11180 ,6934,6935,6936 ,0,0,0}, {11180,11206,10540 ,6936,6932,6934 ,0,0,0}, + {11212,10542,10544 ,6937,6935,6938 ,0,0,0}, {10542,11212,11180 ,6935,6937,6936 ,0,0,0}, + {11212,10544,11173 ,6937,6938,6939 ,0,0,0}, {10545,11174,11173 ,6940,6941,6939 ,0,0,0}, + {11173,10544,10545 ,6939,6938,6940 ,0,0,0}, {11174,10547,11218 ,6941,6942,6943 ,0,0,0}, + {10547,11174,10545 ,6942,6941,6940 ,0,0,0}, {11168,11218,10548 ,6944,6943,6945 ,0,0,0}, + {10547,10548,11218 ,6942,6945,6943 ,0,0,0}, {10548,11483,11163 ,6945,6946,6947 ,0,0,0}, + {11163,11168,10548 ,6947,6944,6945 ,0,0,0}, {11160,11483,11484 ,6948,6946,6949 ,0,0,0}, + {11483,11160,11163 ,6946,6948,6947 ,0,0,0}, {11485,11157,11484 ,6950,6951,6949 ,0,0,0}, + {11160,11484,11157 ,6948,6949,6951 ,0,0,0}, {11485,9518,9516 ,6950,126,3135 ,0,0,0}, + {9516,11157,11485 ,3135,6951,6950 ,0,0,0}, {10511,11201,11193 ,6925,6931,6926 ,0,0,0}, + {10496,11186,11201 ,6928,6930,6931 ,0,0,0}, {11196,11189,10509 ,6927,6920,5712 ,0,0,0}, + {10508,11193,11196 ,6924,6926,6927 ,0,0,0}, {11481,11202,11199 ,6919,6918,6922 ,0,0,0}, + {11481,10509,11189 ,6919,5712,6920 ,0,0,0}, {11482,11200,11192 ,6921,6923,6916 ,0,0,0}, + {11482,11481,11199 ,6921,6919,6922 ,0,0,0}, {11479,11480,11184 ,6910,6915,6917 ,0,0,0}, + {11480,11482,11192 ,6915,6921,6916 ,0,0,0}, {10454,11479,11203 ,6952,6910,6909 ,0,0,0}, + {11205,11479,11184 ,6911,6910,6917 ,0,0,0}, {10454,11177,10452 ,6952,6914,6913 ,0,0,0}, + {11177,10454,11203 ,6914,6952,6909 ,0,0,0}, {11209,10451,10452 ,6953,6903,6913 ,0,0,0}, + {11209,10452,11211 ,6953,6913,6912 ,0,0,0}, {11171,11216,10449 ,6904,6954,6905 ,0,0,0}, + {11209,11171,10451 ,6953,6904,6903 ,0,0,0}, {11214,10447,11216 ,6906,6908,6954 ,0,0,0}, + {10449,11216,10447 ,6905,6954,6908 ,0,0,0}, {10406,11167,11220 ,6955,6907,6899 ,0,0,0}, + {10447,11167,10406 ,6908,6907,6955 ,0,0,0}, {10416,10404,11166 ,6956,6898,6897 ,0,0,0}, + {10404,10406,11220 ,6898,6955,6899 ,0,0,0}, {10416,11165,10410 ,6956,6902,6901 ,0,0,0}, + {11165,10416,11166 ,6902,6956,6897 ,0,0,0}, {11159,10415,10410 ,6891,6893,6901 ,0,0,0}, + {11159,10410,11162 ,6891,6901,6900 ,0,0,0}, {11156,11154,11478 ,6892,6957,6896 ,0,0,0}, + {11156,11478,10415 ,6892,6896,6893 ,0,0,0}, {11152,11150,11477 ,6894,6958,6895 ,0,0,0}, + {11154,11152,11478 ,6957,6894,6896 ,0,0,0}, {11148,11475,11150 ,6887,6886,6958 ,0,0,0}, + {11477,11150,11475 ,6895,6958,6886 ,0,0,0}, {11476,11146,11144 ,6889,6888,6959 ,0,0,0}, + {11475,11146,11476 ,6886,6888,6889 ,0,0,0}, {10339,11142,11140 ,5525,6890,6960 ,0,0,0}, + {11476,11144,11142 ,6889,6959,6890 ,0,0,0}, {11140,11138,10336 ,6960,6880,6882 ,0,0,0}, + {10336,10339,11140 ,6882,5525,6960 ,0,0,0}, {11105,10332,10337 ,6961,6885,6881 ,0,0,0}, + {11105,10337,11138 ,6961,6881,6880 ,0,0,0}, {11135,11131,10329 ,6883,6962,6884 ,0,0,0}, + {11105,11135,10332 ,6961,6883,6885 ,0,0,0}, {10330,10329,11104 ,6874,6884,6875 ,0,0,0}, + {11131,11104,10329 ,6962,6875,6884 ,0,0,0}, {10335,11108,11127 ,6963,6876,6878 ,0,0,0}, + {10330,11108,10335 ,6874,6876,6963 ,0,0,0}, {10344,10342,11128 ,6964,6877,6879 ,0,0,0}, + {10342,10335,11127 ,6877,6963,6878 ,0,0,0}, {10344,11111,10345 ,6964,6873,6872 ,0,0,0}, + {11111,10344,11128 ,6873,6964,6879 ,0,0,0}, {11124,11125,10352 ,6871,6865,6867 ,0,0,0}, + {11124,10352,10345 ,6871,6867,6872 ,0,0,0}, {11114,11122,11486 ,6866,6869,6965 ,0,0,0}, + {11114,11486,10352 ,6866,6965,6867 ,0,0,0}, {11474,11121,11473 ,6868,6870,6862 ,0,0,0}, + {11486,11122,11474 ,6965,6869,6868 ,0,0,0}, {9420,11473,11121 ,6863,6862,6870 ,0,0,0}, + {9390,11487,11048 ,6966,6967,6968 ,0,0,0}, {11488,11092,11489 ,6969,6970,6971 ,0,0,0}, + {10960,10961,11490 ,6972,6973,6974 ,0,0,0}, {11094,11491,11095 ,6975,6976,6977 ,0,0,0}, + {11492,11493,11036 ,6978,6979,6980 ,0,0,0}, {11494,11091,11495 ,6981,6982,6983 ,0,0,0}, + {11093,11047,11496 ,6984,6985,6986 ,0,0,0}, {11098,11497,11498 ,6987,6988,6989 ,0,0,0}, + {11089,11499,11090 ,6990,6991,6992 ,0,0,0}, {11099,11500,10972 ,6993,6994,6995 ,0,0,0}, + {11501,11099,11040 ,6996,6993,6997 ,0,0,0}, {10973,11502,11100 ,6998,6999,7000 ,0,0,0}, + {11503,10973,10972 ,7001,6998,6995 ,0,0,0}, {11101,11100,11504 ,7002,7000,7003 ,0,0,0}, + {11502,11504,11100 ,6999,7003,7000 ,0,0,0}, {11505,11085,11101 ,7004,7005,7002 ,0,0,0}, + {11101,11504,11505 ,7002,7003,7004 ,0,0,0}, {11085,11506,11103 ,7005,7006,7007 ,0,0,0}, + {11506,11085,11505 ,7006,7005,7004 ,0,0,0}, {11102,11103,11507 ,7008,7007,7009 ,0,0,0}, + {11506,11507,11103 ,7006,7009,7007 ,0,0,0}, {11508,9412,11102 ,7010,82,7008 ,0,0,0}, + {11102,11507,11508 ,7008,7009,7010 ,0,0,0}, {9411,9412,11508 ,7011,82,7010 ,0,0,0}, + {11040,11498,11501 ,6997,6989,6996 ,0,0,0}, {11500,11503,10972 ,6994,7001,6995 ,0,0,0}, + {11503,11502,10973 ,7001,6999,6998 ,0,0,0}, {11500,11099,11501 ,6994,6993,6996 ,0,0,0}, + {11497,11098,11090 ,6988,6987,6992 ,0,0,0}, {11498,11040,11098 ,6989,6997,6987 ,0,0,0}, + {11090,11499,11497 ,6992,6991,6988 ,0,0,0}, {11494,11499,11089 ,6981,6991,6990 ,0,0,0}, + {11509,11095,11491 ,7012,6977,6976 ,0,0,0}, {11093,11495,11091 ,6984,6983,6982 ,0,0,0}, + {11089,11091,11494 ,6990,6982,6981 ,0,0,0}, {11047,11095,11509 ,6985,6977,7012 ,0,0,0}, + {11047,11509,11496 ,6985,7012,6986 ,0,0,0}, {11495,11093,11496 ,6983,6984,6986 ,0,0,0}, + {11092,10960,11489 ,6970,6972,6971 ,0,0,0}, {11491,11094,11493 ,6976,6975,6979 ,0,0,0}, + {11492,11036,11035 ,6978,6980,7013 ,0,0,0}, {11036,11493,11094 ,6980,6979,6975 ,0,0,0}, + {11035,11092,11488 ,7013,6970,6969 ,0,0,0}, {11035,11488,11492 ,7013,6969,6978 ,0,0,0}, + {10961,11487,11490 ,6973,6967,6974 ,0,0,0}, {11489,10960,11490 ,6971,6972,6974 ,0,0,0}, + {9390,11048,9387 ,6966,6968,7014 ,0,0,0}, {11487,10961,11048 ,6967,6973,6968 ,0,0,0}, + {11509,9405,11496 ,730,730,730 ,0,0,0}, {11504,11502,11500 ,730,730,730 ,0,0,0}, + {11502,11503,11500 ,730,730,730 ,0,0,0}, {11500,11501,11505 ,730,730,730 ,0,0,0}, + {11505,11504,11500 ,730,730,730 ,0,0,0}, {11506,11501,11498 ,730,730,730 ,0,0,0}, + {11501,11506,11505 ,730,730,730 ,0,0,0}, {11497,11507,11498 ,730,730,730 ,0,0,0}, + {11506,11498,11507 ,730,730,730 ,0,0,0}, {11508,11497,9411 ,730,730,730 ,0,0,0}, + {11508,11507,11497 ,730,730,730 ,0,0,0}, {11499,11494,9409 ,730,730,730 ,0,0,0}, + {11497,11499,9411 ,730,730,730 ,0,0,0}, {11491,9400,9403 ,730,730,7015 ,0,0,0}, + {9406,9409,11495 ,730,730,730 ,0,0,0}, {11488,9394,9397 ,7016,7015,7017 ,0,0,0}, + {11493,9397,9399 ,730,7017,7017 ,0,0,0}, {9391,9393,11490 ,730,730,730 ,0,0,0}, + {9390,9366,9368 ,730,730,730 ,0,0,0}, {9364,9391,11487 ,7015,730,730 ,0,0,0}, + {9370,9384,9382 ,730,730,7017 ,0,0,0}, {9366,9385,9372 ,730,7017,7015 ,0,0,0}, + {9378,9374,9379 ,730,730,730 ,0,0,0}, {9374,9382,9379 ,730,7017,730 ,0,0,0}, + {9375,9374,9378 ,730,730,730 ,0,0,0}, {9370,9372,9384 ,730,7015,730 ,0,0,0}, + {9374,9370,9382 ,730,730,7017 ,0,0,0}, {9385,9366,9389 ,7017,730,730 ,0,0,0}, + {9384,9372,9385 ,730,7015,7017 ,0,0,0}, {9390,9389,9366 ,730,730,730 ,0,0,0}, + {11487,9368,9364 ,730,730,7015 ,0,0,0}, {11487,9390,9368 ,730,730,730 ,0,0,0}, + {9393,11489,11490 ,730,7016,730 ,0,0,0}, {11490,11487,9391 ,730,730,730 ,0,0,0}, + {11488,11489,9394 ,7016,7016,7015 ,0,0,0}, {9393,9394,11489 ,730,7015,7016 ,0,0,0}, + {9397,11493,11492 ,7017,730,730 ,0,0,0}, {9397,11492,11488 ,7017,730,7016 ,0,0,0}, + {9399,9400,11491 ,7017,730,730 ,0,0,0}, {11493,9399,11491 ,730,7017,730 ,0,0,0}, + {9403,9405,11509 ,7015,730,730 ,0,0,0}, {11491,9403,11509 ,730,7015,730 ,0,0,0}, + {11496,9406,11495 ,730,730,730 ,0,0,0}, {11496,9405,9406 ,730,730,730 ,0,0,0}, + {11499,9409,9411 ,730,730,730 ,0,0,0}, {11494,11495,9409 ,730,730,730 ,0,0,0}, + {11510,11511,9362 ,7018,7019,7020 ,0,0,0}, {9362,11512,11510 ,7020,7021,7018 ,0,0,0}, + {9362,9345,11512 ,7020,7022,7021 ,0,0,0}, {9362,11513,11514 ,7020,7023,7024 ,0,0,0}, + {11511,11513,9362 ,7019,7023,7020 ,0,0,0}, {9362,11515,11516 ,7020,7025,7026 ,0,0,0}, + {11514,11515,9362 ,7024,7025,7020 ,0,0,0}, {11516,11517,9362 ,7026,7027,7020 ,0,0,0}, + {11518,9362,11519 ,7028,7020,7029 ,0,0,0}, {9362,11517,11519 ,7020,7027,7029 ,0,0,0}, + {11520,9362,11521 ,7030,7020,7031 ,0,0,0}, {9362,11518,11521 ,7020,7028,7031 ,0,0,0}, + {11522,9362,11523 ,7032,7020,7033 ,0,0,0}, {9362,11520,11523 ,7020,7030,7033 ,0,0,0}, + {9361,9362,11522 ,7034,7020,7032 ,0,0,0}, {9344,11017,11512 ,7035,7036,7037 ,0,0,0}, + {11514,11513,11007 ,7038,7039,7040 ,0,0,0}, {11511,11510,11016 ,7041,7042,7043 ,0,0,0}, + {11516,11074,11517 ,7044,7045,7046 ,0,0,0}, {11006,11019,11515 ,7047,7048,7049 ,0,0,0}, + {11075,10900,11518 ,7050,7051,7052 ,0,0,0}, {11075,11519,10966 ,7050,7053,7054 ,0,0,0}, + {10964,11023,11520 ,7055,7056,7057 ,0,0,0}, {11520,11521,10964 ,7057,7058,7055 ,0,0,0}, + {11523,11023,11009 ,7059,7056,7060 ,0,0,0}, {11023,11523,11520 ,7056,7059,7057 ,0,0,0}, + {10997,11522,11009 ,7061,7062,7060 ,0,0,0}, {11523,11009,11522 ,7059,7060,7062 ,0,0,0}, + {10997,9360,9361 ,7061,7063,4910 ,0,0,0}, {9361,11522,10997 ,4910,7062,7061 ,0,0,0}, + {11074,11516,11019 ,7045,7044,7048 ,0,0,0}, {10900,11521,11518 ,7051,7058,7052 ,0,0,0}, + {10964,11521,10900 ,7055,7058,7051 ,0,0,0}, {11007,11513,11015 ,7040,7039,7064 ,0,0,0}, + {10966,11519,11517 ,7054,7053,7046 ,0,0,0}, {11075,11518,11519 ,7050,7052,7053 ,0,0,0}, + {11074,10966,11517 ,7045,7054,7046 ,0,0,0}, {11515,11019,11516 ,7049,7048,7044 ,0,0,0}, + {11514,11007,11006 ,7038,7040,7047 ,0,0,0}, {11006,11515,11514 ,7047,7049,7038 ,0,0,0}, + {11510,11017,11016 ,7042,7036,7043 ,0,0,0}, {11015,11511,11016 ,7064,7041,7043 ,0,0,0}, + {11513,11511,11015 ,7039,7041,7064 ,0,0,0}, {9344,11512,9345 ,7035,7037,4929 ,0,0,0}, + {11017,11510,11512 ,7036,7042,7037 ,0,0,0}, {11524,11525,9328 ,7018,7019,7065 ,0,0,0}, + {9328,11526,11524 ,7065,7021,7018 ,0,0,0}, {9328,9311,11526 ,7065,7066,7021 ,0,0,0}, + {9328,11527,11528 ,7065,7023,7024 ,0,0,0}, {11525,11527,9328 ,7019,7023,7065 ,0,0,0}, + {9328,11529,11530 ,7065,7025,7026 ,0,0,0}, {11528,11529,9328 ,7024,7025,7065 ,0,0,0}, + {11530,11531,9328 ,7026,7027,7065 ,0,0,0}, {11532,9328,11533 ,7028,7065,7029 ,0,0,0}, + {9328,11531,11533 ,7065,7027,7029 ,0,0,0}, {11534,9328,11535 ,7030,7065,7031 ,0,0,0}, + {9328,11532,11535 ,7065,7028,7031 ,0,0,0}, {11536,9328,11537 ,7032,7065,7033 ,0,0,0}, + {9328,11534,11537 ,7065,7030,7033 ,0,0,0}, {9327,9328,11536 ,7067,7065,7032 ,0,0,0}, + {9310,11066,11526 ,7068,7069,7070 ,0,0,0}, {11528,11527,10907 ,7071,7072,7073 ,0,0,0}, + {11525,11524,10946 ,7074,7075,7076 ,0,0,0}, {11530,10926,11531 ,7077,7078,7079 ,0,0,0}, + {10908,11071,11529 ,7047,7080,7081 ,0,0,0}, {10890,11069,11532 ,7082,7083,7084 ,0,0,0}, + {10890,11533,11070 ,7082,7085,7086 ,0,0,0}, {11068,10944,11534 ,7087,7088,7089 ,0,0,0}, + {11534,11535,11068 ,7089,7090,7087 ,0,0,0}, {11537,10944,10945 ,7091,7088,7092 ,0,0,0}, + {10944,11537,11534 ,7088,7091,7089 ,0,0,0}, {11067,11536,10945 ,7093,7094,7092 ,0,0,0}, + {11537,10945,11536 ,7091,7092,7094 ,0,0,0}, {11067,9326,9327 ,7093,4831,4942 ,0,0,0}, + {9327,11536,11067 ,4942,7094,7093 ,0,0,0}, {10926,11530,11071 ,7078,7077,7080 ,0,0,0}, + {11069,11535,11532 ,7083,7090,7084 ,0,0,0}, {11068,11535,11069 ,7087,7090,7083 ,0,0,0}, + {10907,11527,10943 ,7073,7072,7095 ,0,0,0}, {11070,11533,11531 ,7086,7085,7079 ,0,0,0}, + {10890,11532,11533 ,7082,7084,7085 ,0,0,0}, {10926,11070,11531 ,7078,7086,7079 ,0,0,0}, + {11529,11071,11530 ,7081,7080,7077 ,0,0,0}, {11528,10907,10908 ,7071,7073,7047 ,0,0,0}, + {10908,11529,11528 ,7047,7081,7071 ,0,0,0}, {11524,11066,10946 ,7075,7069,7076 ,0,0,0}, + {10943,11525,10946 ,7095,7074,7076 ,0,0,0}, {11527,11525,10943 ,7072,7074,7095 ,0,0,0}, + {9310,11526,9311 ,7068,7070,4899 ,0,0,0}, {11066,11524,11526 ,7069,7075,7070 ,0,0,0}, + {11538,11539,9294 ,7018,7019,7065 ,0,0,0}, {9294,11540,11538 ,7065,7021,7018 ,0,0,0}, + {9294,9277,11540 ,7065,7096,7021 ,0,0,0}, {9294,11541,11542 ,7065,7023,7024 ,0,0,0}, + {11539,11541,9294 ,7019,7023,7065 ,0,0,0}, {9294,11543,11544 ,7065,7025,7026 ,0,0,0}, + {11542,11543,9294 ,7024,7025,7065 ,0,0,0}, {11544,11545,9294 ,7026,7027,7065 ,0,0,0}, + {11546,9294,11547 ,7028,7065,7029 ,0,0,0}, {9294,11545,11547 ,7065,7027,7029 ,0,0,0}, + {11548,9294,11549 ,7030,7065,7031 ,0,0,0}, {9294,11546,11549 ,7065,7028,7031 ,0,0,0}, + {11550,9294,11551 ,7032,7065,7033 ,0,0,0}, {9294,11548,11551 ,7065,7030,7033 ,0,0,0}, + {9293,9294,11550 ,7097,7065,7032 ,0,0,0}, {9276,11064,11540 ,7098,7099,7100 ,0,0,0}, + {11542,11541,11029 ,7101,7102,7103 ,0,0,0}, {11539,11538,11056 ,7104,7105,7076 ,0,0,0}, + {11544,11028,11545 ,7106,7107,7108 ,0,0,0}, {11063,11062,11543 ,7109,7110,7111 ,0,0,0}, + {10940,10937,11546 ,7112,7113,7114 ,0,0,0}, {10940,11547,11057 ,7112,7115,7116 ,0,0,0}, + {10942,10941,11548 ,7117,7118,7119 ,0,0,0}, {11548,11549,10942 ,7119,7120,7117 ,0,0,0}, + {11551,10941,10939 ,7121,7118,7122 ,0,0,0}, {10941,11551,11548 ,7118,7121,7119 ,0,0,0}, + {10938,11550,10939 ,7123,7124,7122 ,0,0,0}, {11551,10939,11550 ,7121,7122,7124 ,0,0,0}, + {10938,9292,9293 ,7123,4831,4831 ,0,0,0}, {9293,11550,10938 ,4831,7124,7123 ,0,0,0}, + {11028,11544,11062 ,7107,7106,7110 ,0,0,0}, {10937,11549,11546 ,7113,7120,7114 ,0,0,0}, + {10942,11549,10937 ,7117,7120,7113 ,0,0,0}, {11029,11541,11055 ,7103,7102,7125 ,0,0,0}, + {11057,11547,11545 ,7116,7115,7108 ,0,0,0}, {10940,11546,11547 ,7112,7114,7115 ,0,0,0}, + {11028,11057,11545 ,7107,7116,7108 ,0,0,0}, {11543,11062,11544 ,7111,7110,7106 ,0,0,0}, + {11542,11029,11063 ,7101,7103,7109 ,0,0,0}, {11063,11543,11542 ,7109,7111,7101 ,0,0,0}, + {11538,11064,11056 ,7105,7099,7076 ,0,0,0}, {11055,11539,11056 ,7125,7104,7076 ,0,0,0}, + {11541,11539,11055 ,7102,7104,7125 ,0,0,0}, {9276,11540,9277 ,7098,7100,4865 ,0,0,0}, + {11064,11538,11540 ,7099,7105,7100 ,0,0,0}, {11552,11553,9260 ,7018,7019,7126 ,0,0,0}, + {9260,11554,11552 ,7126,7021,7018 ,0,0,0}, {9260,9243,11554 ,7126,7127,7021 ,0,0,0}, + {9260,11555,11556 ,7126,7023,7024 ,0,0,0}, {11553,11555,9260 ,7019,7023,7126 ,0,0,0}, + {9260,11557,11558 ,7126,7025,7026 ,0,0,0}, {11556,11557,9260 ,7024,7025,7126 ,0,0,0}, + {11558,11559,9260 ,7026,7027,7126 ,0,0,0}, {11560,9260,11561 ,7028,7126,7029 ,0,0,0}, + {9260,11559,11561 ,7126,7027,7029 ,0,0,0}, {11562,9260,11563 ,7030,7126,7031 ,0,0,0}, + {9260,11560,11563 ,7126,7028,7031 ,0,0,0}, {11564,9260,11565 ,7032,7126,7033 ,0,0,0}, + {9260,11562,11565 ,7126,7030,7033 ,0,0,0}, {9259,9260,11564 ,7128,7126,7032 ,0,0,0}, + {9242,11045,11554 ,7129,7099,7130 ,0,0,0}, {11556,11555,11050 ,7131,7132,7133 ,0,0,0}, + {11553,11552,11044 ,7041,7075,7134 ,0,0,0}, {11558,11051,11559 ,7135,7107,7136 ,0,0,0}, + {11049,11077,11557 ,7137,7138,7139 ,0,0,0}, {10927,10928,11560 ,7140,7141,7142 ,0,0,0}, + {10927,11561,11033 ,7140,7143,7144 ,0,0,0}, {11011,11012,11562 ,7145,7146,7147 ,0,0,0}, + {11562,11563,11011 ,7147,7148,7145 ,0,0,0}, {11565,11012,11097 ,7149,7146,7150 ,0,0,0}, + {11012,11565,11562 ,7146,7149,7147 ,0,0,0}, {11096,11564,11097 ,7151,7152,7150 ,0,0,0}, + {11565,11097,11564 ,7149,7150,7152 ,0,0,0}, {11096,9258,9259 ,7151,7153,4831 ,0,0,0}, + {9259,11564,11096 ,4831,7152,7151 ,0,0,0}, {11051,11558,11077 ,7107,7135,7138 ,0,0,0}, + {10928,11563,11560 ,7141,7148,7142 ,0,0,0}, {11011,11563,10928 ,7145,7148,7141 ,0,0,0}, + {11050,11555,11053 ,7133,7132,7154 ,0,0,0}, {11033,11561,11559 ,7144,7143,7136 ,0,0,0}, + {10927,11560,11561 ,7140,7142,7143 ,0,0,0}, {11051,11033,11559 ,7107,7144,7136 ,0,0,0}, + {11557,11077,11558 ,7139,7138,7135 ,0,0,0}, {11556,11050,11049 ,7131,7133,7137 ,0,0,0}, + {11049,11557,11556 ,7137,7139,7131 ,0,0,0}, {11552,11045,11044 ,7075,7099,7134 ,0,0,0}, + {11053,11553,11044 ,7154,7041,7134 ,0,0,0}, {11555,11553,11053 ,7132,7041,7154 ,0,0,0}, + {9242,11554,9243 ,7129,7130,4929 ,0,0,0}, {11045,11552,11554 ,7099,7075,7130 ,0,0,0}, + {9203,9202,11566 ,4777,21,7155 ,0,0,0}, {10910,10923,11567 ,7156,7157,7158 ,0,0,0}, + {10919,11568,11569 ,7159,7160,7161 ,0,0,0}, {11570,11571,10901 ,7162,7163,7164 ,0,0,0}, + {11572,10967,10925 ,7165,7166,7167 ,0,0,0}, {10978,11022,11573 ,7168,7169,7170 ,0,0,0}, + {10963,11574,11575 ,7171,7172,7173 ,0,0,0}, {10953,11576,10985 ,7174,7175,7176 ,0,0,0}, + {11577,11578,10982 ,7177,7178,7179 ,0,0,0}, {11579,11580,10991 ,7180,7181,7182 ,0,0,0}, + {11581,10983,10985 ,7183,7184,7176 ,0,0,0}, {11582,11583,10992 ,7185,7186,7187 ,0,0,0}, + {11582,10989,11580 ,7185,7188,7181 ,0,0,0}, {10993,11583,11584 ,7189,7186,7190 ,0,0,0}, + {11583,10993,10992 ,7186,7189,7187 ,0,0,0}, {11585,10988,11584 ,7191,7192,7190 ,0,0,0}, + {10993,11584,10988 ,7189,7190,7192 ,0,0,0}, {11585,11586,10986 ,7191,7193,7194 ,0,0,0}, + {10986,10988,11585 ,7194,7192,7191 ,0,0,0}, {10995,11586,11587 ,7195,7193,7196 ,0,0,0}, + {11586,10995,10986 ,7193,7195,7194 ,0,0,0}, {9225,10996,11587 ,7197,7198,7196 ,0,0,0}, + {10995,11587,10996 ,7195,7196,7198 ,0,0,0}, {9226,10996,9225 ,7199,7198,7197 ,0,0,0}, + {10953,11578,11576 ,7174,7178,7175 ,0,0,0}, {10989,10991,11580 ,7188,7182,7181 ,0,0,0}, + {11582,10992,10989 ,7185,7187,7188 ,0,0,0}, {10983,11581,11579 ,7184,7183,7180 ,0,0,0}, + {11579,10991,10983 ,7180,7182,7184 ,0,0,0}, {11581,10985,11576 ,7183,7176,7175 ,0,0,0}, + {11578,10953,10982 ,7178,7174,7179 ,0,0,0}, {10978,11573,11577 ,7168,7170,7177 ,0,0,0}, + {10978,11577,10982 ,7168,7177,7179 ,0,0,0}, {10967,11570,10901 ,7166,7162,7164 ,0,0,0}, + {11575,11022,10963 ,7173,7169,7171 ,0,0,0}, {11022,11575,11573 ,7169,7173,7170 ,0,0,0}, + {10902,10901,11571 ,7200,7164,7163 ,0,0,0}, {10963,10902,11574 ,7171,7200,7172 ,0,0,0}, + {11574,10902,11571 ,7172,7200,7163 ,0,0,0}, {11572,11570,10967 ,7165,7162,7166 ,0,0,0}, + {11588,11572,10925 ,7201,7165,7167 ,0,0,0}, {10910,11567,11588 ,7156,7158,7201 ,0,0,0}, + {10910,11588,10925 ,7156,7201,7167 ,0,0,0}, {11024,11566,11568 ,7202,7155,7160 ,0,0,0}, + {11569,10923,10919 ,7161,7157,7159 ,0,0,0}, {10923,11569,11567 ,7157,7161,7158 ,0,0,0}, + {11024,11568,10919 ,7202,7160,7159 ,0,0,0}, {11566,11024,9203 ,7155,7202,4777 ,0,0,0}, + {9191,11579,9194 ,730,7015,730 ,0,0,0}, {11569,11568,11574 ,730,730,730 ,0,0,0}, + {9201,9197,11578 ,730,730,730 ,0,0,0}, {9195,11581,11576 ,730,730,7015 ,0,0,0}, + {11575,11574,11568 ,730,730,730 ,0,0,0}, {9202,11577,11566 ,730,730,730 ,0,0,0}, + {11572,11588,11567 ,730,730,730 ,0,0,0}, {11567,11569,11571 ,730,730,730 ,0,0,0}, + {11567,11571,11570 ,730,730,730 ,0,0,0}, {11572,11567,11570 ,730,730,730 ,0,0,0}, + {11568,11566,11575 ,730,730,730 ,0,0,0}, {11571,11569,11574 ,730,730,730 ,0,0,0}, + {11566,11573,11575 ,730,730,730 ,0,0,0}, {11577,9202,11578 ,730,730,730 ,0,0,0}, + {11573,11566,11577 ,730,730,730 ,0,0,0}, {11578,9197,11576 ,730,730,7015 ,0,0,0}, + {11578,9202,9201 ,730,730,730 ,0,0,0}, {11581,9195,9194 ,730,730,730 ,0,0,0}, + {11576,9197,9195 ,7015,730,730 ,0,0,0}, {11580,11579,9191 ,730,7015,730 ,0,0,0}, + {11579,11581,9194 ,7015,730,730 ,0,0,0}, {11582,9191,9190 ,7015,730,730 ,0,0,0}, + {9191,11582,11580 ,730,7015,730 ,0,0,0}, {11582,9190,11583 ,7015,730,730 ,0,0,0}, + {9183,11583,9187 ,730,730,730 ,0,0,0}, {11583,9190,9187 ,730,730,730 ,0,0,0}, + {9183,9182,11584 ,730,730,7015 ,0,0,0}, {11584,11583,9183 ,7015,730,730 ,0,0,0}, + {11584,9182,11585 ,7015,730,7015 ,0,0,0}, {9186,11586,11585 ,730,730,7015 ,0,0,0}, + {11585,9182,9186 ,7015,730,730 ,0,0,0}, {11586,9181,11587 ,730,730,7015 ,0,0,0}, + {9181,11586,9186 ,730,730,730 ,0,0,0}, {9177,9225,9181 ,730,7015,730 ,0,0,0}, + {11587,9181,9225 ,7015,730,7015 ,0,0,0}, {9224,9206,9222 ,7015,7015,730 ,0,0,0}, + {9177,9176,9224 ,730,730,7015 ,0,0,0}, {9218,9213,9216 ,7015,7015,7015 ,0,0,0}, + {9210,9219,9207 ,7015,7015,730 ,0,0,0}, {9218,9210,9212 ,7015,7015,7015 ,0,0,0}, + {9213,9218,9212 ,7015,7015,7015 ,0,0,0}, {9222,9207,9219 ,730,730,7015 ,0,0,0}, + {9219,9210,9218 ,7015,7015,7015 ,0,0,0}, {9224,9176,9206 ,7015,730,7015 ,0,0,0}, + {9222,9206,9207 ,730,7015,730 ,0,0,0}, {9224,9225,9177 ,7015,7015,730 ,0,0,0}, + {9153,10884,11589 ,126,7203,7204 ,0,0,0}, {11590,11591,10886 ,7205,7206,7207 ,0,0,0}, + {10936,11592,11004 ,7208,7209,7210 ,0,0,0}, {11025,11027,11593 ,7211,7212,7213 ,0,0,0}, + {11594,10897,11595 ,7214,7215,7216 ,0,0,0}, {11596,11597,10922 ,7217,7218,7219 ,0,0,0}, + {10947,11598,11065 ,7220,7221,7222 ,0,0,0}, {10916,11599,11600 ,7223,7224,7225 ,0,0,0}, + {10914,10915,11601 ,7226,7227,7228 ,0,0,0}, {10912,10906,11602 ,7229,7230,7231 ,0,0,0}, + {11603,10913,10912 ,7232,7233,7229 ,0,0,0}, {10904,10905,11604 ,7234,7235,7236 ,0,0,0}, + {11605,10906,10904 ,7237,7230,7234 ,0,0,0}, {10903,11606,10905 ,7238,7239,7235 ,0,0,0}, + {11604,10905,11606 ,7236,7235,7239 ,0,0,0}, {11607,10903,10896 ,7240,7238,7241 ,0,0,0}, + {10903,11607,11606 ,7238,7240,7239 ,0,0,0}, {10896,10895,11608 ,7241,7242,7243 ,0,0,0}, + {11608,11607,10896 ,7243,7240,7241 ,0,0,0}, {10892,11609,10895 ,7244,7245,7242 ,0,0,0}, + {11608,10895,11609 ,7243,7242,7245 ,0,0,0}, {11610,10892,9175 ,7246,7244,82 ,0,0,0}, + {10892,11610,11609 ,7244,7246,7245 ,0,0,0}, {9173,11610,9175 ,7011,7246,82 ,0,0,0}, + {10913,11603,11599 ,7233,7232,7224 ,0,0,0}, {11602,10906,11605 ,7231,7230,7237 ,0,0,0}, + {11605,10904,11604 ,7237,7234,7236 ,0,0,0}, {11602,11603,10912 ,7231,7232,7229 ,0,0,0}, + {11600,10915,10916 ,7225,7227,7223 ,0,0,0}, {11599,10916,10913 ,7224,7223,7233 ,0,0,0}, + {10915,11600,11601 ,7227,7225,7228 ,0,0,0}, {11596,10914,11601 ,7217,7226,7228 ,0,0,0}, + {11611,11593,11027 ,7247,7213,7212 ,0,0,0}, {10947,10922,11597 ,7220,7219,7218 ,0,0,0}, + {10914,11596,10922 ,7226,7217,7219 ,0,0,0}, {11065,11611,11027 ,7222,7247,7212 ,0,0,0}, + {11065,11598,11611 ,7222,7221,7247 ,0,0,0}, {11597,11598,10947 ,7218,7221,7220 ,0,0,0}, + {10886,11591,10936 ,7207,7206,7208 ,0,0,0}, {11593,11595,11025 ,7213,7216,7211 ,0,0,0}, + {11594,10899,10897 ,7214,7248,7215 ,0,0,0}, {10897,11025,11595 ,7215,7211,7216 ,0,0,0}, + {10899,11590,10886 ,7248,7205,7207 ,0,0,0}, {10899,11594,11590 ,7248,7214,7205 ,0,0,0}, + {11004,11592,11589 ,7210,7209,7204 ,0,0,0}, {11591,11592,10936 ,7206,7209,7208 ,0,0,0}, + {9153,9150,10884 ,126,4726,7203 ,0,0,0}, {11589,10884,11004 ,7204,7203,7210 ,0,0,0}, + {11604,11602,11605 ,7249,7250,7251 ,0,0,0}, {9155,11591,9157 ,726,726,7252 ,0,0,0}, + {11607,11602,11606 ,7253,7250,7253 ,0,0,0}, {11602,11604,11606 ,7250,7249,7253 ,0,0,0}, + {11603,11607,11608 ,7254,7253,7249 ,0,0,0}, {11607,11603,11602 ,7253,7254,7250 ,0,0,0}, + {11608,11609,11599 ,7249,7249,7255 ,0,0,0}, {11599,11603,11608 ,7255,7254,7249 ,0,0,0}, + {11609,11600,11599 ,7249,7256,7255 ,0,0,0}, {11610,9173,11600 ,7257,7257,7256 ,0,0,0}, + {11610,11600,11609 ,7257,7256,7249 ,0,0,0}, {11601,9172,11596 ,7258,726,7259 ,0,0,0}, + {11600,9173,11601 ,7256,7257,7258 ,0,0,0}, {11611,11598,9167 ,7260,7254,7257 ,0,0,0}, + {9169,11597,9172 ,7252,7261,726 ,0,0,0}, {9160,11595,9161 ,726,7262,7252 ,0,0,0}, + {9166,9163,11593 ,726,7252,7263 ,0,0,0}, {11592,9155,9154 ,7253,726,726 ,0,0,0}, + {11590,9160,9157 ,726,726,7252 ,0,0,0}, {9153,9130,9129 ,726,726,726 ,0,0,0}, + {9128,11589,9154 ,7264,7253,726 ,0,0,0}, {9134,9146,9147 ,726,7257,726 ,0,0,0}, + {9129,9135,9149 ,726,7264,726 ,0,0,0}, {9141,9143,9137 ,7257,726,7257 ,0,0,0}, + {9143,9146,9137 ,726,7257,7257 ,0,0,0}, {9141,9137,9139 ,7257,7257,7257 ,0,0,0}, + {9147,9135,9134 ,726,7264,726 ,0,0,0}, {9146,9134,9137 ,7257,726,7257 ,0,0,0}, + {9151,9129,9149 ,726,726,726 ,0,0,0}, {9149,9135,9147 ,726,7264,726 ,0,0,0}, + {9130,9153,11589 ,726,726,7253 ,0,0,0}, {9129,9151,9153 ,726,726,726 ,0,0,0}, + {9154,11589,11592 ,726,7253,7253 ,0,0,0}, {9130,11589,9128 ,726,7253,7264 ,0,0,0}, + {9157,11591,11590 ,7252,726,726 ,0,0,0}, {11591,9155,11592 ,726,726,7253 ,0,0,0}, + {11595,9160,11594 ,7262,726,7262 ,0,0,0}, {11594,9160,11590 ,7262,726,726 ,0,0,0}, + {9163,9161,11593 ,7252,7252,7263 ,0,0,0}, {9161,11595,11593 ,7252,7262,7263 ,0,0,0}, + {11593,11611,9166 ,7263,7260,726 ,0,0,0}, {9169,9167,11598 ,7252,7257,7254 ,0,0,0}, + {9167,9166,11611 ,7257,726,7260 ,0,0,0}, {9172,11597,11596 ,726,7261,7259 ,0,0,0}, + {9169,11598,11597 ,7252,7254,7261 ,0,0,0}, {9172,11601,9173 ,726,7258,7257 ,0,0,0}, + {9103,11612,10878 ,4799,7265,7266 ,0,0,0}, {11613,10880,11614 ,7267,7268,7269 ,0,0,0}, + {10879,11054,11615 ,7270,7271,7272 ,0,0,0}, {11061,11616,10888 ,7273,7274,7275 ,0,0,0}, + {11617,11618,11060 ,7276,7277,7278 ,0,0,0}, {11619,11058,11620 ,7279,7280,7281 ,0,0,0}, + {11078,11030,11621 ,7282,7283,7284 ,0,0,0}, {11079,11622,11623 ,7285,7286,7287 ,0,0,0}, + {10933,11624,10934 ,7288,7289,7290 ,0,0,0}, {11080,11625,10931 ,7291,7292,7293 ,0,0,0}, + {11626,11080,10889 ,7294,7291,7295 ,0,0,0}, {10930,11627,11081 ,7296,7297,7298 ,0,0,0}, + {11628,10930,10931 ,7299,7296,7293 ,0,0,0}, {11082,11081,11629 ,7300,7298,7301 ,0,0,0}, + {11627,11629,11081 ,7297,7301,7298 ,0,0,0}, {11630,11031,11082 ,7302,7303,7300 ,0,0,0}, + {11082,11629,11630 ,7300,7301,7302 ,0,0,0}, {11031,11631,11084 ,7303,7304,7305 ,0,0,0}, + {11631,11031,11630 ,7304,7303,7302 ,0,0,0}, {11083,11084,11632 ,7306,7305,7307 ,0,0,0}, + {11631,11632,11084 ,7304,7307,7305 ,0,0,0}, {11633,9125,11083 ,7308,21,7306 ,0,0,0}, + {11083,11632,11633 ,7306,7307,7308 ,0,0,0}, {9124,9125,11633 ,7309,21,7308 ,0,0,0}, + {10889,11623,11626 ,7295,7287,7294 ,0,0,0}, {11625,11628,10931 ,7292,7299,7293 ,0,0,0}, + {11628,11627,10930 ,7299,7297,7296 ,0,0,0}, {11625,11080,11626 ,7292,7291,7294 ,0,0,0}, + {11622,11079,10934 ,7286,7285,7290 ,0,0,0}, {11623,10889,11079 ,7287,7295,7285 ,0,0,0}, + {10934,11624,11622 ,7290,7289,7286 ,0,0,0}, {11619,11624,10933 ,7279,7289,7288 ,0,0,0}, + {11634,10888,11616 ,7310,7275,7274 ,0,0,0}, {11078,11620,11058 ,7282,7281,7280 ,0,0,0}, + {10933,11058,11619 ,7288,7280,7279 ,0,0,0}, {11030,10888,11634 ,7283,7275,7310 ,0,0,0}, + {11030,11634,11621 ,7283,7310,7284 ,0,0,0}, {11620,11078,11621 ,7281,7282,7284 ,0,0,0}, + {10880,10879,11614 ,7268,7270,7269 ,0,0,0}, {11616,11061,11618 ,7274,7273,7277 ,0,0,0}, + {11617,11060,11059 ,7276,7278,7311 ,0,0,0}, {11060,11618,11061 ,7278,7277,7273 ,0,0,0}, + {11059,10880,11613 ,7311,7268,7267 ,0,0,0}, {11059,11613,11617 ,7311,7267,7276 ,0,0,0}, + {11054,11612,11615 ,7271,7265,7272 ,0,0,0}, {11614,10879,11615 ,7269,7270,7272 ,0,0,0}, + {9103,10878,9100 ,4799,7266,7199 ,0,0,0}, {11612,11054,10878 ,7265,7271,7266 ,0,0,0}, + {11625,9095,9092 ,730,7312,6103 ,0,0,0}, {9088,11629,9091 ,7313,730,730 ,0,0,0}, + {9098,11622,9102 ,7314,7015,7315 ,0,0,0}, {11626,11623,9097 ,730,730,7316 ,0,0,0}, + {11621,11615,11620 ,730,7317,7313 ,0,0,0}, {11624,11612,9103 ,730,7318,7319 ,0,0,0}, + {11613,11614,11634 ,7320,7316,7316 ,0,0,0}, {11616,11618,11613 ,7320,6103,7320 ,0,0,0}, + {11617,11613,11618 ,6111,7320,6103 ,0,0,0}, {11621,11634,11614 ,730,7316,7316 ,0,0,0}, + {11634,11616,11613 ,7316,7320,7320 ,0,0,0}, {11612,11620,11615 ,7318,7313,7317 ,0,0,0}, + {11615,11621,11614 ,7317,730,7316 ,0,0,0}, {11624,11619,11612 ,730,7316,7318 ,0,0,0}, + {11612,11619,11620 ,7318,7316,7313 ,0,0,0}, {9102,11622,9103 ,7315,7015,7319 ,0,0,0}, + {9103,11622,11624 ,7319,7015,730 ,0,0,0}, {9097,11623,9098 ,7316,730,7314 ,0,0,0}, + {9098,11623,11622 ,7314,730,7015 ,0,0,0}, {11626,9097,9095 ,730,7316,7312 ,0,0,0}, + {9092,11628,11625 ,6103,7017,730 ,0,0,0}, {9095,11625,11626 ,7312,730,730 ,0,0,0}, + {11628,9092,11627 ,7017,6103,7017 ,0,0,0}, {9091,11629,11627 ,730,730,7017 ,0,0,0}, + {11627,9092,9091 ,7017,6103,730 ,0,0,0}, {11629,9088,9087 ,730,7313,730 ,0,0,0}, + {9087,9083,11630 ,730,7316,730 ,0,0,0}, {11630,11629,9087 ,730,730,730 ,0,0,0}, + {11631,9083,9085 ,7016,7316,7313 ,0,0,0}, {9083,11631,11630 ,7316,7016,730 ,0,0,0}, + {9079,11632,9085 ,7015,730,7313 ,0,0,0}, {11631,9085,11632 ,7016,7313,730 ,0,0,0}, + {11633,9079,9124 ,730,7015,730 ,0,0,0}, {11633,11632,9079 ,730,730,7015 ,0,0,0}, + {9079,9081,9124 ,7015,7015,730 ,0,0,0}, {9122,9104,9119 ,730,730,730 ,0,0,0}, + {9081,9077,9122 ,7015,730,730 ,0,0,0}, {9116,9112,9113 ,730,730,7017 ,0,0,0}, + {9107,9118,9106 ,7015,7016,730 ,0,0,0}, {9116,9107,9110 ,730,7015,730 ,0,0,0}, + {9112,9116,9110 ,730,730,730 ,0,0,0}, {9119,9106,9118 ,730,730,7016 ,0,0,0}, + {9118,9107,9116 ,7016,7015,730 ,0,0,0}, {9122,9077,9104 ,730,730,730 ,0,0,0}, + {9119,9104,9106 ,730,730,730 ,0,0,0}, {9122,9124,9081 ,730,730,7015 ,0,0,0}, + {9635,11635,11636 ,7321,1711,7322 ,0,0,0}, {9625,9622,11637 ,7323,7324,7325 ,0,0,0}, + {11638,9624,9633 ,7326,7327,7328 ,0,0,0}, {11451,11639,11450 ,7329,7330,7331 ,0,0,0}, + {11640,11641,9629 ,7332,7333,7334 ,0,0,0}, {11448,11642,11447 ,7335,7336,7337 ,0,0,0}, + {11642,11449,11643 ,7336,7338,7339 ,0,0,0}, {11446,11447,11644 ,7340,7337,7341 ,0,0,0}, + {11642,11644,11447 ,7336,7341,7337 ,0,0,0}, {11645,11445,11446 ,1359,1359,7340 ,0,0,0}, + {11446,11644,11645 ,7340,7341,1359 ,0,0,0}, {11643,11449,11450 ,7339,7338,7331 ,0,0,0}, + {11642,11448,11449 ,7336,7335,7338 ,0,0,0}, {11639,11451,11452 ,7330,7329,7342 ,0,0,0}, + {11639,11643,11450 ,7330,7339,7331 ,0,0,0}, {11452,9629,11641 ,7342,7334,7333 ,0,0,0}, + {11641,11639,11452 ,7333,7330,7342 ,0,0,0}, {9628,11637,11640 ,7343,7325,7332 ,0,0,0}, + {9628,11640,9629 ,7343,7332,7334 ,0,0,0}, {9622,11646,11637 ,7324,7344,7325 ,0,0,0}, + {9628,9625,11637 ,7343,7323,7325 ,0,0,0}, {11638,11646,9624 ,7326,7344,7327 ,0,0,0}, + {9622,9624,11646 ,7324,7327,7344 ,0,0,0}, {11638,9632,11636 ,7326,7345,7322 ,0,0,0}, + {9633,9632,11638 ,7328,7345,7326 ,0,0,0}, {11635,9635,9601 ,1711,7321,1711 ,0,0,0}, + {11636,9632,9635 ,7322,7345,7321 ,0,0,0}, {11635,9603,11647 ,2197,7346,7346 ,0,0,0}, + {9603,11635,9601 ,7346,2197,2197 ,0,0,0}, {11648,11649,11455 ,1435,7347,7348 ,0,0,0}, + {11456,11454,11650 ,7349,7350,7351 ,0,0,0}, {11453,11458,11651 ,7352,7353,7354 ,0,0,0}, + {9614,11652,9612 ,7355,7356,7357 ,0,0,0}, {11653,11654,9620 ,7358,7359,7360 ,0,0,0}, + {9608,11655,9606 ,7361,7362,7363 ,0,0,0}, {9608,9610,11655 ,7361,7364,7362 ,0,0,0}, + {9605,9606,11656 ,7365,7363,7366 ,0,0,0}, {11655,11656,9606 ,7362,7366,7363 ,0,0,0}, + {11647,9603,9605 ,1790,1790,7365 ,0,0,0}, {9605,11656,11647 ,7365,7366,1790 ,0,0,0}, + {9612,11657,9610 ,7357,7367,7364 ,0,0,0}, {11655,9610,11657 ,7362,7364,7367 ,0,0,0}, + {11453,11658,11454 ,7352,7368,7350 ,0,0,0}, {9614,9618,11652 ,7355,7369,7356 ,0,0,0}, + {11652,11657,9612 ,7356,7367,7357 ,0,0,0}, {9618,9620,11654 ,7369,7360,7359 ,0,0,0}, + {11654,11652,9618 ,7359,7356,7369 ,0,0,0}, {11653,9620,11457 ,7358,7360,7370 ,0,0,0}, + {11650,11457,11456 ,7351,7370,7349 ,0,0,0}, {11457,11650,11653 ,7370,7351,7358 ,0,0,0}, + {11658,11650,11454 ,7368,7351,7350 ,0,0,0}, {11651,11459,11649 ,7354,7371,7347 ,0,0,0}, + {11459,11651,11458 ,7371,7354,7353 ,0,0,0}, {11658,11453,11651 ,7368,7352,7354 ,0,0,0}, + {11648,11455,11444 ,1435,7348,1435 ,0,0,0}, {11649,11459,11455 ,7347,7371,7348 ,0,0,0}, + {11444,11645,11648 ,1398,7372,1398 ,0,0,0}, {11645,11444,11445 ,7372,1398,7372 ,0,0,0}, + {11645,11649,11648 ,7373,730,730 ,0,0,0}, {11646,11655,11657 ,730,730,730 ,0,0,0}, + {11643,11650,11658 ,7374,7375,7375 ,0,0,0}, {11658,11651,11642 ,7375,730,7373 ,0,0,0}, + {11641,11654,11653 ,7375,7375,7375 ,0,0,0}, {11653,11650,11639 ,7375,7375,730 ,0,0,0}, + {11657,11652,11637 ,730,730,7376 ,0,0,0}, {11652,11654,11640 ,730,7375,7375 ,0,0,0}, + {11636,11656,11638 ,730,730,730 ,0,0,0}, {11655,11638,11656 ,730,730,730 ,0,0,0}, + {11636,11635,11647 ,730,730,730 ,0,0,0}, {11647,11656,11636 ,730,730,730 ,0,0,0}, + {11657,11637,11646 ,730,7376,730 ,0,0,0}, {11655,11646,11638 ,730,730,730 ,0,0,0}, + {11652,11640,11637 ,730,7375,7376 ,0,0,0}, {11654,11641,11640 ,7375,7375,7375 ,0,0,0}, + {11653,11639,11641 ,7375,730,7375 ,0,0,0}, {11650,11643,11639 ,7375,7374,730 ,0,0,0}, + {11658,11642,11643 ,7375,7373,7374 ,0,0,0}, {11651,11644,11642 ,730,730,7373 ,0,0,0}, + {11645,11644,11649 ,7373,730,730 ,0,0,0}, {11651,11649,11644 ,730,730,730 ,0,0,0}, + {11659,9533,11660 ,7377,1435,1435 ,0,0,0}, {11661,9549,11662 ,7378,7379,7379 ,0,0,0}, + {11663,9524,9528 ,7380,7380,7377 ,0,0,0}, {9556,11664,11665 ,7381,7381,7382 ,0,0,0}, + {9551,11666,9554 ,7378,7383,7383 ,0,0,0}, {9563,11667,9565 ,7384,7385,7385 ,0,0,0}, + {11668,9563,9558 ,7384,7384,7382 ,0,0,0}, {9568,9565,11669 ,7386,7385,7386 ,0,0,0}, + {11667,11669,9565 ,7385,7386,7385 ,0,0,0}, {11670,9571,9568 ,7387,7388,7386 ,0,0,0}, + {9568,11669,11670 ,7386,7386,7387 ,0,0,0}, {11665,11668,9558 ,7382,7384,7382 ,0,0,0}, + {11668,11667,9563 ,7384,7385,7384 ,0,0,0}, {9554,11664,9556 ,7383,7381,7381 ,0,0,0}, + {9556,11665,9558 ,7381,7382,7382 ,0,0,0}, {9551,11661,11666 ,7378,7378,7383 ,0,0,0}, + {9554,11666,11664 ,7383,7383,7381 ,0,0,0}, {9549,9524,11662 ,7379,7380,7379 ,0,0,0}, + {9551,9549,11661 ,7378,7379,7378 ,0,0,0}, {11663,9528,11659 ,7380,7377,7377 ,0,0,0}, + {11662,9524,11663 ,7379,7380,7380 ,0,0,0}, {9533,11659,9528 ,1435,7377,7377 ,0,0,0}, + {11660,9530,11671 ,1398,1398,1398 ,0,0,0}, {9530,11660,9533 ,1398,1398,1398 ,0,0,0}, + {11672,11673,9655 ,7389,7390,7390 ,0,0,0}, {11674,9651,11675 ,7391,7391,7392 ,0,0,0}, + {9653,9562,11676 ,7392,7393,7393 ,0,0,0}, {9643,11677,11678 ,7394,7395,7394 ,0,0,0}, + {9648,11679,9647 ,7396,7396,7395 ,0,0,0}, {9638,11680,11681 ,7397,7398,7397 ,0,0,0}, + {11680,9638,9642 ,7398,7397,7398 ,0,0,0}, {11682,9636,11681 ,7399,7399,7397 ,0,0,0}, + {9638,11681,9636 ,7397,7397,7399 ,0,0,0}, {11682,11671,9530 ,7399,1359,1359 ,0,0,0}, + {9530,9636,11682 ,1359,7399,7399 ,0,0,0}, {11675,9653,11676 ,7392,7392,7393 ,0,0,0}, + {9642,9643,11678 ,7398,7394,7394 ,0,0,0}, {11678,11680,9642 ,7394,7398,7398 ,0,0,0}, + {11677,9643,9647 ,7395,7394,7395 ,0,0,0}, {11674,11679,9648 ,7391,7396,7396 ,0,0,0}, + {9647,11679,11677 ,7395,7396,7395 ,0,0,0}, {9653,11675,9651 ,7392,7392,7391 ,0,0,0}, + {9648,9651,11674 ,7396,7391,7391 ,0,0,0}, {9655,11673,9562 ,7390,7390,7393 ,0,0,0}, + {9562,11673,11676 ,7393,7390,7393 ,0,0,0}, {11672,9655,9521 ,7389,7390,7400 ,0,0,0}, + {11670,11672,9521 ,7401,7402,7402 ,0,0,0}, {11670,9521,9571 ,7401,7402,7401 ,0,0,0}, + {11682,11663,11659 ,7403,7403,7404 ,0,0,0}, {11668,11676,11667 ,7375,7375,730 ,0,0,0}, + {11664,11674,11665 ,7375,730,730 ,0,0,0}, {11675,11668,11665 ,730,7375,730 ,0,0,0}, + {11661,11677,11666 ,7373,7375,7373 ,0,0,0}, {11679,11664,11666 ,730,7375,7373 ,0,0,0}, + {11662,11681,11680 ,7405,7406,730 ,0,0,0}, {11678,11661,11662 ,7373,7373,7405 ,0,0,0}, + {11682,11681,11663 ,7403,7406,7403 ,0,0,0}, {11659,11660,11671 ,7404,730,7407 ,0,0,0}, + {11671,11682,11659 ,7407,7403,7404 ,0,0,0}, {11681,11662,11663 ,7406,7405,7403 ,0,0,0}, + {11678,11662,11680 ,7373,7405,730 ,0,0,0}, {11677,11661,11678 ,7375,7373,7373 ,0,0,0}, + {11679,11666,11677 ,730,7373,7375 ,0,0,0}, {11674,11664,11679 ,730,7375,730 ,0,0,0}, + {11675,11665,11674 ,730,730,730 ,0,0,0}, {11676,11668,11675 ,7375,7375,730 ,0,0,0}, + {11673,11667,11676 ,730,730,7375 ,0,0,0}, {11669,11673,11672 ,7373,730,730 ,0,0,0}, + {11673,11669,11667 ,730,7373,730 ,0,0,0}, {11669,11672,11670 ,7373,730,7405 ,0,0,0}, + {11683,11442,11684 ,7408,7409,7410 ,0,0,0}, {11685,11440,11686 ,7411,7412,7412 ,0,0,0}, + {11687,11439,11443 ,7413,7413,7408 ,0,0,0}, {11460,11688,11689 ,7414,7414,7415 ,0,0,0}, + {11441,11690,11461 ,7411,7416,7416 ,0,0,0}, {11437,11691,11438 ,7417,7418,7418 ,0,0,0}, + {11692,11437,11436 ,7417,7417,7415 ,0,0,0}, {11434,11438,11693 ,7419,7418,7419 ,0,0,0}, + {11691,11693,11438 ,7418,7419,7418 ,0,0,0}, {11694,11433,11434 ,1790,1790,7419 ,0,0,0}, + {11434,11693,11694 ,7419,7419,1790 ,0,0,0}, {11689,11692,11436 ,7415,7417,7415 ,0,0,0}, + {11692,11691,11437 ,7417,7418,7417 ,0,0,0}, {11461,11688,11460 ,7416,7414,7414 ,0,0,0}, + {11460,11689,11436 ,7414,7415,7415 ,0,0,0}, {11441,11685,11690 ,7411,7411,7416 ,0,0,0}, + {11461,11690,11688 ,7416,7416,7414 ,0,0,0}, {11440,11439,11686 ,7412,7413,7412 ,0,0,0}, + {11441,11440,11685 ,7411,7412,7411 ,0,0,0}, {11687,11443,11683 ,7413,7408,7408 ,0,0,0}, + {11686,11439,11687 ,7412,7413,7413 ,0,0,0}, {11442,11683,11443 ,7409,7408,7408 ,0,0,0}, + {11463,11695,11684 ,7420,7420,7421 ,0,0,0}, {11463,11684,11442 ,7420,7421,7421 ,0,0,0}, + {11696,11697,11472 ,1711,7422,7422 ,0,0,0}, {11698,11470,11699 ,7423,7423,7424 ,0,0,0}, + {11471,11462,11700 ,7424,7425,7425 ,0,0,0}, {11467,11701,11702 ,7426,7427,7426 ,0,0,0}, + {11469,11703,11468 ,7428,7428,7427 ,0,0,0}, {11465,11704,11705 ,7429,7430,7429 ,0,0,0}, + {11704,11465,11466 ,7430,7429,7430 ,0,0,0}, {11706,11464,11705 ,7431,7431,7429 ,0,0,0}, + {11465,11705,11464 ,7429,7429,7431 ,0,0,0}, {11706,11695,11463 ,7431,7432,82 ,0,0,0}, + {11463,11464,11706 ,82,7431,7431 ,0,0,0}, {11699,11471,11700 ,7424,7424,7425 ,0,0,0}, + {11466,11467,11702 ,7430,7426,7426 ,0,0,0}, {11702,11704,11466 ,7426,7430,7430 ,0,0,0}, + {11701,11467,11468 ,7427,7426,7427 ,0,0,0}, {11698,11703,11469 ,7423,7428,7428 ,0,0,0}, + {11468,11703,11701 ,7427,7428,7427 ,0,0,0}, {11471,11699,11470 ,7424,7424,7423 ,0,0,0}, + {11469,11470,11698 ,7428,7423,7423 ,0,0,0}, {11472,11697,11462 ,7422,7422,7425 ,0,0,0}, + {11462,11697,11700 ,7425,7422,7425 ,0,0,0}, {11696,11472,11435 ,1711,7422,1711 ,0,0,0}, + {11435,11694,11696 ,2197,2197,2197 ,0,0,0}, {11694,11435,11433 ,2197,2197,2197 ,0,0,0}, + {11694,11697,11696 ,7433,730,730 ,0,0,0}, {11685,11686,11702 ,7375,7375,730 ,0,0,0}, + {11689,11699,11692 ,730,730,730 ,0,0,0}, {11699,11700,11691 ,730,7376,730 ,0,0,0}, + {11690,11703,11688 ,730,730,7376 ,0,0,0}, {11698,11689,11688 ,730,730,7376 ,0,0,0}, + {11701,11690,11685 ,7376,730,7375 ,0,0,0}, {11705,11687,11683 ,7375,7376,7376 ,0,0,0}, + {11686,11687,11704 ,7375,7376,7375 ,0,0,0}, {11684,11706,11683 ,7374,7376,7376 ,0,0,0}, + {11705,11683,11706 ,7375,7376,7376 ,0,0,0}, {11695,11706,11684 ,730,7376,7374 ,0,0,0}, + {11704,11687,11705 ,7375,7376,7375 ,0,0,0}, {11702,11686,11704 ,730,7375,7375 ,0,0,0}, + {11701,11685,11702 ,7376,7375,730 ,0,0,0}, {11703,11690,11701 ,730,730,7376 ,0,0,0}, + {11698,11688,11703 ,730,7376,730 ,0,0,0}, {11699,11689,11698 ,730,730,730 ,0,0,0}, + {11699,11691,11692 ,730,730,730 ,0,0,0}, {11700,11693,11691 ,7376,7433,730 ,0,0,0}, + {11694,11693,11697 ,7433,7433,730 ,0,0,0}, {11700,11697,11693 ,7376,730,7433 ,0,0,0}, + {10870,9043,9041 ,7434,4326,7435 ,0,0,0}, {11042,10970,10867 ,7436,7437,7438 ,0,0,0}, + {10871,10969,10872 ,7439,7440,7441 ,0,0,0}, {10877,10865,11013 ,7442,7443,7444 ,0,0,0}, + {10875,11018,11076 ,7445,7446,7447 ,0,0,0}, {11021,11020,10855 ,7448,7449,7450 ,0,0,0}, + {11005,10873,10874 ,7451,7452,7453 ,0,0,0}, {10849,10848,10920 ,7454,7455,7456 ,0,0,0}, + {10851,10909,10911 ,7457,7458,7459 ,0,0,0}, {10839,10956,10843 ,7460,7461,7462 ,0,0,0}, + {10962,10921,10847 ,7463,7464,7465 ,0,0,0}, {10954,10881,10833 ,7466,7467,7468 ,0,0,0}, + {10957,10835,10881 ,7469,7470,7467 ,0,0,0}, {11026,10830,10837 ,7471,7472,7473 ,0,0,0}, + {10834,10830,10955 ,7474,7472,7475 ,0,0,0}, {10949,10838,10842 ,7476,7477,7478 ,0,0,0}, + {10837,10838,10948 ,7473,7477,7479 ,0,0,0}, {10845,10932,10842 ,7480,7481,7478 ,0,0,0}, + {10949,10842,10932 ,7476,7478,7481 ,0,0,0}, {10845,10854,10924 ,7480,7482,7483 ,0,0,0}, + {10924,10932,10845 ,7483,7481,7480 ,0,0,0}, {10898,10854,10853 ,7484,7482,7485 ,0,0,0}, + {10854,10898,10924 ,7482,7484,7483 ,0,0,0}, {10857,10887,10853 ,7486,7487,7485 ,0,0,0}, + {10898,10853,10887 ,7484,7485,7487 ,0,0,0}, {10857,10862,10885 ,7486,7488,7489 ,0,0,0}, + {10885,10887,10857 ,7489,7487,7486 ,0,0,0}, {10935,10862,10861 ,7490,7488,7491 ,0,0,0}, + {10862,10935,10885 ,7488,7490,7489 ,0,0,0}, {9075,10883,10861 ,82,7492,7491 ,0,0,0}, + {10935,10861,10883 ,7490,7491,7492 ,0,0,0}, {9074,10883,9075 ,82,7492,82 ,0,0,0}, + {10948,11026,10837 ,7479,7471,7473 ,0,0,0}, {10948,10838,10949 ,7479,7477,7476 ,0,0,0}, + {10834,10955,10954 ,7474,7475,7466 ,0,0,0}, {10955,10830,11026 ,7475,7472,7471 ,0,0,0}, + {10881,10835,10833 ,7467,7470,7468 ,0,0,0}, {10954,10833,10834 ,7466,7468,7474 ,0,0,0}, + {10957,10956,10839 ,7469,7461,7460 ,0,0,0}, {10957,10839,10835 ,7469,7460,7470 ,0,0,0}, + {10843,10962,10847 ,7462,7463,7465 ,0,0,0}, {10956,10962,10843 ,7461,7463,7462 ,0,0,0}, + {10848,10921,10920 ,7455,7464,7456 ,0,0,0}, {10847,10921,10848 ,7465,7464,7455 ,0,0,0}, + {10851,10849,10909 ,7457,7454,7458 ,0,0,0}, {10849,10920,10909 ,7454,7456,7458 ,0,0,0}, + {11021,10856,10911 ,7448,7493,7459 ,0,0,0}, {10856,10851,10911 ,7493,7457,7459 ,0,0,0}, + {11020,10874,10855 ,7449,7453,7450 ,0,0,0}, {11021,10855,10856 ,7448,7450,7493 ,0,0,0}, + {11005,11014,10873 ,7451,7494,7452 ,0,0,0}, {11020,11005,10874 ,7449,7451,7453 ,0,0,0}, + {11013,10865,11014 ,7444,7443,7494 ,0,0,0}, {10873,11014,10865 ,7452,7494,7443 ,0,0,0}, + {10875,10877,11018 ,7445,7442,7446 ,0,0,0}, {10877,11013,11018 ,7442,7444,7446 ,0,0,0}, + {11042,10866,11076 ,7436,7495,7447 ,0,0,0}, {10866,10875,11076 ,7495,7445,7447 ,0,0,0}, + {10970,10871,10867 ,7437,7439,7438 ,0,0,0}, {11042,10867,10866 ,7436,7438,7495 ,0,0,0}, + {10969,10971,10872 ,7440,7496,7441 ,0,0,0}, {10970,10969,10871 ,7437,7440,7439 ,0,0,0}, + {9043,10870,10971 ,4326,7434,7496 ,0,0,0}, {10872,10971,10870 ,7441,7496,7434 ,0,0,0}, + {11707,8991,8990 ,7497,763,7498 ,0,0,0}, {11708,10863,11709 ,7499,7500,7501 ,0,0,0}, + {11710,10876,10868 ,7502,7503,7504 ,0,0,0}, {11711,11712,10852 ,7505,7506,7507 ,0,0,0}, + {11713,11714,10860 ,7508,7509,7510 ,0,0,0}, {11715,10840,11716 ,7511,7512,7513 ,0,0,0}, + {10844,11717,11716 ,7514,7515,7513 ,0,0,0}, {11718,10832,11719 ,7516,7517,7518 ,0,0,0}, + {10831,11715,11719 ,7519,7511,7518 ,0,0,0}, {11720,10846,10841 ,7520,7521,7522 ,0,0,0}, + {10841,11718,11720 ,7522,7516,7520 ,0,0,0}, {10846,11721,10858 ,7521,7523,7524 ,0,0,0}, + {11721,10846,11720 ,7523,7521,7520 ,0,0,0}, {10859,10858,11722 ,7525,7524,7526 ,0,0,0}, + {11721,11722,10858 ,7523,7526,7524 ,0,0,0}, {9009,10859,11723 ,761,7525,7527 ,0,0,0}, + {10859,11722,11723 ,7525,7526,7527 ,0,0,0}, {9008,10859,9009 ,761,7525,761 ,0,0,0}, + {10831,11719,10832 ,7519,7518,7517 ,0,0,0}, {10841,10832,11718 ,7522,7517,7516 ,0,0,0}, + {10836,10840,11715 ,7528,7512,7511 ,0,0,0}, {10831,10836,11715 ,7519,7528,7511 ,0,0,0}, + {10850,11717,10844 ,7529,7515,7514 ,0,0,0}, {10840,10844,11716 ,7512,7514,7513 ,0,0,0}, + {10852,11712,10850 ,7507,7506,7529 ,0,0,0}, {11717,10850,11712 ,7515,7529,7506 ,0,0,0}, + {10860,11714,10852 ,7510,7509,7507 ,0,0,0}, {11714,11711,10852 ,7509,7505,7507 ,0,0,0}, + {10864,11708,11713 ,7530,7499,7508 ,0,0,0}, {10864,11713,10860 ,7530,7508,7510 ,0,0,0}, + {10863,10876,11709 ,7500,7503,7501 ,0,0,0}, {10864,10863,11708 ,7530,7500,7499 ,0,0,0}, + {11710,10868,11707 ,7502,7504,7497 ,0,0,0}, {11709,10876,11710 ,7501,7503,7502 ,0,0,0}, + {8991,11707,10869 ,763,7497,7531 ,0,0,0}, {11707,10868,10869 ,7497,7504,7531 ,0,0,0}, + {11722,11721,11720 ,7015,7532,7017 ,0,0,0}, {8995,11709,11710 ,7016,7015,7015 ,0,0,0}, + {11715,11718,11719 ,7533,7534,7535 ,0,0,0}, {11720,11715,11722 ,7017,7533,7015 ,0,0,0}, + {11722,11715,11723 ,7015,7533,7016 ,0,0,0}, {11715,11720,11718 ,7533,7017,7534 ,0,0,0}, + {11716,11723,11715 ,7536,7016,7533 ,0,0,0}, {11723,11717,9009 ,7016,730,7015 ,0,0,0}, + {11717,11723,11716 ,730,7016,7536 ,0,0,0}, {11714,9004,11711 ,7535,730,7320 ,0,0,0}, + {11717,11712,9009 ,730,6104,7015 ,0,0,0}, {11708,8998,11713 ,730,730,7534 ,0,0,0}, + {9001,11714,11713 ,7537,7535,7534 ,0,0,0}, {11707,8990,8994 ,7016,7015,730 ,0,0,0}, + {11710,8996,8995 ,7015,730,7016 ,0,0,0}, {8987,8975,8989 ,730,730,730 ,0,0,0}, + {8989,8973,8990 ,730,7016,7015 ,0,0,0}, {8986,8983,8987 ,730,730,730 ,0,0,0}, + {8975,8981,8980 ,730,7016,7016 ,0,0,0}, {8983,8975,8987 ,730,730,730 ,0,0,0}, + {8975,8974,8989 ,730,730,730 ,0,0,0}, {8975,8983,8981 ,730,730,7016 ,0,0,0}, + {8973,8994,8990 ,7016,730,7015 ,0,0,0}, {8974,8973,8989 ,730,7016,730 ,0,0,0}, + {8996,11710,8994 ,730,7015,730 ,0,0,0}, {8994,11710,11707 ,730,7015,7016 ,0,0,0}, + {8995,8998,11709 ,7016,730,7015 ,0,0,0}, {11713,8998,9000 ,7534,730,7537 ,0,0,0}, + {11709,8998,11708 ,7015,730,730 ,0,0,0}, {11713,9000,9001 ,7534,7537,7537 ,0,0,0}, + {9004,11712,11711 ,730,6104,7320 ,0,0,0}, {11714,9001,9004 ,7535,7537,730 ,0,0,0}, + {9009,11712,9006 ,7015,6104,730 ,0,0,0}, {9004,9006,11712 ,730,730,6104 ,0,0,0}, + {9918,9917,11724 ,7538,7539,7540 ,0,0,0}, {11725,9909,9918 ,7541,7542,7538 ,0,0,0}, + {11725,11726,9909 ,7541,82,7542 ,0,0,0}, {11724,11725,9918 ,7540,7541,7538 ,0,0,0}, + {9917,10288,11727 ,7539,7543,7544 ,0,0,0}, {9947,9946,11728 ,7545,7546,7547 ,0,0,0}, + {11729,11727,10288 ,7548,7544,7543 ,0,0,0}, {10288,9947,11729 ,7543,7545,7548 ,0,0,0}, + {11728,11729,9947 ,7547,7548,7545 ,0,0,0}, {9917,11727,11724 ,7539,7544,7540 ,0,0,0}, + {11728,9946,11730 ,7547,7546,7549 ,0,0,0}, {9945,11731,11730 ,7550,7551,7549 ,0,0,0}, + {11730,9946,9945 ,7549,7546,7550 ,0,0,0}, {11731,9945,9920 ,7551,7550,7552 ,0,0,0}, + {9933,11732,9920 ,7553,7554,7552 ,0,0,0}, {9933,9923,11733 ,7553,7555,7556 ,0,0,0}, + {9933,11733,11732 ,7553,7556,7554 ,0,0,0}, {11734,9914,11735 ,7557,7558,7559 ,0,0,0}, + {11733,9923,11734 ,7556,7555,7557 ,0,0,0}, {11734,9923,9914 ,7557,7555,7558 ,0,0,0}, + {9914,9916,11735 ,7558,7559,7559 ,0,0,0}, {11731,9920,11732 ,7551,7552,7554 ,0,0,0}, + {9910,11726,11736 ,7560,82,7561 ,0,0,0}, {11726,9910,9909 ,82,7560,7542 ,0,0,0}, + {11737,9952,11736 ,7562,7563,7561 ,0,0,0}, {9910,11736,9952 ,7560,7561,7563 ,0,0,0}, + {11737,11738,10166 ,7562,7564,7565 ,0,0,0}, {10166,9952,11737 ,7565,7563,7562 ,0,0,0}, + {9991,11738,11739 ,7566,7564,7567 ,0,0,0}, {11738,9991,10166 ,7564,7566,7565 ,0,0,0}, + {11740,9992,11739 ,7568,7569,7567 ,0,0,0}, {9991,11739,9992 ,7566,7567,7569 ,0,0,0}, + {11740,11741,9988 ,7568,7570,7571 ,0,0,0}, {9988,9992,11740 ,7571,7569,7568 ,0,0,0}, + {9956,11741,11742 ,7572,7570,7573 ,0,0,0}, {11741,9956,9988 ,7570,7572,7571 ,0,0,0}, + {11743,9975,11742 ,7574,7575,7573 ,0,0,0}, {9956,11742,9975 ,7572,7573,7575 ,0,0,0}, + {11743,11744,9976 ,7574,7576,7577 ,0,0,0}, {9976,9975,11743 ,7577,7575,7574 ,0,0,0}, + {9978,11744,11745 ,7578,7576,7579 ,0,0,0}, {11744,9978,9976 ,7576,7578,7577 ,0,0,0}, + {9978,11745,9979 ,7578,7579,7580 ,0,0,0}, {9979,11745,11746 ,7580,7579,7580 ,0,0,0}, + {10804,10810,11746 ,7581,7581,7581 ,0,0,0}, {11746,9416,10795 ,7581,7581,7581 ,0,0,0}, + {10795,10801,11746 ,7581,7581,7581 ,0,0,0}, {10815,11746,10810 ,7581,7581,7581 ,0,0,0}, + {10801,10804,11746 ,7581,7581,7581 ,0,0,0}, {10819,10778,11746 ,7581,7581,7581 ,0,0,0}, + {10819,11746,10815 ,7581,7581,7581 ,0,0,0}, {10778,10790,11746 ,7581,7581,7581 ,0,0,0}, + {9979,11746,10789 ,7581,7581,7581 ,0,0,0}, {10790,10789,11746 ,7581,7581,7581 ,0,0,0}, + {11735,9916,10362 ,7582,7582,7582 ,0,0,0}, {10362,10389,11735 ,7582,7582,7582 ,0,0,0}, + {11735,10375,10355 ,7582,7582,7582 ,0,0,0}, {10389,10375,11735 ,7582,7582,7582 ,0,0,0}, + {11735,10357,10371 ,7582,7582,7582 ,0,0,0}, {10355,10357,11735 ,7582,7582,7582 ,0,0,0}, + {11735,10364,10348 ,7582,7582,7582 ,0,0,0}, {10371,10364,11735 ,7582,7582,7582 ,0,0,0}, + {10352,11735,10347 ,7582,7582,7582 ,0,0,0}, {10348,10347,11735 ,7582,7582,7582 ,0,0,0}, + {11743,9421,9419 ,726,726,726 ,0,0,0}, {11736,11726,9421 ,726,726,726 ,0,0,0}, + {11745,11744,9419 ,726,726,726 ,0,0,0}, {9419,11744,11743 ,726,726,726 ,0,0,0}, + {9419,9413,11746 ,726,726,726 ,0,0,0}, {11746,11745,9419 ,726,726,726 ,0,0,0}, + {9422,9416,11746 ,7583,7583,726 ,0,0,0}, {9422,11746,9413 ,7583,726,726 ,0,0,0}, + {11743,11742,9421 ,726,726,726 ,0,0,0}, {9421,11741,11740 ,726,726,726 ,0,0,0}, + {11742,11741,9421 ,726,726,726 ,0,0,0}, {9421,11739,11738 ,726,726,726 ,0,0,0}, + {11740,11739,9421 ,726,726,726 ,0,0,0}, {9421,11737,11736 ,726,726,726 ,0,0,0}, + {11738,11737,9421 ,726,726,726 ,0,0,0}, {11725,9421,11726 ,726,726,726 ,0,0,0}, + {11724,11727,9421 ,726,726,726 ,0,0,0}, {11724,9421,11725 ,726,726,726 ,0,0,0}, + {11729,11728,9421 ,726,726,726 ,0,0,0}, {11729,9421,11727 ,726,726,726 ,0,0,0}, + {11730,11731,9421 ,726,726,726 ,0,0,0}, {11730,9421,11728 ,726,726,726 ,0,0,0}, + {11732,11733,9421 ,726,726,726 ,0,0,0}, {11732,9421,11731 ,726,726,726 ,0,0,0}, + {9421,11733,11473 ,726,726,726 ,0,0,0}, {11735,11473,11734 ,726,726,726 ,0,0,0}, + {11473,11733,11734 ,726,726,726 ,0,0,0}, {11474,11473,11735 ,726,726,726 ,0,0,0}, + {10352,11486,11735 ,7583,726,726 ,0,0,0}, {11474,11735,11486 ,726,726,726 ,0,0,0}, + {8951,11747,10205 ,7584,7585,7586 ,0,0,0}, {11748,10178,11749 ,7587,7588,7589 ,0,0,0}, + {10216,10138,11750 ,7590,7591,7592 ,0,0,0}, {9905,11751,10167 ,7593,7594,7595 ,0,0,0}, + {11752,11753,9908 ,4334,7596,7597 ,0,0,0}, {11754,9913,11755 ,7598,7599,7600 ,0,0,0}, + {9912,10170,11756 ,7601,7602,7603 ,0,0,0}, {9970,9962,11757 ,7604,7605,7606 ,0,0,0}, + {9966,11758,9962 ,7607,7608,7605 ,0,0,0}, {9967,11759,11760 ,7609,7610,7611 ,0,0,0}, + {9970,11761,9969 ,7604,7612,7613 ,0,0,0}, {11762,9980,11760 ,7614,7615,7611 ,0,0,0}, + {9967,11760,9980 ,7609,7611,7615 ,0,0,0}, {11762,11763,9973 ,7614,7616,7617 ,0,0,0}, + {9973,9980,11762 ,7617,7615,7614 ,0,0,0}, {9982,11763,11764 ,7618,7616,7619 ,0,0,0}, + {11763,9982,9973 ,7616,7618,7617 ,0,0,0}, {11765,9942,11764 ,7620,7621,7619 ,0,0,0}, + {9982,11764,9942 ,7618,7619,7621 ,0,0,0}, {11765,8970,8971 ,7620,7622,4289 ,0,0,0}, + {8971,9942,11765 ,4289,7621,7620 ,0,0,0}, {11757,9962,11758 ,7606,7605,7608 ,0,0,0}, + {11759,9969,11761 ,7610,7613,7612 ,0,0,0}, {9969,11759,9967 ,7613,7610,7609 ,0,0,0}, + {11757,11761,9970 ,7606,7612,7604 ,0,0,0}, {11754,11758,9966 ,7598,7608,7607 ,0,0,0}, + {9912,11756,11755 ,7601,7603,7600 ,0,0,0}, {9912,11755,9913 ,7601,7600,7599 ,0,0,0}, + {9966,9913,11754 ,7607,7599,7598 ,0,0,0}, {10170,11766,11756 ,7602,7623,7603 ,0,0,0}, + {11766,10170,10167 ,7623,7602,7595 ,0,0,0}, {11753,11751,9905 ,7596,7594,7593 ,0,0,0}, + {11751,11766,10167 ,7594,7623,7595 ,0,0,0}, {9908,11753,9905 ,7597,7596,7593 ,0,0,0}, + {10206,11748,11752 ,7624,7587,4334 ,0,0,0}, {10206,11752,9908 ,7624,4334,7597 ,0,0,0}, + {10178,10216,11749 ,7588,7590,7589 ,0,0,0}, {10206,10178,11748 ,7624,7588,7587 ,0,0,0}, + {10138,11747,11750 ,7591,7585,7592 ,0,0,0}, {11749,10216,11750 ,7589,7590,7592 ,0,0,0}, + {8951,10205,8949 ,7584,7586,4535 ,0,0,0}, {11747,10138,10205 ,7585,7591,7586 ,0,0,0}, + {11753,8962,11751 ,726,7625,726 ,0,0,0}, {11762,11760,11763 ,726,726,726 ,0,0,0}, + {11765,11764,11763 ,726,726,726 ,0,0,0}, {11761,11757,11759 ,726,726,726 ,0,0,0}, + {11763,11760,11757 ,726,726,726 ,0,0,0}, {11763,11757,11758 ,726,726,726 ,0,0,0}, + {11759,11757,11760 ,726,726,726 ,0,0,0}, {11758,11754,11765 ,726,726,726 ,0,0,0}, + {11765,11763,11758 ,726,726,726 ,0,0,0}, {11754,11755,8968 ,726,726,7626 ,0,0,0}, + {11754,8970,11765 ,726,726,726 ,0,0,0}, {11766,8964,8965 ,726,726,726 ,0,0,0}, + {8965,8968,11756 ,726,7626,726 ,0,0,0}, {11749,8953,8956 ,726,7627,726 ,0,0,0}, + {8958,8959,11752 ,726,7625,726 ,0,0,0}, {11750,8952,8953 ,7626,7627,7627 ,0,0,0}, + {8948,8933,8932 ,7626,7625,726 ,0,0,0}, {8951,8932,11747 ,726,726,726 ,0,0,0}, + {8944,8935,8945 ,726,7627,7625 ,0,0,0}, {8935,8944,8942 ,7627,726,726 ,0,0,0}, + {8944,8945,8939 ,726,7625,7627 ,0,0,0}, {8945,8948,8947 ,7625,7626,7628 ,0,0,0}, + {8935,8933,8945 ,7627,7625,7625 ,0,0,0}, {8935,8942,8936 ,7627,726,726 ,0,0,0}, + {8951,8948,8932 ,726,7626,726 ,0,0,0}, {8948,8945,8933 ,7626,7625,7625 ,0,0,0}, + {8930,11747,8932 ,726,726,726 ,0,0,0}, {11750,11747,8952 ,7626,726,7627 ,0,0,0}, + {8930,8952,11747 ,726,7627,726 ,0,0,0}, {11749,8956,11748 ,726,726,726 ,0,0,0}, + {8953,11749,11750 ,7627,726,7626 ,0,0,0}, {8958,11752,11748 ,726,726,726 ,0,0,0}, + {11748,8956,8958 ,726,726,726 ,0,0,0}, {8959,8962,11753 ,7625,7625,726 ,0,0,0}, + {11752,8959,11753 ,726,7625,726 ,0,0,0}, {11751,8964,11766 ,726,726,726 ,0,0,0}, + {11751,8962,8964 ,726,7625,726 ,0,0,0}, {8968,11755,11756 ,7626,726,726 ,0,0,0}, + {11756,11766,8965 ,726,726,726 ,0,0,0}, {8968,8970,11754 ,7626,726,726 ,0,0,0}, + {8912,11767,10186 ,4303,7629,7630 ,0,0,0}, {10109,10143,11768 ,7631,7632,7633 ,0,0,0}, + {10275,10187,11769 ,7634,7635,7636 ,0,0,0}, {10171,11770,10172 ,7637,7638,7639 ,0,0,0}, + {11771,11772,10108 ,7640,7641,7642 ,0,0,0}, {11773,11774,9953 ,7643,7644,7645 ,0,0,0}, + {11773,10173,11775 ,7643,7646,7647 ,0,0,0}, {11776,11777,9951 ,7648,7649,7650 ,0,0,0}, + {9951,9950,11776 ,7650,7651,7648 ,0,0,0}, {10134,11777,11778 ,7652,7649,7653 ,0,0,0}, + {11777,10134,9951 ,7649,7652,7650 ,0,0,0}, {11779,10133,11778 ,7654,7655,7653 ,0,0,0}, + {10134,11778,10133 ,7652,7653,7655 ,0,0,0}, {11779,8926,8927 ,7654,126,7656 ,0,0,0}, + {8927,10133,11779 ,7656,7655,7654 ,0,0,0}, {11770,10171,11772 ,7638,7637,7641 ,0,0,0}, + {11774,9950,9953 ,7644,7651,7645 ,0,0,0}, {11776,9950,11774 ,7648,7651,7644 ,0,0,0}, + {11768,10143,11780 ,7633,7632,7657 ,0,0,0}, {11775,10173,10172 ,7647,7646,7639 ,0,0,0}, + {11773,9953,10173 ,7643,7645,7646 ,0,0,0}, {11770,11775,10172 ,7638,7647,7639 ,0,0,0}, + {10108,11772,10171 ,7642,7641,7637 ,0,0,0}, {10109,11768,11771 ,7631,7633,7640 ,0,0,0}, + {11771,10108,10109 ,7640,7642,7631 ,0,0,0}, {10187,11767,11769 ,7635,7629,7636 ,0,0,0}, + {11780,10275,11769 ,7657,7634,7636 ,0,0,0}, {10143,10275,11780 ,7632,7634,7657 ,0,0,0}, + {8912,10186,8913 ,4303,7630,82 ,0,0,0}, {11767,10187,10186 ,7629,7635,7630 ,0,0,0}, + {11774,11773,8909 ,726,7658,7659 ,0,0,0}, {11767,11772,11768 ,7660,7661,726 ,0,0,0}, + {11767,11770,11772 ,7660,7661,7661 ,0,0,0}, {8911,11775,8912 ,7659,726,726 ,0,0,0}, + {11771,11768,11772 ,7661,726,7661 ,0,0,0}, {11769,11767,11768 ,7659,7660,726 ,0,0,0}, + {11770,11767,8912 ,7661,7660,726 ,0,0,0}, {11780,11769,11768 ,726,7659,726 ,0,0,0}, + {11770,8912,11775 ,7661,726,726 ,0,0,0}, {8909,11773,8911 ,7659,7658,7659 ,0,0,0}, + {8911,11773,11775 ,7659,7658,726 ,0,0,0}, {8907,11776,11774 ,726,5488,726 ,0,0,0}, + {8909,8907,11774 ,7659,726,726 ,0,0,0}, {8905,11776,8907 ,726,5488,726 ,0,0,0}, + {8905,11777,11776 ,726,7662,5488 ,0,0,0}, {11778,11777,8902 ,5471,7662,7661 ,0,0,0}, + {8905,8902,11777 ,726,7661,7662 ,0,0,0}, {8901,11778,8902 ,726,5471,7661 ,0,0,0}, + {11779,8901,8899 ,7663,726,7661 ,0,0,0}, {8901,11779,11778 ,726,7663,5471 ,0,0,0}, + {8898,8926,8899 ,7658,726,7661 ,0,0,0}, {11779,8899,8926 ,7663,7661,726 ,0,0,0}, + {8918,8914,8915 ,7658,7664,726 ,0,0,0}, {8918,8924,8914 ,7658,7665,7664 ,0,0,0}, + {8921,8918,8920 ,7666,7658,7667 ,0,0,0}, {8921,8924,8918 ,7666,7665,7658 ,0,0,0}, + {8926,8898,8924 ,726,7658,7665 ,0,0,0}, {8914,8924,8898 ,7664,7665,7658 ,0,0,0}, + {11781,9452,11782 ,726,726,726 ,0,0,0}, {9452,11783,11782 ,726,726,726 ,0,0,0}, + {11784,11785,9452 ,726,726,726 ,0,0,0}, {9452,11781,11784 ,726,726,726 ,0,0,0}, + {11786,11787,9452 ,726,726,726 ,0,0,0}, {11786,9452,11785 ,726,726,726 ,0,0,0}, + {9444,11788,11789 ,7583,726,7661 ,0,0,0}, {9452,11790,11791 ,726,726,726 ,0,0,0}, + {9444,11792,11793 ,7583,7658,7661 ,0,0,0}, {11794,9444,11795 ,726,7583,726 ,0,0,0}, + {11796,11797,9444 ,726,726,7583 ,0,0,0}, {11798,11795,9444 ,726,726,7583 ,0,0,0}, + {9444,11794,11799 ,7583,726,5489 ,0,0,0}, {11796,9444,11800 ,726,7583,7583 ,0,0,0}, + {9444,11797,11798 ,7583,726,726 ,0,0,0}, {9444,11801,11792 ,7583,726,7658 ,0,0,0}, + {11793,11800,9444 ,7661,7583,7583 ,0,0,0}, {11791,11788,9444 ,726,726,7583 ,0,0,0}, + {11801,9444,11789 ,726,7583,7661 ,0,0,0}, {9452,11787,11790 ,726,726,726 ,0,0,0}, + {9452,11791,9444 ,726,726,7583 ,0,0,0}, {9445,11799,9440 ,726,5489,7668 ,0,0,0}, + {11799,9445,9444 ,5489,726,7583 ,0,0,0}, {11783,9452,11802 ,726,726,726 ,0,0,0}, + {11803,9452,9450 ,726,726,726 ,0,0,0}, {9452,11803,11802 ,726,726,726 ,0,0,0}, + {11803,9450,9456 ,726,726,726 ,0,0,0}, {9906,10169,11801 ,7669,7670,7671 ,0,0,0}, + {11789,9907,9906 ,7672,7673,7669 ,0,0,0}, {11789,11788,9907 ,7672,7673,7673 ,0,0,0}, + {11801,11789,9906 ,7671,7672,7669 ,0,0,0}, {10169,10168,11792 ,7670,7674,7675 ,0,0,0}, + {9911,9965,11800 ,7676,7677,7678 ,0,0,0}, {11793,11792,10168 ,7679,7675,7674 ,0,0,0}, + {10168,9911,11793 ,7674,7676,7679 ,0,0,0}, {11800,11793,9911 ,7678,7679,7676 ,0,0,0}, + {10169,11792,11801 ,7670,7675,7671 ,0,0,0}, {11800,9965,11796 ,7678,7677,7680 ,0,0,0}, + {9964,11797,11796 ,7681,7682,7680 ,0,0,0}, {11796,9965,9964 ,7680,7677,7681 ,0,0,0}, + {11797,9964,9963 ,7682,7681,7683 ,0,0,0}, {9957,11798,9963 ,7684,7685,7683 ,0,0,0}, + {9957,9959,11795 ,7684,7686,7687 ,0,0,0}, {9957,11795,11798 ,7684,7687,7685 ,0,0,0}, + {11794,9960,11799 ,7688,7689,7690 ,0,0,0}, {11795,9959,11794 ,7687,7686,7688 ,0,0,0}, + {11794,9959,9960 ,7688,7686,7689 ,0,0,0}, {9960,9961,11799 ,7689,7690,7690 ,0,0,0}, + {11797,9963,11798 ,7682,7683,7685 ,0,0,0}, {9954,11788,11791 ,7691,7673,7692 ,0,0,0}, + {11788,9954,9907 ,7673,7691,7673 ,0,0,0}, {11790,9955,11791 ,7693,7694,7692 ,0,0,0}, + {9954,11791,9955 ,7691,7692,7694 ,0,0,0}, {11790,11787,9986 ,7693,7695,7696 ,0,0,0}, + {9986,9955,11790 ,7696,7694,7693 ,0,0,0}, {9987,11787,11786 ,7697,7695,7698 ,0,0,0}, + {11787,9987,9986 ,7695,7697,7696 ,0,0,0}, {11785,10209,11786 ,7699,7700,7698 ,0,0,0}, + {9987,11786,10209 ,7697,7698,7700 ,0,0,0}, {11785,11784,9990 ,7699,7701,7702 ,0,0,0}, + {9990,10209,11785 ,7702,7700,7699 ,0,0,0}, {9989,11784,11781 ,7703,7701,7704 ,0,0,0}, + {11784,9989,9990 ,7701,7703,7702 ,0,0,0}, {11782,10012,11781 ,7705,7706,7704 ,0,0,0}, + {9989,11781,10012 ,7703,7704,7706 ,0,0,0}, {11782,11783,10015 ,7705,7707,7708 ,0,0,0}, + {10015,10012,11782 ,7708,7706,7705 ,0,0,0}, {10016,11783,11802 ,7709,7707,7710 ,0,0,0}, + {11783,10016,10015 ,7707,7709,7708 ,0,0,0}, {10016,11802,10017 ,7709,7710,7711 ,0,0,0}, + {10017,11802,11803 ,7711,7710,7711 ,0,0,0}, {10718,11803,9456 ,7712,7712,7712 ,0,0,0}, + {11803,10719,10722 ,7712,7712,7712 ,0,0,0}, {10718,10719,11803 ,7712,7712,7712 ,0,0,0}, + {11803,10728,10733 ,7712,7712,7712 ,0,0,0}, {10722,10728,11803 ,7712,7712,7712 ,0,0,0}, + {11803,10737,10701 ,7712,7712,7712 ,0,0,0}, {10733,10737,11803 ,7712,7712,7712 ,0,0,0}, + {11803,10705,10704 ,7712,7712,7712 ,0,0,0}, {10701,10705,11803 ,7712,7712,7712 ,0,0,0}, + {11803,10704,10017 ,7712,7712,7712 ,0,0,0}, {10770,11799,9961 ,7713,7713,7713 ,0,0,0}, + {10770,10820,11799 ,7713,7713,7713 ,0,0,0}, {11799,10820,10806 ,7713,7713,7713 ,0,0,0}, + {10766,10772,11799 ,7713,7713,7713 ,0,0,0}, {10766,11799,10806 ,7713,7713,7713 ,0,0,0}, + {10772,10802,11799 ,7713,7713,7713 ,0,0,0}, {11799,10758,10757 ,7713,7713,7713 ,0,0,0}, + {10802,10758,11799 ,7713,7713,7713 ,0,0,0}, {9440,11799,10762 ,7713,7713,7713 ,0,0,0}, + {10757,10762,11799 ,7713,7713,7713 ,0,0,0}, {8875,11804,10224 ,1435,7714,7715 ,0,0,0}, + {11805,10215,11806 ,7716,7717,7718 ,0,0,0}, {10234,10223,11807 ,7719,7720,7721 ,0,0,0}, + {9895,11808,9996 ,7722,7723,7724 ,0,0,0}, {11809,11810,10237 ,7725,7726,7727 ,0,0,0}, + {11811,10018,11812 ,7728,7729,7730 ,0,0,0}, {10020,9997,11813 ,7731,7732,7733 ,0,0,0}, + {9902,10001,11814 ,7734,7735,7736 ,0,0,0}, {10006,11815,10001 ,7737,7738,7735 ,0,0,0}, + {10002,11816,11817 ,7739,7740,7741 ,0,0,0}, {9902,11818,10004 ,7734,7742,7743 ,0,0,0}, + {11819,10011,11817 ,7744,7745,7741 ,0,0,0}, {10002,11817,10011 ,7739,7741,7745 ,0,0,0}, + {11819,11820,10009 ,7744,7746,7747 ,0,0,0}, {10009,10011,11819 ,7747,7745,7744 ,0,0,0}, + {10022,11820,11821 ,7748,7746,7749 ,0,0,0}, {11820,10022,10009 ,7746,7748,7747 ,0,0,0}, + {11822,10008,11821 ,7750,7751,7749 ,0,0,0}, {10022,11821,10008 ,7748,7749,7751 ,0,0,0}, + {11822,8894,8895 ,7750,1359,1359 ,0,0,0}, {8895,10008,11822 ,1359,7751,7750 ,0,0,0}, + {11814,10001,11815 ,7736,7735,7738 ,0,0,0}, {11816,10004,11818 ,7740,7743,7742 ,0,0,0}, + {10004,11816,10002 ,7743,7740,7739 ,0,0,0}, {11814,11818,9902 ,7736,7742,7734 ,0,0,0}, + {11811,11815,10006 ,7728,7738,7737 ,0,0,0}, {10020,11813,11812 ,7731,7733,7730 ,0,0,0}, + {10020,11812,10018 ,7731,7730,7729 ,0,0,0}, {10006,10018,11811 ,7737,7729,7728 ,0,0,0}, + {9997,11823,11813 ,7732,7752,7733 ,0,0,0}, {11823,9997,9996 ,7752,7732,7724 ,0,0,0}, + {11810,11808,9895 ,7726,7723,7722 ,0,0,0}, {11808,11823,9996 ,7723,7752,7724 ,0,0,0}, + {10237,11810,9895 ,7727,7726,7722 ,0,0,0}, {10225,11805,11809 ,7753,7716,7725 ,0,0,0}, + {10225,11809,10237 ,7753,7725,7727 ,0,0,0}, {10215,10234,11806 ,7717,7719,7718 ,0,0,0}, + {10225,10215,11805 ,7753,7717,7716 ,0,0,0}, {10223,11804,11807 ,7720,7714,7721 ,0,0,0}, + {11806,10234,11807 ,7718,7719,7721 ,0,0,0}, {8875,10224,8873 ,1435,7715,1435 ,0,0,0}, + {11804,10223,10224 ,7714,7720,7715 ,0,0,0}, {11822,11821,11820 ,726,7628,7628 ,0,0,0}, + {8877,11817,8876 ,7627,7628,726 ,0,0,0}, {8856,8854,11818 ,7754,7625,7626 ,0,0,0}, + {11817,11816,8876 ,7628,726,726 ,0,0,0}, {8859,11811,8860 ,7755,726,7756 ,0,0,0}, + {8856,11818,11814 ,7754,7626,7626 ,0,0,0}, {11813,11823,8868 ,726,7628,7757 ,0,0,0}, + {11813,8866,11812 ,726,7758,7626 ,0,0,0}, {8869,8863,11808 ,7759,7760,7628 ,0,0,0}, + {11805,11806,11807 ,7625,7754,726 ,0,0,0}, {8872,8869,11810 ,7628,7759,7627 ,0,0,0}, + {8875,8872,11804 ,7628,7628,7761 ,0,0,0}, {11804,11805,11807 ,7761,7625,726 ,0,0,0}, + {8872,11809,11805 ,7628,7628,7625 ,0,0,0}, {11804,8872,11805 ,7761,7628,7625 ,0,0,0}, + {8872,8871,8869 ,7628,7762,7759 ,0,0,0}, {8872,11810,11809 ,7628,7627,7628 ,0,0,0}, + {8868,11808,8863 ,7757,7628,7760 ,0,0,0}, {11808,11810,8869 ,7628,7627,7759 ,0,0,0}, + {8868,11823,11808 ,7757,7628,7628 ,0,0,0}, {11812,8866,8860 ,7626,7758,7756 ,0,0,0}, + {8868,8866,11813 ,7757,7758,726 ,0,0,0}, {11815,11811,8859 ,7628,726,7755 ,0,0,0}, + {11811,11812,8860 ,726,7626,7756 ,0,0,0}, {11815,8857,11814 ,7628,7628,7626 ,0,0,0}, + {8857,11815,8859 ,7628,7628,7755 ,0,0,0}, {11816,11818,8854 ,726,7626,7625 ,0,0,0}, + {8857,8856,11814 ,7628,7754,7626 ,0,0,0}, {8880,11817,8877 ,7625,7628,7627 ,0,0,0}, + {8854,8876,11816 ,7625,726,726 ,0,0,0}, {11820,11819,8880 ,7628,7628,7625 ,0,0,0}, + {8880,11819,11817 ,7625,7628,7628 ,0,0,0}, {8882,11822,11820 ,7628,726,7628 ,0,0,0}, + {11820,8880,8882 ,7628,7625,7628 ,0,0,0}, {8882,8883,11822 ,7628,7628,726 ,0,0,0}, + {8886,8889,8892 ,7628,7628,7628 ,0,0,0}, {8883,8886,11822 ,7628,7628,726 ,0,0,0}, + {8892,11822,8886 ,7628,726,7628 ,0,0,0}, {8886,8888,8889 ,7628,726,7628 ,0,0,0}, + {11822,8892,8894 ,726,7628,7628 ,0,0,0}, {8836,11824,10185 ,1435,7763,7764 ,0,0,0}, + {10212,10214,11825 ,7765,7766,7767 ,0,0,0}, {10218,10219,11826 ,7768,7769,7770 ,0,0,0}, + {10184,11827,10183 ,7771,7772,7773 ,0,0,0}, {11828,11829,10213 ,7774,4221,7775 ,0,0,0}, + {11830,11831,10211 ,7776,7777,7778 ,0,0,0}, {11830,10210,11832 ,7776,7779,7780 ,0,0,0}, + {11833,11834,10027 ,7781,7782,7783 ,0,0,0}, {10027,10026,11833 ,7783,7784,7781 ,0,0,0}, + {9901,11834,11835 ,7785,7782,7786 ,0,0,0}, {11834,9901,10027 ,7782,7785,7783 ,0,0,0}, + {11836,9900,11835 ,7787,7788,7786 ,0,0,0}, {9901,11835,9900 ,7785,7786,7788 ,0,0,0}, + {11836,8850,8851 ,7787,1359,1359 ,0,0,0}, {8851,9900,11836 ,1359,7788,7787 ,0,0,0}, + {11827,10184,11829 ,7772,7771,4221 ,0,0,0}, {11831,10026,10211 ,7777,7784,7778 ,0,0,0}, + {11833,10026,11831 ,7781,7784,7777 ,0,0,0}, {11825,10214,11837 ,7767,7766,4227 ,0,0,0}, + {11832,10210,10183 ,7780,7779,7773 ,0,0,0}, {11830,10211,10210 ,7776,7778,7779 ,0,0,0}, + {11827,11832,10183 ,7772,7780,7773 ,0,0,0}, {10213,11829,10184 ,7775,4221,7771 ,0,0,0}, + {10212,11825,11828 ,7765,7767,7774 ,0,0,0}, {11828,10213,10212 ,7774,7775,7765 ,0,0,0}, + {10219,11824,11826 ,7769,7763,7770 ,0,0,0}, {11837,10218,11826 ,4227,7768,7770 ,0,0,0}, + {10214,10218,11837 ,7766,7768,4227 ,0,0,0}, {8836,10185,8837 ,1435,7764,1435 ,0,0,0}, + {11824,10219,10185 ,7763,7769,7764 ,0,0,0}, {8835,8844,8836 ,726,5471,7661 ,0,0,0}, + {11827,11830,11832 ,726,726,726 ,0,0,0}, {11833,11831,11830 ,7658,726,726 ,0,0,0}, + {11830,11827,11833 ,726,726,7658 ,0,0,0}, {11833,11829,11834 ,7658,726,7658 ,0,0,0}, + {11829,11833,11827 ,726,7658,726 ,0,0,0}, {11835,11834,11828 ,7658,7658,726 ,0,0,0}, + {11829,11828,11834 ,726,726,7658 ,0,0,0}, {11825,11836,11835 ,7658,7661,7658 ,0,0,0}, + {11835,11828,11825 ,7658,726,7658 ,0,0,0}, {11836,11837,8850 ,7661,7661,7664 ,0,0,0}, + {11837,11836,11825 ,7661,7661,7658 ,0,0,0}, {11837,11826,8850 ,7661,726,7664 ,0,0,0}, + {11826,11824,8848 ,726,726,7662 ,0,0,0}, {8842,8835,8833 ,7789,726,7658 ,0,0,0}, + {8823,8822,8829 ,5488,7668,7661 ,0,0,0}, {8839,8831,8838 ,7790,7664,7791 ,0,0,0}, + {8823,8829,8825 ,5488,7661,7792 ,0,0,0}, {8826,8825,8829 ,5488,7792,7661 ,0,0,0}, + {8831,8829,8838 ,7664,7661,7791 ,0,0,0}, {8838,8829,8822 ,7791,7661,7668 ,0,0,0}, + {8831,8839,8833 ,7664,7790,7658 ,0,0,0}, {8844,8835,8842 ,5471,726,7789 ,0,0,0}, + {8842,8833,8839 ,7789,7658,7790 ,0,0,0}, {8836,8845,11824 ,7661,7583,726 ,0,0,0}, + {8836,8844,8845 ,7661,5471,7583 ,0,0,0}, {11826,8848,8850 ,726,7662,7664 ,0,0,0}, + {8845,8848,11824 ,7583,7662,726 ,0,0,0}, {11838,9481,11839 ,7583,726,726 ,0,0,0}, + {11840,9477,11841 ,7668,726,5470 ,0,0,0}, {11840,11842,9477 ,7668,726,726 ,0,0,0}, + {9477,11843,11841 ,726,726,5470 ,0,0,0}, {11842,11844,9477 ,726,5489,726 ,0,0,0}, + {9477,11845,11846 ,726,7793,7794 ,0,0,0}, {11844,11845,9477 ,5489,7793,726 ,0,0,0}, + {9481,11847,9477 ,726,5470,726 ,0,0,0}, {11847,11843,9477 ,5470,726,726 ,0,0,0}, + {11848,11847,9481 ,726,5470,726 ,0,0,0}, {11849,9477,11846 ,7795,726,7794 ,0,0,0}, + {9481,11850,11848 ,726,5488,726 ,0,0,0}, {11849,11851,9477 ,7795,726,726 ,0,0,0}, + {11852,9477,11853 ,5485,726,7796 ,0,0,0}, {9477,11851,11853 ,726,726,7796 ,0,0,0}, + {9481,11854,11850 ,726,7583,5488 ,0,0,0}, {11855,9477,11852 ,7583,726,5485 ,0,0,0}, + {9481,11856,11854 ,726,726,7583 ,0,0,0}, {9481,11857,11858 ,726,5488,7583 ,0,0,0}, + {9481,11858,11856 ,726,7583,726 ,0,0,0}, {9478,11855,9473 ,5489,7583,7797 ,0,0,0}, + {9481,11838,11857 ,726,7583,5488 ,0,0,0}, {11855,9478,9477 ,7583,5489,726 ,0,0,0}, + {11839,9481,11859 ,726,726,7583 ,0,0,0}, {11860,9481,9488 ,726,726,726 ,0,0,0}, + {9481,11860,11859 ,726,726,7583 ,0,0,0}, {11860,9488,9487 ,726,726,726 ,0,0,0}, + {9896,9998,11840 ,7798,7799,7800 ,0,0,0}, {11841,9894,9896 ,7801,7802,7798 ,0,0,0}, + {11841,11843,9894 ,7801,7802,7802 ,0,0,0}, {11840,11841,9896 ,7800,7801,7798 ,0,0,0}, + {9998,10207,11842 ,7799,7803,7804 ,0,0,0}, {10019,10005,11845 ,7805,7806,7807 ,0,0,0}, + {11844,11842,10207 ,7808,7804,7803 ,0,0,0}, {10207,10019,11844 ,7803,7805,7808 ,0,0,0}, + {11845,11844,10019 ,7807,7808,7805 ,0,0,0}, {9998,11842,11840 ,7799,7804,7800 ,0,0,0}, + {11845,10005,11846 ,7807,7806,7809 ,0,0,0}, {10000,11849,11846 ,7810,7811,7809 ,0,0,0}, + {11846,10005,10000 ,7809,7806,7810 ,0,0,0}, {11849,10000,9999 ,7811,7810,7812 ,0,0,0}, + {9904,11851,9999 ,7813,7814,7812 ,0,0,0}, {9904,9983,11853 ,7813,7815,7816 ,0,0,0}, + {9904,11853,11851 ,7813,7816,7814 ,0,0,0}, {11852,9985,11855 ,7817,7818,7819 ,0,0,0}, + {11853,9983,11852 ,7816,7815,7817 ,0,0,0}, {11852,9983,9985 ,7817,7815,7818 ,0,0,0}, + {9985,10014,11855 ,7818,7819,7819 ,0,0,0}, {11849,9999,11851 ,7811,7812,7814 ,0,0,0}, + {10028,11843,11847 ,7820,7802,7821 ,0,0,0}, {11843,10028,9894 ,7802,7820,7802 ,0,0,0}, + {11848,10032,11847 ,7822,7823,7821 ,0,0,0}, {10028,11847,10032 ,7820,7821,7823 ,0,0,0}, + {11848,11850,9993 ,7822,7824,7825 ,0,0,0}, {9993,10032,11848 ,7825,7823,7822 ,0,0,0}, + {9994,11850,11854 ,7826,7824,7827 ,0,0,0}, {11850,9994,9993 ,7824,7826,7825 ,0,0,0}, + {11856,10069,11854 ,7828,7829,7827 ,0,0,0}, {9994,11854,10069 ,7826,7827,7829 ,0,0,0}, + {11856,11858,9897 ,7828,7830,7831 ,0,0,0}, {9897,10069,11856 ,7831,7829,7828 ,0,0,0}, + {9898,11858,11857 ,7832,7830,7833 ,0,0,0}, {11858,9898,9897 ,7830,7832,7831 ,0,0,0}, + {11838,10056,11857 ,7834,7835,7833 ,0,0,0}, {9898,11857,10056 ,7832,7833,7835 ,0,0,0}, + {11838,11839,10059 ,7834,7836,7837 ,0,0,0}, {10059,10056,11838 ,7837,7835,7834 ,0,0,0}, + {10063,11839,11859 ,7838,7836,7839 ,0,0,0}, {11839,10063,10059 ,7836,7838,7837 ,0,0,0}, + {10063,11859,10064 ,7838,7839,7840 ,0,0,0}, {10064,11859,11860 ,7840,7839,7840 ,0,0,0}, + {10631,11860,9487 ,7841,7841,7841 ,0,0,0}, {11860,10637,10640 ,7841,7841,7841 ,0,0,0}, + {10631,10637,11860 ,7841,7841,7841 ,0,0,0}, {11860,10646,10651 ,7841,7841,7841 ,0,0,0}, + {10640,10646,11860 ,7841,7841,7841 ,0,0,0}, {11860,10655,10614 ,7841,7841,7841 ,0,0,0}, + {10651,10655,11860 ,7841,7841,7841 ,0,0,0}, {11860,10626,10625 ,7841,7841,7841 ,0,0,0}, + {10614,10626,11860 ,7841,7841,7841 ,0,0,0}, {11860,10625,10064 ,7841,7841,7841 ,0,0,0}, + {10692,11855,10014 ,7842,7842,7842 ,0,0,0}, {10692,10738,11855 ,7842,7842,7842 ,0,0,0}, + {11855,10738,10724 ,7842,7842,7842 ,0,0,0}, {10686,10679,11855 ,7842,7842,7842 ,0,0,0}, + {10686,11855,10724 ,7842,7842,7842 ,0,0,0}, {10679,10720,11855 ,7842,7842,7842 ,0,0,0}, + {11855,10712,10674 ,7842,7842,7842 ,0,0,0}, {10720,10712,11855 ,7842,7842,7842 ,0,0,0}, + {9473,11855,10675 ,7842,7842,7842 ,0,0,0}, {10674,10675,11855 ,7842,7842,7842 ,0,0,0}, + {8799,11861,10249 ,1790,7843,4204 ,0,0,0}, {11862,10246,11863 ,7844,4198,4199 ,0,0,0}, + {10235,10248,11864 ,7845,7846,7847 ,0,0,0}, {10226,11865,10044 ,7848,7849,7850 ,0,0,0}, + {11866,11867,10259 ,7851,7852,7853 ,0,0,0}, {11868,10023,11869 ,7854,7855,7856 ,0,0,0}, + {10025,10042,11870 ,7857,7858,7859 ,0,0,0}, {9891,9890,11871 ,7860,7861,7862 ,0,0,0}, + {10046,11872,9890 ,7863,7864,7861 ,0,0,0}, {10050,11873,11874 ,7865,7866,7867 ,0,0,0}, + {9891,11875,10049 ,7860,7868,7869 ,0,0,0}, {11876,10055,11874 ,7870,7871,7867 ,0,0,0}, + {10050,11874,10055 ,7865,7867,7871 ,0,0,0}, {11876,11877,10053 ,7870,7872,7873 ,0,0,0}, + {10053,10055,11876 ,7873,7871,7870 ,0,0,0}, {10038,11877,11878 ,7874,7872,7875 ,0,0,0}, + {11877,10038,10053 ,7872,7874,7873 ,0,0,0}, {11879,10036,11878 ,7876,7877,7875 ,0,0,0}, + {10038,11878,10036 ,7874,7875,7877 ,0,0,0}, {11879,8818,8819 ,7876,1711,1711 ,0,0,0}, + {8819,10036,11879 ,1711,7877,7876 ,0,0,0}, {11871,9890,11872 ,7862,7861,7864 ,0,0,0}, + {11873,10049,11875 ,7866,7869,7868 ,0,0,0}, {10049,11873,10050 ,7869,7866,7865 ,0,0,0}, + {11871,11875,9891 ,7862,7868,7860 ,0,0,0}, {11868,11872,10046 ,7854,7864,7863 ,0,0,0}, + {10025,11870,11869 ,7857,7859,7856 ,0,0,0}, {10025,11869,10023 ,7857,7856,7855 ,0,0,0}, + {10046,10023,11868 ,7863,7855,7854 ,0,0,0}, {10042,11880,11870 ,7858,7878,7859 ,0,0,0}, + {11880,10042,10044 ,7878,7858,7850 ,0,0,0}, {11867,11865,10226 ,7852,7849,7848 ,0,0,0}, + {11865,11880,10044 ,7849,7878,7850 ,0,0,0}, {10259,11867,10226 ,7853,7852,7848 ,0,0,0}, + {10247,11862,11866 ,7879,7844,7851 ,0,0,0}, {10247,11866,10259 ,7879,7851,7853 ,0,0,0}, + {10246,10235,11863 ,4198,7845,4199 ,0,0,0}, {10247,10246,11862 ,7879,4198,7844 ,0,0,0}, + {10248,11861,11864 ,7846,7843,7847 ,0,0,0}, {11863,10235,11864 ,4199,7845,7847 ,0,0,0}, + {8799,10249,8797 ,1790,4204,1790 ,0,0,0}, {11861,10248,10249 ,7843,7846,4204 ,0,0,0}, + {11871,11872,11866 ,726,7880,7881 ,0,0,0}, {11861,11876,11874 ,7882,7627,7625 ,0,0,0}, + {11867,11868,11865 ,7883,7758,726 ,0,0,0}, {11880,11865,11868 ,7884,726,7758 ,0,0,0}, + {11869,11870,11880 ,7880,7761,7884 ,0,0,0}, {11868,11867,11872 ,7758,7883,7880 ,0,0,0}, + {11869,11880,11868 ,7880,7884,7758 ,0,0,0}, {11871,11866,11862 ,726,7881,7885 ,0,0,0}, + {11872,11867,11866 ,7880,7883,7881 ,0,0,0}, {11862,11863,11875 ,7885,7886,7758 ,0,0,0}, + {11875,11871,11862 ,7758,726,7885 ,0,0,0}, {11873,11863,11864 ,726,7886,7887 ,0,0,0}, + {11863,11873,11875 ,7886,726,7758 ,0,0,0}, {11874,11873,11864 ,7625,726,7887 ,0,0,0}, + {8799,11876,11861 ,7758,7627,7882 ,0,0,0}, {11861,11874,11864 ,7882,7625,7887 ,0,0,0}, + {11877,8799,8796 ,7627,7758,7755 ,0,0,0}, {8799,11877,11876 ,7758,7627,7627 ,0,0,0}, + {8795,11878,8796 ,7625,726,7755 ,0,0,0}, {11877,8796,11878 ,7627,7755,726 ,0,0,0}, + {8795,8793,11879 ,7625,7761,726 ,0,0,0}, {11879,11878,8795 ,726,726,7625 ,0,0,0}, + {8818,8793,8787 ,7627,7761,7625 ,0,0,0}, {8793,8818,11879 ,7761,7627,726 ,0,0,0}, + {8784,8812,8790 ,726,7627,7625 ,0,0,0}, {8792,8816,8787 ,7880,726,7625 ,0,0,0}, + {8810,8783,8807 ,7625,726,726 ,0,0,0}, {8804,8780,8801 ,7627,7625,7625 ,0,0,0}, + {8806,8807,8781 ,726,726,7625 ,0,0,0}, {8801,8778,8800 ,7625,7625,726 ,0,0,0}, + {8780,8804,8806 ,7625,7627,726 ,0,0,0}, {8781,8780,8806 ,7625,7625,726 ,0,0,0}, + {8801,8780,8778 ,7625,7625,7625 ,0,0,0}, {8784,8783,8810 ,726,726,7625 ,0,0,0}, + {8781,8807,8783 ,7625,726,726 ,0,0,0}, {8813,8790,8812 ,726,7625,7627 ,0,0,0}, + {8812,8784,8810 ,7627,726,7625 ,0,0,0}, {8792,8813,8816 ,7880,726,726 ,0,0,0}, + {8813,8792,8790 ,726,7880,7625 ,0,0,0}, {8816,8818,8787 ,726,7627,7625 ,0,0,0}, + {8760,11881,10179 ,1790,7888,7889 ,0,0,0}, {10231,10220,11882 ,7890,7891,7892 ,0,0,0}, + {10233,10180,11883 ,7893,7894,7895 ,0,0,0}, {10221,11884,10222 ,7896,7897,4137 ,0,0,0}, + {11885,11886,10232 ,7898,7899,7900 ,0,0,0}, {11887,11888,10230 ,7901,7902,7903 ,0,0,0}, + {11887,10229,11889 ,7901,7904,7905 ,0,0,0}, {11890,11891,10065 ,7906,7907,7908 ,0,0,0}, + {10065,10066,11890 ,7908,7909,7906 ,0,0,0}, {10228,11891,11892 ,7910,7907,7911 ,0,0,0}, + {11891,10228,10065 ,7907,7910,7908 ,0,0,0}, {11893,10039,11892 ,7912,7913,7911 ,0,0,0}, + {10228,11892,10039 ,7910,7911,7913 ,0,0,0}, {11893,8774,8775 ,7912,1711,1711 ,0,0,0}, + {8775,10039,11893 ,1711,7913,7912 ,0,0,0}, {11884,10221,11886 ,7897,7896,7899 ,0,0,0}, + {11888,10066,10230 ,7902,7909,7903 ,0,0,0}, {11890,10066,11888 ,7906,7909,7902 ,0,0,0}, + {11882,10220,11894 ,7892,7891,7914 ,0,0,0}, {11889,10229,10222 ,7905,7904,4137 ,0,0,0}, + {11887,10230,10229 ,7901,7903,7904 ,0,0,0}, {11884,11889,10222 ,7897,7905,4137 ,0,0,0}, + {10232,11886,10221 ,7900,7899,7896 ,0,0,0}, {10231,11882,11885 ,7890,7892,7898 ,0,0,0}, + {11885,10232,10231 ,7898,7900,7890 ,0,0,0}, {10180,11881,11883 ,7894,7888,7895 ,0,0,0}, + {11894,10233,11883 ,7914,7893,7895 ,0,0,0}, {10220,10233,11894 ,7891,7893,7914 ,0,0,0}, + {8760,10179,8761 ,1790,7889,1790 ,0,0,0}, {11881,10180,10179 ,7888,7894,7889 ,0,0,0}, + {11887,8768,11888 ,726,7658,726 ,0,0,0}, {11892,11891,8772 ,726,726,7660 ,0,0,0}, + {8774,11893,11892 ,726,7660,726 ,0,0,0}, {11887,11889,8766 ,726,726,7658 ,0,0,0}, + {8769,8772,11890 ,7660,7660,7659 ,0,0,0}, {11886,11885,8746 ,7659,726,7661 ,0,0,0}, + {11886,8762,11884 ,7659,726,726 ,0,0,0}, {8749,8747,11882 ,7915,7916,726 ,0,0,0}, + {11881,8755,8753 ,7658,7917,5475 ,0,0,0}, {11883,8750,11894 ,7658,726,7659 ,0,0,0}, + {8760,8759,8755 ,7918,7918,7917 ,0,0,0}, {8757,8755,8759 ,7661,7917,7918 ,0,0,0}, + {11883,11881,8753 ,7658,7658,5475 ,0,0,0}, {11881,8760,8755 ,7658,7918,7917 ,0,0,0}, + {8750,11883,8753 ,726,7658,5475 ,0,0,0}, {11894,8750,8749 ,7659,726,7915 ,0,0,0}, + {11882,8747,11885 ,726,7916,726 ,0,0,0}, {11894,8749,11882 ,7659,7915,726 ,0,0,0}, + {11886,8746,8762 ,7659,7661,726 ,0,0,0}, {11885,8747,8746 ,726,7916,7661 ,0,0,0}, + {8763,11889,11884 ,7664,726,726 ,0,0,0}, {8762,8763,11884 ,726,7664,726 ,0,0,0}, + {8768,11887,8766 ,7658,726,7658 ,0,0,0}, {8766,11889,8763 ,7658,726,7664 ,0,0,0}, + {11888,8769,11890 ,726,7660,7659 ,0,0,0}, {11888,8768,8769 ,726,7658,7660 ,0,0,0}, + {11892,8772,8774 ,726,7660,726 ,0,0,0}, {11891,11890,8772 ,726,7659,7660 ,0,0,0}, + {9518,11895,11896 ,726,5469,7919 ,0,0,0}, {11897,9518,11898 ,7920,726,7921 ,0,0,0}, + {9518,11897,11895 ,726,7920,5469 ,0,0,0}, {9518,11899,11898 ,726,726,7921 ,0,0,0}, + {11900,9518,11896 ,7922,726,7919 ,0,0,0}, {11899,9518,11901 ,726,726,7920 ,0,0,0}, + {11900,11902,9518 ,7922,7923,726 ,0,0,0}, {9518,11903,11904 ,726,7924,7925 ,0,0,0}, + {11904,11905,9518 ,7925,7926,726 ,0,0,0}, {11902,11903,9518 ,7923,7924,726 ,0,0,0}, + {11906,11907,9518 ,5472,7927,726 ,0,0,0}, {11906,9518,11905 ,5472,726,7926 ,0,0,0}, + {11908,11909,9518 ,7928,7929,726 ,0,0,0}, {11908,9518,11907 ,7928,726,7927 ,0,0,0}, + {11910,11911,9518 ,726,5489,726 ,0,0,0}, {11910,9518,11909 ,726,726,7929 ,0,0,0}, + {9518,11912,9517 ,726,5488,7583 ,0,0,0}, {11912,9518,11911 ,5488,726,5489 ,0,0,0}, + {9517,11913,11914 ,7583,5470,5489 ,0,0,0}, {11912,11913,9517 ,5488,5470,7583 ,0,0,0}, + {9513,9514,11914 ,5489,5488,5489 ,0,0,0}, {9517,11914,9514 ,7583,5489,5488 ,0,0,0}, + {9508,9513,11914 ,5489,5489,5489 ,0,0,0}, {9518,11485,11901 ,726,5489,7920 ,0,0,0}, + {11485,11915,11916 ,5489,5470,5488 ,0,0,0}, {11901,11485,11916 ,7920,5489,5488 ,0,0,0}, + {11917,11485,11484 ,5489,5489,726 ,0,0,0}, {11485,11917,11915 ,5489,5489,5470 ,0,0,0}, + {10548,11917,11483 ,5489,5489,7583 ,0,0,0}, {11484,11483,11917 ,726,7583,5489 ,0,0,0}, + {10082,10043,11905 ,7930,7931,7932 ,0,0,0}, {11904,10084,10082 ,7933,7934,7930 ,0,0,0}, + {11904,11903,10084 ,7933,7935,7934 ,0,0,0}, {11905,11904,10082 ,7932,7933,7930 ,0,0,0}, + {10043,10227,11906 ,7931,7936,7937 ,0,0,0}, {10024,10045,11908 ,7938,7939,7940 ,0,0,0}, + {11907,11906,10227 ,7941,7937,7936 ,0,0,0}, {10227,10024,11907 ,7936,7938,7941 ,0,0,0}, + {11908,11907,10024 ,7940,7941,7938 ,0,0,0}, {10043,11906,11905 ,7931,7937,7932 ,0,0,0}, + {11908,10045,11909 ,7940,7939,7942 ,0,0,0}, {10047,11910,11909 ,7943,7944,7942 ,0,0,0}, + {11909,10045,10047 ,7942,7939,7943 ,0,0,0}, {11910,10047,9892 ,7944,7943,7945 ,0,0,0}, + {10035,11911,9892 ,7946,7947,7945 ,0,0,0}, {10035,10048,11912 ,7946,7948,7949 ,0,0,0}, + {10035,11912,11911 ,7946,7949,7947 ,0,0,0}, {11913,10040,11914 ,7950,7951,7952 ,0,0,0}, + {11912,10048,11913 ,7949,7948,7950 ,0,0,0}, {11913,10048,10040 ,7950,7948,7951 ,0,0,0}, + {10040,10041,11914 ,7951,7952,7952 ,0,0,0}, {11910,9892,11911 ,7944,7945,7947 ,0,0,0}, + {10204,11903,11902 ,7953,7935,7954 ,0,0,0}, {11903,10204,10084 ,7935,7953,7934 ,0,0,0}, + {11900,10083,11902 ,7955,7956,7954 ,0,0,0}, {10204,11902,10083 ,7953,7954,7956 ,0,0,0}, + {11900,11896,10067 ,7955,7957,7958 ,0,0,0}, {10067,10083,11900 ,7958,7956,7955 ,0,0,0}, + {10068,11896,11895 ,7959,7957,7960 ,0,0,0}, {11896,10068,10067 ,7957,7959,7958 ,0,0,0}, + {11897,10241,11895 ,7961,7962,7960 ,0,0,0}, {10068,11895,10241 ,7959,7960,7962 ,0,0,0}, + {11897,11898,10181 ,7961,7963,7964 ,0,0,0}, {10181,10241,11897 ,7964,7962,7961 ,0,0,0}, + {10182,11898,11899 ,7965,7963,7966 ,0,0,0}, {11898,10182,10181 ,7963,7965,7964 ,0,0,0}, + {11901,10075,11899 ,7967,7968,7966 ,0,0,0}, {10182,11899,10075 ,7965,7966,7968 ,0,0,0}, + {11901,11916,10103 ,7967,7969,7970 ,0,0,0}, {10103,10075,11901 ,7970,7968,7967 ,0,0,0}, + {10104,11916,11915 ,7971,7969,7972 ,0,0,0}, {11916,10104,10103 ,7969,7971,7970 ,0,0,0}, + {10104,11915,10106 ,7971,7972,7973 ,0,0,0}, {10106,11915,11917 ,7973,7972,7973 ,0,0,0}, + {10558,10564,11917 ,7974,7974,7974 ,0,0,0}, {11917,10548,10549 ,7974,7974,7974 ,0,0,0}, + {10549,10555,11917 ,7974,7974,7974 ,0,0,0}, {10569,11917,10564 ,7974,7974,7974 ,0,0,0}, + {10555,10558,11917 ,7974,7974,7974 ,0,0,0}, {10573,10526,11917 ,7974,7974,7974 ,0,0,0}, + {10573,11917,10569 ,7974,7974,7974 ,0,0,0}, {10526,10538,11917 ,7974,7974,7974 ,0,0,0}, + {10106,11917,10537 ,7974,7974,7974 ,0,0,0}, {10538,10537,11917 ,7974,7974,7974 ,0,0,0}, + {11914,10041,10606 ,7975,7975,7975 ,0,0,0}, {10606,10656,11914 ,7975,7975,7975 ,0,0,0}, + {11914,10642,10602 ,7975,7975,7975 ,0,0,0}, {10656,10642,11914 ,7975,7975,7975 ,0,0,0}, + {11914,10608,10638 ,7975,7975,7975 ,0,0,0}, {10602,10608,11914 ,7975,7975,7975 ,0,0,0}, + {11914,10594,10593 ,7975,7975,7975 ,0,0,0}, {10638,10594,11914 ,7975,7975,7975 ,0,0,0}, + {9508,11914,10598 ,7975,7975,7975 ,0,0,0}, {10593,10598,11914 ,7975,7975,7975 ,0,0,0}, + {8723,11918,10254 ,126,7976,7977 ,0,0,0}, {11919,10256,11920 ,7978,7979,7980 ,0,0,0}, + {10270,10257,11921 ,7981,7982,7983 ,0,0,0}, {10071,11922,10062 ,7984,7985,7986 ,0,0,0}, + {11923,11924,10238 ,7987,7988,7989 ,0,0,0}, {11925,10089,11926 ,7990,7991,7992 ,0,0,0}, + {10107,10074,11927 ,7993,7994,7995 ,0,0,0}, {10099,10100,11928 ,7996,7997,7998 ,0,0,0}, + {10090,11929,10100 ,7999,8000,7997 ,0,0,0}, {10091,11930,11931 ,8001,8002,8003 ,0,0,0}, + {10099,11932,10093 ,7996,8004,8005 ,0,0,0}, {11933,10094,11931 ,8006,8007,8003 ,0,0,0}, + {10091,11931,10094 ,8001,8003,8007 ,0,0,0}, {11933,11934,10097 ,8006,8008,8009 ,0,0,0}, + {10097,10094,11933 ,8009,8007,8006 ,0,0,0}, {10136,11934,11935 ,8010,8008,8011 ,0,0,0}, + {11934,10136,10097 ,8008,8010,8009 ,0,0,0}, {11936,10098,11935 ,8012,8013,8011 ,0,0,0}, + {10136,11935,10098 ,8010,8011,8013 ,0,0,0}, {11936,8742,8743 ,8012,8014,4346 ,0,0,0}, + {8743,10098,11936 ,4346,8013,8012 ,0,0,0}, {11928,10100,11929 ,7998,7997,8000 ,0,0,0}, + {11930,10093,11932 ,8002,8005,8004 ,0,0,0}, {10093,11930,10091 ,8005,8002,8001 ,0,0,0}, + {11928,11932,10099 ,7998,8004,7996 ,0,0,0}, {11925,11929,10090 ,7990,8000,7999 ,0,0,0}, + {10107,11927,11926 ,7993,7995,7992 ,0,0,0}, {10107,11926,10089 ,7993,7992,7991 ,0,0,0}, + {10090,10089,11925 ,7999,7991,7990 ,0,0,0}, {10074,11937,11927 ,7994,8015,7995 ,0,0,0}, + {11937,10074,10062 ,8015,7994,7986 ,0,0,0}, {11924,11922,10071 ,7988,7985,7984 ,0,0,0}, + {11922,11937,10062 ,7985,8015,7986 ,0,0,0}, {10238,11924,10071 ,7989,7988,7984 ,0,0,0}, + {10255,11919,11923 ,8016,7978,7987 ,0,0,0}, {10255,11923,10238 ,8016,7987,7989 ,0,0,0}, + {10256,10270,11920 ,7979,7981,7980 ,0,0,0}, {10255,10256,11919 ,8016,7979,7978 ,0,0,0}, + {10257,11918,11921 ,7982,7976,7983 ,0,0,0}, {11920,10270,11921 ,7980,7981,7983 ,0,0,0}, + {8723,10254,8721 ,126,7977,4289 ,0,0,0}, {11918,10257,10254 ,7976,7982,7977 ,0,0,0}, + {11936,11935,11934 ,7625,7880,7758 ,0,0,0}, {8728,11919,11920 ,7626,7880,726 ,0,0,0}, + {11934,11931,11928 ,7758,8017,8018 ,0,0,0}, {11934,11933,11931 ,7758,7758,8017 ,0,0,0}, + {11930,11928,11931 ,8017,8018,8017 ,0,0,0}, {11930,11932,11928 ,8017,7758,8018 ,0,0,0}, + {11929,11934,11928 ,8019,7758,8018 ,0,0,0}, {11929,11925,11936 ,8019,7884,7625 ,0,0,0}, + {11936,11934,11929 ,7625,7758,8019 ,0,0,0}, {11925,11926,8740 ,7884,8020,7625 ,0,0,0}, + {11925,8742,11936 ,7884,7625,7625 ,0,0,0}, {11937,8736,8737 ,8021,7625,726 ,0,0,0}, + {8737,8740,11927 ,726,7625,7257 ,0,0,0}, {8730,8731,11923 ,726,726,8017 ,0,0,0}, + {8734,11922,11924 ,7625,8022,7761 ,0,0,0}, {8725,11921,8724 ,7626,726,7626 ,0,0,0}, + {11920,8725,8728 ,726,7626,7626 ,0,0,0}, {8720,8705,8704 ,7625,726,726 ,0,0,0}, + {8723,8704,11918 ,7625,726,7625 ,0,0,0}, {8716,8707,8717 ,726,726,7625 ,0,0,0}, + {8707,8716,8714 ,726,726,726 ,0,0,0}, {8711,8716,8717 ,7625,726,7625 ,0,0,0}, + {8719,8717,8720 ,7625,7625,7625 ,0,0,0}, {8717,8707,8705 ,7625,726,726 ,0,0,0}, + {8708,8707,8714 ,726,726,726 ,0,0,0}, {8704,8723,8720 ,726,7625,7625 ,0,0,0}, + {8705,8720,8717 ,726,7625,7625 ,0,0,0}, {11918,8702,8724 ,7625,726,7626 ,0,0,0}, + {8702,11918,8704 ,726,7625,726 ,0,0,0}, {11921,8725,11920 ,726,7626,726 ,0,0,0}, + {11918,8724,11921 ,7625,7626,726 ,0,0,0}, {8728,8730,11919 ,7626,726,7880 ,0,0,0}, + {11923,8731,11924 ,8017,726,7761 ,0,0,0}, {11919,8730,11923 ,7880,726,8017 ,0,0,0}, + {11924,8731,8734 ,7761,726,7625 ,0,0,0}, {11922,8736,11937 ,8022,7625,8021 ,0,0,0}, + {11922,8734,8736 ,8022,7625,7625 ,0,0,0}, {8740,11926,11927 ,7625,8020,7257 ,0,0,0}, + {11927,11937,8737 ,7257,8021,726 ,0,0,0}, {8740,8742,11925 ,7625,7625,7884 ,0,0,0}, + {8684,11938,10253 ,8023,8024,8025 ,0,0,0}, {9995,10198,11939 ,8026,8027,8028 ,0,0,0}, + {10305,10251,11940 ,8029,8030,8031 ,0,0,0}, {10244,11941,10236 ,8032,8033,8034 ,0,0,0}, + {11942,11943,10203 ,8035,8036,8037 ,0,0,0}, {11944,11945,10243 ,8038,8039,8040 ,0,0,0}, + {11944,10245,11946 ,8038,8041,8042 ,0,0,0}, {11947,11948,10242 ,8043,8044,8045 ,0,0,0}, + {10242,10142,11947 ,8045,8046,8043 ,0,0,0}, {10139,11948,11949 ,8047,8044,8048 ,0,0,0}, + {11948,10139,10242 ,8044,8047,8045 ,0,0,0}, {11950,10140,11949 ,8049,8050,8048 ,0,0,0}, + {10139,11949,10140 ,8047,8048,8050 ,0,0,0}, {11950,8698,8699 ,8049,82,82 ,0,0,0}, + {8699,10140,11950 ,82,8050,8049 ,0,0,0}, {11941,10244,11943 ,8033,8032,8036 ,0,0,0}, + {11945,10142,10243 ,8039,8046,8040 ,0,0,0}, {11947,10142,11945 ,8043,8046,8039 ,0,0,0}, + {11939,10198,11951 ,8028,8027,8051 ,0,0,0}, {11946,10245,10236 ,8042,8041,8034 ,0,0,0}, + {11944,10243,10245 ,8038,8040,8041 ,0,0,0}, {11941,11946,10236 ,8033,8042,8034 ,0,0,0}, + {10203,11943,10244 ,8037,8036,8032 ,0,0,0}, {9995,11939,11942 ,8026,8028,8035 ,0,0,0}, + {11942,10203,9995 ,8035,8037,8026 ,0,0,0}, {10251,11938,11940 ,8030,8024,8031 ,0,0,0}, + {11951,10305,11940 ,8051,8029,8031 ,0,0,0}, {10198,10305,11951 ,8027,8029,8051 ,0,0,0}, + {8684,10253,8685 ,8023,8025,8052 ,0,0,0}, {11938,10251,10253 ,8024,8030,8025 ,0,0,0}, + {11944,8681,11945 ,726,726,726 ,0,0,0}, {11948,8677,8674 ,726,7661,726 ,0,0,0}, + {11941,11943,11938 ,726,7660,726 ,0,0,0}, {11946,8684,8683 ,726,726,726 ,0,0,0}, + {11940,11938,11939 ,7661,726,726 ,0,0,0}, {11939,11951,11940 ,726,7658,7661 ,0,0,0}, + {11939,11943,11942 ,726,7660,726 ,0,0,0}, {11938,8684,11941 ,726,726,726 ,0,0,0}, + {11943,11939,11938 ,7660,726,726 ,0,0,0}, {11946,8683,11944 ,726,726,726 ,0,0,0}, + {11941,8684,11946 ,726,726,726 ,0,0,0}, {11944,8683,8681 ,726,726,726 ,0,0,0}, + {11945,8679,11947 ,726,7658,726 ,0,0,0}, {11945,8681,8679 ,726,726,7658 ,0,0,0}, + {11948,11947,8677 ,726,726,7661 ,0,0,0}, {8679,8677,11947 ,7658,7661,726 ,0,0,0}, + {11948,8674,11949 ,726,726,726 ,0,0,0}, {8673,11950,11949 ,726,726,726 ,0,0,0}, + {11949,8674,8673 ,726,726,726 ,0,0,0}, {11950,8671,8698 ,726,726,726 ,0,0,0}, + {8671,11950,8673 ,726,726,726 ,0,0,0}, {8671,8670,8698 ,726,726,726 ,0,0,0}, + {8690,8686,8687 ,7659,726,726 ,0,0,0}, {8690,8696,8686 ,7659,726,726 ,0,0,0}, + {8693,8690,8692 ,726,7659,726 ,0,0,0}, {8693,8696,8690 ,726,726,7659 ,0,0,0}, + {8698,8670,8696 ,726,726,726 ,0,0,0}, {8686,8696,8670 ,726,726,726 ,0,0,0}, + {11952,11953,11480 ,726,8053,7583 ,0,0,0}, {11482,11954,11481 ,726,726,726 ,0,0,0}, + {11953,11955,11480 ,8053,7922,7583 ,0,0,0}, {11952,11480,11956 ,726,7583,5472 ,0,0,0}, + {11480,11957,11958 ,7583,7664,5488 ,0,0,0}, {11955,11957,11480 ,7922,7664,7583 ,0,0,0}, + {11959,11960,11480 ,7920,726,7583 ,0,0,0}, {11958,11961,11480 ,5488,5471,7583 ,0,0,0}, + {11962,11963,11482 ,7664,7583,726 ,0,0,0}, {11482,11964,11965 ,726,5488,7664 ,0,0,0}, + {11966,11482,11967 ,726,726,726 ,0,0,0}, {11968,11969,11482 ,7664,7664,726 ,0,0,0}, + {11970,11967,11482 ,726,726,726 ,0,0,0}, {11482,11966,11954 ,726,726,726 ,0,0,0}, + {11968,11482,11971 ,7664,726,7664 ,0,0,0}, {11482,11969,11970 ,726,7664,726 ,0,0,0}, + {11482,11963,11971 ,726,7583,7664 ,0,0,0}, {11482,11965,11972 ,726,7664,726 ,0,0,0}, + {11482,11972,11962 ,726,726,7664 ,0,0,0}, {11960,11482,11480 ,726,726,7583 ,0,0,0}, + {11960,11964,11482 ,726,5488,726 ,0,0,0}, {11480,11961,11959 ,7583,5471,7920 ,0,0,0}, + {10509,11481,11954 ,726,726,726 ,0,0,0}, {11956,11480,11973 ,5472,7583,7793 ,0,0,0}, + {11974,11480,11479 ,5471,7583,7664 ,0,0,0}, {11480,11974,11973 ,7583,5471,7793 ,0,0,0}, + {11974,11479,10454 ,5471,7664,7920 ,0,0,0}, {10061,10060,11972 ,8054,8055,8056 ,0,0,0}, + {11965,10070,10061 ,8057,8058,8054 ,0,0,0}, {11965,11964,10070 ,8057,8058,8058 ,0,0,0}, + {11972,11965,10061 ,8056,8057,8054 ,0,0,0}, {10060,10239,11962 ,8055,8059,8060 ,0,0,0}, + {10137,10081,11971 ,8061,8062,8063 ,0,0,0}, {11963,11962,10239 ,8064,8060,8059 ,0,0,0}, + {10239,10137,11963 ,8059,8061,8064 ,0,0,0}, {11971,11963,10137 ,8063,8064,8061 ,0,0,0}, + {10060,11962,11972 ,8055,8060,8056 ,0,0,0}, {11971,10081,11968 ,8063,8062,8065 ,0,0,0}, + {10080,11969,11968 ,8066,8067,8065 ,0,0,0}, {11968,10081,10080 ,8065,8062,8066 ,0,0,0}, + {11969,10080,10240 ,8067,8066,8068 ,0,0,0}, {10088,11970,10240 ,8069,8070,8068 ,0,0,0}, + {10088,10087,11967 ,8069,8071,8072 ,0,0,0}, {10088,11967,11970 ,8069,8072,8070 ,0,0,0}, + {11966,10102,11954 ,8073,8074,8075 ,0,0,0}, {11967,10087,11966 ,8072,8071,8073 ,0,0,0}, + {11966,10087,10102 ,8073,8071,8074 ,0,0,0}, {10102,10105,11954 ,8074,8075,8075 ,0,0,0}, + {11969,10240,11970 ,8067,8068,8070 ,0,0,0}, {9893,11964,11960 ,8076,8058,8077 ,0,0,0}, + {11964,9893,10070 ,8058,8076,8058 ,0,0,0}, {11959,10141,11960 ,8078,8079,8077 ,0,0,0}, + {9893,11960,10141 ,8076,8077,8079 ,0,0,0}, {11959,11961,10085 ,8078,8080,8081 ,0,0,0}, + {10085,10141,11959 ,8081,8079,8078 ,0,0,0}, {10086,11961,11958 ,8082,8080,8083 ,0,0,0}, + {11961,10086,10085 ,8080,8082,8081 ,0,0,0}, {11957,10263,11958 ,8084,8085,8083 ,0,0,0}, + {10086,11958,10263 ,8082,8083,8085 ,0,0,0}, {11957,11955,10031 ,8084,8086,8087 ,0,0,0}, + {10031,10263,11957 ,8087,8085,8084 ,0,0,0}, {10030,11955,11953 ,8088,8086,8089 ,0,0,0}, + {11955,10030,10031 ,8086,8088,8087 ,0,0,0}, {11952,10114,11953 ,8090,8091,8089 ,0,0,0}, + {10030,11953,10114 ,8088,8089,8091 ,0,0,0}, {11952,11956,10154 ,8090,8092,8093 ,0,0,0}, + {10154,10114,11952 ,8093,8091,8090 ,0,0,0}, {10155,11956,11973 ,8094,8092,8095 ,0,0,0}, + {11956,10155,10154 ,8092,8094,8093 ,0,0,0}, {10155,11973,10156 ,8094,8095,8096 ,0,0,0}, + {10156,11973,11974 ,8096,8095,8096 ,0,0,0}, {10461,11974,10454 ,8097,8098,8097 ,0,0,0}, + {11974,10462,10465 ,8098,8097,8098 ,0,0,0}, {10461,10462,11974 ,8097,8097,8098 ,0,0,0}, + {11974,10471,10476 ,8098,8098,8097 ,0,0,0}, {10465,10471,11974 ,8098,8098,8098 ,0,0,0}, + {11974,10480,10439 ,8098,8098,8097 ,0,0,0}, {10476,10480,11974 ,8097,8098,8098 ,0,0,0}, + {11974,10443,10442 ,8098,8097,8097 ,0,0,0}, {10439,10443,11974 ,8097,8097,8098 ,0,0,0}, + {11974,10442,10156 ,8098,8097,8098 ,0,0,0}, {10518,11954,10105 ,8099,8099,8099 ,0,0,0}, + {10518,10574,11954 ,8099,8099,8099 ,0,0,0}, {11954,10574,10560 ,8099,8099,8099 ,0,0,0}, + {10514,10520,11954 ,8099,8099,8099 ,0,0,0}, {10514,11954,10560 ,8099,8099,8099 ,0,0,0}, + {10520,10556,11954 ,8099,8099,8099 ,0,0,0}, {11954,10503,10502 ,8099,8099,8099 ,0,0,0}, + {10556,10503,11954 ,8099,8099,8099 ,0,0,0}, {10509,11954,10507 ,8099,8099,8099 ,0,0,0}, + {10502,10507,11954 ,8099,8099,8099 ,0,0,0}, {8647,11975,10297 ,1359,8100,4482 ,0,0,0}, + {11976,10296,11977 ,4475,8101,8102 ,0,0,0}, {10298,10295,11978 ,8103,8104,4478 ,0,0,0}, + {10129,11979,10121 ,8105,8106,8107 ,0,0,0}, {11980,11981,10301 ,4472,8108,8109 ,0,0,0}, + {11982,10158,11983 ,8110,8111,8112 ,0,0,0}, {10157,10119,11984 ,8113,8114,8115 ,0,0,0}, + {10132,10125,11985 ,8116,8117,8118 ,0,0,0}, {10160,11986,10125 ,8119,8120,8117 ,0,0,0}, + {10150,11987,11988 ,8121,8122,8123 ,0,0,0}, {10132,11989,10152 ,8116,8124,8125 ,0,0,0}, + {11990,10149,11988 ,8126,8127,8123 ,0,0,0}, {10150,11988,10149 ,8121,8123,8127 ,0,0,0}, + {11990,11991,10147 ,8126,8128,8129 ,0,0,0}, {10147,10149,11990 ,8129,8127,8126 ,0,0,0}, + {10144,11991,11992 ,8130,8128,8131 ,0,0,0}, {11991,10144,10147 ,8128,8130,8129 ,0,0,0}, + {11993,10145,11992 ,8132,8133,8131 ,0,0,0}, {10144,11992,10145 ,8130,8131,8133 ,0,0,0}, + {11993,8666,8667 ,8132,1435,1435 ,0,0,0}, {8667,10145,11993 ,1435,8133,8132 ,0,0,0}, + {11985,10125,11986 ,8118,8117,8120 ,0,0,0}, {11987,10152,11989 ,8122,8125,8124 ,0,0,0}, + {10152,11987,10150 ,8125,8122,8121 ,0,0,0}, {11985,11989,10132 ,8118,8124,8116 ,0,0,0}, + {11982,11986,10160 ,8110,8120,8119 ,0,0,0}, {10157,11984,11983 ,8113,8115,8112 ,0,0,0}, + {10157,11983,10158 ,8113,8112,8111 ,0,0,0}, {10160,10158,11982 ,8119,8111,8110 ,0,0,0}, + {10119,11994,11984 ,8114,8134,8115 ,0,0,0}, {11994,10119,10121 ,8134,8114,8107 ,0,0,0}, + {11981,11979,10129 ,8108,8106,8105 ,0,0,0}, {11979,11994,10121 ,8106,8134,8107 ,0,0,0}, + {10301,11981,10129 ,8109,8108,8105 ,0,0,0}, {10277,11976,11980 ,4474,4475,4472 ,0,0,0}, + {10277,11980,10301 ,4474,4472,8109 ,0,0,0}, {10296,10298,11977 ,8101,8103,8102 ,0,0,0}, + {10277,10296,11976 ,4474,8101,4475 ,0,0,0}, {10295,11975,11978 ,8104,8100,4478 ,0,0,0}, + {11977,10298,11978 ,8102,8103,4478 ,0,0,0}, {8647,10297,8645 ,1359,4482,1359 ,0,0,0}, + {11975,10295,10297 ,8100,8104,4482 ,0,0,0}, {8641,11979,11981 ,726,726,726 ,0,0,0}, + {11987,8648,11988 ,726,7626,7758 ,0,0,0}, {11993,11992,11991 ,7625,7625,726 ,0,0,0}, + {11989,11985,8628 ,8135,7628,7626 ,0,0,0}, {8628,8626,11989 ,7626,7626,8135 ,0,0,0}, + {8638,11983,11984 ,726,7627,726 ,0,0,0}, {8631,11982,8632 ,726,7628,726 ,0,0,0}, + {8635,11979,8641 ,726,726,726 ,0,0,0}, {11984,11994,8640 ,726,726,726 ,0,0,0}, + {11976,11977,11978 ,7628,7628,726 ,0,0,0}, {8644,8641,11981 ,726,726,726 ,0,0,0}, + {8647,8644,11975 ,726,726,726 ,0,0,0}, {11975,11976,11978 ,726,7628,726 ,0,0,0}, + {11975,8644,11976 ,726,726,7628 ,0,0,0}, {11981,11980,8644 ,726,726,726 ,0,0,0}, + {8644,11980,11976 ,726,726,7628 ,0,0,0}, {11979,8635,8640 ,726,726,726 ,0,0,0}, + {8644,8643,8641 ,726,726,726 ,0,0,0}, {8640,8638,11984 ,726,726,726 ,0,0,0}, + {8640,11994,11979 ,726,726,726 ,0,0,0}, {11982,11983,8632 ,7628,7627,726 ,0,0,0}, + {8632,11983,8638 ,726,7627,726 ,0,0,0}, {8629,11986,8631 ,726,726,726 ,0,0,0}, + {8631,11986,11982 ,726,726,7628 ,0,0,0}, {8629,8628,11985 ,726,7626,7628 ,0,0,0}, + {11985,11986,8629 ,7628,726,726 ,0,0,0}, {8626,8648,11987 ,7626,7626,726 ,0,0,0}, + {8626,11987,11989 ,7626,726,8135 ,0,0,0}, {8649,11988,8648 ,7626,7758,7626 ,0,0,0}, + {11990,11988,8652 ,8135,7758,7628 ,0,0,0}, {8649,8652,11988 ,7626,7628,7758 ,0,0,0}, + {8652,8654,11991 ,7628,726,726 ,0,0,0}, {11991,11990,8652 ,726,8135,7628 ,0,0,0}, + {11993,8654,8655 ,7625,726,7626 ,0,0,0}, {8654,11993,11991 ,726,7625,726 ,0,0,0}, + {8658,8661,8664 ,7626,726,7626 ,0,0,0}, {8655,8658,11993 ,7626,7626,7625 ,0,0,0}, + {8664,11993,8658 ,7626,7625,7626 ,0,0,0}, {8658,8660,8661 ,7626,7627,726 ,0,0,0}, + {11993,8664,8666 ,7625,7626,8135 ,0,0,0}, {8608,11995,10283 ,1359,8136,8137 ,0,0,0}, + {10266,10268,11996 ,8138,8139,8140 ,0,0,0}, {10285,10287,11997 ,8141,8142,8143 ,0,0,0}, + {10073,11998,10072 ,8144,8145,8146 ,0,0,0}, {11999,12000,10267 ,8147,8148,8149 ,0,0,0}, + {12001,12002,10265 ,8150,8151,8152 ,0,0,0}, {12001,10264,12003 ,8150,8153,8154 ,0,0,0}, + {12004,12005,10197 ,8155,8156,8157 ,0,0,0}, {10197,10196,12004 ,8157,8158,8155 ,0,0,0}, + {10111,12005,12006 ,8159,8156,8160 ,0,0,0}, {12005,10111,10197 ,8156,8159,8157 ,0,0,0}, + {12007,10110,12006 ,8161,8162,8160 ,0,0,0}, {10111,12006,10110 ,8159,8160,8162 ,0,0,0}, + {12007,8622,8623 ,8161,1435,1435 ,0,0,0}, {8623,10110,12007 ,1435,8162,8161 ,0,0,0}, + {11998,10073,12000 ,8145,8144,8148 ,0,0,0}, {12002,10196,10265 ,8151,8158,8152 ,0,0,0}, + {12004,10196,12002 ,8155,8158,8151 ,0,0,0}, {11996,10268,12008 ,8140,8139,8163 ,0,0,0}, + {12003,10264,10072 ,8154,8153,8146 ,0,0,0}, {12001,10265,10264 ,8150,8152,8153 ,0,0,0}, + {11998,12003,10072 ,8145,8154,8146 ,0,0,0}, {10267,12000,10073 ,8149,8148,8144 ,0,0,0}, + {10266,11996,11999 ,8138,8140,8147 ,0,0,0}, {11999,10267,10266 ,8147,8149,8138 ,0,0,0}, + {10287,11995,11997 ,8142,8136,8143 ,0,0,0}, {12008,10285,11997 ,8163,8141,8143 ,0,0,0}, + {10268,10285,12008 ,8139,8141,8163 ,0,0,0}, {8608,10283,8609 ,1359,8137,1359 ,0,0,0}, + {11995,10287,10283 ,8136,8142,8137 ,0,0,0}, {12005,12000,11999 ,726,7661,7661 ,0,0,0}, + {12001,12003,12004 ,7661,7658,726 ,0,0,0}, {12004,12002,12001 ,726,726,7661 ,0,0,0}, + {11998,12000,12004 ,7658,7661,726 ,0,0,0}, {11998,12004,12003 ,7658,726,7658 ,0,0,0}, + {11999,12006,12005 ,7661,726,726 ,0,0,0}, {12000,12005,12004 ,7661,726,726 ,0,0,0}, + {12006,11999,11996 ,726,7661,7658 ,0,0,0}, {11996,12008,12007 ,7658,7661,726 ,0,0,0}, + {12007,12006,11996 ,726,726,7658 ,0,0,0}, {8622,12008,11997 ,726,7661,7658 ,0,0,0}, + {12008,8622,12007 ,7661,726,726 ,0,0,0}, {8607,8616,8608 ,7658,726,726 ,0,0,0}, + {11995,8620,11997 ,7658,7660,7658 ,0,0,0}, {8614,8607,8605 ,726,7658,726 ,0,0,0}, + {8595,8594,8601 ,726,726,726 ,0,0,0}, {8611,8603,8610 ,726,726,726 ,0,0,0}, + {8601,8598,8597 ,726,726,726 ,0,0,0}, {8601,8594,8610 ,726,726,726 ,0,0,0}, + {8595,8601,8597 ,726,726,726 ,0,0,0}, {8605,8603,8611 ,726,726,726 ,0,0,0}, + {8603,8601,8610 ,726,726,726 ,0,0,0}, {8616,8607,8614 ,726,7658,726 ,0,0,0}, + {8614,8605,8611 ,726,726,726 ,0,0,0}, {8608,8617,11995 ,726,726,7658 ,0,0,0}, + {8608,8616,8617 ,726,726,726 ,0,0,0}, {11997,8620,8622 ,7658,7660,726 ,0,0,0}, + {8617,8620,11995 ,726,7660,7658 ,0,0,0}, {12009,12010,11477 ,726,726,7664 ,0,0,0}, + {12011,12009,11477 ,726,726,7664 ,0,0,0}, {12011,11477,12012 ,726,7664,726 ,0,0,0}, + {12013,11477,12010 ,726,7664,726 ,0,0,0}, {12014,12015,11477 ,726,726,7664 ,0,0,0}, + {12014,11477,12013 ,726,7664,726 ,0,0,0}, {12016,11477,11475 ,726,7664,726 ,0,0,0}, + {12012,11477,12016 ,726,7664,726 ,0,0,0}, {12017,11477,12015 ,726,7664,726 ,0,0,0}, + {11477,12017,12018 ,7664,726,726 ,0,0,0}, {12016,11475,12019 ,726,726,726 ,0,0,0}, + {12020,11477,12018 ,726,7664,726 ,0,0,0}, {12021,12019,11475 ,7583,726,726 ,0,0,0}, + {11475,12022,12021 ,726,7664,7583 ,0,0,0}, {11477,12020,12023 ,7664,726,726 ,0,0,0}, + {11477,12023,12024 ,7664,726,726 ,0,0,0}, {12025,12022,11475 ,726,7664,726 ,0,0,0}, + {12026,12027,11475 ,726,726,726 ,0,0,0}, {12027,12025,11475 ,726,726,726 ,0,0,0}, + {12028,11475,12029 ,726,726,726 ,0,0,0}, {12028,12026,11475 ,726,726,726 ,0,0,0}, + {11478,12024,10415 ,7664,726,726 ,0,0,0}, {12024,11478,11477 ,726,7664,7664 ,0,0,0}, + {12029,11475,12030 ,726,726,726 ,0,0,0}, {12031,11475,11476 ,726,726,7664 ,0,0,0}, + {11475,12031,12030 ,726,726,726 ,0,0,0}, {12031,11476,10339 ,726,7664,5488 ,0,0,0}, + {10127,10120,12009 ,8164,8165,8166 ,0,0,0}, {12011,10128,10127 ,8167,8168,8164 ,0,0,0}, + {12011,12012,10128 ,8167,8168,8168 ,0,0,0}, {12009,12011,10127 ,8166,8167,8164 ,0,0,0}, + {10120,10261,12010 ,8165,8169,8170 ,0,0,0}, {10159,10161,12014 ,8171,8172,8173 ,0,0,0}, + {12013,12010,10261 ,8174,8170,8169 ,0,0,0}, {10261,10159,12013 ,8169,8171,8174 ,0,0,0}, + {12014,12013,10159 ,8173,8174,8171 ,0,0,0}, {10120,12010,12009 ,8165,8170,8166 ,0,0,0}, + {12014,10161,12015 ,8173,8172,8175 ,0,0,0}, {10124,12017,12015 ,8176,8177,8175 ,0,0,0}, + {12015,10161,10124 ,8175,8172,8176 ,0,0,0}, {12017,10124,10126 ,8177,8176,8178 ,0,0,0}, + {10131,12018,10126 ,8179,8180,8178 ,0,0,0}, {10131,10163,12020 ,8179,8181,8182 ,0,0,0}, + {10131,12020,12018 ,8179,8182,8180 ,0,0,0}, {12023,10165,12024 ,8183,8184,8185 ,0,0,0}, + {12020,10163,12023 ,8182,8181,8183 ,0,0,0}, {12023,10163,10165 ,8183,8181,8184 ,0,0,0}, + {10165,10164,12024 ,8184,8185,8185 ,0,0,0}, {12017,10126,12018 ,8177,8178,8180 ,0,0,0}, + {10123,12012,12016 ,8186,8168,8187 ,0,0,0}, {12012,10123,10128 ,8168,8186,8168 ,0,0,0}, + {12019,10122,12016 ,8188,8189,8187 ,0,0,0}, {10123,12016,10122 ,8186,8187,8189 ,0,0,0}, + {12019,12021,10289 ,8188,8190,8191 ,0,0,0}, {10289,10122,12019 ,8191,8189,8188 ,0,0,0}, + {10117,12021,12022 ,8192,8190,8193 ,0,0,0}, {12021,10117,10289 ,8190,8192,8191 ,0,0,0}, + {12025,10118,12022 ,8194,8195,8193 ,0,0,0}, {10117,12022,10118 ,8192,8193,8195 ,0,0,0}, + {12025,12027,10191 ,8194,8196,8197 ,0,0,0}, {10191,10118,12025 ,8197,8195,8194 ,0,0,0}, + {10192,12027,12026 ,8198,8196,8199 ,0,0,0}, {12027,10192,10191 ,8196,8198,8197 ,0,0,0}, + {12028,9935,12026 ,8200,8201,8199 ,0,0,0}, {10192,12026,9935 ,8198,8199,8201 ,0,0,0}, + {12028,12029,9938 ,8200,8202,8203 ,0,0,0}, {9938,9935,12028 ,8203,8201,8200 ,0,0,0}, + {9939,12029,12030 ,8204,8202,8205 ,0,0,0}, {12029,9939,9938 ,8202,8204,8203 ,0,0,0}, + {9939,12030,9940 ,8204,8205,8206 ,0,0,0}, {9940,12030,12031 ,8206,8205,8206 ,0,0,0}, + {10340,12031,10339 ,8207,8207,8207 ,0,0,0}, {12031,10370,10373 ,8207,8207,8207 ,0,0,0}, + {10340,10370,12031 ,8207,8207,8207 ,0,0,0}, {12031,10379,10384 ,8207,8207,8207 ,0,0,0}, + {10373,10379,12031 ,8207,8207,8207 ,0,0,0}, {12031,10388,10318 ,8207,8207,8207 ,0,0,0}, + {10384,10388,12031 ,8207,8207,8207 ,0,0,0}, {12031,10321,10320 ,8207,8207,8207 ,0,0,0}, + {10318,10321,12031 ,8207,8207,8207 ,0,0,0}, {12031,10320,9940 ,8207,8207,8207 ,0,0,0}, + {10430,12024,10164 ,8208,8208,8208 ,0,0,0}, {10430,10481,12024 ,8208,8208,8208 ,0,0,0}, + {12024,10481,10467 ,8208,8208,8208 ,0,0,0}, {10424,10417,12024 ,8208,8208,8208 ,0,0,0}, + {10424,12024,10467 ,8208,8208,8208 ,0,0,0}, {10417,10463,12024 ,8208,8208,8208 ,0,0,0}, + {12024,10455,10409 ,8208,8208,8208 ,0,0,0}, {10463,10455,12024 ,8208,8208,8208 ,0,0,0}, + {10415,12024,10411 ,8208,8208,8208 ,0,0,0}, {10409,10411,12024 ,8208,8208,8208 ,0,0,0}, + {8571,12032,9927 ,1711,8209,4414 ,0,0,0}, {12033,10190,12034 ,8210,8211,8212 ,0,0,0}, + {10175,9928,12035 ,8213,8214,4410 ,0,0,0}, {10189,12036,9919 ,4402,8215,8216 ,0,0,0}, + {12037,12038,10188 ,8217,8218,8219 ,0,0,0}, {12039,9949,12040 ,8220,8221,8222 ,0,0,0}, + {9948,10174,12041 ,8223,8224,8225 ,0,0,0}, {9922,9921,12042 ,8226,8227,8228 ,0,0,0}, + {9944,12043,9921 ,8229,8230,8227 ,0,0,0}, {9925,12044,12045 ,8231,8232,8233 ,0,0,0}, + {9922,12046,9924 ,8226,8234,8235 ,0,0,0}, {12047,9941,12045 ,8236,8237,8233 ,0,0,0}, + {9925,12045,9941 ,8231,8233,8237 ,0,0,0}, {12047,12048,9929 ,8236,8238,8239 ,0,0,0}, + {9929,9941,12047 ,8239,8237,8236 ,0,0,0}, {10177,12048,12049 ,8240,8238,8241 ,0,0,0}, + {12048,10177,9929 ,8238,8240,8239 ,0,0,0}, {12050,9937,12049 ,8242,8243,8241 ,0,0,0}, + {10177,12049,9937 ,8240,8241,8243 ,0,0,0}, {12050,8590,8591 ,8242,1790,1790 ,0,0,0}, + {8591,9937,12050 ,1790,8243,8242 ,0,0,0}, {12042,9921,12043 ,8228,8227,8230 ,0,0,0}, + {12044,9924,12046 ,8232,8235,8234 ,0,0,0}, {9924,12044,9925 ,8235,8232,8231 ,0,0,0}, + {12042,12046,9922 ,8228,8234,8226 ,0,0,0}, {12039,12043,9944 ,8220,8230,8229 ,0,0,0}, + {9948,12041,12040 ,8223,8225,8222 ,0,0,0}, {9948,12040,9949 ,8223,8222,8221 ,0,0,0}, + {9944,9949,12039 ,8229,8221,8220 ,0,0,0}, {10174,12051,12041 ,8224,8244,8225 ,0,0,0}, + {12051,10174,9919 ,8244,8224,8216 ,0,0,0}, {12038,12036,10189 ,8218,8215,4402 ,0,0,0}, + {12036,12051,9919 ,8215,8244,8216 ,0,0,0}, {10188,12038,10189 ,8219,8218,4402 ,0,0,0}, + {9889,12033,12037 ,8245,8210,8217 ,0,0,0}, {9889,12037,10188 ,8245,8217,8219 ,0,0,0}, + {10190,10175,12034 ,8211,8213,8212 ,0,0,0}, {9889,10190,12033 ,8245,8211,8210 ,0,0,0}, + {9928,12032,12035 ,8214,8209,4410 ,0,0,0}, {12034,10175,12035 ,8212,8213,4410 ,0,0,0}, + {8571,9927,8569 ,1711,4414,1711 ,0,0,0}, {12032,9928,9927 ,8209,8214,4414 ,0,0,0}, + {12037,12042,12043 ,726,726,7626 ,0,0,0}, {12051,12040,12041 ,726,726,726 ,0,0,0}, + {12039,12051,12036 ,726,726,726 ,0,0,0}, {12038,12039,12036 ,726,726,726 ,0,0,0}, + {12038,12043,12039 ,726,7626,726 ,0,0,0}, {12051,12039,12040 ,726,726,726 ,0,0,0}, + {12038,12037,12043 ,726,726,7626 ,0,0,0}, {12033,12046,12042 ,726,726,726 ,0,0,0}, + {12037,12033,12042 ,726,726,726 ,0,0,0}, {12046,12034,12044 ,726,726,7626 ,0,0,0}, + {12034,12046,12033 ,726,726,726 ,0,0,0}, {12045,12044,12035 ,7628,7626,726 ,0,0,0}, + {12034,12035,12044 ,726,726,7626 ,0,0,0}, {12032,12047,12045 ,726,726,7628 ,0,0,0}, + {12045,12035,12032 ,7628,726,726 ,0,0,0}, {12047,8571,12048 ,726,726,726 ,0,0,0}, + {8571,12047,12032 ,726,726,726 ,0,0,0}, {12049,12048,8568 ,7625,726,726 ,0,0,0}, + {8571,8568,12048 ,726,726,726 ,0,0,0}, {12049,8568,8567 ,7625,726,726 ,0,0,0}, + {12050,12049,8567 ,726,7625,726 ,0,0,0}, {8567,8565,12050 ,726,726,726 ,0,0,0}, + {8559,8590,8565 ,726,726,726 ,0,0,0}, {12050,8565,8590 ,726,726,726 ,0,0,0}, + {8562,8556,8584 ,726,726,7625 ,0,0,0}, {8559,8564,8588 ,726,726,726 ,0,0,0}, + {8553,8578,8579 ,7626,726,726 ,0,0,0}, {8579,8582,8555 ,726,726,726 ,0,0,0}, + {8578,8552,8576 ,726,7625,7625 ,0,0,0}, {8552,8573,8576 ,7625,726,7625 ,0,0,0}, + {8550,8573,8552 ,726,726,7625 ,0,0,0}, {8550,8572,8573 ,726,726,726 ,0,0,0}, + {8555,8553,8579 ,726,7626,726 ,0,0,0}, {8552,8578,8553 ,7625,726,7626 ,0,0,0}, + {8582,8584,8556 ,726,7625,726 ,0,0,0}, {8555,8582,8556 ,726,726,726 ,0,0,0}, + {8562,8585,8564 ,726,726,726 ,0,0,0}, {8562,8584,8585 ,726,7625,726 ,0,0,0}, + {8559,8588,8590 ,726,726,726 ,0,0,0}, {8585,8588,8564 ,726,726,726 ,0,0,0}, + {8532,12052,10201 ,1711,8246,8247 ,0,0,0}, {10260,10274,12053 ,8248,8249,8250 ,0,0,0}, + {10273,10202,12054 ,8251,8252,8253 ,0,0,0}, {10113,12055,10112 ,8254,8255,8256 ,0,0,0}, + {12056,12057,10294 ,8257,8258,8259 ,0,0,0}, {12058,12059,10292 ,8260,8261,8262 ,0,0,0}, + {12058,10291,12060 ,8260,8263,8264 ,0,0,0}, {12061,12062,10194 ,8265,8266,8267 ,0,0,0}, + {10194,10195,12061 ,8267,8268,8265 ,0,0,0}, {10290,12062,12063 ,8269,8266,8270 ,0,0,0}, + {12062,10290,10194 ,8266,8269,8267 ,0,0,0}, {12064,10193,12063 ,8271,8272,8270 ,0,0,0}, + {10290,12063,10193 ,8269,8270,8272 ,0,0,0}, {12064,8546,8547 ,8271,1790,1790 ,0,0,0}, + {8547,10193,12064 ,1790,8272,8271 ,0,0,0}, {12055,10113,12057 ,8255,8254,8258 ,0,0,0}, + {12059,10195,10292 ,8261,8268,8262 ,0,0,0}, {12061,10195,12059 ,8265,8268,8261 ,0,0,0}, + {12053,10274,12065 ,8250,8249,8273 ,0,0,0}, {12060,10291,10112 ,8264,8263,8256 ,0,0,0}, + {12058,10292,10291 ,8260,8262,8263 ,0,0,0}, {12055,12060,10112 ,8255,8264,8256 ,0,0,0}, + {10294,12057,10113 ,8259,8258,8254 ,0,0,0}, {10260,12053,12056 ,8248,8250,8257 ,0,0,0}, + {12056,10294,10260 ,8257,8259,8248 ,0,0,0}, {10202,12052,12054 ,8252,8246,8253 ,0,0,0}, + {12065,10273,12054 ,8273,8251,8253 ,0,0,0}, {10274,10273,12065 ,8249,8251,8273 ,0,0,0}, + {8532,10201,8533 ,1711,8247,1711 ,0,0,0}, {12052,10202,10201 ,8246,8252,8247 ,0,0,0}, + {8546,12064,12063 ,726,7658,726 ,0,0,0}, {12065,8521,12053 ,726,726,726 ,0,0,0}, + {8544,12063,12062 ,7660,726,7660 ,0,0,0}, {12058,8540,12059 ,7660,726,7660 ,0,0,0}, + {8541,8544,12061 ,7660,7660,7583 ,0,0,0}, {8534,12055,12057 ,7660,7661,7661 ,0,0,0}, + {8538,12058,12060 ,726,7660,7658 ,0,0,0}, {8519,12053,8521 ,726,726,726 ,0,0,0}, + {12057,12056,8518 ,7661,726,726 ,0,0,0}, {12052,8527,8525 ,726,726,726 ,0,0,0}, + {12054,8522,12065 ,726,726,726 ,0,0,0}, {8532,8531,8527 ,726,726,726 ,0,0,0}, + {8529,8527,8531 ,726,726,726 ,0,0,0}, {8527,12052,8532 ,726,726,726 ,0,0,0}, + {12054,8525,8522 ,726,726,726 ,0,0,0}, {12054,12052,8525 ,726,726,726 ,0,0,0}, + {12056,12053,8519 ,726,726,726 ,0,0,0}, {8521,12065,8522 ,726,726,726 ,0,0,0}, + {8518,8534,12057 ,726,7660,7661 ,0,0,0}, {8519,8518,12056 ,726,726,726 ,0,0,0}, + {12060,12055,8535 ,7658,7661,7659 ,0,0,0}, {8535,12055,8534 ,7659,7661,7660 ,0,0,0}, + {8538,12060,8535 ,726,7658,7659 ,0,0,0}, {8541,12059,8540 ,7660,7660,726 ,0,0,0}, + {12058,8538,8540 ,7660,726,726 ,0,0,0}, {8544,12062,12061 ,7660,7660,7583 ,0,0,0}, + {8541,12061,12059 ,7660,7583,7660 ,0,0,0}, {8544,8546,12063 ,7660,726,726 ,0,0,0}, + {10299,8491,12066 ,8274,8275,8276 ,0,0,0}, {10300,10276,12067 ,8277,8278,8279 ,0,0,0}, + {12068,10276,10293 ,8280,8278,8281 ,0,0,0}, {12069,12070,10200 ,8282,8283,8284 ,0,0,0}, + {12071,10272,10271 ,8285,8286,8287 ,0,0,0}, {10281,10269,12072 ,8288,8289,8290 ,0,0,0}, + {10280,12073,12074 ,8291,8292,8293 ,0,0,0}, {10303,12075,10286 ,8294,8295,8296 ,0,0,0}, + {12076,12077,10282 ,1631,8297,1631 ,0,0,0}, {12078,12079,10284 ,8298,8299,8300 ,0,0,0}, + {12078,10304,12080 ,8298,8301,8302 ,0,0,0}, {12081,12082,10279 ,8303,8304,8305 ,0,0,0}, + {12081,10278,12079 ,8303,8306,8299 ,0,0,0}, {10217,12082,12083 ,8307,8304,8308 ,0,0,0}, + {12082,10217,10279 ,8304,8307,8305 ,0,0,0}, {12084,10258,12083 ,8309,8310,8308 ,0,0,0}, + {10217,12083,10258 ,8307,8308,8310 ,0,0,0}, {10199,12084,10252 ,8311,8309,8312 ,0,0,0}, + {10199,10258,12084 ,8311,8310,8309 ,0,0,0}, {10250,10252,12085 ,8313,8312,8314 ,0,0,0}, + {12084,12085,10252 ,8309,8314,8312 ,0,0,0}, {12086,8515,10250 ,8315,126,8313 ,0,0,0}, + {10250,12085,12086 ,8313,8314,8315 ,0,0,0}, {8513,8515,12086 ,126,126,8315 ,0,0,0}, + {10278,10284,12079 ,8306,8300,8299 ,0,0,0}, {12081,10279,10278 ,8303,8305,8306 ,0,0,0}, + {10304,10286,12080 ,8301,8296,8302 ,0,0,0}, {12078,10284,10304 ,8298,8300,8301 ,0,0,0}, + {12077,12075,10303 ,8297,8295,8294 ,0,0,0}, {12075,12080,10286 ,8295,8302,8296 ,0,0,0}, + {10281,12076,10282 ,8288,1631,1631 ,0,0,0}, {10282,12077,10303 ,1631,8297,8294 ,0,0,0}, + {10269,12074,12072 ,8289,8293,8290 ,0,0,0}, {10281,12072,12076 ,8288,8290,1631 ,0,0,0}, + {10280,10302,12073 ,8291,8316,8292 ,0,0,0}, {10269,10280,12074 ,8289,8291,8293 ,0,0,0}, + {10200,12070,10302 ,8284,8283,8316 ,0,0,0}, {12073,10302,12070 ,8292,8316,8283 ,0,0,0}, + {12071,12069,10272 ,8285,8282,8286 ,0,0,0}, {12069,10200,10272 ,8282,8284,8286 ,0,0,0}, + {10300,12087,10271 ,8277,8317,8287 ,0,0,0}, {12087,12071,10271 ,8317,8285,8287 ,0,0,0}, + {10276,12088,12067 ,8278,8318,8279 ,0,0,0}, {10300,12067,12087 ,8277,8279,8317 ,0,0,0}, + {12068,10293,12066 ,8280,8281,8276 ,0,0,0}, {12088,10276,12068 ,8318,8278,8280 ,0,0,0}, + {8491,10299,8490 ,8275,8274,4114 ,0,0,0}, {12066,10293,10299 ,8276,8281,8274 ,0,0,0}, + {12078,12089,12079 ,726,726,726 ,0,0,0}, {12090,8464,12086 ,726,726,726 ,0,0,0}, + {12091,12082,12092 ,726,726,726 ,0,0,0}, {8495,8449,8448 ,726,726,7661 ,0,0,0}, + {8504,8506,8458 ,726,726,726 ,0,0,0}, {12093,12085,12084 ,726,726,726 ,0,0,0}, + {8509,8512,8463 ,726,726,726 ,0,0,0}, {8513,8464,8512 ,726,726,726 ,0,0,0}, + {8461,8459,8510 ,7658,726,726 ,0,0,0}, {8509,8463,8461 ,726,726,7658 ,0,0,0}, + {12093,12090,12085 ,726,726,726 ,0,0,0}, {8506,8507,8459 ,726,726,726 ,0,0,0}, + {8504,8458,8455 ,726,726,726 ,0,0,0}, {8500,8453,8498 ,726,726,726 ,0,0,0}, + {8501,8455,8453 ,726,726,726 ,0,0,0}, {8449,8495,8498 ,726,726,726 ,0,0,0}, + {12091,12084,12083 ,726,726,726 ,0,0,0}, {12079,12094,12081 ,726,7661,726 ,0,0,0}, + {12081,12094,12092 ,726,7661,726 ,0,0,0}, {8428,8468,8467 ,7658,726,7658 ,0,0,0}, + {8494,8448,8428 ,726,7661,7658 ,0,0,0}, {12095,12089,12080 ,726,726,726 ,0,0,0}, + {8468,8432,8469 ,726,7658,726 ,0,0,0}, {8471,8433,8434 ,7661,7658,726 ,0,0,0}, + {12075,12077,12096 ,726,7661,726 ,0,0,0}, {12075,12096,12095 ,726,726,726 ,0,0,0}, + {12077,12076,12097 ,7661,7658,7658 ,0,0,0}, {8475,8474,8434 ,726,726,726 ,0,0,0}, + {8438,8477,8435 ,726,7583,726 ,0,0,0}, {12098,12099,12074 ,726,726,726 ,0,0,0}, + {12099,12097,12072 ,726,7658,726 ,0,0,0}, {8487,8441,8444 ,7664,726,7664 ,0,0,0}, + {12098,12074,12073 ,726,726,7661 ,0,0,0}, {12100,12073,12070 ,726,7661,7664 ,0,0,0}, + {8447,8491,8489 ,726,726,7664 ,0,0,0}, {12101,12066,8447 ,7664,726,726 ,0,0,0}, + {12100,12069,12102 ,726,7583,726 ,0,0,0}, {12068,12103,12088 ,7664,7664,726 ,0,0,0}, + {8469,8432,8433 ,726,7658,7658 ,0,0,0}, {12067,12088,12104 ,7664,726,7664 ,0,0,0}, + {12103,12104,12088 ,7664,7664,726 ,0,0,0}, {12068,12066,12101 ,7664,726,7664 ,0,0,0}, + {12068,12101,12103 ,7664,7664,7664 ,0,0,0}, {12105,12102,12071 ,7664,726,7583 ,0,0,0}, + {12105,12071,12087 ,7664,7583,7664 ,0,0,0}, {8491,8447,12066 ,726,726,726 ,0,0,0}, + {8440,8441,8483 ,726,726,726 ,0,0,0}, {8438,8440,8480 ,726,726,7664 ,0,0,0}, + {12105,12087,12104 ,7664,7664,7664 ,0,0,0}, {12087,12067,12104 ,7664,7664,7664 ,0,0,0}, + {12069,12071,12102 ,7583,7583,726 ,0,0,0}, {12070,12069,12100 ,7664,7583,726 ,0,0,0}, + {12098,12073,12100 ,726,7661,726 ,0,0,0}, {12072,12074,12099 ,726,726,726 ,0,0,0}, + {12076,12072,12097 ,7658,726,7658 ,0,0,0}, {12096,12077,12097 ,726,7661,7658 ,0,0,0}, + {12080,12075,12095 ,726,726,726 ,0,0,0}, {12078,12080,12089 ,726,726,726 ,0,0,0}, + {12094,12079,12089 ,7661,726,726 ,0,0,0}, {12082,12081,12092 ,726,726,726 ,0,0,0}, + {12083,12082,12091 ,726,726,726 ,0,0,0}, {12093,12084,12091 ,726,726,726 ,0,0,0}, + {12086,12085,12090 ,726,726,726 ,0,0,0}, {8513,12086,8464 ,726,726,726 ,0,0,0}, + {8463,8512,8464 ,726,726,726 ,0,0,0}, {8510,8509,8461 ,726,726,7658 ,0,0,0}, + {8507,8510,8459 ,726,726,726 ,0,0,0}, {8458,8506,8459 ,726,726,726 ,0,0,0}, + {8501,8504,8455 ,726,726,726 ,0,0,0}, {8500,8501,8453 ,726,726,726 ,0,0,0}, + {8449,8498,8453 ,726,726,726 ,0,0,0}, {8494,8495,8448 ,726,726,7661 ,0,0,0}, + {8467,8494,8428 ,7658,726,7658 ,0,0,0}, {8432,8468,8428 ,7658,726,7658 ,0,0,0}, + {8474,8471,8434 ,726,7661,726 ,0,0,0}, {8471,8469,8433 ,7661,726,7658 ,0,0,0}, + {8435,8475,8434 ,726,726,726 ,0,0,0}, {8438,8480,8477 ,726,7664,7583 ,0,0,0}, + {8435,8477,8475 ,726,7583,726 ,0,0,0}, {8440,8481,8480 ,726,7664,7664 ,0,0,0}, + {8483,8441,8487 ,726,726,7664 ,0,0,0}, {8481,8440,8483 ,7664,726,726 ,0,0,0}, + {8487,8444,8489 ,7664,7664,7664 ,0,0,0}, {8447,8489,8444 ,726,7664,7664 ,0,0,0}, + {12106,12107,8431 ,726,726,726 ,0,0,0}, {8450,8452,8460 ,726,726,726 ,0,0,0}, + {8429,8450,8465 ,726,726,726 ,0,0,0}, {8431,8430,12106 ,726,726,726 ,0,0,0}, + {8456,8457,8460 ,726,726,726 ,0,0,0}, {8451,8454,8452 ,726,726,726 ,0,0,0}, + {8456,8460,8454 ,726,726,726 ,0,0,0}, {8452,8454,8460 ,726,726,726 ,0,0,0}, + {8460,8462,8450 ,726,726,726 ,0,0,0}, {12106,8429,8465 ,726,726,726 ,0,0,0}, + {8465,8450,8462 ,726,726,726 ,0,0,0}, {8431,12107,12108 ,726,726,726 ,0,0,0}, + {12106,8430,8429 ,726,726,726 ,0,0,0}, {8436,12108,12109 ,726,726,726 ,0,0,0}, + {12108,8436,8431 ,726,726,726 ,0,0,0}, {12109,8439,8437 ,726,726,7658 ,0,0,0}, + {8436,12109,8437 ,726,726,7658 ,0,0,0}, {12110,8439,12109 ,726,726,726 ,0,0,0}, + {8439,12111,8442 ,726,726,7661 ,0,0,0}, {12111,8439,12110 ,726,726,726 ,0,0,0}, + {12111,12112,8442 ,726,726,7661 ,0,0,0}, {8443,12112,8445 ,726,726,7661 ,0,0,0}, + {8443,8442,12112 ,726,7661,726 ,0,0,0}, {8445,12113,12114 ,7661,726,726 ,0,0,0}, + {12112,12113,8445 ,726,726,7661 ,0,0,0}, {12115,8446,12114 ,726,7658,726 ,0,0,0}, + {8445,12114,8446 ,7661,726,7658 ,0,0,0}, {12116,12117,12118 ,726,726,7660 ,0,0,0}, + {12118,12119,12116 ,7660,726,726 ,0,0,0}, {12117,12120,12121 ,726,726,7658 ,0,0,0}, + {12117,12115,12118 ,726,726,7660 ,0,0,0}, {12117,12122,12115 ,726,7661,726 ,0,0,0}, + {12117,12116,12120 ,726,726,726 ,0,0,0}, {12115,12122,8446 ,726,7661,7658 ,0,0,0}, + {12122,8447,8446 ,8319,81,8320 ,0,0,0}, {12120,12105,12121 ,8321,8322,8323 ,0,0,0}, + {12117,12104,12103 ,8324,8325,8326 ,0,0,0}, {12118,12115,12098 ,8327,8328,8329 ,0,0,0}, + {12116,12119,12100 ,8330,8331,8332 ,0,0,0}, {12112,12096,12113 ,8333,8334,8335 ,0,0,0}, + {12097,12114,12113 ,8336,8337,8335 ,0,0,0}, {12110,12094,12111 ,7530,8338,8339 ,0,0,0}, + {12089,12112,12111 ,8340,8333,8339 ,0,0,0}, {12109,12091,12092 ,8341,8342,8343 ,0,0,0}, + {12092,12110,12109 ,8343,7530,8341 ,0,0,0}, {12091,12108,12093 ,8342,8344,8345 ,0,0,0}, + {12108,12091,12109 ,8344,8342,8341 ,0,0,0}, {12090,12093,12107 ,8346,8345,8347 ,0,0,0}, + {12108,12107,12093 ,8344,8347,8345 ,0,0,0}, {8465,12090,12106 ,96,8346,8348 ,0,0,0}, + {12090,12107,12106 ,8346,8347,8348 ,0,0,0}, {8464,12090,8465 ,96,8346,96 ,0,0,0}, + {12089,12111,12094 ,8340,8339,8338 ,0,0,0}, {12092,12094,12110 ,8343,8338,7530 ,0,0,0}, + {12095,12096,12112 ,8349,8334,8333 ,0,0,0}, {12089,12095,12112 ,8340,8349,8333 ,0,0,0}, + {12099,12114,12097 ,8350,8337,8336 ,0,0,0}, {12096,12097,12113 ,8334,8336,8335 ,0,0,0}, + {12098,12115,12099 ,8329,8328,8350 ,0,0,0}, {12114,12099,12115 ,8337,8350,8328 ,0,0,0}, + {12100,12119,12098 ,8332,8331,8329 ,0,0,0}, {12119,12118,12098 ,8331,8327,8329 ,0,0,0}, + {12102,12120,12116 ,7516,8321,8330 ,0,0,0}, {12102,12116,12100 ,7516,8330,8332 ,0,0,0}, + {12105,12104,12121 ,8322,8325,8323 ,0,0,0}, {12102,12105,12120 ,7516,8322,8321 ,0,0,0}, + {12117,12103,12122 ,8324,8326,8319 ,0,0,0}, {12121,12104,12117 ,8323,8325,8324 ,0,0,0}, + {8447,12122,12101 ,81,8319,8351 ,0,0,0}, {12122,12103,12101 ,8319,8326,8351 ,0,0,0} +// MotorHacker.prt + , {12123,12124,12125 ,4056,4057,4058 ,0,0,0}, {12126,12127,12125 ,4059,4060,4058 ,0,0,0}, + {12123,12125,12127 ,4056,4058,4060 ,0,0,0}, {12128,12126,12129 ,4061,4059,4062 ,0,0,0}, + {12128,12127,12126 ,4061,4060,4059 ,0,0,0}, {12130,12129,12131 ,4063,4062,4064 ,0,0,0}, + {12126,12131,12129 ,4059,4064,4062 ,0,0,0}, {12132,12133,12130 ,4065,4066,4063 ,0,0,0}, + {12130,12131,12132 ,4063,4064,4065 ,0,0,0}, {12133,12134,12135 ,4066,4067,4068 ,0,0,0}, + {12134,12133,12132 ,4067,4066,4065 ,0,0,0}, {12136,12135,12137 ,4069,4068,4070 ,0,0,0}, + {12134,12137,12135 ,4067,4070,4068 ,0,0,0}, {12138,12139,12136 ,4071,4072,4069 ,0,0,0}, + {12136,12137,12138 ,4069,4070,4071 ,0,0,0}, {12140,12141,12139 ,4073,81,4072 ,0,0,0}, + {12140,12139,12138 ,4073,4072,4071 ,0,0,0}, {12141,12142,12139 ,81,81,4072 ,0,0,0}, + {12143,12124,12123 ,4074,4057,4056 ,0,0,0}, {12143,12144,12145 ,4074,4075,4076 ,0,0,0}, + {12145,12124,12143 ,4076,4057,4074 ,0,0,0}, {12146,12147,12144 ,4077,4078,4075 ,0,0,0}, + {12144,12147,12145 ,4075,4078,4076 ,0,0,0}, {12148,12149,12146 ,4079,4080,4077 ,0,0,0}, + {12146,12144,12148 ,4077,4075,4079 ,0,0,0}, {12149,12150,12151 ,4080,4081,4082 ,0,0,0}, + {12150,12149,12148 ,4081,4080,4079 ,0,0,0}, {12152,12151,12153 ,4083,4082,4084 ,0,0,0}, + {12150,12153,12151 ,4081,4084,4082 ,0,0,0}, {12154,12155,12152 ,4085,4086,4083 ,0,0,0}, + {12152,12153,12154 ,4083,4084,4085 ,0,0,0}, {12155,12156,12157 ,4086,4087,4088 ,0,0,0}, + {12156,12155,12154 ,4087,4086,4085 ,0,0,0}, {12157,12158,12159 ,4088,4089,4090 ,0,0,0}, + {12156,12158,12157 ,4087,4089,4088 ,0,0,0}, {12157,12159,12160 ,4088,4090,4091 ,0,0,0}, + {12161,12162,12163 ,2394,2394,4092 ,0,0,0}, {12164,12165,12163 ,4093,4094,4092 ,0,0,0}, + {12161,12163,12165 ,2394,4092,4094 ,0,0,0}, {12164,12166,12167 ,4093,4095,4096 ,0,0,0}, + {12167,12165,12164 ,4096,4094,4093 ,0,0,0}, {12168,12166,12169 ,4097,4095,4098 ,0,0,0}, + {12166,12168,12167 ,4095,4097,4096 ,0,0,0}, {12170,12171,12169 ,4099,4100,4098 ,0,0,0}, + {12168,12169,12171 ,4097,4098,4100 ,0,0,0}, {12170,12172,12173 ,4099,4101,4102 ,0,0,0}, + {12173,12171,12170 ,4102,4100,4099 ,0,0,0}, {12174,12172,12175 ,4103,4101,4104 ,0,0,0}, + {12172,12174,12173 ,4101,4103,4102 ,0,0,0}, {12176,12177,12175 ,4105,4106,4104 ,0,0,0}, + {12174,12175,12177 ,4103,4104,4106 ,0,0,0}, {12176,12178,12179 ,4105,4107,4108 ,0,0,0}, + {12179,12177,12176 ,4108,4106,4105 ,0,0,0}, {12180,12181,12178 ,4109,4110,4107 ,0,0,0}, + {12178,12181,12179 ,4107,4110,4108 ,0,0,0}, {12182,12183,12180 ,4111,4112,4109 ,0,0,0}, + {12180,12178,12182 ,4109,4107,4111 ,0,0,0}, {12183,12184,12185 ,4112,4113,4114 ,0,0,0}, + {12184,12183,12182 ,4113,4112,4111 ,0,0,0}, {12184,12186,12185 ,4113,4114,4114 ,0,0,0}, + {12187,12162,12161 ,4115,2394,2394 ,0,0,0}, {12187,12188,12189 ,4115,4116,4117 ,0,0,0}, + {12189,12162,12187 ,4117,2394,4115 ,0,0,0}, {12190,12188,12191 ,4118,4116,4119 ,0,0,0}, + {12188,12190,12189 ,4116,4118,4117 ,0,0,0}, {12192,12193,12191 ,4120,4121,4119 ,0,0,0}, + {12190,12191,12193 ,4118,4119,4121 ,0,0,0}, {12192,12194,12195 ,4120,4122,4123 ,0,0,0}, + {12195,12193,12192 ,4123,4121,4120 ,0,0,0}, {12196,12194,12197 ,4124,4122,4125 ,0,0,0}, + {12194,12196,12195 ,4122,4124,4123 ,0,0,0}, {12198,12199,12197 ,4126,4127,4125 ,0,0,0}, + {12196,12197,12199 ,4124,4125,4127 ,0,0,0}, {12198,12200,12201 ,4126,4128,4129 ,0,0,0}, + {12201,12199,12198 ,4129,4127,4126 ,0,0,0}, {12202,12200,12203 ,4130,4128,4131 ,0,0,0}, + {12200,12202,12201 ,4128,4130,4129 ,0,0,0}, {12203,12204,12205 ,4131,4132,4133 ,0,0,0}, + {12202,12203,12205 ,4130,4131,4133 ,0,0,0}, {12204,12206,12207 ,4132,4134,4135 ,0,0,0}, + {12206,12204,12203 ,4134,4132,4131 ,0,0,0}, {12208,12207,12209 ,126,4135,4136 ,0,0,0}, + {12206,12209,12207 ,4134,4136,4135 ,0,0,0}, {12208,12209,12210 ,126,4136,126 ,0,0,0}, + {12211,12212,12213 ,4137,4138,4139 ,0,0,0}, {12211,12214,12215 ,4137,4140,4141 ,0,0,0}, + {12214,12216,12215 ,4140,4142,4141 ,0,0,0}, {12213,12214,12211 ,4139,4140,4137 ,0,0,0}, + {12217,12218,12219 ,4143,4144,4145 ,0,0,0}, {12216,12217,12219 ,4142,4143,4145 ,0,0,0}, + {12218,12220,12221 ,4144,4146,4147 ,0,0,0}, {12220,12218,12217 ,4146,4144,4143 ,0,0,0}, + {12221,12220,12222 ,4147,4146,4148 ,0,0,0}, {12223,12221,12222 ,4149,4147,4148 ,0,0,0}, + {12223,12224,12225 ,4149,4150,4151 ,0,0,0}, {12223,12222,12224 ,4149,4148,4150 ,0,0,0}, + {12219,12215,12216 ,4145,4141,4142 ,0,0,0}, {12226,12227,12228 ,4152,1711,1711 ,0,0,0}, + {12226,12228,12225 ,4152,1711,4151 ,0,0,0}, {12224,12226,12225 ,4150,4152,4151 ,0,0,0}, + {12213,12212,12229 ,4139,4138,4153 ,0,0,0}, {12230,12229,12231 ,4154,4153,4155 ,0,0,0}, + {12212,12231,12229 ,4138,4155,4153 ,0,0,0}, {12232,12233,12230 ,4156,4157,4154 ,0,0,0}, + {12230,12231,12232 ,4154,4155,4156 ,0,0,0}, {12233,12234,12235 ,4157,4158,4159 ,0,0,0}, + {12234,12233,12232 ,4158,4157,4156 ,0,0,0}, {12236,12235,12237 ,4160,4159,4161 ,0,0,0}, + {12234,12237,12235 ,4158,4161,4159 ,0,0,0}, {12238,12239,12236 ,4162,4163,4160 ,0,0,0}, + {12236,12237,12238 ,4160,4161,4162 ,0,0,0}, {12239,12240,12241 ,4163,4164,1790 ,0,0,0}, + {12240,12239,12238 ,4164,4163,4162 ,0,0,0}, {12240,12242,12241 ,4164,1790,1790 ,0,0,0}, + {12243,12244,12245 ,4165,4166,4167 ,0,0,0}, {12246,12247,12248 ,4168,4169,4170 ,0,0,0}, + {12247,12243,12245 ,4169,4165,4167 ,0,0,0}, {12249,12246,12248 ,4171,4168,4170 ,0,0,0}, + {12247,12246,12243 ,4169,4168,4165 ,0,0,0}, {12249,12248,12250 ,4171,4170,4172 ,0,0,0}, + {12250,12251,12252 ,4172,4173,4174 ,0,0,0}, {12253,12252,12251 ,4175,4174,4173 ,0,0,0}, + {12254,12255,12256 ,4176,4177,4178 ,0,0,0}, {12251,12257,12253 ,4173,4179,4175 ,0,0,0}, + {12256,12258,12259 ,4178,4180,4181 ,0,0,0}, {12258,12257,12259 ,4180,4179,4181 ,0,0,0}, + {12253,12257,12258 ,4175,4179,4180 ,0,0,0}, {12256,12259,12254 ,4178,4181,4176 ,0,0,0}, + {12255,12254,12260 ,4177,4176,4182 ,0,0,0}, {12255,12260,12261 ,4177,4182,4183 ,0,0,0}, + {12262,12261,12260 ,4184,4183,4182 ,0,0,0}, {12263,12264,12265 ,4185,1711,4186 ,0,0,0}, + {12265,12261,12262 ,4186,4183,4184 ,0,0,0}, {12263,12265,12262 ,4185,4186,4184 ,0,0,0}, + {12263,12266,12264 ,4185,1711,1711 ,0,0,0}, {12249,12250,12252 ,4171,4172,4174 ,0,0,0}, + {12245,12244,12267 ,4167,4166,4187 ,0,0,0}, {12268,12267,12269 ,4188,4187,4189 ,0,0,0}, + {12244,12269,12267 ,4166,4189,4187 ,0,0,0}, {12270,12271,12268 ,4190,4191,4188 ,0,0,0}, + {12268,12269,12270 ,4188,4189,4190 ,0,0,0}, {12271,12272,12273 ,4191,4192,4193 ,0,0,0}, + {12272,12271,12270 ,4192,4191,4190 ,0,0,0}, {12274,12273,12275 ,4194,4193,4195 ,0,0,0}, + {12272,12275,12273 ,4192,4195,4193 ,0,0,0}, {12276,12277,12274 ,4196,4197,4194 ,0,0,0}, + {12274,12275,12276 ,4194,4195,4196 ,0,0,0}, {12277,12278,12279 ,4197,4198,4199 ,0,0,0}, + {12278,12277,12276 ,4198,4197,4196 ,0,0,0}, {12280,12279,12281 ,4200,4199,4201 ,0,0,0}, + {12278,12281,12279 ,4198,4201,4199 ,0,0,0}, {12282,12283,12280 ,4202,4203,4200 ,0,0,0}, + {12280,12281,12282 ,4200,4201,4202 ,0,0,0}, {12283,12284,12285 ,4203,4204,1790 ,0,0,0}, + {12284,12283,12282 ,4204,4203,4202 ,0,0,0}, {12284,12286,12285 ,4204,1790,1790 ,0,0,0}, + {12287,12288,12289 ,4205,4206,4207 ,0,0,0}, {12287,12290,12291 ,4205,4208,4209 ,0,0,0}, + {12290,12292,12291 ,4208,4210,4209 ,0,0,0}, {12289,12290,12287 ,4207,4208,4205 ,0,0,0}, + {12293,12294,12295 ,4211,4212,4213 ,0,0,0}, {12292,12293,12295 ,4210,4211,4213 ,0,0,0}, + {12294,12296,12297 ,4212,4214,4215 ,0,0,0}, {12296,12294,12293 ,4214,4212,4211 ,0,0,0}, + {12297,12296,12298 ,4215,4214,4216 ,0,0,0}, {12299,12297,12298 ,4217,4215,4216 ,0,0,0}, + {12299,12300,12301 ,4217,4218,4219 ,0,0,0}, {12299,12298,12300 ,4217,4216,4218 ,0,0,0}, + {12295,12291,12292 ,4213,4209,4210 ,0,0,0}, {12302,12303,12304 ,4220,1359,1359 ,0,0,0}, + {12302,12304,12301 ,4220,1359,4219 ,0,0,0}, {12300,12302,12301 ,4218,4220,4219 ,0,0,0}, + {12289,12288,12305 ,4207,4206,4221 ,0,0,0}, {12306,12305,12307 ,4222,4221,4223 ,0,0,0}, + {12288,12307,12305 ,4206,4223,4221 ,0,0,0}, {12308,12309,12306 ,4224,4225,4222 ,0,0,0}, + {12306,12307,12308 ,4222,4223,4224 ,0,0,0}, {12309,12310,12311 ,4225,4226,4227 ,0,0,0}, + {12310,12309,12308 ,4226,4225,4224 ,0,0,0}, {12312,12311,12313 ,4228,4227,4229 ,0,0,0}, + {12310,12313,12311 ,4226,4229,4227 ,0,0,0}, {12314,12315,12312 ,4230,4231,4228 ,0,0,0}, + {12312,12313,12314 ,4228,4229,4230 ,0,0,0}, {12315,12316,12317 ,4231,4232,1435 ,0,0,0}, + {12316,12315,12314 ,4232,4231,4230 ,0,0,0}, {12316,12318,12317 ,4232,1435,1435 ,0,0,0}, + {12319,12320,12321 ,4233,4234,4235 ,0,0,0}, {12322,12323,12324 ,4236,4237,4238 ,0,0,0}, + {12323,12319,12321 ,4237,4233,4235 ,0,0,0}, {12325,12322,12324 ,4239,4236,4238 ,0,0,0}, + {12323,12322,12319 ,4237,4236,4233 ,0,0,0}, {12325,12324,12326 ,4239,4238,4240 ,0,0,0}, + {12326,12327,12328 ,4240,4241,4242 ,0,0,0}, {12329,12328,12327 ,4243,4242,4241 ,0,0,0}, + {12330,12331,12332 ,4244,4245,4246 ,0,0,0}, {12327,12333,12329 ,4241,4247,4243 ,0,0,0}, + {12332,12334,12335 ,4246,4248,4249 ,0,0,0}, {12334,12333,12335 ,4248,4247,4249 ,0,0,0}, + {12329,12333,12334 ,4243,4247,4248 ,0,0,0}, {12332,12335,12330 ,4246,4249,4244 ,0,0,0}, + {12331,12330,12336 ,4245,4244,4250 ,0,0,0}, {12331,12336,12337 ,4245,4250,4251 ,0,0,0}, + {12338,12337,12336 ,4252,4251,4250 ,0,0,0}, {12339,12340,12341 ,4253,1359,4254 ,0,0,0}, + {12341,12337,12338 ,4254,4251,4252 ,0,0,0}, {12339,12341,12338 ,4253,4254,4252 ,0,0,0}, + {12339,12342,12340 ,4253,1359,1359 ,0,0,0}, {12325,12326,12328 ,4239,4240,4242 ,0,0,0}, + {12321,12320,12343 ,4235,4234,4255 ,0,0,0}, {12344,12343,12345 ,4256,4255,4257 ,0,0,0}, + {12320,12345,12343 ,4234,4257,4255 ,0,0,0}, {12346,12347,12344 ,4258,4259,4256 ,0,0,0}, + {12344,12345,12346 ,4256,4257,4258 ,0,0,0}, {12347,12348,12349 ,4259,4260,4261 ,0,0,0}, + {12348,12347,12346 ,4260,4259,4258 ,0,0,0}, {12350,12349,12351 ,4262,4261,4263 ,0,0,0}, + {12348,12351,12349 ,4260,4263,4261 ,0,0,0}, {12352,12353,12350 ,4264,4265,4262 ,0,0,0}, + {12350,12351,12352 ,4262,4263,4264 ,0,0,0}, {12353,12354,12355 ,4265,4266,4267 ,0,0,0}, + {12354,12353,12352 ,4266,4265,4264 ,0,0,0}, {12356,12355,12357 ,4268,4267,4269 ,0,0,0}, + {12354,12357,12355 ,4266,4269,4267 ,0,0,0}, {12358,12359,12356 ,4270,4271,4268 ,0,0,0}, + {12356,12357,12358 ,4268,4269,4270 ,0,0,0}, {12359,12360,12361 ,4271,4272,1435 ,0,0,0}, + {12360,12359,12358 ,4272,4271,4270 ,0,0,0}, {12360,12362,12361 ,4272,1435,1435 ,0,0,0}, + {12363,12364,12365 ,4273,4274,4275 ,0,0,0}, {12363,12366,12367 ,4273,4276,4277 ,0,0,0}, + {12366,12368,12367 ,4276,4278,4277 ,0,0,0}, {12365,12366,12363 ,4275,4276,4273 ,0,0,0}, + {12369,12370,12371 ,4279,4280,4281 ,0,0,0}, {12368,12369,12371 ,4278,4279,4281 ,0,0,0}, + {12370,12372,12373 ,4280,4282,4283 ,0,0,0}, {12372,12370,12369 ,4282,4280,4279 ,0,0,0}, + {12373,12372,12374 ,4283,4282,4284 ,0,0,0}, {12375,12373,12374 ,4285,4283,4284 ,0,0,0}, + {12375,12376,12377 ,4285,4286,4287 ,0,0,0}, {12375,12374,12376 ,4285,4284,4286 ,0,0,0}, + {12371,12367,12368 ,4281,4277,4278 ,0,0,0}, {12378,12379,12380 ,4288,126,4289 ,0,0,0}, + {12378,12380,12377 ,4288,4289,4287 ,0,0,0}, {12376,12378,12377 ,4286,4288,4287 ,0,0,0}, + {12365,12364,12381 ,4275,4274,4290 ,0,0,0}, {12382,12381,12383 ,4291,4290,4292 ,0,0,0}, + {12364,12383,12381 ,4274,4292,4290 ,0,0,0}, {12384,12385,12382 ,4293,4294,4291 ,0,0,0}, + {12382,12383,12384 ,4291,4292,4293 ,0,0,0}, {12385,12386,12387 ,4294,4295,4296 ,0,0,0}, + {12386,12385,12384 ,4295,4294,4293 ,0,0,0}, {12388,12387,12389 ,4297,4296,4298 ,0,0,0}, + {12386,12389,12387 ,4295,4298,4296 ,0,0,0}, {12390,12391,12388 ,4299,4300,4297 ,0,0,0}, + {12388,12389,12390 ,4297,4298,4299 ,0,0,0}, {12391,12392,12393 ,4300,4301,4302 ,0,0,0}, + {12392,12391,12390 ,4301,4300,4299 ,0,0,0}, {12392,12394,12393 ,4301,4303,4302 ,0,0,0}, + {12395,12396,12397 ,4304,4305,4306 ,0,0,0}, {12398,12399,12400 ,4307,4308,4309 ,0,0,0}, + {12399,12395,12397 ,4308,4304,4306 ,0,0,0}, {12401,12398,12400 ,4310,4307,4309 ,0,0,0}, + {12399,12398,12395 ,4308,4307,4304 ,0,0,0}, {12401,12400,12402 ,4310,4309,4311 ,0,0,0}, + {12402,12403,12404 ,4311,4312,4313 ,0,0,0}, {12405,12404,12403 ,4314,4313,4312 ,0,0,0}, + {12406,12407,12408 ,4315,4316,4317 ,0,0,0}, {12403,12409,12405 ,4312,4318,4314 ,0,0,0}, + {12408,12410,12411 ,4317,4319,4320 ,0,0,0}, {12410,12409,12411 ,4319,4318,4320 ,0,0,0}, + {12405,12409,12410 ,4314,4318,4319 ,0,0,0}, {12408,12411,12406 ,4317,4320,4315 ,0,0,0}, + {12407,12406,12412 ,4316,4315,4321 ,0,0,0}, {12407,12412,12413 ,4316,4321,4322 ,0,0,0}, + {12414,12413,12412 ,4323,4322,4321 ,0,0,0}, {12415,12416,12417 ,4324,126,4325 ,0,0,0}, + {12417,12413,12414 ,4325,4322,4323 ,0,0,0}, {12415,12417,12414 ,4324,4325,4323 ,0,0,0}, + {12415,12418,12416 ,4324,4326,126 ,0,0,0}, {12401,12402,12404 ,4310,4311,4313 ,0,0,0}, + {12397,12396,12419 ,4306,4305,4327 ,0,0,0}, {12420,12419,12421 ,4328,4327,4329 ,0,0,0}, + {12396,12421,12419 ,4305,4329,4327 ,0,0,0}, {12422,12423,12420 ,4330,4331,4328 ,0,0,0}, + {12420,12421,12422 ,4328,4329,4330 ,0,0,0}, {12423,12424,12425 ,4331,4332,4333 ,0,0,0}, + {12424,12423,12422 ,4332,4331,4330 ,0,0,0}, {12426,12425,12427 ,4334,4333,4335 ,0,0,0}, + {12424,12427,12425 ,4332,4335,4333 ,0,0,0}, {12428,12429,12426 ,4336,4337,4334 ,0,0,0}, + {12426,12427,12428 ,4334,4335,4336 ,0,0,0}, {12429,12430,12431 ,4337,4338,4339 ,0,0,0}, + {12430,12429,12428 ,4338,4337,4336 ,0,0,0}, {12432,12431,12433 ,4340,4339,4341 ,0,0,0}, + {12430,12433,12431 ,4338,4341,4339 ,0,0,0}, {12434,12435,12432 ,4342,4343,4340 ,0,0,0}, + {12432,12433,12434 ,4340,4341,4342 ,0,0,0}, {12435,12436,12437 ,4343,4344,4345 ,0,0,0}, + {12436,12435,12434 ,4344,4343,4342 ,0,0,0}, {12436,12438,12437 ,4344,4346,4345 ,0,0,0}, + {12439,12440,12441 ,4347,4348,4349 ,0,0,0}, {12439,12442,12443 ,4347,4350,4351 ,0,0,0}, + {12442,12444,12443 ,4350,4352,4351 ,0,0,0}, {12441,12442,12439 ,4349,4350,4347 ,0,0,0}, + {12445,12446,12447 ,4353,4354,4355 ,0,0,0}, {12444,12445,12447 ,4352,4353,4355 ,0,0,0}, + {12446,12448,12449 ,4354,4356,4357 ,0,0,0}, {12448,12446,12445 ,4356,4354,4353 ,0,0,0}, + {12449,12448,12450 ,4357,4356,4358 ,0,0,0}, {12451,12449,12450 ,4359,4357,4358 ,0,0,0}, + {12451,12452,12453 ,4359,4360,4361 ,0,0,0}, {12451,12450,12452 ,4359,4358,4360 ,0,0,0}, + {12447,12443,12444 ,4355,4351,4352 ,0,0,0}, {12454,12455,12456 ,4362,1790,1790 ,0,0,0}, + {12454,12456,12453 ,4362,1790,4361 ,0,0,0}, {12452,12454,12453 ,4360,4362,4361 ,0,0,0}, + {12441,12440,12457 ,4349,4348,4363 ,0,0,0}, {12458,12457,12459 ,4364,4363,4365 ,0,0,0}, + {12440,12459,12457 ,4348,4365,4363 ,0,0,0}, {12460,12461,12458 ,4366,4367,4364 ,0,0,0}, + {12458,12459,12460 ,4364,4365,4366 ,0,0,0}, {12461,12462,12463 ,4367,4368,4369 ,0,0,0}, + {12462,12461,12460 ,4368,4367,4366 ,0,0,0}, {12464,12463,12465 ,4370,4369,4371 ,0,0,0}, + {12462,12465,12463 ,4368,4371,4369 ,0,0,0}, {12466,12467,12464 ,4372,4373,4370 ,0,0,0}, + {12464,12465,12466 ,4370,4371,4372 ,0,0,0}, {12467,12468,12469 ,4373,4374,1711 ,0,0,0}, + {12468,12467,12466 ,4374,4373,4372 ,0,0,0}, {12468,12470,12469 ,4374,1711,1711 ,0,0,0}, + {12471,12472,12473 ,4375,4376,4377 ,0,0,0}, {12474,12475,12476 ,4378,4379,4380 ,0,0,0}, + {12475,12471,12473 ,4379,4375,4377 ,0,0,0}, {12477,12474,12476 ,4381,4378,4380 ,0,0,0}, + {12475,12474,12471 ,4379,4378,4375 ,0,0,0}, {12477,12476,12478 ,4381,4380,4382 ,0,0,0}, + {12478,12479,12480 ,4382,4383,4384 ,0,0,0}, {12481,12480,12479 ,4385,4384,4383 ,0,0,0}, + {12482,12483,12484 ,4386,4387,4388 ,0,0,0}, {12479,12485,12481 ,4383,4389,4385 ,0,0,0}, + {12484,12486,12487 ,4388,4390,4391 ,0,0,0}, {12486,12485,12487 ,4390,4389,4391 ,0,0,0}, + {12481,12485,12486 ,4385,4389,4390 ,0,0,0}, {12484,12487,12482 ,4388,4391,4386 ,0,0,0}, + {12483,12482,12488 ,4387,4386,4392 ,0,0,0}, {12483,12488,12489 ,4387,4392,4393 ,0,0,0}, + {12490,12489,12488 ,4394,4393,4392 ,0,0,0}, {12491,12492,12493 ,4395,1790,4396 ,0,0,0}, + {12493,12489,12490 ,4396,4393,4394 ,0,0,0}, {12491,12493,12490 ,4395,4396,4394 ,0,0,0}, + {12491,12494,12492 ,4395,1790,1790 ,0,0,0}, {12477,12478,12480 ,4381,4382,4384 ,0,0,0}, + {12473,12472,12495 ,4377,4376,4397 ,0,0,0}, {12496,12495,12497 ,4398,4397,4399 ,0,0,0}, + {12472,12497,12495 ,4376,4399,4397 ,0,0,0}, {12498,12499,12496 ,4400,4401,4398 ,0,0,0}, + {12496,12497,12498 ,4398,4399,4400 ,0,0,0}, {12499,12500,12501 ,4401,4402,4403 ,0,0,0}, + {12500,12499,12498 ,4402,4401,4400 ,0,0,0}, {12502,12501,12503 ,4404,4403,4405 ,0,0,0}, + {12500,12503,12501 ,4402,4405,4403 ,0,0,0}, {12504,12505,12502 ,4406,4407,4404 ,0,0,0}, + {12502,12503,12504 ,4404,4405,4406 ,0,0,0}, {12505,12506,12507 ,4407,4408,4409 ,0,0,0}, + {12506,12505,12504 ,4408,4407,4406 ,0,0,0}, {12508,12507,12509 ,4410,4409,4411 ,0,0,0}, + {12506,12509,12507 ,4408,4411,4409 ,0,0,0}, {12510,12511,12508 ,4412,4413,4410 ,0,0,0}, + {12508,12509,12510 ,4410,4411,4412 ,0,0,0}, {12511,12512,12513 ,4413,4414,1711 ,0,0,0}, + {12512,12511,12510 ,4414,4413,4412 ,0,0,0}, {12512,12514,12513 ,4414,1711,1711 ,0,0,0}, + {12515,12516,12517 ,4415,4416,4417 ,0,0,0}, {12515,12518,12519 ,4415,4418,4419 ,0,0,0}, + {12518,12520,12519 ,4418,4420,4419 ,0,0,0}, {12517,12518,12515 ,4417,4418,4415 ,0,0,0}, + {12521,12522,12523 ,4421,4422,4423 ,0,0,0}, {12520,12521,12523 ,4420,4421,4423 ,0,0,0}, + {12522,12524,12525 ,4422,4424,4425 ,0,0,0}, {12524,12522,12521 ,4424,4422,4421 ,0,0,0}, + {12525,12524,12526 ,4425,4424,4426 ,0,0,0}, {12527,12525,12526 ,4427,4425,4426 ,0,0,0}, + {12527,12528,12529 ,4427,4428,4429 ,0,0,0}, {12527,12526,12528 ,4427,4426,4428 ,0,0,0}, + {12523,12519,12520 ,4423,4419,4420 ,0,0,0}, {12530,12531,12532 ,4430,1435,1435 ,0,0,0}, + {12530,12532,12529 ,4430,1435,4429 ,0,0,0}, {12528,12530,12529 ,4428,4430,4429 ,0,0,0}, + {12517,12516,12533 ,4417,4416,4431 ,0,0,0}, {12534,12533,12535 ,4432,4431,4433 ,0,0,0}, + {12516,12535,12533 ,4416,4433,4431 ,0,0,0}, {12536,12537,12534 ,4434,4435,4432 ,0,0,0}, + {12534,12535,12536 ,4432,4433,4434 ,0,0,0}, {12537,12538,12539 ,4435,4436,4437 ,0,0,0}, + {12538,12537,12536 ,4436,4435,4434 ,0,0,0}, {12540,12539,12541 ,4438,4437,4439 ,0,0,0}, + {12538,12541,12539 ,4436,4439,4437 ,0,0,0}, {12542,12543,12540 ,4440,4441,4438 ,0,0,0}, + {12540,12541,12542 ,4438,4439,4440 ,0,0,0}, {12543,12544,12545 ,4441,4442,1359 ,0,0,0}, + {12544,12543,12542 ,4442,4441,4440 ,0,0,0}, {12544,12546,12545 ,4442,1359,1359 ,0,0,0}, + {12547,12548,12549 ,4443,4444,4445 ,0,0,0}, {12550,12551,12552 ,4446,4447,4448 ,0,0,0}, + {12551,12547,12549 ,4447,4443,4445 ,0,0,0}, {12553,12550,12552 ,4449,4446,4448 ,0,0,0}, + {12551,12550,12547 ,4447,4446,4443 ,0,0,0}, {12553,12552,12554 ,4449,4448,4450 ,0,0,0}, + {12554,12555,12556 ,4450,4451,4452 ,0,0,0}, {12557,12556,12555 ,4453,4452,4451 ,0,0,0}, + {12558,12559,12560 ,4454,4455,4456 ,0,0,0}, {12555,12561,12557 ,4451,4457,4453 ,0,0,0}, + {12560,12562,12563 ,4456,4458,4459 ,0,0,0}, {12562,12561,12563 ,4458,4457,4459 ,0,0,0}, + {12557,12561,12562 ,4453,4457,4458 ,0,0,0}, {12560,12563,12558 ,4456,4459,4454 ,0,0,0}, + {12559,12558,12564 ,4455,4454,4460 ,0,0,0}, {12559,12564,12565 ,4455,4460,4461 ,0,0,0}, + {12566,12565,12564 ,4462,4461,4460 ,0,0,0}, {12567,12568,12569 ,4463,1435,4464 ,0,0,0}, + {12569,12565,12566 ,4464,4461,4462 ,0,0,0}, {12567,12569,12566 ,4463,4464,4462 ,0,0,0}, + {12567,12570,12568 ,4463,1435,1435 ,0,0,0}, {12553,12554,12556 ,4449,4450,4452 ,0,0,0}, + {12549,12548,12571 ,4445,4444,4465 ,0,0,0}, {12572,12571,12573 ,4466,4465,4467 ,0,0,0}, + {12548,12573,12571 ,4444,4467,4465 ,0,0,0}, {12574,12575,12572 ,4468,4469,4466 ,0,0,0}, + {12572,12573,12574 ,4466,4467,4468 ,0,0,0}, {12575,12576,12577 ,4469,4470,4471 ,0,0,0}, + {12576,12575,12574 ,4470,4469,4468 ,0,0,0}, {12578,12577,12579 ,4472,4471,4473 ,0,0,0}, + {12576,12579,12577 ,4470,4473,4471 ,0,0,0}, {12580,12581,12578 ,4474,4475,4472 ,0,0,0}, + {12578,12579,12580 ,4472,4473,4474 ,0,0,0}, {12581,12582,12583 ,4475,4476,4477 ,0,0,0}, + {12582,12581,12580 ,4476,4475,4474 ,0,0,0}, {12584,12583,12585 ,4478,4477,4479 ,0,0,0}, + {12582,12585,12583 ,4476,4479,4477 ,0,0,0}, {12586,12587,12584 ,4480,4481,4478 ,0,0,0}, + {12584,12585,12586 ,4478,4479,4480 ,0,0,0}, {12587,12588,12589 ,4481,4482,1359 ,0,0,0}, + {12588,12587,12586 ,4482,4481,4480 ,0,0,0}, {12588,12590,12589 ,4482,1359,1359 ,0,0,0}, + {12591,12592,12593 ,4483,4484,4485 ,0,0,0}, {12591,12594,12595 ,4483,4486,4487 ,0,0,0}, + {12594,12596,12595 ,4486,4488,4487 ,0,0,0}, {12593,12594,12591 ,4485,4486,4483 ,0,0,0}, + {12597,12598,12599 ,4489,4490,4491 ,0,0,0}, {12596,12597,12599 ,4488,4489,4491 ,0,0,0}, + {12598,12600,12601 ,4490,4492,4493 ,0,0,0}, {12600,12598,12597 ,4492,4490,4489 ,0,0,0}, + {12601,12600,12602 ,4493,4492,4494 ,0,0,0}, {12603,12601,12602 ,4495,4493,4494 ,0,0,0}, + {12603,12604,12605 ,4495,4496,4497 ,0,0,0}, {12603,12602,12604 ,4495,4494,4496 ,0,0,0}, + {12599,12595,12596 ,4491,4487,4488 ,0,0,0}, {12606,12607,12608 ,4498,4499,82 ,0,0,0}, + {12606,12608,12605 ,4498,82,4497 ,0,0,0}, {12604,12606,12605 ,4496,4498,4497 ,0,0,0}, + {12593,12592,12609 ,4485,4484,4500 ,0,0,0}, {12610,12609,12611 ,4501,4500,4502 ,0,0,0}, + {12592,12611,12609 ,4484,4502,4500 ,0,0,0}, {12612,12613,12610 ,4503,4504,4501 ,0,0,0}, + {12610,12611,12612 ,4501,4502,4503 ,0,0,0}, {12613,12614,12615 ,4504,4505,4506 ,0,0,0}, + {12614,12613,12612 ,4505,4504,4503 ,0,0,0}, {12616,12615,12617 ,4507,4506,4508 ,0,0,0}, + {12614,12617,12615 ,4505,4508,4506 ,0,0,0}, {12618,12619,12616 ,4509,4510,4507 ,0,0,0}, + {12616,12617,12618 ,4507,4508,4509 ,0,0,0}, {12619,12620,12621 ,4510,4511,4512 ,0,0,0}, + {12620,12619,12618 ,4511,4510,4509 ,0,0,0}, {12620,12622,12621 ,4511,4513,4512 ,0,0,0}, + {12623,12624,12625 ,4514,4515,4516 ,0,0,0}, {12626,12627,12628 ,4517,4518,4519 ,0,0,0}, + {12627,12623,12625 ,4518,4514,4516 ,0,0,0}, {12629,12626,12628 ,4520,4517,4519 ,0,0,0}, + {12627,12626,12623 ,4518,4517,4514 ,0,0,0}, {12629,12628,12630 ,4520,4519,4521 ,0,0,0}, + {12630,12631,12632 ,4521,4522,4523 ,0,0,0}, {12633,12632,12631 ,4524,4523,4522 ,0,0,0}, + {12634,12635,12636 ,4525,4526,4527 ,0,0,0}, {12631,12637,12633 ,4522,4528,4524 ,0,0,0}, + {12636,12638,12639 ,4527,4529,4530 ,0,0,0}, {12638,12637,12639 ,4529,4528,4530 ,0,0,0}, + {12633,12637,12638 ,4524,4528,4529 ,0,0,0}, {12636,12639,12634 ,4527,4530,4525 ,0,0,0}, + {12635,12634,12640 ,4526,4525,4531 ,0,0,0}, {12635,12640,12641 ,4526,4531,4532 ,0,0,0}, + {12642,12641,12640 ,4533,4532,4531 ,0,0,0}, {12643,12644,12645 ,4534,4535,4536 ,0,0,0}, + {12645,12641,12642 ,4536,4532,4533 ,0,0,0}, {12643,12645,12642 ,4534,4536,4533 ,0,0,0}, + {12643,12646,12644 ,4534,4537,4535 ,0,0,0}, {12629,12630,12632 ,4520,4521,4523 ,0,0,0}, + {12625,12624,12647 ,4516,4515,4538 ,0,0,0}, {12648,12647,12649 ,4539,4538,4540 ,0,0,0}, + {12624,12649,12647 ,4515,4540,4538 ,0,0,0}, {12650,12651,12648 ,4541,4542,4539 ,0,0,0}, + {12648,12649,12650 ,4539,4540,4541 ,0,0,0}, {12651,12652,12653 ,4542,4543,4544 ,0,0,0}, + {12652,12651,12650 ,4543,4542,4541 ,0,0,0}, {12654,12653,12655 ,4545,4544,4546 ,0,0,0}, + {12652,12655,12653 ,4543,4546,4544 ,0,0,0}, {12656,12657,12654 ,4547,4548,4545 ,0,0,0}, + {12654,12655,12656 ,4545,4546,4547 ,0,0,0}, {12657,12658,12659 ,4548,4549,4550 ,0,0,0}, + {12658,12657,12656 ,4549,4548,4547 ,0,0,0}, {12660,12659,12661 ,4551,4550,4552 ,0,0,0}, + {12658,12661,12659 ,4549,4552,4550 ,0,0,0}, {12662,12663,12660 ,4553,4554,4551 ,0,0,0}, + {12660,12661,12662 ,4551,4552,4553 ,0,0,0}, {12663,12664,12665 ,4554,4555,4556 ,0,0,0}, + {12664,12663,12662 ,4555,4554,4553 ,0,0,0}, {12664,12666,12665 ,4555,126,4556 ,0,0,0}, + {12667,12668,12669 ,4557,4558,4559 ,0,0,0}, {12670,12671,12669 ,4560,4561,4559 ,0,0,0}, + {12667,12669,12671 ,4557,4559,4561 ,0,0,0}, {12672,12670,12673 ,4562,4560,4563 ,0,0,0}, + {12672,12671,12670 ,4562,4561,4560 ,0,0,0}, {12674,12673,12675 ,4564,4563,4565 ,0,0,0}, + {12670,12675,12673 ,4560,4565,4563 ,0,0,0}, {12676,12677,12674 ,4081,4566,4564 ,0,0,0}, + {12674,12675,12676 ,4564,4565,4081 ,0,0,0}, {12677,12678,12679 ,4566,4567,4568 ,0,0,0}, + {12678,12677,12676 ,4567,4566,4081 ,0,0,0}, {12680,12679,12681 ,4569,4568,4570 ,0,0,0}, + {12678,12681,12679 ,4567,4570,4568 ,0,0,0}, {12682,12683,12680 ,4571,4572,4569 ,0,0,0}, + {12680,12681,12682 ,4569,4570,4571 ,0,0,0}, {12684,12685,12683 ,4573,763,4572 ,0,0,0}, + {12684,12683,12682 ,4573,4572,4571 ,0,0,0}, {12685,12686,12683 ,763,763,4572 ,0,0,0}, + {12687,12668,12667 ,4574,4558,4557 ,0,0,0}, {12687,12688,12689 ,4574,4575,4576 ,0,0,0}, + {12689,12668,12687 ,4576,4558,4574 ,0,0,0}, {12690,12691,12688 ,4577,4578,4575 ,0,0,0}, + {12688,12691,12689 ,4575,4578,4576 ,0,0,0}, {12692,12693,12690 ,4579,4580,4577 ,0,0,0}, + {12690,12688,12692 ,4577,4575,4579 ,0,0,0}, {12693,12694,12695 ,4580,4065,4581 ,0,0,0}, + {12694,12693,12692 ,4065,4580,4579 ,0,0,0}, {12696,12695,12697 ,4582,4581,4583 ,0,0,0}, + {12694,12697,12695 ,4065,4583,4581 ,0,0,0}, {12698,12699,12696 ,4584,4585,4582 ,0,0,0}, + {12696,12697,12698 ,4582,4583,4584 ,0,0,0}, {12699,12700,12701 ,4585,4586,4587 ,0,0,0}, + {12700,12699,12698 ,4586,4585,4584 ,0,0,0}, {12701,12702,12703 ,4587,4588,54 ,0,0,0}, + {12700,12702,12701 ,4586,4588,4587 ,0,0,0}, {12701,12703,12704 ,4587,54,4589 ,0,0,0}, + {12705,12706,12707 ,4590,4591,4557 ,0,0,0}, {12708,12706,12709 ,4592,4591,4593 ,0,0,0}, + {12706,12708,12707 ,4591,4592,4557 ,0,0,0}, {12710,12711,12709 ,4594,4595,4593 ,0,0,0}, + {12708,12709,12711 ,4592,4593,4595 ,0,0,0}, {12710,12712,12713 ,4594,4596,4597 ,0,0,0}, + {12713,12711,12710 ,4597,4595,4594 ,0,0,0}, {12714,12712,12715 ,4598,4596,4599 ,0,0,0}, + {12712,12714,12713 ,4596,4598,4597 ,0,0,0}, {12716,12717,12715 ,4600,4601,4599 ,0,0,0}, + {12714,12715,12717 ,4598,4599,4601 ,0,0,0}, {12716,12718,12719 ,4600,4602,4603 ,0,0,0}, + {12719,12717,12716 ,4603,4601,4600 ,0,0,0}, {12720,12718,12721 ,4604,4602,4605 ,0,0,0}, + {12718,12720,12719 ,4602,4604,4603 ,0,0,0}, {12722,12723,12721 ,4606,4607,4605 ,0,0,0}, + {12720,12721,12723 ,4604,4605,4607 ,0,0,0}, {12722,12724,12725 ,4606,4608,4609 ,0,0,0}, + {12725,12723,12722 ,4609,4607,4606 ,0,0,0}, {12726,12724,12727 ,4610,4608,4611 ,0,0,0}, + {12724,12726,12725 ,4608,4610,4609 ,0,0,0}, {12728,12729,12727 ,4612,4613,4611 ,0,0,0}, + {12726,12727,12729 ,4610,4611,4613 ,0,0,0}, {12728,12730,12731 ,4612,4614,4615 ,0,0,0}, + {12731,12729,12728 ,4615,4613,4612 ,0,0,0}, {12732,12730,12733 ,4616,4614,4617 ,0,0,0}, + {12730,12732,12731 ,4614,4616,4615 ,0,0,0}, {12734,12735,12733 ,4618,4619,4617 ,0,0,0}, + {12732,12733,12735 ,4616,4617,4619 ,0,0,0}, {12734,12736,12737 ,4618,4620,4621 ,0,0,0}, + {12737,12735,12734 ,4621,4619,4618 ,0,0,0}, {12736,12738,12737 ,4620,4620,4621 ,0,0,0}, + {12739,12705,12707 ,4622,4590,4557 ,0,0,0}, {12740,12741,12739 ,4623,4624,4622 ,0,0,0}, + {12705,12739,12741 ,4590,4622,4624 ,0,0,0}, {12740,12742,12743 ,4623,4625,4626 ,0,0,0}, + {12743,12741,12740 ,4626,4624,4623 ,0,0,0}, {12744,12742,12745 ,4627,4625,4628 ,0,0,0}, + {12742,12744,12743 ,4625,4627,4626 ,0,0,0}, {12746,12747,12745 ,4629,4630,4628 ,0,0,0}, + {12744,12745,12747 ,4627,4628,4630 ,0,0,0}, {12746,12748,12749 ,4629,4631,4632 ,0,0,0}, + {12749,12747,12746 ,4632,4630,4629 ,0,0,0}, {12750,12748,12751 ,4633,4631,4634 ,0,0,0}, + {12748,12750,12749 ,4631,4633,4632 ,0,0,0}, {12752,12753,12751 ,4635,4636,4634 ,0,0,0}, + {12750,12751,12753 ,4633,4634,4636 ,0,0,0}, {12752,12754,12755 ,4635,4637,4638 ,0,0,0}, + {12755,12753,12752 ,4638,4636,4635 ,0,0,0}, {12756,12754,12757 ,4639,4637,4640 ,0,0,0}, + {12754,12756,12755 ,4637,4639,4638 ,0,0,0}, {12758,12759,12757 ,4641,4642,4640 ,0,0,0}, + {12756,12757,12759 ,4639,4640,4642 ,0,0,0}, {12758,12760,12761 ,4641,4643,4644 ,0,0,0}, + {12761,12759,12758 ,4644,4642,4641 ,0,0,0}, {12762,12760,12763 ,4645,4643,4646 ,0,0,0}, + {12760,12762,12761 ,4643,4645,4644 ,0,0,0}, {12764,12765,12763 ,4647,4648,4646 ,0,0,0}, + {12762,12763,12765 ,4645,4646,4648 ,0,0,0}, {12764,12766,12767 ,4647,4649,4650 ,0,0,0}, + {12767,12765,12764 ,4650,4648,4647 ,0,0,0}, {12768,12766,12769 ,4651,4649,82 ,0,0,0}, + {12766,12768,12767 ,4649,4651,4650 ,0,0,0}, {12768,12769,12770 ,4651,82,4652 ,0,0,0}, + {12771,12772,12773 ,4653,4654,4655 ,0,0,0}, {12774,12775,12776 ,4656,4657,4658 ,0,0,0}, + {12773,12776,12775 ,4655,4658,4657 ,0,0,0}, {12777,12778,12779 ,4659,4660,4661 ,0,0,0}, + {12780,12781,12774 ,4662,4663,4656 ,0,0,0}, {12777,12781,12780 ,4659,4663,4662 ,0,0,0}, + {12780,12778,12777 ,4662,4660,4659 ,0,0,0}, {12781,12775,12774 ,4663,4657,4656 ,0,0,0}, + {12782,12783,12784 ,4664,4665,4666 ,0,0,0}, {12783,12785,12784 ,4665,4667,4666 ,0,0,0}, + {12786,12787,12788 ,4668,4669,4670 ,0,0,0}, {12786,12788,12785 ,4668,4670,4667 ,0,0,0}, + {12783,12786,12785 ,4665,4668,4667 ,0,0,0}, {12778,12782,12779 ,4660,4664,4661 ,0,0,0}, + {12782,12784,12779 ,4664,4666,4661 ,0,0,0}, {12789,12790,12791 ,4671,4672,4673 ,0,0,0}, + {12792,12793,12794 ,4674,4675,4676 ,0,0,0}, {12791,12790,12792 ,4673,4672,4674 ,0,0,0}, + {12795,12796,12797 ,4677,4678,4679 ,0,0,0}, {12791,12792,12794 ,4673,4674,4676 ,0,0,0}, + {12797,12796,12793 ,4679,4678,4675 ,0,0,0}, {12796,12794,12793 ,4678,4676,4675 ,0,0,0}, + {12787,12790,12789 ,4669,4672,4671 ,0,0,0}, {12798,12795,12797 ,4677,4677,4679 ,0,0,0}, + {12788,12787,12789 ,4670,4669,4671 ,0,0,0}, {12772,12776,12773 ,4654,4658,4655 ,0,0,0}, + {12799,12772,12771 ,4680,4654,4653 ,0,0,0}, {12799,12800,12801 ,4680,4681,4682 ,0,0,0}, + {12800,12799,12771 ,4681,4680,4653 ,0,0,0}, {12802,12801,12803 ,4683,4682,4684 ,0,0,0}, + {12800,12803,12801 ,4681,4684,4682 ,0,0,0}, {12804,12805,12802 ,4685,4686,4683 ,0,0,0}, + {12802,12803,12804 ,4683,4684,4685 ,0,0,0}, {12805,12806,12807 ,4686,4687,4688 ,0,0,0}, + {12806,12805,12804 ,4687,4686,4685 ,0,0,0}, {12808,12807,12809 ,4689,4688,4690 ,0,0,0}, + {12806,12809,12807 ,4687,4690,4688 ,0,0,0}, {12810,12811,12808 ,4691,4692,4689 ,0,0,0}, + {12808,12809,12810 ,4689,4690,4691 ,0,0,0}, {12811,12812,12813 ,4692,4693,4694 ,0,0,0}, + {12812,12811,12810 ,4693,4692,4691 ,0,0,0}, {12814,12813,12815 ,4695,4694,4696 ,0,0,0}, + {12812,12815,12813 ,4693,4696,4694 ,0,0,0}, {12816,12817,12814 ,4697,4698,4695 ,0,0,0}, + {12814,12815,12816 ,4695,4696,4697 ,0,0,0}, {12817,12818,12819 ,4698,4699,4700 ,0,0,0}, + {12818,12817,12816 ,4699,4698,4697 ,0,0,0}, {12818,12820,12819 ,4699,4701,4700 ,0,0,0}, + {12821,12822,12823 ,4702,4703,4704 ,0,0,0}, {12824,12825,12826 ,4705,4706,4707 ,0,0,0}, + {12822,12826,12825 ,4703,4707,4706 ,0,0,0}, {12827,12828,12829 ,4708,4709,4710 ,0,0,0}, + {12830,12824,12831 ,4711,4705,4712 ,0,0,0}, {12827,12830,12831 ,4708,4711,4712 ,0,0,0}, + {12830,12827,12829 ,4711,4708,4710 ,0,0,0}, {12831,12824,12826 ,4712,4705,4707 ,0,0,0}, + {12832,12833,12834 ,4713,4714,4715 ,0,0,0}, {12834,12833,12835 ,4715,4714,4716 ,0,0,0}, + {12836,12837,12838 ,4717,4718,4719 ,0,0,0}, {12836,12835,12837 ,4717,4716,4718 ,0,0,0}, + {12834,12835,12836 ,4715,4716,4717 ,0,0,0}, {12829,12828,12832 ,4710,4709,4713 ,0,0,0}, + {12832,12828,12833 ,4713,4709,4714 ,0,0,0}, {12839,12840,12841 ,4720,4721,4722 ,0,0,0}, + {12842,12843,12844 ,4723,4724,4725 ,0,0,0}, {12840,12842,12841 ,4721,4723,4722 ,0,0,0}, + {12845,12846,12847 ,4726,4727,4728 ,0,0,0}, {12840,12843,12842 ,4721,4724,4723 ,0,0,0}, + {12846,12844,12847 ,4727,4725,4728 ,0,0,0}, {12847,12844,12843 ,4728,4725,4724 ,0,0,0}, + {12838,12839,12841 ,4719,4720,4722 ,0,0,0}, {12848,12846,12845 ,4726,4727,4726 ,0,0,0}, + {12837,12839,12838 ,4718,4720,4719 ,0,0,0}, {12823,12822,12825 ,4704,4703,4706 ,0,0,0}, + {12849,12821,12823 ,4729,4702,4704 ,0,0,0}, {12849,12850,12851 ,4729,4730,4731 ,0,0,0}, + {12851,12821,12849 ,4731,4702,4729 ,0,0,0}, {12852,12853,12850 ,4732,4733,4730 ,0,0,0}, + {12851,12850,12853 ,4731,4730,4733 ,0,0,0}, {12854,12852,12855 ,4734,4732,4735 ,0,0,0}, + {12852,12854,12853 ,4732,4734,4733 ,0,0,0}, {12855,12856,12857 ,4735,4736,4737 ,0,0,0}, + {12857,12854,12855 ,4737,4734,4735 ,0,0,0}, {12858,12859,12856 ,4738,4739,4736 ,0,0,0}, + {12857,12856,12859 ,4737,4736,4739 ,0,0,0}, {12860,12858,12861 ,4740,4738,4741 ,0,0,0}, + {12858,12860,12859 ,4738,4740,4739 ,0,0,0}, {12861,12862,12863 ,4741,4742,4743 ,0,0,0}, + {12863,12860,12861 ,4743,4740,4741 ,0,0,0}, {12864,12865,12862 ,4744,4745,4742 ,0,0,0}, + {12863,12862,12865 ,4743,4742,4745 ,0,0,0}, {12866,12864,12867 ,4746,4744,4747 ,0,0,0}, + {12864,12866,12865 ,4744,4746,4745 ,0,0,0}, {12867,12868,12869 ,4747,4748,4749 ,0,0,0}, + {12869,12866,12867 ,4749,4746,4747 ,0,0,0}, {12869,12868,12870 ,4749,4748,4750 ,0,0,0}, + {12871,12872,12873 ,4751,4752,4753 ,0,0,0}, {12874,12875,12876 ,4754,4755,4756 ,0,0,0}, + {12872,12876,12875 ,4752,4756,4755 ,0,0,0}, {12877,12878,12879 ,4757,4758,4759 ,0,0,0}, + {12880,12874,12881 ,4760,4754,4761 ,0,0,0}, {12880,12881,12877 ,4760,4761,4757 ,0,0,0}, + {12877,12879,12880 ,4757,4759,4760 ,0,0,0}, {12874,12876,12881 ,4754,4756,4761 ,0,0,0}, + {12882,12883,12884 ,4762,4763,4764 ,0,0,0}, {12885,12883,12882 ,4765,4763,4762 ,0,0,0}, + {12886,12887,12888 ,4766,4767,4768 ,0,0,0}, {12886,12888,12885 ,4766,4768,4765 ,0,0,0}, + {12885,12888,12883 ,4765,4768,4763 ,0,0,0}, {12878,12884,12879 ,4758,4764,4759 ,0,0,0}, + {12882,12884,12878 ,4762,4764,4758 ,0,0,0}, {12889,12890,12891 ,4769,4770,4771 ,0,0,0}, + {12892,12893,12894 ,4772,4773,4774 ,0,0,0}, {12891,12890,12894 ,4771,4770,4774 ,0,0,0}, + {12895,12896,12897 ,4775,4776,4777 ,0,0,0}, {12890,12892,12894 ,4770,4772,4774 ,0,0,0}, + {12895,12893,12896 ,4775,4773,4776 ,0,0,0}, {12893,12892,12896 ,4773,4772,4776 ,0,0,0}, + {12889,12891,12887 ,4769,4771,4767 ,0,0,0}, {12898,12895,12897 ,4777,4775,4777 ,0,0,0}, + {12886,12889,12887 ,4766,4769,4767 ,0,0,0}, {12872,12875,12873 ,4752,4755,4753 ,0,0,0}, + {12871,12873,12899 ,4751,4753,4778 ,0,0,0}, {12899,12900,12901 ,4778,4779,4780 ,0,0,0}, + {12901,12871,12899 ,4780,4751,4778 ,0,0,0}, {12902,12900,12903 ,4781,4779,4782 ,0,0,0}, + {12900,12902,12901 ,4779,4781,4780 ,0,0,0}, {12904,12905,12903 ,4783,4784,4782 ,0,0,0}, + {12902,12903,12905 ,4781,4782,4784 ,0,0,0}, {12904,12906,12907 ,4783,4785,4786 ,0,0,0}, + {12907,12905,12904 ,4786,4784,4783 ,0,0,0}, {12908,12906,12909 ,4787,4785,4788 ,0,0,0}, + {12906,12908,12907 ,4785,4787,4786 ,0,0,0}, {12910,12911,12909 ,4789,4790,4788 ,0,0,0}, + {12908,12909,12911 ,4787,4788,4790 ,0,0,0}, {12910,12912,12913 ,4789,4791,4792 ,0,0,0}, + {12913,12911,12910 ,4792,4790,4789 ,0,0,0}, {12914,12912,12915 ,4793,4791,4794 ,0,0,0}, + {12912,12914,12913 ,4791,4793,4792 ,0,0,0}, {12916,12917,12915 ,4795,4796,4794 ,0,0,0}, + {12914,12915,12917 ,4793,4794,4796 ,0,0,0}, {12916,12918,12919 ,4795,4797,4798 ,0,0,0}, + {12919,12917,12916 ,4798,4796,4795 ,0,0,0}, {12918,12920,12919 ,4797,4799,4798 ,0,0,0}, + {12918,12921,12920 ,4797,324,4799 ,0,0,0}, {12922,12923,12924 ,82,4800,4801 ,0,0,0}, + {12924,12925,12926 ,4801,4802,4803 ,0,0,0}, {12925,12927,12926 ,4802,4804,4803 ,0,0,0}, + {12924,12926,12922 ,4801,4803,82 ,0,0,0}, {12928,12929,12930 ,4805,4806,4807 ,0,0,0}, + {12930,12929,12927 ,4807,4806,4804 ,0,0,0}, {12928,12931,12932 ,4805,4808,4809 ,0,0,0}, + {12932,12929,12928 ,4809,4806,4805 ,0,0,0}, {12932,12931,12933 ,4809,4808,4810 ,0,0,0}, + {12933,12931,12934 ,4810,4808,4811 ,0,0,0}, {12934,12935,12936 ,4811,4812,4813 ,0,0,0}, + {12933,12934,12936 ,4810,4811,4813 ,0,0,0}, {12927,12925,12930 ,4804,4802,4807 ,0,0,0}, + {12937,12938,12939 ,4814,4815,4816 ,0,0,0}, {12937,12939,12935 ,4814,4816,4812 ,0,0,0}, + {12935,12939,12936 ,4812,4816,4813 ,0,0,0}, {12922,12940,12923 ,82,4817,4800 ,0,0,0}, + {12941,12940,12942 ,4818,4817,4819 ,0,0,0}, {12940,12941,12923 ,4817,4818,4800 ,0,0,0}, + {12943,12944,12942 ,4820,4821,4819 ,0,0,0}, {12941,12942,12944 ,4818,4819,4821 ,0,0,0}, + {12943,12945,12946 ,4820,4822,4823 ,0,0,0}, {12946,12944,12943 ,4823,4821,4820 ,0,0,0}, + {12947,12945,12948 ,4824,4822,4825 ,0,0,0}, {12945,12947,12946 ,4822,4824,4823 ,0,0,0}, + {12949,12950,12948 ,4826,4827,4825 ,0,0,0}, {12947,12948,12950 ,4824,4825,4827 ,0,0,0}, + {12949,12951,12952 ,4826,4828,4829 ,0,0,0}, {12952,12950,12949 ,4829,4827,4826 ,0,0,0}, + {12953,12951,12954 ,4830,4828,4831 ,0,0,0}, {12951,12953,12952 ,4828,4830,4829 ,0,0,0}, + {12949,12948,12955 ,4832,4833,4834 ,0,0,0}, {12955,12951,12949 ,4834,4835,4832 ,0,0,0}, + {12955,12954,12951 ,4834,4836,4835 ,0,0,0}, {12955,12945,12943 ,4834,4837,4838 ,0,0,0}, + {12948,12945,12955 ,4833,4837,4834 ,0,0,0}, {12955,12942,12940 ,4834,4839,4840 ,0,0,0}, + {12943,12942,12955 ,4838,4839,4834 ,0,0,0}, {12940,12922,12955 ,4840,4841,4834 ,0,0,0}, + {12927,12955,12926 ,4842,4834,4843 ,0,0,0}, {12955,12922,12926 ,4834,4841,4843 ,0,0,0}, + {12932,12955,12929 ,4844,4834,4845 ,0,0,0}, {12955,12927,12929 ,4834,4842,4845 ,0,0,0}, + {12936,12955,12933 ,4846,4834,4847 ,0,0,0}, {12955,12932,12933 ,4834,4844,4847 ,0,0,0}, + {12938,12955,12939 ,4848,4834,4849 ,0,0,0}, {12955,12936,12939 ,4834,4846,4849 ,0,0,0}, + {12956,12957,12958 ,82,4850,4851 ,0,0,0}, {12958,12959,12960 ,4851,4852,4853 ,0,0,0}, + {12959,12961,12960 ,4852,4854,4853 ,0,0,0}, {12958,12960,12956 ,4851,4853,82 ,0,0,0}, + {12962,12963,12964 ,4855,4856,4857 ,0,0,0}, {12964,12963,12961 ,4857,4856,4854 ,0,0,0}, + {12962,12965,12966 ,4855,4858,4859 ,0,0,0}, {12966,12963,12962 ,4859,4856,4855 ,0,0,0}, + {12966,12965,12967 ,4859,4858,4860 ,0,0,0}, {12967,12965,12968 ,4860,4858,4861 ,0,0,0}, + {12968,12969,12970 ,4861,4862,4863 ,0,0,0}, {12967,12968,12970 ,4860,4861,4863 ,0,0,0}, + {12961,12959,12964 ,4854,4852,4857 ,0,0,0}, {12971,12972,12973 ,4864,4865,4866 ,0,0,0}, + {12971,12973,12969 ,4864,4866,4862 ,0,0,0}, {12969,12973,12970 ,4862,4866,4863 ,0,0,0}, + {12956,12974,12957 ,82,4867,4850 ,0,0,0}, {12975,12974,12976 ,4868,4867,4869 ,0,0,0}, + {12974,12975,12957 ,4867,4868,4850 ,0,0,0}, {12977,12978,12976 ,4870,4871,4869 ,0,0,0}, + {12975,12976,12978 ,4868,4869,4871 ,0,0,0}, {12977,12979,12980 ,4870,4872,4873 ,0,0,0}, + {12980,12978,12977 ,4873,4871,4870 ,0,0,0}, {12981,12979,12982 ,4874,4872,4875 ,0,0,0}, + {12979,12981,12980 ,4872,4874,4873 ,0,0,0}, {12983,12984,12982 ,4876,4877,4875 ,0,0,0}, + {12981,12982,12984 ,4874,4875,4877 ,0,0,0}, {12983,12985,12986 ,4876,4878,4829 ,0,0,0}, + {12986,12984,12983 ,4829,4877,4876 ,0,0,0}, {12987,12985,12988 ,4879,4878,4831 ,0,0,0}, + {12985,12987,12986 ,4878,4879,4829 ,0,0,0}, {12983,12982,12989 ,4832,4833,4880 ,0,0,0}, + {12989,12985,12983 ,4880,4835,4832 ,0,0,0}, {12989,12988,12985 ,4880,4881,4835 ,0,0,0}, + {12989,12979,12977 ,4880,4837,4838 ,0,0,0}, {12982,12979,12989 ,4833,4837,4880 ,0,0,0}, + {12989,12976,12974 ,4880,4839,4840 ,0,0,0}, {12977,12976,12989 ,4838,4839,4880 ,0,0,0}, + {12974,12956,12989 ,4840,4882,4880 ,0,0,0}, {12961,12989,12960 ,4842,4880,4843 ,0,0,0}, + {12989,12956,12960 ,4880,4882,4843 ,0,0,0}, {12966,12989,12963 ,4844,4880,4845 ,0,0,0}, + {12989,12961,12963 ,4880,4842,4845 ,0,0,0}, {12970,12989,12967 ,4846,4880,4847 ,0,0,0}, + {12989,12966,12967 ,4880,4844,4847 ,0,0,0}, {12972,12989,12973 ,4883,4880,4849 ,0,0,0}, + {12989,12970,12973 ,4880,4846,4849 ,0,0,0}, {12990,12991,12992 ,4884,4885,4886 ,0,0,0}, + {12992,12993,12994 ,4886,4887,4888 ,0,0,0}, {12993,12995,12994 ,4887,4889,4888 ,0,0,0}, + {12992,12994,12990 ,4886,4888,4884 ,0,0,0}, {12996,12997,12998 ,4890,4891,4857 ,0,0,0}, + {12998,12997,12995 ,4857,4891,4889 ,0,0,0}, {12996,12999,13000 ,4890,4892,4893 ,0,0,0}, + {13000,12997,12996 ,4893,4891,4890 ,0,0,0}, {13000,12999,13001 ,4893,4892,4894 ,0,0,0}, + {13001,12999,13002 ,4894,4892,4895 ,0,0,0}, {13002,13003,13004 ,4895,4896,4897 ,0,0,0}, + {13001,13002,13004 ,4894,4895,4897 ,0,0,0}, {12995,12993,12998 ,4889,4887,4857 ,0,0,0}, + {13005,13006,13007 ,4898,4899,4900 ,0,0,0}, {13005,13007,13003 ,4898,4900,4896 ,0,0,0}, + {13003,13007,13004 ,4896,4900,4897 ,0,0,0}, {12990,13008,12991 ,4884,4901,4885 ,0,0,0}, + {13009,13008,13010 ,4868,4901,4902 ,0,0,0}, {13008,13009,12991 ,4901,4868,4885 ,0,0,0}, + {13011,13012,13010 ,4820,4903,4902 ,0,0,0}, {13009,13010,13012 ,4868,4902,4903 ,0,0,0}, + {13011,13013,13014 ,4820,4904,4905 ,0,0,0}, {13014,13012,13011 ,4905,4903,4820 ,0,0,0}, + {13015,13013,13016 ,4906,4904,4907 ,0,0,0}, {13013,13015,13014 ,4904,4906,4905 ,0,0,0}, + {13017,13018,13016 ,4826,4877,4907 ,0,0,0}, {13015,13016,13018 ,4906,4907,4877 ,0,0,0}, + {13017,13019,13020 ,4826,4828,4908 ,0,0,0}, {13020,13018,13017 ,4908,4877,4826 ,0,0,0}, + {13021,13019,13022 ,4909,4828,4910 ,0,0,0}, {13019,13021,13020 ,4828,4909,4908 ,0,0,0}, + {13017,13016,13023 ,4832,4833,4880 ,0,0,0}, {13023,13019,13017 ,4880,4835,4832 ,0,0,0}, + {13023,13022,13019 ,4880,4911,4835 ,0,0,0}, {13023,13013,13011 ,4880,4837,4838 ,0,0,0}, + {13016,13013,13023 ,4833,4837,4880 ,0,0,0}, {13023,13010,13008 ,4880,4839,4840 ,0,0,0}, + {13011,13010,13023 ,4838,4839,4880 ,0,0,0}, {13008,12990,13023 ,4840,4912,4880 ,0,0,0}, + {12995,13023,12994 ,4842,4880,4843 ,0,0,0}, {13023,12990,12994 ,4880,4912,4843 ,0,0,0}, + {13000,13023,12997 ,4844,4880,4845 ,0,0,0}, {13023,12995,12997 ,4880,4842,4845 ,0,0,0}, + {13004,13023,13001 ,4846,4880,4847 ,0,0,0}, {13023,13000,13001 ,4880,4844,4847 ,0,0,0}, + {13006,13023,13007 ,4913,4880,4849 ,0,0,0}, {13023,13004,13007 ,4880,4846,4849 ,0,0,0}, + {13024,13025,13026 ,4914,4915,4916 ,0,0,0}, {13026,13027,13028 ,4916,4917,4918 ,0,0,0}, + {13027,13029,13028 ,4917,4919,4918 ,0,0,0}, {13026,13028,13024 ,4916,4918,4914 ,0,0,0}, + {13030,13031,13032 ,4920,4921,4922 ,0,0,0}, {13032,13031,13029 ,4922,4921,4919 ,0,0,0}, + {13030,13033,13034 ,4920,4923,4924 ,0,0,0}, {13034,13031,13030 ,4924,4921,4920 ,0,0,0}, + {13034,13033,13035 ,4924,4923,4925 ,0,0,0}, {13035,13033,13036 ,4925,4923,4926 ,0,0,0}, + {13036,13037,13038 ,4926,4927,4928 ,0,0,0}, {13035,13036,13038 ,4925,4926,4928 ,0,0,0}, + {13029,13027,13032 ,4919,4917,4922 ,0,0,0}, {13039,13040,13041 ,4929,4815,4930 ,0,0,0}, + {13039,13041,13037 ,4929,4930,4927 ,0,0,0}, {13037,13041,13038 ,4927,4930,4928 ,0,0,0}, + {13024,13042,13025 ,4914,4931,4915 ,0,0,0}, {13043,13042,13044 ,4932,4931,4933 ,0,0,0}, + {13042,13043,13025 ,4931,4932,4915 ,0,0,0}, {13045,13046,13044 ,4934,4821,4933 ,0,0,0}, + {13043,13044,13046 ,4932,4933,4821 ,0,0,0}, {13045,13047,13048 ,4934,4935,4936 ,0,0,0}, + {13048,13046,13045 ,4936,4821,4934 ,0,0,0}, {13049,13047,13050 ,4937,4935,4938 ,0,0,0}, + {13047,13049,13048 ,4935,4937,4936 ,0,0,0}, {13051,13052,13050 ,4826,4877,4938 ,0,0,0}, + {13049,13050,13052 ,4937,4938,4877 ,0,0,0}, {13051,13053,13054 ,4826,4939,4940 ,0,0,0}, + {13054,13052,13051 ,4940,4877,4826 ,0,0,0}, {13055,13053,13056 ,4941,4939,4942 ,0,0,0}, + {13053,13055,13054 ,4939,4941,4940 ,0,0,0}, {13051,13050,13057 ,4832,4833,4943 ,0,0,0}, + {13057,13053,13051 ,4943,4835,4832 ,0,0,0}, {13057,13056,13053 ,4943,4944,4835 ,0,0,0}, + {13057,13047,13045 ,4943,4837,4838 ,0,0,0}, {13050,13047,13057 ,4833,4837,4943 ,0,0,0}, + {13057,13044,13042 ,4943,4839,4840 ,0,0,0}, {13045,13044,13057 ,4838,4839,4943 ,0,0,0}, + {13042,13024,13057 ,4840,4945,4943 ,0,0,0}, {13029,13057,13028 ,4842,4943,4843 ,0,0,0}, + {13057,13024,13028 ,4943,4945,4843 ,0,0,0}, {13034,13057,13031 ,4844,4943,4845 ,0,0,0}, + {13057,13029,13031 ,4943,4842,4845 ,0,0,0}, {13038,13057,13035 ,4846,4943,4847 ,0,0,0}, + {13057,13034,13035 ,4943,4844,4847 ,0,0,0}, {13040,13057,13041 ,4946,4943,4849 ,0,0,0}, + {13057,13038,13041 ,4943,4846,4849 ,0,0,0}, {13058,13059,13060 ,4947,4948,4949 ,0,0,0}, + {13061,13062,13063 ,4950,4951,4952 ,0,0,0}, {13060,13063,13062 ,4949,4952,4951 ,0,0,0}, + {13064,13065,13066 ,4953,4954,4955 ,0,0,0}, {13067,13068,13061 ,4956,4957,4950 ,0,0,0}, + {13064,13068,13067 ,4953,4957,4956 ,0,0,0}, {13067,13065,13064 ,4956,4954,4953 ,0,0,0}, + {13068,13062,13061 ,4957,4951,4950 ,0,0,0}, {13069,13070,13071 ,4958,4959,4960 ,0,0,0}, + {13070,13072,13071 ,4959,4961,4960 ,0,0,0}, {13073,13074,13075 ,4962,4963,4964 ,0,0,0}, + {13073,13075,13072 ,4962,4964,4961 ,0,0,0}, {13070,13073,13072 ,4959,4962,4961 ,0,0,0}, + {13065,13069,13066 ,4954,4958,4955 ,0,0,0}, {13069,13071,13066 ,4958,4960,4955 ,0,0,0}, + {13076,13077,13078 ,4965,4966,4967 ,0,0,0}, {13079,13080,13081 ,4968,4969,4970 ,0,0,0}, + {13078,13077,13079 ,4967,4966,4968 ,0,0,0}, {13082,13083,13084 ,4726,4971,4972 ,0,0,0}, + {13078,13079,13081 ,4967,4968,4970 ,0,0,0}, {13084,13083,13080 ,4972,4971,4969 ,0,0,0}, + {13083,13081,13080 ,4971,4970,4969 ,0,0,0}, {13074,13077,13076 ,4963,4966,4965 ,0,0,0}, + {13085,13082,13084 ,4726,4726,4972 ,0,0,0}, {13075,13074,13076 ,4964,4963,4965 ,0,0,0}, + {13059,13063,13060 ,4948,4952,4949 ,0,0,0}, {13086,13059,13058 ,4973,4948,4947 ,0,0,0}, + {13086,13087,13088 ,4973,4974,4975 ,0,0,0}, {13087,13086,13058 ,4974,4973,4947 ,0,0,0}, + {13089,13088,13090 ,4976,4975,4977 ,0,0,0}, {13087,13090,13088 ,4974,4977,4975 ,0,0,0}, + {13091,13092,13089 ,4978,4979,4976 ,0,0,0}, {13089,13090,13091 ,4976,4977,4978 ,0,0,0}, + {13092,13093,13094 ,4979,4980,4981 ,0,0,0}, {13093,13092,13091 ,4980,4979,4978 ,0,0,0}, + {13095,13094,13096 ,4982,4981,4983 ,0,0,0}, {13093,13096,13094 ,4980,4983,4981 ,0,0,0}, + {13097,13098,13095 ,4984,4985,4982 ,0,0,0}, {13095,13096,13097 ,4982,4983,4984 ,0,0,0}, + {13098,13099,13100 ,4985,4986,4987 ,0,0,0}, {13099,13098,13097 ,4986,4985,4984 ,0,0,0}, + {13101,13100,13102 ,4988,4987,4989 ,0,0,0}, {13099,13102,13100 ,4986,4989,4987 ,0,0,0}, + {13103,13104,13101 ,4990,4991,4988 ,0,0,0}, {13101,13102,13103 ,4988,4989,4990 ,0,0,0}, + {13104,13105,13106 ,4991,4992,4748 ,0,0,0}, {13105,13104,13103 ,4992,4991,4990 ,0,0,0}, + {13105,13107,13106 ,4992,4750,4748 ,0,0,0}, {13108,13109,13110 ,4993,4994,4995 ,0,0,0}, + {13111,13112,13113 ,4996,4997,4998 ,0,0,0}, {13109,13114,13115 ,4994,4999,5000 ,0,0,0}, + {13114,13109,13108 ,4999,4994,4993 ,0,0,0}, {13114,13116,13115 ,4999,5001,5000 ,0,0,0}, + {13110,13117,13108 ,4995,5002,4993 ,0,0,0}, {13111,13117,13118 ,4996,5002,5003 ,0,0,0}, + {13110,13118,13117 ,4995,5003,5002 ,0,0,0}, {13119,13120,13121 ,5004,5005,5006 ,0,0,0}, + {13111,13118,13112 ,4996,5003,4997 ,0,0,0}, {13122,13123,13124 ,5007,5008,5009 ,0,0,0}, + {13125,13126,13127 ,5010,5011,5012 ,0,0,0}, {13128,13129,13130 ,5013,5014,5015 ,0,0,0}, + {13131,13132,13133 ,5016,5017,5018 ,0,0,0}, {13134,13135,13136 ,5019,5020,5021 ,0,0,0}, + {13137,13138,13129 ,5022,5023,5014 ,0,0,0}, {13139,13140,13141 ,5024,5025,5026 ,0,0,0}, + {13140,13135,13142 ,5025,5020,5027 ,0,0,0}, {13143,13144,13145 ,5028,5029,5030 ,0,0,0}, + {13146,13147,13139 ,5031,5032,5024 ,0,0,0}, {13148,13149,13150 ,5033,5034,5035 ,0,0,0}, + {13151,13145,13152 ,5036,5030,5037 ,0,0,0}, {13153,13154,13155 ,5038,5039,5040 ,0,0,0}, + {13156,13154,13157 ,5041,5039,5042 ,0,0,0}, {13158,13159,13160 ,5043,5044,5045 ,0,0,0}, + {13155,13161,13158 ,5040,5046,5043 ,0,0,0}, {13162,13163,13164 ,5047,5048,5049 ,0,0,0}, + {13162,13165,13166 ,5047,5050,5051 ,0,0,0}, {13167,13168,13169 ,5052,5053,5054 ,0,0,0}, + {13170,13171,13169 ,5055,5056,5054 ,0,0,0}, {13172,13173,13174 ,5057,5058,5059 ,0,0,0}, + {13173,13167,13175 ,5058,5052,5060 ,0,0,0}, {13176,13177,13178 ,5061,5062,5063 ,0,0,0}, + {13172,13179,13176 ,5057,5064,5061 ,0,0,0}, {13180,13181,13182 ,5065,5066,5067 ,0,0,0}, + {13180,13183,13184 ,5065,5068,5069 ,0,0,0}, {13185,13186,13187 ,5070,5071,5072 ,0,0,0}, + {13185,13188,13181 ,5070,5073,5066 ,0,0,0}, {13189,13186,13190 ,5074,5071,5075 ,0,0,0}, + {13186,13189,13187 ,5071,5074,5072 ,0,0,0}, {13191,13192,13190 ,5076,5077,5075 ,0,0,0}, + {13189,13190,13192 ,5074,5075,5077 ,0,0,0}, {13193,13194,13192 ,5078,5079,5077 ,0,0,0}, + {13192,13191,13193 ,5077,5076,5078 ,0,0,0}, {13194,13195,13196 ,5079,5080,5081 ,0,0,0}, + {13195,13194,13193 ,5080,5079,5078 ,0,0,0}, {13197,13196,13198 ,5082,5081,5083 ,0,0,0}, + {13195,13198,13196 ,5080,5083,5081 ,0,0,0}, {13199,13200,13197 ,5084,5085,5082 ,0,0,0}, + {13197,13198,13199 ,5082,5083,5084 ,0,0,0}, {13200,13201,13202 ,5085,5086,5087 ,0,0,0}, + {13201,13200,13199 ,5086,5085,5084 ,0,0,0}, {13203,13202,13204 ,5088,5087,5089 ,0,0,0}, + {13201,13204,13202 ,5086,5089,5087 ,0,0,0}, {13205,13203,13206 ,5090,5088,5091 ,0,0,0}, + {13203,13204,13206 ,5088,5089,5091 ,0,0,0}, {13205,13207,13208 ,5090,5092,5093 ,0,0,0}, + {13208,13203,13205 ,5093,5088,5090 ,0,0,0}, {13209,13207,13210 ,5094,5092,5095 ,0,0,0}, + {13207,13209,13208 ,5092,5094,5093 ,0,0,0}, {13211,13212,13210 ,126,5096,5095 ,0,0,0}, + {13209,13210,13212 ,5094,5095,5096 ,0,0,0}, {13213,13212,13211 ,126,5096,126 ,0,0,0}, + {13182,13181,13188 ,5067,5066,5073 ,0,0,0}, {13185,13187,13188 ,5070,5072,5073 ,0,0,0}, + {13178,13183,13176 ,5063,5068,5061 ,0,0,0}, {13180,13182,13183 ,5065,5067,5068 ,0,0,0}, + {13178,13184,13183 ,5063,5069,5068 ,0,0,0}, {13174,13179,13172 ,5059,5064,5057 ,0,0,0}, + {13176,13179,13177 ,5061,5064,5062 ,0,0,0}, {13168,13167,13173 ,5053,5052,5058 ,0,0,0}, + {13173,13175,13174 ,5058,5060,5059 ,0,0,0}, {13170,13163,13171 ,5055,5048,5056 ,0,0,0}, + {13168,13170,13169 ,5053,5055,5054 ,0,0,0}, {13162,13164,13165 ,5047,5049,5050 ,0,0,0}, + {13163,13170,13164 ,5048,5055,5049 ,0,0,0}, {13159,13166,13160 ,5044,5051,5045 ,0,0,0}, + {13166,13165,13160 ,5051,5050,5045 ,0,0,0}, {13155,13158,13153 ,5040,5043,5038 ,0,0,0}, + {13161,13159,13158 ,5046,5044,5043 ,0,0,0}, {13148,13156,13149 ,5033,5041,5034 ,0,0,0}, + {13157,13154,13153 ,5042,5039,5038 ,0,0,0}, {13149,13156,13157 ,5034,5041,5042 ,0,0,0}, + {13150,13151,13152 ,5035,5036,5037 ,0,0,0}, {13149,13151,13150 ,5034,5036,5035 ,0,0,0}, + {13145,13147,13143 ,5030,5032,5028 ,0,0,0}, {13152,13145,13144 ,5037,5030,5029 ,0,0,0}, + {13214,13146,13139 ,5097,5031,5024 ,0,0,0}, {13146,13143,13147 ,5031,5028,5032 ,0,0,0}, + {13215,13140,13142 ,5098,5025,5027 ,0,0,0}, {13139,13141,13214 ,5024,5026,5097 ,0,0,0}, + {13140,13215,13141 ,5025,5098,5026 ,0,0,0}, {13136,13137,13134 ,5021,5022,5019 ,0,0,0}, + {13142,13135,13134 ,5027,5020,5019 ,0,0,0}, {13130,13133,13128 ,5015,5018,5013 ,0,0,0}, + {13137,13136,13138 ,5022,5021,5023 ,0,0,0}, {13129,13138,13130 ,5014,5023,5015 ,0,0,0}, + {13122,13131,13133 ,5007,5016,5018 ,0,0,0}, {13132,13128,13133 ,5017,5013,5018 ,0,0,0}, + {13123,13127,13124 ,5008,5012,5009 ,0,0,0}, {13122,13124,13131 ,5007,5009,5016 ,0,0,0}, + {13125,13119,13126 ,5010,5004,5011 ,0,0,0}, {13123,13125,13127 ,5008,5010,5012 ,0,0,0}, + {13121,13120,13113 ,5006,5005,4998 ,0,0,0}, {13126,13119,13121 ,5011,5004,5006 ,0,0,0}, + {13111,13113,13120 ,4996,4998,5005 ,0,0,0}, {13216,13217,13218 ,5099,5100,5101 ,0,0,0}, + {13219,13220,13221 ,5102,5103,5104 ,0,0,0}, {13222,13220,13219 ,5105,5103,5102 ,0,0,0}, + {13223,13219,13221 ,5106,5102,5104 ,0,0,0}, {13224,13225,13226 ,5107,5108,5109 ,0,0,0}, + {13227,13228,13223 ,5110,5108,5106 ,0,0,0}, {13225,13229,13226 ,5108,5111,5109 ,0,0,0}, + {13225,13228,13229 ,5108,5108,5111 ,0,0,0}, {13229,13230,13231 ,5111,5112,5113 ,0,0,0}, + {13230,13232,13231 ,5112,5114,5113 ,0,0,0}, {13231,13232,13233 ,5113,5114,5115 ,0,0,0}, + {13232,13234,13233 ,5114,5116,5115 ,0,0,0}, {13235,13236,13234 ,5117,5118,5116 ,0,0,0}, + {13235,13237,13238 ,5117,5119,5120 ,0,0,0}, {13239,13238,13237 ,5121,5120,5119 ,0,0,0}, + {13239,13237,13240 ,5121,5119,5122 ,0,0,0}, {13240,13241,13239 ,5122,5123,5121 ,0,0,0}, + {13236,13233,13234 ,5118,5115,5116 ,0,0,0}, {13238,13236,13235 ,5120,5118,5117 ,0,0,0}, + {13241,13242,13243 ,5123,5124,5125 ,0,0,0}, {13242,13241,13240 ,5124,5123,5122 ,0,0,0}, + {12820,13243,13242 ,5126,5125,5124 ,0,0,0}, {13222,13219,13244 ,5105,5102,5127 ,0,0,0}, + {13245,13246,13247 ,5128,5129,5130 ,0,0,0}, {13245,13244,13246 ,5128,5127,5129 ,0,0,0}, + {13246,13248,13247 ,5129,5131,5130 ,0,0,0}, {13248,13246,13249 ,5131,5129,5132 ,0,0,0}, + {13250,13251,13252 ,5133,5134,5135 ,0,0,0}, {13250,13249,13251 ,5133,5132,5134 ,0,0,0}, + {13253,13252,13251 ,5136,5135,5134 ,0,0,0}, {13252,13253,13254 ,5135,5136,5137 ,0,0,0}, + {13255,13256,13257 ,5138,5139,5140 ,0,0,0}, {13258,13259,13253 ,5141,5142,5136 ,0,0,0}, + {13260,13261,13258 ,5143,5144,5141 ,0,0,0}, {13261,13260,13262 ,5144,5143,5145 ,0,0,0}, + {13263,13264,13260 ,5146,5147,5143 ,0,0,0}, {13217,13216,13265 ,5100,5099,5148 ,0,0,0}, + {13266,13267,13263 ,5149,5150,5146 ,0,0,0}, {13268,13269,13270 ,5151,5152,5153 ,0,0,0}, + {13271,13272,13273 ,5154,5155,5156 ,0,0,0}, {13274,13275,13276 ,5157,5158,5159 ,0,0,0}, + {13277,13278,13279 ,5160,5161,5162 ,0,0,0}, {13280,13281,13282 ,5163,5164,5165 ,0,0,0}, + {13283,13284,13285 ,5166,5167,5168 ,0,0,0}, {13283,13286,13287 ,5166,5169,5170 ,0,0,0}, + {13288,13289,13290 ,5171,5172,5173 ,0,0,0}, {13291,13292,13293 ,5174,5175,5176 ,0,0,0}, + {13294,13295,13296 ,5177,5178,5179 ,0,0,0}, {13297,13289,13288 ,5180,5172,5171 ,0,0,0}, + {13298,13299,13300 ,5179,5181,5182 ,0,0,0}, {13298,13296,13295 ,5179,5179,5178 ,0,0,0}, + {13301,13302,13303 ,5183,5184,5185 ,0,0,0}, {13304,13301,13300 ,5186,5183,5182 ,0,0,0}, + {13305,13306,13307 ,5187,5188,5189 ,0,0,0}, {13308,13305,13303 ,5190,5187,5185 ,0,0,0}, + {13309,13310,13311 ,5191,5192,5193 ,0,0,0}, {13310,13309,13307 ,5192,5191,5189 ,0,0,0}, + {13312,13313,13311 ,5194,5195,5193 ,0,0,0}, {13309,13311,13313 ,5191,5193,5195 ,0,0,0}, + {13312,13314,13315 ,5194,5196,5197 ,0,0,0}, {13315,13313,13312 ,5197,5195,5194 ,0,0,0}, + {13308,13306,13305 ,5190,5188,5187 ,0,0,0}, {13306,13310,13307 ,5188,5192,5189 ,0,0,0}, + {13302,13308,13303 ,5184,5190,5185 ,0,0,0}, {13304,13302,13301 ,5186,5184,5183 ,0,0,0}, + {13299,13304,13300 ,5181,5186,5182 ,0,0,0}, {13299,13298,13295 ,5181,5179,5178 ,0,0,0}, + {13295,13316,13299 ,5178,5198,5181 ,0,0,0}, {13288,13316,13297 ,5171,5198,5180 ,0,0,0}, + {13316,13295,13297 ,5198,5178,5180 ,0,0,0}, {13317,13318,13319 ,5199,5200,5201 ,0,0,0}, + {13290,13289,13291 ,5173,5172,5174 ,0,0,0}, {13317,13320,13321 ,5199,5202,5203 ,0,0,0}, + {13321,13318,13317 ,5203,5200,5199 ,0,0,0}, {13322,13320,13323 ,5204,5202,5205 ,0,0,0}, + {13320,13322,13321 ,5202,5204,5203 ,0,0,0}, {13324,12918,13323 ,5206,5207,5205 ,0,0,0}, + {13322,13323,12918 ,5204,5205,5207 ,0,0,0}, {12921,12918,13324 ,5197,5207,5206 ,0,0,0}, + {13319,13318,13325 ,5201,5200,5208 ,0,0,0}, {13326,13327,13328 ,5209,5210,5211 ,0,0,0}, + {13319,13325,13328 ,5201,5208,5211 ,0,0,0}, {13326,13329,13327 ,5209,5212,5210 ,0,0,0}, + {13328,13325,13326 ,5211,5208,5209 ,0,0,0}, {13292,13284,13293 ,5175,5167,5176 ,0,0,0}, + {13329,13330,13327 ,5212,5213,5210 ,0,0,0}, {13296,13330,13294 ,5179,5213,5177 ,0,0,0}, + {13329,13294,13330 ,5212,5177,5213 ,0,0,0}, {13291,13293,13290 ,5174,5176,5173 ,0,0,0}, + {13282,13271,13280 ,5165,5154,5163 ,0,0,0}, {13283,13285,13286 ,5166,5168,5169 ,0,0,0}, + {13284,13292,13285 ,5167,5175,5168 ,0,0,0}, {13286,13279,13287 ,5169,5162,5170 ,0,0,0}, + {13281,13278,13277 ,5164,5161,5160 ,0,0,0}, {13278,13287,13279 ,5161,5170,5162 ,0,0,0}, + {13282,13281,13277 ,5165,5164,5160 ,0,0,0}, {13268,13275,13274 ,5151,5158,5157 ,0,0,0}, + {13271,13273,13280 ,5154,5156,5163 ,0,0,0}, {13272,13276,13273 ,5155,5159,5156 ,0,0,0}, + {13270,13275,13268 ,5153,5158,5151 ,0,0,0}, {13272,13274,13276 ,5155,5157,5159 ,0,0,0}, + {13218,13270,13269 ,5101,5153,5152 ,0,0,0}, {13269,12870,13266 ,5152,5214,5149 ,0,0,0}, + {13224,13331,13225 ,5107,5215,5108 ,0,0,0}, {13230,13229,13228 ,5112,5111,5108 ,0,0,0}, + {13227,13332,13228 ,5110,5216,5108 ,0,0,0}, {13230,13228,13332 ,5112,5108,5216 ,0,0,0}, + {13333,13331,13334 ,5217,5215,5218 ,0,0,0}, {13221,13227,13223 ,5104,5110,5106 ,0,0,0}, + {13335,13333,13336 ,5219,5217,5220 ,0,0,0}, {13335,13337,13333 ,5219,5221,5217 ,0,0,0}, + {13338,13337,13339 ,5222,5221,5223 ,0,0,0}, {13245,13222,13244 ,5128,5105,5127 ,0,0,0}, + {13340,13338,13341 ,5224,5222,5225 ,0,0,0}, {13340,13342,13338 ,5224,5226,5222 ,0,0,0}, + {13343,13342,13344 ,5227,5226,5228 ,0,0,0}, {13250,13248,13249 ,5133,5131,5132 ,0,0,0}, + {13345,13346,13343 ,5229,5230,5227 ,0,0,0}, {13347,13346,13345 ,5231,5230,5229 ,0,0,0}, + {13348,13346,13349 ,5232,5230,5233 ,0,0,0}, {13259,13254,13253 ,5142,5137,5136 ,0,0,0}, + {13257,13348,13255 ,5140,5232,5138 ,0,0,0}, {13261,13259,13258 ,5144,5142,5141 ,0,0,0}, + {13350,13257,13351 ,5234,5140,5235 ,0,0,0}, {13264,13262,13260 ,5147,5145,5143 ,0,0,0}, + {13216,13350,13265 ,5099,5234,5148 ,0,0,0}, {13267,13264,13263 ,5150,5147,5146 ,0,0,0}, + {13267,13266,12870 ,5150,5149,5214 ,0,0,0}, {13269,13266,13218 ,5152,5149,5101 ,0,0,0}, + {13218,13266,13216 ,5101,5149,5099 ,0,0,0}, {13351,13265,13350 ,5235,5148,5234 ,0,0,0}, + {13256,13351,13257 ,5139,5235,5140 ,0,0,0}, {13349,13255,13348 ,5233,5138,5232 ,0,0,0}, + {13347,13349,13346 ,5231,5233,5230 ,0,0,0}, {13344,13345,13343 ,5228,5229,5227 ,0,0,0}, + {13340,13344,13342 ,5224,5228,5226 ,0,0,0}, {13339,13341,13338 ,5223,5225,5222 ,0,0,0}, + {13335,13339,13337 ,5219,5223,5221 ,0,0,0}, {13334,13336,13333 ,5218,5220,5217 ,0,0,0}, + {13224,13334,13331 ,5107,5218,5215 ,0,0,0}, {13352,13353,13354 ,5236,5237,5238 ,0,0,0}, + {13355,13356,13354 ,5239,5240,5238 ,0,0,0}, {13352,13354,13356 ,5236,5238,5240 ,0,0,0}, + {13355,13357,13358 ,5239,5241,5242 ,0,0,0}, {13358,13356,13355 ,5242,5240,5239 ,0,0,0}, + {13359,13357,13360 ,5243,5241,5244 ,0,0,0}, {13357,13359,13358 ,5241,5243,5242 ,0,0,0}, + {13361,13362,13360 ,5245,5246,5244 ,0,0,0}, {13359,13360,13362 ,5243,5244,5246 ,0,0,0}, + {13361,13363,13364 ,5245,5247,5248 ,0,0,0}, {13364,13362,13361 ,5248,5246,5245 ,0,0,0}, + {13365,13363,13366 ,5249,5247,5250 ,0,0,0}, {13363,13365,13364 ,5247,5249,5248 ,0,0,0}, + {13367,13368,13366 ,5251,5252,5250 ,0,0,0}, {13365,13366,13368 ,5249,5250,5252 ,0,0,0}, + {13367,13369,13370 ,5251,5253,5254 ,0,0,0}, {13370,13368,13367 ,5254,5252,5251 ,0,0,0}, + {13371,13369,13372 ,5255,5253,5256 ,0,0,0}, {13369,13371,13370 ,5253,5255,5254 ,0,0,0}, + {13373,13374,13372 ,5257,5258,5256 ,0,0,0}, {13371,13372,13374 ,5255,5256,5258 ,0,0,0}, + {13373,13375,13376 ,5257,5259,5260 ,0,0,0}, {13376,13374,13373 ,5260,5258,5257 ,0,0,0}, + {13377,13375,13378 ,5261,5259,5262 ,0,0,0}, {13375,13377,13376 ,5259,5261,5260 ,0,0,0}, + {13379,13380,13378 ,5263,5264,5262 ,0,0,0}, {13377,13378,13380 ,5261,5262,5264 ,0,0,0}, + {13379,13381,13382 ,5263,5265,5266 ,0,0,0}, {13382,13380,13379 ,5266,5264,5263 ,0,0,0}, + {13383,13381,13384 ,5267,5265,5268 ,0,0,0}, {13381,13383,13382 ,5265,5267,5266 ,0,0,0}, + {13385,13386,13384 ,5269,5270,5268 ,0,0,0}, {13383,13384,13386 ,5267,5268,5270 ,0,0,0}, + {13385,13387,13388 ,5269,5271,5272 ,0,0,0}, {13388,13386,13385 ,5272,5270,5269 ,0,0,0}, + {13389,13387,13390 ,5273,5271,5274 ,0,0,0}, {13387,13389,13388 ,5271,5273,5272 ,0,0,0}, + {13391,13392,13390 ,5275,5276,5274 ,0,0,0}, {13389,13390,13392 ,5273,5274,5276 ,0,0,0}, + {13391,13393,13394 ,5275,5277,5278 ,0,0,0}, {13394,13392,13391 ,5278,5276,5275 ,0,0,0}, + {13395,13393,13396 ,5279,5277,5280 ,0,0,0}, {13393,13395,13394 ,5277,5279,5278 ,0,0,0}, + {13397,13398,13396 ,5281,5282,5280 ,0,0,0}, {13395,13396,13398 ,5279,5280,5282 ,0,0,0}, + {13399,13397,13400 ,5283,5281,5284 ,0,0,0}, {13399,13398,13397 ,5283,5282,5281 ,0,0,0}, + {13401,13400,13402 ,5285,5284,5286 ,0,0,0}, {13397,13402,13400 ,5281,5286,5284 ,0,0,0}, + {13403,13401,13404 ,5287,5285,5288 ,0,0,0}, {13401,13402,13404 ,5285,5286,5288 ,0,0,0}, + {13403,13405,13406 ,5287,5289,5290 ,0,0,0}, {13406,13401,13403 ,5290,5285,5287 ,0,0,0}, + {13405,13407,13406 ,5289,5291,5290 ,0,0,0}, {13408,13353,13352 ,5292,5237,5236 ,0,0,0}, + {13408,13409,13410 ,5292,5293,5294 ,0,0,0}, {13410,13353,13408 ,5294,5237,5292 ,0,0,0}, + {13411,13409,13412 ,5295,5293,5296 ,0,0,0}, {13409,13411,13410 ,5293,5295,5294 ,0,0,0}, + {13413,13414,13412 ,5297,5298,5296 ,0,0,0}, {13411,13412,13414 ,5295,5296,5298 ,0,0,0}, + {13413,13415,13416 ,5297,5299,5300 ,0,0,0}, {13416,13414,13413 ,5300,5298,5297 ,0,0,0}, + {13417,13415,13418 ,5301,5299,5302 ,0,0,0}, {13415,13417,13416 ,5299,5301,5300 ,0,0,0}, + {13419,13420,13418 ,5303,5304,5302 ,0,0,0}, {13417,13418,13420 ,5301,5302,5304 ,0,0,0}, + {13419,13421,13422 ,5303,5305,5306 ,0,0,0}, {13422,13420,13419 ,5306,5304,5303 ,0,0,0}, + {13423,13421,13424 ,5307,5305,5308 ,0,0,0}, {13421,13423,13422 ,5305,5307,5306 ,0,0,0}, + {13425,13426,13424 ,5309,5310,5308 ,0,0,0}, {13423,13424,13426 ,5307,5308,5310 ,0,0,0}, + {13425,13427,13428 ,5309,5311,5312 ,0,0,0}, {13428,13426,13425 ,5312,5310,5309 ,0,0,0}, + {13429,13427,13430 ,5313,5311,5314 ,0,0,0}, {13427,13429,13428 ,5311,5313,5312 ,0,0,0}, + {13431,13432,13430 ,5315,5316,5314 ,0,0,0}, {13429,13430,13432 ,5313,5314,5316 ,0,0,0}, + {13431,13433,13434 ,5315,5317,5318 ,0,0,0}, {13434,13432,13431 ,5318,5316,5315 ,0,0,0}, + {13435,13433,13436 ,5319,5317,5320 ,0,0,0}, {13433,13435,13434 ,5317,5319,5318 ,0,0,0}, + {13437,13438,13436 ,5321,5322,5320 ,0,0,0}, {13435,13436,13438 ,5319,5320,5322 ,0,0,0}, + {13437,13439,13440 ,5321,5323,5324 ,0,0,0}, {13440,13438,13437 ,5324,5322,5321 ,0,0,0}, + {13441,13439,13442 ,5325,5323,5326 ,0,0,0}, {13439,13441,13440 ,5323,5325,5324 ,0,0,0}, + {13443,13444,13442 ,5327,5328,5326 ,0,0,0}, {13441,13442,13444 ,5325,5326,5328 ,0,0,0}, + {13443,13445,13446 ,5327,5329,5330 ,0,0,0}, {13446,13444,13443 ,5330,5328,5327 ,0,0,0}, + {13447,13445,13448 ,5331,5329,5332 ,0,0,0}, {13445,13447,13446 ,5329,5331,5330 ,0,0,0}, + {13449,13450,13448 ,5333,5334,5332 ,0,0,0}, {13447,13448,13450 ,5331,5332,5334 ,0,0,0}, + {13449,13451,13452 ,5333,5335,5336 ,0,0,0}, {13452,13450,13449 ,5336,5334,5333 ,0,0,0}, + {13453,13454,13451 ,5337,5338,5335 ,0,0,0}, {13451,13454,13452 ,5335,5338,5336 ,0,0,0}, + {13455,13456,13453 ,5339,5340,5337 ,0,0,0}, {13453,13451,13455 ,5337,5335,5339 ,0,0,0}, + {13457,13458,13456 ,5341,5342,5340 ,0,0,0}, {13457,13456,13455 ,5341,5340,5339 ,0,0,0}, + {13459,13458,13460 ,5343,5342,5344 ,0,0,0}, {13458,13459,13456 ,5342,5343,5340 ,0,0,0}, + {13459,13460,13461 ,5343,5344,5345 ,0,0,0}, {13462,13463,13464 ,5346,5347,5348 ,0,0,0}, + {13465,13466,13464 ,5349,5350,5348 ,0,0,0}, {13462,13464,13466 ,5346,5348,5350 ,0,0,0}, + {13465,13467,13468 ,5349,5351,5352 ,0,0,0}, {13468,13466,13465 ,5352,5350,5349 ,0,0,0}, + {13469,13467,13470 ,5353,5351,5354 ,0,0,0}, {13467,13469,13468 ,5351,5353,5352 ,0,0,0}, + {13471,13472,13470 ,5355,5356,5354 ,0,0,0}, {13469,13470,13472 ,5353,5354,5356 ,0,0,0}, + {13471,13473,13474 ,5355,5357,5358 ,0,0,0}, {13474,13472,13471 ,5358,5356,5355 ,0,0,0}, + {13475,13473,13476 ,5359,5357,5360 ,0,0,0}, {13473,13475,13474 ,5357,5359,5358 ,0,0,0}, + {13477,13478,13476 ,5361,5362,5360 ,0,0,0}, {13475,13476,13478 ,5359,5360,5362 ,0,0,0}, + {13477,13479,13480 ,5361,5363,5364 ,0,0,0}, {13480,13478,13477 ,5364,5362,5361 ,0,0,0}, + {13481,13479,13482 ,5365,5363,5366 ,0,0,0}, {13479,13481,13480 ,5363,5365,5364 ,0,0,0}, + {13483,13484,13482 ,5367,5368,5366 ,0,0,0}, {13481,13482,13484 ,5365,5366,5368 ,0,0,0}, + {13483,13485,13486 ,5367,5369,5370 ,0,0,0}, {13486,13484,13483 ,5370,5368,5367 ,0,0,0}, + {13487,13485,13488 ,5371,5369,5372 ,0,0,0}, {13485,13487,13486 ,5369,5371,5370 ,0,0,0}, + {13489,13490,13488 ,5373,5374,5372 ,0,0,0}, {13487,13488,13490 ,5371,5372,5374 ,0,0,0}, + {13489,13491,13492 ,5373,5375,5376 ,0,0,0}, {13492,13490,13489 ,5376,5374,5373 ,0,0,0}, + {13493,13491,13494 ,5377,5375,5378 ,0,0,0}, {13491,13493,13492 ,5375,5377,5376 ,0,0,0}, + {13495,13496,13494 ,5379,5380,5378 ,0,0,0}, {13493,13494,13496 ,5377,5378,5380 ,0,0,0}, + {13495,13497,13498 ,5379,5381,5382 ,0,0,0}, {13498,13496,13495 ,5382,5380,5379 ,0,0,0}, + {13499,13497,13500 ,5383,5381,5384 ,0,0,0}, {13497,13499,13498 ,5381,5383,5382 ,0,0,0}, + {13501,13502,13500 ,5385,5386,5384 ,0,0,0}, {13499,13500,13502 ,5383,5384,5386 ,0,0,0}, + {13501,13503,13504 ,5385,5387,5388 ,0,0,0}, {13504,13502,13501 ,5388,5386,5385 ,0,0,0}, + {13505,13503,13506 ,5389,5387,5390 ,0,0,0}, {13503,13505,13504 ,5387,5389,5388 ,0,0,0}, + {13507,13508,13506 ,5391,5392,5390 ,0,0,0}, {13505,13506,13508 ,5389,5390,5392 ,0,0,0}, + {13507,13509,13510 ,5391,5393,5394 ,0,0,0}, {13510,13508,13507 ,5394,5392,5391 ,0,0,0}, + {13511,13509,13512 ,5395,5393,5396 ,0,0,0}, {13509,13511,13510 ,5393,5395,5394 ,0,0,0}, + {13513,13514,13512 ,5397,5398,5396 ,0,0,0}, {13511,13512,13514 ,5395,5396,5398 ,0,0,0}, + {13513,13515,13516 ,5397,5399,5400 ,0,0,0}, {13516,13514,13513 ,5400,5398,5397 ,0,0,0}, + {13517,13515,13518 ,5401,5399,5402 ,0,0,0}, {13515,13517,13516 ,5399,5401,5400 ,0,0,0}, + {13519,13520,13518 ,5403,5404,5402 ,0,0,0}, {13517,13518,13520 ,5401,5402,5404 ,0,0,0}, + {13519,13521,13522 ,5403,5405,5406 ,0,0,0}, {13522,13520,13519 ,5406,5404,5403 ,0,0,0}, + {13521,13523,13522 ,5405,5407,5406 ,0,0,0}, {13524,13463,13462 ,5408,5347,5346 ,0,0,0}, + {13524,13525,13526 ,5408,5409,5410 ,0,0,0}, {13526,13463,13524 ,5410,5347,5408 ,0,0,0}, + {13527,13525,13528 ,5411,5409,5412 ,0,0,0}, {13525,13527,13526 ,5409,5411,5410 ,0,0,0}, + {13529,13530,13528 ,5413,5414,5412 ,0,0,0}, {13527,13528,13530 ,5411,5412,5414 ,0,0,0}, + {13529,13531,13532 ,5413,5415,5416 ,0,0,0}, {13532,13530,13529 ,5416,5414,5413 ,0,0,0}, + {13533,13531,13534 ,5417,5415,5418 ,0,0,0}, {13531,13533,13532 ,5415,5417,5416 ,0,0,0}, + {13535,13536,13534 ,5419,5420,5418 ,0,0,0}, {13533,13534,13536 ,5417,5418,5420 ,0,0,0}, + {13535,13537,13538 ,5419,5421,5422 ,0,0,0}, {13538,13536,13535 ,5422,5420,5419 ,0,0,0}, + {13539,13537,13540 ,5423,5421,5424 ,0,0,0}, {13537,13539,13538 ,5421,5423,5422 ,0,0,0}, + {13541,13542,13540 ,5425,5426,5424 ,0,0,0}, {13539,13540,13542 ,5423,5424,5426 ,0,0,0}, + {13541,13543,13544 ,5425,5427,5428 ,0,0,0}, {13544,13542,13541 ,5428,5426,5425 ,0,0,0}, + {13545,13543,13546 ,5429,5427,5430 ,0,0,0}, {13543,13545,13544 ,5427,5429,5428 ,0,0,0}, + {13547,13548,13546 ,5431,5432,5430 ,0,0,0}, {13545,13546,13548 ,5429,5430,5432 ,0,0,0}, + {13547,13549,13550 ,5431,5433,5434 ,0,0,0}, {13550,13548,13547 ,5434,5432,5431 ,0,0,0}, + {13551,13549,13552 ,5435,5433,5436 ,0,0,0}, {13549,13551,13550 ,5433,5435,5434 ,0,0,0}, + {13553,13554,13552 ,5437,5438,5436 ,0,0,0}, {13551,13552,13554 ,5435,5436,5438 ,0,0,0}, + {13553,13555,13556 ,5437,5439,5440 ,0,0,0}, {13556,13554,13553 ,5440,5438,5437 ,0,0,0}, + {13557,13555,13558 ,5441,5439,5442 ,0,0,0}, {13555,13557,13556 ,5439,5441,5440 ,0,0,0}, + {13559,13560,13558 ,5443,5444,5442 ,0,0,0}, {13557,13558,13560 ,5441,5442,5444 ,0,0,0}, + {13559,13561,13562 ,5443,5445,5446 ,0,0,0}, {13562,13560,13559 ,5446,5444,5443 ,0,0,0}, + {13563,13561,13564 ,5447,5445,5448 ,0,0,0}, {13561,13563,13562 ,5445,5447,5446 ,0,0,0}, + {13565,13566,13564 ,5449,5450,5448 ,0,0,0}, {13563,13564,13566 ,5447,5448,5450 ,0,0,0}, + {13565,13567,13568 ,5449,5451,5452 ,0,0,0}, {13568,13566,13565 ,5452,5450,5449 ,0,0,0}, + {13569,13567,13570 ,5453,5451,5454 ,0,0,0}, {13567,13569,13568 ,5451,5453,5452 ,0,0,0}, + {13571,13572,13570 ,5455,5456,5454 ,0,0,0}, {13569,13570,13572 ,5453,5454,5456 ,0,0,0}, + {13571,13573,13574 ,5455,5457,5458 ,0,0,0}, {13574,13572,13571 ,5458,5456,5455 ,0,0,0}, + {13575,13573,13576 ,5459,5457,5460 ,0,0,0}, {13573,13575,13574 ,5457,5459,5458 ,0,0,0}, + {13577,13578,13576 ,5461,5462,5460 ,0,0,0}, {13575,13576,13578 ,5459,5460,5462 ,0,0,0}, + {13577,13579,13580 ,5461,5463,5464 ,0,0,0}, {13580,13578,13577 ,5464,5462,5461 ,0,0,0}, + {13581,13579,13582 ,5465,5463,5466 ,0,0,0}, {13579,13581,13580 ,5463,5465,5464 ,0,0,0}, + {13581,13582,13583 ,5465,5466,5467 ,0,0,0}, {13584,12618,12617 ,5468,5469,5469 ,0,0,0}, + {13585,13586,13587 ,726,726,726 ,0,0,0}, {13588,12351,12348 ,726,5470,726 ,0,0,0}, + {13589,13590,13591 ,5471,726,726 ,0,0,0}, {13592,13593,13594 ,726,726,726 ,0,0,0}, + {13595,12573,13596 ,5468,5471,5469 ,0,0,0}, {13597,13598,13599 ,5470,726,726 ,0,0,0}, + {13600,13601,13602 ,5471,5469,5469 ,0,0,0}, {13603,13602,12546 ,5468,5469,5469 ,0,0,0}, + {13604,13605,12652 ,5469,5472,5468 ,0,0,0}, {13606,13607,13608 ,5469,5468,5471 ,0,0,0}, + {13609,13610,13611 ,5473,5474,726 ,0,0,0}, {13612,13613,13614 ,5475,5476,5471 ,0,0,0}, + {13615,13616,13617 ,5477,5478,5469 ,0,0,0}, {13610,13609,13618 ,5474,5473,5479 ,0,0,0}, + {13619,13620,13621 ,5471,5469,726 ,0,0,0}, {13622,13623,12611 ,5468,5469,5471 ,0,0,0}, + {13624,13625,13626 ,726,5480,5481 ,0,0,0}, {13617,13627,13628 ,5469,726,5468 ,0,0,0}, + {13629,13630,13631 ,5475,5475,5482 ,0,0,0}, {13632,12286,13629 ,5468,5483,5475 ,0,0,0}, + {13631,13633,13634 ,5482,5482,5482 ,0,0,0}, {13630,13633,13631 ,5475,5482,5482 ,0,0,0}, + {13634,13635,13631 ,5482,5475,5482 ,0,0,0}, {13626,13620,13636 ,5481,5469,5475 ,0,0,0}, + {13637,12666,13638 ,726,5471,5484 ,0,0,0}, {13610,13618,13628 ,5474,5479,5468 ,0,0,0}, + {13639,13640,13641 ,5475,5485,5468 ,0,0,0}, {13642,13643,13644 ,5486,5483,5468 ,0,0,0}, + {13627,13610,13628 ,726,5474,5468 ,0,0,0}, {12611,13623,12612 ,5471,5469,726 ,0,0,0}, + {12618,13584,12620 ,5469,5468,726 ,0,0,0}, {12624,12623,13645 ,5471,5471,726 ,0,0,0}, + {12652,12622,13604 ,5468,5468,5469 ,0,0,0}, {12650,12622,12652 ,5471,5468,5468 ,0,0,0}, + {12624,13646,12649 ,5471,5471,5469 ,0,0,0}, {13647,12656,12655 ,5468,5478,726 ,0,0,0}, + {12623,13648,13645 ,5471,726,726 ,0,0,0}, {12579,13649,13650 ,5471,5468,726 ,0,0,0}, + {13651,12666,12664 ,5475,5471,726 ,0,0,0}, {13652,13653,13654 ,5469,5482,5483 ,0,0,0}, + {13655,13653,13656 ,5468,5482,5475 ,0,0,0}, {13657,13658,13659 ,726,5468,5468 ,0,0,0}, + {13660,13608,13661 ,726,5471,5469 ,0,0,0}, {13662,13663,13664 ,5475,5475,726 ,0,0,0}, + {13658,13657,13665 ,5468,726,5483 ,0,0,0}, {13666,13667,13668 ,5480,5487,5475 ,0,0,0}, + {13665,13669,13652 ,5483,5478,5469 ,0,0,0}, {13670,13671,13672 ,5475,5479,5474 ,0,0,0}, + {13672,13638,13670 ,5474,5484,5475 ,0,0,0}, {13673,13674,13672 ,5473,726,5474 ,0,0,0}, + {13673,13672,13671 ,5473,5474,5479 ,0,0,0}, {13655,13654,13653 ,5468,5483,5482 ,0,0,0}, + {13667,13662,13675 ,5487,5475,726 ,0,0,0}, {13653,13652,13669 ,5482,5469,5478 ,0,0,0}, + {13676,13677,13637 ,5486,5478,726 ,0,0,0}, {13660,13661,13659 ,726,5469,5468 ,0,0,0}, + {12576,13649,12579 ,726,5468,5471 ,0,0,0}, {13670,13638,12666 ,5475,5484,5471 ,0,0,0}, + {13678,13679,13680 ,726,726,726 ,0,0,0}, {13681,13682,12582 ,5468,5469,726 ,0,0,0}, + {13651,12664,13683 ,5475,726,5482 ,0,0,0}, {13684,12588,13685 ,726,726,5470 ,0,0,0}, + {12661,13686,13687 ,5475,5485,5475 ,0,0,0}, {13688,13689,12506 ,5471,726,5471 ,0,0,0}, + {12410,13690,12405 ,726,5470,726 ,0,0,0}, {13691,13692,13693 ,5470,5471,5471 ,0,0,0}, + {13694,13695,13696 ,726,726,5470 ,0,0,0}, {13696,13597,13694 ,5470,5470,726 ,0,0,0}, + {13678,13599,13679 ,726,726,726 ,0,0,0}, {13697,13698,13699 ,726,726,5470 ,0,0,0}, + {13591,13691,13693 ,726,5470,5471 ,0,0,0}, {13695,13700,13701 ,726,726,726 ,0,0,0}, + {12590,13702,13703 ,726,5470,726 ,0,0,0}, {13704,13705,13706 ,5470,726,726 ,0,0,0}, + {13679,13599,13598 ,726,726,726 ,0,0,0}, {13702,13707,13708 ,5470,726,5468 ,0,0,0}, + {13679,13709,13680 ,726,726,726 ,0,0,0}, {13708,13710,13711 ,5468,5468,726 ,0,0,0}, + {13707,13710,13708 ,726,5468,5468 ,0,0,0}, {13711,13712,13708 ,726,5471,5468 ,0,0,0}, + {13713,13714,13715 ,726,726,5471 ,0,0,0}, {12590,13707,13702 ,726,726,5470 ,0,0,0}, + {13703,13716,13717 ,726,726,726 ,0,0,0}, {13718,13719,13720 ,726,5488,5489 ,0,0,0}, + {12548,13721,13722 ,5471,5470,726 ,0,0,0}, {12576,13602,13649 ,726,5469,5468 ,0,0,0}, + {13723,12503,12500 ,726,726,5471 ,0,0,0}, {13724,12427,12424 ,726,726,726 ,0,0,0}, + {13725,12360,13726 ,726,5470,726 ,0,0,0}, {13727,12503,13723 ,726,726,726 ,0,0,0}, + {13728,13729,13730 ,726,726,726 ,0,0,0}, {13731,13732,13733 ,5489,726,726 ,0,0,0}, + {12497,13734,12498 ,726,5471,726 ,0,0,0}, {13735,13729,13736 ,726,726,726 ,0,0,0}, + {13737,13738,13739 ,726,726,5489 ,0,0,0}, {13740,13741,13742 ,726,726,726 ,0,0,0}, + {13743,13729,13735 ,726,726,726 ,0,0,0}, {13585,13587,13742 ,726,726,726 ,0,0,0}, + {13744,13745,13746 ,726,726,5489 ,0,0,0}, {13586,13728,13730 ,726,726,726 ,0,0,0}, + {13747,13748,13749 ,726,726,726 ,0,0,0}, {13745,13750,13747 ,726,5488,726 ,0,0,0}, + {13743,13730,13729 ,726,726,726 ,0,0,0}, {13594,13731,12514 ,726,5489,726 ,0,0,0}, + {13751,13752,13753 ,5489,726,726 ,0,0,0}, {13751,13754,13752 ,5489,5488,726 ,0,0,0}, + {13755,13756,13757 ,726,5471,726 ,0,0,0}, {13752,13754,13758 ,726,5488,726 ,0,0,0}, + {13759,13752,13758 ,726,726,726 ,0,0,0}, {13760,12472,13761 ,726,726,726 ,0,0,0}, + {12430,13762,13763 ,726,726,726 ,0,0,0}, {12588,12586,13685 ,726,726,5470 ,0,0,0}, + {13594,12510,13764 ,726,726,726 ,0,0,0}, {13756,13765,13766 ,5471,5471,726 ,0,0,0}, + {13767,12328,13768 ,726,5470,726 ,0,0,0}, {13757,13769,13755 ,726,5471,726 ,0,0,0}, + {12438,13770,13771 ,5489,726,726 ,0,0,0}, {13772,13773,13774 ,726,726,726 ,0,0,0}, + {13775,13776,13774 ,726,5471,726 ,0,0,0}, {13739,13738,13777 ,5489,726,5488 ,0,0,0}, + {13724,13778,12427 ,726,726,726 ,0,0,0}, {13732,13594,13753 ,726,726,726 ,0,0,0}, + {13779,13724,13777 ,726,726,5488 ,0,0,0}, {12354,13780,13781 ,726,5471,726 ,0,0,0}, + {13782,13783,13773 ,726,5488,726 ,0,0,0}, {13774,13784,13785 ,726,5471,726 ,0,0,0}, + {13786,13787,13788 ,726,726,5488 ,0,0,0}, {13789,13790,13786 ,726,726,726 ,0,0,0}, + {13791,13790,13792 ,726,726,726 ,0,0,0}, {13793,12438,13771 ,726,5489,726 ,0,0,0}, + {13794,13774,13795 ,726,726,726 ,0,0,0}, {13771,13770,13796 ,726,726,726 ,0,0,0}, + {13773,13797,13782 ,726,726,726 ,0,0,0}, {13798,13796,13770 ,726,726,726 ,0,0,0}, + {13773,13783,13774 ,726,5488,726 ,0,0,0}, {13798,13799,13796 ,726,5488,726 ,0,0,0}, + {13800,13797,13773 ,726,726,726 ,0,0,0}, {13796,13799,13801 ,726,5488,726 ,0,0,0}, + {13774,13802,13784 ,726,726,5471 ,0,0,0}, {12633,13803,12632 ,5469,5468,5468 ,0,0,0}, + {12633,12638,13804 ,5469,726,726 ,0,0,0}, {13805,12345,13806 ,726,5471,5471 ,0,0,0}, + {13807,12252,13808 ,5470,5468,5468 ,0,0,0}, {12362,13809,13810 ,5470,726,726 ,0,0,0}, + {13811,13812,13813 ,5468,726,5469 ,0,0,0}, {13814,13815,13816 ,5471,5468,726 ,0,0,0}, + {13817,13811,13818 ,5468,5468,726 ,0,0,0}, {13819,13820,13821 ,726,5470,5469 ,0,0,0}, + {13822,13823,13824 ,726,5469,726 ,0,0,0}, {13825,13826,13827 ,5471,5469,726 ,0,0,0}, + {13828,12649,13829 ,726,5469,5470 ,0,0,0}, {13793,13830,13831 ,726,5489,726 ,0,0,0}, + {13774,13776,13832 ,726,5471,726 ,0,0,0}, {13833,12536,12535 ,5468,726,5469 ,0,0,0}, + {13834,13835,13724 ,5470,5471,726 ,0,0,0}, {13588,13836,12351 ,726,726,5470 ,0,0,0}, + {13837,12396,12395 ,5471,726,726 ,0,0,0}, {13838,12638,12636 ,726,726,5468 ,0,0,0}, + {13839,13840,13841 ,726,5470,5471 ,0,0,0}, {13842,13843,13844 ,5471,726,5470 ,0,0,0}, + {13845,13846,13847 ,726,5470,726 ,0,0,0}, {13809,13848,13810 ,726,726,726 ,0,0,0}, + {13848,13809,13849 ,726,726,726 ,0,0,0}, {13810,13840,12362 ,726,5470,5470 ,0,0,0}, + {13848,13849,13850 ,726,726,726 ,0,0,0}, {13822,13816,13815 ,726,726,5468 ,0,0,0}, + {13848,13850,13851 ,726,726,726 ,0,0,0}, {13852,13853,13854 ,5471,5471,5468 ,0,0,0}, + {13820,13827,13821 ,5470,726,5469 ,0,0,0}, {13855,13819,13856 ,726,726,726 ,0,0,0}, + {13857,13858,13826 ,5468,5469,5469 ,0,0,0}, {13826,13825,13857 ,5469,5471,5468 ,0,0,0}, + {13859,13860,13857 ,5471,726,5468 ,0,0,0}, {13857,13860,13858 ,5468,726,5469 ,0,0,0}, + {12656,13861,12658 ,5478,5487,5468 ,0,0,0}, {12590,12588,13684 ,726,726,726 ,0,0,0}, + {13683,12664,12662 ,5482,726,5468 ,0,0,0}, {13682,12585,12582 ,5469,726,726 ,0,0,0}, + {13603,13600,13602 ,5468,5471,5469 ,0,0,0}, {13862,13601,13600 ,5468,5469,5471 ,0,0,0}, + {13607,13606,13863 ,5468,5469,5469 ,0,0,0}, {13601,13862,13864 ,5469,5468,5470 ,0,0,0}, + {13606,13608,13660 ,5469,5471,726 ,0,0,0}, {13863,13864,13865 ,5469,5470,5469 ,0,0,0}, + {13659,13661,13657 ,5468,5469,726 ,0,0,0}, {13665,13652,13658 ,5483,5469,5468 ,0,0,0}, + {13663,13669,13664 ,5475,5478,726 ,0,0,0}, {13669,13665,13664 ,5478,5483,726 ,0,0,0}, + {13676,13666,13677 ,5486,5480,5478 ,0,0,0}, {13667,13663,13662 ,5487,5475,5475 ,0,0,0}, + {13666,13668,13677 ,5480,5475,5478 ,0,0,0}, {13668,13667,13675 ,5475,5487,726 ,0,0,0}, + {13638,13676,13637 ,5484,5486,726 ,0,0,0}, {13651,13670,12666 ,5475,5475,5471 ,0,0,0}, + {13683,12662,13687 ,5482,5468,5475 ,0,0,0}, {13687,12662,12661 ,5475,5468,5475 ,0,0,0}, + {12658,13861,13686 ,5468,5487,5485 ,0,0,0}, {13686,12661,12658 ,5485,5475,5468 ,0,0,0}, + {13647,13861,12656 ,5468,5487,5478 ,0,0,0}, {13605,13647,12655 ,5472,5468,726 ,0,0,0}, + {13829,12649,13646 ,5470,5469,5471 ,0,0,0}, {12652,13605,12655 ,5468,5472,726 ,0,0,0}, + {13866,13867,12632 ,5471,5470,5468 ,0,0,0}, {12629,13867,13868 ,726,5470,726 ,0,0,0}, + {13614,13869,13612 ,5471,5468,5475 ,0,0,0}, {13623,13870,12612 ,5469,5469,726 ,0,0,0}, + {13871,13872,13632 ,5472,5482,5468 ,0,0,0}, {12595,12264,12591 ,5468,5468,5468 ,0,0,0}, + {12272,12270,13811 ,5471,726,5468 ,0,0,0}, {12527,12174,12525 ,5471,726,5469 ,0,0,0}, + {12538,13873,12541 ,5471,726,726 ,0,0,0}, {13723,12500,13589 ,726,5471,5471 ,0,0,0}, + {12194,13874,13875 ,726,726,5470 ,0,0,0}, {13876,13877,12436 ,726,726,726 ,0,0,0}, + {13878,12556,13879 ,726,726,5471 ,0,0,0}, {12171,13880,12168 ,5471,5471,5471 ,0,0,0}, + {12183,13881,13882 ,726,5469,5469 ,0,0,0}, {12522,12635,12641 ,5471,5469,5469 ,0,0,0}, + {12629,12632,13867 ,726,5468,5470 ,0,0,0}, {12645,12523,12641 ,5468,726,5469 ,0,0,0}, + {12635,12179,12636 ,5469,5471,5468 ,0,0,0}, {13838,13804,12638 ,726,726,726 ,0,0,0}, + {13804,13803,12633 ,726,5468,5469 ,0,0,0}, {13803,13866,12632 ,5468,5471,5468 ,0,0,0}, + {12626,12629,13868 ,726,726,726 ,0,0,0}, {12622,12650,13828 ,5468,5471,726 ,0,0,0}, + {12626,13648,12623 ,726,726,5471 ,0,0,0}, {13648,12626,13868 ,726,726,726 ,0,0,0}, + {13645,13646,12624 ,726,5471,5471 ,0,0,0}, {12649,13828,12650 ,5469,726,5471 ,0,0,0}, + {12620,13883,12622 ,726,5468,5468 ,0,0,0}, {13613,13604,13884 ,5476,5469,5468 ,0,0,0}, + {13883,13604,12622 ,5468,5469,5468 ,0,0,0}, {12612,13870,12614 ,726,5469,5470 ,0,0,0}, + {12617,12614,13885 ,5469,5470,726 ,0,0,0}, {13870,13885,12614 ,5469,726,5470 ,0,0,0}, + {13616,13615,13640 ,5478,5477,5485 ,0,0,0}, {12592,12264,13622 ,726,5468,5468 ,0,0,0}, + {12592,13622,12611 ,726,5468,5471 ,0,0,0}, {13886,13887,12284 ,5470,5470,5468 ,0,0,0}, + {12286,13630,13629 ,5483,5475,5475 ,0,0,0}, {13888,12270,12269 ,5468,726,5468 ,0,0,0}, + {13889,12244,13890 ,5469,5468,5471 ,0,0,0}, {12358,13726,12360 ,726,726,5470 ,0,0,0}, + {13891,13892,12320 ,5471,5471,5471 ,0,0,0}, {13893,12408,13894 ,726,726,5471 ,0,0,0}, + {13895,13896,13897 ,5471,5470,5471 ,0,0,0}, {12404,12405,13898 ,726,726,726 ,0,0,0}, + {12348,13765,13588 ,726,5471,726 ,0,0,0}, {13778,13724,13899 ,726,726,726 ,0,0,0}, + {12644,13900,12516 ,726,5468,5469 ,0,0,0}, {12541,13901,12542 ,726,726,5468 ,0,0,0}, + {12510,13594,12512 ,726,726,726 ,0,0,0}, {13689,12509,12506 ,726,5471,5471 ,0,0,0}, + {12470,13590,13589 ,726,726,5471 ,0,0,0}, {13591,13590,13691 ,726,726,5470 ,0,0,0}, + {13700,13713,13701 ,726,726,726 ,0,0,0}, {13715,13902,13692 ,5471,726,5471 ,0,0,0}, + {13693,13692,13902 ,5471,5471,726 ,0,0,0}, {13714,13713,13700 ,726,726,726 ,0,0,0}, + {13714,13902,13715 ,726,726,5471 ,0,0,0}, {13701,13696,13695 ,726,5470,726 ,0,0,0}, + {13597,13599,13694 ,5470,726,726 ,0,0,0}, {13698,13598,13699 ,726,726,5470 ,0,0,0}, + {13598,13597,13699 ,726,5470,5470 ,0,0,0}, {13705,13717,13716 ,726,726,726 ,0,0,0}, + {13697,13706,13903 ,726,726,5471 ,0,0,0}, {13903,13698,13697 ,5471,726,726 ,0,0,0}, + {13705,13704,13717 ,726,5470,726 ,0,0,0}, {13706,13705,13903 ,726,726,5471 ,0,0,0}, + {13702,13716,13703 ,5470,726,726 ,0,0,0}, {13684,13707,12590 ,726,726,726 ,0,0,0}, + {12576,12574,13602 ,726,726,5469 ,0,0,0}, {13685,12586,13904 ,5470,726,5470 ,0,0,0}, + {12585,13682,13904 ,726,5469,5470 ,0,0,0}, {13904,12586,12585 ,5470,726,726 ,0,0,0}, + {13681,12580,13650 ,5468,726,726 ,0,0,0}, {12580,13681,12582 ,726,5468,726 ,0,0,0}, + {12579,13650,12580 ,5471,726,726 ,0,0,0}, {13722,12573,12548 ,726,5471,5471 ,0,0,0}, + {12548,12547,13721 ,5471,5471,5470 ,0,0,0}, {13596,12573,13722 ,5469,5471,726 ,0,0,0}, + {13905,13906,12550 ,5470,5470,726 ,0,0,0}, {13878,12553,12556 ,726,5470,726 ,0,0,0}, + {13906,12547,12550 ,5470,5471,726 ,0,0,0}, {12557,12562,13907 ,726,726,726 ,0,0,0}, + {12557,13908,12556 ,726,5470,726 ,0,0,0}, {13909,12562,12560 ,726,726,5470 ,0,0,0}, + {12449,12451,12188 ,726,726,726 ,0,0,0}, {12565,12446,12559 ,726,726,5471 ,0,0,0}, + {12462,13910,12465 ,726,726,5470 ,0,0,0}, {12536,13911,12538 ,726,5471,5471 ,0,0,0}, + {13912,12294,12297 ,5471,5470,726 ,0,0,0}, {13913,12167,13914 ,726,726,5470 ,0,0,0}, + {12484,12198,13915 ,5471,5470,5470 ,0,0,0}, {13916,13917,12480 ,726,5471,726 ,0,0,0}, + {12174,12527,12173 ,726,5471,726 ,0,0,0}, {12645,12644,12519 ,5468,726,5471 ,0,0,0}, + {12569,12447,12565 ,5470,5471,726 ,0,0,0}, {12460,12459,13918 ,726,726,726 ,0,0,0}, + {12187,12161,12559 ,5470,5471,5471 ,0,0,0}, {13909,13907,12562 ,726,726,726 ,0,0,0}, + {13907,13908,12557 ,726,5470,726 ,0,0,0}, {13908,13879,12556 ,5470,5471,726 ,0,0,0}, + {12553,13905,12550 ,5470,5470,726 ,0,0,0}, {13905,12553,13878 ,5470,5470,726 ,0,0,0}, + {13603,12546,12544 ,5468,5469,726 ,0,0,0}, {13906,13721,12547 ,5470,5470,5471 ,0,0,0}, + {12574,12546,13602 ,726,5469,5469 ,0,0,0}, {13595,12574,12573 ,5468,726,5471 ,0,0,0}, + {13595,12546,12574 ,5468,5469,726 ,0,0,0}, {12544,12542,13901 ,726,5468,726 ,0,0,0}, + {12544,13901,13603 ,726,726,5468 ,0,0,0}, {12541,13873,13901 ,726,726,726 ,0,0,0}, + {12538,13911,13873 ,5471,5471,726 ,0,0,0}, {12535,13900,13833 ,5469,5468,5468 ,0,0,0}, + {12536,13833,13911 ,726,5468,5471 ,0,0,0}, {12516,12515,12644 ,5469,5468,726 ,0,0,0}, + {12535,12516,13900 ,5469,5469,5468 ,0,0,0}, {12519,12523,12645 ,5471,726,5468 ,0,0,0}, + {12515,12519,12644 ,5468,5471,726 ,0,0,0}, {12523,12522,12641 ,726,5471,5469 ,0,0,0}, + {12174,12177,12525 ,726,726,5469 ,0,0,0}, {12173,12527,12529 ,726,5471,5470 ,0,0,0}, + {13880,13914,12168 ,5471,5470,5471 ,0,0,0}, {12171,12173,12529 ,5471,726,5470 ,0,0,0}, + {13913,13909,12165 ,726,726,5470 ,0,0,0}, {12568,13919,12440 ,5470,5470,726 ,0,0,0}, + {12465,13920,12466 ,5470,5470,5470 ,0,0,0}, {13877,12438,12436 ,726,5489,726 ,0,0,0}, + {13763,12433,12430 ,726,726,726 ,0,0,0}, {13921,13777,13724 ,5489,5488,726 ,0,0,0}, + {13777,13921,13739 ,5488,5489,5489 ,0,0,0}, {13740,13718,13741 ,726,726,726 ,0,0,0}, + {13720,13922,13737 ,5489,726,726 ,0,0,0}, {13738,13737,13922 ,726,726,726 ,0,0,0}, + {13719,13718,13740 ,5488,726,726 ,0,0,0}, {13719,13922,13720 ,5488,726,5489 ,0,0,0}, + {13741,13585,13742 ,726,726,726 ,0,0,0}, {13586,13730,13587 ,726,726,726 ,0,0,0}, + {13746,13728,13744 ,5489,726,726 ,0,0,0}, {13728,13586,13744 ,726,726,726 ,0,0,0}, + {13732,13749,13733 ,726,726,726 ,0,0,0}, {13747,13746,13745 ,726,5489,726 ,0,0,0}, + {13749,13748,13733 ,726,726,726 ,0,0,0}, {13748,13747,13750 ,726,726,5488 ,0,0,0}, + {13732,13731,13594 ,726,5489,726 ,0,0,0}, {13753,13594,13751 ,726,726,5489 ,0,0,0}, + {12500,12498,13589 ,5471,726,5471 ,0,0,0}, {13594,13764,13592 ,726,726,726 ,0,0,0}, + {12509,13689,13764 ,5471,726,726 ,0,0,0}, {13764,12510,12509 ,726,726,5471 ,0,0,0}, + {13688,12504,13727 ,5471,726,726 ,0,0,0}, {12504,13688,12506 ,726,5471,5471 ,0,0,0}, + {12503,13727,12504 ,726,726,726 ,0,0,0}, {13923,12472,13760 ,5471,726,726 ,0,0,0}, + {12472,12471,13761 ,726,726,726 ,0,0,0}, {12497,12472,13923 ,726,726,5471 ,0,0,0}, + {13924,13925,12474 ,726,726,726 ,0,0,0}, {13917,12477,12480 ,5471,726,726 ,0,0,0}, + {13925,12471,12474 ,726,726,726 ,0,0,0}, {12481,12486,13926 ,726,726,726 ,0,0,0}, + {12481,13927,12480 ,726,5471,726 ,0,0,0}, {13915,12486,12484 ,5470,726,5471 ,0,0,0}, + {12203,12370,12373 ,5471,5471,726 ,0,0,0}, {12489,12370,12483 ,726,5471,726 ,0,0,0}, + {13928,12198,12197 ,5471,5470,726 ,0,0,0}, {12462,12460,13929 ,726,726,726 ,0,0,0}, + {12203,12200,12483 ,5471,726,726 ,0,0,0}, {12384,13930,12386 ,726,5470,726 ,0,0,0}, + {12291,12417,12416 ,5470,726,726 ,0,0,0}, {12404,13931,12401 ,726,726,5471 ,0,0,0}, + {12451,12191,12188 ,726,726,726 ,0,0,0}, {12569,12568,12443 ,5470,5470,726 ,0,0,0}, + {12493,12371,12489 ,5471,726,726 ,0,0,0}, {13893,12410,12408 ,726,726,726 ,0,0,0}, + {12483,12200,12484 ,726,726,5471 ,0,0,0}, {13915,13926,12486 ,5470,726,726 ,0,0,0}, + {13926,13927,12481 ,726,5471,726 ,0,0,0}, {13927,13916,12480 ,5471,726,726 ,0,0,0}, + {12477,13924,12474 ,726,726,726 ,0,0,0}, {13924,12477,13917 ,726,726,5471 ,0,0,0}, + {13932,12470,12468 ,5470,726,726 ,0,0,0}, {13925,13761,12471 ,726,726,726 ,0,0,0}, + {12498,12470,13589 ,726,726,5471 ,0,0,0}, {12470,12498,13734 ,726,726,5471 ,0,0,0}, + {13923,13734,12497 ,5471,5471,726 ,0,0,0}, {12470,13932,13590 ,726,5470,726 ,0,0,0}, + {12468,12466,13920 ,726,5470,5470 ,0,0,0}, {12468,13920,13932 ,726,5470,5470 ,0,0,0}, + {12465,13910,13920 ,5470,726,5470 ,0,0,0}, {12462,13929,13910 ,726,726,726 ,0,0,0}, + {12459,13919,13918 ,726,5470,726 ,0,0,0}, {12460,13918,13929 ,726,726,726 ,0,0,0}, + {12440,12439,12568 ,726,5470,5470 ,0,0,0}, {12459,12440,13919 ,726,726,5470 ,0,0,0}, + {12443,12447,12569 ,726,5471,5470 ,0,0,0}, {12439,12443,12568 ,5470,726,5470 ,0,0,0}, + {12447,12446,12565 ,5471,726,726 ,0,0,0}, {12188,12187,12449 ,726,5470,726 ,0,0,0}, + {12191,12453,12192 ,726,726,5471 ,0,0,0}, {12194,12192,13874 ,726,5471,726 ,0,0,0}, + {12451,12453,12191 ,726,726,726 ,0,0,0}, {13915,12198,13928 ,5470,5470,5471 ,0,0,0}, + {12434,13876,12436 ,5488,726,726 ,0,0,0}, {12636,12181,13838 ,5468,5470,726 ,0,0,0}, + {12360,13725,12362 ,5470,726,5470 ,0,0,0}, {13781,12357,12354 ,726,726,726 ,0,0,0}, + {13765,13933,13766 ,5471,726,726 ,0,0,0}, {13756,13766,13757 ,5471,726,726 ,0,0,0}, + {13802,13934,13769 ,726,5471,5471 ,0,0,0}, {13755,13769,13934 ,726,5471,5471 ,0,0,0}, + {13774,13832,13802 ,726,726,726 ,0,0,0}, {13832,13934,13802 ,726,5471,726 ,0,0,0}, + {13785,13795,13774 ,726,726,726 ,0,0,0}, {13935,13775,13774 ,726,726,726 ,0,0,0}, + {13772,13774,13787 ,726,726,726 ,0,0,0}, {13788,13787,13774 ,5488,726,726 ,0,0,0}, + {13830,13791,13831 ,5489,726,726 ,0,0,0}, {13790,13787,13786 ,726,726,726 ,0,0,0}, + {13791,13792,13831 ,726,726,726 ,0,0,0}, {13792,13790,13789 ,726,726,726 ,0,0,0}, + {13771,13830,13793 ,726,5489,726 ,0,0,0}, {13877,13770,12438 ,726,726,5489 ,0,0,0}, + {12422,12421,13724 ,726,5471,726 ,0,0,0}, {12433,13936,12434 ,726,726,5488 ,0,0,0}, + {13876,12434,13936 ,726,5488,726 ,0,0,0}, {13762,12428,13778 ,726,726,726 ,0,0,0}, + {13763,13936,12433 ,726,726,726 ,0,0,0}, {12428,13762,12430 ,726,726,726 ,0,0,0}, + {12427,13778,12428 ,726,726,726 ,0,0,0}, {13834,13724,13937 ,5470,726,5471 ,0,0,0}, + {13937,12396,13837 ,5471,726,5471 ,0,0,0}, {13937,13724,12396 ,5471,726,726 ,0,0,0}, + {12398,13938,12395 ,5471,726,726 ,0,0,0}, {12404,13939,13931 ,726,726,726 ,0,0,0}, + {12398,13940,13938 ,5471,726,726 ,0,0,0}, {13941,12389,12386 ,5471,726,726 ,0,0,0}, + {12389,13942,12390 ,726,726,726 ,0,0,0}, {13943,12384,12383 ,726,726,5471 ,0,0,0}, + {12492,13944,12364 ,5471,5471,5471 ,0,0,0}, {12367,12493,12492 ,726,5471,5471 ,0,0,0}, + {12203,12483,12370 ,5471,726,5471 ,0,0,0}, {13945,13946,13947 ,5470,726,726 ,0,0,0}, + {13948,12210,12380 ,726,5470,5471 ,0,0,0}, {12416,13949,12288 ,726,726,726 ,0,0,0}, + {13950,12314,12313 ,5471,5470,5471 ,0,0,0}, {12313,12310,13951 ,5471,726,726 ,0,0,0}, + {12413,12294,12407 ,726,5470,726 ,0,0,0}, {12206,12373,12375 ,5471,726,726 ,0,0,0}, + {12417,12295,12413 ,726,5471,726 ,0,0,0}, {12307,13952,12308 ,726,726,5471 ,0,0,0}, + {12407,13953,12408 ,726,726,726 ,0,0,0}, {13893,13690,12410 ,726,5470,726 ,0,0,0}, + {13690,13898,12405 ,5470,726,726 ,0,0,0}, {13898,13939,12404 ,726,726,726 ,0,0,0}, + {12401,13940,12398 ,5471,726,5471 ,0,0,0}, {13940,12401,13931 ,726,5471,726 ,0,0,0}, + {13942,13954,12392 ,726,726,726 ,0,0,0}, {12392,13954,13724 ,726,726,726 ,0,0,0}, + {13938,13837,12395 ,726,5471,726 ,0,0,0}, {12424,12422,13724 ,726,726,726 ,0,0,0}, + {13724,12421,12396 ,726,5471,726 ,0,0,0}, {12394,13724,13835 ,5471,726,5471 ,0,0,0}, + {13954,13921,13724 ,726,5489,726 ,0,0,0}, {12392,12390,13942 ,726,726,726 ,0,0,0}, + {12389,13941,13942 ,726,5471,726 ,0,0,0}, {12386,13930,13941 ,726,5470,5471 ,0,0,0}, + {12383,13944,13943 ,5471,5471,726 ,0,0,0}, {12384,13943,13930 ,726,726,5470 ,0,0,0}, + {12364,12363,12492 ,5471,726,5471 ,0,0,0}, {12383,12364,13944 ,5471,5471,5471 ,0,0,0}, + {12367,12371,12493 ,726,726,5471 ,0,0,0}, {12363,12367,12492 ,726,726,5471 ,0,0,0}, + {12371,12370,12489 ,726,5471,726 ,0,0,0}, {12206,12203,12373 ,5471,5471,726 ,0,0,0}, + {12206,12375,12209 ,5471,726,726 ,0,0,0}, {12377,12210,12209 ,726,5470,726 ,0,0,0}, + {12377,12209,12375 ,726,726,726 ,0,0,0}, {12377,12380,12210 ,726,5471,5470 ,0,0,0}, + {13955,12253,12258 ,5468,5469,5470 ,0,0,0}, {13811,13823,13818 ,5468,5469,726 ,0,0,0}, + {12598,12261,12599 ,5468,5471,5469 ,0,0,0}, {12281,12278,13811 ,5469,5471,5468 ,0,0,0}, + {12242,13824,13823 ,5469,726,5469 ,0,0,0}, {13822,13824,13816 ,726,726,726 ,0,0,0}, + {13856,13853,13855 ,726,5471,726 ,0,0,0}, {13852,13956,13814 ,5471,5468,5471 ,0,0,0}, + {13815,13814,13956 ,5468,5471,5468 ,0,0,0}, {13854,13853,13856 ,5468,5471,726 ,0,0,0}, + {13854,13956,13852 ,5468,5468,5471 ,0,0,0}, {13855,13820,13819 ,726,5470,726 ,0,0,0}, + {13827,13826,13821 ,726,5469,5469 ,0,0,0}, {13846,13825,13847 ,5470,5471,726 ,0,0,0}, + {13825,13827,13847 ,5471,726,726 ,0,0,0}, {13843,13839,13841 ,726,726,5471 ,0,0,0}, + {13845,13844,13957 ,726,5470,726 ,0,0,0}, {13957,13846,13845 ,726,5470,726 ,0,0,0}, + {13843,13842,13839 ,726,5471,726 ,0,0,0}, {13844,13843,13957 ,5470,726,726 ,0,0,0}, + {13810,13841,13840 ,726,5471,5470 ,0,0,0}, {13725,13809,12362 ,726,726,5470 ,0,0,0}, + {12348,12346,13765 ,726,5470,5471 ,0,0,0}, {12357,13958,12358 ,726,726,726 ,0,0,0}, + {13726,12358,13958 ,726,726,726 ,0,0,0}, {13780,12352,13836 ,5471,5470,726 ,0,0,0}, + {13781,13958,12357 ,726,726,726 ,0,0,0}, {12352,13780,12354 ,5470,5471,726 ,0,0,0}, + {12351,13836,12352 ,5470,726,5470 ,0,0,0}, {13892,12345,12320 ,5471,5471,5471 ,0,0,0}, + {12320,12319,13891 ,5471,726,5471 ,0,0,0}, {13806,12345,13892 ,5471,5471,5471 ,0,0,0}, + {13959,13960,12322 ,5471,726,726 ,0,0,0}, {13767,12325,12328 ,726,5470,5470 ,0,0,0}, + {13960,12319,12322 ,726,726,726 ,0,0,0}, {12329,12334,13961 ,5470,726,726 ,0,0,0}, + {12329,13962,12328 ,5470,726,5470 ,0,0,0}, {13963,12334,12332 ,726,726,726 ,0,0,0}, + {12221,12223,13964 ,726,5471,5471 ,0,0,0}, {12308,13965,12310 ,5471,726,726 ,0,0,0}, + {13966,13967,13968 ,5471,726,726 ,0,0,0}, {12256,13966,13969 ,5471,5471,5471 ,0,0,0}, + {13838,12181,13970 ,726,5470,5469 ,0,0,0}, {12598,12601,13971 ,5468,5468,5470 ,0,0,0}, + {12237,13972,12238 ,726,726,5471 ,0,0,0}, {12256,13969,12258 ,5471,5471,5470 ,0,0,0}, + {12337,12218,12331 ,726,5470,5470 ,0,0,0}, {12299,13973,13974 ,5470,5471,726 ,0,0,0}, + {12341,12219,12337 ,726,5471,726 ,0,0,0}, {13975,13964,12223 ,5471,5471,5471 ,0,0,0}, + {13976,13977,12331 ,726,5471,5470 ,0,0,0}, {13963,13961,12334 ,726,726,726 ,0,0,0}, + {13961,13962,12329 ,726,726,5470 ,0,0,0}, {13962,13768,12328 ,726,726,5470 ,0,0,0}, + {12325,13959,12322 ,5470,5471,726 ,0,0,0}, {13959,12325,13767 ,5471,5470,726 ,0,0,0}, + {12316,13950,13933 ,5471,5471,726 ,0,0,0}, {13933,12318,12316 ,726,726,5471 ,0,0,0}, + {13960,13891,12319 ,726,5471,726 ,0,0,0}, {12346,12318,13765 ,5470,726,5471 ,0,0,0}, + {13805,12346,12345 ,726,5470,5471 ,0,0,0}, {13805,12318,12346 ,726,726,5470 ,0,0,0}, + {13765,12318,13933 ,5471,726,726 ,0,0,0}, {12316,12314,13950 ,5471,5470,5471 ,0,0,0}, + {12313,13951,13950 ,5471,726,5471 ,0,0,0}, {12310,13965,13951 ,726,726,726 ,0,0,0}, + {12307,13949,13952 ,726,726,726 ,0,0,0}, {12308,13952,13965 ,5471,726,726 ,0,0,0}, + {12288,12287,12416 ,726,5471,726 ,0,0,0}, {12307,12288,13949 ,726,726,726 ,0,0,0}, + {12291,12295,12417 ,5470,5471,726 ,0,0,0}, {12287,12291,12416 ,5471,5470,726 ,0,0,0}, + {12295,12294,12413 ,5471,5470,726 ,0,0,0}, {13974,13912,12297 ,726,5471,726 ,0,0,0}, + {12407,12294,13912 ,726,5470,5471 ,0,0,0}, {12304,13978,13979 ,726,726,726 ,0,0,0}, + {13973,12301,13979 ,5471,726,726 ,0,0,0}, {13980,13981,13982 ,5470,5470,5471 ,0,0,0}, + {12284,13887,12286 ,5468,5470,5483 ,0,0,0}, {12592,12591,12264 ,726,5468,5468 ,0,0,0}, + {12284,12282,13886 ,5468,5469,5470 ,0,0,0}, {12620,13584,13883 ,726,5468,5468 ,0,0,0}, + {12617,13885,13584 ,5469,726,5468 ,0,0,0}, {13883,13884,13604 ,5468,5468,5469 ,0,0,0}, + {13613,13884,13614 ,5476,5468,5471 ,0,0,0}, {13641,13644,13639 ,5468,5468,5475 ,0,0,0}, + {13643,13983,13869 ,5483,726,5468 ,0,0,0}, {13612,13869,13983 ,5475,5468,726 ,0,0,0}, + {13642,13644,13641 ,5486,5468,5468 ,0,0,0}, {13642,13983,13643 ,5486,726,5483 ,0,0,0}, + {13639,13616,13640 ,5475,5478,5485 ,0,0,0}, {13617,13628,13615 ,5469,5468,5477 ,0,0,0}, + {13621,13627,13619 ,726,726,5471 ,0,0,0}, {13627,13617,13619 ,726,5469,5471 ,0,0,0}, + {13871,13625,13872 ,5472,5480,5482 ,0,0,0}, {13626,13621,13620 ,5481,726,5469 ,0,0,0}, + {13625,13624,13872 ,5480,726,5482 ,0,0,0}, {13624,13626,13636 ,726,5481,5475 ,0,0,0}, + {13629,13871,13632 ,5475,5472,5468 ,0,0,0}, {13887,13630,12286 ,5470,5475,5483 ,0,0,0}, + {13811,12270,13888 ,5468,726,5468 ,0,0,0}, {12281,13813,12282 ,5469,5469,5469 ,0,0,0}, + {13886,12282,13813 ,5470,5469,5469 ,0,0,0}, {13984,13812,13811 ,5468,726,5468 ,0,0,0}, + {13813,12281,13811 ,5469,5469,5468 ,0,0,0}, {13811,12278,12276 ,5468,5471,5470 ,0,0,0}, + {13811,12275,12272 ,5468,5469,5471 ,0,0,0}, {13985,12244,13889 ,5469,5468,5469 ,0,0,0}, + {12244,12243,13890 ,5468,5471,5471 ,0,0,0}, {12269,12244,13985 ,5468,5468,5469 ,0,0,0}, + {13986,13987,12246 ,5470,5471,5468 ,0,0,0}, {13807,12249,12252 ,5470,726,5468 ,0,0,0}, + {13987,12243,12246 ,5471,5471,5468 ,0,0,0}, {12601,12603,13988 ,5468,5468,5468 ,0,0,0}, + {12215,12341,12340 ,5471,726,726 ,0,0,0}, {12253,13989,12252 ,5469,5469,5468 ,0,0,0}, + {13990,12232,12231 ,726,5471,726 ,0,0,0}, {13991,12237,12234 ,726,726,5470 ,0,0,0}, + {13992,12212,12340 ,726,5470,726 ,0,0,0}, {13993,12234,12232 ,726,5470,5471 ,0,0,0}, + {12598,12255,12261 ,5468,5469,5471 ,0,0,0}, {12601,13988,13971 ,5468,5468,5470 ,0,0,0}, + {12261,12265,12599 ,5471,726,5469 ,0,0,0}, {12264,12595,12265 ,5468,5468,726 ,0,0,0}, + {12599,12265,12595 ,5469,726,5468 ,0,0,0}, {12180,13882,13970 ,5469,5469,5469 ,0,0,0}, + {12605,12185,13994 ,5471,5470,726 ,0,0,0}, {12185,13881,12183 ,5470,5469,726 ,0,0,0}, + {12255,13995,12256 ,5469,5471,5471 ,0,0,0}, {13969,13955,12258 ,5471,5468,5470 ,0,0,0}, + {13955,13989,12253 ,5468,5469,5469 ,0,0,0}, {13989,13808,12252 ,5469,5468,5468 ,0,0,0}, + {12249,13986,12246 ,726,5470,5468 ,0,0,0}, {13986,12249,13807 ,5470,726,5470 ,0,0,0}, + {12240,13972,13996 ,726,726,5471 ,0,0,0}, {13996,12242,12240 ,5471,5469,726 ,0,0,0}, + {13987,13890,12243 ,5471,5471,5471 ,0,0,0}, {12242,13823,13811 ,5469,5469,5468 ,0,0,0}, + {13811,13888,12242 ,5468,5468,5469 ,0,0,0}, {13985,13888,12269 ,5469,5468,5468 ,0,0,0}, + {12242,13996,13824 ,5469,5471,726 ,0,0,0}, {12240,12238,13972 ,726,5471,726 ,0,0,0}, + {12237,13991,13972 ,726,726,726 ,0,0,0}, {12234,13993,13991 ,5470,726,726 ,0,0,0}, + {12231,13992,13990 ,726,726,726 ,0,0,0}, {12232,13990,13993 ,5471,726,726 ,0,0,0}, + {12212,12211,12340 ,5470,726,726 ,0,0,0}, {12231,12212,13992 ,726,5470,726 ,0,0,0}, + {12215,12219,12341 ,5471,5471,726 ,0,0,0}, {12211,12215,12340 ,726,5471,726 ,0,0,0}, + {12219,12218,12337 ,5471,5470,726 ,0,0,0}, {13964,13976,12221 ,5471,726,726 ,0,0,0}, + {13975,12225,13997 ,5471,726,726 ,0,0,0}, {13895,13997,13896 ,5471,726,5470 ,0,0,0}, + {12223,12225,13975 ,5471,726,5471 ,0,0,0}, {13969,13966,13968 ,5471,5471,726 ,0,0,0}, + {13963,12332,13998 ,726,726,5471 ,0,0,0}, {13909,12560,12165 ,726,5470,5470 ,0,0,0}, + {13963,13998,13980 ,726,5471,5470 ,0,0,0}, {12200,12198,12484 ,726,5470,5471 ,0,0,0}, + {12194,13875,12197 ,726,5470,726 ,0,0,0}, {13928,12197,13875 ,5471,726,5470 ,0,0,0}, + {12560,12559,12161 ,5470,5471,5471 ,0,0,0}, {12456,12192,12453 ,726,5471,726 ,0,0,0}, + {12456,13874,12192 ,726,726,5471 ,0,0,0}, {12187,12559,12446 ,5470,5471,726 ,0,0,0}, + {12446,12449,12187 ,726,726,5470 ,0,0,0}, {12560,12161,12165 ,5470,5471,5470 ,0,0,0}, + {13913,12165,12167 ,726,5470,726 ,0,0,0}, {12179,12635,12177 ,5471,5469,726 ,0,0,0}, + {13914,12167,12168 ,5470,726,5471 ,0,0,0}, {12532,12171,12529 ,726,5471,5470 ,0,0,0}, + {12532,13880,12171 ,726,5471,5471 ,0,0,0}, {12635,12522,12177 ,5469,5471,726 ,0,0,0}, + {12522,12525,12177 ,5471,5469,726 ,0,0,0}, {12179,12181,12636 ,5471,5470,5468 ,0,0,0}, + {13970,12181,12180 ,5469,5470,5469 ,0,0,0}, {13995,12255,13971 ,5471,5469,5470 ,0,0,0}, + {13882,12180,12183 ,5469,5469,726 ,0,0,0}, {12608,12185,12605 ,5469,5470,5471 ,0,0,0}, + {12608,13881,12185 ,5469,5469,5470 ,0,0,0}, {13971,12255,12598 ,5470,5469,5468 ,0,0,0}, + {13994,13988,12603 ,726,5468,5468 ,0,0,0}, {13994,12603,12605 ,726,5468,5471 ,0,0,0}, + {13995,13966,12256 ,5471,5471,5471 ,0,0,0}, {13895,13897,13967 ,5471,5471,726 ,0,0,0}, + {13968,13967,13897 ,726,726,5471 ,0,0,0}, {12332,12331,13977 ,726,5470,5471 ,0,0,0}, + {12228,13997,12225 ,726,726,726 ,0,0,0}, {12228,13896,13997 ,726,5470,726 ,0,0,0}, + {13976,12331,12218 ,726,5470,5470 ,0,0,0}, {12218,12221,13976 ,5470,726,726 ,0,0,0}, + {12332,13977,13998 ,726,5471,5471 ,0,0,0}, {13982,13981,13999 ,5471,5470,726 ,0,0,0}, + {13980,13998,13981 ,5470,5471,5470 ,0,0,0}, {13999,13979,13978 ,726,726,726 ,0,0,0}, + {13978,13982,13999 ,726,5471,726 ,0,0,0}, {13979,12301,12304 ,726,726,726 ,0,0,0}, + {13973,12299,12301 ,5471,5470,726 ,0,0,0}, {13974,12297,12299 ,726,726,5470 ,0,0,0}, + {12407,13912,13953 ,726,5471,726 ,0,0,0}, {13894,14000,13893 ,5471,5471,726 ,0,0,0}, + {12408,13953,13894 ,726,726,5471 ,0,0,0}, {13946,14000,13947 ,726,5471,726 ,0,0,0}, + {13894,13947,14000 ,5471,726,5471 ,0,0,0}, {13946,13945,13948 ,726,5470,726 ,0,0,0}, + {12210,13948,13945 ,5470,726,5470 ,0,0,0}, {13984,13811,13817 ,5468,5468,5468 ,0,0,0}, + {12276,12275,13811 ,5470,5469,5468 ,0,0,0}, {13774,13794,13788 ,726,726,5488 ,0,0,0}, + {13783,13935,13774 ,5488,726,726 ,0,0,0}, {13724,12394,12392 ,726,5471,726 ,0,0,0}, + {13899,13724,13779 ,726,726,726 ,0,0,0}, {13865,13864,13862 ,5469,5470,5468 ,0,0,0}, + {13865,13607,13863 ,5469,5468,5469 ,0,0,0}, {13751,13594,13593 ,5489,726,726 ,0,0,0}, + {12514,12512,13594 ,726,726,726 ,0,0,0}, {14001,14002,14003 ,5490,5491,5492 ,0,0,0}, + {14004,14005,14006 ,5493,5494,5495 ,0,0,0}, {14007,14005,14008 ,5496,5494,5497 ,0,0,0}, + {14009,14010,14011 ,5498,5499,5500 ,0,0,0}, {14012,14013,14014 ,5501,5502,5503 ,0,0,0}, + {14015,14016,14017 ,5504,5505,5506 ,0,0,0}, {14018,14019,14020 ,5507,5508,5509 ,0,0,0}, + {13631,13635,14015 ,5510,5511,5504 ,0,0,0}, {14021,14022,14023 ,5512,5513,5514 ,0,0,0}, + {14012,14017,14016 ,5501,5506,5505 ,0,0,0}, {14024,14025,14022 ,5515,5516,5513 ,0,0,0}, + {14026,14024,14022 ,5517,5515,5513 ,0,0,0}, {14026,14027,14024 ,5517,5518,5515 ,0,0,0}, + {14027,14026,14028 ,5518,5517,5519 ,0,0,0}, {14029,14025,14030 ,5520,5516,5521 ,0,0,0}, + {14031,14032,14033 ,5522,5523,5524 ,0,0,0}, {14022,14025,14029 ,5513,5516,5520 ,0,0,0}, + {14033,14032,14028 ,5524,5523,5519 ,0,0,0}, {14034,14031,14035 ,5525,5522,5526 ,0,0,0}, + {14036,14037,14038 ,5527,5528,5529 ,0,0,0}, {14036,14029,14030 ,5527,5520,5521 ,0,0,0}, + {14039,14040,14041 ,5530,5531,5532 ,0,0,0}, {14036,14030,14037 ,5527,5521,5528 ,0,0,0}, + {14037,14039,14038 ,5528,5530,5529 ,0,0,0}, {14042,14043,14041 ,5533,5534,5532 ,0,0,0}, + {14019,14044,14020 ,5508,5535,5509 ,0,0,0}, {14041,14040,14042 ,5532,5531,5533 ,0,0,0}, + {14045,14004,14046 ,5536,5493,5537 ,0,0,0}, {14040,14047,14042 ,5531,5538,5533 ,0,0,0}, + {14019,14023,14044 ,5508,5514,5535 ,0,0,0}, {14048,14023,14029 ,5539,5514,5520 ,0,0,0}, + {14049,14050,14051 ,5540,5541,5542 ,0,0,0}, {14052,14049,14053 ,5543,5540,5544 ,0,0,0}, + {13610,13627,14002 ,5545,5546,5491 ,0,0,0}, {14054,14055,14056 ,5547,5548,5549 ,0,0,0}, + {13610,14001,13611 ,5545,5490,726 ,0,0,0}, {14057,13611,14001 ,5550,726,5490 ,0,0,0}, + {14058,14043,14059 ,5551,5534,5552 ,0,0,0}, {14039,14041,14038 ,5530,5532,5529 ,0,0,0}, + {14041,14043,14058 ,5532,5534,5551 ,0,0,0}, {14059,14060,14058 ,5552,5553,5551 ,0,0,0}, + {14061,14038,14058 ,5554,5529,5551 ,0,0,0}, {14023,14048,14044 ,5514,5539,5535 ,0,0,0}, + {14061,14048,14036 ,5554,5539,5527 ,0,0,0}, {14026,14062,14028 ,5517,5555,5519 ,0,0,0}, + {14036,14048,14029 ,5527,5539,5520 ,0,0,0}, {14063,14064,14033 ,5556,5557,5524 ,0,0,0}, + {14022,14029,14023 ,5513,5520,5514 ,0,0,0}, {14062,14026,14021 ,5555,5517,5512 ,0,0,0}, + {14031,14033,14035 ,5522,5524,5526 ,0,0,0}, {14027,14028,14032 ,5518,5519,5523 ,0,0,0}, + {14028,14062,14063 ,5519,5555,5556 ,0,0,0}, {14065,14035,14033 ,5558,5526,5524 ,0,0,0}, + {14041,14058,14038 ,5532,5551,5529 ,0,0,0}, {14066,14060,14059 ,5559,5553,5552 ,0,0,0}, + {14066,14053,14060 ,5559,5544,5553 ,0,0,0}, {14038,14061,14036 ,5529,5554,5527 ,0,0,0}, + {14060,14067,14061 ,5553,5560,5554 ,0,0,0}, {14019,14008,14021 ,5508,5497,5512 ,0,0,0}, + {14067,14044,14048 ,5560,5535,5539 ,0,0,0}, {14004,14064,14063 ,5493,5557,5556 ,0,0,0}, + {14045,14064,14004 ,5536,5557,5493 ,0,0,0}, {14022,14021,14026 ,5513,5512,5517 ,0,0,0}, + {14023,14019,14021 ,5514,5508,5512 ,0,0,0}, {14028,14063,14033 ,5519,5556,5524 ,0,0,0}, + {14008,14005,14062 ,5497,5494,5555 ,0,0,0}, {14033,14064,14065 ,5524,5557,5558 ,0,0,0}, + {14063,14005,14004 ,5556,5494,5493 ,0,0,0}, {14068,14065,14064 ,5561,5558,5557 ,0,0,0}, + {14058,14060,14061 ,5551,5553,5554 ,0,0,0}, {14052,14053,14066 ,5543,5544,5559 ,0,0,0}, + {14069,14051,14070 ,5562,5542,5563 ,0,0,0}, {14061,14067,14048 ,5554,5560,5539 ,0,0,0}, + {14071,14067,14053 ,5564,5560,5544 ,0,0,0}, {14008,14019,14018 ,5497,5508,5507 ,0,0,0}, + {14071,14020,14044 ,5564,5509,5535 ,0,0,0}, {14072,14046,14006 ,5565,5537,5495 ,0,0,0}, + {14062,14005,14063 ,5555,5494,5556 ,0,0,0}, {14021,14008,14062 ,5512,5497,5555 ,0,0,0}, + {14008,14018,14007 ,5497,5507,5496 ,0,0,0}, {14045,14046,14073 ,5536,5537,5566 ,0,0,0}, + {14007,14006,14005 ,5496,5495,5494 ,0,0,0}, {14064,14045,14068 ,5557,5536,5561 ,0,0,0}, + {14004,14006,14046 ,5493,5495,5537 ,0,0,0}, {14074,14068,14045 ,5567,5561,5536 ,0,0,0}, + {14060,14053,14067 ,5553,5544,5560 ,0,0,0}, {14050,14049,14052 ,5541,5540,5543 ,0,0,0}, + {14020,14075,14018 ,5509,5568,5507 ,0,0,0}, {14067,14071,14044 ,5560,5564,5535 ,0,0,0}, + {14076,14071,14049 ,5569,5564,5540 ,0,0,0}, {14018,14077,14007 ,5507,5570,5496 ,0,0,0}, + {14076,14075,14020 ,5569,5568,5509 ,0,0,0}, {14007,14078,14006 ,5496,5571,5495 ,0,0,0}, + {14077,14018,14075 ,5570,5507,5568 ,0,0,0}, {14046,14009,14073 ,5537,5498,5566 ,0,0,0}, + {14078,14007,14077 ,5571,5496,5570 ,0,0,0}, {14079,14073,14011 ,5572,5566,5500 ,0,0,0}, + {14072,14006,14078 ,5565,5495,5571 ,0,0,0}, {14045,14073,14074 ,5536,5566,5567 ,0,0,0}, + {14046,14072,14009 ,5537,5565,5498 ,0,0,0}, {14079,14074,14073 ,5572,5567,5566 ,0,0,0}, + {14053,14049,14071 ,5544,5540,5564 ,0,0,0}, {14070,14051,14050 ,5563,5542,5541 ,0,0,0}, + {14075,14055,14077 ,5568,5548,5570 ,0,0,0}, {14071,14076,14020 ,5564,5569,5509 ,0,0,0}, + {14051,14080,14076 ,5542,5573,5569 ,0,0,0}, {14077,14054,14078 ,5570,5547,5571 ,0,0,0}, + {14080,14055,14075 ,5573,5548,5568 ,0,0,0}, {14078,14081,14072 ,5571,5574,5565 ,0,0,0}, + {14055,14054,14077 ,5548,5547,5570 ,0,0,0}, {14082,14009,14072 ,5575,5498,5565 ,0,0,0}, + {14081,14078,14054 ,5574,5571,5547 ,0,0,0}, {14083,14011,14014 ,5576,5500,5503 ,0,0,0}, + {14072,14081,14082 ,5565,5574,5575 ,0,0,0}, {14082,14010,14009 ,5575,5499,5498 ,0,0,0}, + {14079,14011,14083 ,5572,5500,5576 ,0,0,0}, {14073,14009,14011 ,5566,5498,5500 ,0,0,0}, + {14049,14051,14076 ,5540,5542,5569 ,0,0,0}, {14084,14069,14070 ,5577,5562,5563 ,0,0,0}, + {14085,14081,14054 ,5578,5574,5547 ,0,0,0}, {14076,14080,14075 ,5569,5573,5568 ,0,0,0}, + {14069,14003,14080 ,5562,5492,5573 ,0,0,0}, {14086,14082,14081 ,5579,5575,5574 ,0,0,0}, + {14003,14056,14055 ,5492,5549,5548 ,0,0,0}, {14087,14010,14082 ,5580,5499,5575 ,0,0,0}, + {14056,14085,14054 ,5549,5578,5547 ,0,0,0}, {14017,14012,14088 ,5506,5501,5581 ,0,0,0}, + {14085,14086,14081 ,5578,5579,5574 ,0,0,0}, {14014,14010,14089 ,5503,5499,5582 ,0,0,0}, + {14087,14082,14086 ,5580,5575,5579 ,0,0,0}, {14089,14010,14087 ,5582,5499,5580 ,0,0,0}, + {14083,14014,14013 ,5576,5503,5502 ,0,0,0}, {14011,14010,14014 ,5500,5499,5503 ,0,0,0}, + {14051,14069,14080 ,5542,5562,5573 ,0,0,0}, {14001,14084,14057 ,5490,5577,5550 ,0,0,0}, + {14002,14090,14056 ,5491,5583,5549 ,0,0,0}, {14080,14003,14055 ,5573,5492,5548 ,0,0,0}, + {14002,14056,14003 ,5491,5549,5492 ,0,0,0}, {14090,14091,14085 ,5583,5584,5578 ,0,0,0}, + {14090,14085,14056 ,5583,5578,5549 ,0,0,0}, {14091,14092,14086 ,5584,5585,5579 ,0,0,0}, + {14091,14086,14085 ,5584,5579,5578 ,0,0,0}, {14092,14093,14087 ,5585,5586,5580 ,0,0,0}, + {14092,14087,14086 ,5585,5580,5579 ,0,0,0}, {14093,14088,14089 ,5586,5581,5582 ,0,0,0}, + {14089,14087,14093 ,5582,5580,5586 ,0,0,0}, {14088,14012,14089 ,5581,5501,5582 ,0,0,0}, + {14013,14012,14016 ,5502,5501,5505 ,0,0,0}, {14014,14089,14012 ,5503,5582,5501 ,0,0,0}, + {14084,14001,14069 ,5577,5490,5562 ,0,0,0}, {14003,14069,14001 ,5492,5562,5490 ,0,0,0}, + {14090,13627,13621 ,5583,5546,5587 ,0,0,0}, {13610,14002,14001 ,5545,5491,5490 ,0,0,0}, + {14091,13621,13626 ,5584,5587,5588 ,0,0,0}, {13627,14090,14002 ,5546,5583,5491 ,0,0,0}, + {14092,13626,13625 ,5585,5588,5589 ,0,0,0}, {13621,14091,14090 ,5587,5584,5583 ,0,0,0}, + {14093,13625,13871 ,5586,5589,5590 ,0,0,0}, {13626,14092,14091 ,5588,5585,5584 ,0,0,0}, + {14088,13871,13629 ,5581,5590,5591 ,0,0,0}, {13625,14093,14092 ,5589,5586,5585 ,0,0,0}, + {14017,13629,13631 ,5506,5591,5510 ,0,0,0}, {13871,14088,14093 ,5590,5581,5586 ,0,0,0}, + {13631,14015,14017 ,5510,5504,5506 ,0,0,0}, {13629,14017,14088 ,5591,5506,5581 ,0,0,0}, + {14094,14095,14096 ,5592,5593,5594 ,0,0,0}, {14097,14098,14099 ,5595,5596,5597 ,0,0,0}, + {14095,14100,14096 ,5593,5598,5594 ,0,0,0}, {14101,14099,14098 ,5599,5597,5596 ,0,0,0}, + {14102,14103,14104 ,5600,5601,5602 ,0,0,0}, {14105,14106,14103 ,5603,5604,5601 ,0,0,0}, + {14107,14108,14109 ,5605,5606,5607 ,0,0,0}, {14110,14106,14105 ,5608,5604,5603 ,0,0,0}, + {14106,14104,14103 ,5604,5602,5601 ,0,0,0}, {14111,14103,14097 ,5609,5601,5595 ,0,0,0}, + {14112,14113,14114 ,5610,5611,5612 ,0,0,0}, {14115,14116,14117 ,5613,5614,5615 ,0,0,0}, + {14118,14113,14119 ,5616,5611,5617 ,0,0,0}, {14120,14121,14094 ,5618,5619,5592 ,0,0,0}, + {14108,13857,13825 ,5606,5620,5621 ,0,0,0}, {14122,14123,14124 ,5622,5623,5624 ,0,0,0}, + {14125,13859,14107 ,5625,5626,5605 ,0,0,0}, {13857,14107,13859 ,5620,5605,5626 ,0,0,0}, + {14126,14127,14128 ,5627,5628,5629 ,0,0,0}, {14100,14129,14096 ,5598,5630,5594 ,0,0,0}, + {14130,14131,14132 ,5631,5632,5633 ,0,0,0}, {14133,14134,14135 ,5634,5635,5636 ,0,0,0}, + {14124,14127,14136 ,5624,5628,5637 ,0,0,0}, {14137,14138,14139 ,5638,5639,5640 ,0,0,0}, + {14140,14094,14141 ,5641,5592,5642 ,0,0,0}, {14138,14133,14139 ,5639,5634,5640 ,0,0,0}, + {14120,14101,14098 ,5618,5599,5596 ,0,0,0}, {13848,13851,14137 ,5643,5644,5638 ,0,0,0}, + {14101,14120,14142 ,5599,5618,5645 ,0,0,0}, {14142,14120,14140 ,5645,5618,5641 ,0,0,0}, + {14143,14144,14140 ,5646,5647,5641 ,0,0,0}, {14120,14098,14121 ,5618,5596,5619 ,0,0,0}, + {14143,14145,14146 ,5646,5648,5649 ,0,0,0}, {14146,14144,14143 ,5649,5647,5646 ,0,0,0}, + {14147,14148,14149 ,5650,5651,5652 ,0,0,0}, {14148,14147,14145 ,5651,5650,5648 ,0,0,0}, + {14105,14103,14111 ,5603,5601,5609 ,0,0,0}, {14150,14102,14104 ,5653,5600,5602 ,0,0,0}, + {14150,14151,14102 ,5653,5654,5600 ,0,0,0}, {14111,14097,14099 ,5609,5595,5597 ,0,0,0}, + {14152,14097,14102 ,5655,5595,5600 ,0,0,0}, {14094,14121,14095 ,5592,5619,5593 ,0,0,0}, + {14152,14121,14098 ,5655,5619,5596 ,0,0,0}, {14143,14153,14145 ,5646,5656,5648 ,0,0,0}, + {14154,14148,14155 ,5657,5651,5658 ,0,0,0}, {14142,14140,14144 ,5645,5641,5647 ,0,0,0}, + {14140,14120,14094 ,5641,5618,5592 ,0,0,0}, {14146,14145,14147 ,5649,5648,5650 ,0,0,0}, + {14141,14153,14143 ,5642,5656,5646 ,0,0,0}, {14148,14156,14149 ,5651,5659,5652 ,0,0,0}, + {14145,14153,14155 ,5648,5656,5658 ,0,0,0}, {14157,14156,14148 ,5660,5659,5651 ,0,0,0}, + {14103,14102,14097 ,5601,5600,5595 ,0,0,0}, {14158,14151,14150 ,5661,5654,5653 ,0,0,0}, + {14158,14114,14151 ,5661,5612,5654 ,0,0,0}, {14097,14152,14098 ,5595,5655,5596 ,0,0,0}, + {14151,14159,14152 ,5654,5662,5655 ,0,0,0}, {14096,14128,14141 ,5594,5629,5642 ,0,0,0}, + {14159,14095,14121 ,5662,5593,5619 ,0,0,0}, {14124,14154,14155 ,5624,5657,5658 ,0,0,0}, + {14123,14154,14124 ,5623,5657,5624 ,0,0,0}, {14140,14141,14143 ,5641,5642,5646 ,0,0,0}, + {14094,14096,14141 ,5592,5594,5642 ,0,0,0}, {14145,14155,14148 ,5648,5658,5651 ,0,0,0}, + {14128,14127,14153 ,5629,5628,5656 ,0,0,0}, {14148,14154,14157 ,5651,5657,5660 ,0,0,0}, + {14155,14127,14124 ,5658,5628,5624 ,0,0,0}, {14160,14157,14154 ,5663,5660,5657 ,0,0,0}, + {14102,14151,14152 ,5600,5654,5655 ,0,0,0}, {14112,14114,14158 ,5610,5612,5661 ,0,0,0}, + {14161,14118,14162 ,5664,5616,5665 ,0,0,0}, {14152,14159,14121 ,5655,5662,5619 ,0,0,0}, + {14163,14159,14114 ,5666,5662,5612 ,0,0,0}, {14128,14096,14129 ,5629,5594,5630 ,0,0,0}, + {14163,14100,14095 ,5666,5598,5593 ,0,0,0}, {14164,14122,14136 ,5667,5622,5637 ,0,0,0}, + {14153,14127,14155 ,5656,5628,5658 ,0,0,0}, {14141,14128,14153 ,5642,5629,5656 ,0,0,0}, + {14128,14129,14126 ,5629,5630,5627 ,0,0,0}, {14123,14122,14165 ,5623,5622,5668 ,0,0,0}, + {14126,14136,14127 ,5627,5637,5628 ,0,0,0}, {14154,14123,14160 ,5657,5623,5663 ,0,0,0}, + {14124,14136,14122 ,5624,5637,5622 ,0,0,0}, {14166,14160,14123 ,5669,5663,5623 ,0,0,0}, + {14151,14114,14159 ,5654,5612,5662 ,0,0,0}, {14119,14113,14112 ,5617,5611,5610 ,0,0,0}, + {14100,14167,14129 ,5598,5670,5630 ,0,0,0}, {14159,14163,14095 ,5662,5666,5593 ,0,0,0}, + {14168,14163,14113 ,5671,5666,5611 ,0,0,0}, {14129,14169,14126 ,5630,5672,5627 ,0,0,0}, + {14168,14167,14100 ,5671,5670,5598 ,0,0,0}, {14126,14170,14136 ,5627,5673,5637 ,0,0,0}, + {14169,14129,14167 ,5672,5630,5670 ,0,0,0}, {14122,14131,14165 ,5622,5632,5668 ,0,0,0}, + {14170,14126,14169 ,5673,5627,5672 ,0,0,0}, {14171,14165,14130 ,5674,5668,5631 ,0,0,0}, + {14164,14136,14170 ,5667,5637,5673 ,0,0,0}, {14123,14165,14166 ,5623,5668,5669 ,0,0,0}, + {14122,14164,14131 ,5622,5667,5632 ,0,0,0}, {14171,14166,14165 ,5674,5669,5668 ,0,0,0}, + {14114,14113,14163 ,5612,5611,5666 ,0,0,0}, {14162,14118,14119 ,5665,5616,5617 ,0,0,0}, + {14167,14115,14169 ,5670,5613,5672 ,0,0,0}, {14163,14168,14100 ,5666,5671,5598 ,0,0,0}, + {14118,14172,14168 ,5616,5675,5671 ,0,0,0}, {14169,14117,14170 ,5672,5615,5673 ,0,0,0}, + {14172,14115,14167 ,5675,5613,5670 ,0,0,0}, {14170,14173,14164 ,5673,5676,5667 ,0,0,0}, + {14115,14117,14169 ,5613,5615,5672 ,0,0,0}, {14174,14131,14164 ,5677,5632,5667 ,0,0,0}, + {14173,14170,14117 ,5676,5673,5615 ,0,0,0}, {14175,14130,14135 ,5678,5631,5636 ,0,0,0}, + {14164,14173,14174 ,5667,5676,5677 ,0,0,0}, {14174,14132,14131 ,5677,5633,5632 ,0,0,0}, + {14171,14130,14175 ,5674,5631,5678 ,0,0,0}, {14165,14131,14130 ,5668,5632,5631 ,0,0,0}, + {14113,14118,14168 ,5611,5616,5671 ,0,0,0}, {14176,14161,14162 ,5679,5664,5665 ,0,0,0}, + {14177,14173,14117 ,5680,5676,5615 ,0,0,0}, {14168,14172,14167 ,5671,5675,5670 ,0,0,0}, + {14161,14109,14172 ,5664,5607,5675 ,0,0,0}, {14178,14174,14173 ,5681,5677,5676 ,0,0,0}, + {14109,14116,14115 ,5607,5614,5613 ,0,0,0}, {14179,14132,14174 ,5682,5633,5677 ,0,0,0}, + {14116,14177,14117 ,5614,5680,5615 ,0,0,0}, {14139,14133,14180 ,5640,5634,5683 ,0,0,0}, + {14177,14178,14173 ,5680,5681,5676 ,0,0,0}, {14135,14132,14181 ,5636,5633,5684 ,0,0,0}, + {14179,14174,14178 ,5682,5677,5681 ,0,0,0}, {14181,14132,14179 ,5684,5633,5682 ,0,0,0}, + {14175,14135,14134 ,5678,5636,5635 ,0,0,0}, {14130,14132,14135 ,5631,5633,5636 ,0,0,0}, + {14118,14161,14172 ,5616,5664,5675 ,0,0,0}, {14107,14176,14125 ,5605,5679,5625 ,0,0,0}, + {14108,14182,14116 ,5606,5685,5614 ,0,0,0}, {14172,14109,14115 ,5675,5607,5613 ,0,0,0}, + {14108,14116,14109 ,5606,5614,5607 ,0,0,0}, {14182,14183,14177 ,5685,5686,5680 ,0,0,0}, + {14182,14177,14116 ,5685,5680,5614 ,0,0,0}, {14183,14184,14178 ,5686,5687,5681 ,0,0,0}, + {14183,14178,14177 ,5686,5681,5680 ,0,0,0}, {14184,14185,14179 ,5687,5688,5682 ,0,0,0}, + {14184,14179,14178 ,5687,5682,5681 ,0,0,0}, {14185,14180,14181 ,5688,5683,5684 ,0,0,0}, + {14181,14179,14185 ,5684,5682,5688 ,0,0,0}, {14180,14133,14181 ,5683,5634,5684 ,0,0,0}, + {14134,14133,14138 ,5635,5634,5639 ,0,0,0}, {14135,14181,14133 ,5636,5684,5634 ,0,0,0}, + {14176,14107,14161 ,5679,5605,5664 ,0,0,0}, {14109,14161,14107 ,5607,5664,5605 ,0,0,0}, + {14182,13825,13846 ,5685,5621,5689 ,0,0,0}, {13857,14108,14107 ,5620,5606,5605 ,0,0,0}, + {14183,13846,13957 ,5686,5689,5690 ,0,0,0}, {13825,14182,14108 ,5621,5685,5606 ,0,0,0}, + {14184,13957,13843 ,5687,5690,5691 ,0,0,0}, {13846,14183,14182 ,5689,5686,5685 ,0,0,0}, + {14185,13843,13841 ,5688,5691,5692 ,0,0,0}, {13957,14184,14183 ,5690,5687,5686 ,0,0,0}, + {14180,13841,13810 ,5683,5692,5693 ,0,0,0}, {13843,14185,14184 ,5691,5688,5687 ,0,0,0}, + {14139,13810,13848 ,5640,5693,5643 ,0,0,0}, {13841,14180,14185 ,5692,5683,5688 ,0,0,0}, + {13848,14137,14139 ,5643,5638,5640 ,0,0,0}, {13810,14139,14180 ,5693,5640,5683 ,0,0,0}, + {14186,14187,14188 ,5694,5695,5696 ,0,0,0}, {14189,14190,14191 ,5697,5698,5699 ,0,0,0}, + {14188,14192,14193 ,5696,5700,5701 ,0,0,0}, {14192,14194,14193 ,5700,5702,5701 ,0,0,0}, + {14195,14196,14197 ,5703,5704,5705 ,0,0,0}, {14197,14198,14195 ,5705,5706,5703 ,0,0,0}, + {14199,14200,14201 ,5707,5708,5709 ,0,0,0}, {14202,14196,14203 ,5710,5704,5711 ,0,0,0}, + {14202,14197,14196 ,5710,5705,5704 ,0,0,0}, {14203,14204,14202 ,5711,5712,5710 ,0,0,0}, + {14205,14191,14206 ,5713,5699,5714 ,0,0,0}, {14207,14208,14209 ,5715,5716,5717 ,0,0,0}, + {14199,13773,13772 ,5707,5718,5719 ,0,0,0}, {14210,14211,14212 ,5720,5721,5722 ,0,0,0}, + {14213,13800,14201 ,5723,5724,5709 ,0,0,0}, {14214,14215,14208 ,5725,5726,5716 ,0,0,0}, + {13773,14201,13800 ,5718,5709,5724 ,0,0,0}, {14216,14217,14218 ,5727,5728,5729 ,0,0,0}, + {14219,14193,14194 ,5730,5701,5702 ,0,0,0}, {14220,14221,14222 ,5731,5732,5733 ,0,0,0}, + {14223,14224,14188 ,5734,5735,5696 ,0,0,0}, {14225,14226,14227 ,5736,5737,5738 ,0,0,0}, + {14218,14228,14229 ,5729,5739,5740 ,0,0,0}, {14230,14228,14231 ,5741,5739,5742 ,0,0,0}, + {14232,14233,14234 ,5743,5744,5745 ,0,0,0}, {14186,14190,14189 ,5694,5698,5697 ,0,0,0}, + {14233,14220,14234 ,5744,5731,5745 ,0,0,0}, {14224,14235,14186 ,5735,5746,5694 ,0,0,0}, + {13796,13801,14232 ,5747,5748,5743 ,0,0,0}, {14236,14237,14224 ,5749,5750,5735 ,0,0,0}, + {14235,14190,14186 ,5746,5698,5694 ,0,0,0}, {14236,14238,14239 ,5749,5751,5752 ,0,0,0}, + {14224,14237,14235 ,5735,5750,5746 ,0,0,0}, {14240,14241,14242 ,5753,5754,5755 ,0,0,0}, + {14237,14236,14239 ,5750,5749,5752 ,0,0,0}, {14243,14242,14244 ,5756,5755,5757 ,0,0,0}, + {14241,14240,14238 ,5754,5753,5751 ,0,0,0}, {14206,14196,14205 ,5714,5704,5713 ,0,0,0}, + {14196,14206,14203 ,5704,5714,5711 ,0,0,0}, {14198,14245,14195 ,5706,5758,5703 ,0,0,0}, + {14205,14189,14191 ,5713,5697,5699 ,0,0,0}, {14246,14205,14195 ,5759,5713,5703 ,0,0,0}, + {14188,14187,14192 ,5696,5695,5700 ,0,0,0}, {14246,14187,14189 ,5759,5695,5697 ,0,0,0}, + {14236,14247,14238 ,5749,5760,5751 ,0,0,0}, {14189,14187,14186 ,5697,5695,5694 ,0,0,0}, + {14248,14249,14241 ,5761,5762,5754 ,0,0,0}, {14224,14186,14188 ,5735,5694,5696 ,0,0,0}, + {14247,14236,14223 ,5760,5749,5734 ,0,0,0}, {14242,14241,14244 ,5755,5754,5757 ,0,0,0}, + {14239,14238,14240 ,5752,5751,5753 ,0,0,0}, {14238,14247,14248 ,5751,5760,5761 ,0,0,0}, + {14250,14244,14241 ,5763,5757,5754 ,0,0,0}, {14196,14195,14205 ,5704,5703,5713 ,0,0,0}, + {14251,14245,14198 ,5764,5758,5706 ,0,0,0}, {14251,14214,14245 ,5764,5725,5758 ,0,0,0}, + {14205,14246,14189 ,5713,5759,5697 ,0,0,0}, {14245,14252,14246 ,5758,5765,5759 ,0,0,0}, + {14193,14231,14223 ,5701,5742,5734 ,0,0,0}, {14252,14192,14187 ,5765,5700,5695 ,0,0,0}, + {14218,14249,14248 ,5729,5762,5761 ,0,0,0}, {14217,14249,14218 ,5728,5762,5729 ,0,0,0}, + {14224,14223,14236 ,5735,5734,5749 ,0,0,0}, {14188,14193,14223 ,5696,5701,5734 ,0,0,0}, + {14238,14248,14241 ,5751,5761,5754 ,0,0,0}, {14231,14228,14247 ,5742,5739,5760 ,0,0,0}, + {14241,14249,14250 ,5754,5762,5763 ,0,0,0}, {14248,14228,14218 ,5761,5739,5729 ,0,0,0}, + {14253,14250,14249 ,5766,5763,5762 ,0,0,0}, {14195,14245,14246 ,5703,5758,5759 ,0,0,0}, + {14215,14214,14251 ,5726,5725,5764 ,0,0,0}, {14254,14207,14255 ,5767,5715,5768 ,0,0,0}, + {14246,14252,14187 ,5759,5765,5695 ,0,0,0}, {14256,14252,14214 ,5769,5765,5725 ,0,0,0}, + {14231,14193,14219 ,5742,5701,5730 ,0,0,0}, {14256,14194,14192 ,5769,5702,5700 ,0,0,0}, + {14257,14216,14229 ,5770,5727,5740 ,0,0,0}, {14247,14228,14248 ,5760,5739,5761 ,0,0,0}, + {14223,14231,14247 ,5734,5742,5760 ,0,0,0}, {14231,14219,14230 ,5742,5730,5741 ,0,0,0}, + {14217,14216,14258 ,5728,5727,5771 ,0,0,0}, {14230,14229,14228 ,5741,5740,5739 ,0,0,0}, + {14249,14217,14253 ,5762,5728,5766 ,0,0,0}, {14218,14229,14216 ,5729,5740,5727 ,0,0,0}, + {14259,14253,14217 ,5772,5766,5728 ,0,0,0}, {14245,14214,14252 ,5758,5725,5765 ,0,0,0}, + {14209,14208,14215 ,5717,5716,5726 ,0,0,0}, {14194,14260,14219 ,5702,5773,5730 ,0,0,0}, + {14252,14256,14192 ,5765,5769,5700 ,0,0,0}, {14261,14256,14208 ,5774,5769,5716 ,0,0,0}, + {14219,14262,14230 ,5730,5775,5741 ,0,0,0}, {14261,14260,14194 ,5774,5773,5702 ,0,0,0}, + {14230,14263,14229 ,5741,5776,5740 ,0,0,0}, {14262,14219,14260 ,5775,5730,5773 ,0,0,0}, + {14216,14226,14258 ,5727,5737,5771 ,0,0,0}, {14263,14230,14262 ,5776,5741,5775 ,0,0,0}, + {14264,14258,14225 ,5777,5771,5736 ,0,0,0}, {14257,14229,14263 ,5770,5740,5776 ,0,0,0}, + {14217,14258,14259 ,5728,5771,5772 ,0,0,0}, {14216,14257,14226 ,5727,5770,5737 ,0,0,0}, + {14264,14259,14258 ,5777,5772,5771 ,0,0,0}, {14214,14208,14256 ,5725,5716,5769 ,0,0,0}, + {14255,14207,14209 ,5768,5715,5717 ,0,0,0}, {14260,14211,14262 ,5773,5721,5775 ,0,0,0}, + {14256,14261,14194 ,5769,5774,5702 ,0,0,0}, {14207,14265,14261 ,5715,5778,5774 ,0,0,0}, + {14262,14210,14263 ,5775,5720,5776 ,0,0,0}, {14265,14211,14260 ,5778,5721,5773 ,0,0,0}, + {14263,14266,14257 ,5776,5779,5770 ,0,0,0}, {14211,14210,14262 ,5721,5720,5775 ,0,0,0}, + {14267,14226,14257 ,5780,5737,5770 ,0,0,0}, {14266,14263,14210 ,5779,5776,5720 ,0,0,0}, + {14268,14225,14222 ,5781,5736,5733 ,0,0,0}, {14257,14266,14267 ,5770,5779,5780 ,0,0,0}, + {14267,14227,14226 ,5780,5738,5737 ,0,0,0}, {14264,14225,14268 ,5777,5736,5781 ,0,0,0}, + {14258,14226,14225 ,5771,5737,5736 ,0,0,0}, {14208,14207,14261 ,5716,5715,5774 ,0,0,0}, + {14269,14254,14255 ,5782,5767,5768 ,0,0,0}, {14270,14266,14210 ,5783,5779,5720 ,0,0,0}, + {14261,14265,14260 ,5774,5778,5773 ,0,0,0}, {14254,14200,14265 ,5767,5708,5778 ,0,0,0}, + {14271,14267,14266 ,5784,5780,5779 ,0,0,0}, {14200,14212,14211 ,5708,5722,5721 ,0,0,0}, + {14272,14227,14267 ,5785,5738,5780 ,0,0,0}, {14212,14270,14210 ,5722,5783,5720 ,0,0,0}, + {14234,14220,14273 ,5745,5731,5786 ,0,0,0}, {14270,14271,14266 ,5783,5784,5779 ,0,0,0}, + {14222,14227,14274 ,5733,5738,5787 ,0,0,0}, {14272,14267,14271 ,5785,5780,5784 ,0,0,0}, + {14274,14227,14272 ,5787,5738,5785 ,0,0,0}, {14268,14222,14221 ,5781,5733,5732 ,0,0,0}, + {14225,14227,14222 ,5736,5738,5733 ,0,0,0}, {14207,14254,14265 ,5715,5767,5778 ,0,0,0}, + {14201,14269,14213 ,5709,5782,5723 ,0,0,0}, {14199,14275,14212 ,5707,5788,5722 ,0,0,0}, + {14265,14200,14211 ,5778,5708,5721 ,0,0,0}, {14199,14212,14200 ,5707,5722,5708 ,0,0,0}, + {14275,14276,14270 ,5788,5789,5783 ,0,0,0}, {14275,14270,14212 ,5788,5783,5722 ,0,0,0}, + {14276,14277,14271 ,5789,5790,5784 ,0,0,0}, {14276,14271,14270 ,5789,5784,5783 ,0,0,0}, + {14277,14278,14272 ,5790,5791,5785 ,0,0,0}, {14277,14272,14271 ,5790,5785,5784 ,0,0,0}, + {14278,14273,14274 ,5791,5786,5787 ,0,0,0}, {14274,14272,14278 ,5787,5785,5791 ,0,0,0}, + {14273,14220,14274 ,5786,5731,5787 ,0,0,0}, {14221,14220,14233 ,5732,5731,5744 ,0,0,0}, + {14222,14274,14220 ,5733,5787,5731 ,0,0,0}, {14269,14201,14254 ,5782,5709,5767 ,0,0,0}, + {14200,14254,14201 ,5708,5767,5709 ,0,0,0}, {14275,13772,13787 ,5788,5719,5792 ,0,0,0}, + {13773,14199,14201 ,5718,5707,5709 ,0,0,0}, {14276,13787,13790 ,5789,5792,5793 ,0,0,0}, + {13772,14275,14199 ,5719,5788,5707 ,0,0,0}, {14277,13790,13791 ,5790,5793,5794 ,0,0,0}, + {13787,14276,14275 ,5792,5789,5788 ,0,0,0}, {14278,13791,13830 ,5791,5794,5795 ,0,0,0}, + {13790,14277,14276 ,5793,5790,5789 ,0,0,0}, {14273,13830,13771 ,5786,5795,5796 ,0,0,0}, + {13791,14278,14277 ,5794,5791,5790 ,0,0,0}, {14234,13771,13796 ,5745,5796,5747 ,0,0,0}, + {13830,14273,14278 ,5795,5786,5791 ,0,0,0}, {13796,14232,14234 ,5747,5743,5745 ,0,0,0}, + {13771,14234,14273 ,5796,5745,5786 ,0,0,0}, {14279,14280,14281 ,5797,5798,5799 ,0,0,0}, + {14282,13196,13197 ,5800,5801,5802 ,0,0,0}, {14281,14283,14284 ,5799,5803,5804 ,0,0,0}, + {14283,14285,14284 ,5803,5805,5804 ,0,0,0}, {14286,14287,14288 ,5806,5807,5808 ,0,0,0}, + {14288,14289,14286 ,5808,5809,5806 ,0,0,0}, {14290,14291,14292 ,5810,5811,5812 ,0,0,0}, + {14293,14287,13202 ,5813,5807,5814 ,0,0,0}, {14293,14288,14287 ,5813,5808,5807 ,0,0,0}, + {13202,13203,14293 ,5814,5815,5813 ,0,0,0}, {14294,13197,13200 ,5816,5802,5817 ,0,0,0}, + {14295,14296,14297 ,5818,5819,5820 ,0,0,0}, {14290,13729,13728 ,5810,5821,5822 ,0,0,0}, + {14298,14299,14300 ,5823,5824,5825 ,0,0,0}, {14301,13736,14292 ,5826,5827,5812 ,0,0,0}, + {14302,14303,14296 ,5828,5829,5819 ,0,0,0}, {13729,14292,13736 ,5821,5812,5827 ,0,0,0}, + {14304,14305,14306 ,5830,5831,5832 ,0,0,0}, {14307,14284,14285 ,5833,5804,5805 ,0,0,0}, + {14308,14309,14310 ,5834,5835,5836 ,0,0,0}, {14311,14312,14281 ,5837,5838,5799 ,0,0,0}, + {14313,14314,14315 ,5839,5840,5841 ,0,0,0}, {14306,14316,14317 ,5832,5842,5843 ,0,0,0}, + {14318,14316,14319 ,5844,5842,5845 ,0,0,0}, {14320,14321,14322 ,5846,5847,5848 ,0,0,0}, + {14279,13196,14282 ,5797,5801,5800 ,0,0,0}, {14321,14308,14322 ,5847,5834,5848 ,0,0,0}, + {14312,13194,14279 ,5838,5849,5797 ,0,0,0}, {13752,13759,14320 ,5850,5851,5846 ,0,0,0}, + {14323,13192,14312 ,5852,5853,5838 ,0,0,0}, {13194,13196,14279 ,5849,5801,5797 ,0,0,0}, + {14323,14324,13189 ,5852,5854,5855 ,0,0,0}, {14312,13192,13194 ,5838,5853,5849 ,0,0,0}, + {13187,14325,13188 ,5856,5857,5858 ,0,0,0}, {13192,14323,13189 ,5853,5852,5855 ,0,0,0}, + {13182,13188,14326 ,5067,5858,5859 ,0,0,0}, {14325,13187,14324 ,5857,5856,5854 ,0,0,0}, + {13200,14287,14294 ,5817,5807,5816 ,0,0,0}, {14287,13200,13202 ,5807,5817,5814 ,0,0,0}, + {14289,14327,14286 ,5809,5860,5806 ,0,0,0}, {14294,14282,13197 ,5816,5800,5802 ,0,0,0}, + {14328,14294,14286 ,5861,5816,5806 ,0,0,0}, {14281,14280,14283 ,5799,5798,5803 ,0,0,0}, + {14328,14280,14282 ,5861,5798,5800 ,0,0,0}, {14323,14329,14324 ,5852,5862,5854 ,0,0,0}, + {14282,14280,14279 ,5800,5798,5797 ,0,0,0}, {14330,14331,14325 ,5863,5864,5857 ,0,0,0}, + {14312,14279,14281 ,5838,5797,5799 ,0,0,0}, {14329,14323,14311 ,5862,5852,5837 ,0,0,0}, + {13188,14325,14326 ,5858,5857,5859 ,0,0,0}, {13189,14324,13187 ,5855,5854,5856 ,0,0,0}, + {14324,14329,14330 ,5854,5862,5863 ,0,0,0}, {14332,14326,14325 ,5865,5859,5857 ,0,0,0}, + {14287,14286,14294 ,5807,5806,5816 ,0,0,0}, {14333,14327,14289 ,5866,5860,5809 ,0,0,0}, + {14333,14302,14327 ,5866,5828,5860 ,0,0,0}, {14294,14328,14282 ,5816,5861,5800 ,0,0,0}, + {14327,14334,14328 ,5860,5867,5861 ,0,0,0}, {14284,14319,14311 ,5804,5845,5837 ,0,0,0}, + {14334,14283,14280 ,5867,5803,5798 ,0,0,0}, {14306,14331,14330 ,5832,5864,5863 ,0,0,0}, + {14305,14331,14306 ,5831,5864,5832 ,0,0,0}, {14312,14311,14323 ,5838,5837,5852 ,0,0,0}, + {14281,14284,14311 ,5799,5804,5837 ,0,0,0}, {14324,14330,14325 ,5854,5863,5857 ,0,0,0}, + {14319,14316,14329 ,5845,5842,5862 ,0,0,0}, {14325,14331,14332 ,5857,5864,5865 ,0,0,0}, + {14330,14316,14306 ,5863,5842,5832 ,0,0,0}, {14335,14332,14331 ,5868,5865,5864 ,0,0,0}, + {14286,14327,14328 ,5806,5860,5861 ,0,0,0}, {14303,14302,14333 ,5829,5828,5866 ,0,0,0}, + {14336,14295,14337 ,5869,5818,5870 ,0,0,0}, {14328,14334,14280 ,5861,5867,5798 ,0,0,0}, + {14338,14334,14302 ,5871,5867,5828 ,0,0,0}, {14319,14284,14307 ,5845,5804,5833 ,0,0,0}, + {14338,14285,14283 ,5871,5805,5803 ,0,0,0}, {14339,14304,14317 ,5872,5830,5843 ,0,0,0}, + {14329,14316,14330 ,5862,5842,5863 ,0,0,0}, {14311,14319,14329 ,5837,5845,5862 ,0,0,0}, + {14319,14307,14318 ,5845,5833,5844 ,0,0,0}, {14305,14304,14340 ,5831,5830,5873 ,0,0,0}, + {14318,14317,14316 ,5844,5843,5842 ,0,0,0}, {14331,14305,14335 ,5864,5831,5868 ,0,0,0}, + {14306,14317,14304 ,5832,5843,5830 ,0,0,0}, {14341,14335,14305 ,5874,5868,5831 ,0,0,0}, + {14327,14302,14334 ,5860,5828,5867 ,0,0,0}, {14297,14296,14303 ,5820,5819,5829 ,0,0,0}, + {14285,14342,14307 ,5805,5875,5833 ,0,0,0}, {14334,14338,14283 ,5867,5871,5803 ,0,0,0}, + {14343,14338,14296 ,5876,5871,5819 ,0,0,0}, {14307,14344,14318 ,5833,5877,5844 ,0,0,0}, + {14343,14342,14285 ,5876,5875,5805 ,0,0,0}, {14318,14345,14317 ,5844,5878,5843 ,0,0,0}, + {14344,14307,14342 ,5877,5833,5875 ,0,0,0}, {14304,14314,14340 ,5830,5840,5873 ,0,0,0}, + {14345,14318,14344 ,5878,5844,5877 ,0,0,0}, {14346,14340,14313 ,5879,5873,5839 ,0,0,0}, + {14339,14317,14345 ,5872,5843,5878 ,0,0,0}, {14305,14340,14341 ,5831,5873,5874 ,0,0,0}, + {14304,14339,14314 ,5830,5872,5840 ,0,0,0}, {14346,14341,14340 ,5879,5874,5873 ,0,0,0}, + {14302,14296,14338 ,5828,5819,5871 ,0,0,0}, {14337,14295,14297 ,5870,5818,5820 ,0,0,0}, + {14342,14299,14344 ,5875,5824,5877 ,0,0,0}, {14338,14343,14285 ,5871,5876,5805 ,0,0,0}, + {14295,14347,14343 ,5818,5880,5876 ,0,0,0}, {14344,14298,14345 ,5877,5823,5878 ,0,0,0}, + {14347,14299,14342 ,5880,5824,5875 ,0,0,0}, {14345,14348,14339 ,5878,5881,5872 ,0,0,0}, + {14299,14298,14344 ,5824,5823,5877 ,0,0,0}, {14349,14314,14339 ,5882,5840,5872 ,0,0,0}, + {14348,14345,14298 ,5881,5878,5823 ,0,0,0}, {14350,14313,14310 ,5883,5839,5836 ,0,0,0}, + {14339,14348,14349 ,5872,5881,5882 ,0,0,0}, {14349,14315,14314 ,5882,5841,5840 ,0,0,0}, + {14346,14313,14350 ,5879,5839,5883 ,0,0,0}, {14340,14314,14313 ,5873,5840,5839 ,0,0,0}, + {14296,14295,14343 ,5819,5818,5876 ,0,0,0}, {14351,14336,14337 ,5884,5869,5870 ,0,0,0}, + {14352,14348,14298 ,5885,5881,5823 ,0,0,0}, {14343,14347,14342 ,5876,5880,5875 ,0,0,0}, + {14336,14291,14347 ,5869,5811,5880 ,0,0,0}, {14353,14349,14348 ,5886,5882,5881 ,0,0,0}, + {14291,14300,14299 ,5811,5825,5824 ,0,0,0}, {14354,14315,14349 ,5887,5841,5882 ,0,0,0}, + {14300,14352,14298 ,5825,5885,5823 ,0,0,0}, {14322,14308,14355 ,5848,5834,5888 ,0,0,0}, + {14352,14353,14348 ,5885,5886,5881 ,0,0,0}, {14310,14315,14356 ,5836,5841,5889 ,0,0,0}, + {14354,14349,14353 ,5887,5882,5886 ,0,0,0}, {14356,14315,14354 ,5889,5841,5887 ,0,0,0}, + {14350,14310,14309 ,5883,5836,5835 ,0,0,0}, {14313,14315,14310 ,5839,5841,5836 ,0,0,0}, + {14295,14336,14347 ,5818,5869,5880 ,0,0,0}, {14292,14351,14301 ,5812,5884,5826 ,0,0,0}, + {14290,14357,14300 ,5810,5890,5825 ,0,0,0}, {14347,14291,14299 ,5880,5811,5824 ,0,0,0}, + {14290,14300,14291 ,5810,5825,5811 ,0,0,0}, {14357,14358,14352 ,5890,5891,5885 ,0,0,0}, + {14357,14352,14300 ,5890,5885,5825 ,0,0,0}, {14358,14359,14353 ,5891,5892,5886 ,0,0,0}, + {14358,14353,14352 ,5891,5886,5885 ,0,0,0}, {14359,14360,14354 ,5892,5893,5887 ,0,0,0}, + {14359,14354,14353 ,5892,5887,5886 ,0,0,0}, {14360,14355,14356 ,5893,5888,5889 ,0,0,0}, + {14356,14354,14360 ,5889,5887,5893 ,0,0,0}, {14355,14308,14356 ,5888,5834,5889 ,0,0,0}, + {14309,14308,14321 ,5835,5834,5847 ,0,0,0}, {14310,14356,14308 ,5836,5889,5834 ,0,0,0}, + {14351,14292,14336 ,5884,5812,5869 ,0,0,0}, {14291,14336,14292 ,5811,5869,5812 ,0,0,0}, + {14357,13728,13746 ,5890,5822,5894 ,0,0,0}, {13729,14290,14292 ,5821,5810,5812 ,0,0,0}, + {14358,13746,13747 ,5891,5894,5895 ,0,0,0}, {13728,14357,14290 ,5822,5890,5810 ,0,0,0}, + {14359,13747,13749 ,5892,5895,5896 ,0,0,0}, {13746,14358,14357 ,5894,5891,5890 ,0,0,0}, + {14360,13749,13732 ,5893,5896,5897 ,0,0,0}, {13747,14359,14358 ,5895,5892,5891 ,0,0,0}, + {14355,13732,13753 ,5888,5897,5898 ,0,0,0}, {13749,14360,14359 ,5896,5893,5892 ,0,0,0}, + {14322,13753,13752 ,5848,5898,5850 ,0,0,0}, {13732,14355,14360 ,5897,5888,5893 ,0,0,0}, + {13752,14320,14322 ,5850,5846,5848 ,0,0,0}, {13753,14322,14355 ,5898,5848,5888 ,0,0,0}, + {14361,14362,14363 ,5899,5900,5901 ,0,0,0}, {14364,14365,13165 ,5902,5903,5904 ,0,0,0}, + {14362,14366,14363 ,5900,5905,5901 ,0,0,0}, {13160,13165,14365 ,5906,5904,5903 ,0,0,0}, + {14367,14368,14369 ,5907,5908,5909 ,0,0,0}, {13170,14370,14368 ,5910,5911,5908 ,0,0,0}, + {14371,14372,14373 ,5912,5913,5914 ,0,0,0}, {13168,14370,13170 ,5915,5911,5910 ,0,0,0}, + {14370,14369,14368 ,5911,5909,5908 ,0,0,0}, {13164,14368,14364 ,5916,5908,5902 ,0,0,0}, + {14374,14375,14376 ,5917,5918,5919 ,0,0,0}, {14377,14378,14379 ,5920,5921,5922 ,0,0,0}, + {14380,14375,14381 ,5923,5918,5924 ,0,0,0}, {14382,14383,14361 ,5925,5926,5899 ,0,0,0}, + {14372,13679,13598 ,5913,5927,5928 ,0,0,0}, {14384,14385,14386 ,5929,5930,5931 ,0,0,0}, + {14387,13709,14371 ,5932,5933,5912 ,0,0,0}, {13679,14371,13709 ,5927,5912,5933 ,0,0,0}, + {14388,14389,14390 ,5934,5935,5936 ,0,0,0}, {14366,14391,14363 ,5905,5937,5901 ,0,0,0}, + {14392,14393,14394 ,5938,5939,5940 ,0,0,0}, {14395,14396,14397 ,5941,5942,5943 ,0,0,0}, + {14386,14389,14398 ,5931,5935,5944 ,0,0,0}, {14399,14400,14401 ,5945,5946,5947 ,0,0,0}, + {14402,14361,14403 ,5948,5899,5949 ,0,0,0}, {14400,14395,14401 ,5946,5941,5947 ,0,0,0}, + {14382,13160,14365 ,5925,5906,5903 ,0,0,0}, {13708,13712,14399 ,5950,5951,5945 ,0,0,0}, + {13160,14382,13158 ,5906,5925,5952 ,0,0,0}, {13158,14382,14402 ,5952,5925,5948 ,0,0,0}, + {14404,13153,14402 ,5953,5954,5948 ,0,0,0}, {14382,14365,14383 ,5925,5903,5926 ,0,0,0}, + {14404,14405,13157 ,5953,5955,5956 ,0,0,0}, {13157,13153,14404 ,5956,5954,5953 ,0,0,0}, + {13149,14406,13151 ,5957,5958,5959 ,0,0,0}, {14406,13149,14405 ,5958,5957,5955 ,0,0,0}, + {13170,14368,13164 ,5910,5908,5916 ,0,0,0}, {14407,14367,14369 ,5960,5907,5909 ,0,0,0}, + {14407,14408,14367 ,5960,5961,5907 ,0,0,0}, {13164,14364,13165 ,5916,5902,5904 ,0,0,0}, + {14409,14364,14367 ,5962,5902,5907 ,0,0,0}, {14361,14383,14362 ,5899,5926,5900 ,0,0,0}, + {14409,14383,14365 ,5962,5926,5903 ,0,0,0}, {14404,14410,14405 ,5953,5963,5955 ,0,0,0}, + {14411,14406,14412 ,5964,5958,5965 ,0,0,0}, {13158,14402,13153 ,5952,5948,5954 ,0,0,0}, + {14402,14382,14361 ,5948,5925,5899 ,0,0,0}, {13157,14405,13149 ,5956,5955,5957 ,0,0,0}, + {14403,14410,14404 ,5949,5963,5953 ,0,0,0}, {14406,14413,13151 ,5958,5966,5959 ,0,0,0}, + {14405,14410,14412 ,5955,5963,5965 ,0,0,0}, {14414,14413,14406 ,5967,5966,5958 ,0,0,0}, + {14368,14367,14364 ,5908,5907,5902 ,0,0,0}, {14415,14408,14407 ,5968,5961,5960 ,0,0,0}, + {14415,14376,14408 ,5968,5919,5961 ,0,0,0}, {14364,14409,14365 ,5902,5962,5903 ,0,0,0}, + {14408,14416,14409 ,5961,5969,5962 ,0,0,0}, {14363,14390,14403 ,5901,5936,5949 ,0,0,0}, + {14416,14362,14383 ,5969,5900,5926 ,0,0,0}, {14386,14411,14412 ,5931,5964,5965 ,0,0,0}, + {14385,14411,14386 ,5930,5964,5931 ,0,0,0}, {14402,14403,14404 ,5948,5949,5953 ,0,0,0}, + {14361,14363,14403 ,5899,5901,5949 ,0,0,0}, {14405,14412,14406 ,5955,5965,5958 ,0,0,0}, + {14390,14389,14410 ,5936,5935,5963 ,0,0,0}, {14406,14411,14414 ,5958,5964,5967 ,0,0,0}, + {14412,14389,14386 ,5965,5935,5931 ,0,0,0}, {14417,14414,14411 ,5970,5967,5964 ,0,0,0}, + {14367,14408,14409 ,5907,5961,5962 ,0,0,0}, {14374,14376,14415 ,5917,5919,5968 ,0,0,0}, + {14418,14380,14419 ,5971,5923,5972 ,0,0,0}, {14409,14416,14383 ,5962,5969,5926 ,0,0,0}, + {14420,14416,14376 ,5973,5969,5919 ,0,0,0}, {14390,14363,14391 ,5936,5901,5937 ,0,0,0}, + {14420,14366,14362 ,5973,5905,5900 ,0,0,0}, {14421,14384,14398 ,5974,5929,5944 ,0,0,0}, + {14410,14389,14412 ,5963,5935,5965 ,0,0,0}, {14403,14390,14410 ,5949,5936,5963 ,0,0,0}, + {14390,14391,14388 ,5936,5937,5934 ,0,0,0}, {14385,14384,14422 ,5930,5929,5975 ,0,0,0}, + {14388,14398,14389 ,5934,5944,5935 ,0,0,0}, {14411,14385,14417 ,5964,5930,5970 ,0,0,0}, + {14386,14398,14384 ,5931,5944,5929 ,0,0,0}, {14423,14417,14385 ,5976,5970,5930 ,0,0,0}, + {14408,14376,14416 ,5961,5919,5969 ,0,0,0}, {14381,14375,14374 ,5924,5918,5917 ,0,0,0}, + {14366,14424,14391 ,5905,5977,5937 ,0,0,0}, {14416,14420,14362 ,5969,5973,5900 ,0,0,0}, + {14425,14420,14375 ,5978,5973,5918 ,0,0,0}, {14391,14426,14388 ,5937,5979,5934 ,0,0,0}, + {14425,14424,14366 ,5978,5977,5905 ,0,0,0}, {14388,14427,14398 ,5934,5980,5944 ,0,0,0}, + {14426,14391,14424 ,5979,5937,5977 ,0,0,0}, {14384,14393,14422 ,5929,5939,5975 ,0,0,0}, + {14427,14388,14426 ,5980,5934,5979 ,0,0,0}, {14428,14422,14392 ,5981,5975,5938 ,0,0,0}, + {14421,14398,14427 ,5974,5944,5980 ,0,0,0}, {14385,14422,14423 ,5930,5975,5976 ,0,0,0}, + {14384,14421,14393 ,5929,5974,5939 ,0,0,0}, {14428,14423,14422 ,5981,5976,5975 ,0,0,0}, + {14376,14375,14420 ,5919,5918,5973 ,0,0,0}, {14419,14380,14381 ,5972,5923,5924 ,0,0,0}, + {14424,14377,14426 ,5977,5920,5979 ,0,0,0}, {14420,14425,14366 ,5973,5978,5905 ,0,0,0}, + {14380,14429,14425 ,5923,5982,5978 ,0,0,0}, {14426,14379,14427 ,5979,5922,5980 ,0,0,0}, + {14429,14377,14424 ,5982,5920,5977 ,0,0,0}, {14427,14430,14421 ,5980,5983,5974 ,0,0,0}, + {14377,14379,14426 ,5920,5922,5979 ,0,0,0}, {14431,14393,14421 ,5984,5939,5974 ,0,0,0}, + {14430,14427,14379 ,5983,5980,5922 ,0,0,0}, {14432,14392,14397 ,5985,5938,5943 ,0,0,0}, + {14421,14430,14431 ,5974,5983,5984 ,0,0,0}, {14431,14394,14393 ,5984,5940,5939 ,0,0,0}, + {14428,14392,14432 ,5981,5938,5985 ,0,0,0}, {14422,14393,14392 ,5975,5939,5938 ,0,0,0}, + {14375,14380,14425 ,5918,5923,5978 ,0,0,0}, {14433,14418,14419 ,5986,5971,5972 ,0,0,0}, + {14434,14430,14379 ,5987,5983,5922 ,0,0,0}, {14425,14429,14424 ,5978,5982,5977 ,0,0,0}, + {14418,14373,14429 ,5971,5914,5982 ,0,0,0}, {14435,14431,14430 ,5988,5984,5983 ,0,0,0}, + {14373,14378,14377 ,5914,5921,5920 ,0,0,0}, {14436,14394,14431 ,5989,5940,5984 ,0,0,0}, + {14378,14434,14379 ,5921,5987,5922 ,0,0,0}, {14401,14395,14437 ,5947,5941,5990 ,0,0,0}, + {14434,14435,14430 ,5987,5988,5983 ,0,0,0}, {14397,14394,14438 ,5943,5940,5991 ,0,0,0}, + {14436,14431,14435 ,5989,5984,5988 ,0,0,0}, {14438,14394,14436 ,5991,5940,5989 ,0,0,0}, + {14432,14397,14396 ,5985,5943,5942 ,0,0,0}, {14392,14394,14397 ,5938,5940,5943 ,0,0,0}, + {14380,14418,14429 ,5923,5971,5982 ,0,0,0}, {14371,14433,14387 ,5912,5986,5932 ,0,0,0}, + {14372,14439,14378 ,5913,5992,5921 ,0,0,0}, {14429,14373,14377 ,5982,5914,5920 ,0,0,0}, + {14372,14378,14373 ,5913,5921,5914 ,0,0,0}, {14439,14440,14434 ,5992,5993,5987 ,0,0,0}, + {14439,14434,14378 ,5992,5987,5921 ,0,0,0}, {14440,14441,14435 ,5993,5994,5988 ,0,0,0}, + {14440,14435,14434 ,5993,5988,5987 ,0,0,0}, {14441,14442,14436 ,5994,5995,5989 ,0,0,0}, + {14441,14436,14435 ,5994,5989,5988 ,0,0,0}, {14442,14437,14438 ,5995,5990,5991 ,0,0,0}, + {14438,14436,14442 ,5991,5989,5995 ,0,0,0}, {14437,14395,14438 ,5990,5941,5991 ,0,0,0}, + {14396,14395,14400 ,5942,5941,5946 ,0,0,0}, {14397,14438,14395 ,5943,5991,5941 ,0,0,0}, + {14433,14371,14418 ,5986,5912,5971 ,0,0,0}, {14373,14418,14371 ,5914,5971,5912 ,0,0,0}, + {14439,13598,13698 ,5992,5928,5996 ,0,0,0}, {13679,14372,14371 ,5927,5913,5912 ,0,0,0}, + {14440,13698,13903 ,5993,5996,5997 ,0,0,0}, {13598,14439,14372 ,5928,5992,5913 ,0,0,0}, + {14441,13903,13705 ,5994,5997,5998 ,0,0,0}, {13698,14440,14439 ,5996,5993,5992 ,0,0,0}, + {14442,13705,13716 ,5995,5998,5999 ,0,0,0}, {13903,14441,14440 ,5997,5994,5993 ,0,0,0}, + {14437,13716,13702 ,5990,5999,6000 ,0,0,0}, {13705,14442,14441 ,5998,5995,5994 ,0,0,0}, + {14401,13702,13708 ,5947,6000,5950 ,0,0,0}, {13716,14437,14442 ,5999,5990,5995 ,0,0,0}, + {13708,14399,14401 ,5950,5945,5947 ,0,0,0}, {13702,14401,14437 ,6000,5947,5990 ,0,0,0}, + {14443,14444,14445 ,6001,6002,6003 ,0,0,0}, {14446,13133,13130 ,6004,6005,6006 ,0,0,0}, + {14445,14447,14448 ,6003,6007,6008 ,0,0,0}, {14447,14449,14448 ,6007,6009,6008 ,0,0,0}, + {14450,14451,14452 ,6010,6011,6012 ,0,0,0}, {14452,14453,14450 ,6012,6013,6010 ,0,0,0}, + {14454,14455,14456 ,6014,6015,6016 ,0,0,0}, {14457,14451,13136 ,6017,6011,6018 ,0,0,0}, + {14457,14452,14451 ,6017,6012,6011 ,0,0,0}, {13136,13135,14457 ,6018,5020,6017 ,0,0,0}, + {14458,13130,13138 ,6019,6006,6020 ,0,0,0}, {14459,14460,14461 ,6021,6022,6023 ,0,0,0}, + {14454,13653,13669 ,6014,6024,6025 ,0,0,0}, {14462,14463,14464 ,6026,6027,6028 ,0,0,0}, + {14465,13656,14456 ,6029,6030,6016 ,0,0,0}, {14466,14467,14460 ,6031,6032,6022 ,0,0,0}, + {13653,14456,13656 ,6024,6016,6030 ,0,0,0}, {14468,14469,14470 ,6033,6034,6035 ,0,0,0}, + {14471,14448,14449 ,6036,6008,6009 ,0,0,0}, {14472,14473,14474 ,6037,6038,6039 ,0,0,0}, + {14475,14476,14445 ,6040,6041,6003 ,0,0,0}, {14477,14478,14479 ,6042,6043,6044 ,0,0,0}, + {14470,14480,14481 ,6035,6045,6046 ,0,0,0}, {14482,14480,14483 ,6047,6045,6048 ,0,0,0}, + {14484,14485,14486 ,6049,6050,6051 ,0,0,0}, {14443,13133,14446 ,6001,6005,6004 ,0,0,0}, + {14485,14472,14486 ,6050,6037,6051 ,0,0,0}, {14476,13122,14443 ,6041,6052,6001 ,0,0,0}, + {13672,13674,14484 ,6053,6054,6049 ,0,0,0}, {14487,13123,14476 ,6055,6056,6041 ,0,0,0}, + {13122,13133,14443 ,6052,6005,6001 ,0,0,0}, {14487,14488,13125 ,6055,6057,6058 ,0,0,0}, + {14476,13123,13122 ,6041,6056,6052 ,0,0,0}, {13119,14489,13120 ,6059,6060,6061 ,0,0,0}, + {13123,14487,13125 ,6056,6055,6058 ,0,0,0}, {13111,13120,14490 ,6062,6061,6063 ,0,0,0}, + {14489,13119,14488 ,6060,6059,6057 ,0,0,0}, {13138,14451,14458 ,6020,6011,6019 ,0,0,0}, + {14451,13138,13136 ,6011,6020,6018 ,0,0,0}, {14453,14491,14450 ,6013,6064,6010 ,0,0,0}, + {14458,14446,13130 ,6019,6004,6006 ,0,0,0}, {14492,14458,14450 ,6065,6019,6010 ,0,0,0}, + {14445,14444,14447 ,6003,6002,6007 ,0,0,0}, {14492,14444,14446 ,6065,6002,6004 ,0,0,0}, + {14487,14493,14488 ,6055,6066,6057 ,0,0,0}, {14446,14444,14443 ,6004,6002,6001 ,0,0,0}, + {14494,14495,14489 ,6067,6068,6060 ,0,0,0}, {14476,14443,14445 ,6041,6001,6003 ,0,0,0}, + {14493,14487,14475 ,6066,6055,6040 ,0,0,0}, {13120,14489,14490 ,6061,6060,6063 ,0,0,0}, + {13125,14488,13119 ,6058,6057,6059 ,0,0,0}, {14488,14493,14494 ,6057,6066,6067 ,0,0,0}, + {14496,14490,14489 ,6069,6063,6060 ,0,0,0}, {14451,14450,14458 ,6011,6010,6019 ,0,0,0}, + {14497,14491,14453 ,6070,6064,6013 ,0,0,0}, {14497,14466,14491 ,6070,6031,6064 ,0,0,0}, + {14458,14492,14446 ,6019,6065,6004 ,0,0,0}, {14491,14498,14492 ,6064,6071,6065 ,0,0,0}, + {14448,14483,14475 ,6008,6048,6040 ,0,0,0}, {14498,14447,14444 ,6071,6007,6002 ,0,0,0}, + {14470,14495,14494 ,6035,6068,6067 ,0,0,0}, {14469,14495,14470 ,6034,6068,6035 ,0,0,0}, + {14476,14475,14487 ,6041,6040,6055 ,0,0,0}, {14445,14448,14475 ,6003,6008,6040 ,0,0,0}, + {14488,14494,14489 ,6057,6067,6060 ,0,0,0}, {14483,14480,14493 ,6048,6045,6066 ,0,0,0}, + {14489,14495,14496 ,6060,6068,6069 ,0,0,0}, {14494,14480,14470 ,6067,6045,6035 ,0,0,0}, + {14499,14496,14495 ,6072,6069,6068 ,0,0,0}, {14450,14491,14492 ,6010,6064,6065 ,0,0,0}, + {14467,14466,14497 ,6032,6031,6070 ,0,0,0}, {14500,14459,14501 ,6073,6021,6074 ,0,0,0}, + {14492,14498,14444 ,6065,6071,6002 ,0,0,0}, {14502,14498,14466 ,6075,6071,6031 ,0,0,0}, + {14483,14448,14471 ,6048,6008,6036 ,0,0,0}, {14502,14449,14447 ,6075,6009,6007 ,0,0,0}, + {14503,14468,14481 ,6076,6033,6046 ,0,0,0}, {14493,14480,14494 ,6066,6045,6067 ,0,0,0}, + {14475,14483,14493 ,6040,6048,6066 ,0,0,0}, {14483,14471,14482 ,6048,6036,6047 ,0,0,0}, + {14469,14468,14504 ,6034,6033,6077 ,0,0,0}, {14482,14481,14480 ,6047,6046,6045 ,0,0,0}, + {14495,14469,14499 ,6068,6034,6072 ,0,0,0}, {14470,14481,14468 ,6035,6046,6033 ,0,0,0}, + {14505,14499,14469 ,6078,6072,6034 ,0,0,0}, {14491,14466,14498 ,6064,6031,6071 ,0,0,0}, + {14461,14460,14467 ,6023,6022,6032 ,0,0,0}, {14449,14506,14471 ,6009,6079,6036 ,0,0,0}, + {14498,14502,14447 ,6071,6075,6007 ,0,0,0}, {14507,14502,14460 ,6080,6075,6022 ,0,0,0}, + {14471,14508,14482 ,6036,6081,6047 ,0,0,0}, {14507,14506,14449 ,6080,6079,6009 ,0,0,0}, + {14482,14509,14481 ,6047,6082,6046 ,0,0,0}, {14508,14471,14506 ,6081,6036,6079 ,0,0,0}, + {14468,14478,14504 ,6033,6043,6077 ,0,0,0}, {14509,14482,14508 ,6082,6047,6081 ,0,0,0}, + {14510,14504,14477 ,6083,6077,6042 ,0,0,0}, {14503,14481,14509 ,6076,6046,6082 ,0,0,0}, + {14469,14504,14505 ,6034,6077,6078 ,0,0,0}, {14468,14503,14478 ,6033,6076,6043 ,0,0,0}, + {14510,14505,14504 ,6083,6078,6077 ,0,0,0}, {14466,14460,14502 ,6031,6022,6075 ,0,0,0}, + {14501,14459,14461 ,6074,6021,6023 ,0,0,0}, {14506,14463,14508 ,6079,6027,6081 ,0,0,0}, + {14502,14507,14449 ,6075,6080,6009 ,0,0,0}, {14459,14511,14507 ,6021,6084,6080 ,0,0,0}, + {14508,14462,14509 ,6081,6026,6082 ,0,0,0}, {14511,14463,14506 ,6084,6027,6079 ,0,0,0}, + {14509,14512,14503 ,6082,6085,6076 ,0,0,0}, {14463,14462,14508 ,6027,6026,6081 ,0,0,0}, + {14513,14478,14503 ,6086,6043,6076 ,0,0,0}, {14512,14509,14462 ,6085,6082,6026 ,0,0,0}, + {14514,14477,14474 ,6087,6042,6039 ,0,0,0}, {14503,14512,14513 ,6076,6085,6086 ,0,0,0}, + {14513,14479,14478 ,6086,6044,6043 ,0,0,0}, {14510,14477,14514 ,6083,6042,6087 ,0,0,0}, + {14504,14478,14477 ,6077,6043,6042 ,0,0,0}, {14460,14459,14507 ,6022,6021,6080 ,0,0,0}, + {14515,14500,14501 ,6088,6073,6074 ,0,0,0}, {14516,14512,14462 ,6089,6085,6026 ,0,0,0}, + {14507,14511,14506 ,6080,6084,6079 ,0,0,0}, {14500,14455,14511 ,6073,6015,6084 ,0,0,0}, + {14517,14513,14512 ,6090,6086,6085 ,0,0,0}, {14455,14464,14463 ,6015,6028,6027 ,0,0,0}, + {14518,14479,14513 ,6091,6044,6086 ,0,0,0}, {14464,14516,14462 ,6028,6089,6026 ,0,0,0}, + {14486,14472,14519 ,6051,6037,6092 ,0,0,0}, {14516,14517,14512 ,6089,6090,6085 ,0,0,0}, + {14474,14479,14520 ,6039,6044,6093 ,0,0,0}, {14518,14513,14517 ,6091,6086,6090 ,0,0,0}, + {14520,14479,14518 ,6093,6044,6091 ,0,0,0}, {14514,14474,14473 ,6087,6039,6038 ,0,0,0}, + {14477,14479,14474 ,6042,6044,6039 ,0,0,0}, {14459,14500,14511 ,6021,6073,6084 ,0,0,0}, + {14456,14515,14465 ,6016,6088,6029 ,0,0,0}, {14454,14521,14464 ,6014,6094,6028 ,0,0,0}, + {14511,14455,14463 ,6084,6015,6027 ,0,0,0}, {14454,14464,14455 ,6014,6028,6015 ,0,0,0}, + {14521,14522,14516 ,6094,6095,6089 ,0,0,0}, {14521,14516,14464 ,6094,6089,6028 ,0,0,0}, + {14522,14523,14517 ,6095,6096,6090 ,0,0,0}, {14522,14517,14516 ,6095,6090,6089 ,0,0,0}, + {14523,14524,14518 ,6096,6097,6091 ,0,0,0}, {14523,14518,14517 ,6096,6091,6090 ,0,0,0}, + {14524,14519,14520 ,6097,6092,6093 ,0,0,0}, {14520,14518,14524 ,6093,6091,6097 ,0,0,0}, + {14519,14472,14520 ,6092,6037,6093 ,0,0,0}, {14473,14472,14485 ,6038,6037,6050 ,0,0,0}, + {14474,14520,14472 ,6039,6093,6037 ,0,0,0}, {14515,14456,14500 ,6088,6016,6073 ,0,0,0}, + {14455,14500,14456 ,6015,6073,6016 ,0,0,0}, {14521,13669,13663 ,6094,6025,6098 ,0,0,0}, + {13653,14454,14456 ,6024,6014,6016 ,0,0,0}, {14522,13663,13667 ,6095,6098,6099 ,0,0,0}, + {13669,14521,14454 ,6025,6094,6014 ,0,0,0}, {14523,13667,13666 ,6096,6099,6100 ,0,0,0}, + {13663,14522,14521 ,6098,6095,6094 ,0,0,0}, {14524,13666,13676 ,6097,6100,6101 ,0,0,0}, + {13667,14523,14522 ,6099,6096,6095 ,0,0,0}, {14519,13676,13638 ,6092,6101,6102 ,0,0,0}, + {13666,14524,14523 ,6100,6097,6096 ,0,0,0}, {14486,13638,13672 ,6051,6102,6053 ,0,0,0}, + {13676,14519,14524 ,6101,6092,6097 ,0,0,0}, {13672,14484,14486 ,6053,6049,6051 ,0,0,0}, + {13638,14486,14519 ,6102,6051,6092 ,0,0,0}, {14525,14526,14527 ,730,6103,6103 ,0,0,0}, + {12755,12697,12694 ,6103,730,730 ,0,0,0}, {14528,14526,14529 ,6104,6103,6105 ,0,0,0}, + {14528,14530,14531 ,6104,6106,6103 ,0,0,0}, {14532,14527,14533 ,6107,6103,6108 ,0,0,0}, + {14530,14534,14535 ,6106,6109,6110 ,0,0,0}, {14536,14537,14533 ,6103,6111,6108 ,0,0,0}, + {14535,14538,14539 ,6110,6112,6110 ,0,0,0}, {14540,14536,14541 ,6111,6103,6103 ,0,0,0}, + {14539,14542,14543 ,6110,6113,6112 ,0,0,0}, {14543,14544,14545 ,6112,6109,6110 ,0,0,0}, + {14545,14546,14547 ,6110,6106,6114 ,0,0,0}, {14541,14548,14549 ,6103,730,6115 ,0,0,0}, + {14550,14547,14551 ,6105,6114,6104 ,0,0,0}, {14552,14553,14554 ,6111,730,6111 ,0,0,0}, + {14555,14547,14550 ,6111,6114,6105 ,0,0,0}, {14554,14556,14557 ,6111,6110,6114 ,0,0,0}, + {14558,14559,14560 ,730,6114,6108 ,0,0,0}, {12703,12768,12770 ,6110,6111,6110 ,0,0,0}, + {14561,14562,14563 ,6115,730,6111 ,0,0,0}, {12767,12702,12765 ,730,730,6114 ,0,0,0}, + {14564,14565,12686 ,6111,6110,6110 ,0,0,0}, {12698,12761,12700 ,730,6114,6103 ,0,0,0}, + {12683,12733,12730 ,730,730,6114 ,0,0,0}, {12697,12756,12759 ,730,730,6103 ,0,0,0}, + {12727,12679,12728 ,6114,730,730 ,0,0,0}, {12753,12755,12694 ,730,6103,730 ,0,0,0}, + {12677,12721,12674 ,6103,6103,730 ,0,0,0}, {12747,12749,12688 ,730,730,730 ,0,0,0}, + {12715,12712,12673 ,730,730,730 ,0,0,0}, {12741,12687,12667 ,730,730,730 ,0,0,0}, + {12671,12710,12709 ,730,730,730 ,0,0,0}, {12671,12672,12710 ,730,730,730 ,0,0,0}, + {12673,12712,12672 ,730,730,730 ,0,0,0}, {12741,12667,12705 ,730,730,730 ,0,0,0}, + {12667,12671,12706 ,730,730,730 ,0,0,0}, {12716,12674,12718 ,6103,730,730 ,0,0,0}, + {12673,12674,12716 ,730,730,6103 ,0,0,0}, {12687,12744,12688 ,730,730,730 ,0,0,0}, + {12687,12743,12744 ,730,730,730 ,0,0,0}, {12677,12679,12724 ,6103,730,6103 ,0,0,0}, + {12677,12724,12722 ,6103,6103,730 ,0,0,0}, {12694,12692,12750 ,730,730,6103 ,0,0,0}, + {12749,12692,12688 ,730,730,730 ,0,0,0}, {12683,12730,12680 ,730,6114,6103 ,0,0,0}, + {12679,12680,12728 ,730,6103,730 ,0,0,0}, {12697,12755,12756 ,730,6103,730 ,0,0,0}, + {12736,12734,12686 ,6110,6111,6110 ,0,0,0}, {12683,12686,12734 ,730,6110,6111 ,0,0,0}, + {12698,12759,12761 ,730,6103,6114 ,0,0,0}, {12697,12759,12698 ,730,6103,730 ,0,0,0}, + {14563,14566,14564 ,6111,6111,6111 ,0,0,0}, {14567,14564,14566 ,6114,6111,6111 ,0,0,0}, + {12761,12762,12700 ,6114,730,6103 ,0,0,0}, {12700,12765,12702 ,6103,6114,730 ,0,0,0}, + {12762,12765,12700 ,730,6114,6103 ,0,0,0}, {12767,12768,12702 ,730,6111,730 ,0,0,0}, + {14568,14560,14559 ,6107,6108,6114 ,0,0,0}, {12703,12702,12768 ,6110,730,6111 ,0,0,0}, + {12770,14556,12703 ,6110,6110,6110 ,0,0,0}, {14559,14555,14569 ,6114,6111,730 ,0,0,0}, + {14570,14571,14558 ,6111,6110,730 ,0,0,0}, {14571,14561,14563 ,6110,6115,6111 ,0,0,0}, + {14544,14546,14545 ,6109,6106,6110 ,0,0,0}, {12753,12694,12750 ,730,730,6103 ,0,0,0}, + {12750,12692,12749 ,6103,730,730 ,0,0,0}, {12747,12688,12744 ,730,730,730 ,0,0,0}, + {12743,12687,12741 ,730,730,730 ,0,0,0}, {12705,12667,12706 ,730,730,730 ,0,0,0}, + {12706,12671,12709 ,730,730,730 ,0,0,0}, {12710,12672,12712 ,730,730,730 ,0,0,0}, + {12715,12673,12716 ,730,730,6103 ,0,0,0}, {12718,12674,12721 ,730,730,6103 ,0,0,0}, + {12721,12677,12722 ,6103,6103,730 ,0,0,0}, {12724,12679,12727 ,6103,730,6114 ,0,0,0}, + {12728,12680,12730 ,730,6103,6114 ,0,0,0}, {12733,12683,12734 ,730,730,6111 ,0,0,0}, + {12736,12686,14565 ,6110,6110,6110 ,0,0,0}, {14565,14564,14567 ,6110,6111,6114 ,0,0,0}, + {14566,14563,14562 ,6111,6111,730 ,0,0,0}, {14561,14571,14570 ,6115,6110,6111 ,0,0,0}, + {14572,14558,14560 ,6111,730,6108 ,0,0,0}, {14558,14572,14570 ,730,6111,6111 ,0,0,0}, + {14568,14559,14569 ,6107,6114,730 ,0,0,0}, {14569,14555,14550 ,730,6111,6105 ,0,0,0}, + {14551,14547,14546 ,6104,6114,6106 ,0,0,0}, {14545,14539,14543 ,6110,6110,6112 ,0,0,0}, + {14542,14539,14538 ,6113,6110,6112 ,0,0,0}, {14538,14535,14534 ,6112,6110,6109 ,0,0,0}, + {14530,14535,14531 ,6106,6110,6103 ,0,0,0}, {14528,14531,14526 ,6104,6103,6103 ,0,0,0}, + {14525,14529,14526 ,730,6105,6103 ,0,0,0}, {14532,14525,14527 ,6107,730,6103 ,0,0,0}, + {14536,14533,14527 ,6103,6108,6103 ,0,0,0}, {14536,14540,14537 ,6103,6111,6111 ,0,0,0}, + {14541,14549,14540 ,6103,6115,6111 ,0,0,0}, {14541,14553,14548 ,6103,730,730 ,0,0,0}, + {14552,14554,14557 ,6111,6111,6114 ,0,0,0}, {14548,14553,14552 ,730,730,6111 ,0,0,0}, + {14556,14554,12703 ,6110,6111,6110 ,0,0,0}, {12739,12707,14573 ,6116,6117,6118 ,0,0,0}, + {12742,14574,14575 ,6119,6120,6121 ,0,0,0}, {14576,14577,12894 ,6122,6123,6124 ,0,0,0}, + {12984,12754,12981 ,6125,6126,6127 ,0,0,0}, {12910,12909,13321 ,6128,6129,6130 ,0,0,0}, + {12840,12843,12764 ,6131,6132,6122 ,0,0,0}, {14578,12845,14579 ,6133,6134,6135 ,0,0,0}, + {14580,14581,14582 ,6136,6137,6138 ,0,0,0}, {12711,12791,12794 ,6122,6120,6139 ,0,0,0}, + {14577,12879,12884 ,6123,6140,6141 ,0,0,0}, {14583,12962,12964 ,6139,6142,6143 ,0,0,0}, + {13234,14584,13235 ,6144,6145,6146 ,0,0,0}, {13292,14585,13285 ,6147,6148,6149 ,0,0,0}, + {12812,14586,12815 ,6150,6144,6150 ,0,0,0}, {14587,12870,13269 ,6151,6134,6152 ,0,0,0}, + {14588,12771,14589 ,6145,6153,6154 ,0,0,0}, {14587,13269,14590 ,6151,6152,6155 ,0,0,0}, + {14591,13269,13268 ,6156,6152,6157 ,0,0,0}, {14592,14593,14594 ,6158,6144,6159 ,0,0,0}, + {14595,14596,14597 ,6160,6161,6162 ,0,0,0}, {13268,14598,14591 ,6157,6163,6156 ,0,0,0}, + {14599,14600,13268 ,6158,6164,6157 ,0,0,0}, {13274,14601,14599 ,6155,6165,6158 ,0,0,0}, + {14602,13279,14603 ,6166,6167,6116 ,0,0,0}, {13274,14599,13268 ,6155,6158,6157 ,0,0,0}, + {13286,14603,13279 ,6168,6116,6167 ,0,0,0}, {14594,14582,14581 ,6159,6138,6137 ,0,0,0}, + {14604,14605,14606 ,6122,6169,6170 ,0,0,0}, {14607,13274,13272 ,6171,6155,6172 ,0,0,0}, + {13272,14608,14607 ,6172,6118,6171 ,0,0,0}, {14609,14610,13282 ,6173,6174,6175 ,0,0,0}, + {13272,13271,14608 ,6172,6176,6118 ,0,0,0}, {13271,14610,14611 ,6176,6174,6177 ,0,0,0}, + {14612,12935,12934 ,6120,6146,6154 ,0,0,0}, {13271,13282,14610 ,6176,6175,6174 ,0,0,0}, + {14609,13282,13277 ,6173,6175,6178 ,0,0,0}, {14589,12773,14613 ,6154,6120,6145 ,0,0,0}, + {14614,14615,14616 ,6177,6179,6180 ,0,0,0}, {14617,14609,13277 ,6181,6173,6178 ,0,0,0}, + {14615,14618,14604 ,6179,6182,6122 ,0,0,0}, {14592,14619,14593 ,6158,6183,6144 ,0,0,0}, + {14606,14605,14620 ,6170,6169,6184 ,0,0,0}, {13286,13285,14621 ,6168,6149,6185 ,0,0,0}, + {14622,12719,14623 ,6186,6187,6119 ,0,0,0}, {12815,14624,12816 ,6150,6144,6188 ,0,0,0}, + {14625,13237,14626 ,6145,6144,6150 ,0,0,0}, {14619,13002,14627 ,6183,6189,6190 ,0,0,0}, + {13232,14628,14629 ,6154,6120,6127 ,0,0,0}, {12969,12968,13332 ,6191,6142,6192 ,0,0,0}, + {14574,12742,12740 ,6120,6119,6122 ,0,0,0}, {13326,12900,12899 ,6193,6194,6195 ,0,0,0}, + {12971,13227,13221 ,6196,6186,6197 ,0,0,0}, {12847,12769,12766 ,6196,6134,6138 ,0,0,0}, + {14577,12998,12993 ,6123,6198,6199 ,0,0,0}, {12764,12843,12766 ,6122,6132,6138 ,0,0,0}, + {12839,12840,12763 ,6157,6131,6137 ,0,0,0}, {12839,12763,12760 ,6157,6137,6131 ,0,0,0}, + {12758,12837,12760 ,6200,6143,6131 ,0,0,0}, {12746,12957,12975 ,6117,6201,6202 ,0,0,0}, + {14580,14630,14631 ,6136,6200,6156 ,0,0,0}, {12831,14632,12826 ,6118,6203,6132 ,0,0,0}, + {14633,12833,12835 ,6133,6204,6133 ,0,0,0}, {12763,12840,12764 ,6137,6131,6122 ,0,0,0}, + {12843,12847,12766 ,6132,6196,6138 ,0,0,0}, {12833,14634,12828 ,6204,6153,6201 ,0,0,0}, + {14635,12826,14632 ,6201,6132,6203 ,0,0,0}, {12748,12746,12975 ,6187,6117,6202 ,0,0,0}, + {12760,12837,12839 ,6131,6143,6157 ,0,0,0}, {12822,13252,13254 ,6132,6144,6205 ,0,0,0}, + {12835,12987,14633 ,6133,6201,6133 ,0,0,0}, {12758,12987,12837 ,6200,6201,6143 ,0,0,0}, + {13259,12821,13254 ,6206,6116,6205 ,0,0,0}, {12853,13259,13261 ,6207,6206,6204 ,0,0,0}, + {14636,14637,12827 ,6132,6119,6207 ,0,0,0}, {13252,12822,12826 ,6144,6132,6132 ,0,0,0}, + {12821,13259,12851 ,6116,6206,6121 ,0,0,0}, {12821,12822,13254 ,6116,6132,6205 ,0,0,0}, + {13262,12857,13261 ,6208,6207,6204 ,0,0,0}, {12853,12851,13259 ,6207,6121,6206 ,0,0,0}, + {12854,12853,13261 ,6209,6207,6204 ,0,0,0}, {13262,13264,12860 ,6208,6142,6196 ,0,0,0}, + {12857,12854,13261 ,6207,6209,6204 ,0,0,0}, {12859,12857,13262 ,6133,6207,6208 ,0,0,0}, + {13262,12860,12859 ,6208,6196,6133 ,0,0,0}, {13264,12863,12860 ,6142,6134,6196 ,0,0,0}, + {13267,12865,13264 ,6148,6131,6142 ,0,0,0}, {13264,12865,12863 ,6142,6131,6134 ,0,0,0}, + {13267,12866,12865 ,6148,6205,6131 ,0,0,0}, {12866,13267,12869 ,6205,6148,6204 ,0,0,0}, + {13267,12870,12869 ,6148,6134,6204 ,0,0,0}, {14591,14590,13269 ,6156,6155,6152 ,0,0,0}, + {14607,14601,13274 ,6171,6165,6155 ,0,0,0}, {14600,14598,13268 ,6164,6163,6157 ,0,0,0}, + {14608,13271,14611 ,6118,6176,6177 ,0,0,0}, {14602,14638,13277 ,6166,6210,6178 ,0,0,0}, + {14639,13291,14640 ,6157,6190,6211 ,0,0,0}, {14617,14641,14642 ,6181,6212,6182 ,0,0,0}, + {12883,14577,12884 ,6174,6123,6141 ,0,0,0}, {14643,14644,14577 ,6213,6214,6123 ,0,0,0}, + {13329,13326,12873 ,6215,6193,6216 ,0,0,0}, {13012,13014,12874 ,6217,6218,6219 ,0,0,0}, + {12899,12873,13326 ,6195,6216,6193 ,0,0,0}, {12904,12903,13318 ,6220,6221,6222 ,0,0,0}, + {12900,13325,12903 ,6194,6223,6221 ,0,0,0}, {13321,12909,12906 ,6130,6129,6181 ,0,0,0}, + {12906,13318,13321 ,6181,6222,6130 ,0,0,0}, {12915,13322,12916 ,6224,6225,6226 ,0,0,0}, + {12912,13321,13322 ,6227,6130,6225 ,0,0,0}, {12992,14577,12993 ,6212,6123,6199 ,0,0,0}, + {12923,14645,12924 ,6203,6228,6201 ,0,0,0}, {13014,12875,12874 ,6218,6229,6219 ,0,0,0}, + {14646,14647,14648 ,6230,6231,6232 ,0,0,0}, {13014,13015,13294 ,6218,6200,6233 ,0,0,0}, + {12915,12912,13322 ,6224,6227,6225 ,0,0,0}, {13322,12918,12916 ,6225,6234,6226 ,0,0,0}, + {12912,12910,13321 ,6227,6128,6130 ,0,0,0}, {12992,12991,14577 ,6212,6235,6123 ,0,0,0}, + {12904,13318,12906 ,6220,6222,6181 ,0,0,0}, {13325,13318,12903 ,6223,6222,6221 ,0,0,0}, + {13326,13325,12900 ,6193,6223,6194 ,0,0,0}, {12875,13329,12873 ,6229,6215,6216 ,0,0,0}, + {13329,12875,13294 ,6215,6229,6233 ,0,0,0}, {14644,12999,14577 ,6214,6236,6123 ,0,0,0}, + {13002,12999,14627 ,6189,6236,6190 ,0,0,0}, {14577,14649,14650 ,6123,6170,6214 ,0,0,0}, + {12891,14577,12887 ,6237,6123,6167 ,0,0,0}, {14576,14649,14577 ,6122,6170,6123 ,0,0,0}, + {12893,14651,14652 ,6238,6180,6179 ,0,0,0}, {14653,12930,14654 ,6197,6165,6196 ,0,0,0}, + {14655,12735,14656 ,6131,6122,6132 ,0,0,0}, {12898,14657,14651 ,6239,6240,6180 ,0,0,0}, + {14658,14659,14597 ,6171,6152,6162 ,0,0,0}, {12726,14660,12725 ,6204,6208,6126 ,0,0,0}, + {14661,14620,14662 ,6241,6184,6136 ,0,0,0}, {14663,12941,12944 ,6179,6179,6202 ,0,0,0}, + {12953,14660,12952 ,6127,6208,6242 ,0,0,0}, {13078,14664,14665 ,6156,6200,6136 ,0,0,0}, + {13081,13083,14666 ,6137,6135,6133 ,0,0,0}, {14667,14668,14669 ,6207,6133,6208 ,0,0,0}, + {13039,13072,13075 ,6196,6158,6159 ,0,0,0}, {13062,13032,13027 ,6181,6243,6139 ,0,0,0}, + {13046,13048,14670 ,6244,6245,6246 ,0,0,0}, {13025,14671,14672 ,6247,6190,6136 ,0,0,0}, + {14673,14647,14674 ,6248,6231,6170 ,0,0,0}, {14675,14676,13054 ,6152,6249,6250 ,0,0,0}, + {14677,14647,14673 ,6251,6231,6248 ,0,0,0}, {14678,14679,14680 ,6252,6253,6254 ,0,0,0}, + {14679,14646,14680 ,6253,6230,6254 ,0,0,0}, {14681,14682,14683 ,6255,6256,6257 ,0,0,0}, + {14684,14685,14686 ,6258,6259,6260 ,0,0,0}, {14679,14678,14686 ,6253,6252,6260 ,0,0,0}, + {14686,14685,14679 ,6260,6259,6253 ,0,0,0}, {14685,14684,14687 ,6259,6258,6261 ,0,0,0}, + {14688,14683,14689 ,6262,6257,6263 ,0,0,0}, {14687,14689,14685 ,6261,6263,6259 ,0,0,0}, + {14683,14682,14689 ,6257,6256,6263 ,0,0,0}, {14690,14691,14682 ,6264,6265,6256 ,0,0,0}, + {14687,14688,14689 ,6261,6262,6263 ,0,0,0}, {14681,14690,14682 ,6255,6264,6256 ,0,0,0}, + {14680,14646,14648 ,6254,6230,6232 ,0,0,0}, {14692,14693,13055 ,6138,6134,6266 ,0,0,0}, + {14648,14647,14677 ,6232,6231,6251 ,0,0,0}, {14674,14693,14692 ,6170,6134,6138 ,0,0,0}, + {14694,13048,13049 ,6267,6245,6268 ,0,0,0}, {13026,14672,14695 ,6167,6136,6199 ,0,0,0}, + {13043,13046,14671 ,6235,6244,6190 ,0,0,0}, {14696,13097,14697 ,6197,6164,6191 ,0,0,0}, + {13091,13090,14698 ,6171,6118,6269 ,0,0,0}, {13036,13033,13066 ,6270,6270,6174 ,0,0,0}, + {14696,13099,13097 ,6197,6163,6164 ,0,0,0}, {13071,13036,13066 ,6127,6270,6174 ,0,0,0}, + {14699,14631,14630 ,6137,6156,6200 ,0,0,0}, {14700,14701,14702 ,6213,6271,6169 ,0,0,0}, + {13060,13062,14703 ,6173,6181,6272 ,0,0,0}, {13102,13099,14696 ,6156,6163,6197 ,0,0,0}, + {14692,14704,14674 ,6138,6273,6170 ,0,0,0}, {14705,13103,13102 ,6201,6155,6156 ,0,0,0}, + {14705,13107,13105 ,6201,6134,6151 ,0,0,0}, {14706,14660,14707 ,6214,6208,6133 ,0,0,0}, + {14706,12720,12723 ,6214,6208,6117 ,0,0,0}, {14708,14709,14710 ,6190,6214,6199 ,0,0,0}, + {13097,13096,14697 ,6164,6158,6191 ,0,0,0}, {13091,14698,14697 ,6171,6269,6191 ,0,0,0}, + {14711,14712,14713 ,6274,6118,6183 ,0,0,0}, {14714,14715,14716 ,6149,6275,6214 ,0,0,0}, + {14717,14673,14704 ,6243,6248,6273 ,0,0,0}, {14717,14704,14718 ,6243,6273,6276 ,0,0,0}, + {14716,14606,14620 ,6214,6170,6184 ,0,0,0}, {14604,14618,14605 ,6122,6182,6169 ,0,0,0}, + {14616,14719,14614 ,6180,6244,6177 ,0,0,0}, {14615,14614,14618 ,6179,6177,6182 ,0,0,0}, + {14592,14720,13003 ,6158,6127,6249 ,0,0,0}, {12898,14719,14657 ,6239,6244,6240 ,0,0,0}, + {14616,14657,14719 ,6180,6240,6244 ,0,0,0}, {12898,14651,12895 ,6239,6180,6277 ,0,0,0}, + {14592,13003,13002 ,6158,6249,6189 ,0,0,0}, {12894,12893,14652 ,6124,6238,6179 ,0,0,0}, + {12893,12895,14651 ,6238,6277,6180 ,0,0,0}, {13021,13289,13297 ,6278,6279,6280 ,0,0,0}, + {13289,14640,13291 ,6279,6211,6190 ,0,0,0}, {14576,12894,14652 ,6122,6124,6179 ,0,0,0}, + {14721,14577,14650 ,6275,6123,6214 ,0,0,0}, {12894,14577,12891 ,6124,6123,6237 ,0,0,0}, + {13295,13018,13297 ,6281,6282,6280 ,0,0,0}, {13005,14720,14722 ,6283,6127,6174 ,0,0,0}, + {13003,14720,13005 ,6249,6127,6283 ,0,0,0}, {14593,14582,14594 ,6144,6138,6159 ,0,0,0}, + {14580,14631,14581 ,6136,6156,6137 ,0,0,0}, {14699,14578,14579 ,6137,6133,6135 ,0,0,0}, + {14578,14699,14630 ,6133,6137,6200 ,0,0,0}, {14578,12769,12845 ,6133,6134,6134 ,0,0,0}, + {13252,14635,13250 ,6144,6201,6209 ,0,0,0}, {12845,12769,12847 ,6134,6134,6196 ,0,0,0}, + {12987,12758,12986 ,6201,6200,6158 ,0,0,0}, {12751,12748,12978 ,6208,6187,6284 ,0,0,0}, + {12984,12986,12757 ,6125,6158,6204 ,0,0,0}, {14723,13247,13248 ,6191,6165,6179 ,0,0,0}, + {13245,14724,13222 ,6142,6172,6197 ,0,0,0}, {12969,13227,12971 ,6191,6186,6196 ,0,0,0}, + {13332,13227,12969 ,6192,6186,6191 ,0,0,0}, {13332,12968,13230 ,6192,6142,6285 ,0,0,0}, + {14725,12965,12962 ,6192,6228,6142 ,0,0,0}, {12791,12711,12713 ,6120,6122,6119 ,0,0,0}, + {12714,12789,12713 ,6171,6202,6119 ,0,0,0}, {14726,13242,13240 ,6150,6144,6150 ,0,0,0}, + {14586,12812,12810 ,6144,6150,6187 ,0,0,0}, {12818,12816,14624 ,6150,6188,6144 ,0,0,0}, + {12810,14727,14586 ,6187,6144,6144 ,0,0,0}, {12784,14622,14728 ,6165,6186,6286 ,0,0,0}, + {14727,12806,14729 ,6144,6192,6144 ,0,0,0}, {12804,12803,14729 ,6145,6145,6144 ,0,0,0}, + {14730,14731,14660 ,6143,6133,6208 ,0,0,0}, {14612,14732,12935 ,6120,6176,6146 ,0,0,0}, + {14655,12732,12735 ,6131,6137,6122 ,0,0,0}, {12738,13083,13082 ,6134,6135,6134 ,0,0,0}, + {14654,12925,12924 ,6196,6139,6201 ,0,0,0}, {14653,12931,12928 ,6197,6286,6165 ,0,0,0}, + {14663,12944,14733 ,6179,6202,6139 ,0,0,0}, {12947,14733,12946 ,6203,6139,6228 ,0,0,0}, + {13081,14666,14664 ,6137,6133,6200 ,0,0,0}, {14664,13078,13081 ,6200,6156,6137 ,0,0,0}, + {14734,14735,14736 ,6209,6207,6166 ,0,0,0}, {14737,13076,14665 ,6138,6137,6136 ,0,0,0}, + {14732,12937,12935 ,6176,6191,6146 ,0,0,0}, {14738,14739,14740 ,6186,6228,6287 ,0,0,0}, + {12931,14653,14612 ,6286,6197,6120 ,0,0,0}, {12931,14612,12934 ,6286,6120,6154 ,0,0,0}, + {12930,14653,12928 ,6165,6197,6165 ,0,0,0}, {12925,14654,12930 ,6139,6196,6165 ,0,0,0}, + {14645,12923,12941 ,6228,6203,6179 ,0,0,0}, {14645,14654,12924 ,6228,6196,6201 ,0,0,0}, + {12729,14660,12726 ,6200,6208,6204 ,0,0,0}, {14663,14645,12941 ,6179,6228,6179 ,0,0,0}, + {14741,14733,12947 ,6133,6139,6203 ,0,0,0}, {12946,14733,12944 ,6228,6139,6202 ,0,0,0}, + {12729,12731,14660 ,6200,6131,6208 ,0,0,0}, {14660,14742,12952 ,6208,6207,6242 ,0,0,0}, + {12737,13082,14743 ,6138,6134,6196 ,0,0,0}, {14660,12731,12732 ,6208,6131,6137 ,0,0,0}, + {14660,12723,12725 ,6208,6117,6126 ,0,0,0}, {12720,14706,14623 ,6208,6214,6119 ,0,0,0}, + {14660,14706,12723 ,6208,6214,6117 ,0,0,0}, {14588,12800,12771 ,6145,6120,6153 ,0,0,0}, + {14744,14745,12775 ,6201,6121,6288 ,0,0,0}, {12719,12720,14623 ,6187,6208,6119 ,0,0,0}, + {14746,12777,12779 ,6139,6192,6131 ,0,0,0}, {14613,12775,14745 ,6145,6288,6121 ,0,0,0}, + {12810,12809,14727 ,6187,6145,6144 ,0,0,0}, {12809,12806,14727 ,6145,6192,6144 ,0,0,0}, + {12803,12800,14588 ,6145,6120,6145 ,0,0,0}, {14745,14747,14613 ,6121,6289,6145 ,0,0,0}, + {14738,14747,14748 ,6186,6289,6191 ,0,0,0}, {14745,14748,14747 ,6121,6191,6289 ,0,0,0}, + {14738,14740,14732 ,6186,6287,6176 ,0,0,0}, {14738,14748,14739 ,6186,6191,6228 ,0,0,0}, + {12937,14732,14740 ,6191,6176,6287 ,0,0,0}, {14749,12740,12739 ,6202,6122,6116 ,0,0,0}, + {14750,14751,13220 ,6165,6191,6187 ,0,0,0}, {14752,13248,13250 ,6126,6179,6209 ,0,0,0}, + {14753,14628,13230 ,6154,6120,6285 ,0,0,0}, {12957,12746,14754 ,6201,6117,6120 ,0,0,0}, + {14755,14756,12959 ,6197,6201,6207 ,0,0,0}, {14575,14754,12745 ,6121,6120,6171 ,0,0,0}, + {12708,12796,12795 ,6116,6120,6201 ,0,0,0}, {14575,12745,12742 ,6121,6171,6119 ,0,0,0}, + {12748,12975,12978 ,6187,6202,6284 ,0,0,0}, {12978,12980,12751 ,6284,6140,6208 ,0,0,0}, + {12752,12980,12981 ,6117,6140,6127 ,0,0,0}, {12752,12981,12754 ,6117,6127,6126 ,0,0,0}, + {12754,12984,12757 ,6126,6125,6204 ,0,0,0}, {12758,12757,12986 ,6200,6204,6158 ,0,0,0}, + {12835,12837,12987 ,6133,6143,6201 ,0,0,0}, {12831,12827,14637 ,6118,6207,6119 ,0,0,0}, + {12833,14633,14634 ,6204,6133,6153 ,0,0,0}, {14636,12827,12828 ,6132,6207,6201 ,0,0,0}, + {14636,12828,14634 ,6132,6201,6153 ,0,0,0}, {14632,12831,14637 ,6203,6118,6119 ,0,0,0}, + {12826,14635,13252 ,6132,6201,6144 ,0,0,0}, {14752,13250,14635 ,6126,6209,6201 ,0,0,0}, + {14757,13247,14723 ,6242,6165,6191 ,0,0,0}, {14723,13248,14752 ,6191,6179,6126 ,0,0,0}, + {13245,14757,14758 ,6142,6242,6197 ,0,0,0}, {14757,13245,13247 ,6242,6142,6165 ,0,0,0}, + {14724,14750,13222 ,6172,6165,6197 ,0,0,0}, {14758,14724,13245 ,6197,6172,6142 ,0,0,0}, + {13220,14751,13221 ,6187,6191,6197 ,0,0,0}, {13222,14750,13220 ,6197,6165,6187 ,0,0,0}, + {12971,13221,14759 ,6196,6197,6202 ,0,0,0}, {13221,14751,14759 ,6197,6191,6202 ,0,0,0}, + {14619,14592,13002 ,6183,6158,6189 ,0,0,0}, {14722,14760,14761 ,6174,6118,6273 ,0,0,0}, + {12996,14577,12999 ,6290,6123,6236 ,0,0,0}, {14644,14627,12999 ,6214,6190,6236 ,0,0,0}, + {12996,12998,14577 ,6290,6198,6123 ,0,0,0}, {12888,14577,12883 ,6152,6123,6174 ,0,0,0}, + {13009,13012,12880 ,6124,6217,6291 ,0,0,0}, {12991,12879,14577 ,6235,6140,6123 ,0,0,0}, + {13009,12880,12879 ,6124,6291,6140 ,0,0,0}, {13009,12879,12991 ,6124,6140,6235 ,0,0,0}, + {13012,12874,12880 ,6217,6219,6291 ,0,0,0}, {13014,13294,12875 ,6218,6233,6229 ,0,0,0}, + {13015,13018,13295 ,6200,6282,6281 ,0,0,0}, {13015,13295,13294 ,6200,6281,6233 ,0,0,0}, + {13020,13021,13297 ,6269,6278,6280 ,0,0,0}, {13018,13020,13297 ,6282,6269,6280 ,0,0,0}, + {13289,13021,14762 ,6279,6278,6292 ,0,0,0}, {14762,14640,13289 ,6292,6211,6279 ,0,0,0}, + {14763,13291,14639 ,6293,6190,6157 ,0,0,0}, {13292,14763,14764 ,6147,6293,6266 ,0,0,0}, + {14763,13292,13291 ,6293,6147,6190 ,0,0,0}, {14585,14765,13285 ,6148,6273,6149 ,0,0,0}, + {14764,14585,13292 ,6266,6148,6147 ,0,0,0}, {14621,14766,13286 ,6185,6294,6168 ,0,0,0}, + {14765,14621,13285 ,6273,6185,6149 ,0,0,0}, {13277,13279,14602 ,6178,6167,6166 ,0,0,0}, + {14766,14603,13286 ,6294,6116,6168 ,0,0,0}, {14638,14617,13277 ,6210,6181,6178 ,0,0,0}, + {14642,14641,14760 ,6182,6212,6118 ,0,0,0}, {14638,14641,14617 ,6210,6212,6181 ,0,0,0}, + {14722,14761,13005 ,6174,6273,6283 ,0,0,0}, {14760,14641,14761 ,6118,6212,6273 ,0,0,0}, + {13027,14695,14703 ,6139,6199,6272 ,0,0,0}, {13058,14767,13087 ,6174,6295,6177 ,0,0,0}, + {14658,14717,14718 ,6171,6243,6276 ,0,0,0}, {13093,13091,14697 ,6165,6171,6191 ,0,0,0}, + {14767,13058,14768 ,6295,6174,6162 ,0,0,0}, {14703,13062,13027 ,6272,6181,6139 ,0,0,0}, + {13026,14695,13027 ,6167,6199,6139 ,0,0,0}, {13025,14672,13026 ,6247,6136,6167 ,0,0,0}, + {13043,14671,13025 ,6235,6190,6247 ,0,0,0}, {14670,14671,13046 ,6246,6190,6244 ,0,0,0}, + {14694,14670,13048 ,6267,6246,6245 ,0,0,0}, {13049,13052,14676 ,6268,6185,6249 ,0,0,0}, + {14676,14694,13049 ,6249,6267,6268 ,0,0,0}, {13055,14675,13054 ,6266,6152,6250 ,0,0,0}, + {13054,14676,13052 ,6250,6249,6185 ,0,0,0}, {13055,14693,14675 ,6266,6134,6152 ,0,0,0}, + {14673,14674,14704 ,6248,6170,6273 ,0,0,0}, {14661,14769,14620 ,6241,6296,6184 ,0,0,0}, + {14658,14718,14659 ,6171,6276,6152 ,0,0,0}, {14661,14662,14770 ,6241,6136,6200 ,0,0,0}, + {14770,14596,14595 ,6200,6161,6160 ,0,0,0}, {14595,14597,14659 ,6160,6162,6152 ,0,0,0}, + {14770,14662,14596 ,6200,6136,6161 ,0,0,0}, {14769,14714,14716 ,6296,6149,6214 ,0,0,0}, + {14716,14620,14769 ,6214,6184,6296 ,0,0,0}, {14701,14715,14714 ,6271,6275,6149 ,0,0,0}, + {14702,14709,14700 ,6169,6214,6213 ,0,0,0}, {14701,14700,14715 ,6271,6213,6275 ,0,0,0}, + {14710,14711,14708 ,6199,6274,6190 ,0,0,0}, {14702,14710,14709 ,6169,6199,6214 ,0,0,0}, + {14713,14712,14771 ,6183,6118,6144 ,0,0,0}, {14708,14711,14713 ,6190,6274,6183 ,0,0,0}, + {13039,14771,14712 ,6196,6144,6118 ,0,0,0}, {12714,12717,12788 ,6171,6117,6139 ,0,0,0}, + {14624,12820,12818 ,6144,6150,6150 ,0,0,0}, {14624,12815,14586 ,6144,6150,6144 ,0,0,0}, + {12785,12788,12717 ,6197,6139,6117 ,0,0,0}, {12719,14622,12785 ,6187,6186,6197 ,0,0,0}, + {14588,14729,12803 ,6145,6144,6145 ,0,0,0}, {12806,12804,14729 ,6192,6145,6144 ,0,0,0}, + {12773,12775,14613 ,6120,6288,6145 ,0,0,0}, {12771,12773,14589 ,6153,6120,6154 ,0,0,0}, + {12779,12784,14728 ,6131,6165,6286 ,0,0,0}, {12781,14772,14744 ,6144,6242,6201 ,0,0,0}, + {14744,12775,12781 ,6201,6288,6144 ,0,0,0}, {14728,14746,12779 ,6286,6139,6131 ,0,0,0}, + {12777,14746,14772 ,6192,6139,6242 ,0,0,0}, {12777,14772,12781 ,6192,6242,6144 ,0,0,0}, + {12784,12785,14622 ,6165,6197,6186 ,0,0,0}, {12717,12719,12785 ,6117,6187,6197 ,0,0,0}, + {12714,12788,12789 ,6171,6139,6202 ,0,0,0}, {12713,12789,12791 ,6119,6202,6120 ,0,0,0}, + {12796,12708,12794 ,6120,6116,6139 ,0,0,0}, {12711,12794,12708 ,6122,6139,6116 ,0,0,0}, + {12708,12795,12707 ,6116,6201,6117 ,0,0,0}, {12740,14749,14574 ,6122,6202,6120 ,0,0,0}, + {12707,12795,14573 ,6117,6201,6118 ,0,0,0}, {14749,12739,14573 ,6202,6116,6118 ,0,0,0}, + {14754,12746,12745 ,6120,6117,6171 ,0,0,0}, {14755,12958,14754 ,6197,6197,6120 ,0,0,0}, + {12957,14754,12958 ,6201,6120,6197 ,0,0,0}, {12965,14773,12968 ,6228,6145,6142 ,0,0,0}, + {12964,12959,14756 ,6143,6207,6201 ,0,0,0}, {12959,12958,14755 ,6207,6197,6197 ,0,0,0}, + {14725,12962,14583 ,6192,6142,6139 ,0,0,0}, {14583,12964,14756 ,6139,6143,6201 ,0,0,0}, + {12965,14725,14773 ,6228,6192,6145 ,0,0,0}, {14753,13230,12968 ,6154,6285,6142 ,0,0,0}, + {14753,12968,14773 ,6154,6142,6145 ,0,0,0}, {14628,13232,13230 ,6120,6154,6285 ,0,0,0}, + {13234,14629,14774 ,6144,6127,6187 ,0,0,0}, {14629,13234,13232 ,6127,6144,6154 ,0,0,0}, + {14774,14584,13234 ,6187,6145,6144 ,0,0,0}, {13235,14775,14626 ,6146,6145,6150 ,0,0,0}, + {14584,14775,13235 ,6145,6145,6146 ,0,0,0}, {13235,14626,13237 ,6146,6150,6144 ,0,0,0}, + {13240,13237,14776 ,6150,6144,6146 ,0,0,0}, {14625,14776,13237 ,6145,6146,6144 ,0,0,0}, + {13240,14777,14726 ,6150,6144,6150 ,0,0,0}, {13240,14776,14777 ,6150,6146,6144 ,0,0,0}, + {14778,13242,14779 ,6150,6144,6150 ,0,0,0}, {13242,14726,14779 ,6144,6150,6150 ,0,0,0}, + {12820,13242,14778 ,6150,6144,6150 ,0,0,0}, {14780,14781,14782 ,6131,6203,6207 ,0,0,0}, + {14737,14771,13075 ,6138,6144,6159 ,0,0,0}, {14705,13102,14696 ,6201,6156,6197 ,0,0,0}, + {14705,13105,13103 ,6201,6151,6155 ,0,0,0}, {14771,13039,13075 ,6144,6196,6159 ,0,0,0}, + {13060,14768,13058 ,6173,6162,6174 ,0,0,0}, {13087,14767,13090 ,6177,6295,6118 ,0,0,0}, + {13096,13093,14697 ,6158,6165,6191 ,0,0,0}, {14767,14698,13090 ,6295,6269,6118 ,0,0,0}, + {14768,13060,14703 ,6162,6173,6272 ,0,0,0}, {13062,13068,13032 ,6181,6182,6243 ,0,0,0}, + {13071,13072,13037 ,6127,6158,6297 ,0,0,0}, {13064,13030,13068 ,6118,6155,6182 ,0,0,0}, + {13032,13068,13030 ,6243,6182,6155 ,0,0,0}, {13064,13066,13033 ,6118,6174,6270 ,0,0,0}, + {13033,13030,13064 ,6270,6155,6118 ,0,0,0}, {13036,13071,13037 ,6270,6127,6297 ,0,0,0}, + {13039,13037,13072 ,6196,6297,6158 ,0,0,0}, {14737,13075,13076 ,6138,6159,6137 ,0,0,0}, + {14665,13076,13078 ,6136,6137,6156 ,0,0,0}, {14783,14784,14785 ,6205,6132,6116 ,0,0,0}, + {14784,14741,14786 ,6132,6133,6132 ,0,0,0}, {12732,14655,14660 ,6137,6131,6208 ,0,0,0}, + {14666,13083,12738 ,6133,6135,6134 ,0,0,0}, {12737,14743,14656 ,6138,6196,6132 ,0,0,0}, + {12737,12738,13082 ,6138,6134,6134 ,0,0,0}, {14656,12735,12737 ,6132,6122,6138 ,0,0,0}, + {14660,14655,14787 ,6208,6131,6157 ,0,0,0}, {14787,14730,14660 ,6157,6143,6208 ,0,0,0}, + {14786,12950,14788 ,6132,6172,6118 ,0,0,0}, {14789,14790,14660 ,6204,6201,6208 ,0,0,0}, + {14660,14791,14792 ,6208,6172,6214 ,0,0,0}, {14660,14790,14742 ,6208,6201,6207 ,0,0,0}, + {14791,14660,12953 ,6172,6208,6127 ,0,0,0}, {12952,14742,12950 ,6242,6207,6172 ,0,0,0}, + {14788,12950,14742 ,6118,6172,6207 ,0,0,0}, {14786,14741,12947 ,6132,6133,6203 ,0,0,0}, + {12947,12950,14786 ,6203,6172,6132 ,0,0,0}, {14784,14783,14741 ,6132,6205,6133 ,0,0,0}, + {14734,14785,14793 ,6209,6116,6121 ,0,0,0}, {14785,14734,14783 ,6116,6209,6205 ,0,0,0}, + {14793,14735,14734 ,6121,6207,6209 ,0,0,0}, {14736,14794,14667 ,6166,6209,6207 ,0,0,0}, + {14735,14794,14736 ,6207,6209,6166 ,0,0,0}, {14736,14667,14669 ,6166,6207,6208 ,0,0,0}, + {14782,14669,14795 ,6207,6208,6196 ,0,0,0}, {14668,14795,14669 ,6133,6196,6208 ,0,0,0}, + {14782,14796,14780 ,6207,6134,6131 ,0,0,0}, {14782,14795,14796 ,6207,6196,6134 ,0,0,0}, + {14797,14781,14798 ,6204,6203,6205 ,0,0,0}, {14781,14780,14798 ,6203,6131,6205 ,0,0,0}, + {13107,14781,14797 ,6134,6203,6204 ,0,0,0}, {14577,12888,12887 ,6123,6152,6167 ,0,0,0}, + {14577,14721,14643 ,6123,6275,6213 ,0,0,0}, {12980,12752,12751 ,6140,6117,6208 ,0,0,0}, + {14660,14731,14789 ,6208,6133,6204 ,0,0,0}, {14660,14792,14707 ,6208,6214,6133 ,0,0,0}, + {14799,13483,13482 ,6298,6299,6299 ,0,0,0}, {13488,14800,13489 ,6298,6298,6300 ,0,0,0}, + {14801,14802,13180 ,6301,6302,6302 ,0,0,0}, {13482,13479,14803 ,6299,6300,6303 ,0,0,0}, + {13177,14804,14805 ,6304,6304,6305 ,0,0,0}, {13473,14806,13476 ,6301,6299,6306 ,0,0,0}, + {13175,14807,14808 ,6305,6307,6308 ,0,0,0}, {14809,13470,13467 ,6298,6298,6309 ,0,0,0}, + {14810,13163,14811 ,6310,6311,6312 ,0,0,0}, {14812,14813,13169 ,6308,6313,6314 ,0,0,0}, + {13159,13583,14814 ,6315,6316,6317 ,0,0,0}, {14814,14815,13166 ,6317,6318,6319 ,0,0,0}, + {13154,13578,13580 ,6320,6321,6322 ,0,0,0}, {13538,13121,13536 ,6299,6303,6323 ,0,0,0}, + {13542,13544,13124 ,6324,6298,6306 ,0,0,0}, {13144,13568,13569 ,6325,6326,6327 ,0,0,0}, + {13545,13548,13132 ,6298,6328,6324 ,0,0,0}, {13560,13562,13141 ,6301,6329,6330 ,0,0,0}, + {13560,13215,13557 ,6301,6324,6331 ,0,0,0}, {13134,13554,13556 ,6332,6328,6333 ,0,0,0}, + {13554,13137,13551 ,6328,6334,6335 ,0,0,0}, {13563,13214,13562 ,6336,6298,6329 ,0,0,0}, + {13557,13142,13556 ,6331,6337,6333 ,0,0,0}, {13143,13566,13568 ,6338,6339,6326 ,0,0,0}, + {13563,13566,13146 ,6336,6339,6324 ,0,0,0}, {13548,13550,13128 ,6328,6328,6299 ,0,0,0}, + {13550,13551,13129 ,6328,6335,6340 ,0,0,0}, {13150,13572,13574 ,6341,6342,6343 ,0,0,0}, + {13152,13569,13572 ,6344,6327,6342 ,0,0,0}, {13574,13575,13148 ,6343,6345,6346 ,0,0,0}, + {13544,13545,13131 ,6298,6298,6347 ,0,0,0}, {13539,13542,13127 ,6348,6324,6316 ,0,0,0}, + {13156,13575,13578 ,6349,6345,6321 ,0,0,0}, {13155,13580,13581 ,6350,6322,6351 ,0,0,0}, + {13126,13539,13127 ,6324,6348,6316 ,0,0,0}, {13112,13533,13113 ,6300,6352,6353 ,0,0,0}, + {13161,13581,13583 ,6354,6351,6316 ,0,0,0}, {13109,13527,13110 ,6355,6299,6298 ,0,0,0}, + {13532,13118,13530 ,6299,6356,6357 ,0,0,0}, {14812,13171,14810 ,6308,6358,6310 ,0,0,0}, + {14815,14811,13162 ,6318,6312,6359 ,0,0,0}, {13465,13464,14816 ,6316,6306,6360 ,0,0,0}, + {14816,13464,13115 ,6360,6306,6299 ,0,0,0}, {14816,14817,13465 ,6360,6298,6316 ,0,0,0}, + {14813,14807,13167 ,6313,6307,6304 ,0,0,0}, {13174,14808,14818 ,6336,6308,6311 ,0,0,0}, + {13121,13538,13126 ,6303,6299,6324 ,0,0,0}, {14818,14804,13179 ,6311,6304,6314 ,0,0,0}, + {13473,13471,14819 ,6301,6300,6340 ,0,0,0}, {14820,13471,13470 ,6301,6300,6298 ,0,0,0}, + {14821,14801,13184 ,6301,6301,6333 ,0,0,0}, {13178,14805,14821 ,6361,6305,6301 ,0,0,0}, + {14822,13479,13477 ,6300,6300,6357 ,0,0,0}, {13476,14823,13477 ,6306,6355,6357 ,0,0,0}, + {14824,14825,13185 ,6353,6311,6301 ,0,0,0}, {13181,14802,14824 ,6362,6302,6353 ,0,0,0}, + {13485,13483,14826 ,6300,6299,6300 ,0,0,0}, {13186,14825,14827 ,6300,6311,6363 ,0,0,0}, + {13190,14827,14828 ,6301,6363,6353 ,0,0,0}, {13191,14828,14829 ,6300,6353,6328 ,0,0,0}, + {13485,14830,13488 ,6300,6300,6298 ,0,0,0}, {14831,13193,14829 ,6303,6352,6328 ,0,0,0}, + {14831,14832,13195 ,6303,6352,6340 ,0,0,0}, {14833,13491,13489 ,6299,6316,6300 ,0,0,0}, + {14834,13198,14832 ,6300,6340,6352 ,0,0,0}, {14835,13494,13491 ,6298,6364,6316 ,0,0,0}, + {13199,14834,14836 ,6316,6300,6306 ,0,0,0}, {14837,13495,13494 ,6364,6298,6364 ,0,0,0}, + {14836,14838,13201 ,6306,6340,6340 ,0,0,0}, {14839,13497,13495 ,6300,6300,6298 ,0,0,0}, + {14840,13204,14838 ,6323,6340,6340 ,0,0,0}, {14841,13500,13497 ,6298,6300,6300 ,0,0,0}, + {13206,14840,14842 ,6300,6323,6340 ,0,0,0}, {14843,13501,13500 ,6364,6300,6300 ,0,0,0}, + {14842,14844,13205 ,6340,6303,6303 ,0,0,0}, {14845,13503,13501 ,6300,6365,6300 ,0,0,0}, + {14846,13207,14844 ,6300,6300,6303 ,0,0,0}, {14847,13506,13503 ,6366,6300,6365 ,0,0,0}, + {13210,14846,14848 ,6300,6300,6316 ,0,0,0}, {14849,13507,13506 ,6367,6367,6300 ,0,0,0}, + {14848,14850,13211 ,6316,6300,6300 ,0,0,0}, {14851,13509,13507 ,6300,6300,6367 ,0,0,0}, + {14852,13211,14853 ,6301,6300,6300 ,0,0,0}, {14854,13512,13509 ,6368,6300,6300 ,0,0,0}, + {14855,14852,14856 ,6300,6301,6300 ,0,0,0}, {14857,13513,13512 ,6369,6367,6300 ,0,0,0}, + {14858,14855,14859 ,6316,6300,6300 ,0,0,0}, {13513,14860,13515 ,6367,6367,6300 ,0,0,0}, + {13518,13515,14861 ,6364,6300,6370 ,0,0,0}, {14862,13521,13519 ,6300,6316,6300 ,0,0,0}, + {14863,14858,14864 ,6300,6316,6316 ,0,0,0}, {14865,14866,14867 ,6300,6371,6300 ,0,0,0}, + {14868,14869,14870 ,6306,6300,6303 ,0,0,0}, {14871,14872,14873 ,6369,6300,6367 ,0,0,0}, + {14874,14875,14876 ,6301,6301,6300 ,0,0,0}, {14877,14878,14879 ,6300,6369,6367 ,0,0,0}, + {14880,14881,14882 ,6316,6316,6300 ,0,0,0}, {14883,14884,14885 ,6364,6300,6300 ,0,0,0}, + {14886,14877,14887 ,6364,6300,6316 ,0,0,0}, {14888,14889,14890 ,6300,6364,6316 ,0,0,0}, + {14885,14891,14890 ,6300,6316,6316 ,0,0,0}, {14892,14893,14894 ,6364,6372,6364 ,0,0,0}, + {14893,14886,14895 ,6372,6364,6300 ,0,0,0}, {14880,14889,14896 ,6316,6364,6367 ,0,0,0}, + {14897,14883,14892 ,6370,6364,6364 ,0,0,0}, {14873,14898,14899 ,6367,6367,6316 ,0,0,0}, + {14900,14878,14899 ,6316,6369,6316 ,0,0,0}, {14901,14874,14902 ,6306,6301,6303 ,0,0,0}, + {14902,14882,14903 ,6303,6300,6340 ,0,0,0}, {14904,14905,14867 ,6371,6300,6300 ,0,0,0}, + {14906,14871,14905 ,6300,6369,6300 ,0,0,0}, {14907,14868,14908 ,6300,6306,6300 ,0,0,0}, + {14907,14908,14876 ,6300,6300,6300 ,0,0,0}, {14909,14910,13521 ,6300,6300,6316 ,0,0,0}, + {14865,14910,14911 ,6300,6300,6316 ,0,0,0}, {14863,14912,14913 ,6300,6303,6301 ,0,0,0}, + {14869,14913,14914 ,6300,6301,6301 ,0,0,0}, {13519,13518,14915 ,6300,6364,6369 ,0,0,0}, + {13464,13463,13115 ,6306,6298,6299 ,0,0,0}, {13115,13463,13526 ,6299,6298,6340 ,0,0,0}, + {14817,14809,13467 ,6298,6298,6309 ,0,0,0}, {14817,13467,13465 ,6298,6309,6316 ,0,0,0}, + {14809,14820,13470 ,6298,6301,6298 ,0,0,0}, {14820,14819,13471 ,6301,6340,6300 ,0,0,0}, + {14819,14806,13473 ,6340,6299,6301 ,0,0,0}, {14806,14823,13476 ,6299,6355,6306 ,0,0,0}, + {14823,14822,13477 ,6355,6300,6357 ,0,0,0}, {14822,14803,13479 ,6300,6303,6300 ,0,0,0}, + {14803,14799,13482 ,6303,6298,6299 ,0,0,0}, {14799,14826,13483 ,6298,6300,6299 ,0,0,0}, + {14826,14830,13485 ,6300,6300,6300 ,0,0,0}, {14830,14800,13488 ,6300,6298,6298 ,0,0,0}, + {14800,14833,13489 ,6298,6299,6300 ,0,0,0}, {14833,14835,13491 ,6299,6298,6316 ,0,0,0}, + {14835,14837,13494 ,6298,6364,6364 ,0,0,0}, {14837,14839,13495 ,6364,6300,6298 ,0,0,0}, + {14839,14841,13497 ,6300,6298,6300 ,0,0,0}, {14841,14843,13500 ,6298,6364,6300 ,0,0,0}, + {14843,14845,13501 ,6364,6300,6300 ,0,0,0}, {14845,14847,13503 ,6300,6366,6365 ,0,0,0}, + {14847,14849,13506 ,6366,6367,6300 ,0,0,0}, {14849,14851,13507 ,6367,6300,6367 ,0,0,0}, + {14851,14854,13509 ,6300,6368,6300 ,0,0,0}, {14854,14857,13512 ,6368,6369,6300 ,0,0,0}, + {14857,14860,13513 ,6369,6367,6367 ,0,0,0}, {14860,14861,13515 ,6367,6370,6300 ,0,0,0}, + {14861,14915,13518 ,6370,6369,6364 ,0,0,0}, {14915,14862,13519 ,6369,6300,6300 ,0,0,0}, + {14862,14909,13521 ,6300,6300,6316 ,0,0,0}, {14909,14911,14910 ,6300,6316,6300 ,0,0,0}, + {14911,14866,14865 ,6316,6371,6300 ,0,0,0}, {14866,14904,14867 ,6371,6371,6300 ,0,0,0}, + {14904,14906,14905 ,6371,6300,6300 ,0,0,0}, {14906,14872,14871 ,6300,6300,6369 ,0,0,0}, + {14872,14898,14873 ,6300,6367,6367 ,0,0,0}, {14898,14900,14899 ,6367,6316,6316 ,0,0,0}, + {14900,14879,14878 ,6316,6367,6369 ,0,0,0}, {14879,14887,14877 ,6367,6316,6300 ,0,0,0}, + {14887,14895,14886 ,6316,6300,6364 ,0,0,0}, {14895,14894,14893 ,6300,6364,6372 ,0,0,0}, + {14894,14897,14892 ,6364,6370,6364 ,0,0,0}, {14897,14884,14883 ,6370,6300,6364 ,0,0,0}, + {14884,14891,14885 ,6300,6316,6300 ,0,0,0}, {14891,14888,14890 ,6316,6300,6316 ,0,0,0}, + {14888,14896,14889 ,6300,6367,6364 ,0,0,0}, {14896,14881,14880 ,6367,6316,6316 ,0,0,0}, + {14881,14903,14882 ,6316,6340,6300 ,0,0,0}, {14903,14901,14902 ,6340,6306,6303 ,0,0,0}, + {14901,14875,14874 ,6306,6301,6301 ,0,0,0}, {14875,14907,14876 ,6301,6300,6300 ,0,0,0}, + {14868,14870,14908 ,6306,6303,6300 ,0,0,0}, {14869,14914,14870 ,6300,6301,6303 ,0,0,0}, + {14913,14912,14914 ,6301,6303,6301 ,0,0,0}, {14863,14864,14912 ,6300,6316,6303 ,0,0,0}, + {14858,14859,14864 ,6316,6300,6316 ,0,0,0}, {14855,14856,14859 ,6300,6300,6300 ,0,0,0}, + {14852,14853,14856 ,6301,6300,6300 ,0,0,0}, {13211,14850,14853 ,6300,6300,6300 ,0,0,0}, + {13211,13210,14848 ,6300,6300,6316 ,0,0,0}, {13210,13207,14846 ,6300,6300,6300 ,0,0,0}, + {13207,13205,14844 ,6300,6303,6303 ,0,0,0}, {13205,13206,14842 ,6303,6300,6340 ,0,0,0}, + {13206,13204,14840 ,6300,6340,6323 ,0,0,0}, {13204,13201,14838 ,6340,6340,6340 ,0,0,0}, + {13201,13199,14836 ,6340,6316,6306 ,0,0,0}, {13199,13198,14834 ,6316,6340,6300 ,0,0,0}, + {13198,13195,14832 ,6340,6340,6352 ,0,0,0}, {13195,13193,14831 ,6340,6352,6303 ,0,0,0}, + {13193,13191,14829 ,6352,6300,6328 ,0,0,0}, {13191,13190,14828 ,6300,6301,6353 ,0,0,0}, + {13190,13186,14827 ,6301,6300,6363 ,0,0,0}, {13186,13185,14825 ,6300,6301,6311 ,0,0,0}, + {13185,13181,14824 ,6301,6362,6353 ,0,0,0}, {13181,13180,14802 ,6362,6302,6302 ,0,0,0}, + {13180,13184,14801 ,6302,6333,6301 ,0,0,0}, {13184,13178,14821 ,6333,6361,6301 ,0,0,0}, + {13178,13177,14805 ,6361,6304,6305 ,0,0,0}, {13177,13179,14804 ,6304,6314,6304 ,0,0,0}, + {13179,13174,14818 ,6314,6336,6311 ,0,0,0}, {13174,13175,14808 ,6336,6305,6308 ,0,0,0}, + {13175,13167,14807 ,6305,6304,6307 ,0,0,0}, {13167,13169,14813 ,6304,6314,6313 ,0,0,0}, + {13169,13171,14812 ,6314,6358,6308 ,0,0,0}, {13171,13163,14810 ,6358,6311,6310 ,0,0,0}, + {13163,13162,14811 ,6311,6359,6312 ,0,0,0}, {13162,13166,14815 ,6359,6319,6318 ,0,0,0}, + {13166,13159,14814 ,6319,6315,6317 ,0,0,0}, {13159,13161,13583 ,6315,6354,6316 ,0,0,0}, + {13161,13155,13581 ,6354,6350,6351 ,0,0,0}, {13155,13154,13580 ,6350,6320,6322 ,0,0,0}, + {13154,13156,13578 ,6320,6349,6321 ,0,0,0}, {13156,13148,13575 ,6349,6346,6345 ,0,0,0}, + {13148,13150,13574 ,6346,6341,6343 ,0,0,0}, {13150,13152,13572 ,6341,6344,6342 ,0,0,0}, + {13152,13144,13569 ,6344,6325,6327 ,0,0,0}, {13144,13143,13568 ,6325,6338,6326 ,0,0,0}, + {13143,13146,13566 ,6338,6324,6339 ,0,0,0}, {13146,13214,13563 ,6324,6298,6336 ,0,0,0}, + {13214,13141,13562 ,6298,6330,6329 ,0,0,0}, {13141,13215,13560 ,6330,6324,6301 ,0,0,0}, + {13215,13142,13557 ,6324,6337,6331 ,0,0,0}, {13142,13134,13556 ,6337,6332,6333 ,0,0,0}, + {13134,13137,13554 ,6332,6334,6328 ,0,0,0}, {13137,13129,13551 ,6334,6340,6335 ,0,0,0}, + {13129,13128,13550 ,6340,6299,6328 ,0,0,0}, {13128,13132,13548 ,6299,6324,6328 ,0,0,0}, + {13132,13131,13545 ,6324,6347,6298 ,0,0,0}, {13131,13124,13544 ,6347,6306,6298 ,0,0,0}, + {13124,13127,13542 ,6306,6316,6324 ,0,0,0}, {13126,13538,13539 ,6324,6299,6348 ,0,0,0}, + {13113,13536,13121 ,6353,6323,6303 ,0,0,0}, {13112,13532,13533 ,6300,6299,6352 ,0,0,0}, + {13113,13533,13536 ,6353,6352,6323 ,0,0,0}, {13118,13110,13530 ,6356,6298,6357 ,0,0,0}, + {13112,13118,13532 ,6300,6356,6299 ,0,0,0}, {13527,13109,13526 ,6299,6355,6340 ,0,0,0}, + {13530,13110,13527 ,6357,6298,6299 ,0,0,0}, {13115,13526,13109 ,6299,6340,6355 ,0,0,0}, + {14910,13523,13521 ,6373,6374,6375 ,0,0,0}, {14916,14917,14905 ,6376,6377,6378 ,0,0,0}, + {14867,14918,14865 ,6379,6380,6381 ,0,0,0}, {14899,14878,14919 ,6382,6383,6384 ,0,0,0}, + {14871,14873,14920 ,6385,6386,6387 ,0,0,0}, {14921,14922,14893 ,6388,6389,6390 ,0,0,0}, + {14923,14924,14877 ,6391,6392,6393 ,0,0,0}, {14885,14890,14925 ,6394,6395,6396 ,0,0,0}, + {14892,14883,14926 ,6397,6398,6399 ,0,0,0}, {14927,14928,14882 ,6400,6401,6402 ,0,0,0}, + {14929,14930,14889 ,6403,6404,6405 ,0,0,0}, {14876,14908,14931 ,6406,6407,6408 ,0,0,0}, + {14902,14874,14932 ,6409,6410,6411 ,0,0,0}, {14933,14934,14912 ,6412,6413,6414 ,0,0,0}, + {14935,14936,14870 ,6415,6416,6417 ,0,0,0}, {14937,14856,14938 ,6418,6419,6420 ,0,0,0}, + {14864,14859,14939 ,6421,6422,6423 ,0,0,0}, {14848,14940,14941 ,6424,6425,6426 ,0,0,0}, + {14850,14942,14853 ,6427,6428,6429 ,0,0,0}, {14943,14944,14842 ,6430,6431,6432 ,0,0,0}, + {14945,14846,14844 ,6433,6434,6435 ,0,0,0}, {14946,14838,14836 ,6436,6437,6438 ,0,0,0}, + {14840,14838,14947 ,6439,6437,6440 ,0,0,0}, {14948,14832,14949 ,6441,6442,6443 ,0,0,0}, + {14834,14948,14950 ,6444,6441,6445 ,0,0,0}, {14829,14828,14951 ,6446,6447,6448 ,0,0,0}, + {14831,14952,14949 ,6449,6450,6443 ,0,0,0}, {14827,14825,14953 ,6451,6452,6453 ,0,0,0}, + {14827,14954,14828 ,6451,6454,6447 ,0,0,0}, {14824,14802,14955 ,6455,6456,6457 ,0,0,0}, + {14824,14956,14825 ,6455,6458,6452 ,0,0,0}, {14957,14802,14801 ,6459,6456,6460 ,0,0,0}, + {14802,14957,14955 ,6456,6459,6457 ,0,0,0}, {14821,14958,14801 ,6461,6462,6460 ,0,0,0}, + {14957,14801,14958 ,6459,6460,6462 ,0,0,0}, {14821,14805,14959 ,6461,6463,6464 ,0,0,0}, + {14959,14958,14821 ,6464,6462,6461 ,0,0,0}, {14960,14805,14804 ,6465,6463,6466 ,0,0,0}, + {14805,14960,14959 ,6463,6465,6464 ,0,0,0}, {14818,14961,14804 ,6467,6468,6466 ,0,0,0}, + {14960,14804,14961 ,6465,6466,6468 ,0,0,0}, {14818,14808,14962 ,6467,6469,6470 ,0,0,0}, + {14962,14961,14818 ,6470,6468,6467 ,0,0,0}, {14963,14808,14807 ,6471,6469,6472 ,0,0,0}, + {14808,14963,14962 ,6469,6471,6470 ,0,0,0}, {14813,14964,14807 ,6473,6474,6472 ,0,0,0}, + {14963,14807,14964 ,6471,6472,6474 ,0,0,0}, {14813,14812,14965 ,6473,6475,6476 ,0,0,0}, + {14965,14964,14813 ,6476,6474,6473 ,0,0,0}, {14966,14812,14810 ,6477,6475,6478 ,0,0,0}, + {14812,14966,14965 ,6475,6477,6476 ,0,0,0}, {14811,14967,14810 ,6479,6480,6478 ,0,0,0}, + {14966,14810,14967 ,6477,6478,6480 ,0,0,0}, {14811,14815,14968 ,6479,6481,6482 ,0,0,0}, + {14968,14967,14811 ,6482,6480,6479 ,0,0,0}, {14969,14815,14814 ,6483,6481,6484 ,0,0,0}, + {14815,14969,14968 ,6481,6483,6482 ,0,0,0}, {13583,14970,14814 ,6485,6486,6484 ,0,0,0}, + {14969,14814,14970 ,6483,6484,6486 ,0,0,0}, {13582,14970,13583 ,6487,6486,6485 ,0,0,0}, + {14956,14953,14825 ,6458,6453,6452 ,0,0,0}, {14824,14955,14956 ,6455,6457,6458 ,0,0,0}, + {14954,14951,14828 ,6454,6448,6447 ,0,0,0}, {14827,14953,14954 ,6451,6453,6454 ,0,0,0}, + {14831,14829,14952 ,6449,6446,6450 ,0,0,0}, {14829,14951,14952 ,6446,6448,6450 ,0,0,0}, + {14832,14948,14834 ,6442,6441,6444 ,0,0,0}, {14832,14831,14949 ,6442,6449,6443 ,0,0,0}, + {14946,14836,14950 ,6436,6438,6445 ,0,0,0}, {14836,14834,14950 ,6438,6444,6445 ,0,0,0}, + {14840,14947,14943 ,6439,6440,6430 ,0,0,0}, {14947,14838,14946 ,6440,6437,6436 ,0,0,0}, + {14944,14844,14842 ,6431,6435,6432 ,0,0,0}, {14943,14842,14840 ,6430,6432,6439 ,0,0,0}, + {14945,14940,14846 ,6433,6425,6434 ,0,0,0}, {14944,14945,14844 ,6431,6433,6435 ,0,0,0}, + {14848,14941,14850 ,6424,6426,6427 ,0,0,0}, {14846,14940,14848 ,6434,6425,6424 ,0,0,0}, + {14853,14942,14938 ,6429,6428,6420 ,0,0,0}, {14850,14941,14942 ,6427,6426,6428 ,0,0,0}, + {14859,14856,14937 ,6422,6419,6418 ,0,0,0}, {14856,14853,14938 ,6419,6429,6420 ,0,0,0}, + {14933,14864,14939 ,6412,6421,6423 ,0,0,0}, {14939,14859,14937 ,6423,6422,6418 ,0,0,0}, + {14934,14914,14912 ,6413,6488,6414 ,0,0,0}, {14933,14912,14864 ,6412,6414,6421 ,0,0,0}, + {14870,14914,14935 ,6417,6488,6415 ,0,0,0}, {14934,14935,14914 ,6413,6415,6488 ,0,0,0}, + {14908,14936,14931 ,6407,6416,6408 ,0,0,0}, {14870,14936,14908 ,6417,6416,6407 ,0,0,0}, + {14874,14876,14971 ,6410,6406,6489 ,0,0,0}, {14876,14931,14971 ,6406,6408,6489 ,0,0,0}, + {14927,14902,14932 ,6400,6409,6411 ,0,0,0}, {14932,14874,14971 ,6411,6410,6489 ,0,0,0}, + {14928,14880,14882 ,6401,6490,6402 ,0,0,0}, {14927,14882,14902 ,6400,6402,6409 ,0,0,0}, + {14889,14880,14929 ,6405,6490,6403 ,0,0,0}, {14928,14929,14880 ,6401,6403,6490 ,0,0,0}, + {14890,14930,14925 ,6395,6404,6396 ,0,0,0}, {14889,14930,14890 ,6405,6404,6395 ,0,0,0}, + {14883,14885,14972 ,6398,6394,6491 ,0,0,0}, {14885,14925,14972 ,6394,6396,6491 ,0,0,0}, + {14921,14892,14926 ,6388,6397,6399 ,0,0,0}, {14926,14883,14972 ,6399,6398,6491 ,0,0,0}, + {14922,14886,14893 ,6389,6492,6390 ,0,0,0}, {14921,14893,14892 ,6388,6390,6397 ,0,0,0}, + {14877,14886,14923 ,6393,6492,6391 ,0,0,0}, {14922,14923,14886 ,6389,6391,6492 ,0,0,0}, + {14878,14924,14919 ,6383,6392,6384 ,0,0,0}, {14877,14924,14878 ,6393,6392,6383 ,0,0,0}, + {14873,14899,14973 ,6386,6382,6493 ,0,0,0}, {14899,14919,14973 ,6382,6384,6493 ,0,0,0}, + {14916,14871,14920 ,6376,6385,6387 ,0,0,0}, {14920,14873,14973 ,6387,6386,6493 ,0,0,0}, + {14917,14867,14905 ,6377,6379,6378 ,0,0,0}, {14916,14905,14871 ,6376,6378,6385 ,0,0,0}, + {14918,14974,14865 ,6380,6494,6381 ,0,0,0}, {14917,14918,14867 ,6377,6380,6379 ,0,0,0}, + {13523,14910,14974 ,6374,6373,6494 ,0,0,0}, {14865,14974,14910 ,6381,6494,6373 ,0,0,0}, + {13534,13420,13535 ,6495,6495,6496 ,0,0,0}, {13541,13540,13426 ,6497,6496,6496 ,0,0,0}, + {14929,14928,14975 ,6498,6499,6500 ,0,0,0}, {13417,13534,13531 ,6501,6495,6501 ,0,0,0}, + {14926,14972,14976 ,6502,6503,6503 ,0,0,0}, {13528,13411,13414 ,6496,6504,6501 ,0,0,0}, + {14977,14919,14924 ,6498,6505,6506 ,0,0,0}, {13353,13462,13466 ,6507,6495,6495 ,0,0,0}, + {13363,13361,13475 ,6508,6509,6504 ,0,0,0}, {14978,14917,14916 ,6510,6511,6512 ,0,0,0}, + {13522,13405,13403 ,6513,6500,6514 ,0,0,0}, {13523,13405,13522 ,6515,6500,6513 ,0,0,0}, + {13517,13520,13404 ,6516,6517,6518 ,0,0,0}, {13484,13486,13369 ,6519,6520,6497 ,0,0,0}, + {13490,13492,13375 ,6521,6522,6523 ,0,0,0}, {13514,13397,13396 ,6524,6525,6526 ,0,0,0}, + {13493,13379,13378 ,6527,6500,6498 ,0,0,0}, {13510,13391,13508 ,6528,6522,6529 ,0,0,0}, + {13508,13390,13505 ,6529,6530,6531 ,0,0,0}, {13385,13502,13387 ,6532,6533,6502 ,0,0,0}, + {13499,13385,13384 ,6534,6532,6495 ,0,0,0}, {13511,13393,13510 ,6535,6502,6528 ,0,0,0}, + {13504,13505,13387 ,6533,6531,6502 ,0,0,0}, {13514,13396,13511 ,6524,6526,6535 ,0,0,0}, + {13393,13511,13396 ,6502,6535,6526 ,0,0,0}, {13496,13381,13379 ,6503,6514,6500 ,0,0,0}, + {13384,13381,13498 ,6495,6514,6530 ,0,0,0}, {13402,13397,13516 ,6536,6525,6537 ,0,0,0}, + {13397,13514,13516 ,6525,6524,6537 ,0,0,0}, {13402,13516,13517 ,6536,6537,6516 ,0,0,0}, + {13493,13378,13492 ,6527,6498,6522 ,0,0,0}, {13490,13373,13487 ,6521,6501,6509 ,0,0,0}, + {13517,13404,13402 ,6516,6518,6536 ,0,0,0}, {13404,13520,13403 ,6518,6517,6514 ,0,0,0}, + {13487,13372,13486 ,6509,6500,6520 ,0,0,0}, {13367,13481,13369 ,6508,6509,6497 ,0,0,0}, + {13522,13403,13520 ,6513,6514,6517 ,0,0,0}, {13363,13478,13366 ,6508,6508,6495 ,0,0,0}, + {13366,13480,13367 ,6495,6530,6508 ,0,0,0}, {14979,14918,14980 ,6538,6539,6540 ,0,0,0}, + {14974,13405,13523 ,6541,6500,6515 ,0,0,0}, {13474,13360,13472 ,6495,6496,6542 ,0,0,0}, + {13361,13360,13474 ,6509,6496,6495 ,0,0,0}, {13468,13469,13355 ,6542,6504,6507 ,0,0,0}, + {14973,14919,14981 ,6543,6505,6500 ,0,0,0}, {14982,14923,14983 ,6503,6533,6500 ,0,0,0}, + {13466,13468,13354 ,6495,6542,6495 ,0,0,0}, {14984,14983,14921 ,6508,6500,6538 ,0,0,0}, + {13411,13525,13410 ,6504,6542,6501 ,0,0,0}, {13353,13410,13524 ,6507,6501,6495 ,0,0,0}, + {14930,14985,14986 ,6527,6530,6498 ,0,0,0}, {14972,14925,14987 ,6503,6527,6499 ,0,0,0}, + {13417,13531,13416 ,6501,6501,6544 ,0,0,0}, {13529,13414,13416 ,6504,6501,6544 ,0,0,0}, + {14932,14988,14989 ,6508,6530,6544 ,0,0,0}, {14990,14927,14989 ,6498,6500,6544 ,0,0,0}, + {13422,13537,13535 ,6495,6495,6496 ,0,0,0}, {14971,14931,14988 ,6523,6504,6530 ,0,0,0}, + {14936,14991,14931 ,6500,6504,6504 ,0,0,0}, {14936,14935,14992 ,6500,6522,6500 ,0,0,0}, + {13540,13537,13423 ,6496,6495,6496 ,0,0,0}, {14993,14935,14934 ,6515,6522,6504 ,0,0,0}, + {14933,14994,14934 ,6508,6500,6504 ,0,0,0}, {13543,13426,13428 ,6495,6496,6508 ,0,0,0}, + {14994,14933,14995 ,6500,6508,6498 ,0,0,0}, {13546,13428,13429 ,6504,6508,6507 ,0,0,0}, + {14996,14995,14939 ,6515,6498,6545 ,0,0,0}, {13547,13429,13432 ,6507,6507,6495 ,0,0,0}, + {14997,14996,14937 ,6498,6515,6504 ,0,0,0}, {13549,13432,13434 ,6504,6495,6495 ,0,0,0}, + {14998,14997,14938 ,6504,6498,6504 ,0,0,0}, {13434,13435,13552 ,6495,6504,6504 ,0,0,0}, + {14999,14998,14942 ,6504,6504,6498 ,0,0,0}, {13553,13552,13435 ,6504,6504,6504 ,0,0,0}, + {14999,14941,14940 ,6504,6504,6504 ,0,0,0}, {13555,13553,13438 ,6546,6504,6504 ,0,0,0}, + {15000,14940,14945 ,6508,6504,6504 ,0,0,0}, {13558,13555,13440 ,6507,6546,6504 ,0,0,0}, + {15001,14945,14944 ,6508,6504,6508 ,0,0,0}, {13559,13558,13441 ,6547,6507,6548 ,0,0,0}, + {15002,14944,14943 ,6498,6508,6498 ,0,0,0}, {13561,13559,13444 ,6546,6547,6548 ,0,0,0}, + {15003,14943,14947 ,6504,6498,6498 ,0,0,0}, {13446,13564,13444 ,6549,6547,6548 ,0,0,0}, + {14947,15004,15003 ,6498,6504,6504 ,0,0,0}, {13565,13446,13447 ,6549,6549,6550 ,0,0,0}, + {15004,14946,15005 ,6504,6504,6498 ,0,0,0}, {13447,13450,13567 ,6550,6549,6504 ,0,0,0}, + {13570,13450,13452 ,6549,6549,6545 ,0,0,0}, {13573,13571,13454 ,6549,6504,6504 ,0,0,0}, + {15005,14950,15006 ,6498,6504,6504 ,0,0,0}, {13579,13577,13459 ,6551,6504,6515 ,0,0,0}, + {14951,15007,14952 ,6504,6508,6515 ,0,0,0}, {15008,14969,15009 ,6504,6545,6515 ,0,0,0}, + {15010,14953,14956 ,6508,6552,6504 ,0,0,0}, {14966,15011,15012 ,6553,6504,6554 ,0,0,0}, + {15013,15014,14957 ,6555,6504,6515 ,0,0,0}, {14961,14962,15015 ,6504,6504,6504 ,0,0,0}, + {14966,15012,14965 ,6553,6554,6504 ,0,0,0}, {14959,15016,15017 ,6504,6504,6515 ,0,0,0}, + {15015,15016,14960 ,6504,6504,6515 ,0,0,0}, {14964,15018,14963 ,6548,6504,6504 ,0,0,0}, + {14964,14965,15019 ,6548,6504,6549 ,0,0,0}, {15013,14958,15017 ,6555,6504,6515 ,0,0,0}, + {15020,14962,14963 ,6504,6504,6504 ,0,0,0}, {15021,14968,15008 ,6504,6548,6504 ,0,0,0}, + {15011,14967,15021 ,6504,6548,6504 ,0,0,0}, {14955,15022,14956 ,6504,6544,6504 ,0,0,0}, + {14955,15014,15022 ,6504,6504,6544 ,0,0,0}, {13582,13579,13461 ,6515,6551,6554 ,0,0,0}, + {13461,15009,14970 ,6554,6515,6545 ,0,0,0}, {14954,15023,14951 ,6515,6504,6504 ,0,0,0}, + {15024,14954,14953 ,6508,6515,6552 ,0,0,0}, {13576,13573,13453 ,6504,6549,6549 ,0,0,0}, + {13456,13577,13576 ,6545,6504,6504 ,0,0,0}, {14948,15025,15006 ,6508,6498,6504 ,0,0,0}, + {15007,15025,14949 ,6508,6498,6498 ,0,0,0}, {13571,13452,13454 ,6504,6545,6504 ,0,0,0}, + {13469,13472,13357 ,6504,6542,6504 ,0,0,0}, {15026,14920,15027 ,6556,6557,6558 ,0,0,0}, + {14975,14928,14990 ,6500,6499,6498 ,0,0,0}, {13391,13510,13393 ,6522,6528,6502 ,0,0,0}, + {13390,13508,13391 ,6530,6529,6522 ,0,0,0}, {13387,13505,13390 ,6502,6531,6530 ,0,0,0}, + {13387,13502,13504 ,6502,6533,6533 ,0,0,0}, {13385,13499,13502 ,6532,6534,6533 ,0,0,0}, + {13384,13498,13499 ,6495,6530,6534 ,0,0,0}, {13381,13496,13498 ,6514,6503,6530 ,0,0,0}, + {13379,13493,13496 ,6500,6527,6503 ,0,0,0}, {13375,13492,13378 ,6523,6522,6498 ,0,0,0}, + {13373,13490,13375 ,6501,6521,6523 ,0,0,0}, {13372,13487,13373 ,6500,6509,6501 ,0,0,0}, + {13369,13486,13372 ,6497,6520,6500 ,0,0,0}, {13369,13481,13484 ,6497,6509,6519 ,0,0,0}, + {13367,13480,13481 ,6508,6530,6509 ,0,0,0}, {13366,13478,13480 ,6495,6508,6530 ,0,0,0}, + {13363,13475,13478 ,6508,6504,6508 ,0,0,0}, {13361,13474,13475 ,6509,6495,6504 ,0,0,0}, + {13357,13472,13360 ,6504,6542,6496 ,0,0,0}, {13355,13469,13357 ,6507,6504,6504 ,0,0,0}, + {13354,13468,13355 ,6495,6542,6507 ,0,0,0}, {13353,13466,13354 ,6507,6495,6495 ,0,0,0}, + {13353,13524,13462 ,6507,6495,6495 ,0,0,0}, {13410,13525,13524 ,6501,6542,6495 ,0,0,0}, + {13411,13528,13525 ,6504,6496,6542 ,0,0,0}, {13414,13529,13528 ,6501,6504,6496 ,0,0,0}, + {13416,13531,13529 ,6544,6501,6504 ,0,0,0}, {13420,13534,13417 ,6495,6495,6501 ,0,0,0}, + {13422,13535,13420 ,6495,6496,6495 ,0,0,0}, {13423,13537,13422 ,6496,6495,6495 ,0,0,0}, + {13426,13540,13423 ,6496,6496,6496 ,0,0,0}, {13426,13543,13541 ,6496,6495,6497 ,0,0,0}, + {13428,13546,13543 ,6508,6504,6495 ,0,0,0}, {13429,13547,13546 ,6507,6507,6504 ,0,0,0}, + {13432,13549,13547 ,6495,6504,6507 ,0,0,0}, {13434,13552,13549 ,6495,6504,6504 ,0,0,0}, + {13438,13553,13435 ,6504,6504,6504 ,0,0,0}, {13440,13555,13438 ,6504,6546,6504 ,0,0,0}, + {13441,13558,13440 ,6548,6507,6504 ,0,0,0}, {13444,13559,13441 ,6548,6547,6548 ,0,0,0}, + {13444,13564,13561 ,6548,6547,6546 ,0,0,0}, {13446,13565,13564 ,6549,6549,6547 ,0,0,0}, + {13447,13567,13565 ,6550,6504,6549 ,0,0,0}, {13450,13570,13567 ,6549,6549,6504 ,0,0,0}, + {13452,13571,13570 ,6545,6504,6549 ,0,0,0}, {13453,13573,13454 ,6549,6549,6504 ,0,0,0}, + {13456,13576,13453 ,6545,6504,6549 ,0,0,0}, {13459,13577,13456 ,6515,6504,6545 ,0,0,0}, + {13461,13579,13459 ,6554,6551,6515 ,0,0,0}, {13461,14970,13582 ,6554,6545,6515 ,0,0,0}, + {15009,14969,14970 ,6515,6545,6545 ,0,0,0}, {15008,14968,14969 ,6504,6548,6545 ,0,0,0}, + {15021,14967,14968 ,6504,6548,6548 ,0,0,0}, {15011,14966,14967 ,6504,6553,6548 ,0,0,0}, + {15019,14965,15012 ,6549,6504,6554 ,0,0,0}, {15018,14964,15019 ,6504,6548,6549 ,0,0,0}, + {15020,14963,15018 ,6504,6504,6504 ,0,0,0}, {15015,14962,15020 ,6504,6504,6504 ,0,0,0}, + {15015,14960,14961 ,6504,6515,6504 ,0,0,0}, {15016,14959,14960 ,6504,6504,6515 ,0,0,0}, + {15017,14958,14959 ,6515,6504,6504 ,0,0,0}, {15013,14957,14958 ,6555,6515,6504 ,0,0,0}, + {15014,14955,14957 ,6504,6504,6515 ,0,0,0}, {15010,14956,15022 ,6508,6504,6544 ,0,0,0}, + {15024,14953,15010 ,6508,6552,6508 ,0,0,0}, {15023,14954,15024 ,6504,6515,6508 ,0,0,0}, + {15007,14951,15023 ,6508,6504,6504 ,0,0,0}, {15007,14949,14952 ,6508,6498,6515 ,0,0,0}, + {15025,14948,14949 ,6498,6508,6498 ,0,0,0}, {15006,14950,14948 ,6504,6504,6508 ,0,0,0}, + {15005,14946,14950 ,6498,6504,6504 ,0,0,0}, {15004,14947,14946 ,6504,6498,6504 ,0,0,0}, + {15002,14943,15003 ,6498,6498,6504 ,0,0,0}, {15001,14944,15002 ,6508,6508,6498 ,0,0,0}, + {15000,14945,15001 ,6508,6504,6508 ,0,0,0}, {14999,14940,15000 ,6504,6504,6508 ,0,0,0}, + {14999,14942,14941 ,6504,6498,6504 ,0,0,0}, {14998,14938,14942 ,6504,6504,6498 ,0,0,0}, + {14997,14937,14938 ,6498,6504,6504 ,0,0,0}, {14996,14939,14937 ,6515,6545,6504 ,0,0,0}, + {14995,14933,14939 ,6498,6508,6545 ,0,0,0}, {14993,14934,14994 ,6515,6504,6500 ,0,0,0}, + {14992,14935,14993 ,6500,6522,6515 ,0,0,0}, {14991,14936,14992 ,6504,6500,6500 ,0,0,0}, + {14988,14931,14991 ,6530,6504,6504 ,0,0,0}, {14988,14932,14971 ,6530,6508,6523 ,0,0,0}, + {14989,14927,14932 ,6544,6500,6508 ,0,0,0}, {14990,14928,14927 ,6498,6499,6500 ,0,0,0}, + {14985,14929,14975 ,6530,6498,6500 ,0,0,0}, {14986,14925,14930 ,6498,6527,6527 ,0,0,0}, + {14985,14930,14929 ,6530,6527,6498 ,0,0,0}, {14987,14976,14972 ,6499,6503,6503 ,0,0,0}, + {14986,14987,14925 ,6498,6499,6527 ,0,0,0}, {14976,14984,14926 ,6503,6508,6502 ,0,0,0}, + {14921,14983,14922 ,6538,6500,6559 ,0,0,0}, {14926,14984,14921 ,6502,6508,6538 ,0,0,0}, + {14924,14923,14982 ,6506,6533,6503 ,0,0,0}, {14923,14922,14983 ,6533,6559,6500 ,0,0,0}, + {14981,14919,14977 ,6500,6505,6498 ,0,0,0}, {14977,14924,14982 ,6498,6506,6503 ,0,0,0}, + {15027,14973,14981 ,6558,6543,6500 ,0,0,0}, {15026,14916,14920 ,6556,6512,6557 ,0,0,0}, + {15027,14920,14973 ,6558,6557,6543 ,0,0,0}, {14978,14980,14917 ,6510,6540,6511 ,0,0,0}, + {15026,14978,14916 ,6556,6510,6512 ,0,0,0}, {14918,14979,14974 ,6539,6538,6541 ,0,0,0}, + {14917,14980,14918 ,6511,6540,6539 ,0,0,0}, {13405,14974,14979 ,6500,6541,6538 ,0,0,0}, + {14979,13407,13405 ,6560,6561,6562 ,0,0,0}, {15026,15028,14978 ,6563,6564,6565 ,0,0,0}, + {14980,15029,15030 ,6566,6567,6568 ,0,0,0}, {14977,14982,15031 ,6569,6570,6571 ,0,0,0}, + {15027,14981,15032 ,6572,6573,6574 ,0,0,0}, {15033,15034,14976 ,6575,6576,6577 ,0,0,0}, + {15035,15036,14983 ,6578,6579,6580 ,0,0,0}, {14985,14975,15037 ,6581,6582,6583 ,0,0,0}, + {14987,14986,15038 ,6584,6585,6586 ,0,0,0}, {15039,15040,14988 ,6587,6588,6589 ,0,0,0}, + {15041,14990,14989 ,6590,6591,6592 ,0,0,0}, {14993,14994,15042 ,6593,6594,6595 ,0,0,0}, + {14992,15043,15044 ,6596,6597,6598 ,0,0,0}, {15045,15046,14997 ,6599,6600,6601 ,0,0,0}, + {15047,15048,14995 ,6602,6603,6604 ,0,0,0}, {15049,15000,15050 ,6605,6606,6607 ,0,0,0}, + {14998,14999,15051 ,6608,6609,6610 ,0,0,0}, {15002,15003,15052 ,6611,6612,6613 ,0,0,0}, + {15002,15053,15001 ,6611,6614,6615 ,0,0,0}, {15006,15054,15005 ,6616,6617,6618 ,0,0,0}, + {15055,15056,15004 ,6619,6620,6621 ,0,0,0}, {15007,15057,15025 ,6622,6623,6624 ,0,0,0}, + {15058,15006,15025 ,6625,6616,6624 ,0,0,0}, {15059,15060,15024 ,6626,6627,6628 ,0,0,0}, + {15061,15023,15060 ,6629,6630,6627 ,0,0,0}, {15062,15063,15022 ,6631,6632,6633 ,0,0,0}, + {15059,15010,15063 ,6626,6634,6632 ,0,0,0}, {15013,15064,15014 ,6635,6636,6637 ,0,0,0}, + {15062,15014,15064 ,6631,6637,6636 ,0,0,0}, {15013,15017,15065 ,6635,6638,6639 ,0,0,0}, + {15065,15064,15013 ,6639,6636,6635 ,0,0,0}, {15066,15017,15016 ,6640,6638,6641 ,0,0,0}, + {15017,15066,15065 ,6638,6640,6639 ,0,0,0}, {15015,15067,15016 ,6642,6643,6641 ,0,0,0}, + {15066,15016,15067 ,6640,6641,6643 ,0,0,0}, {15015,15020,15068 ,6642,6644,6645 ,0,0,0}, + {15068,15067,15015 ,6645,6643,6642 ,0,0,0}, {15069,15020,15018 ,6646,6644,6647 ,0,0,0}, + {15020,15069,15068 ,6644,6646,6645 ,0,0,0}, {15019,15070,15018 ,6648,6649,6647 ,0,0,0}, + {15069,15018,15070 ,6646,6647,6649 ,0,0,0}, {15019,15012,15071 ,6648,6650,6651 ,0,0,0}, + {15071,15070,15019 ,6651,6649,6648 ,0,0,0}, {15072,15012,15011 ,6652,6650,6653 ,0,0,0}, + {15012,15072,15071 ,6650,6652,6651 ,0,0,0}, {15011,15073,15074 ,6653,6654,6655 ,0,0,0}, + {15072,15011,15074 ,6652,6653,6655 ,0,0,0}, {15073,15021,15075 ,6654,6656,6657 ,0,0,0}, + {15021,15073,15011 ,6656,6654,6653 ,0,0,0}, {15075,15008,15009 ,6657,6658,6659 ,0,0,0}, + {15021,15008,15075 ,6656,6658,6657 ,0,0,0}, {13461,15076,15009 ,6660,6661,6659 ,0,0,0}, + {15075,15009,15076 ,6657,6659,6661 ,0,0,0}, {13460,15076,13461 ,6660,6661,6660 ,0,0,0}, + {15010,15022,15063 ,6634,6633,6632 ,0,0,0}, {15062,15022,15014 ,6631,6633,6637 ,0,0,0}, + {15023,15024,15060 ,6630,6628,6627 ,0,0,0}, {15059,15024,15010 ,6626,6628,6634 ,0,0,0}, + {15061,15057,15007 ,6629,6623,6622 ,0,0,0}, {15061,15007,15023 ,6629,6622,6630 ,0,0,0}, + {15054,15006,15058 ,6617,6616,6625 ,0,0,0}, {15057,15058,15025 ,6623,6625,6624 ,0,0,0}, + {15005,15055,15004 ,6618,6619,6621 ,0,0,0}, {15054,15055,15005 ,6617,6619,6618 ,0,0,0}, + {15003,15056,15052 ,6612,6620,6613 ,0,0,0}, {15004,15056,15003 ,6621,6620,6612 ,0,0,0}, + {15053,15050,15001 ,6614,6607,6615 ,0,0,0}, {15002,15052,15053 ,6611,6613,6614 ,0,0,0}, + {14999,15000,15049 ,6609,6606,6605 ,0,0,0}, {15000,15001,15050 ,6606,6615,6607 ,0,0,0}, + {15045,14998,15051 ,6599,6608,6610 ,0,0,0}, {15051,14999,15049 ,6610,6609,6605 ,0,0,0}, + {15046,14996,14997 ,6600,6662,6601 ,0,0,0}, {15045,14997,14998 ,6599,6601,6608 ,0,0,0}, + {14995,14996,15047 ,6604,6662,6602 ,0,0,0}, {15046,15047,14996 ,6600,6602,6662 ,0,0,0}, + {14994,15048,15042 ,6594,6603,6595 ,0,0,0}, {14995,15048,14994 ,6604,6603,6594 ,0,0,0}, + {14992,14993,15043 ,6596,6593,6597 ,0,0,0}, {14993,15042,15043 ,6593,6595,6597 ,0,0,0}, + {15039,14991,15044 ,6587,6663,6598 ,0,0,0}, {14991,14992,15044 ,6663,6596,6598 ,0,0,0}, + {15040,14989,14988 ,6588,6592,6589 ,0,0,0}, {15039,14988,14991 ,6587,6589,6663 ,0,0,0}, + {15041,15077,14990 ,6590,6664,6591 ,0,0,0}, {15040,15041,14989 ,6588,6590,6592 ,0,0,0}, + {15037,14975,15077 ,6583,6582,6664 ,0,0,0}, {14990,15077,14975 ,6591,6664,6582 ,0,0,0}, + {14986,14985,15078 ,6585,6581,6665 ,0,0,0}, {14985,15037,15078 ,6581,6583,6665 ,0,0,0}, + {15033,14987,15038 ,6575,6584,6586 ,0,0,0}, {15038,14986,15078 ,6586,6585,6665 ,0,0,0}, + {15034,14984,14976 ,6576,6666,6577 ,0,0,0}, {15033,14976,14987 ,6575,6577,6584 ,0,0,0}, + {14983,14984,15035 ,6580,6666,6578 ,0,0,0}, {15034,15035,14984 ,6576,6578,6666 ,0,0,0}, + {14982,15036,15031 ,6570,6579,6571 ,0,0,0}, {14983,15036,14982 ,6580,6579,6570 ,0,0,0}, + {14981,14977,15079 ,6573,6569,6667 ,0,0,0}, {14977,15031,15079 ,6569,6571,6667 ,0,0,0}, + {15028,15027,15032 ,6564,6572,6574 ,0,0,0}, {15032,14981,15079 ,6574,6573,6667 ,0,0,0}, + {15028,15029,14978 ,6564,6567,6565 ,0,0,0}, {15028,15026,15027 ,6564,6563,6572 ,0,0,0}, + {15030,15080,14980 ,6568,6668,6566 ,0,0,0}, {14978,15029,14980 ,6565,6567,6566 ,0,0,0}, + {13407,14979,15080 ,6561,6560,6668 ,0,0,0}, {14980,15080,14979 ,6566,6668,6560 ,0,0,0}, + {13371,13374,13278 ,6669,6670,6671 ,0,0,0}, {15033,15038,15081 ,6672,6671,6671 ,0,0,0}, + {13284,13380,13293 ,6673,6674,6671 ,0,0,0}, {13374,13376,13287 ,6670,6669,6675 ,0,0,0}, + {13386,13316,13288 ,6670,6676,6677 ,0,0,0}, {15082,15083,15051 ,6324,6298,6672 ,0,0,0}, + {15084,15043,15042 ,6671,6672,6671 ,0,0,0}, {15085,15086,15047 ,6672,6671,6671 ,0,0,0}, + {13399,13310,13306 ,6678,6671,6679 ,0,0,0}, {15044,15043,15087 ,6671,6672,6680 ,0,0,0}, + {13312,13406,13314 ,6679,6671,6671 ,0,0,0}, {15088,15089,15041 ,6672,6672,6672 ,0,0,0}, + {15090,15091,15028 ,6672,6681,6672 ,0,0,0}, {15080,15030,15092 ,6671,6681,6672 ,0,0,0}, + {15093,15035,15034 ,6672,6672,6681 ,0,0,0}, {15031,15094,15095 ,6672,6672,6672 ,0,0,0}, + {15096,15079,15095 ,6672,6671,6672 ,0,0,0}, {15033,15097,15034 ,6672,6671,6681 ,0,0,0}, + {15036,15093,15094 ,6672,6672,6672 ,0,0,0}, {15090,15032,15096 ,6672,6672,6672 ,0,0,0}, + {15098,15099,15078 ,6671,6672,6672 ,0,0,0}, {15030,15029,15100 ,6681,6671,6671 ,0,0,0}, + {15037,15101,15098 ,6671,6681,6671 ,0,0,0}, {13407,15080,13314 ,6671,6671,6671 ,0,0,0}, + {15077,15089,15101 ,6672,6672,6681 ,0,0,0}, {13310,13400,13311 ,6671,6682,6672 ,0,0,0}, + {13312,13311,13401 ,6679,6672,6298 ,0,0,0}, {15044,15102,15039 ,6671,6671,6672 ,0,0,0}, + {15102,15088,15040 ,6671,6672,6672 ,0,0,0}, {13394,13395,13302 ,6672,6681,6670 ,0,0,0}, + {13306,13308,13398 ,6679,6669,6669 ,0,0,0}, {15086,15103,15048 ,6671,6672,6671 ,0,0,0}, + {13392,13394,13304 ,6671,6672,6681 ,0,0,0}, {13299,13316,13388 ,6669,6676,6298 ,0,0,0}, + {13299,13389,13392 ,6669,6669,6671 ,0,0,0}, {15104,15045,15083 ,6672,6671,6298 ,0,0,0}, + {15104,15085,15046 ,6672,6672,6672 ,0,0,0}, {13382,13290,13293 ,6683,6669,6671 ,0,0,0}, + {13288,13290,13383 ,6677,6669,6684 ,0,0,0}, {15053,15105,15050 ,6671,6685,6686 ,0,0,0}, + {15082,15049,15050 ,6324,6687,6686 ,0,0,0}, {15053,15052,15106 ,6671,6688,6688 ,0,0,0}, + {13376,13377,13283 ,6669,6689,6684 ,0,0,0}, {15107,15108,15055 ,6672,6690,6671 ,0,0,0}, + {15108,15109,15056 ,6690,6686,6690 ,0,0,0}, {15110,15107,15054 ,6691,6672,6691 ,0,0,0}, + {13278,13281,13370 ,6671,6692,6672 ,0,0,0}, {13280,13368,13281 ,6693,6673,6692 ,0,0,0}, + {13273,13365,13280 ,6672,6689,6693 ,0,0,0}, {15058,15111,15110 ,6686,6690,6691 ,0,0,0}, + {13364,13273,13276 ,6694,6672,6695 ,0,0,0}, {15057,15112,15111 ,6690,6691,6690 ,0,0,0}, + {13276,13275,13362 ,6695,6696,6697 ,0,0,0}, {15112,15061,15060 ,6691,6672,6688 ,0,0,0}, + {13270,13358,13359 ,6698,6699,6700 ,0,0,0}, {15113,15114,15059 ,6672,6688,6688 ,0,0,0}, + {15063,15062,15115 ,6688,6691,6701 ,0,0,0}, {15116,15064,15065 ,6686,6672,6671 ,0,0,0}, + {13356,13358,13218 ,6676,6699,6702 ,0,0,0}, {15066,15117,15118 ,6672,6671,6671 ,0,0,0}, + {13356,13217,13352 ,6676,6687,6703 ,0,0,0}, {15119,15067,15068 ,6686,6704,6672 ,0,0,0}, + {13217,13265,13408 ,6687,6705,6676 ,0,0,0}, {15070,15120,15069 ,6686,6706,6672 ,0,0,0}, + {13351,13409,13265 ,6698,6699,6705 ,0,0,0}, {13413,13256,13255 ,6697,6707,6708 ,0,0,0}, + {13412,13351,13256 ,6709,6698,6707 ,0,0,0}, {15121,15073,15075 ,6690,6671,6701 ,0,0,0}, + {13255,13349,13415 ,6708,6672,6694 ,0,0,0}, {15076,13243,15122 ,6690,6690,6686 ,0,0,0}, + {13419,13418,13347 ,6673,6689,6710 ,0,0,0}, {13241,13243,13458 ,6711,6690,6690 ,0,0,0}, + {13421,13419,13345 ,6686,6673,6692 ,0,0,0}, {13455,13239,13457 ,6712,6713,6685 ,0,0,0}, + {13340,13341,13427 ,6714,6684,6669 ,0,0,0}, {13451,13236,13238 ,6715,6716,6717 ,0,0,0}, + {13336,13433,13335 ,6718,6719,6691 ,0,0,0}, {13439,13437,13224 ,6298,6670,6676 ,0,0,0}, + {13445,13229,13231 ,6686,6704,6720 ,0,0,0}, {13231,13233,13448 ,6720,6669,6715 ,0,0,0}, + {13439,13226,13442 ,6298,6718,6669 ,0,0,0}, {13226,13229,13443 ,6718,6704,6691 ,0,0,0}, + {15114,15060,15059 ,6688,6688,6688 ,0,0,0}, {13334,13437,13436 ,6676,6670,6684 ,0,0,0}, + {13451,13449,13236 ,6715,6669,6716 ,0,0,0}, {13238,13239,13455 ,6717,6713,6712 ,0,0,0}, + {13238,13455,13451 ,6717,6712,6715 ,0,0,0}, {13339,13430,13341 ,6673,6721,6684 ,0,0,0}, + {13339,13335,13431 ,6673,6691,6670 ,0,0,0}, {13241,13458,13457 ,6711,6690,6685 ,0,0,0}, + {13241,13457,13239 ,6711,6685,6713 ,0,0,0}, {13344,13424,13421 ,6691,6669,6686 ,0,0,0}, + {13425,13344,13340 ,6720,6691,6714 ,0,0,0}, {13460,13458,13243 ,6671,6690,6690 ,0,0,0}, + {15074,15123,15124 ,6686,6722,6688 ,0,0,0}, {15071,15072,15125 ,6691,6723,6706 ,0,0,0}, + {13449,13448,13233 ,6669,6715,6669 ,0,0,0}, {13449,13233,13236 ,6669,6669,6716 ,0,0,0}, + {13448,13445,13231 ,6715,6686,6720 ,0,0,0}, {13445,13443,13229 ,6686,6691,6704 ,0,0,0}, + {13443,13442,13226 ,6691,6669,6718 ,0,0,0}, {13439,13224,13226 ,6298,6676,6718 ,0,0,0}, + {13437,13334,13224 ,6670,6676,6676 ,0,0,0}, {13436,13433,13336 ,6684,6719,6718 ,0,0,0}, + {13436,13336,13334 ,6684,6718,6676 ,0,0,0}, {13433,13431,13335 ,6719,6670,6691 ,0,0,0}, + {13431,13430,13339 ,6670,6721,6673 ,0,0,0}, {13430,13427,13341 ,6721,6669,6684 ,0,0,0}, + {13427,13425,13340 ,6669,6720,6714 ,0,0,0}, {13425,13424,13344 ,6720,6669,6691 ,0,0,0}, + {13421,13345,13344 ,6686,6692,6691 ,0,0,0}, {13419,13347,13345 ,6673,6710,6692 ,0,0,0}, + {13418,13415,13349 ,6689,6694,6672 ,0,0,0}, {13418,13349,13347 ,6689,6672,6710 ,0,0,0}, + {13415,13413,13255 ,6694,6697,6708 ,0,0,0}, {13413,13412,13256 ,6697,6709,6707 ,0,0,0}, + {13412,13409,13351 ,6709,6699,6698 ,0,0,0}, {13409,13408,13265 ,6699,6676,6705 ,0,0,0}, + {13408,13352,13217 ,6676,6703,6687 ,0,0,0}, {13356,13218,13217 ,6676,6702,6687 ,0,0,0}, + {13358,13270,13218 ,6699,6698,6702 ,0,0,0}, {13359,13362,13275 ,6700,6697,6696 ,0,0,0}, + {13359,13275,13270 ,6700,6696,6698 ,0,0,0}, {13362,13364,13276 ,6697,6694,6695 ,0,0,0}, + {13364,13365,13273 ,6694,6689,6672 ,0,0,0}, {13365,13368,13280 ,6689,6673,6693 ,0,0,0}, + {13368,13370,13281 ,6673,6672,6692 ,0,0,0}, {13370,13371,13278 ,6672,6669,6671 ,0,0,0}, + {13374,13287,13278 ,6670,6675,6671 ,0,0,0}, {13376,13283,13287 ,6669,6684,6675 ,0,0,0}, + {13377,13380,13284 ,6689,6674,6673 ,0,0,0}, {13377,13284,13283 ,6689,6673,6684 ,0,0,0}, + {13380,13382,13293 ,6674,6683,6671 ,0,0,0}, {13382,13383,13290 ,6683,6684,6669 ,0,0,0}, + {13383,13386,13288 ,6684,6670,6677 ,0,0,0}, {13386,13388,13316 ,6670,6298,6676 ,0,0,0}, + {13388,13389,13299 ,6298,6669,6669 ,0,0,0}, {13392,13304,13299 ,6671,6681,6669 ,0,0,0}, + {13394,13302,13304 ,6672,6670,6681 ,0,0,0}, {13395,13398,13308 ,6681,6669,6669 ,0,0,0}, + {13395,13308,13302 ,6681,6669,6670 ,0,0,0}, {13398,13399,13306 ,6669,6678,6679 ,0,0,0}, + {13399,13400,13310 ,6678,6682,6671 ,0,0,0}, {13400,13401,13311 ,6682,6298,6672 ,0,0,0}, + {13401,13406,13312 ,6298,6671,6679 ,0,0,0}, {13406,13407,13314 ,6671,6671,6671 ,0,0,0}, + {15080,15092,13314 ,6671,6672,6671 ,0,0,0}, {15030,15100,15092 ,6681,6671,6672 ,0,0,0}, + {15029,15028,15091 ,6671,6672,6681 ,0,0,0}, {15029,15091,15100 ,6671,6681,6671 ,0,0,0}, + {15028,15032,15090 ,6672,6672,6672 ,0,0,0}, {15032,15079,15096 ,6672,6671,6672 ,0,0,0}, + {15079,15031,15095 ,6671,6672,6672 ,0,0,0}, {15031,15036,15094 ,6672,6672,6672 ,0,0,0}, + {15036,15035,15093 ,6672,6672,6672 ,0,0,0}, {15034,15097,15093 ,6681,6671,6672 ,0,0,0}, + {15033,15081,15097 ,6672,6671,6671 ,0,0,0}, {15038,15078,15099 ,6671,6672,6672 ,0,0,0}, + {15038,15099,15081 ,6671,6672,6671 ,0,0,0}, {15078,15037,15098 ,6672,6671,6671 ,0,0,0}, + {15037,15077,15101 ,6671,6672,6681 ,0,0,0}, {15077,15041,15089 ,6672,6672,6672 ,0,0,0}, + {15041,15040,15088 ,6672,6672,6672 ,0,0,0}, {15040,15039,15102 ,6672,6672,6671 ,0,0,0}, + {15044,15087,15102 ,6671,6680,6671 ,0,0,0}, {15043,15084,15087 ,6672,6671,6680 ,0,0,0}, + {15042,15048,15103 ,6671,6671,6672 ,0,0,0}, {15042,15103,15084 ,6671,6672,6671 ,0,0,0}, + {15048,15047,15086 ,6671,6671,6671 ,0,0,0}, {15047,15046,15085 ,6671,6672,6672 ,0,0,0}, + {15046,15045,15104 ,6672,6671,6672 ,0,0,0}, {15045,15051,15083 ,6671,6672,6298 ,0,0,0}, + {15051,15049,15082 ,6672,6687,6324 ,0,0,0}, {15050,15105,15082 ,6686,6685,6324 ,0,0,0}, + {15053,15106,15105 ,6671,6688,6685 ,0,0,0}, {15052,15056,15109 ,6688,6690,6686 ,0,0,0}, + {15052,15109,15106 ,6688,6686,6688 ,0,0,0}, {15056,15055,15108 ,6690,6671,6690 ,0,0,0}, + {15055,15054,15107 ,6671,6691,6672 ,0,0,0}, {15054,15058,15110 ,6691,6686,6691 ,0,0,0}, + {15058,15057,15111 ,6686,6690,6690 ,0,0,0}, {15057,15061,15112 ,6690,6672,6691 ,0,0,0}, + {15060,15114,15112 ,6688,6688,6691 ,0,0,0}, {15063,15113,15059 ,6688,6672,6688 ,0,0,0}, + {15062,15126,15115 ,6691,6691,6701 ,0,0,0}, {15063,15115,15113 ,6688,6701,6672 ,0,0,0}, + {15116,15126,15064 ,6686,6691,6672 ,0,0,0}, {15062,15064,15126 ,6691,6672,6691 ,0,0,0}, + {15116,15065,15118 ,6686,6671,6671 ,0,0,0}, {15117,15066,15067 ,6671,6672,6704 ,0,0,0}, + {15118,15065,15066 ,6671,6671,6672 ,0,0,0}, {15119,15068,15069 ,6686,6672,6672 ,0,0,0}, + {15119,15117,15067 ,6686,6671,6704 ,0,0,0}, {15127,15120,15070 ,6688,6706,6686 ,0,0,0}, + {15120,15119,15069 ,6706,6686,6672 ,0,0,0}, {15127,15071,15125 ,6688,6691,6706 ,0,0,0}, + {15071,15127,15070 ,6691,6688,6686 ,0,0,0}, {15072,15124,15125 ,6723,6688,6706 ,0,0,0}, + {15074,15073,15123 ,6686,6671,6722 ,0,0,0}, {15072,15074,15124 ,6723,6686,6688 ,0,0,0}, + {15121,15075,15122 ,6690,6701,6686 ,0,0,0}, {15123,15073,15121 ,6722,6671,6690 ,0,0,0}, + {13243,15076,13460 ,6690,6690,6671 ,0,0,0}, {15122,15075,15076 ,6686,6701,6690 ,0,0,0}, + {15122,12820,14624 ,6724,6725,6726 ,0,0,0}, {14586,15123,15121 ,6727,6728,6729 ,0,0,0}, + {15125,14588,15127 ,6730,6731,6732 ,0,0,0}, {14729,15124,14727 ,6733,6734,6735 ,0,0,0}, + {15128,14738,15129 ,6736,6737,6738 ,0,0,0}, {14613,15128,15130 ,6739,6736,6736 ,0,0,0}, + {14654,15131,15132 ,6740,6741,6742 ,0,0,0}, {14653,15133,14612 ,6743,6744,6745 ,0,0,0}, + {14736,15134,15135 ,6746,6747,6748 ,0,0,0}, {14783,15136,14741 ,6749,6750,6751 ,0,0,0}, + {15137,15138,14781 ,6752,6753,6754 ,0,0,0}, {15134,14669,14782 ,6747,6755,6756 ,0,0,0}, + {15104,14705,14696 ,6757,6758,6759 ,0,0,0}, {13107,14705,15137 ,6760,6758,6752 ,0,0,0}, + {15086,14698,15103 ,6761,6762,6763 ,0,0,0}, {14697,15086,15085 ,6764,6761,6765 ,0,0,0}, + {14768,14703,15087 ,6766,6767,6768 ,0,0,0}, {14768,15084,14767 ,6766,6769,6770 ,0,0,0}, + {15102,14695,15088 ,6771,6772,6773 ,0,0,0}, {14695,15102,14703 ,6772,6771,6767 ,0,0,0}, + {15089,15088,14672 ,6774,6773,6775 ,0,0,0}, {14695,14672,15088 ,6772,6775,6773 ,0,0,0}, + {14670,15101,14671 ,6776,6777,6778 ,0,0,0}, {15089,14672,14671 ,6774,6775,6778 ,0,0,0}, + {14676,15099,14694 ,6779,6780,6781 ,0,0,0}, {15098,14670,14694 ,6782,6776,6781 ,0,0,0}, + {14675,15097,15081 ,6783,6784,6785 ,0,0,0}, {15094,15093,15139 ,6786,6787,6788 ,0,0,0}, + {15139,14693,15140 ,6788,6789,6788 ,0,0,0}, {15093,15097,14693 ,6787,6784,6789 ,0,0,0}, + {15141,14674,14647 ,6790,6791,6792 ,0,0,0}, {14674,15141,15140 ,6791,6790,6788 ,0,0,0}, + {14646,15142,14647 ,6793,6794,6792 ,0,0,0}, {15141,14647,15142 ,6790,6792,6794 ,0,0,0}, + {14646,14679,15143 ,6793,6795,6796 ,0,0,0}, {15143,15142,14646 ,6796,6794,6793 ,0,0,0}, + {15144,14679,14685 ,6797,6795,6798 ,0,0,0}, {14679,15144,15143 ,6795,6797,6796 ,0,0,0}, + {14689,15145,14685 ,6799,6800,6798 ,0,0,0}, {15144,14685,15145 ,6797,6798,6800 ,0,0,0}, + {14689,14682,15146 ,6799,6801,6802 ,0,0,0}, {15146,15145,14689 ,6802,6800,6799 ,0,0,0}, + {15147,14682,14691 ,6803,6801,6804 ,0,0,0}, {14682,15147,15146 ,6801,6803,6802 ,0,0,0}, + {12921,13324,14691 ,6805,6806,6804 ,0,0,0}, {15147,14691,13324 ,6803,6804,6806 ,0,0,0}, + {15091,15148,15149 ,6807,6808,6809 ,0,0,0}, {15093,14693,15139 ,6787,6789,6788 ,0,0,0}, + {15140,14693,14674 ,6788,6789,6791 ,0,0,0}, {14675,14693,15097 ,6783,6789,6784 ,0,0,0}, + {14676,14675,15081 ,6779,6783,6785 ,0,0,0}, {15081,15099,14676 ,6785,6780,6779 ,0,0,0}, + {14694,15099,15098 ,6781,6780,6782 ,0,0,0}, {14670,15098,15101 ,6776,6782,6777 ,0,0,0}, + {15101,15089,14671 ,6777,6774,6778 ,0,0,0}, {15139,15150,15094 ,6788,6810,6786 ,0,0,0}, + {15148,15091,15090 ,6808,6807,6811 ,0,0,0}, {15150,15095,15094 ,6810,6812,6786 ,0,0,0}, + {15149,15151,15100 ,6809,6813,6814 ,0,0,0}, {15100,15091,15149 ,6814,6807,6809 ,0,0,0}, + {15100,15152,15092 ,6814,6815,6816 ,0,0,0}, {15152,15100,15151 ,6815,6814,6813 ,0,0,0}, + {13314,15092,13315 ,6817,6816,6818 ,0,0,0}, {15152,13315,15092 ,6815,6818,6816 ,0,0,0}, + {15090,15153,15148 ,6811,6819,6808 ,0,0,0}, {14703,15102,15087 ,6767,6771,6768 ,0,0,0}, + {15153,15090,15096 ,6819,6811,6820 ,0,0,0}, {15154,15153,15096 ,6821,6819,6820 ,0,0,0}, + {15095,15150,15154 ,6812,6810,6821 ,0,0,0}, {15095,15154,15096 ,6812,6821,6820 ,0,0,0}, + {15087,15084,14768 ,6768,6769,6766 ,0,0,0}, {14734,15135,15136 ,6822,6748,6750 ,0,0,0}, + {14767,15103,14698 ,6770,6763,6762 ,0,0,0}, {15103,14767,15084 ,6763,6770,6769 ,0,0,0}, + {15086,14697,14698 ,6761,6764,6762 ,0,0,0}, {14696,14697,15085 ,6759,6764,6765 ,0,0,0}, + {15083,14705,15104 ,6823,6758,6757 ,0,0,0}, {15085,15104,14696 ,6765,6757,6759 ,0,0,0}, + {13107,15137,14781 ,6760,6752,6754 ,0,0,0}, {15083,15137,14705 ,6823,6752,6758 ,0,0,0}, + {15134,14736,14669 ,6747,6746,6755 ,0,0,0}, {15138,15134,14782 ,6753,6747,6756 ,0,0,0}, + {15136,14783,14734 ,6750,6749,6822 ,0,0,0}, {15155,14733,15156 ,6824,6825,6826 ,0,0,0}, + {15136,15156,14741 ,6750,6826,6751 ,0,0,0}, {15155,15131,14663 ,6824,6741,6827 ,0,0,0}, + {14733,15155,14663 ,6825,6824,6827 ,0,0,0}, {15132,15133,14653 ,6742,6744,6743 ,0,0,0}, + {14663,15131,14645 ,6827,6741,6828 ,0,0,0}, {15126,15116,15157 ,6829,6830,6831 ,0,0,0}, + {15117,15119,15130 ,6832,6833,6736 ,0,0,0}, {15133,15129,14732 ,6744,6738,6834 ,0,0,0}, + {15121,14624,14586 ,6729,6726,6727 ,0,0,0}, {15125,15124,14729 ,6730,6734,6733 ,0,0,0}, + {14589,14613,15120 ,6835,6739,6836 ,0,0,0}, {14747,15128,14613 ,6837,6736,6739 ,0,0,0}, + {15127,14589,15120 ,6732,6835,6836 ,0,0,0}, {14729,14588,15125 ,6733,6731,6730 ,0,0,0}, + {15127,14588,14589 ,6732,6731,6835 ,0,0,0}, {15123,14727,15124 ,6728,6735,6734 ,0,0,0}, + {14727,15123,14586 ,6735,6728,6727 ,0,0,0}, {14624,15121,15122 ,6726,6729,6724 ,0,0,0}, + {12820,15122,13243 ,6725,6724,6838 ,0,0,0}, {15105,15158,15082 ,6839,6840,6841 ,0,0,0}, + {15083,15082,15158 ,6823,6841,6840 ,0,0,0}, {15158,15105,15159 ,6840,6839,6842 ,0,0,0}, + {15083,15158,15137 ,6823,6840,6752 ,0,0,0}, {15160,15159,15106 ,6843,6842,6844 ,0,0,0}, + {14782,14781,15138 ,6756,6754,6753 ,0,0,0}, {15108,15160,15109 ,6845,6843,6846 ,0,0,0}, + {15108,15161,15160 ,6845,6847,6843 ,0,0,0}, {15162,15161,15107 ,6848,6847,6849 ,0,0,0}, + {14734,14736,15135 ,6822,6746,6748 ,0,0,0}, {15111,15162,15110 ,6850,6848,6851 ,0,0,0}, + {15111,15163,15162 ,6850,6852,6848 ,0,0,0}, {15164,15163,15112 ,6853,6852,6854 ,0,0,0}, + {14733,14741,15156 ,6825,6751,6826 ,0,0,0}, {15114,15165,15164 ,6855,6856,6853 ,0,0,0}, + {15113,15165,15114 ,6857,6856,6855 ,0,0,0}, {15166,15165,15115 ,6858,6856,6859 ,0,0,0}, + {14654,14645,15131 ,6740,6828,6741 ,0,0,0}, {15157,15166,15126 ,6831,6858,6829 ,0,0,0}, + {14653,14654,15132 ,6743,6740,6742 ,0,0,0}, {15167,15157,15118 ,6860,6831,6861 ,0,0,0}, + {14732,14612,15133 ,6834,6745,6744 ,0,0,0}, {15130,15167,15117 ,6736,6860,6832 ,0,0,0}, + {14738,14732,15129 ,6737,6834,6738 ,0,0,0}, {15120,14613,15130 ,6836,6739,6736 ,0,0,0}, + {14738,15128,14747 ,6737,6736,6837 ,0,0,0}, {15120,15130,15119 ,6836,6736,6833 ,0,0,0}, + {15118,15117,15167 ,6861,6832,6860 ,0,0,0}, {15116,15118,15157 ,6830,6861,6831 ,0,0,0}, + {15115,15126,15166 ,6859,6829,6858 ,0,0,0}, {15113,15115,15165 ,6857,6859,6856 ,0,0,0}, + {15112,15114,15164 ,6854,6855,6853 ,0,0,0}, {15111,15112,15163 ,6850,6854,6852 ,0,0,0}, + {15107,15110,15162 ,6849,6851,6848 ,0,0,0}, {15108,15107,15161 ,6845,6849,6847 ,0,0,0}, + {15106,15109,15160 ,6844,6846,6843 ,0,0,0}, {15105,15106,15159 ,6839,6844,6842 ,0,0,0}, + {15168,13115,13116 ,6862,6863,6864 ,0,0,0}, {14820,14809,14047 ,6865,6866,6867 ,0,0,0}, + {15169,14817,14816 ,6868,6869,6870 ,0,0,0}, {14819,14040,14806 ,6871,6872,6873 ,0,0,0}, + {14025,14799,14803 ,6874,6875,6876 ,0,0,0}, {14037,14822,14823 ,6877,6878,6879 ,0,0,0}, + {14833,14032,14031 ,6880,6881,6882 ,0,0,0}, {14830,14024,14027 ,6883,6884,6885 ,0,0,0}, + {15170,14843,14841 ,6886,6887,6888 ,0,0,0}, {15171,14837,14034 ,6889,6890,5525 ,0,0,0}, + {14854,14851,14110 ,6891,6892,6893 ,0,0,0}, {14847,15172,15173 ,6894,6895,6896 ,0,0,0}, + {14861,14099,14915 ,6897,6898,6899 ,0,0,0}, {14857,14105,14860 ,6900,6901,6902 ,0,0,0}, + {14146,14866,14144 ,6903,6904,6905 ,0,0,0}, {14909,14862,14142 ,6906,6907,6908 ,0,0,0}, + {14898,15174,14900 ,6909,6910,6911 ,0,0,0}, {14906,14147,14872 ,6912,6913,6914 ,0,0,0}, + {15175,14887,14879 ,6915,6916,6917 ,0,0,0}, {14897,15176,14884 ,6918,6919,6920 ,0,0,0}, + {15177,14894,14895 ,6921,6922,6923 ,0,0,0}, {14203,14206,14888 ,6924,6925,6926 ,0,0,0}, + {14203,14891,14204 ,6924,6927,5712 ,0,0,0}, {14191,14190,14881 ,6928,6929,6930 ,0,0,0}, + {14191,14896,14206 ,6928,6931,6925 ,0,0,0}, {14901,14903,14190 ,6932,6933,6929 ,0,0,0}, + {14190,14903,14881 ,6929,6933,6930 ,0,0,0}, {14901,14190,14235 ,6932,6929,6934 ,0,0,0}, + {14235,14237,14875 ,6934,6935,6936 ,0,0,0}, {14875,14901,14235 ,6936,6932,6934 ,0,0,0}, + {14907,14237,14239 ,6937,6935,6938 ,0,0,0}, {14237,14907,14875 ,6935,6937,6936 ,0,0,0}, + {14907,14239,14868 ,6937,6938,6939 ,0,0,0}, {14240,14869,14868 ,6940,6941,6939 ,0,0,0}, + {14868,14239,14240 ,6939,6938,6940 ,0,0,0}, {14869,14242,14913 ,6941,6942,6943 ,0,0,0}, + {14242,14869,14240 ,6942,6941,6940 ,0,0,0}, {14863,14913,14243 ,6944,6943,6945 ,0,0,0}, + {14242,14243,14913 ,6942,6945,6943 ,0,0,0}, {14243,15178,14858 ,6945,6946,6947 ,0,0,0}, + {14858,14863,14243 ,6947,6944,6945 ,0,0,0}, {14855,15178,15179 ,6948,6946,6949 ,0,0,0}, + {15178,14855,14858 ,6946,6948,6947 ,0,0,0}, {15180,14852,15179 ,6950,6951,6949 ,0,0,0}, + {14855,15179,14852 ,6948,6949,6951 ,0,0,0}, {15180,13213,13211 ,6950,126,3135 ,0,0,0}, + {13211,14852,15180 ,3135,6951,6950 ,0,0,0}, {14206,14896,14888 ,6925,6931,6926 ,0,0,0}, + {14191,14881,14896 ,6928,6930,6931 ,0,0,0}, {14891,14884,14204 ,6927,6920,5712 ,0,0,0}, + {14203,14888,14891 ,6924,6926,6927 ,0,0,0}, {15176,14897,14894 ,6919,6918,6922 ,0,0,0}, + {15176,14204,14884 ,6919,5712,6920 ,0,0,0}, {15177,14895,14887 ,6921,6923,6916 ,0,0,0}, + {15177,15176,14894 ,6921,6919,6922 ,0,0,0}, {15174,15175,14879 ,6910,6915,6917 ,0,0,0}, + {15175,15177,14887 ,6915,6921,6916 ,0,0,0}, {14149,15174,14898 ,6952,6910,6909 ,0,0,0}, + {14900,15174,14879 ,6911,6910,6917 ,0,0,0}, {14149,14872,14147 ,6952,6914,6913 ,0,0,0}, + {14872,14149,14898 ,6914,6952,6909 ,0,0,0}, {14904,14146,14147 ,6953,6903,6913 ,0,0,0}, + {14904,14147,14906 ,6953,6913,6912 ,0,0,0}, {14866,14911,14144 ,6904,6954,6905 ,0,0,0}, + {14904,14866,14146 ,6953,6904,6903 ,0,0,0}, {14909,14142,14911 ,6906,6908,6954 ,0,0,0}, + {14144,14911,14142 ,6905,6954,6908 ,0,0,0}, {14101,14862,14915 ,6955,6907,6899 ,0,0,0}, + {14142,14862,14101 ,6908,6907,6955 ,0,0,0}, {14111,14099,14861 ,6956,6898,6897 ,0,0,0}, + {14099,14101,14915 ,6898,6955,6899 ,0,0,0}, {14111,14860,14105 ,6956,6902,6901 ,0,0,0}, + {14860,14111,14861 ,6902,6956,6897 ,0,0,0}, {14854,14110,14105 ,6891,6893,6901 ,0,0,0}, + {14854,14105,14857 ,6891,6901,6900 ,0,0,0}, {14851,14849,15173 ,6892,6957,6896 ,0,0,0}, + {14851,15173,14110 ,6892,6896,6893 ,0,0,0}, {14847,14845,15172 ,6894,6958,6895 ,0,0,0}, + {14849,14847,15173 ,6957,6894,6896 ,0,0,0}, {14843,15170,14845 ,6887,6886,6958 ,0,0,0}, + {15172,14845,15170 ,6895,6958,6886 ,0,0,0}, {15171,14841,14839 ,6889,6888,6959 ,0,0,0}, + {15170,14841,15171 ,6886,6888,6889 ,0,0,0}, {14034,14837,14835 ,5525,6890,6960 ,0,0,0}, + {15171,14839,14837 ,6889,6959,6890 ,0,0,0}, {14835,14833,14031 ,6960,6880,6882 ,0,0,0}, + {14031,14034,14835 ,6882,5525,6960 ,0,0,0}, {14800,14027,14032 ,6961,6885,6881 ,0,0,0}, + {14800,14032,14833 ,6961,6881,6880 ,0,0,0}, {14830,14826,14024 ,6883,6962,6884 ,0,0,0}, + {14800,14830,14027 ,6961,6883,6885 ,0,0,0}, {14025,14024,14799 ,6874,6884,6875 ,0,0,0}, + {14826,14799,14024 ,6962,6875,6884 ,0,0,0}, {14030,14803,14822 ,6963,6876,6878 ,0,0,0}, + {14025,14803,14030 ,6874,6876,6963 ,0,0,0}, {14039,14037,14823 ,6964,6877,6879 ,0,0,0}, + {14037,14030,14822 ,6877,6963,6878 ,0,0,0}, {14039,14806,14040 ,6964,6873,6872 ,0,0,0}, + {14806,14039,14823 ,6873,6964,6879 ,0,0,0}, {14819,14820,14047 ,6871,6865,6867 ,0,0,0}, + {14819,14047,14040 ,6871,6867,6872 ,0,0,0}, {14809,14817,15181 ,6866,6869,6965 ,0,0,0}, + {14809,15181,14047 ,6866,6965,6867 ,0,0,0}, {15169,14816,15168 ,6868,6870,6862 ,0,0,0}, + {15181,14817,15169 ,6965,6869,6868 ,0,0,0}, {13115,15168,14816 ,6863,6862,6870 ,0,0,0}, + {13085,15182,14743 ,6966,6967,6968 ,0,0,0}, {15183,14787,15184 ,6969,6970,6971 ,0,0,0}, + {14655,14656,15185 ,6972,6973,6974 ,0,0,0}, {14789,15186,14790 ,6975,6976,6977 ,0,0,0}, + {15187,15188,14731 ,6978,6979,6980 ,0,0,0}, {15189,14786,15190 ,6981,6982,6983 ,0,0,0}, + {14788,14742,15191 ,6984,6985,6986 ,0,0,0}, {14793,15192,15193 ,6987,6988,6989 ,0,0,0}, + {14784,15194,14785 ,6990,6991,6992 ,0,0,0}, {14794,15195,14667 ,6993,6994,6995 ,0,0,0}, + {15196,14794,14735 ,6996,6993,6997 ,0,0,0}, {14668,15197,14795 ,6998,6999,7000 ,0,0,0}, + {15198,14668,14667 ,7001,6998,6995 ,0,0,0}, {14796,14795,15199 ,7002,7000,7003 ,0,0,0}, + {15197,15199,14795 ,6999,7003,7000 ,0,0,0}, {15200,14780,14796 ,7004,7005,7002 ,0,0,0}, + {14796,15199,15200 ,7002,7003,7004 ,0,0,0}, {14780,15201,14798 ,7005,7006,7007 ,0,0,0}, + {15201,14780,15200 ,7006,7005,7004 ,0,0,0}, {14797,14798,15202 ,7008,7007,7009 ,0,0,0}, + {15201,15202,14798 ,7006,7009,7007 ,0,0,0}, {15203,13107,14797 ,7010,82,7008 ,0,0,0}, + {14797,15202,15203 ,7008,7009,7010 ,0,0,0}, {13106,13107,15203 ,7011,82,7010 ,0,0,0}, + {14735,15193,15196 ,6997,6989,6996 ,0,0,0}, {15195,15198,14667 ,6994,7001,6995 ,0,0,0}, + {15198,15197,14668 ,7001,6999,6998 ,0,0,0}, {15195,14794,15196 ,6994,6993,6996 ,0,0,0}, + {15192,14793,14785 ,6988,6987,6992 ,0,0,0}, {15193,14735,14793 ,6989,6997,6987 ,0,0,0}, + {14785,15194,15192 ,6992,6991,6988 ,0,0,0}, {15189,15194,14784 ,6981,6991,6990 ,0,0,0}, + {15204,14790,15186 ,7012,6977,6976 ,0,0,0}, {14788,15190,14786 ,6984,6983,6982 ,0,0,0}, + {14784,14786,15189 ,6990,6982,6981 ,0,0,0}, {14742,14790,15204 ,6985,6977,7012 ,0,0,0}, + {14742,15204,15191 ,6985,7012,6986 ,0,0,0}, {15190,14788,15191 ,6983,6984,6986 ,0,0,0}, + {14787,14655,15184 ,6970,6972,6971 ,0,0,0}, {15186,14789,15188 ,6976,6975,6979 ,0,0,0}, + {15187,14731,14730 ,6978,6980,7013 ,0,0,0}, {14731,15188,14789 ,6980,6979,6975 ,0,0,0}, + {14730,14787,15183 ,7013,6970,6969 ,0,0,0}, {14730,15183,15187 ,7013,6969,6978 ,0,0,0}, + {14656,15182,15185 ,6973,6967,6974 ,0,0,0}, {15184,14655,15185 ,6971,6972,6974 ,0,0,0}, + {13085,14743,13082 ,6966,6968,7014 ,0,0,0}, {15182,14656,14743 ,6967,6973,6968 ,0,0,0}, + {15204,13100,15191 ,730,730,730 ,0,0,0}, {15199,15197,15195 ,730,730,730 ,0,0,0}, + {15197,15198,15195 ,730,730,730 ,0,0,0}, {15195,15196,15200 ,730,730,730 ,0,0,0}, + {15200,15199,15195 ,730,730,730 ,0,0,0}, {15201,15196,15193 ,730,730,730 ,0,0,0}, + {15196,15201,15200 ,730,730,730 ,0,0,0}, {15192,15202,15193 ,730,730,730 ,0,0,0}, + {15201,15193,15202 ,730,730,730 ,0,0,0}, {15203,15192,13106 ,730,730,730 ,0,0,0}, + {15203,15202,15192 ,730,730,730 ,0,0,0}, {15194,15189,13104 ,730,730,730 ,0,0,0}, + {15192,15194,13106 ,730,730,730 ,0,0,0}, {15186,13095,13098 ,730,730,7015 ,0,0,0}, + {13101,13104,15190 ,730,730,730 ,0,0,0}, {15183,13089,13092 ,7016,7015,7017 ,0,0,0}, + {15188,13092,13094 ,730,7017,7017 ,0,0,0}, {13086,13088,15185 ,730,730,730 ,0,0,0}, + {13085,13061,13063 ,730,730,730 ,0,0,0}, {13059,13086,15182 ,7015,730,730 ,0,0,0}, + {13065,13079,13077 ,730,730,7017 ,0,0,0}, {13061,13080,13067 ,730,7017,7015 ,0,0,0}, + {13073,13069,13074 ,730,730,730 ,0,0,0}, {13069,13077,13074 ,730,7017,730 ,0,0,0}, + {13070,13069,13073 ,730,730,730 ,0,0,0}, {13065,13067,13079 ,730,7015,730 ,0,0,0}, + {13069,13065,13077 ,730,730,7017 ,0,0,0}, {13080,13061,13084 ,7017,730,730 ,0,0,0}, + {13079,13067,13080 ,730,7015,7017 ,0,0,0}, {13085,13084,13061 ,730,730,730 ,0,0,0}, + {15182,13063,13059 ,730,730,7015 ,0,0,0}, {15182,13085,13063 ,730,730,730 ,0,0,0}, + {13088,15184,15185 ,730,7016,730 ,0,0,0}, {15185,15182,13086 ,730,730,730 ,0,0,0}, + {15183,15184,13089 ,7016,7016,7015 ,0,0,0}, {13088,13089,15184 ,730,7015,7016 ,0,0,0}, + {13092,15188,15187 ,7017,730,730 ,0,0,0}, {13092,15187,15183 ,7017,730,7016 ,0,0,0}, + {13094,13095,15186 ,7017,730,730 ,0,0,0}, {15188,13094,15186 ,730,7017,730 ,0,0,0}, + {13098,13100,15204 ,7015,730,730 ,0,0,0}, {15186,13098,15204 ,730,7015,730 ,0,0,0}, + {15191,13101,15190 ,730,730,730 ,0,0,0}, {15191,13100,13101 ,730,730,730 ,0,0,0}, + {15194,13104,13106 ,730,730,730 ,0,0,0}, {15189,15190,13104 ,730,730,730 ,0,0,0}, + {15205,15206,13057 ,7018,7019,7020 ,0,0,0}, {13057,15207,15205 ,7020,7021,7018 ,0,0,0}, + {13057,13040,15207 ,7020,7022,7021 ,0,0,0}, {13057,15208,15209 ,7020,7023,7024 ,0,0,0}, + {15206,15208,13057 ,7019,7023,7020 ,0,0,0}, {13057,15210,15211 ,7020,7025,7026 ,0,0,0}, + {15209,15210,13057 ,7024,7025,7020 ,0,0,0}, {15211,15212,13057 ,7026,7027,7020 ,0,0,0}, + {15213,13057,15214 ,7028,7020,7029 ,0,0,0}, {13057,15212,15214 ,7020,7027,7029 ,0,0,0}, + {15215,13057,15216 ,7030,7020,7031 ,0,0,0}, {13057,15213,15216 ,7020,7028,7031 ,0,0,0}, + {15217,13057,15218 ,7032,7020,7033 ,0,0,0}, {13057,15215,15218 ,7020,7030,7033 ,0,0,0}, + {13056,13057,15217 ,7034,7020,7032 ,0,0,0}, {13039,14712,15207 ,7035,7036,7037 ,0,0,0}, + {15209,15208,14702 ,7038,7039,7040 ,0,0,0}, {15206,15205,14711 ,7041,7042,7043 ,0,0,0}, + {15211,14769,15212 ,7044,7045,7046 ,0,0,0}, {14701,14714,15210 ,7047,7048,7049 ,0,0,0}, + {14770,14595,15213 ,7050,7051,7052 ,0,0,0}, {14770,15214,14661 ,7050,7053,7054 ,0,0,0}, + {14659,14718,15215 ,7055,7056,7057 ,0,0,0}, {15215,15216,14659 ,7057,7058,7055 ,0,0,0}, + {15218,14718,14704 ,7059,7056,7060 ,0,0,0}, {14718,15218,15215 ,7056,7059,7057 ,0,0,0}, + {14692,15217,14704 ,7061,7062,7060 ,0,0,0}, {15218,14704,15217 ,7059,7060,7062 ,0,0,0}, + {14692,13055,13056 ,7061,7063,4910 ,0,0,0}, {13056,15217,14692 ,4910,7062,7061 ,0,0,0}, + {14769,15211,14714 ,7045,7044,7048 ,0,0,0}, {14595,15216,15213 ,7051,7058,7052 ,0,0,0}, + {14659,15216,14595 ,7055,7058,7051 ,0,0,0}, {14702,15208,14710 ,7040,7039,7064 ,0,0,0}, + {14661,15214,15212 ,7054,7053,7046 ,0,0,0}, {14770,15213,15214 ,7050,7052,7053 ,0,0,0}, + {14769,14661,15212 ,7045,7054,7046 ,0,0,0}, {15210,14714,15211 ,7049,7048,7044 ,0,0,0}, + {15209,14702,14701 ,7038,7040,7047 ,0,0,0}, {14701,15210,15209 ,7047,7049,7038 ,0,0,0}, + {15205,14712,14711 ,7042,7036,7043 ,0,0,0}, {14710,15206,14711 ,7064,7041,7043 ,0,0,0}, + {15208,15206,14710 ,7039,7041,7064 ,0,0,0}, {13039,15207,13040 ,7035,7037,4929 ,0,0,0}, + {14712,15205,15207 ,7036,7042,7037 ,0,0,0}, {15219,15220,13023 ,7018,7019,7065 ,0,0,0}, + {13023,15221,15219 ,7065,7021,7018 ,0,0,0}, {13023,13006,15221 ,7065,7066,7021 ,0,0,0}, + {13023,15222,15223 ,7065,7023,7024 ,0,0,0}, {15220,15222,13023 ,7019,7023,7065 ,0,0,0}, + {13023,15224,15225 ,7065,7025,7026 ,0,0,0}, {15223,15224,13023 ,7024,7025,7065 ,0,0,0}, + {15225,15226,13023 ,7026,7027,7065 ,0,0,0}, {15227,13023,15228 ,7028,7065,7029 ,0,0,0}, + {13023,15226,15228 ,7065,7027,7029 ,0,0,0}, {15229,13023,15230 ,7030,7065,7031 ,0,0,0}, + {13023,15227,15230 ,7065,7028,7031 ,0,0,0}, {15231,13023,15232 ,7032,7065,7033 ,0,0,0}, + {13023,15229,15232 ,7065,7030,7033 ,0,0,0}, {13022,13023,15231 ,7067,7065,7032 ,0,0,0}, + {13005,14761,15221 ,7068,7069,7070 ,0,0,0}, {15223,15222,14602 ,7071,7072,7073 ,0,0,0}, + {15220,15219,14641 ,7074,7075,7076 ,0,0,0}, {15225,14621,15226 ,7077,7078,7079 ,0,0,0}, + {14603,14766,15224 ,7047,7080,7081 ,0,0,0}, {14585,14764,15227 ,7082,7083,7084 ,0,0,0}, + {14585,15228,14765 ,7082,7085,7086 ,0,0,0}, {14763,14639,15229 ,7087,7088,7089 ,0,0,0}, + {15229,15230,14763 ,7089,7090,7087 ,0,0,0}, {15232,14639,14640 ,7091,7088,7092 ,0,0,0}, + {14639,15232,15229 ,7088,7091,7089 ,0,0,0}, {14762,15231,14640 ,7093,7094,7092 ,0,0,0}, + {15232,14640,15231 ,7091,7092,7094 ,0,0,0}, {14762,13021,13022 ,7093,4831,4942 ,0,0,0}, + {13022,15231,14762 ,4942,7094,7093 ,0,0,0}, {14621,15225,14766 ,7078,7077,7080 ,0,0,0}, + {14764,15230,15227 ,7083,7090,7084 ,0,0,0}, {14763,15230,14764 ,7087,7090,7083 ,0,0,0}, + {14602,15222,14638 ,7073,7072,7095 ,0,0,0}, {14765,15228,15226 ,7086,7085,7079 ,0,0,0}, + {14585,15227,15228 ,7082,7084,7085 ,0,0,0}, {14621,14765,15226 ,7078,7086,7079 ,0,0,0}, + {15224,14766,15225 ,7081,7080,7077 ,0,0,0}, {15223,14602,14603 ,7071,7073,7047 ,0,0,0}, + {14603,15224,15223 ,7047,7081,7071 ,0,0,0}, {15219,14761,14641 ,7075,7069,7076 ,0,0,0}, + {14638,15220,14641 ,7095,7074,7076 ,0,0,0}, {15222,15220,14638 ,7072,7074,7095 ,0,0,0}, + {13005,15221,13006 ,7068,7070,4899 ,0,0,0}, {14761,15219,15221 ,7069,7075,7070 ,0,0,0}, + {15233,15234,12989 ,7018,7019,7065 ,0,0,0}, {12989,15235,15233 ,7065,7021,7018 ,0,0,0}, + {12989,12972,15235 ,7065,7096,7021 ,0,0,0}, {12989,15236,15237 ,7065,7023,7024 ,0,0,0}, + {15234,15236,12989 ,7019,7023,7065 ,0,0,0}, {12989,15238,15239 ,7065,7025,7026 ,0,0,0}, + {15237,15238,12989 ,7024,7025,7065 ,0,0,0}, {15239,15240,12989 ,7026,7027,7065 ,0,0,0}, + {15241,12989,15242 ,7028,7065,7029 ,0,0,0}, {12989,15240,15242 ,7065,7027,7029 ,0,0,0}, + {15243,12989,15244 ,7030,7065,7031 ,0,0,0}, {12989,15241,15244 ,7065,7028,7031 ,0,0,0}, + {15245,12989,15246 ,7032,7065,7033 ,0,0,0}, {12989,15243,15246 ,7065,7030,7033 ,0,0,0}, + {12988,12989,15245 ,7097,7065,7032 ,0,0,0}, {12971,14759,15235 ,7098,7099,7100 ,0,0,0}, + {15237,15236,14724 ,7101,7102,7103 ,0,0,0}, {15234,15233,14751 ,7104,7105,7076 ,0,0,0}, + {15239,14723,15240 ,7106,7107,7108 ,0,0,0}, {14758,14757,15238 ,7109,7110,7111 ,0,0,0}, + {14635,14632,15241 ,7112,7113,7114 ,0,0,0}, {14635,15242,14752 ,7112,7115,7116 ,0,0,0}, + {14637,14636,15243 ,7117,7118,7119 ,0,0,0}, {15243,15244,14637 ,7119,7120,7117 ,0,0,0}, + {15246,14636,14634 ,7121,7118,7122 ,0,0,0}, {14636,15246,15243 ,7118,7121,7119 ,0,0,0}, + {14633,15245,14634 ,7123,7124,7122 ,0,0,0}, {15246,14634,15245 ,7121,7122,7124 ,0,0,0}, + {14633,12987,12988 ,7123,4831,4831 ,0,0,0}, {12988,15245,14633 ,4831,7124,7123 ,0,0,0}, + {14723,15239,14757 ,7107,7106,7110 ,0,0,0}, {14632,15244,15241 ,7113,7120,7114 ,0,0,0}, + {14637,15244,14632 ,7117,7120,7113 ,0,0,0}, {14724,15236,14750 ,7103,7102,7125 ,0,0,0}, + {14752,15242,15240 ,7116,7115,7108 ,0,0,0}, {14635,15241,15242 ,7112,7114,7115 ,0,0,0}, + {14723,14752,15240 ,7107,7116,7108 ,0,0,0}, {15238,14757,15239 ,7111,7110,7106 ,0,0,0}, + {15237,14724,14758 ,7101,7103,7109 ,0,0,0}, {14758,15238,15237 ,7109,7111,7101 ,0,0,0}, + {15233,14759,14751 ,7105,7099,7076 ,0,0,0}, {14750,15234,14751 ,7125,7104,7076 ,0,0,0}, + {15236,15234,14750 ,7102,7104,7125 ,0,0,0}, {12971,15235,12972 ,7098,7100,4865 ,0,0,0}, + {14759,15233,15235 ,7099,7105,7100 ,0,0,0}, {15247,15248,12955 ,7018,7019,7126 ,0,0,0}, + {12955,15249,15247 ,7126,7021,7018 ,0,0,0}, {12955,12938,15249 ,7126,7127,7021 ,0,0,0}, + {12955,15250,15251 ,7126,7023,7024 ,0,0,0}, {15248,15250,12955 ,7019,7023,7126 ,0,0,0}, + {12955,15252,15253 ,7126,7025,7026 ,0,0,0}, {15251,15252,12955 ,7024,7025,7126 ,0,0,0}, + {15253,15254,12955 ,7026,7027,7126 ,0,0,0}, {15255,12955,15256 ,7028,7126,7029 ,0,0,0}, + {12955,15254,15256 ,7126,7027,7029 ,0,0,0}, {15257,12955,15258 ,7030,7126,7031 ,0,0,0}, + {12955,15255,15258 ,7126,7028,7031 ,0,0,0}, {15259,12955,15260 ,7032,7126,7033 ,0,0,0}, + {12955,15257,15260 ,7126,7030,7033 ,0,0,0}, {12954,12955,15259 ,7128,7126,7032 ,0,0,0}, + {12937,14740,15249 ,7129,7099,7130 ,0,0,0}, {15251,15250,14745 ,7131,7132,7133 ,0,0,0}, + {15248,15247,14739 ,7041,7075,7134 ,0,0,0}, {15253,14746,15254 ,7135,7107,7136 ,0,0,0}, + {14744,14772,15252 ,7137,7138,7139 ,0,0,0}, {14622,14623,15255 ,7140,7141,7142 ,0,0,0}, + {14622,15256,14728 ,7140,7143,7144 ,0,0,0}, {14706,14707,15257 ,7145,7146,7147 ,0,0,0}, + {15257,15258,14706 ,7147,7148,7145 ,0,0,0}, {15260,14707,14792 ,7149,7146,7150 ,0,0,0}, + {14707,15260,15257 ,7146,7149,7147 ,0,0,0}, {14791,15259,14792 ,7151,7152,7150 ,0,0,0}, + {15260,14792,15259 ,7149,7150,7152 ,0,0,0}, {14791,12953,12954 ,7151,7153,4831 ,0,0,0}, + {12954,15259,14791 ,4831,7152,7151 ,0,0,0}, {14746,15253,14772 ,7107,7135,7138 ,0,0,0}, + {14623,15258,15255 ,7141,7148,7142 ,0,0,0}, {14706,15258,14623 ,7145,7148,7141 ,0,0,0}, + {14745,15250,14748 ,7133,7132,7154 ,0,0,0}, {14728,15256,15254 ,7144,7143,7136 ,0,0,0}, + {14622,15255,15256 ,7140,7142,7143 ,0,0,0}, {14746,14728,15254 ,7107,7144,7136 ,0,0,0}, + {15252,14772,15253 ,7139,7138,7135 ,0,0,0}, {15251,14745,14744 ,7131,7133,7137 ,0,0,0}, + {14744,15252,15251 ,7137,7139,7131 ,0,0,0}, {15247,14740,14739 ,7075,7099,7134 ,0,0,0}, + {14748,15248,14739 ,7154,7041,7134 ,0,0,0}, {15250,15248,14748 ,7132,7041,7154 ,0,0,0}, + {12937,15249,12938 ,7129,7130,4929 ,0,0,0}, {14740,15247,15249 ,7099,7075,7130 ,0,0,0}, + {12898,12897,15261 ,4777,21,7155 ,0,0,0}, {14605,14618,15262 ,7156,7157,7158 ,0,0,0}, + {14614,15263,15264 ,7159,7160,7161 ,0,0,0}, {15265,15266,14596 ,7162,7163,7164 ,0,0,0}, + {15267,14662,14620 ,7165,7166,7167 ,0,0,0}, {14673,14717,15268 ,7168,7169,7170 ,0,0,0}, + {14658,15269,15270 ,7171,7172,7173 ,0,0,0}, {14648,15271,14680 ,7174,7175,7176 ,0,0,0}, + {15272,15273,14677 ,7177,7178,7179 ,0,0,0}, {15274,15275,14686 ,7180,7181,7182 ,0,0,0}, + {15276,14678,14680 ,7183,7184,7176 ,0,0,0}, {15277,15278,14687 ,7185,7186,7187 ,0,0,0}, + {15277,14684,15275 ,7185,7188,7181 ,0,0,0}, {14688,15278,15279 ,7189,7186,7190 ,0,0,0}, + {15278,14688,14687 ,7186,7189,7187 ,0,0,0}, {15280,14683,15279 ,7191,7192,7190 ,0,0,0}, + {14688,15279,14683 ,7189,7190,7192 ,0,0,0}, {15280,15281,14681 ,7191,7193,7194 ,0,0,0}, + {14681,14683,15280 ,7194,7192,7191 ,0,0,0}, {14690,15281,15282 ,7195,7193,7196 ,0,0,0}, + {15281,14690,14681 ,7193,7195,7194 ,0,0,0}, {12920,14691,15282 ,7197,7198,7196 ,0,0,0}, + {14690,15282,14691 ,7195,7196,7198 ,0,0,0}, {12921,14691,12920 ,7199,7198,7197 ,0,0,0}, + {14648,15273,15271 ,7174,7178,7175 ,0,0,0}, {14684,14686,15275 ,7188,7182,7181 ,0,0,0}, + {15277,14687,14684 ,7185,7187,7188 ,0,0,0}, {14678,15276,15274 ,7184,7183,7180 ,0,0,0}, + {15274,14686,14678 ,7180,7182,7184 ,0,0,0}, {15276,14680,15271 ,7183,7176,7175 ,0,0,0}, + {15273,14648,14677 ,7178,7174,7179 ,0,0,0}, {14673,15268,15272 ,7168,7170,7177 ,0,0,0}, + {14673,15272,14677 ,7168,7177,7179 ,0,0,0}, {14662,15265,14596 ,7166,7162,7164 ,0,0,0}, + {15270,14717,14658 ,7173,7169,7171 ,0,0,0}, {14717,15270,15268 ,7169,7173,7170 ,0,0,0}, + {14597,14596,15266 ,7200,7164,7163 ,0,0,0}, {14658,14597,15269 ,7171,7200,7172 ,0,0,0}, + {15269,14597,15266 ,7172,7200,7163 ,0,0,0}, {15267,15265,14662 ,7165,7162,7166 ,0,0,0}, + {15283,15267,14620 ,7201,7165,7167 ,0,0,0}, {14605,15262,15283 ,7156,7158,7201 ,0,0,0}, + {14605,15283,14620 ,7156,7201,7167 ,0,0,0}, {14719,15261,15263 ,7202,7155,7160 ,0,0,0}, + {15264,14618,14614 ,7161,7157,7159 ,0,0,0}, {14618,15264,15262 ,7157,7161,7158 ,0,0,0}, + {14719,15263,14614 ,7202,7160,7159 ,0,0,0}, {15261,14719,12898 ,7155,7202,4777 ,0,0,0}, + {12886,15274,12889 ,730,7015,730 ,0,0,0}, {15264,15263,15269 ,730,730,730 ,0,0,0}, + {12896,12892,15273 ,730,730,730 ,0,0,0}, {12890,15276,15271 ,730,730,7015 ,0,0,0}, + {15270,15269,15263 ,730,730,730 ,0,0,0}, {12897,15272,15261 ,730,730,730 ,0,0,0}, + {15267,15283,15262 ,730,730,730 ,0,0,0}, {15262,15264,15266 ,730,730,730 ,0,0,0}, + {15262,15266,15265 ,730,730,730 ,0,0,0}, {15267,15262,15265 ,730,730,730 ,0,0,0}, + {15263,15261,15270 ,730,730,730 ,0,0,0}, {15266,15264,15269 ,730,730,730 ,0,0,0}, + {15261,15268,15270 ,730,730,730 ,0,0,0}, {15272,12897,15273 ,730,730,730 ,0,0,0}, + {15268,15261,15272 ,730,730,730 ,0,0,0}, {15273,12892,15271 ,730,730,7015 ,0,0,0}, + {15273,12897,12896 ,730,730,730 ,0,0,0}, {15276,12890,12889 ,730,730,730 ,0,0,0}, + {15271,12892,12890 ,7015,730,730 ,0,0,0}, {15275,15274,12886 ,730,7015,730 ,0,0,0}, + {15274,15276,12889 ,7015,730,730 ,0,0,0}, {15277,12886,12885 ,7015,730,730 ,0,0,0}, + {12886,15277,15275 ,730,7015,730 ,0,0,0}, {15277,12885,15278 ,7015,730,730 ,0,0,0}, + {12878,15278,12882 ,730,730,730 ,0,0,0}, {15278,12885,12882 ,730,730,730 ,0,0,0}, + {12878,12877,15279 ,730,730,7015 ,0,0,0}, {15279,15278,12878 ,7015,730,730 ,0,0,0}, + {15279,12877,15280 ,7015,730,7015 ,0,0,0}, {12881,15281,15280 ,730,730,7015 ,0,0,0}, + {15280,12877,12881 ,7015,730,730 ,0,0,0}, {15281,12876,15282 ,730,730,7015 ,0,0,0}, + {12876,15281,12881 ,730,730,730 ,0,0,0}, {12872,12920,12876 ,730,7015,730 ,0,0,0}, + {15282,12876,12920 ,7015,730,7015 ,0,0,0}, {12919,12901,12917 ,7015,7015,730 ,0,0,0}, + {12872,12871,12919 ,730,730,7015 ,0,0,0}, {12913,12908,12911 ,7015,7015,7015 ,0,0,0}, + {12905,12914,12902 ,7015,7015,730 ,0,0,0}, {12913,12905,12907 ,7015,7015,7015 ,0,0,0}, + {12908,12913,12907 ,7015,7015,7015 ,0,0,0}, {12917,12902,12914 ,730,730,7015 ,0,0,0}, + {12914,12905,12913 ,7015,7015,7015 ,0,0,0}, {12919,12871,12901 ,7015,730,7015 ,0,0,0}, + {12917,12901,12902 ,730,7015,730 ,0,0,0}, {12919,12920,12872 ,7015,7015,730 ,0,0,0}, + {12848,14579,15284 ,126,7203,7204 ,0,0,0}, {15285,15286,14581 ,7205,7206,7207 ,0,0,0}, + {14631,15287,14699 ,7208,7209,7210 ,0,0,0}, {14720,14722,15288 ,7211,7212,7213 ,0,0,0}, + {15289,14592,15290 ,7214,7215,7216 ,0,0,0}, {15291,15292,14617 ,7217,7218,7219 ,0,0,0}, + {14642,15293,14760 ,7220,7221,7222 ,0,0,0}, {14611,15294,15295 ,7223,7224,7225 ,0,0,0}, + {14609,14610,15296 ,7226,7227,7228 ,0,0,0}, {14607,14601,15297 ,7229,7230,7231 ,0,0,0}, + {15298,14608,14607 ,7232,7233,7229 ,0,0,0}, {14599,14600,15299 ,7234,7235,7236 ,0,0,0}, + {15300,14601,14599 ,7237,7230,7234 ,0,0,0}, {14598,15301,14600 ,7238,7239,7235 ,0,0,0}, + {15299,14600,15301 ,7236,7235,7239 ,0,0,0}, {15302,14598,14591 ,7240,7238,7241 ,0,0,0}, + {14598,15302,15301 ,7238,7240,7239 ,0,0,0}, {14591,14590,15303 ,7241,7242,7243 ,0,0,0}, + {15303,15302,14591 ,7243,7240,7241 ,0,0,0}, {14587,15304,14590 ,7244,7245,7242 ,0,0,0}, + {15303,14590,15304 ,7243,7242,7245 ,0,0,0}, {15305,14587,12870 ,7246,7244,82 ,0,0,0}, + {14587,15305,15304 ,7244,7246,7245 ,0,0,0}, {12868,15305,12870 ,7011,7246,82 ,0,0,0}, + {14608,15298,15294 ,7233,7232,7224 ,0,0,0}, {15297,14601,15300 ,7231,7230,7237 ,0,0,0}, + {15300,14599,15299 ,7237,7234,7236 ,0,0,0}, {15297,15298,14607 ,7231,7232,7229 ,0,0,0}, + {15295,14610,14611 ,7225,7227,7223 ,0,0,0}, {15294,14611,14608 ,7224,7223,7233 ,0,0,0}, + {14610,15295,15296 ,7227,7225,7228 ,0,0,0}, {15291,14609,15296 ,7217,7226,7228 ,0,0,0}, + {15306,15288,14722 ,7247,7213,7212 ,0,0,0}, {14642,14617,15292 ,7220,7219,7218 ,0,0,0}, + {14609,15291,14617 ,7226,7217,7219 ,0,0,0}, {14760,15306,14722 ,7222,7247,7212 ,0,0,0}, + {14760,15293,15306 ,7222,7221,7247 ,0,0,0}, {15292,15293,14642 ,7218,7221,7220 ,0,0,0}, + {14581,15286,14631 ,7207,7206,7208 ,0,0,0}, {15288,15290,14720 ,7213,7216,7211 ,0,0,0}, + {15289,14594,14592 ,7214,7248,7215 ,0,0,0}, {14592,14720,15290 ,7215,7211,7216 ,0,0,0}, + {14594,15285,14581 ,7248,7205,7207 ,0,0,0}, {14594,15289,15285 ,7248,7214,7205 ,0,0,0}, + {14699,15287,15284 ,7210,7209,7204 ,0,0,0}, {15286,15287,14631 ,7206,7209,7208 ,0,0,0}, + {12848,12845,14579 ,126,4726,7203 ,0,0,0}, {15284,14579,14699 ,7204,7203,7210 ,0,0,0}, + {15299,15297,15300 ,7249,7250,7251 ,0,0,0}, {12850,15286,12852 ,726,726,7252 ,0,0,0}, + {15302,15297,15301 ,7253,7250,7253 ,0,0,0}, {15297,15299,15301 ,7250,7249,7253 ,0,0,0}, + {15298,15302,15303 ,7254,7253,7249 ,0,0,0}, {15302,15298,15297 ,7253,7254,7250 ,0,0,0}, + {15303,15304,15294 ,7249,7249,7255 ,0,0,0}, {15294,15298,15303 ,7255,7254,7249 ,0,0,0}, + {15304,15295,15294 ,7249,7256,7255 ,0,0,0}, {15305,12868,15295 ,7257,7257,7256 ,0,0,0}, + {15305,15295,15304 ,7257,7256,7249 ,0,0,0}, {15296,12867,15291 ,7258,726,7259 ,0,0,0}, + {15295,12868,15296 ,7256,7257,7258 ,0,0,0}, {15306,15293,12862 ,7260,7254,7257 ,0,0,0}, + {12864,15292,12867 ,7252,7261,726 ,0,0,0}, {12855,15290,12856 ,726,7262,7252 ,0,0,0}, + {12861,12858,15288 ,726,7252,7263 ,0,0,0}, {15287,12850,12849 ,7253,726,726 ,0,0,0}, + {15285,12855,12852 ,726,726,7252 ,0,0,0}, {12848,12825,12824 ,726,726,726 ,0,0,0}, + {12823,15284,12849 ,7264,7253,726 ,0,0,0}, {12829,12841,12842 ,726,7257,726 ,0,0,0}, + {12824,12830,12844 ,726,7264,726 ,0,0,0}, {12836,12838,12832 ,7257,726,7257 ,0,0,0}, + {12838,12841,12832 ,726,7257,7257 ,0,0,0}, {12836,12832,12834 ,7257,7257,7257 ,0,0,0}, + {12842,12830,12829 ,726,7264,726 ,0,0,0}, {12841,12829,12832 ,7257,726,7257 ,0,0,0}, + {12846,12824,12844 ,726,726,726 ,0,0,0}, {12844,12830,12842 ,726,7264,726 ,0,0,0}, + {12825,12848,15284 ,726,726,7253 ,0,0,0}, {12824,12846,12848 ,726,726,726 ,0,0,0}, + {12849,15284,15287 ,726,7253,7253 ,0,0,0}, {12825,15284,12823 ,726,7253,7264 ,0,0,0}, + {12852,15286,15285 ,7252,726,726 ,0,0,0}, {15286,12850,15287 ,726,726,7253 ,0,0,0}, + {15290,12855,15289 ,7262,726,7262 ,0,0,0}, {15289,12855,15285 ,7262,726,726 ,0,0,0}, + {12858,12856,15288 ,7252,7252,7263 ,0,0,0}, {12856,15290,15288 ,7252,7262,7263 ,0,0,0}, + {15288,15306,12861 ,7263,7260,726 ,0,0,0}, {12864,12862,15293 ,7252,7257,7254 ,0,0,0}, + {12862,12861,15306 ,7257,726,7260 ,0,0,0}, {12867,15292,15291 ,726,7261,7259 ,0,0,0}, + {12864,15293,15292 ,7252,7254,7261 ,0,0,0}, {12867,15296,12868 ,726,7258,7257 ,0,0,0}, + {12798,15307,14573 ,4799,7265,7266 ,0,0,0}, {15308,14575,15309 ,7267,7268,7269 ,0,0,0}, + {14574,14749,15310 ,7270,7271,7272 ,0,0,0}, {14756,15311,14583 ,7273,7274,7275 ,0,0,0}, + {15312,15313,14755 ,7276,7277,7278 ,0,0,0}, {15314,14753,15315 ,7279,7280,7281 ,0,0,0}, + {14773,14725,15316 ,7282,7283,7284 ,0,0,0}, {14774,15317,15318 ,7285,7286,7287 ,0,0,0}, + {14628,15319,14629 ,7288,7289,7290 ,0,0,0}, {14775,15320,14626 ,7291,7292,7293 ,0,0,0}, + {15321,14775,14584 ,7294,7291,7295 ,0,0,0}, {14625,15322,14776 ,7296,7297,7298 ,0,0,0}, + {15323,14625,14626 ,7299,7296,7293 ,0,0,0}, {14777,14776,15324 ,7300,7298,7301 ,0,0,0}, + {15322,15324,14776 ,7297,7301,7298 ,0,0,0}, {15325,14726,14777 ,7302,7303,7300 ,0,0,0}, + {14777,15324,15325 ,7300,7301,7302 ,0,0,0}, {14726,15326,14779 ,7303,7304,7305 ,0,0,0}, + {15326,14726,15325 ,7304,7303,7302 ,0,0,0}, {14778,14779,15327 ,7306,7305,7307 ,0,0,0}, + {15326,15327,14779 ,7304,7307,7305 ,0,0,0}, {15328,12820,14778 ,7308,21,7306 ,0,0,0}, + {14778,15327,15328 ,7306,7307,7308 ,0,0,0}, {12819,12820,15328 ,7309,21,7308 ,0,0,0}, + {14584,15318,15321 ,7295,7287,7294 ,0,0,0}, {15320,15323,14626 ,7292,7299,7293 ,0,0,0}, + {15323,15322,14625 ,7299,7297,7296 ,0,0,0}, {15320,14775,15321 ,7292,7291,7294 ,0,0,0}, + {15317,14774,14629 ,7286,7285,7290 ,0,0,0}, {15318,14584,14774 ,7287,7295,7285 ,0,0,0}, + {14629,15319,15317 ,7290,7289,7286 ,0,0,0}, {15314,15319,14628 ,7279,7289,7288 ,0,0,0}, + {15329,14583,15311 ,7310,7275,7274 ,0,0,0}, {14773,15315,14753 ,7282,7281,7280 ,0,0,0}, + {14628,14753,15314 ,7288,7280,7279 ,0,0,0}, {14725,14583,15329 ,7283,7275,7310 ,0,0,0}, + {14725,15329,15316 ,7283,7310,7284 ,0,0,0}, {15315,14773,15316 ,7281,7282,7284 ,0,0,0}, + {14575,14574,15309 ,7268,7270,7269 ,0,0,0}, {15311,14756,15313 ,7274,7273,7277 ,0,0,0}, + {15312,14755,14754 ,7276,7278,7311 ,0,0,0}, {14755,15313,14756 ,7278,7277,7273 ,0,0,0}, + {14754,14575,15308 ,7311,7268,7267 ,0,0,0}, {14754,15308,15312 ,7311,7267,7276 ,0,0,0}, + {14749,15307,15310 ,7271,7265,7272 ,0,0,0}, {15309,14574,15310 ,7269,7270,7272 ,0,0,0}, + {12798,14573,12795 ,4799,7266,7199 ,0,0,0}, {15307,14749,14573 ,7265,7271,7266 ,0,0,0}, + {15320,12790,12787 ,730,7312,6103 ,0,0,0}, {12783,15324,12786 ,7313,730,730 ,0,0,0}, + {12793,15317,12797 ,7314,7015,7315 ,0,0,0}, {15321,15318,12792 ,730,730,7316 ,0,0,0}, + {15316,15310,15315 ,730,7317,7313 ,0,0,0}, {15319,15307,12798 ,730,7318,7319 ,0,0,0}, + {15308,15309,15329 ,7320,7316,7316 ,0,0,0}, {15311,15313,15308 ,7320,6103,7320 ,0,0,0}, + {15312,15308,15313 ,6111,7320,6103 ,0,0,0}, {15316,15329,15309 ,730,7316,7316 ,0,0,0}, + {15329,15311,15308 ,7316,7320,7320 ,0,0,0}, {15307,15315,15310 ,7318,7313,7317 ,0,0,0}, + {15310,15316,15309 ,7317,730,7316 ,0,0,0}, {15319,15314,15307 ,730,7316,7318 ,0,0,0}, + {15307,15314,15315 ,7318,7316,7313 ,0,0,0}, {12797,15317,12798 ,7315,7015,7319 ,0,0,0}, + {12798,15317,15319 ,7319,7015,730 ,0,0,0}, {12792,15318,12793 ,7316,730,7314 ,0,0,0}, + {12793,15318,15317 ,7314,730,7015 ,0,0,0}, {15321,12792,12790 ,730,7316,7312 ,0,0,0}, + {12787,15323,15320 ,6103,7017,730 ,0,0,0}, {12790,15320,15321 ,7312,730,730 ,0,0,0}, + {15323,12787,15322 ,7017,6103,7017 ,0,0,0}, {12786,15324,15322 ,730,730,7017 ,0,0,0}, + {15322,12787,12786 ,7017,6103,730 ,0,0,0}, {15324,12783,12782 ,730,7313,730 ,0,0,0}, + {12782,12778,15325 ,730,7316,730 ,0,0,0}, {15325,15324,12782 ,730,730,730 ,0,0,0}, + {15326,12778,12780 ,7016,7316,7313 ,0,0,0}, {12778,15326,15325 ,7316,7016,730 ,0,0,0}, + {12774,15327,12780 ,7015,730,7313 ,0,0,0}, {15326,12780,15327 ,7016,7313,730 ,0,0,0}, + {15328,12774,12819 ,730,7015,730 ,0,0,0}, {15328,15327,12774 ,730,730,7015 ,0,0,0}, + {12774,12776,12819 ,7015,7015,730 ,0,0,0}, {12817,12799,12814 ,730,730,730 ,0,0,0}, + {12776,12772,12817 ,7015,730,730 ,0,0,0}, {12811,12807,12808 ,730,730,7017 ,0,0,0}, + {12802,12813,12801 ,7015,7016,730 ,0,0,0}, {12811,12802,12805 ,730,7015,730 ,0,0,0}, + {12807,12811,12805 ,730,730,730 ,0,0,0}, {12814,12801,12813 ,730,730,7016 ,0,0,0}, + {12813,12802,12811 ,7016,7015,730 ,0,0,0}, {12817,12772,12799 ,730,730,730 ,0,0,0}, + {12814,12799,12801 ,730,730,730 ,0,0,0}, {12817,12819,12776 ,730,730,7015 ,0,0,0}, + {13330,15330,15331 ,7321,1711,7322 ,0,0,0}, {13320,13317,15332 ,7323,7324,7325 ,0,0,0}, + {15333,13319,13328 ,7326,7327,7328 ,0,0,0}, {15146,15334,15145 ,7329,7330,7331 ,0,0,0}, + {15335,15336,13324 ,7332,7333,7334 ,0,0,0}, {15143,15337,15142 ,7335,7336,7337 ,0,0,0}, + {15337,15144,15338 ,7336,7338,7339 ,0,0,0}, {15141,15142,15339 ,7340,7337,7341 ,0,0,0}, + {15337,15339,15142 ,7336,7341,7337 ,0,0,0}, {15340,15140,15141 ,1359,1359,7340 ,0,0,0}, + {15141,15339,15340 ,7340,7341,1359 ,0,0,0}, {15338,15144,15145 ,7339,7338,7331 ,0,0,0}, + {15337,15143,15144 ,7336,7335,7338 ,0,0,0}, {15334,15146,15147 ,7330,7329,7342 ,0,0,0}, + {15334,15338,15145 ,7330,7339,7331 ,0,0,0}, {15147,13324,15336 ,7342,7334,7333 ,0,0,0}, + {15336,15334,15147 ,7333,7330,7342 ,0,0,0}, {13323,15332,15335 ,7343,7325,7332 ,0,0,0}, + {13323,15335,13324 ,7343,7332,7334 ,0,0,0}, {13317,15341,15332 ,7324,7344,7325 ,0,0,0}, + {13323,13320,15332 ,7343,7323,7325 ,0,0,0}, {15333,15341,13319 ,7326,7344,7327 ,0,0,0}, + {13317,13319,15341 ,7324,7327,7344 ,0,0,0}, {15333,13327,15331 ,7326,7345,7322 ,0,0,0}, + {13328,13327,15333 ,7328,7345,7326 ,0,0,0}, {15330,13330,13296 ,1711,7321,1711 ,0,0,0}, + {15331,13327,13330 ,7322,7345,7321 ,0,0,0}, {15330,13298,15342 ,2197,7346,7346 ,0,0,0}, + {13298,15330,13296 ,7346,2197,2197 ,0,0,0}, {15343,15344,15150 ,1435,7347,7348 ,0,0,0}, + {15151,15149,15345 ,7349,7350,7351 ,0,0,0}, {15148,15153,15346 ,7352,7353,7354 ,0,0,0}, + {13309,15347,13307 ,7355,7356,7357 ,0,0,0}, {15348,15349,13315 ,7358,7359,7360 ,0,0,0}, + {13303,15350,13301 ,7361,7362,7363 ,0,0,0}, {13303,13305,15350 ,7361,7364,7362 ,0,0,0}, + {13300,13301,15351 ,7365,7363,7366 ,0,0,0}, {15350,15351,13301 ,7362,7366,7363 ,0,0,0}, + {15342,13298,13300 ,1790,1790,7365 ,0,0,0}, {13300,15351,15342 ,7365,7366,1790 ,0,0,0}, + {13307,15352,13305 ,7357,7367,7364 ,0,0,0}, {15350,13305,15352 ,7362,7364,7367 ,0,0,0}, + {15148,15353,15149 ,7352,7368,7350 ,0,0,0}, {13309,13313,15347 ,7355,7369,7356 ,0,0,0}, + {15347,15352,13307 ,7356,7367,7357 ,0,0,0}, {13313,13315,15349 ,7369,7360,7359 ,0,0,0}, + {15349,15347,13313 ,7359,7356,7369 ,0,0,0}, {15348,13315,15152 ,7358,7360,7370 ,0,0,0}, + {15345,15152,15151 ,7351,7370,7349 ,0,0,0}, {15152,15345,15348 ,7370,7351,7358 ,0,0,0}, + {15353,15345,15149 ,7368,7351,7350 ,0,0,0}, {15346,15154,15344 ,7354,7371,7347 ,0,0,0}, + {15154,15346,15153 ,7371,7354,7353 ,0,0,0}, {15353,15148,15346 ,7368,7352,7354 ,0,0,0}, + {15343,15150,15139 ,1435,7348,1435 ,0,0,0}, {15344,15154,15150 ,7347,7371,7348 ,0,0,0}, + {15139,15340,15343 ,1398,7372,1398 ,0,0,0}, {15340,15139,15140 ,7372,1398,7372 ,0,0,0}, + {15340,15344,15343 ,7373,730,730 ,0,0,0}, {15341,15350,15352 ,730,730,730 ,0,0,0}, + {15338,15345,15353 ,7374,7375,7375 ,0,0,0}, {15353,15346,15337 ,7375,730,7373 ,0,0,0}, + {15336,15349,15348 ,7375,7375,7375 ,0,0,0}, {15348,15345,15334 ,7375,7375,730 ,0,0,0}, + {15352,15347,15332 ,730,730,7376 ,0,0,0}, {15347,15349,15335 ,730,7375,7375 ,0,0,0}, + {15331,15351,15333 ,730,730,730 ,0,0,0}, {15350,15333,15351 ,730,730,730 ,0,0,0}, + {15331,15330,15342 ,730,730,730 ,0,0,0}, {15342,15351,15331 ,730,730,730 ,0,0,0}, + {15352,15332,15341 ,730,7376,730 ,0,0,0}, {15350,15341,15333 ,730,730,730 ,0,0,0}, + {15347,15335,15332 ,730,7375,7376 ,0,0,0}, {15349,15336,15335 ,7375,7375,7375 ,0,0,0}, + {15348,15334,15336 ,7375,730,7375 ,0,0,0}, {15345,15338,15334 ,7375,7374,730 ,0,0,0}, + {15353,15337,15338 ,7375,7373,7374 ,0,0,0}, {15346,15339,15337 ,730,730,7373 ,0,0,0}, + {15340,15339,15344 ,7373,730,730 ,0,0,0}, {15346,15344,15339 ,730,730,730 ,0,0,0}, + {15354,13228,15355 ,7377,1435,1435 ,0,0,0}, {15356,13244,15357 ,7378,7379,7379 ,0,0,0}, + {15358,13219,13223 ,7380,7380,7377 ,0,0,0}, {13251,15359,15360 ,7381,7381,7382 ,0,0,0}, + {13246,15361,13249 ,7378,7383,7383 ,0,0,0}, {13258,15362,13260 ,7384,7385,7385 ,0,0,0}, + {15363,13258,13253 ,7384,7384,7382 ,0,0,0}, {13263,13260,15364 ,7386,7385,7386 ,0,0,0}, + {15362,15364,13260 ,7385,7386,7385 ,0,0,0}, {15365,13266,13263 ,7387,7388,7386 ,0,0,0}, + {13263,15364,15365 ,7386,7386,7387 ,0,0,0}, {15360,15363,13253 ,7382,7384,7382 ,0,0,0}, + {15363,15362,13258 ,7384,7385,7384 ,0,0,0}, {13249,15359,13251 ,7383,7381,7381 ,0,0,0}, + {13251,15360,13253 ,7381,7382,7382 ,0,0,0}, {13246,15356,15361 ,7378,7378,7383 ,0,0,0}, + {13249,15361,15359 ,7383,7383,7381 ,0,0,0}, {13244,13219,15357 ,7379,7380,7379 ,0,0,0}, + {13246,13244,15356 ,7378,7379,7378 ,0,0,0}, {15358,13223,15354 ,7380,7377,7377 ,0,0,0}, + {15357,13219,15358 ,7379,7380,7380 ,0,0,0}, {13228,15354,13223 ,1435,7377,7377 ,0,0,0}, + {15355,13225,15366 ,1398,1398,1398 ,0,0,0}, {13225,15355,13228 ,1398,1398,1398 ,0,0,0}, + {15367,15368,13350 ,7389,7390,7390 ,0,0,0}, {15369,13346,15370 ,7391,7391,7392 ,0,0,0}, + {13348,13257,15371 ,7392,7393,7393 ,0,0,0}, {13338,15372,15373 ,7394,7395,7394 ,0,0,0}, + {13343,15374,13342 ,7396,7396,7395 ,0,0,0}, {13333,15375,15376 ,7397,7398,7397 ,0,0,0}, + {15375,13333,13337 ,7398,7397,7398 ,0,0,0}, {15377,13331,15376 ,7399,7399,7397 ,0,0,0}, + {13333,15376,13331 ,7397,7397,7399 ,0,0,0}, {15377,15366,13225 ,7399,1359,1359 ,0,0,0}, + {13225,13331,15377 ,1359,7399,7399 ,0,0,0}, {15370,13348,15371 ,7392,7392,7393 ,0,0,0}, + {13337,13338,15373 ,7398,7394,7394 ,0,0,0}, {15373,15375,13337 ,7394,7398,7398 ,0,0,0}, + {15372,13338,13342 ,7395,7394,7395 ,0,0,0}, {15369,15374,13343 ,7391,7396,7396 ,0,0,0}, + {13342,15374,15372 ,7395,7396,7395 ,0,0,0}, {13348,15370,13346 ,7392,7392,7391 ,0,0,0}, + {13343,13346,15369 ,7396,7391,7391 ,0,0,0}, {13350,15368,13257 ,7390,7390,7393 ,0,0,0}, + {13257,15368,15371 ,7393,7390,7393 ,0,0,0}, {15367,13350,13216 ,7389,7390,7400 ,0,0,0}, + {15365,15367,13216 ,7401,7402,7402 ,0,0,0}, {15365,13216,13266 ,7401,7402,7401 ,0,0,0}, + {15377,15358,15354 ,7403,7403,7404 ,0,0,0}, {15363,15371,15362 ,7375,7375,730 ,0,0,0}, + {15359,15369,15360 ,7375,730,730 ,0,0,0}, {15370,15363,15360 ,730,7375,730 ,0,0,0}, + {15356,15372,15361 ,7373,7375,7373 ,0,0,0}, {15374,15359,15361 ,730,7375,7373 ,0,0,0}, + {15357,15376,15375 ,7405,7406,730 ,0,0,0}, {15373,15356,15357 ,7373,7373,7405 ,0,0,0}, + {15377,15376,15358 ,7403,7406,7403 ,0,0,0}, {15354,15355,15366 ,7404,730,7407 ,0,0,0}, + {15366,15377,15354 ,7407,7403,7404 ,0,0,0}, {15376,15357,15358 ,7406,7405,7403 ,0,0,0}, + {15373,15357,15375 ,7373,7405,730 ,0,0,0}, {15372,15356,15373 ,7375,7373,7373 ,0,0,0}, + {15374,15361,15372 ,730,7373,7375 ,0,0,0}, {15369,15359,15374 ,730,7375,730 ,0,0,0}, + {15370,15360,15369 ,730,730,730 ,0,0,0}, {15371,15363,15370 ,7375,7375,730 ,0,0,0}, + {15368,15362,15371 ,730,730,7375 ,0,0,0}, {15364,15368,15367 ,7373,730,730 ,0,0,0}, + {15368,15364,15362 ,730,7373,730 ,0,0,0}, {15364,15367,15365 ,7373,730,7405 ,0,0,0}, + {15378,15137,15379 ,7408,7409,7410 ,0,0,0}, {15380,15135,15381 ,7411,7412,7412 ,0,0,0}, + {15382,15134,15138 ,7413,7413,7408 ,0,0,0}, {15155,15383,15384 ,7414,7414,7415 ,0,0,0}, + {15136,15385,15156 ,7411,7416,7416 ,0,0,0}, {15132,15386,15133 ,7417,7418,7418 ,0,0,0}, + {15387,15132,15131 ,7417,7417,7415 ,0,0,0}, {15129,15133,15388 ,7419,7418,7419 ,0,0,0}, + {15386,15388,15133 ,7418,7419,7418 ,0,0,0}, {15389,15128,15129 ,1790,1790,7419 ,0,0,0}, + {15129,15388,15389 ,7419,7419,1790 ,0,0,0}, {15384,15387,15131 ,7415,7417,7415 ,0,0,0}, + {15387,15386,15132 ,7417,7418,7417 ,0,0,0}, {15156,15383,15155 ,7416,7414,7414 ,0,0,0}, + {15155,15384,15131 ,7414,7415,7415 ,0,0,0}, {15136,15380,15385 ,7411,7411,7416 ,0,0,0}, + {15156,15385,15383 ,7416,7416,7414 ,0,0,0}, {15135,15134,15381 ,7412,7413,7412 ,0,0,0}, + {15136,15135,15380 ,7411,7412,7411 ,0,0,0}, {15382,15138,15378 ,7413,7408,7408 ,0,0,0}, + {15381,15134,15382 ,7412,7413,7413 ,0,0,0}, {15137,15378,15138 ,7409,7408,7408 ,0,0,0}, + {15158,15390,15379 ,7420,7420,7421 ,0,0,0}, {15158,15379,15137 ,7420,7421,7421 ,0,0,0}, + {15391,15392,15167 ,1711,7422,7422 ,0,0,0}, {15393,15165,15394 ,7423,7423,7424 ,0,0,0}, + {15166,15157,15395 ,7424,7425,7425 ,0,0,0}, {15162,15396,15397 ,7426,7427,7426 ,0,0,0}, + {15164,15398,15163 ,7428,7428,7427 ,0,0,0}, {15160,15399,15400 ,7429,7430,7429 ,0,0,0}, + {15399,15160,15161 ,7430,7429,7430 ,0,0,0}, {15401,15159,15400 ,7431,7431,7429 ,0,0,0}, + {15160,15400,15159 ,7429,7429,7431 ,0,0,0}, {15401,15390,15158 ,7431,7432,82 ,0,0,0}, + {15158,15159,15401 ,82,7431,7431 ,0,0,0}, {15394,15166,15395 ,7424,7424,7425 ,0,0,0}, + {15161,15162,15397 ,7430,7426,7426 ,0,0,0}, {15397,15399,15161 ,7426,7430,7430 ,0,0,0}, + {15396,15162,15163 ,7427,7426,7427 ,0,0,0}, {15393,15398,15164 ,7423,7428,7428 ,0,0,0}, + {15163,15398,15396 ,7427,7428,7427 ,0,0,0}, {15166,15394,15165 ,7424,7424,7423 ,0,0,0}, + {15164,15165,15393 ,7428,7423,7423 ,0,0,0}, {15167,15392,15157 ,7422,7422,7425 ,0,0,0}, + {15157,15392,15395 ,7425,7422,7425 ,0,0,0}, {15391,15167,15130 ,1711,7422,1711 ,0,0,0}, + {15130,15389,15391 ,2197,2197,2197 ,0,0,0}, {15389,15130,15128 ,2197,2197,2197 ,0,0,0}, + {15389,15392,15391 ,7433,730,730 ,0,0,0}, {15380,15381,15397 ,7375,7375,730 ,0,0,0}, + {15384,15394,15387 ,730,730,730 ,0,0,0}, {15394,15395,15386 ,730,7376,730 ,0,0,0}, + {15385,15398,15383 ,730,730,7376 ,0,0,0}, {15393,15384,15383 ,730,730,7376 ,0,0,0}, + {15396,15385,15380 ,7376,730,7375 ,0,0,0}, {15400,15382,15378 ,7375,7376,7376 ,0,0,0}, + {15381,15382,15399 ,7375,7376,7375 ,0,0,0}, {15379,15401,15378 ,7374,7376,7376 ,0,0,0}, + {15400,15378,15401 ,7375,7376,7376 ,0,0,0}, {15390,15401,15379 ,730,7376,7374 ,0,0,0}, + {15399,15382,15400 ,7375,7376,7375 ,0,0,0}, {15397,15381,15399 ,730,7375,7375 ,0,0,0}, + {15396,15380,15397 ,7376,7375,730 ,0,0,0}, {15398,15385,15396 ,730,730,7376 ,0,0,0}, + {15393,15383,15398 ,730,7376,730 ,0,0,0}, {15394,15384,15393 ,730,730,730 ,0,0,0}, + {15394,15386,15387 ,730,730,730 ,0,0,0}, {15395,15388,15386 ,7376,7433,730 ,0,0,0}, + {15389,15388,15392 ,7433,7433,730 ,0,0,0}, {15395,15392,15388 ,7376,730,7433 ,0,0,0}, + {14565,12738,12736 ,7434,4326,7435 ,0,0,0}, {14737,14665,14562 ,7436,7437,7438 ,0,0,0}, + {14566,14664,14567 ,7439,7440,7441 ,0,0,0}, {14572,14560,14708 ,7442,7443,7444 ,0,0,0}, + {14570,14713,14771 ,7445,7446,7447 ,0,0,0}, {14716,14715,14550 ,7448,7449,7450 ,0,0,0}, + {14700,14568,14569 ,7451,7452,7453 ,0,0,0}, {14544,14543,14615 ,7454,7455,7456 ,0,0,0}, + {14546,14604,14606 ,7457,7458,7459 ,0,0,0}, {14534,14651,14538 ,7460,7461,7462 ,0,0,0}, + {14657,14616,14542 ,7463,7464,7465 ,0,0,0}, {14649,14576,14528 ,7466,7467,7468 ,0,0,0}, + {14652,14530,14576 ,7469,7470,7467 ,0,0,0}, {14721,14525,14532 ,7471,7472,7473 ,0,0,0}, + {14529,14525,14650 ,7474,7472,7475 ,0,0,0}, {14644,14533,14537 ,7476,7477,7478 ,0,0,0}, + {14532,14533,14643 ,7473,7477,7479 ,0,0,0}, {14540,14627,14537 ,7480,7481,7478 ,0,0,0}, + {14644,14537,14627 ,7476,7478,7481 ,0,0,0}, {14540,14549,14619 ,7480,7482,7483 ,0,0,0}, + {14619,14627,14540 ,7483,7481,7480 ,0,0,0}, {14593,14549,14548 ,7484,7482,7485 ,0,0,0}, + {14549,14593,14619 ,7482,7484,7483 ,0,0,0}, {14552,14582,14548 ,7486,7487,7485 ,0,0,0}, + {14593,14548,14582 ,7484,7485,7487 ,0,0,0}, {14552,14557,14580 ,7486,7488,7489 ,0,0,0}, + {14580,14582,14552 ,7489,7487,7486 ,0,0,0}, {14630,14557,14556 ,7490,7488,7491 ,0,0,0}, + {14557,14630,14580 ,7488,7490,7489 ,0,0,0}, {12770,14578,14556 ,82,7492,7491 ,0,0,0}, + {14630,14556,14578 ,7490,7491,7492 ,0,0,0}, {12769,14578,12770 ,82,7492,82 ,0,0,0}, + {14643,14721,14532 ,7479,7471,7473 ,0,0,0}, {14643,14533,14644 ,7479,7477,7476 ,0,0,0}, + {14529,14650,14649 ,7474,7475,7466 ,0,0,0}, {14650,14525,14721 ,7475,7472,7471 ,0,0,0}, + {14576,14530,14528 ,7467,7470,7468 ,0,0,0}, {14649,14528,14529 ,7466,7468,7474 ,0,0,0}, + {14652,14651,14534 ,7469,7461,7460 ,0,0,0}, {14652,14534,14530 ,7469,7460,7470 ,0,0,0}, + {14538,14657,14542 ,7462,7463,7465 ,0,0,0}, {14651,14657,14538 ,7461,7463,7462 ,0,0,0}, + {14543,14616,14615 ,7455,7464,7456 ,0,0,0}, {14542,14616,14543 ,7465,7464,7455 ,0,0,0}, + {14546,14544,14604 ,7457,7454,7458 ,0,0,0}, {14544,14615,14604 ,7454,7456,7458 ,0,0,0}, + {14716,14551,14606 ,7448,7493,7459 ,0,0,0}, {14551,14546,14606 ,7493,7457,7459 ,0,0,0}, + {14715,14569,14550 ,7449,7453,7450 ,0,0,0}, {14716,14550,14551 ,7448,7450,7493 ,0,0,0}, + {14700,14709,14568 ,7451,7494,7452 ,0,0,0}, {14715,14700,14569 ,7449,7451,7453 ,0,0,0}, + {14708,14560,14709 ,7444,7443,7494 ,0,0,0}, {14568,14709,14560 ,7452,7494,7443 ,0,0,0}, + {14570,14572,14713 ,7445,7442,7446 ,0,0,0}, {14572,14708,14713 ,7442,7444,7446 ,0,0,0}, + {14737,14561,14771 ,7436,7495,7447 ,0,0,0}, {14561,14570,14771 ,7495,7445,7447 ,0,0,0}, + {14665,14566,14562 ,7437,7439,7438 ,0,0,0}, {14737,14562,14561 ,7436,7438,7495 ,0,0,0}, + {14664,14666,14567 ,7440,7496,7441 ,0,0,0}, {14665,14664,14566 ,7437,7440,7439 ,0,0,0}, + {12738,14565,14666 ,4326,7434,7496 ,0,0,0}, {14567,14666,14565 ,7441,7496,7434 ,0,0,0}, + {15402,12686,12685 ,7497,763,7498 ,0,0,0}, {15403,14558,15404 ,7499,7500,7501 ,0,0,0}, + {15405,14571,14563 ,7502,7503,7504 ,0,0,0}, {15406,15407,14547 ,7505,7506,7507 ,0,0,0}, + {15408,15409,14555 ,7508,7509,7510 ,0,0,0}, {15410,14535,15411 ,7511,7512,7513 ,0,0,0}, + {14539,15412,15411 ,7514,7515,7513 ,0,0,0}, {15413,14527,15414 ,7516,7517,7518 ,0,0,0}, + {14526,15410,15414 ,7519,7511,7518 ,0,0,0}, {15415,14541,14536 ,7520,7521,7522 ,0,0,0}, + {14536,15413,15415 ,7522,7516,7520 ,0,0,0}, {14541,15416,14553 ,7521,7523,7524 ,0,0,0}, + {15416,14541,15415 ,7523,7521,7520 ,0,0,0}, {14554,14553,15417 ,7525,7524,7526 ,0,0,0}, + {15416,15417,14553 ,7523,7526,7524 ,0,0,0}, {12704,14554,15418 ,761,7525,7527 ,0,0,0}, + {14554,15417,15418 ,7525,7526,7527 ,0,0,0}, {12703,14554,12704 ,761,7525,761 ,0,0,0}, + {14526,15414,14527 ,7519,7518,7517 ,0,0,0}, {14536,14527,15413 ,7522,7517,7516 ,0,0,0}, + {14531,14535,15410 ,7528,7512,7511 ,0,0,0}, {14526,14531,15410 ,7519,7528,7511 ,0,0,0}, + {14545,15412,14539 ,7529,7515,7514 ,0,0,0}, {14535,14539,15411 ,7512,7514,7513 ,0,0,0}, + {14547,15407,14545 ,7507,7506,7529 ,0,0,0}, {15412,14545,15407 ,7515,7529,7506 ,0,0,0}, + {14555,15409,14547 ,7510,7509,7507 ,0,0,0}, {15409,15406,14547 ,7509,7505,7507 ,0,0,0}, + {14559,15403,15408 ,7530,7499,7508 ,0,0,0}, {14559,15408,14555 ,7530,7508,7510 ,0,0,0}, + {14558,14571,15404 ,7500,7503,7501 ,0,0,0}, {14559,14558,15403 ,7530,7500,7499 ,0,0,0}, + {15405,14563,15402 ,7502,7504,7497 ,0,0,0}, {15404,14571,15405 ,7501,7503,7502 ,0,0,0}, + {12686,15402,14564 ,763,7497,7531 ,0,0,0}, {15402,14563,14564 ,7497,7504,7531 ,0,0,0}, + {15417,15416,15415 ,7015,7532,7017 ,0,0,0}, {12690,15404,15405 ,7016,7015,7015 ,0,0,0}, + {15410,15413,15414 ,7533,7534,7535 ,0,0,0}, {15415,15410,15417 ,7017,7533,7015 ,0,0,0}, + {15417,15410,15418 ,7015,7533,7016 ,0,0,0}, {15410,15415,15413 ,7533,7017,7534 ,0,0,0}, + {15411,15418,15410 ,7536,7016,7533 ,0,0,0}, {15418,15412,12704 ,7016,730,7015 ,0,0,0}, + {15412,15418,15411 ,730,7016,7536 ,0,0,0}, {15409,12699,15406 ,7535,730,7320 ,0,0,0}, + {15412,15407,12704 ,730,6104,7015 ,0,0,0}, {15403,12693,15408 ,730,730,7534 ,0,0,0}, + {12696,15409,15408 ,7537,7535,7534 ,0,0,0}, {15402,12685,12689 ,7016,7015,730 ,0,0,0}, + {15405,12691,12690 ,7015,730,7016 ,0,0,0}, {12682,12670,12684 ,730,730,730 ,0,0,0}, + {12684,12668,12685 ,730,7016,7015 ,0,0,0}, {12681,12678,12682 ,730,730,730 ,0,0,0}, + {12670,12676,12675 ,730,7016,7016 ,0,0,0}, {12678,12670,12682 ,730,730,730 ,0,0,0}, + {12670,12669,12684 ,730,730,730 ,0,0,0}, {12670,12678,12676 ,730,730,7016 ,0,0,0}, + {12668,12689,12685 ,7016,730,7015 ,0,0,0}, {12669,12668,12684 ,730,7016,730 ,0,0,0}, + {12691,15405,12689 ,730,7015,730 ,0,0,0}, {12689,15405,15402 ,730,7015,7016 ,0,0,0}, + {12690,12693,15404 ,7016,730,7015 ,0,0,0}, {15408,12693,12695 ,7534,730,7537 ,0,0,0}, + {15404,12693,15403 ,7015,730,730 ,0,0,0}, {15408,12695,12696 ,7534,7537,7537 ,0,0,0}, + {12699,15407,15406 ,730,6104,7320 ,0,0,0}, {15409,12696,12699 ,7535,7537,730 ,0,0,0}, + {12704,15407,12701 ,7015,6104,730 ,0,0,0}, {12699,12701,15407 ,730,730,6104 ,0,0,0}, + {13613,13612,15419 ,7538,7539,7540 ,0,0,0}, {15420,13604,13613 ,7541,7542,7538 ,0,0,0}, + {15420,15421,13604 ,7541,82,7542 ,0,0,0}, {15419,15420,13613 ,7540,7541,7538 ,0,0,0}, + {13612,13983,15422 ,7539,7543,7544 ,0,0,0}, {13642,13641,15423 ,7545,7546,7547 ,0,0,0}, + {15424,15422,13983 ,7548,7544,7543 ,0,0,0}, {13983,13642,15424 ,7543,7545,7548 ,0,0,0}, + {15423,15424,13642 ,7547,7548,7545 ,0,0,0}, {13612,15422,15419 ,7539,7544,7540 ,0,0,0}, + {15423,13641,15425 ,7547,7546,7549 ,0,0,0}, {13640,15426,15425 ,7550,7551,7549 ,0,0,0}, + {15425,13641,13640 ,7549,7546,7550 ,0,0,0}, {15426,13640,13615 ,7551,7550,7552 ,0,0,0}, + {13628,15427,13615 ,7553,7554,7552 ,0,0,0}, {13628,13618,15428 ,7553,7555,7556 ,0,0,0}, + {13628,15428,15427 ,7553,7556,7554 ,0,0,0}, {15429,13609,15430 ,7557,7558,7559 ,0,0,0}, + {15428,13618,15429 ,7556,7555,7557 ,0,0,0}, {15429,13618,13609 ,7557,7555,7558 ,0,0,0}, + {13609,13611,15430 ,7558,7559,7559 ,0,0,0}, {15426,13615,15427 ,7551,7552,7554 ,0,0,0}, + {13605,15421,15431 ,7560,82,7561 ,0,0,0}, {15421,13605,13604 ,82,7560,7542 ,0,0,0}, + {15432,13647,15431 ,7562,7563,7561 ,0,0,0}, {13605,15431,13647 ,7560,7561,7563 ,0,0,0}, + {15432,15433,13861 ,7562,7564,7565 ,0,0,0}, {13861,13647,15432 ,7565,7563,7562 ,0,0,0}, + {13686,15433,15434 ,7566,7564,7567 ,0,0,0}, {15433,13686,13861 ,7564,7566,7565 ,0,0,0}, + {15435,13687,15434 ,7568,7569,7567 ,0,0,0}, {13686,15434,13687 ,7566,7567,7569 ,0,0,0}, + {15435,15436,13683 ,7568,7570,7571 ,0,0,0}, {13683,13687,15435 ,7571,7569,7568 ,0,0,0}, + {13651,15436,15437 ,7572,7570,7573 ,0,0,0}, {15436,13651,13683 ,7570,7572,7571 ,0,0,0}, + {15438,13670,15437 ,7574,7575,7573 ,0,0,0}, {13651,15437,13670 ,7572,7573,7575 ,0,0,0}, + {15438,15439,13671 ,7574,7576,7577 ,0,0,0}, {13671,13670,15438 ,7577,7575,7574 ,0,0,0}, + {13673,15439,15440 ,7578,7576,7579 ,0,0,0}, {15439,13673,13671 ,7576,7578,7577 ,0,0,0}, + {13673,15440,13674 ,7578,7579,7580 ,0,0,0}, {13674,15440,15441 ,7580,7579,7580 ,0,0,0}, + {14499,14505,15441 ,7581,7581,7581 ,0,0,0}, {15441,13111,14490 ,7581,7581,7581 ,0,0,0}, + {14490,14496,15441 ,7581,7581,7581 ,0,0,0}, {14510,15441,14505 ,7581,7581,7581 ,0,0,0}, + {14496,14499,15441 ,7581,7581,7581 ,0,0,0}, {14514,14473,15441 ,7581,7581,7581 ,0,0,0}, + {14514,15441,14510 ,7581,7581,7581 ,0,0,0}, {14473,14485,15441 ,7581,7581,7581 ,0,0,0}, + {13674,15441,14484 ,7581,7581,7581 ,0,0,0}, {14485,14484,15441 ,7581,7581,7581 ,0,0,0}, + {15430,13611,14057 ,7582,7582,7582 ,0,0,0}, {14057,14084,15430 ,7582,7582,7582 ,0,0,0}, + {15430,14070,14050 ,7582,7582,7582 ,0,0,0}, {14084,14070,15430 ,7582,7582,7582 ,0,0,0}, + {15430,14052,14066 ,7582,7582,7582 ,0,0,0}, {14050,14052,15430 ,7582,7582,7582 ,0,0,0}, + {15430,14059,14043 ,7582,7582,7582 ,0,0,0}, {14066,14059,15430 ,7582,7582,7582 ,0,0,0}, + {14047,15430,14042 ,7582,7582,7582 ,0,0,0}, {14043,14042,15430 ,7582,7582,7582 ,0,0,0}, + {15438,13116,13114 ,726,726,726 ,0,0,0}, {15431,15421,13116 ,726,726,726 ,0,0,0}, + {15440,15439,13114 ,726,726,726 ,0,0,0}, {13114,15439,15438 ,726,726,726 ,0,0,0}, + {13114,13108,15441 ,726,726,726 ,0,0,0}, {15441,15440,13114 ,726,726,726 ,0,0,0}, + {13117,13111,15441 ,7583,7583,726 ,0,0,0}, {13117,15441,13108 ,7583,726,726 ,0,0,0}, + {15438,15437,13116 ,726,726,726 ,0,0,0}, {13116,15436,15435 ,726,726,726 ,0,0,0}, + {15437,15436,13116 ,726,726,726 ,0,0,0}, {13116,15434,15433 ,726,726,726 ,0,0,0}, + {15435,15434,13116 ,726,726,726 ,0,0,0}, {13116,15432,15431 ,726,726,726 ,0,0,0}, + {15433,15432,13116 ,726,726,726 ,0,0,0}, {15420,13116,15421 ,726,726,726 ,0,0,0}, + {15419,15422,13116 ,726,726,726 ,0,0,0}, {15419,13116,15420 ,726,726,726 ,0,0,0}, + {15424,15423,13116 ,726,726,726 ,0,0,0}, {15424,13116,15422 ,726,726,726 ,0,0,0}, + {15425,15426,13116 ,726,726,726 ,0,0,0}, {15425,13116,15423 ,726,726,726 ,0,0,0}, + {15427,15428,13116 ,726,726,726 ,0,0,0}, {15427,13116,15426 ,726,726,726 ,0,0,0}, + {13116,15428,15168 ,726,726,726 ,0,0,0}, {15430,15168,15429 ,726,726,726 ,0,0,0}, + {15168,15428,15429 ,726,726,726 ,0,0,0}, {15169,15168,15430 ,726,726,726 ,0,0,0}, + {14047,15181,15430 ,7583,726,726 ,0,0,0}, {15169,15430,15181 ,726,726,726 ,0,0,0}, + {12646,15442,13900 ,7584,7585,7586 ,0,0,0}, {15443,13873,15444 ,7587,7588,7589 ,0,0,0}, + {13911,13833,15445 ,7590,7591,7592 ,0,0,0}, {13600,15446,13862 ,7593,7594,7595 ,0,0,0}, + {15447,15448,13603 ,4334,7596,7597 ,0,0,0}, {15449,13608,15450 ,7598,7599,7600 ,0,0,0}, + {13607,13865,15451 ,7601,7602,7603 ,0,0,0}, {13665,13657,15452 ,7604,7605,7606 ,0,0,0}, + {13661,15453,13657 ,7607,7608,7605 ,0,0,0}, {13662,15454,15455 ,7609,7610,7611 ,0,0,0}, + {13665,15456,13664 ,7604,7612,7613 ,0,0,0}, {15457,13675,15455 ,7614,7615,7611 ,0,0,0}, + {13662,15455,13675 ,7609,7611,7615 ,0,0,0}, {15457,15458,13668 ,7614,7616,7617 ,0,0,0}, + {13668,13675,15457 ,7617,7615,7614 ,0,0,0}, {13677,15458,15459 ,7618,7616,7619 ,0,0,0}, + {15458,13677,13668 ,7616,7618,7617 ,0,0,0}, {15460,13637,15459 ,7620,7621,7619 ,0,0,0}, + {13677,15459,13637 ,7618,7619,7621 ,0,0,0}, {15460,12665,12666 ,7620,7622,4289 ,0,0,0}, + {12666,13637,15460 ,4289,7621,7620 ,0,0,0}, {15452,13657,15453 ,7606,7605,7608 ,0,0,0}, + {15454,13664,15456 ,7610,7613,7612 ,0,0,0}, {13664,15454,13662 ,7613,7610,7609 ,0,0,0}, + {15452,15456,13665 ,7606,7612,7604 ,0,0,0}, {15449,15453,13661 ,7598,7608,7607 ,0,0,0}, + {13607,15451,15450 ,7601,7603,7600 ,0,0,0}, {13607,15450,13608 ,7601,7600,7599 ,0,0,0}, + {13661,13608,15449 ,7607,7599,7598 ,0,0,0}, {13865,15461,15451 ,7602,7623,7603 ,0,0,0}, + {15461,13865,13862 ,7623,7602,7595 ,0,0,0}, {15448,15446,13600 ,7596,7594,7593 ,0,0,0}, + {15446,15461,13862 ,7594,7623,7595 ,0,0,0}, {13603,15448,13600 ,7597,7596,7593 ,0,0,0}, + {13901,15443,15447 ,7624,7587,4334 ,0,0,0}, {13901,15447,13603 ,7624,4334,7597 ,0,0,0}, + {13873,13911,15444 ,7588,7590,7589 ,0,0,0}, {13901,13873,15443 ,7624,7588,7587 ,0,0,0}, + {13833,15442,15445 ,7591,7585,7592 ,0,0,0}, {15444,13911,15445 ,7589,7590,7592 ,0,0,0}, + {12646,13900,12644 ,7584,7586,4535 ,0,0,0}, {15442,13833,13900 ,7585,7591,7586 ,0,0,0}, + {15448,12657,15446 ,726,7625,726 ,0,0,0}, {15457,15455,15458 ,726,726,726 ,0,0,0}, + {15460,15459,15458 ,726,726,726 ,0,0,0}, {15456,15452,15454 ,726,726,726 ,0,0,0}, + {15458,15455,15452 ,726,726,726 ,0,0,0}, {15458,15452,15453 ,726,726,726 ,0,0,0}, + {15454,15452,15455 ,726,726,726 ,0,0,0}, {15453,15449,15460 ,726,726,726 ,0,0,0}, + {15460,15458,15453 ,726,726,726 ,0,0,0}, {15449,15450,12663 ,726,726,7626 ,0,0,0}, + {15449,12665,15460 ,726,726,726 ,0,0,0}, {15461,12659,12660 ,726,726,726 ,0,0,0}, + {12660,12663,15451 ,726,7626,726 ,0,0,0}, {15444,12648,12651 ,726,7627,726 ,0,0,0}, + {12653,12654,15447 ,726,7625,726 ,0,0,0}, {15445,12647,12648 ,7626,7627,7627 ,0,0,0}, + {12643,12628,12627 ,7626,7625,726 ,0,0,0}, {12646,12627,15442 ,726,726,726 ,0,0,0}, + {12639,12630,12640 ,726,7627,7625 ,0,0,0}, {12630,12639,12637 ,7627,726,726 ,0,0,0}, + {12639,12640,12634 ,726,7625,7627 ,0,0,0}, {12640,12643,12642 ,7625,7626,7628 ,0,0,0}, + {12630,12628,12640 ,7627,7625,7625 ,0,0,0}, {12630,12637,12631 ,7627,726,726 ,0,0,0}, + {12646,12643,12627 ,726,7626,726 ,0,0,0}, {12643,12640,12628 ,7626,7625,7625 ,0,0,0}, + {12625,15442,12627 ,726,726,726 ,0,0,0}, {15445,15442,12647 ,7626,726,7627 ,0,0,0}, + {12625,12647,15442 ,726,7627,726 ,0,0,0}, {15444,12651,15443 ,726,726,726 ,0,0,0}, + {12648,15444,15445 ,7627,726,7626 ,0,0,0}, {12653,15447,15443 ,726,726,726 ,0,0,0}, + {15443,12651,12653 ,726,726,726 ,0,0,0}, {12654,12657,15448 ,7625,7625,726 ,0,0,0}, + {15447,12654,15448 ,726,7625,726 ,0,0,0}, {15446,12659,15461 ,726,726,726 ,0,0,0}, + {15446,12657,12659 ,726,7625,726 ,0,0,0}, {12663,15450,15451 ,7626,726,726 ,0,0,0}, + {15451,15461,12660 ,726,726,726 ,0,0,0}, {12663,12665,15449 ,7626,726,726 ,0,0,0}, + {12607,15462,13881 ,4303,7629,7630 ,0,0,0}, {13804,13838,15463 ,7631,7632,7633 ,0,0,0}, + {13970,13882,15464 ,7634,7635,7636 ,0,0,0}, {13866,15465,13867 ,7637,7638,7639 ,0,0,0}, + {15466,15467,13803 ,7640,7641,7642 ,0,0,0}, {15468,15469,13648 ,7643,7644,7645 ,0,0,0}, + {15468,13868,15470 ,7643,7646,7647 ,0,0,0}, {15471,15472,13646 ,7648,7649,7650 ,0,0,0}, + {13646,13645,15471 ,7650,7651,7648 ,0,0,0}, {13829,15472,15473 ,7652,7649,7653 ,0,0,0}, + {15472,13829,13646 ,7649,7652,7650 ,0,0,0}, {15474,13828,15473 ,7654,7655,7653 ,0,0,0}, + {13829,15473,13828 ,7652,7653,7655 ,0,0,0}, {15474,12621,12622 ,7654,126,7656 ,0,0,0}, + {12622,13828,15474 ,7656,7655,7654 ,0,0,0}, {15465,13866,15467 ,7638,7637,7641 ,0,0,0}, + {15469,13645,13648 ,7644,7651,7645 ,0,0,0}, {15471,13645,15469 ,7648,7651,7644 ,0,0,0}, + {15463,13838,15475 ,7633,7632,7657 ,0,0,0}, {15470,13868,13867 ,7647,7646,7639 ,0,0,0}, + {15468,13648,13868 ,7643,7645,7646 ,0,0,0}, {15465,15470,13867 ,7638,7647,7639 ,0,0,0}, + {13803,15467,13866 ,7642,7641,7637 ,0,0,0}, {13804,15463,15466 ,7631,7633,7640 ,0,0,0}, + {15466,13803,13804 ,7640,7642,7631 ,0,0,0}, {13882,15462,15464 ,7635,7629,7636 ,0,0,0}, + {15475,13970,15464 ,7657,7634,7636 ,0,0,0}, {13838,13970,15475 ,7632,7634,7657 ,0,0,0}, + {12607,13881,12608 ,4303,7630,82 ,0,0,0}, {15462,13882,13881 ,7629,7635,7630 ,0,0,0}, + {15469,15468,12604 ,726,7658,7659 ,0,0,0}, {15462,15467,15463 ,7660,7661,726 ,0,0,0}, + {15462,15465,15467 ,7660,7661,7661 ,0,0,0}, {12606,15470,12607 ,7659,726,726 ,0,0,0}, + {15466,15463,15467 ,7661,726,7661 ,0,0,0}, {15464,15462,15463 ,7659,7660,726 ,0,0,0}, + {15465,15462,12607 ,7661,7660,726 ,0,0,0}, {15475,15464,15463 ,726,7659,726 ,0,0,0}, + {15465,12607,15470 ,7661,726,726 ,0,0,0}, {12604,15468,12606 ,7659,7658,7659 ,0,0,0}, + {12606,15468,15470 ,7659,7658,726 ,0,0,0}, {12602,15471,15469 ,726,5488,726 ,0,0,0}, + {12604,12602,15469 ,7659,726,726 ,0,0,0}, {12600,15471,12602 ,726,5488,726 ,0,0,0}, + {12600,15472,15471 ,726,7662,5488 ,0,0,0}, {15473,15472,12597 ,5471,7662,7661 ,0,0,0}, + {12600,12597,15472 ,726,7661,7662 ,0,0,0}, {12596,15473,12597 ,726,5471,7661 ,0,0,0}, + {15474,12596,12594 ,7663,726,7661 ,0,0,0}, {12596,15474,15473 ,726,7663,5471 ,0,0,0}, + {12593,12621,12594 ,7658,726,7661 ,0,0,0}, {15474,12594,12621 ,7663,7661,726 ,0,0,0}, + {12613,12609,12610 ,7658,7664,726 ,0,0,0}, {12613,12619,12609 ,7658,7665,7664 ,0,0,0}, + {12616,12613,12615 ,7666,7658,7667 ,0,0,0}, {12616,12619,12613 ,7666,7665,7658 ,0,0,0}, + {12621,12593,12619 ,726,7658,7665 ,0,0,0}, {12609,12619,12593 ,7664,7665,7658 ,0,0,0}, + {15476,13147,15477 ,726,726,726 ,0,0,0}, {13147,15478,15477 ,726,726,726 ,0,0,0}, + {15479,15480,13147 ,726,726,726 ,0,0,0}, {13147,15476,15479 ,726,726,726 ,0,0,0}, + {15481,15482,13147 ,726,726,726 ,0,0,0}, {15481,13147,15480 ,726,726,726 ,0,0,0}, + {13139,15483,15484 ,7583,726,7661 ,0,0,0}, {13147,15485,15486 ,726,726,726 ,0,0,0}, + {13139,15487,15488 ,7583,7658,7661 ,0,0,0}, {15489,13139,15490 ,726,7583,726 ,0,0,0}, + {15491,15492,13139 ,726,726,7583 ,0,0,0}, {15493,15490,13139 ,726,726,7583 ,0,0,0}, + {13139,15489,15494 ,7583,726,5489 ,0,0,0}, {15491,13139,15495 ,726,7583,7583 ,0,0,0}, + {13139,15492,15493 ,7583,726,726 ,0,0,0}, {13139,15496,15487 ,7583,726,7658 ,0,0,0}, + {15488,15495,13139 ,7661,7583,7583 ,0,0,0}, {15486,15483,13139 ,726,726,7583 ,0,0,0}, + {15496,13139,15484 ,726,7583,7661 ,0,0,0}, {13147,15482,15485 ,726,726,726 ,0,0,0}, + {13147,15486,13139 ,726,726,7583 ,0,0,0}, {13140,15494,13135 ,726,5489,7668 ,0,0,0}, + {15494,13140,13139 ,5489,726,7583 ,0,0,0}, {15478,13147,15497 ,726,726,726 ,0,0,0}, + {15498,13147,13145 ,726,726,726 ,0,0,0}, {13147,15498,15497 ,726,726,726 ,0,0,0}, + {15498,13145,13151 ,726,726,726 ,0,0,0}, {13601,13864,15496 ,7669,7670,7671 ,0,0,0}, + {15484,13602,13601 ,7672,7673,7669 ,0,0,0}, {15484,15483,13602 ,7672,7673,7673 ,0,0,0}, + {15496,15484,13601 ,7671,7672,7669 ,0,0,0}, {13864,13863,15487 ,7670,7674,7675 ,0,0,0}, + {13606,13660,15495 ,7676,7677,7678 ,0,0,0}, {15488,15487,13863 ,7679,7675,7674 ,0,0,0}, + {13863,13606,15488 ,7674,7676,7679 ,0,0,0}, {15495,15488,13606 ,7678,7679,7676 ,0,0,0}, + {13864,15487,15496 ,7670,7675,7671 ,0,0,0}, {15495,13660,15491 ,7678,7677,7680 ,0,0,0}, + {13659,15492,15491 ,7681,7682,7680 ,0,0,0}, {15491,13660,13659 ,7680,7677,7681 ,0,0,0}, + {15492,13659,13658 ,7682,7681,7683 ,0,0,0}, {13652,15493,13658 ,7684,7685,7683 ,0,0,0}, + {13652,13654,15490 ,7684,7686,7687 ,0,0,0}, {13652,15490,15493 ,7684,7687,7685 ,0,0,0}, + {15489,13655,15494 ,7688,7689,7690 ,0,0,0}, {15490,13654,15489 ,7687,7686,7688 ,0,0,0}, + {15489,13654,13655 ,7688,7686,7689 ,0,0,0}, {13655,13656,15494 ,7689,7690,7690 ,0,0,0}, + {15492,13658,15493 ,7682,7683,7685 ,0,0,0}, {13649,15483,15486 ,7691,7673,7692 ,0,0,0}, + {15483,13649,13602 ,7673,7691,7673 ,0,0,0}, {15485,13650,15486 ,7693,7694,7692 ,0,0,0}, + {13649,15486,13650 ,7691,7692,7694 ,0,0,0}, {15485,15482,13681 ,7693,7695,7696 ,0,0,0}, + {13681,13650,15485 ,7696,7694,7693 ,0,0,0}, {13682,15482,15481 ,7697,7695,7698 ,0,0,0}, + {15482,13682,13681 ,7695,7697,7696 ,0,0,0}, {15480,13904,15481 ,7699,7700,7698 ,0,0,0}, + {13682,15481,13904 ,7697,7698,7700 ,0,0,0}, {15480,15479,13685 ,7699,7701,7702 ,0,0,0}, + {13685,13904,15480 ,7702,7700,7699 ,0,0,0}, {13684,15479,15476 ,7703,7701,7704 ,0,0,0}, + {15479,13684,13685 ,7701,7703,7702 ,0,0,0}, {15477,13707,15476 ,7705,7706,7704 ,0,0,0}, + {13684,15476,13707 ,7703,7704,7706 ,0,0,0}, {15477,15478,13710 ,7705,7707,7708 ,0,0,0}, + {13710,13707,15477 ,7708,7706,7705 ,0,0,0}, {13711,15478,15497 ,7709,7707,7710 ,0,0,0}, + {15478,13711,13710 ,7707,7709,7708 ,0,0,0}, {13711,15497,13712 ,7709,7710,7711 ,0,0,0}, + {13712,15497,15498 ,7711,7710,7711 ,0,0,0}, {14413,15498,13151 ,7712,7712,7712 ,0,0,0}, + {15498,14414,14417 ,7712,7712,7712 ,0,0,0}, {14413,14414,15498 ,7712,7712,7712 ,0,0,0}, + {15498,14423,14428 ,7712,7712,7712 ,0,0,0}, {14417,14423,15498 ,7712,7712,7712 ,0,0,0}, + {15498,14432,14396 ,7712,7712,7712 ,0,0,0}, {14428,14432,15498 ,7712,7712,7712 ,0,0,0}, + {15498,14400,14399 ,7712,7712,7712 ,0,0,0}, {14396,14400,15498 ,7712,7712,7712 ,0,0,0}, + {15498,14399,13712 ,7712,7712,7712 ,0,0,0}, {14465,15494,13656 ,7713,7713,7713 ,0,0,0}, + {14465,14515,15494 ,7713,7713,7713 ,0,0,0}, {15494,14515,14501 ,7713,7713,7713 ,0,0,0}, + {14461,14467,15494 ,7713,7713,7713 ,0,0,0}, {14461,15494,14501 ,7713,7713,7713 ,0,0,0}, + {14467,14497,15494 ,7713,7713,7713 ,0,0,0}, {15494,14453,14452 ,7713,7713,7713 ,0,0,0}, + {14497,14453,15494 ,7713,7713,7713 ,0,0,0}, {13135,15494,14457 ,7713,7713,7713 ,0,0,0}, + {14452,14457,15494 ,7713,7713,7713 ,0,0,0}, {12570,15499,13919 ,1435,7714,7715 ,0,0,0}, + {15500,13910,15501 ,7716,7717,7718 ,0,0,0}, {13929,13918,15502 ,7719,7720,7721 ,0,0,0}, + {13590,15503,13691 ,7722,7723,7724 ,0,0,0}, {15504,15505,13932 ,7725,7726,7727 ,0,0,0}, + {15506,13713,15507 ,7728,7729,7730 ,0,0,0}, {13715,13692,15508 ,7731,7732,7733 ,0,0,0}, + {13597,13696,15509 ,7734,7735,7736 ,0,0,0}, {13701,15510,13696 ,7737,7738,7735 ,0,0,0}, + {13697,15511,15512 ,7739,7740,7741 ,0,0,0}, {13597,15513,13699 ,7734,7742,7743 ,0,0,0}, + {15514,13706,15512 ,7744,7745,7741 ,0,0,0}, {13697,15512,13706 ,7739,7741,7745 ,0,0,0}, + {15514,15515,13704 ,7744,7746,7747 ,0,0,0}, {13704,13706,15514 ,7747,7745,7744 ,0,0,0}, + {13717,15515,15516 ,7748,7746,7749 ,0,0,0}, {15515,13717,13704 ,7746,7748,7747 ,0,0,0}, + {15517,13703,15516 ,7750,7751,7749 ,0,0,0}, {13717,15516,13703 ,7748,7749,7751 ,0,0,0}, + {15517,12589,12590 ,7750,1359,1359 ,0,0,0}, {12590,13703,15517 ,1359,7751,7750 ,0,0,0}, + {15509,13696,15510 ,7736,7735,7738 ,0,0,0}, {15511,13699,15513 ,7740,7743,7742 ,0,0,0}, + {13699,15511,13697 ,7743,7740,7739 ,0,0,0}, {15509,15513,13597 ,7736,7742,7734 ,0,0,0}, + {15506,15510,13701 ,7728,7738,7737 ,0,0,0}, {13715,15508,15507 ,7731,7733,7730 ,0,0,0}, + {13715,15507,13713 ,7731,7730,7729 ,0,0,0}, {13701,13713,15506 ,7737,7729,7728 ,0,0,0}, + {13692,15518,15508 ,7732,7752,7733 ,0,0,0}, {15518,13692,13691 ,7752,7732,7724 ,0,0,0}, + {15505,15503,13590 ,7726,7723,7722 ,0,0,0}, {15503,15518,13691 ,7723,7752,7724 ,0,0,0}, + {13932,15505,13590 ,7727,7726,7722 ,0,0,0}, {13920,15500,15504 ,7753,7716,7725 ,0,0,0}, + {13920,15504,13932 ,7753,7725,7727 ,0,0,0}, {13910,13929,15501 ,7717,7719,7718 ,0,0,0}, + {13920,13910,15500 ,7753,7717,7716 ,0,0,0}, {13918,15499,15502 ,7720,7714,7721 ,0,0,0}, + {15501,13929,15502 ,7718,7719,7721 ,0,0,0}, {12570,13919,12568 ,1435,7715,1435 ,0,0,0}, + {15499,13918,13919 ,7714,7720,7715 ,0,0,0}, {15517,15516,15515 ,726,7628,7628 ,0,0,0}, + {12572,15512,12571 ,7627,7628,726 ,0,0,0}, {12551,12549,15513 ,7754,7625,7626 ,0,0,0}, + {15512,15511,12571 ,7628,726,726 ,0,0,0}, {12554,15506,12555 ,7755,726,7756 ,0,0,0}, + {12551,15513,15509 ,7754,7626,7626 ,0,0,0}, {15508,15518,12563 ,726,7628,7757 ,0,0,0}, + {15508,12561,15507 ,726,7758,7626 ,0,0,0}, {12564,12558,15503 ,7759,7760,7628 ,0,0,0}, + {15500,15501,15502 ,7625,7754,726 ,0,0,0}, {12567,12564,15505 ,7628,7759,7627 ,0,0,0}, + {12570,12567,15499 ,7628,7628,7761 ,0,0,0}, {15499,15500,15502 ,7761,7625,726 ,0,0,0}, + {12567,15504,15500 ,7628,7628,7625 ,0,0,0}, {15499,12567,15500 ,7761,7628,7625 ,0,0,0}, + {12567,12566,12564 ,7628,7762,7759 ,0,0,0}, {12567,15505,15504 ,7628,7627,7628 ,0,0,0}, + {12563,15503,12558 ,7757,7628,7760 ,0,0,0}, {15503,15505,12564 ,7628,7627,7759 ,0,0,0}, + {12563,15518,15503 ,7757,7628,7628 ,0,0,0}, {15507,12561,12555 ,7626,7758,7756 ,0,0,0}, + {12563,12561,15508 ,7757,7758,726 ,0,0,0}, {15510,15506,12554 ,7628,726,7755 ,0,0,0}, + {15506,15507,12555 ,726,7626,7756 ,0,0,0}, {15510,12552,15509 ,7628,7628,7626 ,0,0,0}, + {12552,15510,12554 ,7628,7628,7755 ,0,0,0}, {15511,15513,12549 ,726,7626,7625 ,0,0,0}, + {12552,12551,15509 ,7628,7754,7626 ,0,0,0}, {12575,15512,12572 ,7625,7628,7627 ,0,0,0}, + {12549,12571,15511 ,7625,726,726 ,0,0,0}, {15515,15514,12575 ,7628,7628,7625 ,0,0,0}, + {12575,15514,15512 ,7625,7628,7628 ,0,0,0}, {12577,15517,15515 ,7628,726,7628 ,0,0,0}, + {15515,12575,12577 ,7628,7625,7628 ,0,0,0}, {12577,12578,15517 ,7628,7628,726 ,0,0,0}, + {12581,12584,12587 ,7628,7628,7628 ,0,0,0}, {12578,12581,15517 ,7628,7628,726 ,0,0,0}, + {12587,15517,12581 ,7628,726,7628 ,0,0,0}, {12581,12583,12584 ,7628,726,7628 ,0,0,0}, + {15517,12587,12589 ,726,7628,7628 ,0,0,0}, {12531,15519,13880 ,1435,7763,7764 ,0,0,0}, + {13907,13909,15520 ,7765,7766,7767 ,0,0,0}, {13913,13914,15521 ,7768,7769,7770 ,0,0,0}, + {13879,15522,13878 ,7771,7772,7773 ,0,0,0}, {15523,15524,13908 ,7774,4221,7775 ,0,0,0}, + {15525,15526,13906 ,7776,7777,7778 ,0,0,0}, {15525,13905,15527 ,7776,7779,7780 ,0,0,0}, + {15528,15529,13722 ,7781,7782,7783 ,0,0,0}, {13722,13721,15528 ,7783,7784,7781 ,0,0,0}, + {13596,15529,15530 ,7785,7782,7786 ,0,0,0}, {15529,13596,13722 ,7782,7785,7783 ,0,0,0}, + {15531,13595,15530 ,7787,7788,7786 ,0,0,0}, {13596,15530,13595 ,7785,7786,7788 ,0,0,0}, + {15531,12545,12546 ,7787,1359,1359 ,0,0,0}, {12546,13595,15531 ,1359,7788,7787 ,0,0,0}, + {15522,13879,15524 ,7772,7771,4221 ,0,0,0}, {15526,13721,13906 ,7777,7784,7778 ,0,0,0}, + {15528,13721,15526 ,7781,7784,7777 ,0,0,0}, {15520,13909,15532 ,7767,7766,4227 ,0,0,0}, + {15527,13905,13878 ,7780,7779,7773 ,0,0,0}, {15525,13906,13905 ,7776,7778,7779 ,0,0,0}, + {15522,15527,13878 ,7772,7780,7773 ,0,0,0}, {13908,15524,13879 ,7775,4221,7771 ,0,0,0}, + {13907,15520,15523 ,7765,7767,7774 ,0,0,0}, {15523,13908,13907 ,7774,7775,7765 ,0,0,0}, + {13914,15519,15521 ,7769,7763,7770 ,0,0,0}, {15532,13913,15521 ,4227,7768,7770 ,0,0,0}, + {13909,13913,15532 ,7766,7768,4227 ,0,0,0}, {12531,13880,12532 ,1435,7764,1435 ,0,0,0}, + {15519,13914,13880 ,7763,7769,7764 ,0,0,0}, {12530,12539,12531 ,726,5471,7661 ,0,0,0}, + {15522,15525,15527 ,726,726,726 ,0,0,0}, {15528,15526,15525 ,7658,726,726 ,0,0,0}, + {15525,15522,15528 ,726,726,7658 ,0,0,0}, {15528,15524,15529 ,7658,726,7658 ,0,0,0}, + {15524,15528,15522 ,726,7658,726 ,0,0,0}, {15530,15529,15523 ,7658,7658,726 ,0,0,0}, + {15524,15523,15529 ,726,726,7658 ,0,0,0}, {15520,15531,15530 ,7658,7661,7658 ,0,0,0}, + {15530,15523,15520 ,7658,726,7658 ,0,0,0}, {15531,15532,12545 ,7661,7661,7664 ,0,0,0}, + {15532,15531,15520 ,7661,7661,7658 ,0,0,0}, {15532,15521,12545 ,7661,726,7664 ,0,0,0}, + {15521,15519,12543 ,726,726,7662 ,0,0,0}, {12537,12530,12528 ,7789,726,7658 ,0,0,0}, + {12518,12517,12524 ,5488,7668,7661 ,0,0,0}, {12534,12526,12533 ,7790,7664,7791 ,0,0,0}, + {12518,12524,12520 ,5488,7661,7792 ,0,0,0}, {12521,12520,12524 ,5488,7792,7661 ,0,0,0}, + {12526,12524,12533 ,7664,7661,7791 ,0,0,0}, {12533,12524,12517 ,7791,7661,7668 ,0,0,0}, + {12526,12534,12528 ,7664,7790,7658 ,0,0,0}, {12539,12530,12537 ,5471,726,7789 ,0,0,0}, + {12537,12528,12534 ,7789,7658,7790 ,0,0,0}, {12531,12540,15519 ,7661,7583,726 ,0,0,0}, + {12531,12539,12540 ,7661,5471,7583 ,0,0,0}, {15521,12543,12545 ,726,7662,7664 ,0,0,0}, + {12540,12543,15519 ,7583,7662,726 ,0,0,0}, {15533,13176,15534 ,7583,726,726 ,0,0,0}, + {15535,13172,15536 ,7668,726,5470 ,0,0,0}, {15535,15537,13172 ,7668,726,726 ,0,0,0}, + {13172,15538,15536 ,726,726,5470 ,0,0,0}, {15537,15539,13172 ,726,5489,726 ,0,0,0}, + {13172,15540,15541 ,726,7793,7794 ,0,0,0}, {15539,15540,13172 ,5489,7793,726 ,0,0,0}, + {13176,15542,13172 ,726,5470,726 ,0,0,0}, {15542,15538,13172 ,5470,726,726 ,0,0,0}, + {15543,15542,13176 ,726,5470,726 ,0,0,0}, {15544,13172,15541 ,7795,726,7794 ,0,0,0}, + {13176,15545,15543 ,726,5488,726 ,0,0,0}, {15544,15546,13172 ,7795,726,726 ,0,0,0}, + {15547,13172,15548 ,5485,726,7796 ,0,0,0}, {13172,15546,15548 ,726,726,7796 ,0,0,0}, + {13176,15549,15545 ,726,7583,5488 ,0,0,0}, {15550,13172,15547 ,7583,726,5485 ,0,0,0}, + {13176,15551,15549 ,726,726,7583 ,0,0,0}, {13176,15552,15553 ,726,5488,7583 ,0,0,0}, + {13176,15553,15551 ,726,7583,726 ,0,0,0}, {13173,15550,13168 ,5489,7583,7797 ,0,0,0}, + {13176,15533,15552 ,726,7583,5488 ,0,0,0}, {15550,13173,13172 ,7583,5489,726 ,0,0,0}, + {15534,13176,15554 ,726,726,7583 ,0,0,0}, {15555,13176,13183 ,726,726,726 ,0,0,0}, + {13176,15555,15554 ,726,726,7583 ,0,0,0}, {15555,13183,13182 ,726,726,726 ,0,0,0}, + {13591,13693,15535 ,7798,7799,7800 ,0,0,0}, {15536,13589,13591 ,7801,7802,7798 ,0,0,0}, + {15536,15538,13589 ,7801,7802,7802 ,0,0,0}, {15535,15536,13591 ,7800,7801,7798 ,0,0,0}, + {13693,13902,15537 ,7799,7803,7804 ,0,0,0}, {13714,13700,15540 ,7805,7806,7807 ,0,0,0}, + {15539,15537,13902 ,7808,7804,7803 ,0,0,0}, {13902,13714,15539 ,7803,7805,7808 ,0,0,0}, + {15540,15539,13714 ,7807,7808,7805 ,0,0,0}, {13693,15537,15535 ,7799,7804,7800 ,0,0,0}, + {15540,13700,15541 ,7807,7806,7809 ,0,0,0}, {13695,15544,15541 ,7810,7811,7809 ,0,0,0}, + {15541,13700,13695 ,7809,7806,7810 ,0,0,0}, {15544,13695,13694 ,7811,7810,7812 ,0,0,0}, + {13599,15546,13694 ,7813,7814,7812 ,0,0,0}, {13599,13678,15548 ,7813,7815,7816 ,0,0,0}, + {13599,15548,15546 ,7813,7816,7814 ,0,0,0}, {15547,13680,15550 ,7817,7818,7819 ,0,0,0}, + {15548,13678,15547 ,7816,7815,7817 ,0,0,0}, {15547,13678,13680 ,7817,7815,7818 ,0,0,0}, + {13680,13709,15550 ,7818,7819,7819 ,0,0,0}, {15544,13694,15546 ,7811,7812,7814 ,0,0,0}, + {13723,15538,15542 ,7820,7802,7821 ,0,0,0}, {15538,13723,13589 ,7802,7820,7802 ,0,0,0}, + {15543,13727,15542 ,7822,7823,7821 ,0,0,0}, {13723,15542,13727 ,7820,7821,7823 ,0,0,0}, + {15543,15545,13688 ,7822,7824,7825 ,0,0,0}, {13688,13727,15543 ,7825,7823,7822 ,0,0,0}, + {13689,15545,15549 ,7826,7824,7827 ,0,0,0}, {15545,13689,13688 ,7824,7826,7825 ,0,0,0}, + {15551,13764,15549 ,7828,7829,7827 ,0,0,0}, {13689,15549,13764 ,7826,7827,7829 ,0,0,0}, + {15551,15553,13592 ,7828,7830,7831 ,0,0,0}, {13592,13764,15551 ,7831,7829,7828 ,0,0,0}, + {13593,15553,15552 ,7832,7830,7833 ,0,0,0}, {15553,13593,13592 ,7830,7832,7831 ,0,0,0}, + {15533,13751,15552 ,7834,7835,7833 ,0,0,0}, {13593,15552,13751 ,7832,7833,7835 ,0,0,0}, + {15533,15534,13754 ,7834,7836,7837 ,0,0,0}, {13754,13751,15533 ,7837,7835,7834 ,0,0,0}, + {13758,15534,15554 ,7838,7836,7839 ,0,0,0}, {15534,13758,13754 ,7836,7838,7837 ,0,0,0}, + {13758,15554,13759 ,7838,7839,7840 ,0,0,0}, {13759,15554,15555 ,7840,7839,7840 ,0,0,0}, + {14326,15555,13182 ,7841,7841,7841 ,0,0,0}, {15555,14332,14335 ,7841,7841,7841 ,0,0,0}, + {14326,14332,15555 ,7841,7841,7841 ,0,0,0}, {15555,14341,14346 ,7841,7841,7841 ,0,0,0}, + {14335,14341,15555 ,7841,7841,7841 ,0,0,0}, {15555,14350,14309 ,7841,7841,7841 ,0,0,0}, + {14346,14350,15555 ,7841,7841,7841 ,0,0,0}, {15555,14321,14320 ,7841,7841,7841 ,0,0,0}, + {14309,14321,15555 ,7841,7841,7841 ,0,0,0}, {15555,14320,13759 ,7841,7841,7841 ,0,0,0}, + {14387,15550,13709 ,7842,7842,7842 ,0,0,0}, {14387,14433,15550 ,7842,7842,7842 ,0,0,0}, + {15550,14433,14419 ,7842,7842,7842 ,0,0,0}, {14381,14374,15550 ,7842,7842,7842 ,0,0,0}, + {14381,15550,14419 ,7842,7842,7842 ,0,0,0}, {14374,14415,15550 ,7842,7842,7842 ,0,0,0}, + {15550,14407,14369 ,7842,7842,7842 ,0,0,0}, {14415,14407,15550 ,7842,7842,7842 ,0,0,0}, + {13168,15550,14370 ,7842,7842,7842 ,0,0,0}, {14369,14370,15550 ,7842,7842,7842 ,0,0,0}, + {12494,15556,13944 ,1790,7843,4204 ,0,0,0}, {15557,13941,15558 ,7844,4198,4199 ,0,0,0}, + {13930,13943,15559 ,7845,7846,7847 ,0,0,0}, {13921,15560,13739 ,7848,7849,7850 ,0,0,0}, + {15561,15562,13954 ,7851,7852,7853 ,0,0,0}, {15563,13718,15564 ,7854,7855,7856 ,0,0,0}, + {13720,13737,15565 ,7857,7858,7859 ,0,0,0}, {13586,13585,15566 ,7860,7861,7862 ,0,0,0}, + {13741,15567,13585 ,7863,7864,7861 ,0,0,0}, {13745,15568,15569 ,7865,7866,7867 ,0,0,0}, + {13586,15570,13744 ,7860,7868,7869 ,0,0,0}, {15571,13750,15569 ,7870,7871,7867 ,0,0,0}, + {13745,15569,13750 ,7865,7867,7871 ,0,0,0}, {15571,15572,13748 ,7870,7872,7873 ,0,0,0}, + {13748,13750,15571 ,7873,7871,7870 ,0,0,0}, {13733,15572,15573 ,7874,7872,7875 ,0,0,0}, + {15572,13733,13748 ,7872,7874,7873 ,0,0,0}, {15574,13731,15573 ,7876,7877,7875 ,0,0,0}, + {13733,15573,13731 ,7874,7875,7877 ,0,0,0}, {15574,12513,12514 ,7876,1711,1711 ,0,0,0}, + {12514,13731,15574 ,1711,7877,7876 ,0,0,0}, {15566,13585,15567 ,7862,7861,7864 ,0,0,0}, + {15568,13744,15570 ,7866,7869,7868 ,0,0,0}, {13744,15568,13745 ,7869,7866,7865 ,0,0,0}, + {15566,15570,13586 ,7862,7868,7860 ,0,0,0}, {15563,15567,13741 ,7854,7864,7863 ,0,0,0}, + {13720,15565,15564 ,7857,7859,7856 ,0,0,0}, {13720,15564,13718 ,7857,7856,7855 ,0,0,0}, + {13741,13718,15563 ,7863,7855,7854 ,0,0,0}, {13737,15575,15565 ,7858,7878,7859 ,0,0,0}, + {15575,13737,13739 ,7878,7858,7850 ,0,0,0}, {15562,15560,13921 ,7852,7849,7848 ,0,0,0}, + {15560,15575,13739 ,7849,7878,7850 ,0,0,0}, {13954,15562,13921 ,7853,7852,7848 ,0,0,0}, + {13942,15557,15561 ,7879,7844,7851 ,0,0,0}, {13942,15561,13954 ,7879,7851,7853 ,0,0,0}, + {13941,13930,15558 ,4198,7845,4199 ,0,0,0}, {13942,13941,15557 ,7879,4198,7844 ,0,0,0}, + {13943,15556,15559 ,7846,7843,7847 ,0,0,0}, {15558,13930,15559 ,4199,7845,7847 ,0,0,0}, + {12494,13944,12492 ,1790,4204,1790 ,0,0,0}, {15556,13943,13944 ,7843,7846,4204 ,0,0,0}, + {15566,15567,15561 ,726,7880,7881 ,0,0,0}, {15556,15571,15569 ,7882,7627,7625 ,0,0,0}, + {15562,15563,15560 ,7883,7758,726 ,0,0,0}, {15575,15560,15563 ,7884,726,7758 ,0,0,0}, + {15564,15565,15575 ,7880,7761,7884 ,0,0,0}, {15563,15562,15567 ,7758,7883,7880 ,0,0,0}, + {15564,15575,15563 ,7880,7884,7758 ,0,0,0}, {15566,15561,15557 ,726,7881,7885 ,0,0,0}, + {15567,15562,15561 ,7880,7883,7881 ,0,0,0}, {15557,15558,15570 ,7885,7886,7758 ,0,0,0}, + {15570,15566,15557 ,7758,726,7885 ,0,0,0}, {15568,15558,15559 ,726,7886,7887 ,0,0,0}, + {15558,15568,15570 ,7886,726,7758 ,0,0,0}, {15569,15568,15559 ,7625,726,7887 ,0,0,0}, + {12494,15571,15556 ,7758,7627,7882 ,0,0,0}, {15556,15569,15559 ,7882,7625,7887 ,0,0,0}, + {15572,12494,12491 ,7627,7758,7755 ,0,0,0}, {12494,15572,15571 ,7758,7627,7627 ,0,0,0}, + {12490,15573,12491 ,7625,726,7755 ,0,0,0}, {15572,12491,15573 ,7627,7755,726 ,0,0,0}, + {12490,12488,15574 ,7625,7761,726 ,0,0,0}, {15574,15573,12490 ,726,726,7625 ,0,0,0}, + {12513,12488,12482 ,7627,7761,7625 ,0,0,0}, {12488,12513,15574 ,7761,7627,726 ,0,0,0}, + {12479,12507,12485 ,726,7627,7625 ,0,0,0}, {12487,12511,12482 ,7880,726,7625 ,0,0,0}, + {12505,12478,12502 ,7625,726,726 ,0,0,0}, {12499,12475,12496 ,7627,7625,7625 ,0,0,0}, + {12501,12502,12476 ,726,726,7625 ,0,0,0}, {12496,12473,12495 ,7625,7625,726 ,0,0,0}, + {12475,12499,12501 ,7625,7627,726 ,0,0,0}, {12476,12475,12501 ,7625,7625,726 ,0,0,0}, + {12496,12475,12473 ,7625,7625,7625 ,0,0,0}, {12479,12478,12505 ,726,726,7625 ,0,0,0}, + {12476,12502,12478 ,7625,726,726 ,0,0,0}, {12508,12485,12507 ,726,7625,7627 ,0,0,0}, + {12507,12479,12505 ,7627,726,7625 ,0,0,0}, {12487,12508,12511 ,7880,726,726 ,0,0,0}, + {12508,12487,12485 ,726,7880,7625 ,0,0,0}, {12511,12513,12482 ,726,7627,7625 ,0,0,0}, + {12455,15576,13874 ,1790,7888,7889 ,0,0,0}, {13926,13915,15577 ,7890,7891,7892 ,0,0,0}, + {13928,13875,15578 ,7893,7894,7895 ,0,0,0}, {13916,15579,13917 ,7896,7897,4137 ,0,0,0}, + {15580,15581,13927 ,7898,7899,7900 ,0,0,0}, {15582,15583,13925 ,7901,7902,7903 ,0,0,0}, + {15582,13924,15584 ,7901,7904,7905 ,0,0,0}, {15585,15586,13760 ,7906,7907,7908 ,0,0,0}, + {13760,13761,15585 ,7908,7909,7906 ,0,0,0}, {13923,15586,15587 ,7910,7907,7911 ,0,0,0}, + {15586,13923,13760 ,7907,7910,7908 ,0,0,0}, {15588,13734,15587 ,7912,7913,7911 ,0,0,0}, + {13923,15587,13734 ,7910,7911,7913 ,0,0,0}, {15588,12469,12470 ,7912,1711,1711 ,0,0,0}, + {12470,13734,15588 ,1711,7913,7912 ,0,0,0}, {15579,13916,15581 ,7897,7896,7899 ,0,0,0}, + {15583,13761,13925 ,7902,7909,7903 ,0,0,0}, {15585,13761,15583 ,7906,7909,7902 ,0,0,0}, + {15577,13915,15589 ,7892,7891,7914 ,0,0,0}, {15584,13924,13917 ,7905,7904,4137 ,0,0,0}, + {15582,13925,13924 ,7901,7903,7904 ,0,0,0}, {15579,15584,13917 ,7897,7905,4137 ,0,0,0}, + {13927,15581,13916 ,7900,7899,7896 ,0,0,0}, {13926,15577,15580 ,7890,7892,7898 ,0,0,0}, + {15580,13927,13926 ,7898,7900,7890 ,0,0,0}, {13875,15576,15578 ,7894,7888,7895 ,0,0,0}, + {15589,13928,15578 ,7914,7893,7895 ,0,0,0}, {13915,13928,15589 ,7891,7893,7914 ,0,0,0}, + {12455,13874,12456 ,1790,7889,1790 ,0,0,0}, {15576,13875,13874 ,7888,7894,7889 ,0,0,0}, + {15582,12463,15583 ,726,7658,726 ,0,0,0}, {15587,15586,12467 ,726,726,7660 ,0,0,0}, + {12469,15588,15587 ,726,7660,726 ,0,0,0}, {15582,15584,12461 ,726,726,7658 ,0,0,0}, + {12464,12467,15585 ,7660,7660,7659 ,0,0,0}, {15581,15580,12441 ,7659,726,7661 ,0,0,0}, + {15581,12457,15579 ,7659,726,726 ,0,0,0}, {12444,12442,15577 ,7915,7916,726 ,0,0,0}, + {15576,12450,12448 ,7658,7917,5475 ,0,0,0}, {15578,12445,15589 ,7658,726,7659 ,0,0,0}, + {12455,12454,12450 ,7918,7918,7917 ,0,0,0}, {12452,12450,12454 ,7661,7917,7918 ,0,0,0}, + {15578,15576,12448 ,7658,7658,5475 ,0,0,0}, {15576,12455,12450 ,7658,7918,7917 ,0,0,0}, + {12445,15578,12448 ,726,7658,5475 ,0,0,0}, {15589,12445,12444 ,7659,726,7915 ,0,0,0}, + {15577,12442,15580 ,726,7916,726 ,0,0,0}, {15589,12444,15577 ,7659,7915,726 ,0,0,0}, + {15581,12441,12457 ,7659,7661,726 ,0,0,0}, {15580,12442,12441 ,726,7916,7661 ,0,0,0}, + {12458,15584,15579 ,7664,726,726 ,0,0,0}, {12457,12458,15579 ,726,7664,726 ,0,0,0}, + {12463,15582,12461 ,7658,726,7658 ,0,0,0}, {12461,15584,12458 ,7658,726,7664 ,0,0,0}, + {15583,12464,15585 ,726,7660,7659 ,0,0,0}, {15583,12463,12464 ,726,7658,7660 ,0,0,0}, + {15587,12467,12469 ,726,7660,726 ,0,0,0}, {15586,15585,12467 ,726,7659,7660 ,0,0,0}, + {13213,15590,15591 ,726,5469,7919 ,0,0,0}, {15592,13213,15593 ,7920,726,7921 ,0,0,0}, + {13213,15592,15590 ,726,7920,5469 ,0,0,0}, {13213,15594,15593 ,726,726,7921 ,0,0,0}, + {15595,13213,15591 ,7922,726,7919 ,0,0,0}, {15594,13213,15596 ,726,726,7920 ,0,0,0}, + {15595,15597,13213 ,7922,7923,726 ,0,0,0}, {13213,15598,15599 ,726,7924,7925 ,0,0,0}, + {15599,15600,13213 ,7925,7926,726 ,0,0,0}, {15597,15598,13213 ,7923,7924,726 ,0,0,0}, + {15601,15602,13213 ,5472,7927,726 ,0,0,0}, {15601,13213,15600 ,5472,726,7926 ,0,0,0}, + {15603,15604,13213 ,7928,7929,726 ,0,0,0}, {15603,13213,15602 ,7928,726,7927 ,0,0,0}, + {15605,15606,13213 ,726,5489,726 ,0,0,0}, {15605,13213,15604 ,726,726,7929 ,0,0,0}, + {13213,15607,13212 ,726,5488,7583 ,0,0,0}, {15607,13213,15606 ,5488,726,5489 ,0,0,0}, + {13212,15608,15609 ,7583,5470,5489 ,0,0,0}, {15607,15608,13212 ,5488,5470,7583 ,0,0,0}, + {13208,13209,15609 ,5489,5488,5489 ,0,0,0}, {13212,15609,13209 ,7583,5489,5488 ,0,0,0}, + {13203,13208,15609 ,5489,5489,5489 ,0,0,0}, {13213,15180,15596 ,726,5489,7920 ,0,0,0}, + {15180,15610,15611 ,5489,5470,5488 ,0,0,0}, {15596,15180,15611 ,7920,5489,5488 ,0,0,0}, + {15612,15180,15179 ,5489,5489,726 ,0,0,0}, {15180,15612,15610 ,5489,5489,5470 ,0,0,0}, + {14243,15612,15178 ,5489,5489,7583 ,0,0,0}, {15179,15178,15612 ,726,7583,5489 ,0,0,0}, + {13777,13738,15600 ,7930,7931,7932 ,0,0,0}, {15599,13779,13777 ,7933,7934,7930 ,0,0,0}, + {15599,15598,13779 ,7933,7935,7934 ,0,0,0}, {15600,15599,13777 ,7932,7933,7930 ,0,0,0}, + {13738,13922,15601 ,7931,7936,7937 ,0,0,0}, {13719,13740,15603 ,7938,7939,7940 ,0,0,0}, + {15602,15601,13922 ,7941,7937,7936 ,0,0,0}, {13922,13719,15602 ,7936,7938,7941 ,0,0,0}, + {15603,15602,13719 ,7940,7941,7938 ,0,0,0}, {13738,15601,15600 ,7931,7937,7932 ,0,0,0}, + {15603,13740,15604 ,7940,7939,7942 ,0,0,0}, {13742,15605,15604 ,7943,7944,7942 ,0,0,0}, + {15604,13740,13742 ,7942,7939,7943 ,0,0,0}, {15605,13742,13587 ,7944,7943,7945 ,0,0,0}, + {13730,15606,13587 ,7946,7947,7945 ,0,0,0}, {13730,13743,15607 ,7946,7948,7949 ,0,0,0}, + {13730,15607,15606 ,7946,7949,7947 ,0,0,0}, {15608,13735,15609 ,7950,7951,7952 ,0,0,0}, + {15607,13743,15608 ,7949,7948,7950 ,0,0,0}, {15608,13743,13735 ,7950,7948,7951 ,0,0,0}, + {13735,13736,15609 ,7951,7952,7952 ,0,0,0}, {15605,13587,15606 ,7944,7945,7947 ,0,0,0}, + {13899,15598,15597 ,7953,7935,7954 ,0,0,0}, {15598,13899,13779 ,7935,7953,7934 ,0,0,0}, + {15595,13778,15597 ,7955,7956,7954 ,0,0,0}, {13899,15597,13778 ,7953,7954,7956 ,0,0,0}, + {15595,15591,13762 ,7955,7957,7958 ,0,0,0}, {13762,13778,15595 ,7958,7956,7955 ,0,0,0}, + {13763,15591,15590 ,7959,7957,7960 ,0,0,0}, {15591,13763,13762 ,7957,7959,7958 ,0,0,0}, + {15592,13936,15590 ,7961,7962,7960 ,0,0,0}, {13763,15590,13936 ,7959,7960,7962 ,0,0,0}, + {15592,15593,13876 ,7961,7963,7964 ,0,0,0}, {13876,13936,15592 ,7964,7962,7961 ,0,0,0}, + {13877,15593,15594 ,7965,7963,7966 ,0,0,0}, {15593,13877,13876 ,7963,7965,7964 ,0,0,0}, + {15596,13770,15594 ,7967,7968,7966 ,0,0,0}, {13877,15594,13770 ,7965,7966,7968 ,0,0,0}, + {15596,15611,13798 ,7967,7969,7970 ,0,0,0}, {13798,13770,15596 ,7970,7968,7967 ,0,0,0}, + {13799,15611,15610 ,7971,7969,7972 ,0,0,0}, {15611,13799,13798 ,7969,7971,7970 ,0,0,0}, + {13799,15610,13801 ,7971,7972,7973 ,0,0,0}, {13801,15610,15612 ,7973,7972,7973 ,0,0,0}, + {14253,14259,15612 ,7974,7974,7974 ,0,0,0}, {15612,14243,14244 ,7974,7974,7974 ,0,0,0}, + {14244,14250,15612 ,7974,7974,7974 ,0,0,0}, {14264,15612,14259 ,7974,7974,7974 ,0,0,0}, + {14250,14253,15612 ,7974,7974,7974 ,0,0,0}, {14268,14221,15612 ,7974,7974,7974 ,0,0,0}, + {14268,15612,14264 ,7974,7974,7974 ,0,0,0}, {14221,14233,15612 ,7974,7974,7974 ,0,0,0}, + {13801,15612,14232 ,7974,7974,7974 ,0,0,0}, {14233,14232,15612 ,7974,7974,7974 ,0,0,0}, + {15609,13736,14301 ,7975,7975,7975 ,0,0,0}, {14301,14351,15609 ,7975,7975,7975 ,0,0,0}, + {15609,14337,14297 ,7975,7975,7975 ,0,0,0}, {14351,14337,15609 ,7975,7975,7975 ,0,0,0}, + {15609,14303,14333 ,7975,7975,7975 ,0,0,0}, {14297,14303,15609 ,7975,7975,7975 ,0,0,0}, + {15609,14289,14288 ,7975,7975,7975 ,0,0,0}, {14333,14289,15609 ,7975,7975,7975 ,0,0,0}, + {13203,15609,14293 ,7975,7975,7975 ,0,0,0}, {14288,14293,15609 ,7975,7975,7975 ,0,0,0}, + {12418,15613,13949 ,126,7976,7977 ,0,0,0}, {15614,13951,15615 ,7978,7979,7980 ,0,0,0}, + {13965,13952,15616 ,7981,7982,7983 ,0,0,0}, {13766,15617,13757 ,7984,7985,7986 ,0,0,0}, + {15618,15619,13933 ,7987,7988,7989 ,0,0,0}, {15620,13784,15621 ,7990,7991,7992 ,0,0,0}, + {13802,13769,15622 ,7993,7994,7995 ,0,0,0}, {13794,13795,15623 ,7996,7997,7998 ,0,0,0}, + {13785,15624,13795 ,7999,8000,7997 ,0,0,0}, {13786,15625,15626 ,8001,8002,8003 ,0,0,0}, + {13794,15627,13788 ,7996,8004,8005 ,0,0,0}, {15628,13789,15626 ,8006,8007,8003 ,0,0,0}, + {13786,15626,13789 ,8001,8003,8007 ,0,0,0}, {15628,15629,13792 ,8006,8008,8009 ,0,0,0}, + {13792,13789,15628 ,8009,8007,8006 ,0,0,0}, {13831,15629,15630 ,8010,8008,8011 ,0,0,0}, + {15629,13831,13792 ,8008,8010,8009 ,0,0,0}, {15631,13793,15630 ,8012,8013,8011 ,0,0,0}, + {13831,15630,13793 ,8010,8011,8013 ,0,0,0}, {15631,12437,12438 ,8012,8014,4346 ,0,0,0}, + {12438,13793,15631 ,4346,8013,8012 ,0,0,0}, {15623,13795,15624 ,7998,7997,8000 ,0,0,0}, + {15625,13788,15627 ,8002,8005,8004 ,0,0,0}, {13788,15625,13786 ,8005,8002,8001 ,0,0,0}, + {15623,15627,13794 ,7998,8004,7996 ,0,0,0}, {15620,15624,13785 ,7990,8000,7999 ,0,0,0}, + {13802,15622,15621 ,7993,7995,7992 ,0,0,0}, {13802,15621,13784 ,7993,7992,7991 ,0,0,0}, + {13785,13784,15620 ,7999,7991,7990 ,0,0,0}, {13769,15632,15622 ,7994,8015,7995 ,0,0,0}, + {15632,13769,13757 ,8015,7994,7986 ,0,0,0}, {15619,15617,13766 ,7988,7985,7984 ,0,0,0}, + {15617,15632,13757 ,7985,8015,7986 ,0,0,0}, {13933,15619,13766 ,7989,7988,7984 ,0,0,0}, + {13950,15614,15618 ,8016,7978,7987 ,0,0,0}, {13950,15618,13933 ,8016,7987,7989 ,0,0,0}, + {13951,13965,15615 ,7979,7981,7980 ,0,0,0}, {13950,13951,15614 ,8016,7979,7978 ,0,0,0}, + {13952,15613,15616 ,7982,7976,7983 ,0,0,0}, {15615,13965,15616 ,7980,7981,7983 ,0,0,0}, + {12418,13949,12416 ,126,7977,4289 ,0,0,0}, {15613,13952,13949 ,7976,7982,7977 ,0,0,0}, + {15631,15630,15629 ,7625,7880,7758 ,0,0,0}, {12423,15614,15615 ,7626,7880,726 ,0,0,0}, + {15629,15626,15623 ,7758,8017,8018 ,0,0,0}, {15629,15628,15626 ,7758,7758,8017 ,0,0,0}, + {15625,15623,15626 ,8017,8018,8017 ,0,0,0}, {15625,15627,15623 ,8017,7758,8018 ,0,0,0}, + {15624,15629,15623 ,8019,7758,8018 ,0,0,0}, {15624,15620,15631 ,8019,7884,7625 ,0,0,0}, + {15631,15629,15624 ,7625,7758,8019 ,0,0,0}, {15620,15621,12435 ,7884,8020,7625 ,0,0,0}, + {15620,12437,15631 ,7884,7625,7625 ,0,0,0}, {15632,12431,12432 ,8021,7625,726 ,0,0,0}, + {12432,12435,15622 ,726,7625,7257 ,0,0,0}, {12425,12426,15618 ,726,726,8017 ,0,0,0}, + {12429,15617,15619 ,7625,8022,7761 ,0,0,0}, {12420,15616,12419 ,7626,726,7626 ,0,0,0}, + {15615,12420,12423 ,726,7626,7626 ,0,0,0}, {12415,12400,12399 ,7625,726,726 ,0,0,0}, + {12418,12399,15613 ,7625,726,7625 ,0,0,0}, {12411,12402,12412 ,726,726,7625 ,0,0,0}, + {12402,12411,12409 ,726,726,726 ,0,0,0}, {12406,12411,12412 ,7625,726,7625 ,0,0,0}, + {12414,12412,12415 ,7625,7625,7625 ,0,0,0}, {12412,12402,12400 ,7625,726,726 ,0,0,0}, + {12403,12402,12409 ,726,726,726 ,0,0,0}, {12399,12418,12415 ,726,7625,7625 ,0,0,0}, + {12400,12415,12412 ,726,7625,7625 ,0,0,0}, {15613,12397,12419 ,7625,726,7626 ,0,0,0}, + {12397,15613,12399 ,726,7625,726 ,0,0,0}, {15616,12420,15615 ,726,7626,726 ,0,0,0}, + {15613,12419,15616 ,7625,7626,726 ,0,0,0}, {12423,12425,15614 ,7626,726,7880 ,0,0,0}, + {15618,12426,15619 ,8017,726,7761 ,0,0,0}, {15614,12425,15618 ,7880,726,8017 ,0,0,0}, + {15619,12426,12429 ,7761,726,7625 ,0,0,0}, {15617,12431,15632 ,8022,7625,8021 ,0,0,0}, + {15617,12429,12431 ,8022,7625,7625 ,0,0,0}, {12435,15621,15622 ,7625,8020,7257 ,0,0,0}, + {15622,15632,12432 ,7257,8021,726 ,0,0,0}, {12435,12437,15620 ,7625,7625,7884 ,0,0,0}, + {12379,15633,13948 ,8023,8024,8025 ,0,0,0}, {13690,13893,15634 ,8026,8027,8028 ,0,0,0}, + {14000,13946,15635 ,8029,8030,8031 ,0,0,0}, {13939,15636,13931 ,8032,8033,8034 ,0,0,0}, + {15637,15638,13898 ,8035,8036,8037 ,0,0,0}, {15639,15640,13938 ,8038,8039,8040 ,0,0,0}, + {15639,13940,15641 ,8038,8041,8042 ,0,0,0}, {15642,15643,13937 ,8043,8044,8045 ,0,0,0}, + {13937,13837,15642 ,8045,8046,8043 ,0,0,0}, {13834,15643,15644 ,8047,8044,8048 ,0,0,0}, + {15643,13834,13937 ,8044,8047,8045 ,0,0,0}, {15645,13835,15644 ,8049,8050,8048 ,0,0,0}, + {13834,15644,13835 ,8047,8048,8050 ,0,0,0}, {15645,12393,12394 ,8049,82,82 ,0,0,0}, + {12394,13835,15645 ,82,8050,8049 ,0,0,0}, {15636,13939,15638 ,8033,8032,8036 ,0,0,0}, + {15640,13837,13938 ,8039,8046,8040 ,0,0,0}, {15642,13837,15640 ,8043,8046,8039 ,0,0,0}, + {15634,13893,15646 ,8028,8027,8051 ,0,0,0}, {15641,13940,13931 ,8042,8041,8034 ,0,0,0}, + {15639,13938,13940 ,8038,8040,8041 ,0,0,0}, {15636,15641,13931 ,8033,8042,8034 ,0,0,0}, + {13898,15638,13939 ,8037,8036,8032 ,0,0,0}, {13690,15634,15637 ,8026,8028,8035 ,0,0,0}, + {15637,13898,13690 ,8035,8037,8026 ,0,0,0}, {13946,15633,15635 ,8030,8024,8031 ,0,0,0}, + {15646,14000,15635 ,8051,8029,8031 ,0,0,0}, {13893,14000,15646 ,8027,8029,8051 ,0,0,0}, + {12379,13948,12380 ,8023,8025,8052 ,0,0,0}, {15633,13946,13948 ,8024,8030,8025 ,0,0,0}, + {15639,12376,15640 ,726,726,726 ,0,0,0}, {15643,12372,12369 ,726,7661,726 ,0,0,0}, + {15636,15638,15633 ,726,7660,726 ,0,0,0}, {15641,12379,12378 ,726,726,726 ,0,0,0}, + {15635,15633,15634 ,7661,726,726 ,0,0,0}, {15634,15646,15635 ,726,7658,7661 ,0,0,0}, + {15634,15638,15637 ,726,7660,726 ,0,0,0}, {15633,12379,15636 ,726,726,726 ,0,0,0}, + {15638,15634,15633 ,7660,726,726 ,0,0,0}, {15641,12378,15639 ,726,726,726 ,0,0,0}, + {15636,12379,15641 ,726,726,726 ,0,0,0}, {15639,12378,12376 ,726,726,726 ,0,0,0}, + {15640,12374,15642 ,726,7658,726 ,0,0,0}, {15640,12376,12374 ,726,726,7658 ,0,0,0}, + {15643,15642,12372 ,726,726,7661 ,0,0,0}, {12374,12372,15642 ,7658,7661,726 ,0,0,0}, + {15643,12369,15644 ,726,726,726 ,0,0,0}, {12368,15645,15644 ,726,726,726 ,0,0,0}, + {15644,12369,12368 ,726,726,726 ,0,0,0}, {15645,12366,12393 ,726,726,726 ,0,0,0}, + {12366,15645,12368 ,726,726,726 ,0,0,0}, {12366,12365,12393 ,726,726,726 ,0,0,0}, + {12385,12381,12382 ,7659,726,726 ,0,0,0}, {12385,12391,12381 ,7659,726,726 ,0,0,0}, + {12388,12385,12387 ,726,7659,726 ,0,0,0}, {12388,12391,12385 ,726,726,7659 ,0,0,0}, + {12393,12365,12391 ,726,726,726 ,0,0,0}, {12381,12391,12365 ,726,726,726 ,0,0,0}, + {15647,15648,15175 ,726,8053,7583 ,0,0,0}, {15177,15649,15176 ,726,726,726 ,0,0,0}, + {15648,15650,15175 ,8053,7922,7583 ,0,0,0}, {15647,15175,15651 ,726,7583,5472 ,0,0,0}, + {15175,15652,15653 ,7583,7664,5488 ,0,0,0}, {15650,15652,15175 ,7922,7664,7583 ,0,0,0}, + {15654,15655,15175 ,7920,726,7583 ,0,0,0}, {15653,15656,15175 ,5488,5471,7583 ,0,0,0}, + {15657,15658,15177 ,7664,7583,726 ,0,0,0}, {15177,15659,15660 ,726,5488,7664 ,0,0,0}, + {15661,15177,15662 ,726,726,726 ,0,0,0}, {15663,15664,15177 ,7664,7664,726 ,0,0,0}, + {15665,15662,15177 ,726,726,726 ,0,0,0}, {15177,15661,15649 ,726,726,726 ,0,0,0}, + {15663,15177,15666 ,7664,726,7664 ,0,0,0}, {15177,15664,15665 ,726,7664,726 ,0,0,0}, + {15177,15658,15666 ,726,7583,7664 ,0,0,0}, {15177,15660,15667 ,726,7664,726 ,0,0,0}, + {15177,15667,15657 ,726,726,7664 ,0,0,0}, {15655,15177,15175 ,726,726,7583 ,0,0,0}, + {15655,15659,15177 ,726,5488,726 ,0,0,0}, {15175,15656,15654 ,7583,5471,7920 ,0,0,0}, + {14204,15176,15649 ,726,726,726 ,0,0,0}, {15651,15175,15668 ,5472,7583,7793 ,0,0,0}, + {15669,15175,15174 ,5471,7583,7664 ,0,0,0}, {15175,15669,15668 ,7583,5471,7793 ,0,0,0}, + {15669,15174,14149 ,5471,7664,7920 ,0,0,0}, {13756,13755,15667 ,8054,8055,8056 ,0,0,0}, + {15660,13765,13756 ,8057,8058,8054 ,0,0,0}, {15660,15659,13765 ,8057,8058,8058 ,0,0,0}, + {15667,15660,13756 ,8056,8057,8054 ,0,0,0}, {13755,13934,15657 ,8055,8059,8060 ,0,0,0}, + {13832,13776,15666 ,8061,8062,8063 ,0,0,0}, {15658,15657,13934 ,8064,8060,8059 ,0,0,0}, + {13934,13832,15658 ,8059,8061,8064 ,0,0,0}, {15666,15658,13832 ,8063,8064,8061 ,0,0,0}, + {13755,15657,15667 ,8055,8060,8056 ,0,0,0}, {15666,13776,15663 ,8063,8062,8065 ,0,0,0}, + {13775,15664,15663 ,8066,8067,8065 ,0,0,0}, {15663,13776,13775 ,8065,8062,8066 ,0,0,0}, + {15664,13775,13935 ,8067,8066,8068 ,0,0,0}, {13783,15665,13935 ,8069,8070,8068 ,0,0,0}, + {13783,13782,15662 ,8069,8071,8072 ,0,0,0}, {13783,15662,15665 ,8069,8072,8070 ,0,0,0}, + {15661,13797,15649 ,8073,8074,8075 ,0,0,0}, {15662,13782,15661 ,8072,8071,8073 ,0,0,0}, + {15661,13782,13797 ,8073,8071,8074 ,0,0,0}, {13797,13800,15649 ,8074,8075,8075 ,0,0,0}, + {15664,13935,15665 ,8067,8068,8070 ,0,0,0}, {13588,15659,15655 ,8076,8058,8077 ,0,0,0}, + {15659,13588,13765 ,8058,8076,8058 ,0,0,0}, {15654,13836,15655 ,8078,8079,8077 ,0,0,0}, + {13588,15655,13836 ,8076,8077,8079 ,0,0,0}, {15654,15656,13780 ,8078,8080,8081 ,0,0,0}, + {13780,13836,15654 ,8081,8079,8078 ,0,0,0}, {13781,15656,15653 ,8082,8080,8083 ,0,0,0}, + {15656,13781,13780 ,8080,8082,8081 ,0,0,0}, {15652,13958,15653 ,8084,8085,8083 ,0,0,0}, + {13781,15653,13958 ,8082,8083,8085 ,0,0,0}, {15652,15650,13726 ,8084,8086,8087 ,0,0,0}, + {13726,13958,15652 ,8087,8085,8084 ,0,0,0}, {13725,15650,15648 ,8088,8086,8089 ,0,0,0}, + {15650,13725,13726 ,8086,8088,8087 ,0,0,0}, {15647,13809,15648 ,8090,8091,8089 ,0,0,0}, + {13725,15648,13809 ,8088,8089,8091 ,0,0,0}, {15647,15651,13849 ,8090,8092,8093 ,0,0,0}, + {13849,13809,15647 ,8093,8091,8090 ,0,0,0}, {13850,15651,15668 ,8094,8092,8095 ,0,0,0}, + {15651,13850,13849 ,8092,8094,8093 ,0,0,0}, {13850,15668,13851 ,8094,8095,8096 ,0,0,0}, + {13851,15668,15669 ,8096,8095,8096 ,0,0,0}, {14156,15669,14149 ,8097,8098,8097 ,0,0,0}, + {15669,14157,14160 ,8098,8097,8098 ,0,0,0}, {14156,14157,15669 ,8097,8097,8098 ,0,0,0}, + {15669,14166,14171 ,8098,8098,8097 ,0,0,0}, {14160,14166,15669 ,8098,8098,8098 ,0,0,0}, + {15669,14175,14134 ,8098,8098,8097 ,0,0,0}, {14171,14175,15669 ,8097,8098,8098 ,0,0,0}, + {15669,14138,14137 ,8098,8097,8097 ,0,0,0}, {14134,14138,15669 ,8097,8097,8098 ,0,0,0}, + {15669,14137,13851 ,8098,8097,8098 ,0,0,0}, {14213,15649,13800 ,8099,8099,8099 ,0,0,0}, + {14213,14269,15649 ,8099,8099,8099 ,0,0,0}, {15649,14269,14255 ,8099,8099,8099 ,0,0,0}, + {14209,14215,15649 ,8099,8099,8099 ,0,0,0}, {14209,15649,14255 ,8099,8099,8099 ,0,0,0}, + {14215,14251,15649 ,8099,8099,8099 ,0,0,0}, {15649,14198,14197 ,8099,8099,8099 ,0,0,0}, + {14251,14198,15649 ,8099,8099,8099 ,0,0,0}, {14204,15649,14202 ,8099,8099,8099 ,0,0,0}, + {14197,14202,15649 ,8099,8099,8099 ,0,0,0}, {12342,15670,13992 ,1359,8100,4482 ,0,0,0}, + {15671,13991,15672 ,4475,8101,8102 ,0,0,0}, {13993,13990,15673 ,8103,8104,4478 ,0,0,0}, + {13824,15674,13816 ,8105,8106,8107 ,0,0,0}, {15675,15676,13996 ,4472,8108,8109 ,0,0,0}, + {15677,13853,15678 ,8110,8111,8112 ,0,0,0}, {13852,13814,15679 ,8113,8114,8115 ,0,0,0}, + {13827,13820,15680 ,8116,8117,8118 ,0,0,0}, {13855,15681,13820 ,8119,8120,8117 ,0,0,0}, + {13845,15682,15683 ,8121,8122,8123 ,0,0,0}, {13827,15684,13847 ,8116,8124,8125 ,0,0,0}, + {15685,13844,15683 ,8126,8127,8123 ,0,0,0}, {13845,15683,13844 ,8121,8123,8127 ,0,0,0}, + {15685,15686,13842 ,8126,8128,8129 ,0,0,0}, {13842,13844,15685 ,8129,8127,8126 ,0,0,0}, + {13839,15686,15687 ,8130,8128,8131 ,0,0,0}, {15686,13839,13842 ,8128,8130,8129 ,0,0,0}, + {15688,13840,15687 ,8132,8133,8131 ,0,0,0}, {13839,15687,13840 ,8130,8131,8133 ,0,0,0}, + {15688,12361,12362 ,8132,1435,1435 ,0,0,0}, {12362,13840,15688 ,1435,8133,8132 ,0,0,0}, + {15680,13820,15681 ,8118,8117,8120 ,0,0,0}, {15682,13847,15684 ,8122,8125,8124 ,0,0,0}, + {13847,15682,13845 ,8125,8122,8121 ,0,0,0}, {15680,15684,13827 ,8118,8124,8116 ,0,0,0}, + {15677,15681,13855 ,8110,8120,8119 ,0,0,0}, {13852,15679,15678 ,8113,8115,8112 ,0,0,0}, + {13852,15678,13853 ,8113,8112,8111 ,0,0,0}, {13855,13853,15677 ,8119,8111,8110 ,0,0,0}, + {13814,15689,15679 ,8114,8134,8115 ,0,0,0}, {15689,13814,13816 ,8134,8114,8107 ,0,0,0}, + {15676,15674,13824 ,8108,8106,8105 ,0,0,0}, {15674,15689,13816 ,8106,8134,8107 ,0,0,0}, + {13996,15676,13824 ,8109,8108,8105 ,0,0,0}, {13972,15671,15675 ,4474,4475,4472 ,0,0,0}, + {13972,15675,13996 ,4474,4472,8109 ,0,0,0}, {13991,13993,15672 ,8101,8103,8102 ,0,0,0}, + {13972,13991,15671 ,4474,8101,4475 ,0,0,0}, {13990,15670,15673 ,8104,8100,4478 ,0,0,0}, + {15672,13993,15673 ,8102,8103,4478 ,0,0,0}, {12342,13992,12340 ,1359,4482,1359 ,0,0,0}, + {15670,13990,13992 ,8100,8104,4482 ,0,0,0}, {12336,15674,15676 ,726,726,726 ,0,0,0}, + {15682,12343,15683 ,726,7626,7758 ,0,0,0}, {15688,15687,15686 ,7625,7625,726 ,0,0,0}, + {15684,15680,12323 ,8135,7628,7626 ,0,0,0}, {12323,12321,15684 ,7626,7626,8135 ,0,0,0}, + {12333,15678,15679 ,726,7627,726 ,0,0,0}, {12326,15677,12327 ,726,7628,726 ,0,0,0}, + {12330,15674,12336 ,726,726,726 ,0,0,0}, {15679,15689,12335 ,726,726,726 ,0,0,0}, + {15671,15672,15673 ,7628,7628,726 ,0,0,0}, {12339,12336,15676 ,726,726,726 ,0,0,0}, + {12342,12339,15670 ,726,726,726 ,0,0,0}, {15670,15671,15673 ,726,7628,726 ,0,0,0}, + {15670,12339,15671 ,726,726,7628 ,0,0,0}, {15676,15675,12339 ,726,726,726 ,0,0,0}, + {12339,15675,15671 ,726,726,7628 ,0,0,0}, {15674,12330,12335 ,726,726,726 ,0,0,0}, + {12339,12338,12336 ,726,726,726 ,0,0,0}, {12335,12333,15679 ,726,726,726 ,0,0,0}, + {12335,15689,15674 ,726,726,726 ,0,0,0}, {15677,15678,12327 ,7628,7627,726 ,0,0,0}, + {12327,15678,12333 ,726,7627,726 ,0,0,0}, {12324,15681,12326 ,726,726,726 ,0,0,0}, + {12326,15681,15677 ,726,726,7628 ,0,0,0}, {12324,12323,15680 ,726,7626,7628 ,0,0,0}, + {15680,15681,12324 ,7628,726,726 ,0,0,0}, {12321,12343,15682 ,7626,7626,726 ,0,0,0}, + {12321,15682,15684 ,7626,726,8135 ,0,0,0}, {12344,15683,12343 ,7626,7758,7626 ,0,0,0}, + {15685,15683,12347 ,8135,7758,7628 ,0,0,0}, {12344,12347,15683 ,7626,7628,7758 ,0,0,0}, + {12347,12349,15686 ,7628,726,726 ,0,0,0}, {15686,15685,12347 ,726,8135,7628 ,0,0,0}, + {15688,12349,12350 ,7625,726,7626 ,0,0,0}, {12349,15688,15686 ,726,7625,726 ,0,0,0}, + {12353,12356,12359 ,7626,726,7626 ,0,0,0}, {12350,12353,15688 ,7626,7626,7625 ,0,0,0}, + {12359,15688,12353 ,7626,7625,7626 ,0,0,0}, {12353,12355,12356 ,7626,7627,726 ,0,0,0}, + {15688,12359,12361 ,7625,7626,8135 ,0,0,0}, {12303,15690,13978 ,1359,8136,8137 ,0,0,0}, + {13961,13963,15691 ,8138,8139,8140 ,0,0,0}, {13980,13982,15692 ,8141,8142,8143 ,0,0,0}, + {13768,15693,13767 ,8144,8145,8146 ,0,0,0}, {15694,15695,13962 ,8147,8148,8149 ,0,0,0}, + {15696,15697,13960 ,8150,8151,8152 ,0,0,0}, {15696,13959,15698 ,8150,8153,8154 ,0,0,0}, + {15699,15700,13892 ,8155,8156,8157 ,0,0,0}, {13892,13891,15699 ,8157,8158,8155 ,0,0,0}, + {13806,15700,15701 ,8159,8156,8160 ,0,0,0}, {15700,13806,13892 ,8156,8159,8157 ,0,0,0}, + {15702,13805,15701 ,8161,8162,8160 ,0,0,0}, {13806,15701,13805 ,8159,8160,8162 ,0,0,0}, + {15702,12317,12318 ,8161,1435,1435 ,0,0,0}, {12318,13805,15702 ,1435,8162,8161 ,0,0,0}, + {15693,13768,15695 ,8145,8144,8148 ,0,0,0}, {15697,13891,13960 ,8151,8158,8152 ,0,0,0}, + {15699,13891,15697 ,8155,8158,8151 ,0,0,0}, {15691,13963,15703 ,8140,8139,8163 ,0,0,0}, + {15698,13959,13767 ,8154,8153,8146 ,0,0,0}, {15696,13960,13959 ,8150,8152,8153 ,0,0,0}, + {15693,15698,13767 ,8145,8154,8146 ,0,0,0}, {13962,15695,13768 ,8149,8148,8144 ,0,0,0}, + {13961,15691,15694 ,8138,8140,8147 ,0,0,0}, {15694,13962,13961 ,8147,8149,8138 ,0,0,0}, + {13982,15690,15692 ,8142,8136,8143 ,0,0,0}, {15703,13980,15692 ,8163,8141,8143 ,0,0,0}, + {13963,13980,15703 ,8139,8141,8163 ,0,0,0}, {12303,13978,12304 ,1359,8137,1359 ,0,0,0}, + {15690,13982,13978 ,8136,8142,8137 ,0,0,0}, {15700,15695,15694 ,726,7661,7661 ,0,0,0}, + {15696,15698,15699 ,7661,7658,726 ,0,0,0}, {15699,15697,15696 ,726,726,7661 ,0,0,0}, + {15693,15695,15699 ,7658,7661,726 ,0,0,0}, {15693,15699,15698 ,7658,726,7658 ,0,0,0}, + {15694,15701,15700 ,7661,726,726 ,0,0,0}, {15695,15700,15699 ,7661,726,726 ,0,0,0}, + {15701,15694,15691 ,726,7661,7658 ,0,0,0}, {15691,15703,15702 ,7658,7661,726 ,0,0,0}, + {15702,15701,15691 ,726,726,7658 ,0,0,0}, {12317,15703,15692 ,726,7661,7658 ,0,0,0}, + {15703,12317,15702 ,7661,726,726 ,0,0,0}, {12302,12311,12303 ,7658,726,726 ,0,0,0}, + {15690,12315,15692 ,7658,7660,7658 ,0,0,0}, {12309,12302,12300 ,726,7658,726 ,0,0,0}, + {12290,12289,12296 ,726,726,726 ,0,0,0}, {12306,12298,12305 ,726,726,726 ,0,0,0}, + {12296,12293,12292 ,726,726,726 ,0,0,0}, {12296,12289,12305 ,726,726,726 ,0,0,0}, + {12290,12296,12292 ,726,726,726 ,0,0,0}, {12300,12298,12306 ,726,726,726 ,0,0,0}, + {12298,12296,12305 ,726,726,726 ,0,0,0}, {12311,12302,12309 ,726,7658,726 ,0,0,0}, + {12309,12300,12306 ,726,726,726 ,0,0,0}, {12303,12312,15690 ,726,726,7658 ,0,0,0}, + {12303,12311,12312 ,726,726,726 ,0,0,0}, {15692,12315,12317 ,7658,7660,726 ,0,0,0}, + {12312,12315,15690 ,726,7660,7658 ,0,0,0}, {15704,15705,15172 ,726,726,7664 ,0,0,0}, + {15706,15704,15172 ,726,726,7664 ,0,0,0}, {15706,15172,15707 ,726,7664,726 ,0,0,0}, + {15708,15172,15705 ,726,7664,726 ,0,0,0}, {15709,15710,15172 ,726,726,7664 ,0,0,0}, + {15709,15172,15708 ,726,7664,726 ,0,0,0}, {15711,15172,15170 ,726,7664,726 ,0,0,0}, + {15707,15172,15711 ,726,7664,726 ,0,0,0}, {15712,15172,15710 ,726,7664,726 ,0,0,0}, + {15172,15712,15713 ,7664,726,726 ,0,0,0}, {15711,15170,15714 ,726,726,726 ,0,0,0}, + {15715,15172,15713 ,726,7664,726 ,0,0,0}, {15716,15714,15170 ,7583,726,726 ,0,0,0}, + {15170,15717,15716 ,726,7664,7583 ,0,0,0}, {15172,15715,15718 ,7664,726,726 ,0,0,0}, + {15172,15718,15719 ,7664,726,726 ,0,0,0}, {15720,15717,15170 ,726,7664,726 ,0,0,0}, + {15721,15722,15170 ,726,726,726 ,0,0,0}, {15722,15720,15170 ,726,726,726 ,0,0,0}, + {15723,15170,15724 ,726,726,726 ,0,0,0}, {15723,15721,15170 ,726,726,726 ,0,0,0}, + {15173,15719,14110 ,7664,726,726 ,0,0,0}, {15719,15173,15172 ,726,7664,7664 ,0,0,0}, + {15724,15170,15725 ,726,726,726 ,0,0,0}, {15726,15170,15171 ,726,726,7664 ,0,0,0}, + {15170,15726,15725 ,726,726,726 ,0,0,0}, {15726,15171,14034 ,726,7664,5488 ,0,0,0}, + {13822,13815,15704 ,8164,8165,8166 ,0,0,0}, {15706,13823,13822 ,8167,8168,8164 ,0,0,0}, + {15706,15707,13823 ,8167,8168,8168 ,0,0,0}, {15704,15706,13822 ,8166,8167,8164 ,0,0,0}, + {13815,13956,15705 ,8165,8169,8170 ,0,0,0}, {13854,13856,15709 ,8171,8172,8173 ,0,0,0}, + {15708,15705,13956 ,8174,8170,8169 ,0,0,0}, {13956,13854,15708 ,8169,8171,8174 ,0,0,0}, + {15709,15708,13854 ,8173,8174,8171 ,0,0,0}, {13815,15705,15704 ,8165,8170,8166 ,0,0,0}, + {15709,13856,15710 ,8173,8172,8175 ,0,0,0}, {13819,15712,15710 ,8176,8177,8175 ,0,0,0}, + {15710,13856,13819 ,8175,8172,8176 ,0,0,0}, {15712,13819,13821 ,8177,8176,8178 ,0,0,0}, + {13826,15713,13821 ,8179,8180,8178 ,0,0,0}, {13826,13858,15715 ,8179,8181,8182 ,0,0,0}, + {13826,15715,15713 ,8179,8182,8180 ,0,0,0}, {15718,13860,15719 ,8183,8184,8185 ,0,0,0}, + {15715,13858,15718 ,8182,8181,8183 ,0,0,0}, {15718,13858,13860 ,8183,8181,8184 ,0,0,0}, + {13860,13859,15719 ,8184,8185,8185 ,0,0,0}, {15712,13821,15713 ,8177,8178,8180 ,0,0,0}, + {13818,15707,15711 ,8186,8168,8187 ,0,0,0}, {15707,13818,13823 ,8168,8186,8168 ,0,0,0}, + {15714,13817,15711 ,8188,8189,8187 ,0,0,0}, {13818,15711,13817 ,8186,8187,8189 ,0,0,0}, + {15714,15716,13984 ,8188,8190,8191 ,0,0,0}, {13984,13817,15714 ,8191,8189,8188 ,0,0,0}, + {13812,15716,15717 ,8192,8190,8193 ,0,0,0}, {15716,13812,13984 ,8190,8192,8191 ,0,0,0}, + {15720,13813,15717 ,8194,8195,8193 ,0,0,0}, {13812,15717,13813 ,8192,8193,8195 ,0,0,0}, + {15720,15722,13886 ,8194,8196,8197 ,0,0,0}, {13886,13813,15720 ,8197,8195,8194 ,0,0,0}, + {13887,15722,15721 ,8198,8196,8199 ,0,0,0}, {15722,13887,13886 ,8196,8198,8197 ,0,0,0}, + {15723,13630,15721 ,8200,8201,8199 ,0,0,0}, {13887,15721,13630 ,8198,8199,8201 ,0,0,0}, + {15723,15724,13633 ,8200,8202,8203 ,0,0,0}, {13633,13630,15723 ,8203,8201,8200 ,0,0,0}, + {13634,15724,15725 ,8204,8202,8205 ,0,0,0}, {15724,13634,13633 ,8202,8204,8203 ,0,0,0}, + {13634,15725,13635 ,8204,8205,8206 ,0,0,0}, {13635,15725,15726 ,8206,8205,8206 ,0,0,0}, + {14035,15726,14034 ,8207,8207,8207 ,0,0,0}, {15726,14065,14068 ,8207,8207,8207 ,0,0,0}, + {14035,14065,15726 ,8207,8207,8207 ,0,0,0}, {15726,14074,14079 ,8207,8207,8207 ,0,0,0}, + {14068,14074,15726 ,8207,8207,8207 ,0,0,0}, {15726,14083,14013 ,8207,8207,8207 ,0,0,0}, + {14079,14083,15726 ,8207,8207,8207 ,0,0,0}, {15726,14016,14015 ,8207,8207,8207 ,0,0,0}, + {14013,14016,15726 ,8207,8207,8207 ,0,0,0}, {15726,14015,13635 ,8207,8207,8207 ,0,0,0}, + {14125,15719,13859 ,8208,8208,8208 ,0,0,0}, {14125,14176,15719 ,8208,8208,8208 ,0,0,0}, + {15719,14176,14162 ,8208,8208,8208 ,0,0,0}, {14119,14112,15719 ,8208,8208,8208 ,0,0,0}, + {14119,15719,14162 ,8208,8208,8208 ,0,0,0}, {14112,14158,15719 ,8208,8208,8208 ,0,0,0}, + {15719,14150,14104 ,8208,8208,8208 ,0,0,0}, {14158,14150,15719 ,8208,8208,8208 ,0,0,0}, + {14110,15719,14106 ,8208,8208,8208 ,0,0,0}, {14104,14106,15719 ,8208,8208,8208 ,0,0,0}, + {12266,15727,13622 ,1711,8209,4414 ,0,0,0}, {15728,13885,15729 ,8210,8211,8212 ,0,0,0}, + {13870,13623,15730 ,8213,8214,4410 ,0,0,0}, {13884,15731,13614 ,4402,8215,8216 ,0,0,0}, + {15732,15733,13883 ,8217,8218,8219 ,0,0,0}, {15734,13644,15735 ,8220,8221,8222 ,0,0,0}, + {13643,13869,15736 ,8223,8224,8225 ,0,0,0}, {13617,13616,15737 ,8226,8227,8228 ,0,0,0}, + {13639,15738,13616 ,8229,8230,8227 ,0,0,0}, {13620,15739,15740 ,8231,8232,8233 ,0,0,0}, + {13617,15741,13619 ,8226,8234,8235 ,0,0,0}, {15742,13636,15740 ,8236,8237,8233 ,0,0,0}, + {13620,15740,13636 ,8231,8233,8237 ,0,0,0}, {15742,15743,13624 ,8236,8238,8239 ,0,0,0}, + {13624,13636,15742 ,8239,8237,8236 ,0,0,0}, {13872,15743,15744 ,8240,8238,8241 ,0,0,0}, + {15743,13872,13624 ,8238,8240,8239 ,0,0,0}, {15745,13632,15744 ,8242,8243,8241 ,0,0,0}, + {13872,15744,13632 ,8240,8241,8243 ,0,0,0}, {15745,12285,12286 ,8242,1790,1790 ,0,0,0}, + {12286,13632,15745 ,1790,8243,8242 ,0,0,0}, {15737,13616,15738 ,8228,8227,8230 ,0,0,0}, + {15739,13619,15741 ,8232,8235,8234 ,0,0,0}, {13619,15739,13620 ,8235,8232,8231 ,0,0,0}, + {15737,15741,13617 ,8228,8234,8226 ,0,0,0}, {15734,15738,13639 ,8220,8230,8229 ,0,0,0}, + {13643,15736,15735 ,8223,8225,8222 ,0,0,0}, {13643,15735,13644 ,8223,8222,8221 ,0,0,0}, + {13639,13644,15734 ,8229,8221,8220 ,0,0,0}, {13869,15746,15736 ,8224,8244,8225 ,0,0,0}, + {15746,13869,13614 ,8244,8224,8216 ,0,0,0}, {15733,15731,13884 ,8218,8215,4402 ,0,0,0}, + {15731,15746,13614 ,8215,8244,8216 ,0,0,0}, {13883,15733,13884 ,8219,8218,4402 ,0,0,0}, + {13584,15728,15732 ,8245,8210,8217 ,0,0,0}, {13584,15732,13883 ,8245,8217,8219 ,0,0,0}, + {13885,13870,15729 ,8211,8213,8212 ,0,0,0}, {13584,13885,15728 ,8245,8211,8210 ,0,0,0}, + {13623,15727,15730 ,8214,8209,4410 ,0,0,0}, {15729,13870,15730 ,8212,8213,4410 ,0,0,0}, + {12266,13622,12264 ,1711,4414,1711 ,0,0,0}, {15727,13623,13622 ,8209,8214,4414 ,0,0,0}, + {15732,15737,15738 ,726,726,7626 ,0,0,0}, {15746,15735,15736 ,726,726,726 ,0,0,0}, + {15734,15746,15731 ,726,726,726 ,0,0,0}, {15733,15734,15731 ,726,726,726 ,0,0,0}, + {15733,15738,15734 ,726,7626,726 ,0,0,0}, {15746,15734,15735 ,726,726,726 ,0,0,0}, + {15733,15732,15738 ,726,726,7626 ,0,0,0}, {15728,15741,15737 ,726,726,726 ,0,0,0}, + {15732,15728,15737 ,726,726,726 ,0,0,0}, {15741,15729,15739 ,726,726,7626 ,0,0,0}, + {15729,15741,15728 ,726,726,726 ,0,0,0}, {15740,15739,15730 ,7628,7626,726 ,0,0,0}, + {15729,15730,15739 ,726,726,7626 ,0,0,0}, {15727,15742,15740 ,726,726,7628 ,0,0,0}, + {15740,15730,15727 ,7628,726,726 ,0,0,0}, {15742,12266,15743 ,726,726,726 ,0,0,0}, + {12266,15742,15727 ,726,726,726 ,0,0,0}, {15744,15743,12263 ,7625,726,726 ,0,0,0}, + {12266,12263,15743 ,726,726,726 ,0,0,0}, {15744,12263,12262 ,7625,726,726 ,0,0,0}, + {15745,15744,12262 ,726,7625,726 ,0,0,0}, {12262,12260,15745 ,726,726,726 ,0,0,0}, + {12254,12285,12260 ,726,726,726 ,0,0,0}, {15745,12260,12285 ,726,726,726 ,0,0,0}, + {12257,12251,12279 ,726,726,7625 ,0,0,0}, {12254,12259,12283 ,726,726,726 ,0,0,0}, + {12248,12273,12274 ,7626,726,726 ,0,0,0}, {12274,12277,12250 ,726,726,726 ,0,0,0}, + {12273,12247,12271 ,726,7625,7625 ,0,0,0}, {12247,12268,12271 ,7625,726,7625 ,0,0,0}, + {12245,12268,12247 ,726,726,7625 ,0,0,0}, {12245,12267,12268 ,726,726,726 ,0,0,0}, + {12250,12248,12274 ,726,7626,726 ,0,0,0}, {12247,12273,12248 ,7625,726,7626 ,0,0,0}, + {12277,12279,12251 ,726,7625,726 ,0,0,0}, {12250,12277,12251 ,726,726,726 ,0,0,0}, + {12257,12280,12259 ,726,726,726 ,0,0,0}, {12257,12279,12280 ,726,7625,726 ,0,0,0}, + {12254,12283,12285 ,726,726,726 ,0,0,0}, {12280,12283,12259 ,726,726,726 ,0,0,0}, + {12227,15747,13896 ,1711,8246,8247 ,0,0,0}, {13955,13969,15748 ,8248,8249,8250 ,0,0,0}, + {13968,13897,15749 ,8251,8252,8253 ,0,0,0}, {13808,15750,13807 ,8254,8255,8256 ,0,0,0}, + {15751,15752,13989 ,8257,8258,8259 ,0,0,0}, {15753,15754,13987 ,8260,8261,8262 ,0,0,0}, + {15753,13986,15755 ,8260,8263,8264 ,0,0,0}, {15756,15757,13889 ,8265,8266,8267 ,0,0,0}, + {13889,13890,15756 ,8267,8268,8265 ,0,0,0}, {13985,15757,15758 ,8269,8266,8270 ,0,0,0}, + {15757,13985,13889 ,8266,8269,8267 ,0,0,0}, {15759,13888,15758 ,8271,8272,8270 ,0,0,0}, + {13985,15758,13888 ,8269,8270,8272 ,0,0,0}, {15759,12241,12242 ,8271,1790,1790 ,0,0,0}, + {12242,13888,15759 ,1790,8272,8271 ,0,0,0}, {15750,13808,15752 ,8255,8254,8258 ,0,0,0}, + {15754,13890,13987 ,8261,8268,8262 ,0,0,0}, {15756,13890,15754 ,8265,8268,8261 ,0,0,0}, + {15748,13969,15760 ,8250,8249,8273 ,0,0,0}, {15755,13986,13807 ,8264,8263,8256 ,0,0,0}, + {15753,13987,13986 ,8260,8262,8263 ,0,0,0}, {15750,15755,13807 ,8255,8264,8256 ,0,0,0}, + {13989,15752,13808 ,8259,8258,8254 ,0,0,0}, {13955,15748,15751 ,8248,8250,8257 ,0,0,0}, + {15751,13989,13955 ,8257,8259,8248 ,0,0,0}, {13897,15747,15749 ,8252,8246,8253 ,0,0,0}, + {15760,13968,15749 ,8273,8251,8253 ,0,0,0}, {13969,13968,15760 ,8249,8251,8273 ,0,0,0}, + {12227,13896,12228 ,1711,8247,1711 ,0,0,0}, {15747,13897,13896 ,8246,8252,8247 ,0,0,0}, + {12241,15759,15758 ,726,7658,726 ,0,0,0}, {15760,12216,15748 ,726,726,726 ,0,0,0}, + {12239,15758,15757 ,7660,726,7660 ,0,0,0}, {15753,12235,15754 ,7660,726,7660 ,0,0,0}, + {12236,12239,15756 ,7660,7660,7583 ,0,0,0}, {12229,15750,15752 ,7660,7661,7661 ,0,0,0}, + {12233,15753,15755 ,726,7660,7658 ,0,0,0}, {12214,15748,12216 ,726,726,726 ,0,0,0}, + {15752,15751,12213 ,7661,726,726 ,0,0,0}, {15747,12222,12220 ,726,726,726 ,0,0,0}, + {15749,12217,15760 ,726,726,726 ,0,0,0}, {12227,12226,12222 ,726,726,726 ,0,0,0}, + {12224,12222,12226 ,726,726,726 ,0,0,0}, {12222,15747,12227 ,726,726,726 ,0,0,0}, + {15749,12220,12217 ,726,726,726 ,0,0,0}, {15749,15747,12220 ,726,726,726 ,0,0,0}, + {15751,15748,12214 ,726,726,726 ,0,0,0}, {12216,15760,12217 ,726,726,726 ,0,0,0}, + {12213,12229,15752 ,726,7660,7661 ,0,0,0}, {12214,12213,15751 ,726,726,726 ,0,0,0}, + {15755,15750,12230 ,7658,7661,7659 ,0,0,0}, {12230,15750,12229 ,7659,7661,7660 ,0,0,0}, + {12233,15755,12230 ,726,7658,7659 ,0,0,0}, {12236,15754,12235 ,7660,7660,726 ,0,0,0}, + {15753,12233,12235 ,7660,726,726 ,0,0,0}, {12239,15757,15756 ,7660,7660,7583 ,0,0,0}, + {12236,15756,15754 ,7660,7583,7660 ,0,0,0}, {12239,12241,15758 ,7660,726,726 ,0,0,0}, + {13994,12186,15761 ,8274,8275,8276 ,0,0,0}, {13995,13971,15762 ,8277,8278,8279 ,0,0,0}, + {15763,13971,13988 ,8280,8278,8281 ,0,0,0}, {15764,15765,13895 ,8282,8283,8284 ,0,0,0}, + {15766,13967,13966 ,8285,8286,8287 ,0,0,0}, {13976,13964,15767 ,8288,8289,8290 ,0,0,0}, + {13975,15768,15769 ,8291,8292,8293 ,0,0,0}, {13998,15770,13981 ,8294,8295,8296 ,0,0,0}, + {15771,15772,13977 ,1631,8297,1631 ,0,0,0}, {15773,15774,13979 ,8298,8299,8300 ,0,0,0}, + {15773,13999,15775 ,8298,8301,8302 ,0,0,0}, {15776,15777,13974 ,8303,8304,8305 ,0,0,0}, + {15776,13973,15774 ,8303,8306,8299 ,0,0,0}, {13912,15777,15778 ,8307,8304,8308 ,0,0,0}, + {15777,13912,13974 ,8304,8307,8305 ,0,0,0}, {15779,13953,15778 ,8309,8310,8308 ,0,0,0}, + {13912,15778,13953 ,8307,8308,8310 ,0,0,0}, {13894,15779,13947 ,8311,8309,8312 ,0,0,0}, + {13894,13953,15779 ,8311,8310,8309 ,0,0,0}, {13945,13947,15780 ,8313,8312,8314 ,0,0,0}, + {15779,15780,13947 ,8309,8314,8312 ,0,0,0}, {15781,12210,13945 ,8315,126,8313 ,0,0,0}, + {13945,15780,15781 ,8313,8314,8315 ,0,0,0}, {12208,12210,15781 ,126,126,8315 ,0,0,0}, + {13973,13979,15774 ,8306,8300,8299 ,0,0,0}, {15776,13974,13973 ,8303,8305,8306 ,0,0,0}, + {13999,13981,15775 ,8301,8296,8302 ,0,0,0}, {15773,13979,13999 ,8298,8300,8301 ,0,0,0}, + {15772,15770,13998 ,8297,8295,8294 ,0,0,0}, {15770,15775,13981 ,8295,8302,8296 ,0,0,0}, + {13976,15771,13977 ,8288,1631,1631 ,0,0,0}, {13977,15772,13998 ,1631,8297,8294 ,0,0,0}, + {13964,15769,15767 ,8289,8293,8290 ,0,0,0}, {13976,15767,15771 ,8288,8290,1631 ,0,0,0}, + {13975,13997,15768 ,8291,8316,8292 ,0,0,0}, {13964,13975,15769 ,8289,8291,8293 ,0,0,0}, + {13895,15765,13997 ,8284,8283,8316 ,0,0,0}, {15768,13997,15765 ,8292,8316,8283 ,0,0,0}, + {15766,15764,13967 ,8285,8282,8286 ,0,0,0}, {15764,13895,13967 ,8282,8284,8286 ,0,0,0}, + {13995,15782,13966 ,8277,8317,8287 ,0,0,0}, {15782,15766,13966 ,8317,8285,8287 ,0,0,0}, + {13971,15783,15762 ,8278,8318,8279 ,0,0,0}, {13995,15762,15782 ,8277,8279,8317 ,0,0,0}, + {15763,13988,15761 ,8280,8281,8276 ,0,0,0}, {15783,13971,15763 ,8318,8278,8280 ,0,0,0}, + {12186,13994,12185 ,8275,8274,4114 ,0,0,0}, {15761,13988,13994 ,8276,8281,8274 ,0,0,0}, + {15773,15784,15774 ,726,726,726 ,0,0,0}, {15785,12159,15781 ,726,726,726 ,0,0,0}, + {15786,15777,15787 ,726,726,726 ,0,0,0}, {12190,12144,12143 ,726,726,7661 ,0,0,0}, + {12199,12201,12153 ,726,726,726 ,0,0,0}, {15788,15780,15779 ,726,726,726 ,0,0,0}, + {12204,12207,12158 ,726,726,726 ,0,0,0}, {12208,12159,12207 ,726,726,726 ,0,0,0}, + {12156,12154,12205 ,7658,726,726 ,0,0,0}, {12204,12158,12156 ,726,726,7658 ,0,0,0}, + {15788,15785,15780 ,726,726,726 ,0,0,0}, {12201,12202,12154 ,726,726,726 ,0,0,0}, + {12199,12153,12150 ,726,726,726 ,0,0,0}, {12195,12148,12193 ,726,726,726 ,0,0,0}, + {12196,12150,12148 ,726,726,726 ,0,0,0}, {12144,12190,12193 ,726,726,726 ,0,0,0}, + {15786,15779,15778 ,726,726,726 ,0,0,0}, {15774,15789,15776 ,726,7661,726 ,0,0,0}, + {15776,15789,15787 ,726,7661,726 ,0,0,0}, {12123,12163,12162 ,7658,726,7658 ,0,0,0}, + {12189,12143,12123 ,726,7661,7658 ,0,0,0}, {15790,15784,15775 ,726,726,726 ,0,0,0}, + {12163,12127,12164 ,726,7658,726 ,0,0,0}, {12166,12128,12129 ,7661,7658,726 ,0,0,0}, + {15770,15772,15791 ,726,7661,726 ,0,0,0}, {15770,15791,15790 ,726,726,726 ,0,0,0}, + {15772,15771,15792 ,7661,7658,7658 ,0,0,0}, {12170,12169,12129 ,726,726,726 ,0,0,0}, + {12133,12172,12130 ,726,7583,726 ,0,0,0}, {15793,15794,15769 ,726,726,726 ,0,0,0}, + {15794,15792,15767 ,726,7658,726 ,0,0,0}, {12182,12136,12139 ,7664,726,7664 ,0,0,0}, + {15793,15769,15768 ,726,726,7661 ,0,0,0}, {15795,15768,15765 ,726,7661,7664 ,0,0,0}, + {12142,12186,12184 ,726,726,7664 ,0,0,0}, {15796,15761,12142 ,7664,726,726 ,0,0,0}, + {15795,15764,15797 ,726,7583,726 ,0,0,0}, {15763,15798,15783 ,7664,7664,726 ,0,0,0}, + {12164,12127,12128 ,726,7658,7658 ,0,0,0}, {15762,15783,15799 ,7664,726,7664 ,0,0,0}, + {15798,15799,15783 ,7664,7664,726 ,0,0,0}, {15763,15761,15796 ,7664,726,7664 ,0,0,0}, + {15763,15796,15798 ,7664,7664,7664 ,0,0,0}, {15800,15797,15766 ,7664,726,7583 ,0,0,0}, + {15800,15766,15782 ,7664,7583,7664 ,0,0,0}, {12186,12142,15761 ,726,726,726 ,0,0,0}, + {12135,12136,12178 ,726,726,726 ,0,0,0}, {12133,12135,12175 ,726,726,7664 ,0,0,0}, + {15800,15782,15799 ,7664,7664,7664 ,0,0,0}, {15782,15762,15799 ,7664,7664,7664 ,0,0,0}, + {15764,15766,15797 ,7583,7583,726 ,0,0,0}, {15765,15764,15795 ,7664,7583,726 ,0,0,0}, + {15793,15768,15795 ,726,7661,726 ,0,0,0}, {15767,15769,15794 ,726,726,726 ,0,0,0}, + {15771,15767,15792 ,7658,726,7658 ,0,0,0}, {15791,15772,15792 ,726,7661,7658 ,0,0,0}, + {15775,15770,15790 ,726,726,726 ,0,0,0}, {15773,15775,15784 ,726,726,726 ,0,0,0}, + {15789,15774,15784 ,7661,726,726 ,0,0,0}, {15777,15776,15787 ,726,726,726 ,0,0,0}, + {15778,15777,15786 ,726,726,726 ,0,0,0}, {15788,15779,15786 ,726,726,726 ,0,0,0}, + {15781,15780,15785 ,726,726,726 ,0,0,0}, {12208,15781,12159 ,726,726,726 ,0,0,0}, + {12158,12207,12159 ,726,726,726 ,0,0,0}, {12205,12204,12156 ,726,726,7658 ,0,0,0}, + {12202,12205,12154 ,726,726,726 ,0,0,0}, {12153,12201,12154 ,726,726,726 ,0,0,0}, + {12196,12199,12150 ,726,726,726 ,0,0,0}, {12195,12196,12148 ,726,726,726 ,0,0,0}, + {12144,12193,12148 ,726,726,726 ,0,0,0}, {12189,12190,12143 ,726,726,7661 ,0,0,0}, + {12162,12189,12123 ,7658,726,7658 ,0,0,0}, {12127,12163,12123 ,7658,726,7658 ,0,0,0}, + {12169,12166,12129 ,726,7661,726 ,0,0,0}, {12166,12164,12128 ,7661,726,7658 ,0,0,0}, + {12130,12170,12129 ,726,726,726 ,0,0,0}, {12133,12175,12172 ,726,7664,7583 ,0,0,0}, + {12130,12172,12170 ,726,7583,726 ,0,0,0}, {12135,12176,12175 ,726,7664,7664 ,0,0,0}, + {12178,12136,12182 ,726,726,7664 ,0,0,0}, {12176,12135,12178 ,7664,726,726 ,0,0,0}, + {12182,12139,12184 ,7664,7664,7664 ,0,0,0}, {12142,12184,12139 ,726,7664,7664 ,0,0,0}, + {15801,15802,12126 ,726,726,726 ,0,0,0}, {12145,12147,12155 ,726,726,726 ,0,0,0}, + {12124,12145,12160 ,726,726,726 ,0,0,0}, {12126,12125,15801 ,726,726,726 ,0,0,0}, + {12151,12152,12155 ,726,726,726 ,0,0,0}, {12146,12149,12147 ,726,726,726 ,0,0,0}, + {12151,12155,12149 ,726,726,726 ,0,0,0}, {12147,12149,12155 ,726,726,726 ,0,0,0}, + {12155,12157,12145 ,726,726,726 ,0,0,0}, {15801,12124,12160 ,726,726,726 ,0,0,0}, + {12160,12145,12157 ,726,726,726 ,0,0,0}, {12126,15802,15803 ,726,726,726 ,0,0,0}, + {15801,12125,12124 ,726,726,726 ,0,0,0}, {12131,15803,15804 ,726,726,726 ,0,0,0}, + {15803,12131,12126 ,726,726,726 ,0,0,0}, {15804,12134,12132 ,726,726,7658 ,0,0,0}, + {12131,15804,12132 ,726,726,7658 ,0,0,0}, {15805,12134,15804 ,726,726,726 ,0,0,0}, + {12134,15806,12137 ,726,726,7661 ,0,0,0}, {15806,12134,15805 ,726,726,726 ,0,0,0}, + {15806,15807,12137 ,726,726,7661 ,0,0,0}, {12138,15807,12140 ,726,726,7661 ,0,0,0}, + {12138,12137,15807 ,726,7661,726 ,0,0,0}, {12140,15808,15809 ,7661,726,726 ,0,0,0}, + {15807,15808,12140 ,726,726,7661 ,0,0,0}, {15810,12141,15809 ,726,7658,726 ,0,0,0}, + {12140,15809,12141 ,7661,726,7658 ,0,0,0}, {15811,15812,15813 ,726,726,7660 ,0,0,0}, + {15813,15814,15811 ,7660,726,726 ,0,0,0}, {15812,15815,15816 ,726,726,7658 ,0,0,0}, + {15812,15810,15813 ,726,726,7660 ,0,0,0}, {15812,15817,15810 ,726,7661,726 ,0,0,0}, + {15812,15811,15815 ,726,726,726 ,0,0,0}, {15810,15817,12141 ,726,7661,7658 ,0,0,0}, + {15817,12142,12141 ,8319,81,8320 ,0,0,0}, {15815,15800,15816 ,8321,8322,8323 ,0,0,0}, + {15812,15799,15798 ,8324,8325,8326 ,0,0,0}, {15813,15810,15793 ,8327,8328,8329 ,0,0,0}, + {15811,15814,15795 ,8330,8331,8332 ,0,0,0}, {15807,15791,15808 ,8333,8334,8335 ,0,0,0}, + {15792,15809,15808 ,8336,8337,8335 ,0,0,0}, {15805,15789,15806 ,7530,8338,8339 ,0,0,0}, + {15784,15807,15806 ,8340,8333,8339 ,0,0,0}, {15804,15786,15787 ,8341,8342,8343 ,0,0,0}, + {15787,15805,15804 ,8343,7530,8341 ,0,0,0}, {15786,15803,15788 ,8342,8344,8345 ,0,0,0}, + {15803,15786,15804 ,8344,8342,8341 ,0,0,0}, {15785,15788,15802 ,8346,8345,8347 ,0,0,0}, + {15803,15802,15788 ,8344,8347,8345 ,0,0,0}, {12160,15785,15801 ,96,8346,8348 ,0,0,0}, + {15785,15802,15801 ,8346,8347,8348 ,0,0,0}, {12159,15785,12160 ,96,8346,96 ,0,0,0}, + {15784,15806,15789 ,8340,8339,8338 ,0,0,0}, {15787,15789,15805 ,8343,8338,7530 ,0,0,0}, + {15790,15791,15807 ,8349,8334,8333 ,0,0,0}, {15784,15790,15807 ,8340,8349,8333 ,0,0,0}, + {15794,15809,15792 ,8350,8337,8336 ,0,0,0}, {15791,15792,15808 ,8334,8336,8335 ,0,0,0}, + {15793,15810,15794 ,8329,8328,8350 ,0,0,0}, {15809,15794,15810 ,8337,8350,8328 ,0,0,0}, + {15795,15814,15793 ,8332,8331,8329 ,0,0,0}, {15814,15813,15793 ,8331,8327,8329 ,0,0,0}, + {15797,15815,15811 ,7516,8321,8330 ,0,0,0}, {15797,15811,15795 ,7516,8330,8332 ,0,0,0}, + {15800,15799,15816 ,8322,8325,8323 ,0,0,0}, {15797,15800,15815 ,7516,8322,8321 ,0,0,0}, + {15812,15798,15817 ,8324,8326,8319 ,0,0,0}, {15816,15799,15812 ,8323,8325,8324 ,0,0,0}, + {12142,15817,15796 ,81,8319,8351 ,0,0,0}, {15817,15798,15796 ,8319,8326,8351 ,0,0,0} +// MotorHacker.prt + , {15818,15819,15820 ,4056,4057,4058 ,0,0,0}, {15821,15822,15820 ,4059,4060,4058 ,0,0,0}, + {15818,15820,15822 ,4056,4058,4060 ,0,0,0}, {15823,15821,15824 ,4061,4059,4062 ,0,0,0}, + {15823,15822,15821 ,4061,4060,4059 ,0,0,0}, {15825,15824,15826 ,4063,4062,4064 ,0,0,0}, + {15821,15826,15824 ,4059,4064,4062 ,0,0,0}, {15827,15828,15825 ,4065,4066,4063 ,0,0,0}, + {15825,15826,15827 ,4063,4064,4065 ,0,0,0}, {15828,15829,15830 ,4066,4067,4068 ,0,0,0}, + {15829,15828,15827 ,4067,4066,4065 ,0,0,0}, {15831,15830,15832 ,4069,4068,4070 ,0,0,0}, + {15829,15832,15830 ,4067,4070,4068 ,0,0,0}, {15833,15834,15831 ,4071,4072,4069 ,0,0,0}, + {15831,15832,15833 ,4069,4070,4071 ,0,0,0}, {15835,15836,15834 ,4073,81,4072 ,0,0,0}, + {15835,15834,15833 ,4073,4072,4071 ,0,0,0}, {15836,15837,15834 ,81,81,4072 ,0,0,0}, + {15838,15819,15818 ,4074,4057,4056 ,0,0,0}, {15838,15839,15840 ,4074,4075,4076 ,0,0,0}, + {15840,15819,15838 ,4076,4057,4074 ,0,0,0}, {15841,15842,15839 ,4077,4078,4075 ,0,0,0}, + {15839,15842,15840 ,4075,4078,4076 ,0,0,0}, {15843,15844,15841 ,4079,4080,4077 ,0,0,0}, + {15841,15839,15843 ,4077,4075,4079 ,0,0,0}, {15844,15845,15846 ,4080,4081,4082 ,0,0,0}, + {15845,15844,15843 ,4081,4080,4079 ,0,0,0}, {15847,15846,15848 ,4083,4082,4084 ,0,0,0}, + {15845,15848,15846 ,4081,4084,4082 ,0,0,0}, {15849,15850,15847 ,4085,4086,4083 ,0,0,0}, + {15847,15848,15849 ,4083,4084,4085 ,0,0,0}, {15850,15851,15852 ,4086,4087,4088 ,0,0,0}, + {15851,15850,15849 ,4087,4086,4085 ,0,0,0}, {15852,15853,15854 ,4088,4089,4090 ,0,0,0}, + {15851,15853,15852 ,4087,4089,4088 ,0,0,0}, {15852,15854,15855 ,4088,4090,4091 ,0,0,0}, + {15856,15857,15858 ,2394,2394,4092 ,0,0,0}, {15859,15860,15858 ,4093,4094,4092 ,0,0,0}, + {15856,15858,15860 ,2394,4092,4094 ,0,0,0}, {15859,15861,15862 ,4093,4095,4096 ,0,0,0}, + {15862,15860,15859 ,4096,4094,4093 ,0,0,0}, {15863,15861,15864 ,4097,4095,4098 ,0,0,0}, + {15861,15863,15862 ,4095,4097,4096 ,0,0,0}, {15865,15866,15864 ,4099,4100,4098 ,0,0,0}, + {15863,15864,15866 ,4097,4098,4100 ,0,0,0}, {15865,15867,15868 ,4099,4101,4102 ,0,0,0}, + {15868,15866,15865 ,4102,4100,4099 ,0,0,0}, {15869,15867,15870 ,4103,4101,4104 ,0,0,0}, + {15867,15869,15868 ,4101,4103,4102 ,0,0,0}, {15871,15872,15870 ,4105,4106,4104 ,0,0,0}, + {15869,15870,15872 ,4103,4104,4106 ,0,0,0}, {15871,15873,15874 ,4105,4107,4108 ,0,0,0}, + {15874,15872,15871 ,4108,4106,4105 ,0,0,0}, {15875,15876,15873 ,4109,4110,4107 ,0,0,0}, + {15873,15876,15874 ,4107,4110,4108 ,0,0,0}, {15877,15878,15875 ,4111,4112,4109 ,0,0,0}, + {15875,15873,15877 ,4109,4107,4111 ,0,0,0}, {15878,15879,15880 ,4112,4113,4114 ,0,0,0}, + {15879,15878,15877 ,4113,4112,4111 ,0,0,0}, {15879,15881,15880 ,4113,4114,4114 ,0,0,0}, + {15882,15857,15856 ,4115,2394,2394 ,0,0,0}, {15882,15883,15884 ,4115,4116,4117 ,0,0,0}, + {15884,15857,15882 ,4117,2394,4115 ,0,0,0}, {15885,15883,15886 ,4118,4116,4119 ,0,0,0}, + {15883,15885,15884 ,4116,4118,4117 ,0,0,0}, {15887,15888,15886 ,4120,4121,4119 ,0,0,0}, + {15885,15886,15888 ,4118,4119,4121 ,0,0,0}, {15887,15889,15890 ,4120,4122,4123 ,0,0,0}, + {15890,15888,15887 ,4123,4121,4120 ,0,0,0}, {15891,15889,15892 ,4124,4122,4125 ,0,0,0}, + {15889,15891,15890 ,4122,4124,4123 ,0,0,0}, {15893,15894,15892 ,4126,4127,4125 ,0,0,0}, + {15891,15892,15894 ,4124,4125,4127 ,0,0,0}, {15893,15895,15896 ,4126,4128,4129 ,0,0,0}, + {15896,15894,15893 ,4129,4127,4126 ,0,0,0}, {15897,15895,15898 ,4130,4128,4131 ,0,0,0}, + {15895,15897,15896 ,4128,4130,4129 ,0,0,0}, {15898,15899,15900 ,4131,4132,4133 ,0,0,0}, + {15897,15898,15900 ,4130,4131,4133 ,0,0,0}, {15899,15901,15902 ,4132,4134,4135 ,0,0,0}, + {15901,15899,15898 ,4134,4132,4131 ,0,0,0}, {15903,15902,15904 ,126,4135,4136 ,0,0,0}, + {15901,15904,15902 ,4134,4136,4135 ,0,0,0}, {15903,15904,15905 ,126,4136,126 ,0,0,0}, + {15906,15907,15908 ,4137,4138,4139 ,0,0,0}, {15906,15909,15910 ,4137,4140,4141 ,0,0,0}, + {15909,15911,15910 ,4140,4142,4141 ,0,0,0}, {15908,15909,15906 ,4139,4140,4137 ,0,0,0}, + {15912,15913,15914 ,4143,4144,4145 ,0,0,0}, {15911,15912,15914 ,4142,4143,4145 ,0,0,0}, + {15913,15915,15916 ,4144,4146,4147 ,0,0,0}, {15915,15913,15912 ,4146,4144,4143 ,0,0,0}, + {15916,15915,15917 ,4147,4146,4148 ,0,0,0}, {15918,15916,15917 ,4149,4147,4148 ,0,0,0}, + {15918,15919,15920 ,4149,4150,4151 ,0,0,0}, {15918,15917,15919 ,4149,4148,4150 ,0,0,0}, + {15914,15910,15911 ,4145,4141,4142 ,0,0,0}, {15921,15922,15923 ,4152,1711,1711 ,0,0,0}, + {15921,15923,15920 ,4152,1711,4151 ,0,0,0}, {15919,15921,15920 ,4150,4152,4151 ,0,0,0}, + {15908,15907,15924 ,4139,4138,4153 ,0,0,0}, {15925,15924,15926 ,4154,4153,4155 ,0,0,0}, + {15907,15926,15924 ,4138,4155,4153 ,0,0,0}, {15927,15928,15925 ,4156,4157,4154 ,0,0,0}, + {15925,15926,15927 ,4154,4155,4156 ,0,0,0}, {15928,15929,15930 ,4157,4158,4159 ,0,0,0}, + {15929,15928,15927 ,4158,4157,4156 ,0,0,0}, {15931,15930,15932 ,4160,4159,4161 ,0,0,0}, + {15929,15932,15930 ,4158,4161,4159 ,0,0,0}, {15933,15934,15931 ,4162,4163,4160 ,0,0,0}, + {15931,15932,15933 ,4160,4161,4162 ,0,0,0}, {15934,15935,15936 ,4163,4164,1790 ,0,0,0}, + {15935,15934,15933 ,4164,4163,4162 ,0,0,0}, {15935,15937,15936 ,4164,1790,1790 ,0,0,0}, + {15938,15939,15940 ,4165,4166,4167 ,0,0,0}, {15941,15942,15943 ,4168,4169,4170 ,0,0,0}, + {15942,15938,15940 ,4169,4165,4167 ,0,0,0}, {15944,15941,15943 ,4171,4168,4170 ,0,0,0}, + {15942,15941,15938 ,4169,4168,4165 ,0,0,0}, {15944,15943,15945 ,4171,4170,4172 ,0,0,0}, + {15945,15946,15947 ,4172,4173,4174 ,0,0,0}, {15948,15947,15946 ,4175,4174,4173 ,0,0,0}, + {15949,15950,15951 ,4176,4177,4178 ,0,0,0}, {15946,15952,15948 ,4173,4179,4175 ,0,0,0}, + {15951,15953,15954 ,4178,4180,4181 ,0,0,0}, {15953,15952,15954 ,4180,4179,4181 ,0,0,0}, + {15948,15952,15953 ,4175,4179,4180 ,0,0,0}, {15951,15954,15949 ,4178,4181,4176 ,0,0,0}, + {15950,15949,15955 ,4177,4176,4182 ,0,0,0}, {15950,15955,15956 ,4177,4182,4183 ,0,0,0}, + {15957,15956,15955 ,4184,4183,4182 ,0,0,0}, {15958,15959,15960 ,4185,1711,4186 ,0,0,0}, + {15960,15956,15957 ,4186,4183,4184 ,0,0,0}, {15958,15960,15957 ,4185,4186,4184 ,0,0,0}, + {15958,15961,15959 ,4185,1711,1711 ,0,0,0}, {15944,15945,15947 ,4171,4172,4174 ,0,0,0}, + {15940,15939,15962 ,4167,4166,4187 ,0,0,0}, {15963,15962,15964 ,4188,4187,4189 ,0,0,0}, + {15939,15964,15962 ,4166,4189,4187 ,0,0,0}, {15965,15966,15963 ,4190,4191,4188 ,0,0,0}, + {15963,15964,15965 ,4188,4189,4190 ,0,0,0}, {15966,15967,15968 ,4191,4192,4193 ,0,0,0}, + {15967,15966,15965 ,4192,4191,4190 ,0,0,0}, {15969,15968,15970 ,4194,4193,4195 ,0,0,0}, + {15967,15970,15968 ,4192,4195,4193 ,0,0,0}, {15971,15972,15969 ,4196,4197,4194 ,0,0,0}, + {15969,15970,15971 ,4194,4195,4196 ,0,0,0}, {15972,15973,15974 ,4197,4198,4199 ,0,0,0}, + {15973,15972,15971 ,4198,4197,4196 ,0,0,0}, {15975,15974,15976 ,4200,4199,4201 ,0,0,0}, + {15973,15976,15974 ,4198,4201,4199 ,0,0,0}, {15977,15978,15975 ,4202,4203,4200 ,0,0,0}, + {15975,15976,15977 ,4200,4201,4202 ,0,0,0}, {15978,15979,15980 ,4203,4204,1790 ,0,0,0}, + {15979,15978,15977 ,4204,4203,4202 ,0,0,0}, {15979,15981,15980 ,4204,1790,1790 ,0,0,0}, + {15982,15983,15984 ,4205,4206,4207 ,0,0,0}, {15982,15985,15986 ,4205,4208,4209 ,0,0,0}, + {15985,15987,15986 ,4208,4210,4209 ,0,0,0}, {15984,15985,15982 ,4207,4208,4205 ,0,0,0}, + {15988,15989,15990 ,4211,4212,4213 ,0,0,0}, {15987,15988,15990 ,4210,4211,4213 ,0,0,0}, + {15989,15991,15992 ,4212,4214,4215 ,0,0,0}, {15991,15989,15988 ,4214,4212,4211 ,0,0,0}, + {15992,15991,15993 ,4215,4214,4216 ,0,0,0}, {15994,15992,15993 ,4217,4215,4216 ,0,0,0}, + {15994,15995,15996 ,4217,4218,4219 ,0,0,0}, {15994,15993,15995 ,4217,4216,4218 ,0,0,0}, + {15990,15986,15987 ,4213,4209,4210 ,0,0,0}, {15997,15998,15999 ,4220,1359,1359 ,0,0,0}, + {15997,15999,15996 ,4220,1359,4219 ,0,0,0}, {15995,15997,15996 ,4218,4220,4219 ,0,0,0}, + {15984,15983,16000 ,4207,4206,4221 ,0,0,0}, {16001,16000,16002 ,4222,4221,4223 ,0,0,0}, + {15983,16002,16000 ,4206,4223,4221 ,0,0,0}, {16003,16004,16001 ,4224,4225,4222 ,0,0,0}, + {16001,16002,16003 ,4222,4223,4224 ,0,0,0}, {16004,16005,16006 ,4225,4226,4227 ,0,0,0}, + {16005,16004,16003 ,4226,4225,4224 ,0,0,0}, {16007,16006,16008 ,4228,4227,4229 ,0,0,0}, + {16005,16008,16006 ,4226,4229,4227 ,0,0,0}, {16009,16010,16007 ,4230,4231,4228 ,0,0,0}, + {16007,16008,16009 ,4228,4229,4230 ,0,0,0}, {16010,16011,16012 ,4231,4232,1435 ,0,0,0}, + {16011,16010,16009 ,4232,4231,4230 ,0,0,0}, {16011,16013,16012 ,4232,1435,1435 ,0,0,0}, + {16014,16015,16016 ,4233,4234,4235 ,0,0,0}, {16017,16018,16019 ,4236,4237,4238 ,0,0,0}, + {16018,16014,16016 ,4237,4233,4235 ,0,0,0}, {16020,16017,16019 ,4239,4236,4238 ,0,0,0}, + {16018,16017,16014 ,4237,4236,4233 ,0,0,0}, {16020,16019,16021 ,4239,4238,4240 ,0,0,0}, + {16021,16022,16023 ,4240,4241,4242 ,0,0,0}, {16024,16023,16022 ,4243,4242,4241 ,0,0,0}, + {16025,16026,16027 ,4244,4245,4246 ,0,0,0}, {16022,16028,16024 ,4241,4247,4243 ,0,0,0}, + {16027,16029,16030 ,4246,4248,4249 ,0,0,0}, {16029,16028,16030 ,4248,4247,4249 ,0,0,0}, + {16024,16028,16029 ,4243,4247,4248 ,0,0,0}, {16027,16030,16025 ,4246,4249,4244 ,0,0,0}, + {16026,16025,16031 ,4245,4244,4250 ,0,0,0}, {16026,16031,16032 ,4245,4250,4251 ,0,0,0}, + {16033,16032,16031 ,4252,4251,4250 ,0,0,0}, {16034,16035,16036 ,4253,1359,4254 ,0,0,0}, + {16036,16032,16033 ,4254,4251,4252 ,0,0,0}, {16034,16036,16033 ,4253,4254,4252 ,0,0,0}, + {16034,16037,16035 ,4253,1359,1359 ,0,0,0}, {16020,16021,16023 ,4239,4240,4242 ,0,0,0}, + {16016,16015,16038 ,4235,4234,4255 ,0,0,0}, {16039,16038,16040 ,4256,4255,4257 ,0,0,0}, + {16015,16040,16038 ,4234,4257,4255 ,0,0,0}, {16041,16042,16039 ,4258,4259,4256 ,0,0,0}, + {16039,16040,16041 ,4256,4257,4258 ,0,0,0}, {16042,16043,16044 ,4259,4260,4261 ,0,0,0}, + {16043,16042,16041 ,4260,4259,4258 ,0,0,0}, {16045,16044,16046 ,4262,4261,4263 ,0,0,0}, + {16043,16046,16044 ,4260,4263,4261 ,0,0,0}, {16047,16048,16045 ,4264,4265,4262 ,0,0,0}, + {16045,16046,16047 ,4262,4263,4264 ,0,0,0}, {16048,16049,16050 ,4265,4266,4267 ,0,0,0}, + {16049,16048,16047 ,4266,4265,4264 ,0,0,0}, {16051,16050,16052 ,4268,4267,4269 ,0,0,0}, + {16049,16052,16050 ,4266,4269,4267 ,0,0,0}, {16053,16054,16051 ,4270,4271,4268 ,0,0,0}, + {16051,16052,16053 ,4268,4269,4270 ,0,0,0}, {16054,16055,16056 ,4271,4272,1435 ,0,0,0}, + {16055,16054,16053 ,4272,4271,4270 ,0,0,0}, {16055,16057,16056 ,4272,1435,1435 ,0,0,0}, + {16058,16059,16060 ,4273,4274,4275 ,0,0,0}, {16058,16061,16062 ,4273,4276,4277 ,0,0,0}, + {16061,16063,16062 ,4276,4278,4277 ,0,0,0}, {16060,16061,16058 ,4275,4276,4273 ,0,0,0}, + {16064,16065,16066 ,4279,4280,4281 ,0,0,0}, {16063,16064,16066 ,4278,4279,4281 ,0,0,0}, + {16065,16067,16068 ,4280,4282,4283 ,0,0,0}, {16067,16065,16064 ,4282,4280,4279 ,0,0,0}, + {16068,16067,16069 ,4283,4282,4284 ,0,0,0}, {16070,16068,16069 ,4285,4283,4284 ,0,0,0}, + {16070,16071,16072 ,4285,4286,4287 ,0,0,0}, {16070,16069,16071 ,4285,4284,4286 ,0,0,0}, + {16066,16062,16063 ,4281,4277,4278 ,0,0,0}, {16073,16074,16075 ,4288,126,4289 ,0,0,0}, + {16073,16075,16072 ,4288,4289,4287 ,0,0,0}, {16071,16073,16072 ,4286,4288,4287 ,0,0,0}, + {16060,16059,16076 ,4275,4274,4290 ,0,0,0}, {16077,16076,16078 ,4291,4290,4292 ,0,0,0}, + {16059,16078,16076 ,4274,4292,4290 ,0,0,0}, {16079,16080,16077 ,4293,4294,4291 ,0,0,0}, + {16077,16078,16079 ,4291,4292,4293 ,0,0,0}, {16080,16081,16082 ,4294,4295,4296 ,0,0,0}, + {16081,16080,16079 ,4295,4294,4293 ,0,0,0}, {16083,16082,16084 ,4297,4296,4298 ,0,0,0}, + {16081,16084,16082 ,4295,4298,4296 ,0,0,0}, {16085,16086,16083 ,4299,4300,4297 ,0,0,0}, + {16083,16084,16085 ,4297,4298,4299 ,0,0,0}, {16086,16087,16088 ,4300,4301,4302 ,0,0,0}, + {16087,16086,16085 ,4301,4300,4299 ,0,0,0}, {16087,16089,16088 ,4301,4303,4302 ,0,0,0}, + {16090,16091,16092 ,4304,4305,4306 ,0,0,0}, {16093,16094,16095 ,4307,4308,4309 ,0,0,0}, + {16094,16090,16092 ,4308,4304,4306 ,0,0,0}, {16096,16093,16095 ,4310,4307,4309 ,0,0,0}, + {16094,16093,16090 ,4308,4307,4304 ,0,0,0}, {16096,16095,16097 ,4310,4309,4311 ,0,0,0}, + {16097,16098,16099 ,4311,4312,4313 ,0,0,0}, {16100,16099,16098 ,4314,4313,4312 ,0,0,0}, + {16101,16102,16103 ,4315,4316,4317 ,0,0,0}, {16098,16104,16100 ,4312,4318,4314 ,0,0,0}, + {16103,16105,16106 ,4317,4319,4320 ,0,0,0}, {16105,16104,16106 ,4319,4318,4320 ,0,0,0}, + {16100,16104,16105 ,4314,4318,4319 ,0,0,0}, {16103,16106,16101 ,4317,4320,4315 ,0,0,0}, + {16102,16101,16107 ,4316,4315,4321 ,0,0,0}, {16102,16107,16108 ,4316,4321,4322 ,0,0,0}, + {16109,16108,16107 ,4323,4322,4321 ,0,0,0}, {16110,16111,16112 ,4324,126,4325 ,0,0,0}, + {16112,16108,16109 ,4325,4322,4323 ,0,0,0}, {16110,16112,16109 ,4324,4325,4323 ,0,0,0}, + {16110,16113,16111 ,4324,4326,126 ,0,0,0}, {16096,16097,16099 ,4310,4311,4313 ,0,0,0}, + {16092,16091,16114 ,4306,4305,4327 ,0,0,0}, {16115,16114,16116 ,4328,4327,4329 ,0,0,0}, + {16091,16116,16114 ,4305,4329,4327 ,0,0,0}, {16117,16118,16115 ,4330,4331,4328 ,0,0,0}, + {16115,16116,16117 ,4328,4329,4330 ,0,0,0}, {16118,16119,16120 ,4331,4332,4333 ,0,0,0}, + {16119,16118,16117 ,4332,4331,4330 ,0,0,0}, {16121,16120,16122 ,4334,4333,4335 ,0,0,0}, + {16119,16122,16120 ,4332,4335,4333 ,0,0,0}, {16123,16124,16121 ,4336,4337,4334 ,0,0,0}, + {16121,16122,16123 ,4334,4335,4336 ,0,0,0}, {16124,16125,16126 ,4337,4338,4339 ,0,0,0}, + {16125,16124,16123 ,4338,4337,4336 ,0,0,0}, {16127,16126,16128 ,4340,4339,4341 ,0,0,0}, + {16125,16128,16126 ,4338,4341,4339 ,0,0,0}, {16129,16130,16127 ,4342,4343,4340 ,0,0,0}, + {16127,16128,16129 ,4340,4341,4342 ,0,0,0}, {16130,16131,16132 ,4343,4344,4345 ,0,0,0}, + {16131,16130,16129 ,4344,4343,4342 ,0,0,0}, {16131,16133,16132 ,4344,4346,4345 ,0,0,0}, + {16134,16135,16136 ,4347,4348,4349 ,0,0,0}, {16134,16137,16138 ,4347,4350,4351 ,0,0,0}, + {16137,16139,16138 ,4350,4352,4351 ,0,0,0}, {16136,16137,16134 ,4349,4350,4347 ,0,0,0}, + {16140,16141,16142 ,4353,4354,4355 ,0,0,0}, {16139,16140,16142 ,4352,4353,4355 ,0,0,0}, + {16141,16143,16144 ,4354,4356,4357 ,0,0,0}, {16143,16141,16140 ,4356,4354,4353 ,0,0,0}, + {16144,16143,16145 ,4357,4356,4358 ,0,0,0}, {16146,16144,16145 ,4359,4357,4358 ,0,0,0}, + {16146,16147,16148 ,4359,4360,4361 ,0,0,0}, {16146,16145,16147 ,4359,4358,4360 ,0,0,0}, + {16142,16138,16139 ,4355,4351,4352 ,0,0,0}, {16149,16150,16151 ,4362,1790,1790 ,0,0,0}, + {16149,16151,16148 ,4362,1790,4361 ,0,0,0}, {16147,16149,16148 ,4360,4362,4361 ,0,0,0}, + {16136,16135,16152 ,4349,4348,4363 ,0,0,0}, {16153,16152,16154 ,4364,4363,4365 ,0,0,0}, + {16135,16154,16152 ,4348,4365,4363 ,0,0,0}, {16155,16156,16153 ,4366,4367,4364 ,0,0,0}, + {16153,16154,16155 ,4364,4365,4366 ,0,0,0}, {16156,16157,16158 ,4367,4368,4369 ,0,0,0}, + {16157,16156,16155 ,4368,4367,4366 ,0,0,0}, {16159,16158,16160 ,4370,4369,4371 ,0,0,0}, + {16157,16160,16158 ,4368,4371,4369 ,0,0,0}, {16161,16162,16159 ,4372,4373,4370 ,0,0,0}, + {16159,16160,16161 ,4370,4371,4372 ,0,0,0}, {16162,16163,16164 ,4373,4374,1711 ,0,0,0}, + {16163,16162,16161 ,4374,4373,4372 ,0,0,0}, {16163,16165,16164 ,4374,1711,1711 ,0,0,0}, + {16166,16167,16168 ,4375,4376,4377 ,0,0,0}, {16169,16170,16171 ,4378,4379,4380 ,0,0,0}, + {16170,16166,16168 ,4379,4375,4377 ,0,0,0}, {16172,16169,16171 ,4381,4378,4380 ,0,0,0}, + {16170,16169,16166 ,4379,4378,4375 ,0,0,0}, {16172,16171,16173 ,4381,4380,4382 ,0,0,0}, + {16173,16174,16175 ,4382,4383,4384 ,0,0,0}, {16176,16175,16174 ,4385,4384,4383 ,0,0,0}, + {16177,16178,16179 ,4386,4387,4388 ,0,0,0}, {16174,16180,16176 ,4383,4389,4385 ,0,0,0}, + {16179,16181,16182 ,4388,4390,4391 ,0,0,0}, {16181,16180,16182 ,4390,4389,4391 ,0,0,0}, + {16176,16180,16181 ,4385,4389,4390 ,0,0,0}, {16179,16182,16177 ,4388,4391,4386 ,0,0,0}, + {16178,16177,16183 ,4387,4386,4392 ,0,0,0}, {16178,16183,16184 ,4387,4392,4393 ,0,0,0}, + {16185,16184,16183 ,4394,4393,4392 ,0,0,0}, {16186,16187,16188 ,4395,1790,4396 ,0,0,0}, + {16188,16184,16185 ,4396,4393,4394 ,0,0,0}, {16186,16188,16185 ,4395,4396,4394 ,0,0,0}, + {16186,16189,16187 ,4395,1790,1790 ,0,0,0}, {16172,16173,16175 ,4381,4382,4384 ,0,0,0}, + {16168,16167,16190 ,4377,4376,4397 ,0,0,0}, {16191,16190,16192 ,4398,4397,4399 ,0,0,0}, + {16167,16192,16190 ,4376,4399,4397 ,0,0,0}, {16193,16194,16191 ,4400,4401,4398 ,0,0,0}, + {16191,16192,16193 ,4398,4399,4400 ,0,0,0}, {16194,16195,16196 ,4401,4402,4403 ,0,0,0}, + {16195,16194,16193 ,4402,4401,4400 ,0,0,0}, {16197,16196,16198 ,4404,4403,4405 ,0,0,0}, + {16195,16198,16196 ,4402,4405,4403 ,0,0,0}, {16199,16200,16197 ,4406,4407,4404 ,0,0,0}, + {16197,16198,16199 ,4404,4405,4406 ,0,0,0}, {16200,16201,16202 ,4407,4408,4409 ,0,0,0}, + {16201,16200,16199 ,4408,4407,4406 ,0,0,0}, {16203,16202,16204 ,4410,4409,4411 ,0,0,0}, + {16201,16204,16202 ,4408,4411,4409 ,0,0,0}, {16205,16206,16203 ,4412,4413,4410 ,0,0,0}, + {16203,16204,16205 ,4410,4411,4412 ,0,0,0}, {16206,16207,16208 ,4413,4414,1711 ,0,0,0}, + {16207,16206,16205 ,4414,4413,4412 ,0,0,0}, {16207,16209,16208 ,4414,1711,1711 ,0,0,0}, + {16210,16211,16212 ,4415,4416,4417 ,0,0,0}, {16210,16213,16214 ,4415,4418,4419 ,0,0,0}, + {16213,16215,16214 ,4418,4420,4419 ,0,0,0}, {16212,16213,16210 ,4417,4418,4415 ,0,0,0}, + {16216,16217,16218 ,4421,4422,4423 ,0,0,0}, {16215,16216,16218 ,4420,4421,4423 ,0,0,0}, + {16217,16219,16220 ,4422,4424,4425 ,0,0,0}, {16219,16217,16216 ,4424,4422,4421 ,0,0,0}, + {16220,16219,16221 ,4425,4424,4426 ,0,0,0}, {16222,16220,16221 ,4427,4425,4426 ,0,0,0}, + {16222,16223,16224 ,4427,4428,4429 ,0,0,0}, {16222,16221,16223 ,4427,4426,4428 ,0,0,0}, + {16218,16214,16215 ,4423,4419,4420 ,0,0,0}, {16225,16226,16227 ,4430,1435,1435 ,0,0,0}, + {16225,16227,16224 ,4430,1435,4429 ,0,0,0}, {16223,16225,16224 ,4428,4430,4429 ,0,0,0}, + {16212,16211,16228 ,4417,4416,4431 ,0,0,0}, {16229,16228,16230 ,4432,4431,4433 ,0,0,0}, + {16211,16230,16228 ,4416,4433,4431 ,0,0,0}, {16231,16232,16229 ,4434,4435,4432 ,0,0,0}, + {16229,16230,16231 ,4432,4433,4434 ,0,0,0}, {16232,16233,16234 ,4435,4436,4437 ,0,0,0}, + {16233,16232,16231 ,4436,4435,4434 ,0,0,0}, {16235,16234,16236 ,4438,4437,4439 ,0,0,0}, + {16233,16236,16234 ,4436,4439,4437 ,0,0,0}, {16237,16238,16235 ,4440,4441,4438 ,0,0,0}, + {16235,16236,16237 ,4438,4439,4440 ,0,0,0}, {16238,16239,16240 ,4441,4442,1359 ,0,0,0}, + {16239,16238,16237 ,4442,4441,4440 ,0,0,0}, {16239,16241,16240 ,4442,1359,1359 ,0,0,0}, + {16242,16243,16244 ,4443,4444,4445 ,0,0,0}, {16245,16246,16247 ,4446,4447,4448 ,0,0,0}, + {16246,16242,16244 ,4447,4443,4445 ,0,0,0}, {16248,16245,16247 ,4449,4446,4448 ,0,0,0}, + {16246,16245,16242 ,4447,4446,4443 ,0,0,0}, {16248,16247,16249 ,4449,4448,4450 ,0,0,0}, + {16249,16250,16251 ,4450,4451,4452 ,0,0,0}, {16252,16251,16250 ,4453,4452,4451 ,0,0,0}, + {16253,16254,16255 ,4454,4455,4456 ,0,0,0}, {16250,16256,16252 ,4451,4457,4453 ,0,0,0}, + {16255,16257,16258 ,4456,4458,4459 ,0,0,0}, {16257,16256,16258 ,4458,4457,4459 ,0,0,0}, + {16252,16256,16257 ,4453,4457,4458 ,0,0,0}, {16255,16258,16253 ,4456,4459,4454 ,0,0,0}, + {16254,16253,16259 ,4455,4454,4460 ,0,0,0}, {16254,16259,16260 ,4455,4460,4461 ,0,0,0}, + {16261,16260,16259 ,4462,4461,4460 ,0,0,0}, {16262,16263,16264 ,4463,1435,4464 ,0,0,0}, + {16264,16260,16261 ,4464,4461,4462 ,0,0,0}, {16262,16264,16261 ,4463,4464,4462 ,0,0,0}, + {16262,16265,16263 ,4463,1435,1435 ,0,0,0}, {16248,16249,16251 ,4449,4450,4452 ,0,0,0}, + {16244,16243,16266 ,4445,4444,4465 ,0,0,0}, {16267,16266,16268 ,4466,4465,4467 ,0,0,0}, + {16243,16268,16266 ,4444,4467,4465 ,0,0,0}, {16269,16270,16267 ,4468,4469,4466 ,0,0,0}, + {16267,16268,16269 ,4466,4467,4468 ,0,0,0}, {16270,16271,16272 ,4469,4470,4471 ,0,0,0}, + {16271,16270,16269 ,4470,4469,4468 ,0,0,0}, {16273,16272,16274 ,4472,4471,4473 ,0,0,0}, + {16271,16274,16272 ,4470,4473,4471 ,0,0,0}, {16275,16276,16273 ,4474,4475,4472 ,0,0,0}, + {16273,16274,16275 ,4472,4473,4474 ,0,0,0}, {16276,16277,16278 ,4475,4476,4477 ,0,0,0}, + {16277,16276,16275 ,4476,4475,4474 ,0,0,0}, {16279,16278,16280 ,4478,4477,4479 ,0,0,0}, + {16277,16280,16278 ,4476,4479,4477 ,0,0,0}, {16281,16282,16279 ,4480,4481,4478 ,0,0,0}, + {16279,16280,16281 ,4478,4479,4480 ,0,0,0}, {16282,16283,16284 ,4481,4482,1359 ,0,0,0}, + {16283,16282,16281 ,4482,4481,4480 ,0,0,0}, {16283,16285,16284 ,4482,1359,1359 ,0,0,0}, + {16286,16287,16288 ,4483,4484,4485 ,0,0,0}, {16286,16289,16290 ,4483,4486,4487 ,0,0,0}, + {16289,16291,16290 ,4486,4488,4487 ,0,0,0}, {16288,16289,16286 ,4485,4486,4483 ,0,0,0}, + {16292,16293,16294 ,4489,4490,4491 ,0,0,0}, {16291,16292,16294 ,4488,4489,4491 ,0,0,0}, + {16293,16295,16296 ,4490,4492,4493 ,0,0,0}, {16295,16293,16292 ,4492,4490,4489 ,0,0,0}, + {16296,16295,16297 ,4493,4492,4494 ,0,0,0}, {16298,16296,16297 ,4495,4493,4494 ,0,0,0}, + {16298,16299,16300 ,4495,4496,4497 ,0,0,0}, {16298,16297,16299 ,4495,4494,4496 ,0,0,0}, + {16294,16290,16291 ,4491,4487,4488 ,0,0,0}, {16301,16302,16303 ,4498,4499,82 ,0,0,0}, + {16301,16303,16300 ,4498,82,4497 ,0,0,0}, {16299,16301,16300 ,4496,4498,4497 ,0,0,0}, + {16288,16287,16304 ,4485,4484,4500 ,0,0,0}, {16305,16304,16306 ,4501,4500,4502 ,0,0,0}, + {16287,16306,16304 ,4484,4502,4500 ,0,0,0}, {16307,16308,16305 ,4503,4504,4501 ,0,0,0}, + {16305,16306,16307 ,4501,4502,4503 ,0,0,0}, {16308,16309,16310 ,4504,4505,4506 ,0,0,0}, + {16309,16308,16307 ,4505,4504,4503 ,0,0,0}, {16311,16310,16312 ,4507,4506,4508 ,0,0,0}, + {16309,16312,16310 ,4505,4508,4506 ,0,0,0}, {16313,16314,16311 ,4509,4510,4507 ,0,0,0}, + {16311,16312,16313 ,4507,4508,4509 ,0,0,0}, {16314,16315,16316 ,4510,4511,4512 ,0,0,0}, + {16315,16314,16313 ,4511,4510,4509 ,0,0,0}, {16315,16317,16316 ,4511,4513,4512 ,0,0,0}, + {16318,16319,16320 ,4514,4515,4516 ,0,0,0}, {16321,16322,16323 ,4517,4518,4519 ,0,0,0}, + {16322,16318,16320 ,4518,4514,4516 ,0,0,0}, {16324,16321,16323 ,4520,4517,4519 ,0,0,0}, + {16322,16321,16318 ,4518,4517,4514 ,0,0,0}, {16324,16323,16325 ,4520,4519,4521 ,0,0,0}, + {16325,16326,16327 ,4521,4522,4523 ,0,0,0}, {16328,16327,16326 ,4524,4523,4522 ,0,0,0}, + {16329,16330,16331 ,4525,4526,4527 ,0,0,0}, {16326,16332,16328 ,4522,4528,4524 ,0,0,0}, + {16331,16333,16334 ,4527,4529,4530 ,0,0,0}, {16333,16332,16334 ,4529,4528,4530 ,0,0,0}, + {16328,16332,16333 ,4524,4528,4529 ,0,0,0}, {16331,16334,16329 ,4527,4530,4525 ,0,0,0}, + {16330,16329,16335 ,4526,4525,4531 ,0,0,0}, {16330,16335,16336 ,4526,4531,4532 ,0,0,0}, + {16337,16336,16335 ,4533,4532,4531 ,0,0,0}, {16338,16339,16340 ,4534,4535,4536 ,0,0,0}, + {16340,16336,16337 ,4536,4532,4533 ,0,0,0}, {16338,16340,16337 ,4534,4536,4533 ,0,0,0}, + {16338,16341,16339 ,4534,4537,4535 ,0,0,0}, {16324,16325,16327 ,4520,4521,4523 ,0,0,0}, + {16320,16319,16342 ,4516,4515,4538 ,0,0,0}, {16343,16342,16344 ,4539,4538,4540 ,0,0,0}, + {16319,16344,16342 ,4515,4540,4538 ,0,0,0}, {16345,16346,16343 ,4541,4542,4539 ,0,0,0}, + {16343,16344,16345 ,4539,4540,4541 ,0,0,0}, {16346,16347,16348 ,4542,4543,4544 ,0,0,0}, + {16347,16346,16345 ,4543,4542,4541 ,0,0,0}, {16349,16348,16350 ,4545,4544,4546 ,0,0,0}, + {16347,16350,16348 ,4543,4546,4544 ,0,0,0}, {16351,16352,16349 ,4547,4548,4545 ,0,0,0}, + {16349,16350,16351 ,4545,4546,4547 ,0,0,0}, {16352,16353,16354 ,4548,4549,4550 ,0,0,0}, + {16353,16352,16351 ,4549,4548,4547 ,0,0,0}, {16355,16354,16356 ,4551,4550,4552 ,0,0,0}, + {16353,16356,16354 ,4549,4552,4550 ,0,0,0}, {16357,16358,16355 ,4553,4554,4551 ,0,0,0}, + {16355,16356,16357 ,4551,4552,4553 ,0,0,0}, {16358,16359,16360 ,4554,4555,4556 ,0,0,0}, + {16359,16358,16357 ,4555,4554,4553 ,0,0,0}, {16359,16361,16360 ,4555,126,4556 ,0,0,0}, + {16362,16363,16364 ,4557,4558,4559 ,0,0,0}, {16365,16366,16364 ,4560,4561,4559 ,0,0,0}, + {16362,16364,16366 ,4557,4559,4561 ,0,0,0}, {16367,16365,16368 ,4562,4560,4563 ,0,0,0}, + {16367,16366,16365 ,4562,4561,4560 ,0,0,0}, {16369,16368,16370 ,4564,4563,4565 ,0,0,0}, + {16365,16370,16368 ,4560,4565,4563 ,0,0,0}, {16371,16372,16369 ,4081,4566,4564 ,0,0,0}, + {16369,16370,16371 ,4564,4565,4081 ,0,0,0}, {16372,16373,16374 ,4566,4567,4568 ,0,0,0}, + {16373,16372,16371 ,4567,4566,4081 ,0,0,0}, {16375,16374,16376 ,4569,4568,4570 ,0,0,0}, + {16373,16376,16374 ,4567,4570,4568 ,0,0,0}, {16377,16378,16375 ,4571,4572,4569 ,0,0,0}, + {16375,16376,16377 ,4569,4570,4571 ,0,0,0}, {16379,16380,16378 ,4573,763,4572 ,0,0,0}, + {16379,16378,16377 ,4573,4572,4571 ,0,0,0}, {16380,16381,16378 ,763,763,4572 ,0,0,0}, + {16382,16363,16362 ,4574,4558,4557 ,0,0,0}, {16382,16383,16384 ,4574,4575,4576 ,0,0,0}, + {16384,16363,16382 ,4576,4558,4574 ,0,0,0}, {16385,16386,16383 ,4577,4578,4575 ,0,0,0}, + {16383,16386,16384 ,4575,4578,4576 ,0,0,0}, {16387,16388,16385 ,4579,4580,4577 ,0,0,0}, + {16385,16383,16387 ,4577,4575,4579 ,0,0,0}, {16388,16389,16390 ,4580,4065,4581 ,0,0,0}, + {16389,16388,16387 ,4065,4580,4579 ,0,0,0}, {16391,16390,16392 ,4582,4581,4583 ,0,0,0}, + {16389,16392,16390 ,4065,4583,4581 ,0,0,0}, {16393,16394,16391 ,4584,4585,4582 ,0,0,0}, + {16391,16392,16393 ,4582,4583,4584 ,0,0,0}, {16394,16395,16396 ,4585,4586,4587 ,0,0,0}, + {16395,16394,16393 ,4586,4585,4584 ,0,0,0}, {16396,16397,16398 ,4587,4588,54 ,0,0,0}, + {16395,16397,16396 ,4586,4588,4587 ,0,0,0}, {16396,16398,16399 ,4587,54,4589 ,0,0,0}, + {16400,16401,16402 ,4590,4591,4557 ,0,0,0}, {16403,16401,16404 ,4592,4591,4593 ,0,0,0}, + {16401,16403,16402 ,4591,4592,4557 ,0,0,0}, {16405,16406,16404 ,4594,4595,4593 ,0,0,0}, + {16403,16404,16406 ,4592,4593,4595 ,0,0,0}, {16405,16407,16408 ,4594,4596,4597 ,0,0,0}, + {16408,16406,16405 ,4597,4595,4594 ,0,0,0}, {16409,16407,16410 ,4598,4596,4599 ,0,0,0}, + {16407,16409,16408 ,4596,4598,4597 ,0,0,0}, {16411,16412,16410 ,4600,4601,4599 ,0,0,0}, + {16409,16410,16412 ,4598,4599,4601 ,0,0,0}, {16411,16413,16414 ,4600,4602,4603 ,0,0,0}, + {16414,16412,16411 ,4603,4601,4600 ,0,0,0}, {16415,16413,16416 ,4604,4602,4605 ,0,0,0}, + {16413,16415,16414 ,4602,4604,4603 ,0,0,0}, {16417,16418,16416 ,4606,4607,4605 ,0,0,0}, + {16415,16416,16418 ,4604,4605,4607 ,0,0,0}, {16417,16419,16420 ,4606,4608,4609 ,0,0,0}, + {16420,16418,16417 ,4609,4607,4606 ,0,0,0}, {16421,16419,16422 ,4610,4608,4611 ,0,0,0}, + {16419,16421,16420 ,4608,4610,4609 ,0,0,0}, {16423,16424,16422 ,4612,4613,4611 ,0,0,0}, + {16421,16422,16424 ,4610,4611,4613 ,0,0,0}, {16423,16425,16426 ,4612,4614,4615 ,0,0,0}, + {16426,16424,16423 ,4615,4613,4612 ,0,0,0}, {16427,16425,16428 ,4616,4614,4617 ,0,0,0}, + {16425,16427,16426 ,4614,4616,4615 ,0,0,0}, {16429,16430,16428 ,4618,4619,4617 ,0,0,0}, + {16427,16428,16430 ,4616,4617,4619 ,0,0,0}, {16429,16431,16432 ,4618,4620,4621 ,0,0,0}, + {16432,16430,16429 ,4621,4619,4618 ,0,0,0}, {16431,16433,16432 ,4620,4620,4621 ,0,0,0}, + {16434,16400,16402 ,4622,4590,4557 ,0,0,0}, {16435,16436,16434 ,4623,4624,4622 ,0,0,0}, + {16400,16434,16436 ,4590,4622,4624 ,0,0,0}, {16435,16437,16438 ,4623,4625,4626 ,0,0,0}, + {16438,16436,16435 ,4626,4624,4623 ,0,0,0}, {16439,16437,16440 ,4627,4625,4628 ,0,0,0}, + {16437,16439,16438 ,4625,4627,4626 ,0,0,0}, {16441,16442,16440 ,4629,4630,4628 ,0,0,0}, + {16439,16440,16442 ,4627,4628,4630 ,0,0,0}, {16441,16443,16444 ,4629,4631,4632 ,0,0,0}, + {16444,16442,16441 ,4632,4630,4629 ,0,0,0}, {16445,16443,16446 ,4633,4631,4634 ,0,0,0}, + {16443,16445,16444 ,4631,4633,4632 ,0,0,0}, {16447,16448,16446 ,4635,4636,4634 ,0,0,0}, + {16445,16446,16448 ,4633,4634,4636 ,0,0,0}, {16447,16449,16450 ,4635,4637,4638 ,0,0,0}, + {16450,16448,16447 ,4638,4636,4635 ,0,0,0}, {16451,16449,16452 ,4639,4637,4640 ,0,0,0}, + {16449,16451,16450 ,4637,4639,4638 ,0,0,0}, {16453,16454,16452 ,4641,4642,4640 ,0,0,0}, + {16451,16452,16454 ,4639,4640,4642 ,0,0,0}, {16453,16455,16456 ,4641,4643,4644 ,0,0,0}, + {16456,16454,16453 ,4644,4642,4641 ,0,0,0}, {16457,16455,16458 ,4645,4643,4646 ,0,0,0}, + {16455,16457,16456 ,4643,4645,4644 ,0,0,0}, {16459,16460,16458 ,4647,4648,4646 ,0,0,0}, + {16457,16458,16460 ,4645,4646,4648 ,0,0,0}, {16459,16461,16462 ,4647,4649,4650 ,0,0,0}, + {16462,16460,16459 ,4650,4648,4647 ,0,0,0}, {16463,16461,16464 ,4651,4649,82 ,0,0,0}, + {16461,16463,16462 ,4649,4651,4650 ,0,0,0}, {16463,16464,16465 ,4651,82,4652 ,0,0,0}, + {16466,16467,16468 ,4653,4654,4655 ,0,0,0}, {16469,16470,16471 ,4656,4657,4658 ,0,0,0}, + {16468,16471,16470 ,4655,4658,4657 ,0,0,0}, {16472,16473,16474 ,4659,4660,4661 ,0,0,0}, + {16475,16476,16469 ,4662,4663,4656 ,0,0,0}, {16472,16476,16475 ,4659,4663,4662 ,0,0,0}, + {16475,16473,16472 ,4662,4660,4659 ,0,0,0}, {16476,16470,16469 ,4663,4657,4656 ,0,0,0}, + {16477,16478,16479 ,4664,4665,4666 ,0,0,0}, {16478,16480,16479 ,4665,4667,4666 ,0,0,0}, + {16481,16482,16483 ,4668,4669,4670 ,0,0,0}, {16481,16483,16480 ,4668,4670,4667 ,0,0,0}, + {16478,16481,16480 ,4665,4668,4667 ,0,0,0}, {16473,16477,16474 ,4660,4664,4661 ,0,0,0}, + {16477,16479,16474 ,4664,4666,4661 ,0,0,0}, {16484,16485,16486 ,4671,4672,4673 ,0,0,0}, + {16487,16488,16489 ,4674,4675,4676 ,0,0,0}, {16486,16485,16487 ,4673,4672,4674 ,0,0,0}, + {16490,16491,16492 ,4677,4678,4679 ,0,0,0}, {16486,16487,16489 ,4673,4674,4676 ,0,0,0}, + {16492,16491,16488 ,4679,4678,4675 ,0,0,0}, {16491,16489,16488 ,4678,4676,4675 ,0,0,0}, + {16482,16485,16484 ,4669,4672,4671 ,0,0,0}, {16493,16490,16492 ,4677,4677,4679 ,0,0,0}, + {16483,16482,16484 ,4670,4669,4671 ,0,0,0}, {16467,16471,16468 ,4654,4658,4655 ,0,0,0}, + {16494,16467,16466 ,4680,4654,4653 ,0,0,0}, {16494,16495,16496 ,4680,4681,4682 ,0,0,0}, + {16495,16494,16466 ,4681,4680,4653 ,0,0,0}, {16497,16496,16498 ,4683,4682,4684 ,0,0,0}, + {16495,16498,16496 ,4681,4684,4682 ,0,0,0}, {16499,16500,16497 ,4685,4686,4683 ,0,0,0}, + {16497,16498,16499 ,4683,4684,4685 ,0,0,0}, {16500,16501,16502 ,4686,4687,4688 ,0,0,0}, + {16501,16500,16499 ,4687,4686,4685 ,0,0,0}, {16503,16502,16504 ,4689,4688,4690 ,0,0,0}, + {16501,16504,16502 ,4687,4690,4688 ,0,0,0}, {16505,16506,16503 ,4691,4692,4689 ,0,0,0}, + {16503,16504,16505 ,4689,4690,4691 ,0,0,0}, {16506,16507,16508 ,4692,4693,4694 ,0,0,0}, + {16507,16506,16505 ,4693,4692,4691 ,0,0,0}, {16509,16508,16510 ,4695,4694,4696 ,0,0,0}, + {16507,16510,16508 ,4693,4696,4694 ,0,0,0}, {16511,16512,16509 ,4697,4698,4695 ,0,0,0}, + {16509,16510,16511 ,4695,4696,4697 ,0,0,0}, {16512,16513,16514 ,4698,4699,4700 ,0,0,0}, + {16513,16512,16511 ,4699,4698,4697 ,0,0,0}, {16513,16515,16514 ,4699,4701,4700 ,0,0,0}, + {16516,16517,16518 ,4702,4703,4704 ,0,0,0}, {16519,16520,16521 ,4705,4706,4707 ,0,0,0}, + {16517,16521,16520 ,4703,4707,4706 ,0,0,0}, {16522,16523,16524 ,4708,4709,4710 ,0,0,0}, + {16525,16519,16526 ,4711,4705,4712 ,0,0,0}, {16522,16525,16526 ,4708,4711,4712 ,0,0,0}, + {16525,16522,16524 ,4711,4708,4710 ,0,0,0}, {16526,16519,16521 ,4712,4705,4707 ,0,0,0}, + {16527,16528,16529 ,4713,4714,4715 ,0,0,0}, {16529,16528,16530 ,4715,4714,4716 ,0,0,0}, + {16531,16532,16533 ,4717,4718,4719 ,0,0,0}, {16531,16530,16532 ,4717,4716,4718 ,0,0,0}, + {16529,16530,16531 ,4715,4716,4717 ,0,0,0}, {16524,16523,16527 ,4710,4709,4713 ,0,0,0}, + {16527,16523,16528 ,4713,4709,4714 ,0,0,0}, {16534,16535,16536 ,4720,4721,4722 ,0,0,0}, + {16537,16538,16539 ,4723,4724,4725 ,0,0,0}, {16535,16537,16536 ,4721,4723,4722 ,0,0,0}, + {16540,16541,16542 ,4726,4727,4728 ,0,0,0}, {16535,16538,16537 ,4721,4724,4723 ,0,0,0}, + {16541,16539,16542 ,4727,4725,4728 ,0,0,0}, {16542,16539,16538 ,4728,4725,4724 ,0,0,0}, + {16533,16534,16536 ,4719,4720,4722 ,0,0,0}, {16543,16541,16540 ,4726,4727,4726 ,0,0,0}, + {16532,16534,16533 ,4718,4720,4719 ,0,0,0}, {16518,16517,16520 ,4704,4703,4706 ,0,0,0}, + {16544,16516,16518 ,4729,4702,4704 ,0,0,0}, {16544,16545,16546 ,4729,4730,4731 ,0,0,0}, + {16546,16516,16544 ,4731,4702,4729 ,0,0,0}, {16547,16548,16545 ,4732,4733,4730 ,0,0,0}, + {16546,16545,16548 ,4731,4730,4733 ,0,0,0}, {16549,16547,16550 ,4734,4732,4735 ,0,0,0}, + {16547,16549,16548 ,4732,4734,4733 ,0,0,0}, {16550,16551,16552 ,4735,4736,4737 ,0,0,0}, + {16552,16549,16550 ,4737,4734,4735 ,0,0,0}, {16553,16554,16551 ,4738,4739,4736 ,0,0,0}, + {16552,16551,16554 ,4737,4736,4739 ,0,0,0}, {16555,16553,16556 ,4740,4738,4741 ,0,0,0}, + {16553,16555,16554 ,4738,4740,4739 ,0,0,0}, {16556,16557,16558 ,4741,4742,4743 ,0,0,0}, + {16558,16555,16556 ,4743,4740,4741 ,0,0,0}, {16559,16560,16557 ,4744,4745,4742 ,0,0,0}, + {16558,16557,16560 ,4743,4742,4745 ,0,0,0}, {16561,16559,16562 ,4746,4744,4747 ,0,0,0}, + {16559,16561,16560 ,4744,4746,4745 ,0,0,0}, {16562,16563,16564 ,4747,4748,4749 ,0,0,0}, + {16564,16561,16562 ,4749,4746,4747 ,0,0,0}, {16564,16563,16565 ,4749,4748,4750 ,0,0,0}, + {16566,16567,16568 ,4751,4752,4753 ,0,0,0}, {16569,16570,16571 ,4754,4755,4756 ,0,0,0}, + {16567,16571,16570 ,4752,4756,4755 ,0,0,0}, {16572,16573,16574 ,4757,4758,4759 ,0,0,0}, + {16575,16569,16576 ,4760,4754,4761 ,0,0,0}, {16575,16576,16572 ,4760,4761,4757 ,0,0,0}, + {16572,16574,16575 ,4757,4759,4760 ,0,0,0}, {16569,16571,16576 ,4754,4756,4761 ,0,0,0}, + {16577,16578,16579 ,4762,4763,4764 ,0,0,0}, {16580,16578,16577 ,4765,4763,4762 ,0,0,0}, + {16581,16582,16583 ,4766,4767,4768 ,0,0,0}, {16581,16583,16580 ,4766,4768,4765 ,0,0,0}, + {16580,16583,16578 ,4765,4768,4763 ,0,0,0}, {16573,16579,16574 ,4758,4764,4759 ,0,0,0}, + {16577,16579,16573 ,4762,4764,4758 ,0,0,0}, {16584,16585,16586 ,4769,4770,4771 ,0,0,0}, + {16587,16588,16589 ,4772,4773,4774 ,0,0,0}, {16586,16585,16589 ,4771,4770,4774 ,0,0,0}, + {16590,16591,16592 ,4775,4776,4777 ,0,0,0}, {16585,16587,16589 ,4770,4772,4774 ,0,0,0}, + {16590,16588,16591 ,4775,4773,4776 ,0,0,0}, {16588,16587,16591 ,4773,4772,4776 ,0,0,0}, + {16584,16586,16582 ,4769,4771,4767 ,0,0,0}, {16593,16590,16592 ,4777,4775,4777 ,0,0,0}, + {16581,16584,16582 ,4766,4769,4767 ,0,0,0}, {16567,16570,16568 ,4752,4755,4753 ,0,0,0}, + {16566,16568,16594 ,4751,4753,4778 ,0,0,0}, {16594,16595,16596 ,4778,4779,4780 ,0,0,0}, + {16596,16566,16594 ,4780,4751,4778 ,0,0,0}, {16597,16595,16598 ,4781,4779,4782 ,0,0,0}, + {16595,16597,16596 ,4779,4781,4780 ,0,0,0}, {16599,16600,16598 ,4783,4784,4782 ,0,0,0}, + {16597,16598,16600 ,4781,4782,4784 ,0,0,0}, {16599,16601,16602 ,4783,4785,4786 ,0,0,0}, + {16602,16600,16599 ,4786,4784,4783 ,0,0,0}, {16603,16601,16604 ,4787,4785,4788 ,0,0,0}, + {16601,16603,16602 ,4785,4787,4786 ,0,0,0}, {16605,16606,16604 ,4789,4790,4788 ,0,0,0}, + {16603,16604,16606 ,4787,4788,4790 ,0,0,0}, {16605,16607,16608 ,4789,4791,4792 ,0,0,0}, + {16608,16606,16605 ,4792,4790,4789 ,0,0,0}, {16609,16607,16610 ,4793,4791,4794 ,0,0,0}, + {16607,16609,16608 ,4791,4793,4792 ,0,0,0}, {16611,16612,16610 ,4795,4796,4794 ,0,0,0}, + {16609,16610,16612 ,4793,4794,4796 ,0,0,0}, {16611,16613,16614 ,4795,4797,4798 ,0,0,0}, + {16614,16612,16611 ,4798,4796,4795 ,0,0,0}, {16613,16615,16614 ,4797,4799,4798 ,0,0,0}, + {16613,16616,16615 ,4797,324,4799 ,0,0,0}, {16617,16618,16619 ,82,4800,4801 ,0,0,0}, + {16619,16620,16621 ,4801,4802,4803 ,0,0,0}, {16620,16622,16621 ,4802,4804,4803 ,0,0,0}, + {16619,16621,16617 ,4801,4803,82 ,0,0,0}, {16623,16624,16625 ,4805,4806,4807 ,0,0,0}, + {16625,16624,16622 ,4807,4806,4804 ,0,0,0}, {16623,16626,16627 ,4805,4808,4809 ,0,0,0}, + {16627,16624,16623 ,4809,4806,4805 ,0,0,0}, {16627,16626,16628 ,4809,4808,4810 ,0,0,0}, + {16628,16626,16629 ,4810,4808,4811 ,0,0,0}, {16629,16630,16631 ,4811,4812,4813 ,0,0,0}, + {16628,16629,16631 ,4810,4811,4813 ,0,0,0}, {16622,16620,16625 ,4804,4802,4807 ,0,0,0}, + {16632,16633,16634 ,4814,4815,4816 ,0,0,0}, {16632,16634,16630 ,4814,4816,4812 ,0,0,0}, + {16630,16634,16631 ,4812,4816,4813 ,0,0,0}, {16617,16635,16618 ,82,4817,4800 ,0,0,0}, + {16636,16635,16637 ,4818,4817,4819 ,0,0,0}, {16635,16636,16618 ,4817,4818,4800 ,0,0,0}, + {16638,16639,16637 ,4820,4821,4819 ,0,0,0}, {16636,16637,16639 ,4818,4819,4821 ,0,0,0}, + {16638,16640,16641 ,4820,4822,4823 ,0,0,0}, {16641,16639,16638 ,4823,4821,4820 ,0,0,0}, + {16642,16640,16643 ,4824,4822,4825 ,0,0,0}, {16640,16642,16641 ,4822,4824,4823 ,0,0,0}, + {16644,16645,16643 ,4826,4827,4825 ,0,0,0}, {16642,16643,16645 ,4824,4825,4827 ,0,0,0}, + {16644,16646,16647 ,4826,4828,4829 ,0,0,0}, {16647,16645,16644 ,4829,4827,4826 ,0,0,0}, + {16648,16646,16649 ,4830,4828,4831 ,0,0,0}, {16646,16648,16647 ,4828,4830,4829 ,0,0,0}, + {16644,16643,16650 ,4832,4833,4834 ,0,0,0}, {16650,16646,16644 ,4834,4835,4832 ,0,0,0}, + {16650,16649,16646 ,4834,4836,4835 ,0,0,0}, {16650,16640,16638 ,4834,4837,4838 ,0,0,0}, + {16643,16640,16650 ,4833,4837,4834 ,0,0,0}, {16650,16637,16635 ,4834,4839,4840 ,0,0,0}, + {16638,16637,16650 ,4838,4839,4834 ,0,0,0}, {16635,16617,16650 ,4840,4841,4834 ,0,0,0}, + {16622,16650,16621 ,4842,4834,4843 ,0,0,0}, {16650,16617,16621 ,4834,4841,4843 ,0,0,0}, + {16627,16650,16624 ,4844,4834,4845 ,0,0,0}, {16650,16622,16624 ,4834,4842,4845 ,0,0,0}, + {16631,16650,16628 ,4846,4834,4847 ,0,0,0}, {16650,16627,16628 ,4834,4844,4847 ,0,0,0}, + {16633,16650,16634 ,4848,4834,4849 ,0,0,0}, {16650,16631,16634 ,4834,4846,4849 ,0,0,0}, + {16651,16652,16653 ,82,4850,4851 ,0,0,0}, {16653,16654,16655 ,4851,4852,4853 ,0,0,0}, + {16654,16656,16655 ,4852,4854,4853 ,0,0,0}, {16653,16655,16651 ,4851,4853,82 ,0,0,0}, + {16657,16658,16659 ,4855,4856,4857 ,0,0,0}, {16659,16658,16656 ,4857,4856,4854 ,0,0,0}, + {16657,16660,16661 ,4855,4858,4859 ,0,0,0}, {16661,16658,16657 ,4859,4856,4855 ,0,0,0}, + {16661,16660,16662 ,4859,4858,4860 ,0,0,0}, {16662,16660,16663 ,4860,4858,4861 ,0,0,0}, + {16663,16664,16665 ,4861,4862,4863 ,0,0,0}, {16662,16663,16665 ,4860,4861,4863 ,0,0,0}, + {16656,16654,16659 ,4854,4852,4857 ,0,0,0}, {16666,16667,16668 ,4864,4865,4866 ,0,0,0}, + {16666,16668,16664 ,4864,4866,4862 ,0,0,0}, {16664,16668,16665 ,4862,4866,4863 ,0,0,0}, + {16651,16669,16652 ,82,4867,4850 ,0,0,0}, {16670,16669,16671 ,4868,4867,4869 ,0,0,0}, + {16669,16670,16652 ,4867,4868,4850 ,0,0,0}, {16672,16673,16671 ,4870,4871,4869 ,0,0,0}, + {16670,16671,16673 ,4868,4869,4871 ,0,0,0}, {16672,16674,16675 ,4870,4872,4873 ,0,0,0}, + {16675,16673,16672 ,4873,4871,4870 ,0,0,0}, {16676,16674,16677 ,4874,4872,4875 ,0,0,0}, + {16674,16676,16675 ,4872,4874,4873 ,0,0,0}, {16678,16679,16677 ,4876,4877,4875 ,0,0,0}, + {16676,16677,16679 ,4874,4875,4877 ,0,0,0}, {16678,16680,16681 ,4876,4878,4829 ,0,0,0}, + {16681,16679,16678 ,4829,4877,4876 ,0,0,0}, {16682,16680,16683 ,4879,4878,4831 ,0,0,0}, + {16680,16682,16681 ,4878,4879,4829 ,0,0,0}, {16678,16677,16684 ,4832,4833,4880 ,0,0,0}, + {16684,16680,16678 ,4880,4835,4832 ,0,0,0}, {16684,16683,16680 ,4880,4881,4835 ,0,0,0}, + {16684,16674,16672 ,4880,4837,4838 ,0,0,0}, {16677,16674,16684 ,4833,4837,4880 ,0,0,0}, + {16684,16671,16669 ,4880,4839,4840 ,0,0,0}, {16672,16671,16684 ,4838,4839,4880 ,0,0,0}, + {16669,16651,16684 ,4840,4882,4880 ,0,0,0}, {16656,16684,16655 ,4842,4880,4843 ,0,0,0}, + {16684,16651,16655 ,4880,4882,4843 ,0,0,0}, {16661,16684,16658 ,4844,4880,4845 ,0,0,0}, + {16684,16656,16658 ,4880,4842,4845 ,0,0,0}, {16665,16684,16662 ,4846,4880,4847 ,0,0,0}, + {16684,16661,16662 ,4880,4844,4847 ,0,0,0}, {16667,16684,16668 ,4883,4880,4849 ,0,0,0}, + {16684,16665,16668 ,4880,4846,4849 ,0,0,0}, {16685,16686,16687 ,4884,4885,4886 ,0,0,0}, + {16687,16688,16689 ,4886,4887,4888 ,0,0,0}, {16688,16690,16689 ,4887,4889,4888 ,0,0,0}, + {16687,16689,16685 ,4886,4888,4884 ,0,0,0}, {16691,16692,16693 ,4890,4891,4857 ,0,0,0}, + {16693,16692,16690 ,4857,4891,4889 ,0,0,0}, {16691,16694,16695 ,4890,4892,4893 ,0,0,0}, + {16695,16692,16691 ,4893,4891,4890 ,0,0,0}, {16695,16694,16696 ,4893,4892,4894 ,0,0,0}, + {16696,16694,16697 ,4894,4892,4895 ,0,0,0}, {16697,16698,16699 ,4895,4896,4897 ,0,0,0}, + {16696,16697,16699 ,4894,4895,4897 ,0,0,0}, {16690,16688,16693 ,4889,4887,4857 ,0,0,0}, + {16700,16701,16702 ,4898,4899,4900 ,0,0,0}, {16700,16702,16698 ,4898,4900,4896 ,0,0,0}, + {16698,16702,16699 ,4896,4900,4897 ,0,0,0}, {16685,16703,16686 ,4884,4901,4885 ,0,0,0}, + {16704,16703,16705 ,4868,4901,4902 ,0,0,0}, {16703,16704,16686 ,4901,4868,4885 ,0,0,0}, + {16706,16707,16705 ,4820,4903,4902 ,0,0,0}, {16704,16705,16707 ,4868,4902,4903 ,0,0,0}, + {16706,16708,16709 ,4820,4904,4905 ,0,0,0}, {16709,16707,16706 ,4905,4903,4820 ,0,0,0}, + {16710,16708,16711 ,4906,4904,4907 ,0,0,0}, {16708,16710,16709 ,4904,4906,4905 ,0,0,0}, + {16712,16713,16711 ,4826,4877,4907 ,0,0,0}, {16710,16711,16713 ,4906,4907,4877 ,0,0,0}, + {16712,16714,16715 ,4826,4828,4908 ,0,0,0}, {16715,16713,16712 ,4908,4877,4826 ,0,0,0}, + {16716,16714,16717 ,4909,4828,4910 ,0,0,0}, {16714,16716,16715 ,4828,4909,4908 ,0,0,0}, + {16712,16711,16718 ,4832,4833,4880 ,0,0,0}, {16718,16714,16712 ,4880,4835,4832 ,0,0,0}, + {16718,16717,16714 ,4880,4911,4835 ,0,0,0}, {16718,16708,16706 ,4880,4837,4838 ,0,0,0}, + {16711,16708,16718 ,4833,4837,4880 ,0,0,0}, {16718,16705,16703 ,4880,4839,4840 ,0,0,0}, + {16706,16705,16718 ,4838,4839,4880 ,0,0,0}, {16703,16685,16718 ,4840,4912,4880 ,0,0,0}, + {16690,16718,16689 ,4842,4880,4843 ,0,0,0}, {16718,16685,16689 ,4880,4912,4843 ,0,0,0}, + {16695,16718,16692 ,4844,4880,4845 ,0,0,0}, {16718,16690,16692 ,4880,4842,4845 ,0,0,0}, + {16699,16718,16696 ,4846,4880,4847 ,0,0,0}, {16718,16695,16696 ,4880,4844,4847 ,0,0,0}, + {16701,16718,16702 ,4913,4880,4849 ,0,0,0}, {16718,16699,16702 ,4880,4846,4849 ,0,0,0}, + {16719,16720,16721 ,4914,4915,4916 ,0,0,0}, {16721,16722,16723 ,4916,4917,4918 ,0,0,0}, + {16722,16724,16723 ,4917,4919,4918 ,0,0,0}, {16721,16723,16719 ,4916,4918,4914 ,0,0,0}, + {16725,16726,16727 ,4920,4921,4922 ,0,0,0}, {16727,16726,16724 ,4922,4921,4919 ,0,0,0}, + {16725,16728,16729 ,4920,4923,4924 ,0,0,0}, {16729,16726,16725 ,4924,4921,4920 ,0,0,0}, + {16729,16728,16730 ,4924,4923,4925 ,0,0,0}, {16730,16728,16731 ,4925,4923,4926 ,0,0,0}, + {16731,16732,16733 ,4926,4927,4928 ,0,0,0}, {16730,16731,16733 ,4925,4926,4928 ,0,0,0}, + {16724,16722,16727 ,4919,4917,4922 ,0,0,0}, {16734,16735,16736 ,4929,4815,4930 ,0,0,0}, + {16734,16736,16732 ,4929,4930,4927 ,0,0,0}, {16732,16736,16733 ,4927,4930,4928 ,0,0,0}, + {16719,16737,16720 ,4914,4931,4915 ,0,0,0}, {16738,16737,16739 ,4932,4931,4933 ,0,0,0}, + {16737,16738,16720 ,4931,4932,4915 ,0,0,0}, {16740,16741,16739 ,4934,4821,4933 ,0,0,0}, + {16738,16739,16741 ,4932,4933,4821 ,0,0,0}, {16740,16742,16743 ,4934,4935,4936 ,0,0,0}, + {16743,16741,16740 ,4936,4821,4934 ,0,0,0}, {16744,16742,16745 ,4937,4935,4938 ,0,0,0}, + {16742,16744,16743 ,4935,4937,4936 ,0,0,0}, {16746,16747,16745 ,4826,4877,4938 ,0,0,0}, + {16744,16745,16747 ,4937,4938,4877 ,0,0,0}, {16746,16748,16749 ,4826,4939,4940 ,0,0,0}, + {16749,16747,16746 ,4940,4877,4826 ,0,0,0}, {16750,16748,16751 ,4941,4939,4942 ,0,0,0}, + {16748,16750,16749 ,4939,4941,4940 ,0,0,0}, {16746,16745,16752 ,4832,4833,4943 ,0,0,0}, + {16752,16748,16746 ,4943,4835,4832 ,0,0,0}, {16752,16751,16748 ,4943,4944,4835 ,0,0,0}, + {16752,16742,16740 ,4943,4837,4838 ,0,0,0}, {16745,16742,16752 ,4833,4837,4943 ,0,0,0}, + {16752,16739,16737 ,4943,4839,4840 ,0,0,0}, {16740,16739,16752 ,4838,4839,4943 ,0,0,0}, + {16737,16719,16752 ,4840,4945,4943 ,0,0,0}, {16724,16752,16723 ,4842,4943,4843 ,0,0,0}, + {16752,16719,16723 ,4943,4945,4843 ,0,0,0}, {16729,16752,16726 ,4844,4943,4845 ,0,0,0}, + {16752,16724,16726 ,4943,4842,4845 ,0,0,0}, {16733,16752,16730 ,4846,4943,4847 ,0,0,0}, + {16752,16729,16730 ,4943,4844,4847 ,0,0,0}, {16735,16752,16736 ,4946,4943,4849 ,0,0,0}, + {16752,16733,16736 ,4943,4846,4849 ,0,0,0}, {16753,16754,16755 ,4947,4948,4949 ,0,0,0}, + {16756,16757,16758 ,4950,4951,4952 ,0,0,0}, {16755,16758,16757 ,4949,4952,4951 ,0,0,0}, + {16759,16760,16761 ,4953,4954,4955 ,0,0,0}, {16762,16763,16756 ,4956,4957,4950 ,0,0,0}, + {16759,16763,16762 ,4953,4957,4956 ,0,0,0}, {16762,16760,16759 ,4956,4954,4953 ,0,0,0}, + {16763,16757,16756 ,4957,4951,4950 ,0,0,0}, {16764,16765,16766 ,4958,4959,4960 ,0,0,0}, + {16765,16767,16766 ,4959,4961,4960 ,0,0,0}, {16768,16769,16770 ,4962,4963,4964 ,0,0,0}, + {16768,16770,16767 ,4962,4964,4961 ,0,0,0}, {16765,16768,16767 ,4959,4962,4961 ,0,0,0}, + {16760,16764,16761 ,4954,4958,4955 ,0,0,0}, {16764,16766,16761 ,4958,4960,4955 ,0,0,0}, + {16771,16772,16773 ,4965,4966,4967 ,0,0,0}, {16774,16775,16776 ,4968,4969,4970 ,0,0,0}, + {16773,16772,16774 ,4967,4966,4968 ,0,0,0}, {16777,16778,16779 ,4726,4971,4972 ,0,0,0}, + {16773,16774,16776 ,4967,4968,4970 ,0,0,0}, {16779,16778,16775 ,4972,4971,4969 ,0,0,0}, + {16778,16776,16775 ,4971,4970,4969 ,0,0,0}, {16769,16772,16771 ,4963,4966,4965 ,0,0,0}, + {16780,16777,16779 ,4726,4726,4972 ,0,0,0}, {16770,16769,16771 ,4964,4963,4965 ,0,0,0}, + {16754,16758,16755 ,4948,4952,4949 ,0,0,0}, {16781,16754,16753 ,4973,4948,4947 ,0,0,0}, + {16781,16782,16783 ,4973,4974,4975 ,0,0,0}, {16782,16781,16753 ,4974,4973,4947 ,0,0,0}, + {16784,16783,16785 ,4976,4975,4977 ,0,0,0}, {16782,16785,16783 ,4974,4977,4975 ,0,0,0}, + {16786,16787,16784 ,4978,4979,4976 ,0,0,0}, {16784,16785,16786 ,4976,4977,4978 ,0,0,0}, + {16787,16788,16789 ,4979,4980,4981 ,0,0,0}, {16788,16787,16786 ,4980,4979,4978 ,0,0,0}, + {16790,16789,16791 ,4982,4981,4983 ,0,0,0}, {16788,16791,16789 ,4980,4983,4981 ,0,0,0}, + {16792,16793,16790 ,4984,4985,4982 ,0,0,0}, {16790,16791,16792 ,4982,4983,4984 ,0,0,0}, + {16793,16794,16795 ,4985,4986,4987 ,0,0,0}, {16794,16793,16792 ,4986,4985,4984 ,0,0,0}, + {16796,16795,16797 ,4988,4987,4989 ,0,0,0}, {16794,16797,16795 ,4986,4989,4987 ,0,0,0}, + {16798,16799,16796 ,4990,4991,4988 ,0,0,0}, {16796,16797,16798 ,4988,4989,4990 ,0,0,0}, + {16799,16800,16801 ,4991,4992,4748 ,0,0,0}, {16800,16799,16798 ,4992,4991,4990 ,0,0,0}, + {16800,16802,16801 ,4992,4750,4748 ,0,0,0}, {16803,16804,16805 ,4993,4994,4995 ,0,0,0}, + {16806,16807,16808 ,4996,4997,4998 ,0,0,0}, {16804,16809,16810 ,4994,4999,5000 ,0,0,0}, + {16809,16804,16803 ,4999,4994,4993 ,0,0,0}, {16809,16811,16810 ,4999,5001,5000 ,0,0,0}, + {16805,16812,16803 ,4995,5002,4993 ,0,0,0}, {16806,16812,16813 ,4996,5002,5003 ,0,0,0}, + {16805,16813,16812 ,4995,5003,5002 ,0,0,0}, {16814,16815,16816 ,5004,5005,5006 ,0,0,0}, + {16806,16813,16807 ,4996,5003,4997 ,0,0,0}, {16817,16818,16819 ,5007,5008,5009 ,0,0,0}, + {16820,16821,16822 ,5010,5011,5012 ,0,0,0}, {16823,16824,16825 ,5013,5014,5015 ,0,0,0}, + {16826,16827,16828 ,5016,5017,5018 ,0,0,0}, {16829,16830,16831 ,5019,5020,5021 ,0,0,0}, + {16832,16833,16824 ,5022,5023,5014 ,0,0,0}, {16834,16835,16836 ,5024,5025,5026 ,0,0,0}, + {16835,16830,16837 ,5025,5020,5027 ,0,0,0}, {16838,16839,16840 ,5028,5029,5030 ,0,0,0}, + {16841,16842,16834 ,5031,5032,5024 ,0,0,0}, {16843,16844,16845 ,5033,5034,5035 ,0,0,0}, + {16846,16840,16847 ,5036,5030,5037 ,0,0,0}, {16848,16849,16850 ,5038,5039,5040 ,0,0,0}, + {16851,16849,16852 ,5041,5039,5042 ,0,0,0}, {16853,16854,16855 ,5043,5044,5045 ,0,0,0}, + {16850,16856,16853 ,5040,5046,5043 ,0,0,0}, {16857,16858,16859 ,5047,5048,5049 ,0,0,0}, + {16857,16860,16861 ,5047,5050,5051 ,0,0,0}, {16862,16863,16864 ,5052,5053,5054 ,0,0,0}, + {16865,16866,16864 ,5055,5056,5054 ,0,0,0}, {16867,16868,16869 ,5057,5058,5059 ,0,0,0}, + {16868,16862,16870 ,5058,5052,5060 ,0,0,0}, {16871,16872,16873 ,5061,5062,5063 ,0,0,0}, + {16867,16874,16871 ,5057,5064,5061 ,0,0,0}, {16875,16876,16877 ,5065,5066,5067 ,0,0,0}, + {16875,16878,16879 ,5065,5068,5069 ,0,0,0}, {16880,16881,16882 ,5070,5071,5072 ,0,0,0}, + {16880,16883,16876 ,5070,5073,5066 ,0,0,0}, {16884,16881,16885 ,5074,5071,5075 ,0,0,0}, + {16881,16884,16882 ,5071,5074,5072 ,0,0,0}, {16886,16887,16885 ,5076,5077,5075 ,0,0,0}, + {16884,16885,16887 ,5074,5075,5077 ,0,0,0}, {16888,16889,16887 ,5078,5079,5077 ,0,0,0}, + {16887,16886,16888 ,5077,5076,5078 ,0,0,0}, {16889,16890,16891 ,5079,5080,5081 ,0,0,0}, + {16890,16889,16888 ,5080,5079,5078 ,0,0,0}, {16892,16891,16893 ,5082,5081,5083 ,0,0,0}, + {16890,16893,16891 ,5080,5083,5081 ,0,0,0}, {16894,16895,16892 ,5084,5085,5082 ,0,0,0}, + {16892,16893,16894 ,5082,5083,5084 ,0,0,0}, {16895,16896,16897 ,5085,5086,5087 ,0,0,0}, + {16896,16895,16894 ,5086,5085,5084 ,0,0,0}, {16898,16897,16899 ,5088,5087,5089 ,0,0,0}, + {16896,16899,16897 ,5086,5089,5087 ,0,0,0}, {16900,16898,16901 ,5090,5088,5091 ,0,0,0}, + {16898,16899,16901 ,5088,5089,5091 ,0,0,0}, {16900,16902,16903 ,5090,5092,5093 ,0,0,0}, + {16903,16898,16900 ,5093,5088,5090 ,0,0,0}, {16904,16902,16905 ,5094,5092,5095 ,0,0,0}, + {16902,16904,16903 ,5092,5094,5093 ,0,0,0}, {16906,16907,16905 ,126,5096,5095 ,0,0,0}, + {16904,16905,16907 ,5094,5095,5096 ,0,0,0}, {16908,16907,16906 ,126,5096,126 ,0,0,0}, + {16877,16876,16883 ,5067,5066,5073 ,0,0,0}, {16880,16882,16883 ,5070,5072,5073 ,0,0,0}, + {16873,16878,16871 ,5063,5068,5061 ,0,0,0}, {16875,16877,16878 ,5065,5067,5068 ,0,0,0}, + {16873,16879,16878 ,5063,5069,5068 ,0,0,0}, {16869,16874,16867 ,5059,5064,5057 ,0,0,0}, + {16871,16874,16872 ,5061,5064,5062 ,0,0,0}, {16863,16862,16868 ,5053,5052,5058 ,0,0,0}, + {16868,16870,16869 ,5058,5060,5059 ,0,0,0}, {16865,16858,16866 ,5055,5048,5056 ,0,0,0}, + {16863,16865,16864 ,5053,5055,5054 ,0,0,0}, {16857,16859,16860 ,5047,5049,5050 ,0,0,0}, + {16858,16865,16859 ,5048,5055,5049 ,0,0,0}, {16854,16861,16855 ,5044,5051,5045 ,0,0,0}, + {16861,16860,16855 ,5051,5050,5045 ,0,0,0}, {16850,16853,16848 ,5040,5043,5038 ,0,0,0}, + {16856,16854,16853 ,5046,5044,5043 ,0,0,0}, {16843,16851,16844 ,5033,5041,5034 ,0,0,0}, + {16852,16849,16848 ,5042,5039,5038 ,0,0,0}, {16844,16851,16852 ,5034,5041,5042 ,0,0,0}, + {16845,16846,16847 ,5035,5036,5037 ,0,0,0}, {16844,16846,16845 ,5034,5036,5035 ,0,0,0}, + {16840,16842,16838 ,5030,5032,5028 ,0,0,0}, {16847,16840,16839 ,5037,5030,5029 ,0,0,0}, + {16909,16841,16834 ,5097,5031,5024 ,0,0,0}, {16841,16838,16842 ,5031,5028,5032 ,0,0,0}, + {16910,16835,16837 ,5098,5025,5027 ,0,0,0}, {16834,16836,16909 ,5024,5026,5097 ,0,0,0}, + {16835,16910,16836 ,5025,5098,5026 ,0,0,0}, {16831,16832,16829 ,5021,5022,5019 ,0,0,0}, + {16837,16830,16829 ,5027,5020,5019 ,0,0,0}, {16825,16828,16823 ,5015,5018,5013 ,0,0,0}, + {16832,16831,16833 ,5022,5021,5023 ,0,0,0}, {16824,16833,16825 ,5014,5023,5015 ,0,0,0}, + {16817,16826,16828 ,5007,5016,5018 ,0,0,0}, {16827,16823,16828 ,5017,5013,5018 ,0,0,0}, + {16818,16822,16819 ,5008,5012,5009 ,0,0,0}, {16817,16819,16826 ,5007,5009,5016 ,0,0,0}, + {16820,16814,16821 ,5010,5004,5011 ,0,0,0}, {16818,16820,16822 ,5008,5010,5012 ,0,0,0}, + {16816,16815,16808 ,5006,5005,4998 ,0,0,0}, {16821,16814,16816 ,5011,5004,5006 ,0,0,0}, + {16806,16808,16815 ,4996,4998,5005 ,0,0,0}, {16911,16912,16913 ,5099,5100,5101 ,0,0,0}, + {16914,16915,16916 ,5102,5103,5104 ,0,0,0}, {16917,16915,16914 ,5105,5103,5102 ,0,0,0}, + {16918,16914,16916 ,5106,5102,5104 ,0,0,0}, {16919,16920,16921 ,5107,5108,5109 ,0,0,0}, + {16922,16923,16918 ,5110,5108,5106 ,0,0,0}, {16920,16924,16921 ,5108,5111,5109 ,0,0,0}, + {16920,16923,16924 ,5108,5108,5111 ,0,0,0}, {16924,16925,16926 ,5111,5112,5113 ,0,0,0}, + {16925,16927,16926 ,5112,5114,5113 ,0,0,0}, {16926,16927,16928 ,5113,5114,5115 ,0,0,0}, + {16927,16929,16928 ,5114,5116,5115 ,0,0,0}, {16930,16931,16929 ,5117,5118,5116 ,0,0,0}, + {16930,16932,16933 ,5117,5119,5120 ,0,0,0}, {16934,16933,16932 ,5121,5120,5119 ,0,0,0}, + {16934,16932,16935 ,5121,5119,5122 ,0,0,0}, {16935,16936,16934 ,5122,5123,5121 ,0,0,0}, + {16931,16928,16929 ,5118,5115,5116 ,0,0,0}, {16933,16931,16930 ,5120,5118,5117 ,0,0,0}, + {16936,16937,16938 ,5123,5124,5125 ,0,0,0}, {16937,16936,16935 ,5124,5123,5122 ,0,0,0}, + {16515,16938,16937 ,5126,5125,5124 ,0,0,0}, {16917,16914,16939 ,5105,5102,5127 ,0,0,0}, + {16940,16941,16942 ,5128,5129,5130 ,0,0,0}, {16940,16939,16941 ,5128,5127,5129 ,0,0,0}, + {16941,16943,16942 ,5129,5131,5130 ,0,0,0}, {16943,16941,16944 ,5131,5129,5132 ,0,0,0}, + {16945,16946,16947 ,5133,5134,5135 ,0,0,0}, {16945,16944,16946 ,5133,5132,5134 ,0,0,0}, + {16948,16947,16946 ,5136,5135,5134 ,0,0,0}, {16947,16948,16949 ,5135,5136,5137 ,0,0,0}, + {16950,16951,16952 ,5138,5139,5140 ,0,0,0}, {16953,16954,16948 ,5141,5142,5136 ,0,0,0}, + {16955,16956,16953 ,5143,5144,5141 ,0,0,0}, {16956,16955,16957 ,5144,5143,5145 ,0,0,0}, + {16958,16959,16955 ,5146,5147,5143 ,0,0,0}, {16912,16911,16960 ,5100,5099,5148 ,0,0,0}, + {16961,16962,16958 ,5149,5150,5146 ,0,0,0}, {16963,16964,16965 ,5151,5152,5153 ,0,0,0}, + {16966,16967,16968 ,5154,5155,5156 ,0,0,0}, {16969,16970,16971 ,5157,5158,5159 ,0,0,0}, + {16972,16973,16974 ,5160,5161,5162 ,0,0,0}, {16975,16976,16977 ,5163,5164,5165 ,0,0,0}, + {16978,16979,16980 ,5166,5167,5168 ,0,0,0}, {16978,16981,16982 ,5166,5169,5170 ,0,0,0}, + {16983,16984,16985 ,5171,5172,5173 ,0,0,0}, {16986,16987,16988 ,5174,5175,5176 ,0,0,0}, + {16989,16990,16991 ,5177,5178,5179 ,0,0,0}, {16992,16984,16983 ,5180,5172,5171 ,0,0,0}, + {16993,16994,16995 ,5179,5181,5182 ,0,0,0}, {16993,16991,16990 ,5179,5179,5178 ,0,0,0}, + {16996,16997,16998 ,5183,5184,5185 ,0,0,0}, {16999,16996,16995 ,5186,5183,5182 ,0,0,0}, + {17000,17001,17002 ,5187,5188,5189 ,0,0,0}, {17003,17000,16998 ,5190,5187,5185 ,0,0,0}, + {17004,17005,17006 ,5191,5192,5193 ,0,0,0}, {17005,17004,17002 ,5192,5191,5189 ,0,0,0}, + {17007,17008,17006 ,5194,5195,5193 ,0,0,0}, {17004,17006,17008 ,5191,5193,5195 ,0,0,0}, + {17007,17009,17010 ,5194,5196,5197 ,0,0,0}, {17010,17008,17007 ,5197,5195,5194 ,0,0,0}, + {17003,17001,17000 ,5190,5188,5187 ,0,0,0}, {17001,17005,17002 ,5188,5192,5189 ,0,0,0}, + {16997,17003,16998 ,5184,5190,5185 ,0,0,0}, {16999,16997,16996 ,5186,5184,5183 ,0,0,0}, + {16994,16999,16995 ,5181,5186,5182 ,0,0,0}, {16994,16993,16990 ,5181,5179,5178 ,0,0,0}, + {16990,17011,16994 ,5178,5198,5181 ,0,0,0}, {16983,17011,16992 ,5171,5198,5180 ,0,0,0}, + {17011,16990,16992 ,5198,5178,5180 ,0,0,0}, {17012,17013,17014 ,5199,5200,5201 ,0,0,0}, + {16985,16984,16986 ,5173,5172,5174 ,0,0,0}, {17012,17015,17016 ,5199,5202,5203 ,0,0,0}, + {17016,17013,17012 ,5203,5200,5199 ,0,0,0}, {17017,17015,17018 ,5204,5202,5205 ,0,0,0}, + {17015,17017,17016 ,5202,5204,5203 ,0,0,0}, {17019,16613,17018 ,5206,5207,5205 ,0,0,0}, + {17017,17018,16613 ,5204,5205,5207 ,0,0,0}, {16616,16613,17019 ,5197,5207,5206 ,0,0,0}, + {17014,17013,17020 ,5201,5200,5208 ,0,0,0}, {17021,17022,17023 ,5209,5210,5211 ,0,0,0}, + {17014,17020,17023 ,5201,5208,5211 ,0,0,0}, {17021,17024,17022 ,5209,5212,5210 ,0,0,0}, + {17023,17020,17021 ,5211,5208,5209 ,0,0,0}, {16987,16979,16988 ,5175,5167,5176 ,0,0,0}, + {17024,17025,17022 ,5212,5213,5210 ,0,0,0}, {16991,17025,16989 ,5179,5213,5177 ,0,0,0}, + {17024,16989,17025 ,5212,5177,5213 ,0,0,0}, {16986,16988,16985 ,5174,5176,5173 ,0,0,0}, + {16977,16966,16975 ,5165,5154,5163 ,0,0,0}, {16978,16980,16981 ,5166,5168,5169 ,0,0,0}, + {16979,16987,16980 ,5167,5175,5168 ,0,0,0}, {16981,16974,16982 ,5169,5162,5170 ,0,0,0}, + {16976,16973,16972 ,5164,5161,5160 ,0,0,0}, {16973,16982,16974 ,5161,5170,5162 ,0,0,0}, + {16977,16976,16972 ,5165,5164,5160 ,0,0,0}, {16963,16970,16969 ,5151,5158,5157 ,0,0,0}, + {16966,16968,16975 ,5154,5156,5163 ,0,0,0}, {16967,16971,16968 ,5155,5159,5156 ,0,0,0}, + {16965,16970,16963 ,5153,5158,5151 ,0,0,0}, {16967,16969,16971 ,5155,5157,5159 ,0,0,0}, + {16913,16965,16964 ,5101,5153,5152 ,0,0,0}, {16964,16565,16961 ,5152,5214,5149 ,0,0,0}, + {16919,17026,16920 ,5107,5215,5108 ,0,0,0}, {16925,16924,16923 ,5112,5111,5108 ,0,0,0}, + {16922,17027,16923 ,5110,5216,5108 ,0,0,0}, {16925,16923,17027 ,5112,5108,5216 ,0,0,0}, + {17028,17026,17029 ,5217,5215,5218 ,0,0,0}, {16916,16922,16918 ,5104,5110,5106 ,0,0,0}, + {17030,17028,17031 ,5219,5217,5220 ,0,0,0}, {17030,17032,17028 ,5219,5221,5217 ,0,0,0}, + {17033,17032,17034 ,5222,5221,5223 ,0,0,0}, {16940,16917,16939 ,5128,5105,5127 ,0,0,0}, + {17035,17033,17036 ,5224,5222,5225 ,0,0,0}, {17035,17037,17033 ,5224,5226,5222 ,0,0,0}, + {17038,17037,17039 ,5227,5226,5228 ,0,0,0}, {16945,16943,16944 ,5133,5131,5132 ,0,0,0}, + {17040,17041,17038 ,5229,5230,5227 ,0,0,0}, {17042,17041,17040 ,5231,5230,5229 ,0,0,0}, + {17043,17041,17044 ,5232,5230,5233 ,0,0,0}, {16954,16949,16948 ,5142,5137,5136 ,0,0,0}, + {16952,17043,16950 ,5140,5232,5138 ,0,0,0}, {16956,16954,16953 ,5144,5142,5141 ,0,0,0}, + {17045,16952,17046 ,5234,5140,5235 ,0,0,0}, {16959,16957,16955 ,5147,5145,5143 ,0,0,0}, + {16911,17045,16960 ,5099,5234,5148 ,0,0,0}, {16962,16959,16958 ,5150,5147,5146 ,0,0,0}, + {16962,16961,16565 ,5150,5149,5214 ,0,0,0}, {16964,16961,16913 ,5152,5149,5101 ,0,0,0}, + {16913,16961,16911 ,5101,5149,5099 ,0,0,0}, {17046,16960,17045 ,5235,5148,5234 ,0,0,0}, + {16951,17046,16952 ,5139,5235,5140 ,0,0,0}, {17044,16950,17043 ,5233,5138,5232 ,0,0,0}, + {17042,17044,17041 ,5231,5233,5230 ,0,0,0}, {17039,17040,17038 ,5228,5229,5227 ,0,0,0}, + {17035,17039,17037 ,5224,5228,5226 ,0,0,0}, {17034,17036,17033 ,5223,5225,5222 ,0,0,0}, + {17030,17034,17032 ,5219,5223,5221 ,0,0,0}, {17029,17031,17028 ,5218,5220,5217 ,0,0,0}, + {16919,17029,17026 ,5107,5218,5215 ,0,0,0}, {17047,17048,17049 ,5236,5237,5238 ,0,0,0}, + {17050,17051,17049 ,5239,5240,5238 ,0,0,0}, {17047,17049,17051 ,5236,5238,5240 ,0,0,0}, + {17050,17052,17053 ,5239,5241,5242 ,0,0,0}, {17053,17051,17050 ,5242,5240,5239 ,0,0,0}, + {17054,17052,17055 ,5243,5241,5244 ,0,0,0}, {17052,17054,17053 ,5241,5243,5242 ,0,0,0}, + {17056,17057,17055 ,5245,5246,5244 ,0,0,0}, {17054,17055,17057 ,5243,5244,5246 ,0,0,0}, + {17056,17058,17059 ,5245,5247,5248 ,0,0,0}, {17059,17057,17056 ,5248,5246,5245 ,0,0,0}, + {17060,17058,17061 ,5249,5247,5250 ,0,0,0}, {17058,17060,17059 ,5247,5249,5248 ,0,0,0}, + {17062,17063,17061 ,5251,5252,5250 ,0,0,0}, {17060,17061,17063 ,5249,5250,5252 ,0,0,0}, + {17062,17064,17065 ,5251,5253,5254 ,0,0,0}, {17065,17063,17062 ,5254,5252,5251 ,0,0,0}, + {17066,17064,17067 ,5255,5253,5256 ,0,0,0}, {17064,17066,17065 ,5253,5255,5254 ,0,0,0}, + {17068,17069,17067 ,5257,5258,5256 ,0,0,0}, {17066,17067,17069 ,5255,5256,5258 ,0,0,0}, + {17068,17070,17071 ,5257,5259,5260 ,0,0,0}, {17071,17069,17068 ,5260,5258,5257 ,0,0,0}, + {17072,17070,17073 ,5261,5259,5262 ,0,0,0}, {17070,17072,17071 ,5259,5261,5260 ,0,0,0}, + {17074,17075,17073 ,5263,5264,5262 ,0,0,0}, {17072,17073,17075 ,5261,5262,5264 ,0,0,0}, + {17074,17076,17077 ,5263,5265,5266 ,0,0,0}, {17077,17075,17074 ,5266,5264,5263 ,0,0,0}, + {17078,17076,17079 ,5267,5265,5268 ,0,0,0}, {17076,17078,17077 ,5265,5267,5266 ,0,0,0}, + {17080,17081,17079 ,5269,5270,5268 ,0,0,0}, {17078,17079,17081 ,5267,5268,5270 ,0,0,0}, + {17080,17082,17083 ,5269,5271,5272 ,0,0,0}, {17083,17081,17080 ,5272,5270,5269 ,0,0,0}, + {17084,17082,17085 ,5273,5271,5274 ,0,0,0}, {17082,17084,17083 ,5271,5273,5272 ,0,0,0}, + {17086,17087,17085 ,5275,5276,5274 ,0,0,0}, {17084,17085,17087 ,5273,5274,5276 ,0,0,0}, + {17086,17088,17089 ,5275,5277,5278 ,0,0,0}, {17089,17087,17086 ,5278,5276,5275 ,0,0,0}, + {17090,17088,17091 ,5279,5277,5280 ,0,0,0}, {17088,17090,17089 ,5277,5279,5278 ,0,0,0}, + {17092,17093,17091 ,5281,5282,5280 ,0,0,0}, {17090,17091,17093 ,5279,5280,5282 ,0,0,0}, + {17094,17092,17095 ,5283,5281,5284 ,0,0,0}, {17094,17093,17092 ,5283,5282,5281 ,0,0,0}, + {17096,17095,17097 ,5285,5284,5286 ,0,0,0}, {17092,17097,17095 ,5281,5286,5284 ,0,0,0}, + {17098,17096,17099 ,5287,5285,5288 ,0,0,0}, {17096,17097,17099 ,5285,5286,5288 ,0,0,0}, + {17098,17100,17101 ,5287,5289,5290 ,0,0,0}, {17101,17096,17098 ,5290,5285,5287 ,0,0,0}, + {17100,17102,17101 ,5289,5291,5290 ,0,0,0}, {17103,17048,17047 ,5292,5237,5236 ,0,0,0}, + {17103,17104,17105 ,5292,5293,5294 ,0,0,0}, {17105,17048,17103 ,5294,5237,5292 ,0,0,0}, + {17106,17104,17107 ,5295,5293,5296 ,0,0,0}, {17104,17106,17105 ,5293,5295,5294 ,0,0,0}, + {17108,17109,17107 ,5297,5298,5296 ,0,0,0}, {17106,17107,17109 ,5295,5296,5298 ,0,0,0}, + {17108,17110,17111 ,5297,5299,5300 ,0,0,0}, {17111,17109,17108 ,5300,5298,5297 ,0,0,0}, + {17112,17110,17113 ,5301,5299,5302 ,0,0,0}, {17110,17112,17111 ,5299,5301,5300 ,0,0,0}, + {17114,17115,17113 ,5303,5304,5302 ,0,0,0}, {17112,17113,17115 ,5301,5302,5304 ,0,0,0}, + {17114,17116,17117 ,5303,5305,5306 ,0,0,0}, {17117,17115,17114 ,5306,5304,5303 ,0,0,0}, + {17118,17116,17119 ,5307,5305,5308 ,0,0,0}, {17116,17118,17117 ,5305,5307,5306 ,0,0,0}, + {17120,17121,17119 ,5309,5310,5308 ,0,0,0}, {17118,17119,17121 ,5307,5308,5310 ,0,0,0}, + {17120,17122,17123 ,5309,5311,5312 ,0,0,0}, {17123,17121,17120 ,5312,5310,5309 ,0,0,0}, + {17124,17122,17125 ,5313,5311,5314 ,0,0,0}, {17122,17124,17123 ,5311,5313,5312 ,0,0,0}, + {17126,17127,17125 ,5315,5316,5314 ,0,0,0}, {17124,17125,17127 ,5313,5314,5316 ,0,0,0}, + {17126,17128,17129 ,5315,5317,5318 ,0,0,0}, {17129,17127,17126 ,5318,5316,5315 ,0,0,0}, + {17130,17128,17131 ,5319,5317,5320 ,0,0,0}, {17128,17130,17129 ,5317,5319,5318 ,0,0,0}, + {17132,17133,17131 ,5321,5322,5320 ,0,0,0}, {17130,17131,17133 ,5319,5320,5322 ,0,0,0}, + {17132,17134,17135 ,5321,5323,5324 ,0,0,0}, {17135,17133,17132 ,5324,5322,5321 ,0,0,0}, + {17136,17134,17137 ,5325,5323,5326 ,0,0,0}, {17134,17136,17135 ,5323,5325,5324 ,0,0,0}, + {17138,17139,17137 ,5327,5328,5326 ,0,0,0}, {17136,17137,17139 ,5325,5326,5328 ,0,0,0}, + {17138,17140,17141 ,5327,5329,5330 ,0,0,0}, {17141,17139,17138 ,5330,5328,5327 ,0,0,0}, + {17142,17140,17143 ,5331,5329,5332 ,0,0,0}, {17140,17142,17141 ,5329,5331,5330 ,0,0,0}, + {17144,17145,17143 ,5333,5334,5332 ,0,0,0}, {17142,17143,17145 ,5331,5332,5334 ,0,0,0}, + {17144,17146,17147 ,5333,5335,5336 ,0,0,0}, {17147,17145,17144 ,5336,5334,5333 ,0,0,0}, + {17148,17149,17146 ,5337,5338,5335 ,0,0,0}, {17146,17149,17147 ,5335,5338,5336 ,0,0,0}, + {17150,17151,17148 ,5339,5340,5337 ,0,0,0}, {17148,17146,17150 ,5337,5335,5339 ,0,0,0}, + {17152,17153,17151 ,5341,5342,5340 ,0,0,0}, {17152,17151,17150 ,5341,5340,5339 ,0,0,0}, + {17154,17153,17155 ,5343,5342,5344 ,0,0,0}, {17153,17154,17151 ,5342,5343,5340 ,0,0,0}, + {17154,17155,17156 ,5343,5344,5345 ,0,0,0}, {17157,17158,17159 ,5346,5347,5348 ,0,0,0}, + {17160,17161,17159 ,5349,5350,5348 ,0,0,0}, {17157,17159,17161 ,5346,5348,5350 ,0,0,0}, + {17160,17162,17163 ,5349,5351,5352 ,0,0,0}, {17163,17161,17160 ,5352,5350,5349 ,0,0,0}, + {17164,17162,17165 ,5353,5351,5354 ,0,0,0}, {17162,17164,17163 ,5351,5353,5352 ,0,0,0}, + {17166,17167,17165 ,5355,5356,5354 ,0,0,0}, {17164,17165,17167 ,5353,5354,5356 ,0,0,0}, + {17166,17168,17169 ,5355,5357,5358 ,0,0,0}, {17169,17167,17166 ,5358,5356,5355 ,0,0,0}, + {17170,17168,17171 ,5359,5357,5360 ,0,0,0}, {17168,17170,17169 ,5357,5359,5358 ,0,0,0}, + {17172,17173,17171 ,5361,5362,5360 ,0,0,0}, {17170,17171,17173 ,5359,5360,5362 ,0,0,0}, + {17172,17174,17175 ,5361,5363,5364 ,0,0,0}, {17175,17173,17172 ,5364,5362,5361 ,0,0,0}, + {17176,17174,17177 ,5365,5363,5366 ,0,0,0}, {17174,17176,17175 ,5363,5365,5364 ,0,0,0}, + {17178,17179,17177 ,5367,5368,5366 ,0,0,0}, {17176,17177,17179 ,5365,5366,5368 ,0,0,0}, + {17178,17180,17181 ,5367,5369,5370 ,0,0,0}, {17181,17179,17178 ,5370,5368,5367 ,0,0,0}, + {17182,17180,17183 ,5371,5369,5372 ,0,0,0}, {17180,17182,17181 ,5369,5371,5370 ,0,0,0}, + {17184,17185,17183 ,5373,5374,5372 ,0,0,0}, {17182,17183,17185 ,5371,5372,5374 ,0,0,0}, + {17184,17186,17187 ,5373,5375,5376 ,0,0,0}, {17187,17185,17184 ,5376,5374,5373 ,0,0,0}, + {17188,17186,17189 ,5377,5375,5378 ,0,0,0}, {17186,17188,17187 ,5375,5377,5376 ,0,0,0}, + {17190,17191,17189 ,5379,5380,5378 ,0,0,0}, {17188,17189,17191 ,5377,5378,5380 ,0,0,0}, + {17190,17192,17193 ,5379,5381,5382 ,0,0,0}, {17193,17191,17190 ,5382,5380,5379 ,0,0,0}, + {17194,17192,17195 ,5383,5381,5384 ,0,0,0}, {17192,17194,17193 ,5381,5383,5382 ,0,0,0}, + {17196,17197,17195 ,5385,5386,5384 ,0,0,0}, {17194,17195,17197 ,5383,5384,5386 ,0,0,0}, + {17196,17198,17199 ,5385,5387,5388 ,0,0,0}, {17199,17197,17196 ,5388,5386,5385 ,0,0,0}, + {17200,17198,17201 ,5389,5387,5390 ,0,0,0}, {17198,17200,17199 ,5387,5389,5388 ,0,0,0}, + {17202,17203,17201 ,5391,5392,5390 ,0,0,0}, {17200,17201,17203 ,5389,5390,5392 ,0,0,0}, + {17202,17204,17205 ,5391,5393,5394 ,0,0,0}, {17205,17203,17202 ,5394,5392,5391 ,0,0,0}, + {17206,17204,17207 ,5395,5393,5396 ,0,0,0}, {17204,17206,17205 ,5393,5395,5394 ,0,0,0}, + {17208,17209,17207 ,5397,5398,5396 ,0,0,0}, {17206,17207,17209 ,5395,5396,5398 ,0,0,0}, + {17208,17210,17211 ,5397,5399,5400 ,0,0,0}, {17211,17209,17208 ,5400,5398,5397 ,0,0,0}, + {17212,17210,17213 ,5401,5399,5402 ,0,0,0}, {17210,17212,17211 ,5399,5401,5400 ,0,0,0}, + {17214,17215,17213 ,5403,5404,5402 ,0,0,0}, {17212,17213,17215 ,5401,5402,5404 ,0,0,0}, + {17214,17216,17217 ,5403,5405,5406 ,0,0,0}, {17217,17215,17214 ,5406,5404,5403 ,0,0,0}, + {17216,17218,17217 ,5405,5407,5406 ,0,0,0}, {17219,17158,17157 ,5408,5347,5346 ,0,0,0}, + {17219,17220,17221 ,5408,5409,5410 ,0,0,0}, {17221,17158,17219 ,5410,5347,5408 ,0,0,0}, + {17222,17220,17223 ,5411,5409,5412 ,0,0,0}, {17220,17222,17221 ,5409,5411,5410 ,0,0,0}, + {17224,17225,17223 ,5413,5414,5412 ,0,0,0}, {17222,17223,17225 ,5411,5412,5414 ,0,0,0}, + {17224,17226,17227 ,5413,5415,5416 ,0,0,0}, {17227,17225,17224 ,5416,5414,5413 ,0,0,0}, + {17228,17226,17229 ,5417,5415,5418 ,0,0,0}, {17226,17228,17227 ,5415,5417,5416 ,0,0,0}, + {17230,17231,17229 ,5419,5420,5418 ,0,0,0}, {17228,17229,17231 ,5417,5418,5420 ,0,0,0}, + {17230,17232,17233 ,5419,5421,5422 ,0,0,0}, {17233,17231,17230 ,5422,5420,5419 ,0,0,0}, + {17234,17232,17235 ,5423,5421,5424 ,0,0,0}, {17232,17234,17233 ,5421,5423,5422 ,0,0,0}, + {17236,17237,17235 ,5425,5426,5424 ,0,0,0}, {17234,17235,17237 ,5423,5424,5426 ,0,0,0}, + {17236,17238,17239 ,5425,5427,5428 ,0,0,0}, {17239,17237,17236 ,5428,5426,5425 ,0,0,0}, + {17240,17238,17241 ,5429,5427,5430 ,0,0,0}, {17238,17240,17239 ,5427,5429,5428 ,0,0,0}, + {17242,17243,17241 ,5431,5432,5430 ,0,0,0}, {17240,17241,17243 ,5429,5430,5432 ,0,0,0}, + {17242,17244,17245 ,5431,5433,5434 ,0,0,0}, {17245,17243,17242 ,5434,5432,5431 ,0,0,0}, + {17246,17244,17247 ,5435,5433,5436 ,0,0,0}, {17244,17246,17245 ,5433,5435,5434 ,0,0,0}, + {17248,17249,17247 ,5437,5438,5436 ,0,0,0}, {17246,17247,17249 ,5435,5436,5438 ,0,0,0}, + {17248,17250,17251 ,5437,5439,5440 ,0,0,0}, {17251,17249,17248 ,5440,5438,5437 ,0,0,0}, + {17252,17250,17253 ,5441,5439,5442 ,0,0,0}, {17250,17252,17251 ,5439,5441,5440 ,0,0,0}, + {17254,17255,17253 ,5443,5444,5442 ,0,0,0}, {17252,17253,17255 ,5441,5442,5444 ,0,0,0}, + {17254,17256,17257 ,5443,5445,5446 ,0,0,0}, {17257,17255,17254 ,5446,5444,5443 ,0,0,0}, + {17258,17256,17259 ,5447,5445,5448 ,0,0,0}, {17256,17258,17257 ,5445,5447,5446 ,0,0,0}, + {17260,17261,17259 ,5449,5450,5448 ,0,0,0}, {17258,17259,17261 ,5447,5448,5450 ,0,0,0}, + {17260,17262,17263 ,5449,5451,5452 ,0,0,0}, {17263,17261,17260 ,5452,5450,5449 ,0,0,0}, + {17264,17262,17265 ,5453,5451,5454 ,0,0,0}, {17262,17264,17263 ,5451,5453,5452 ,0,0,0}, + {17266,17267,17265 ,5455,5456,5454 ,0,0,0}, {17264,17265,17267 ,5453,5454,5456 ,0,0,0}, + {17266,17268,17269 ,5455,5457,5458 ,0,0,0}, {17269,17267,17266 ,5458,5456,5455 ,0,0,0}, + {17270,17268,17271 ,5459,5457,5460 ,0,0,0}, {17268,17270,17269 ,5457,5459,5458 ,0,0,0}, + {17272,17273,17271 ,5461,5462,5460 ,0,0,0}, {17270,17271,17273 ,5459,5460,5462 ,0,0,0}, + {17272,17274,17275 ,5461,5463,5464 ,0,0,0}, {17275,17273,17272 ,5464,5462,5461 ,0,0,0}, + {17276,17274,17277 ,5465,5463,5466 ,0,0,0}, {17274,17276,17275 ,5463,5465,5464 ,0,0,0}, + {17276,17277,17278 ,5465,5466,5467 ,0,0,0}, {17279,16313,16312 ,5468,5469,5469 ,0,0,0}, + {17280,17281,17282 ,726,726,726 ,0,0,0}, {17283,16046,16043 ,726,5470,726 ,0,0,0}, + {17284,17285,17286 ,5471,726,726 ,0,0,0}, {17287,17288,17289 ,726,726,726 ,0,0,0}, + {17290,16268,17291 ,5468,5471,5469 ,0,0,0}, {17292,17293,17294 ,5470,726,726 ,0,0,0}, + {17295,17296,17297 ,5471,5469,5469 ,0,0,0}, {17298,17297,16241 ,5468,5469,5469 ,0,0,0}, + {17299,17300,16347 ,5469,5472,5468 ,0,0,0}, {17301,17302,17303 ,5469,5468,5471 ,0,0,0}, + {17304,17305,17306 ,5473,5474,726 ,0,0,0}, {17307,17308,17309 ,5475,5476,5471 ,0,0,0}, + {17310,17311,17312 ,5477,5478,5469 ,0,0,0}, {17305,17304,17313 ,5474,5473,5479 ,0,0,0}, + {17314,17315,17316 ,5471,5469,726 ,0,0,0}, {17317,17318,16306 ,5468,5469,5471 ,0,0,0}, + {17319,17320,17321 ,726,5480,5481 ,0,0,0}, {17312,17322,17323 ,5469,726,5468 ,0,0,0}, + {17324,17325,17326 ,5475,5475,5482 ,0,0,0}, {17327,15981,17324 ,5468,5483,5475 ,0,0,0}, + {17326,17328,17329 ,5482,5482,5482 ,0,0,0}, {17325,17328,17326 ,5475,5482,5482 ,0,0,0}, + {17329,17330,17326 ,5482,5475,5482 ,0,0,0}, {17321,17315,17331 ,5481,5469,5475 ,0,0,0}, + {17332,16361,17333 ,726,5471,5484 ,0,0,0}, {17305,17313,17323 ,5474,5479,5468 ,0,0,0}, + {17334,17335,17336 ,5475,5485,5468 ,0,0,0}, {17337,17338,17339 ,5486,5483,5468 ,0,0,0}, + {17322,17305,17323 ,726,5474,5468 ,0,0,0}, {16306,17318,16307 ,5471,5469,726 ,0,0,0}, + {16313,17279,16315 ,5469,5468,726 ,0,0,0}, {16319,16318,17340 ,5471,5471,726 ,0,0,0}, + {16347,16317,17299 ,5468,5468,5469 ,0,0,0}, {16345,16317,16347 ,5471,5468,5468 ,0,0,0}, + {16319,17341,16344 ,5471,5471,5469 ,0,0,0}, {17342,16351,16350 ,5468,5478,726 ,0,0,0}, + {16318,17343,17340 ,5471,726,726 ,0,0,0}, {16274,17344,17345 ,5471,5468,726 ,0,0,0}, + {17346,16361,16359 ,5475,5471,726 ,0,0,0}, {17347,17348,17349 ,5469,5482,5483 ,0,0,0}, + {17350,17348,17351 ,5468,5482,5475 ,0,0,0}, {17352,17353,17354 ,726,5468,5468 ,0,0,0}, + {17355,17303,17356 ,726,5471,5469 ,0,0,0}, {17357,17358,17359 ,5475,5475,726 ,0,0,0}, + {17353,17352,17360 ,5468,726,5483 ,0,0,0}, {17361,17362,17363 ,5480,5487,5475 ,0,0,0}, + {17360,17364,17347 ,5483,5478,5469 ,0,0,0}, {17365,17366,17367 ,5475,5479,5474 ,0,0,0}, + {17367,17333,17365 ,5474,5484,5475 ,0,0,0}, {17368,17369,17367 ,5473,726,5474 ,0,0,0}, + {17368,17367,17366 ,5473,5474,5479 ,0,0,0}, {17350,17349,17348 ,5468,5483,5482 ,0,0,0}, + {17362,17357,17370 ,5487,5475,726 ,0,0,0}, {17348,17347,17364 ,5482,5469,5478 ,0,0,0}, + {17371,17372,17332 ,5486,5478,726 ,0,0,0}, {17355,17356,17354 ,726,5469,5468 ,0,0,0}, + {16271,17344,16274 ,726,5468,5471 ,0,0,0}, {17365,17333,16361 ,5475,5484,5471 ,0,0,0}, + {17373,17374,17375 ,726,726,726 ,0,0,0}, {17376,17377,16277 ,5468,5469,726 ,0,0,0}, + {17346,16359,17378 ,5475,726,5482 ,0,0,0}, {17379,16283,17380 ,726,726,5470 ,0,0,0}, + {16356,17381,17382 ,5475,5485,5475 ,0,0,0}, {17383,17384,16201 ,5471,726,5471 ,0,0,0}, + {16105,17385,16100 ,726,5470,726 ,0,0,0}, {17386,17387,17388 ,5470,5471,5471 ,0,0,0}, + {17389,17390,17391 ,726,726,5470 ,0,0,0}, {17391,17292,17389 ,5470,5470,726 ,0,0,0}, + {17373,17294,17374 ,726,726,726 ,0,0,0}, {17392,17393,17394 ,726,726,5470 ,0,0,0}, + {17286,17386,17388 ,726,5470,5471 ,0,0,0}, {17390,17395,17396 ,726,726,726 ,0,0,0}, + {16285,17397,17398 ,726,5470,726 ,0,0,0}, {17399,17400,17401 ,5470,726,726 ,0,0,0}, + {17374,17294,17293 ,726,726,726 ,0,0,0}, {17397,17402,17403 ,5470,726,5468 ,0,0,0}, + {17374,17404,17375 ,726,726,726 ,0,0,0}, {17403,17405,17406 ,5468,5468,726 ,0,0,0}, + {17402,17405,17403 ,726,5468,5468 ,0,0,0}, {17406,17407,17403 ,726,5471,5468 ,0,0,0}, + {17408,17409,17410 ,726,726,5471 ,0,0,0}, {16285,17402,17397 ,726,726,5470 ,0,0,0}, + {17398,17411,17412 ,726,726,726 ,0,0,0}, {17413,17414,17415 ,726,5488,5489 ,0,0,0}, + {16243,17416,17417 ,5471,5470,726 ,0,0,0}, {16271,17297,17344 ,726,5469,5468 ,0,0,0}, + {17418,16198,16195 ,726,726,5471 ,0,0,0}, {17419,16122,16119 ,726,726,726 ,0,0,0}, + {17420,16055,17421 ,726,5470,726 ,0,0,0}, {17422,16198,17418 ,726,726,726 ,0,0,0}, + {17423,17424,17425 ,726,726,726 ,0,0,0}, {17426,17427,17428 ,5489,726,726 ,0,0,0}, + {16192,17429,16193 ,726,5471,726 ,0,0,0}, {17430,17424,17431 ,726,726,726 ,0,0,0}, + {17432,17433,17434 ,726,726,5489 ,0,0,0}, {17435,17436,17437 ,726,726,726 ,0,0,0}, + {17438,17424,17430 ,726,726,726 ,0,0,0}, {17280,17282,17437 ,726,726,726 ,0,0,0}, + {17439,17440,17441 ,726,726,5489 ,0,0,0}, {17281,17423,17425 ,726,726,726 ,0,0,0}, + {17442,17443,17444 ,726,726,726 ,0,0,0}, {17440,17445,17442 ,726,5488,726 ,0,0,0}, + {17438,17425,17424 ,726,726,726 ,0,0,0}, {17289,17426,16209 ,726,5489,726 ,0,0,0}, + {17446,17447,17448 ,5489,726,726 ,0,0,0}, {17446,17449,17447 ,5489,5488,726 ,0,0,0}, + {17450,17451,17452 ,726,5471,726 ,0,0,0}, {17447,17449,17453 ,726,5488,726 ,0,0,0}, + {17454,17447,17453 ,726,726,726 ,0,0,0}, {17455,16167,17456 ,726,726,726 ,0,0,0}, + {16125,17457,17458 ,726,726,726 ,0,0,0}, {16283,16281,17380 ,726,726,5470 ,0,0,0}, + {17289,16205,17459 ,726,726,726 ,0,0,0}, {17451,17460,17461 ,5471,5471,726 ,0,0,0}, + {17462,16023,17463 ,726,5470,726 ,0,0,0}, {17452,17464,17450 ,726,5471,726 ,0,0,0}, + {16133,17465,17466 ,5489,726,726 ,0,0,0}, {17467,17468,17469 ,726,726,726 ,0,0,0}, + {17470,17471,17469 ,726,5471,726 ,0,0,0}, {17434,17433,17472 ,5489,726,5488 ,0,0,0}, + {17419,17473,16122 ,726,726,726 ,0,0,0}, {17427,17289,17448 ,726,726,726 ,0,0,0}, + {17474,17419,17472 ,726,726,5488 ,0,0,0}, {16049,17475,17476 ,726,5471,726 ,0,0,0}, + {17477,17478,17468 ,726,5488,726 ,0,0,0}, {17469,17479,17480 ,726,5471,726 ,0,0,0}, + {17481,17482,17483 ,726,726,5488 ,0,0,0}, {17484,17485,17481 ,726,726,726 ,0,0,0}, + {17486,17485,17487 ,726,726,726 ,0,0,0}, {17488,16133,17466 ,726,5489,726 ,0,0,0}, + {17489,17469,17490 ,726,726,726 ,0,0,0}, {17466,17465,17491 ,726,726,726 ,0,0,0}, + {17468,17492,17477 ,726,726,726 ,0,0,0}, {17493,17491,17465 ,726,726,726 ,0,0,0}, + {17468,17478,17469 ,726,5488,726 ,0,0,0}, {17493,17494,17491 ,726,5488,726 ,0,0,0}, + {17495,17492,17468 ,726,726,726 ,0,0,0}, {17491,17494,17496 ,726,5488,726 ,0,0,0}, + {17469,17497,17479 ,726,726,5471 ,0,0,0}, {16328,17498,16327 ,5469,5468,5468 ,0,0,0}, + {16328,16333,17499 ,5469,726,726 ,0,0,0}, {17500,16040,17501 ,726,5471,5471 ,0,0,0}, + {17502,15947,17503 ,5470,5468,5468 ,0,0,0}, {16057,17504,17505 ,5470,726,726 ,0,0,0}, + {17506,17507,17508 ,5468,726,5469 ,0,0,0}, {17509,17510,17511 ,5471,5468,726 ,0,0,0}, + {17512,17506,17513 ,5468,5468,726 ,0,0,0}, {17514,17515,17516 ,726,5470,5469 ,0,0,0}, + {17517,17518,17519 ,726,5469,726 ,0,0,0}, {17520,17521,17522 ,5471,5469,726 ,0,0,0}, + {17523,16344,17524 ,726,5469,5470 ,0,0,0}, {17488,17525,17526 ,726,5489,726 ,0,0,0}, + {17469,17471,17527 ,726,5471,726 ,0,0,0}, {17528,16231,16230 ,5468,726,5469 ,0,0,0}, + {17529,17530,17419 ,5470,5471,726 ,0,0,0}, {17283,17531,16046 ,726,726,5470 ,0,0,0}, + {17532,16091,16090 ,5471,726,726 ,0,0,0}, {17533,16333,16331 ,726,726,5468 ,0,0,0}, + {17534,17535,17536 ,726,5470,5471 ,0,0,0}, {17537,17538,17539 ,5471,726,5470 ,0,0,0}, + {17540,17541,17542 ,726,5470,726 ,0,0,0}, {17504,17543,17505 ,726,726,726 ,0,0,0}, + {17543,17504,17544 ,726,726,726 ,0,0,0}, {17505,17535,16057 ,726,5470,5470 ,0,0,0}, + {17543,17544,17545 ,726,726,726 ,0,0,0}, {17517,17511,17510 ,726,726,5468 ,0,0,0}, + {17543,17545,17546 ,726,726,726 ,0,0,0}, {17547,17548,17549 ,5471,5471,5468 ,0,0,0}, + {17515,17522,17516 ,5470,726,5469 ,0,0,0}, {17550,17514,17551 ,726,726,726 ,0,0,0}, + {17552,17553,17521 ,5468,5469,5469 ,0,0,0}, {17521,17520,17552 ,5469,5471,5468 ,0,0,0}, + {17554,17555,17552 ,5471,726,5468 ,0,0,0}, {17552,17555,17553 ,5468,726,5469 ,0,0,0}, + {16351,17556,16353 ,5478,5487,5468 ,0,0,0}, {16285,16283,17379 ,726,726,726 ,0,0,0}, + {17378,16359,16357 ,5482,726,5468 ,0,0,0}, {17377,16280,16277 ,5469,726,726 ,0,0,0}, + {17298,17295,17297 ,5468,5471,5469 ,0,0,0}, {17557,17296,17295 ,5468,5469,5471 ,0,0,0}, + {17302,17301,17558 ,5468,5469,5469 ,0,0,0}, {17296,17557,17559 ,5469,5468,5470 ,0,0,0}, + {17301,17303,17355 ,5469,5471,726 ,0,0,0}, {17558,17559,17560 ,5469,5470,5469 ,0,0,0}, + {17354,17356,17352 ,5468,5469,726 ,0,0,0}, {17360,17347,17353 ,5483,5469,5468 ,0,0,0}, + {17358,17364,17359 ,5475,5478,726 ,0,0,0}, {17364,17360,17359 ,5478,5483,726 ,0,0,0}, + {17371,17361,17372 ,5486,5480,5478 ,0,0,0}, {17362,17358,17357 ,5487,5475,5475 ,0,0,0}, + {17361,17363,17372 ,5480,5475,5478 ,0,0,0}, {17363,17362,17370 ,5475,5487,726 ,0,0,0}, + {17333,17371,17332 ,5484,5486,726 ,0,0,0}, {17346,17365,16361 ,5475,5475,5471 ,0,0,0}, + {17378,16357,17382 ,5482,5468,5475 ,0,0,0}, {17382,16357,16356 ,5475,5468,5475 ,0,0,0}, + {16353,17556,17381 ,5468,5487,5485 ,0,0,0}, {17381,16356,16353 ,5485,5475,5468 ,0,0,0}, + {17342,17556,16351 ,5468,5487,5478 ,0,0,0}, {17300,17342,16350 ,5472,5468,726 ,0,0,0}, + {17524,16344,17341 ,5470,5469,5471 ,0,0,0}, {16347,17300,16350 ,5468,5472,726 ,0,0,0}, + {17561,17562,16327 ,5471,5470,5468 ,0,0,0}, {16324,17562,17563 ,726,5470,726 ,0,0,0}, + {17309,17564,17307 ,5471,5468,5475 ,0,0,0}, {17318,17565,16307 ,5469,5469,726 ,0,0,0}, + {17566,17567,17327 ,5472,5482,5468 ,0,0,0}, {16290,15959,16286 ,5468,5468,5468 ,0,0,0}, + {15967,15965,17506 ,5471,726,5468 ,0,0,0}, {16222,15869,16220 ,5471,726,5469 ,0,0,0}, + {16233,17568,16236 ,5471,726,726 ,0,0,0}, {17418,16195,17284 ,726,5471,5471 ,0,0,0}, + {15889,17569,17570 ,726,726,5470 ,0,0,0}, {17571,17572,16131 ,726,726,726 ,0,0,0}, + {17573,16251,17574 ,726,726,5471 ,0,0,0}, {15866,17575,15863 ,5471,5471,5471 ,0,0,0}, + {15878,17576,17577 ,726,5469,5469 ,0,0,0}, {16217,16330,16336 ,5471,5469,5469 ,0,0,0}, + {16324,16327,17562 ,726,5468,5470 ,0,0,0}, {16340,16218,16336 ,5468,726,5469 ,0,0,0}, + {16330,15874,16331 ,5469,5471,5468 ,0,0,0}, {17533,17499,16333 ,726,726,726 ,0,0,0}, + {17499,17498,16328 ,726,5468,5469 ,0,0,0}, {17498,17561,16327 ,5468,5471,5468 ,0,0,0}, + {16321,16324,17563 ,726,726,726 ,0,0,0}, {16317,16345,17523 ,5468,5471,726 ,0,0,0}, + {16321,17343,16318 ,726,726,5471 ,0,0,0}, {17343,16321,17563 ,726,726,726 ,0,0,0}, + {17340,17341,16319 ,726,5471,5471 ,0,0,0}, {16344,17523,16345 ,5469,726,5471 ,0,0,0}, + {16315,17578,16317 ,726,5468,5468 ,0,0,0}, {17308,17299,17579 ,5476,5469,5468 ,0,0,0}, + {17578,17299,16317 ,5468,5469,5468 ,0,0,0}, {16307,17565,16309 ,726,5469,5470 ,0,0,0}, + {16312,16309,17580 ,5469,5470,726 ,0,0,0}, {17565,17580,16309 ,5469,726,5470 ,0,0,0}, + {17311,17310,17335 ,5478,5477,5485 ,0,0,0}, {16287,15959,17317 ,726,5468,5468 ,0,0,0}, + {16287,17317,16306 ,726,5468,5471 ,0,0,0}, {17581,17582,15979 ,5470,5470,5468 ,0,0,0}, + {15981,17325,17324 ,5483,5475,5475 ,0,0,0}, {17583,15965,15964 ,5468,726,5468 ,0,0,0}, + {17584,15939,17585 ,5469,5468,5471 ,0,0,0}, {16053,17421,16055 ,726,726,5470 ,0,0,0}, + {17586,17587,16015 ,5471,5471,5471 ,0,0,0}, {17588,16103,17589 ,726,726,5471 ,0,0,0}, + {17590,17591,17592 ,5471,5470,5471 ,0,0,0}, {16099,16100,17593 ,726,726,726 ,0,0,0}, + {16043,17460,17283 ,726,5471,726 ,0,0,0}, {17473,17419,17594 ,726,726,726 ,0,0,0}, + {16339,17595,16211 ,726,5468,5469 ,0,0,0}, {16236,17596,16237 ,726,726,5468 ,0,0,0}, + {16205,17289,16207 ,726,726,726 ,0,0,0}, {17384,16204,16201 ,726,5471,5471 ,0,0,0}, + {16165,17285,17284 ,726,726,5471 ,0,0,0}, {17286,17285,17386 ,726,726,5470 ,0,0,0}, + {17395,17408,17396 ,726,726,726 ,0,0,0}, {17410,17597,17387 ,5471,726,5471 ,0,0,0}, + {17388,17387,17597 ,5471,5471,726 ,0,0,0}, {17409,17408,17395 ,726,726,726 ,0,0,0}, + {17409,17597,17410 ,726,726,5471 ,0,0,0}, {17396,17391,17390 ,726,5470,726 ,0,0,0}, + {17292,17294,17389 ,5470,726,726 ,0,0,0}, {17393,17293,17394 ,726,726,5470 ,0,0,0}, + {17293,17292,17394 ,726,5470,5470 ,0,0,0}, {17400,17412,17411 ,726,726,726 ,0,0,0}, + {17392,17401,17598 ,726,726,5471 ,0,0,0}, {17598,17393,17392 ,5471,726,726 ,0,0,0}, + {17400,17399,17412 ,726,5470,726 ,0,0,0}, {17401,17400,17598 ,726,726,5471 ,0,0,0}, + {17397,17411,17398 ,5470,726,726 ,0,0,0}, {17379,17402,16285 ,726,726,726 ,0,0,0}, + {16271,16269,17297 ,726,726,5469 ,0,0,0}, {17380,16281,17599 ,5470,726,5470 ,0,0,0}, + {16280,17377,17599 ,726,5469,5470 ,0,0,0}, {17599,16281,16280 ,5470,726,726 ,0,0,0}, + {17376,16275,17345 ,5468,726,726 ,0,0,0}, {16275,17376,16277 ,726,5468,726 ,0,0,0}, + {16274,17345,16275 ,5471,726,726 ,0,0,0}, {17417,16268,16243 ,726,5471,5471 ,0,0,0}, + {16243,16242,17416 ,5471,5471,5470 ,0,0,0}, {17291,16268,17417 ,5469,5471,726 ,0,0,0}, + {17600,17601,16245 ,5470,5470,726 ,0,0,0}, {17573,16248,16251 ,726,5470,726 ,0,0,0}, + {17601,16242,16245 ,5470,5471,726 ,0,0,0}, {16252,16257,17602 ,726,726,726 ,0,0,0}, + {16252,17603,16251 ,726,5470,726 ,0,0,0}, {17604,16257,16255 ,726,726,5470 ,0,0,0}, + {16144,16146,15883 ,726,726,726 ,0,0,0}, {16260,16141,16254 ,726,726,5471 ,0,0,0}, + {16157,17605,16160 ,726,726,5470 ,0,0,0}, {16231,17606,16233 ,726,5471,5471 ,0,0,0}, + {17607,15989,15992 ,5471,5470,726 ,0,0,0}, {17608,15862,17609 ,726,726,5470 ,0,0,0}, + {16179,15893,17610 ,5471,5470,5470 ,0,0,0}, {17611,17612,16175 ,726,5471,726 ,0,0,0}, + {15869,16222,15868 ,726,5471,726 ,0,0,0}, {16340,16339,16214 ,5468,726,5471 ,0,0,0}, + {16264,16142,16260 ,5470,5471,726 ,0,0,0}, {16155,16154,17613 ,726,726,726 ,0,0,0}, + {15882,15856,16254 ,5470,5471,5471 ,0,0,0}, {17604,17602,16257 ,726,726,726 ,0,0,0}, + {17602,17603,16252 ,726,5470,726 ,0,0,0}, {17603,17574,16251 ,5470,5471,726 ,0,0,0}, + {16248,17600,16245 ,5470,5470,726 ,0,0,0}, {17600,16248,17573 ,5470,5470,726 ,0,0,0}, + {17298,16241,16239 ,5468,5469,726 ,0,0,0}, {17601,17416,16242 ,5470,5470,5471 ,0,0,0}, + {16269,16241,17297 ,726,5469,5469 ,0,0,0}, {17290,16269,16268 ,5468,726,5471 ,0,0,0}, + {17290,16241,16269 ,5468,5469,726 ,0,0,0}, {16239,16237,17596 ,726,5468,726 ,0,0,0}, + {16239,17596,17298 ,726,726,5468 ,0,0,0}, {16236,17568,17596 ,726,726,726 ,0,0,0}, + {16233,17606,17568 ,5471,5471,726 ,0,0,0}, {16230,17595,17528 ,5469,5468,5468 ,0,0,0}, + {16231,17528,17606 ,726,5468,5471 ,0,0,0}, {16211,16210,16339 ,5469,5468,726 ,0,0,0}, + {16230,16211,17595 ,5469,5469,5468 ,0,0,0}, {16214,16218,16340 ,5471,726,5468 ,0,0,0}, + {16210,16214,16339 ,5468,5471,726 ,0,0,0}, {16218,16217,16336 ,726,5471,5469 ,0,0,0}, + {15869,15872,16220 ,726,726,5469 ,0,0,0}, {15868,16222,16224 ,726,5471,5470 ,0,0,0}, + {17575,17609,15863 ,5471,5470,5471 ,0,0,0}, {15866,15868,16224 ,5471,726,5470 ,0,0,0}, + {17608,17604,15860 ,726,726,5470 ,0,0,0}, {16263,17614,16135 ,5470,5470,726 ,0,0,0}, + {16160,17615,16161 ,5470,5470,5470 ,0,0,0}, {17572,16133,16131 ,726,5489,726 ,0,0,0}, + {17458,16128,16125 ,726,726,726 ,0,0,0}, {17616,17472,17419 ,5489,5488,726 ,0,0,0}, + {17472,17616,17434 ,5488,5489,5489 ,0,0,0}, {17435,17413,17436 ,726,726,726 ,0,0,0}, + {17415,17617,17432 ,5489,726,726 ,0,0,0}, {17433,17432,17617 ,726,726,726 ,0,0,0}, + {17414,17413,17435 ,5488,726,726 ,0,0,0}, {17414,17617,17415 ,5488,726,5489 ,0,0,0}, + {17436,17280,17437 ,726,726,726 ,0,0,0}, {17281,17425,17282 ,726,726,726 ,0,0,0}, + {17441,17423,17439 ,5489,726,726 ,0,0,0}, {17423,17281,17439 ,726,726,726 ,0,0,0}, + {17427,17444,17428 ,726,726,726 ,0,0,0}, {17442,17441,17440 ,726,5489,726 ,0,0,0}, + {17444,17443,17428 ,726,726,726 ,0,0,0}, {17443,17442,17445 ,726,726,5488 ,0,0,0}, + {17427,17426,17289 ,726,5489,726 ,0,0,0}, {17448,17289,17446 ,726,726,5489 ,0,0,0}, + {16195,16193,17284 ,5471,726,5471 ,0,0,0}, {17289,17459,17287 ,726,726,726 ,0,0,0}, + {16204,17384,17459 ,5471,726,726 ,0,0,0}, {17459,16205,16204 ,726,726,5471 ,0,0,0}, + {17383,16199,17422 ,5471,726,726 ,0,0,0}, {16199,17383,16201 ,726,5471,5471 ,0,0,0}, + {16198,17422,16199 ,726,726,726 ,0,0,0}, {17618,16167,17455 ,5471,726,726 ,0,0,0}, + {16167,16166,17456 ,726,726,726 ,0,0,0}, {16192,16167,17618 ,726,726,5471 ,0,0,0}, + {17619,17620,16169 ,726,726,726 ,0,0,0}, {17612,16172,16175 ,5471,726,726 ,0,0,0}, + {17620,16166,16169 ,726,726,726 ,0,0,0}, {16176,16181,17621 ,726,726,726 ,0,0,0}, + {16176,17622,16175 ,726,5471,726 ,0,0,0}, {17610,16181,16179 ,5470,726,5471 ,0,0,0}, + {15898,16065,16068 ,5471,5471,726 ,0,0,0}, {16184,16065,16178 ,726,5471,726 ,0,0,0}, + {17623,15893,15892 ,5471,5470,726 ,0,0,0}, {16157,16155,17624 ,726,726,726 ,0,0,0}, + {15898,15895,16178 ,5471,726,726 ,0,0,0}, {16079,17625,16081 ,726,5470,726 ,0,0,0}, + {15986,16112,16111 ,5470,726,726 ,0,0,0}, {16099,17626,16096 ,726,726,5471 ,0,0,0}, + {16146,15886,15883 ,726,726,726 ,0,0,0}, {16264,16263,16138 ,5470,5470,726 ,0,0,0}, + {16188,16066,16184 ,5471,726,726 ,0,0,0}, {17588,16105,16103 ,726,726,726 ,0,0,0}, + {16178,15895,16179 ,726,726,5471 ,0,0,0}, {17610,17621,16181 ,5470,726,726 ,0,0,0}, + {17621,17622,16176 ,726,5471,726 ,0,0,0}, {17622,17611,16175 ,5471,726,726 ,0,0,0}, + {16172,17619,16169 ,726,726,726 ,0,0,0}, {17619,16172,17612 ,726,726,5471 ,0,0,0}, + {17627,16165,16163 ,5470,726,726 ,0,0,0}, {17620,17456,16166 ,726,726,726 ,0,0,0}, + {16193,16165,17284 ,726,726,5471 ,0,0,0}, {16165,16193,17429 ,726,726,5471 ,0,0,0}, + {17618,17429,16192 ,5471,5471,726 ,0,0,0}, {16165,17627,17285 ,726,5470,726 ,0,0,0}, + {16163,16161,17615 ,726,5470,5470 ,0,0,0}, {16163,17615,17627 ,726,5470,5470 ,0,0,0}, + {16160,17605,17615 ,5470,726,5470 ,0,0,0}, {16157,17624,17605 ,726,726,726 ,0,0,0}, + {16154,17614,17613 ,726,5470,726 ,0,0,0}, {16155,17613,17624 ,726,726,726 ,0,0,0}, + {16135,16134,16263 ,726,5470,5470 ,0,0,0}, {16154,16135,17614 ,726,726,5470 ,0,0,0}, + {16138,16142,16264 ,726,5471,5470 ,0,0,0}, {16134,16138,16263 ,5470,726,5470 ,0,0,0}, + {16142,16141,16260 ,5471,726,726 ,0,0,0}, {15883,15882,16144 ,726,5470,726 ,0,0,0}, + {15886,16148,15887 ,726,726,5471 ,0,0,0}, {15889,15887,17569 ,726,5471,726 ,0,0,0}, + {16146,16148,15886 ,726,726,726 ,0,0,0}, {17610,15893,17623 ,5470,5470,5471 ,0,0,0}, + {16129,17571,16131 ,5488,726,726 ,0,0,0}, {16331,15876,17533 ,5468,5470,726 ,0,0,0}, + {16055,17420,16057 ,5470,726,5470 ,0,0,0}, {17476,16052,16049 ,726,726,726 ,0,0,0}, + {17460,17628,17461 ,5471,726,726 ,0,0,0}, {17451,17461,17452 ,5471,726,726 ,0,0,0}, + {17497,17629,17464 ,726,5471,5471 ,0,0,0}, {17450,17464,17629 ,726,5471,5471 ,0,0,0}, + {17469,17527,17497 ,726,726,726 ,0,0,0}, {17527,17629,17497 ,726,5471,726 ,0,0,0}, + {17480,17490,17469 ,726,726,726 ,0,0,0}, {17630,17470,17469 ,726,726,726 ,0,0,0}, + {17467,17469,17482 ,726,726,726 ,0,0,0}, {17483,17482,17469 ,5488,726,726 ,0,0,0}, + {17525,17486,17526 ,5489,726,726 ,0,0,0}, {17485,17482,17481 ,726,726,726 ,0,0,0}, + {17486,17487,17526 ,726,726,726 ,0,0,0}, {17487,17485,17484 ,726,726,726 ,0,0,0}, + {17466,17525,17488 ,726,5489,726 ,0,0,0}, {17572,17465,16133 ,726,726,5489 ,0,0,0}, + {16117,16116,17419 ,726,5471,726 ,0,0,0}, {16128,17631,16129 ,726,726,5488 ,0,0,0}, + {17571,16129,17631 ,726,5488,726 ,0,0,0}, {17457,16123,17473 ,726,726,726 ,0,0,0}, + {17458,17631,16128 ,726,726,726 ,0,0,0}, {16123,17457,16125 ,726,726,726 ,0,0,0}, + {16122,17473,16123 ,726,726,726 ,0,0,0}, {17529,17419,17632 ,5470,726,5471 ,0,0,0}, + {17632,16091,17532 ,5471,726,5471 ,0,0,0}, {17632,17419,16091 ,5471,726,726 ,0,0,0}, + {16093,17633,16090 ,5471,726,726 ,0,0,0}, {16099,17634,17626 ,726,726,726 ,0,0,0}, + {16093,17635,17633 ,5471,726,726 ,0,0,0}, {17636,16084,16081 ,5471,726,726 ,0,0,0}, + {16084,17637,16085 ,726,726,726 ,0,0,0}, {17638,16079,16078 ,726,726,5471 ,0,0,0}, + {16187,17639,16059 ,5471,5471,5471 ,0,0,0}, {16062,16188,16187 ,726,5471,5471 ,0,0,0}, + {15898,16178,16065 ,5471,726,5471 ,0,0,0}, {17640,17641,17642 ,5470,726,726 ,0,0,0}, + {17643,15905,16075 ,726,5470,5471 ,0,0,0}, {16111,17644,15983 ,726,726,726 ,0,0,0}, + {17645,16009,16008 ,5471,5470,5471 ,0,0,0}, {16008,16005,17646 ,5471,726,726 ,0,0,0}, + {16108,15989,16102 ,726,5470,726 ,0,0,0}, {15901,16068,16070 ,5471,726,726 ,0,0,0}, + {16112,15990,16108 ,726,5471,726 ,0,0,0}, {16002,17647,16003 ,726,726,5471 ,0,0,0}, + {16102,17648,16103 ,726,726,726 ,0,0,0}, {17588,17385,16105 ,726,5470,726 ,0,0,0}, + {17385,17593,16100 ,5470,726,726 ,0,0,0}, {17593,17634,16099 ,726,726,726 ,0,0,0}, + {16096,17635,16093 ,5471,726,5471 ,0,0,0}, {17635,16096,17626 ,726,5471,726 ,0,0,0}, + {17637,17649,16087 ,726,726,726 ,0,0,0}, {16087,17649,17419 ,726,726,726 ,0,0,0}, + {17633,17532,16090 ,726,5471,726 ,0,0,0}, {16119,16117,17419 ,726,726,726 ,0,0,0}, + {17419,16116,16091 ,726,5471,726 ,0,0,0}, {16089,17419,17530 ,5471,726,5471 ,0,0,0}, + {17649,17616,17419 ,726,5489,726 ,0,0,0}, {16087,16085,17637 ,726,726,726 ,0,0,0}, + {16084,17636,17637 ,726,5471,726 ,0,0,0}, {16081,17625,17636 ,726,5470,5471 ,0,0,0}, + {16078,17639,17638 ,5471,5471,726 ,0,0,0}, {16079,17638,17625 ,726,726,5470 ,0,0,0}, + {16059,16058,16187 ,5471,726,5471 ,0,0,0}, {16078,16059,17639 ,5471,5471,5471 ,0,0,0}, + {16062,16066,16188 ,726,726,5471 ,0,0,0}, {16058,16062,16187 ,726,726,5471 ,0,0,0}, + {16066,16065,16184 ,726,5471,726 ,0,0,0}, {15901,15898,16068 ,5471,5471,726 ,0,0,0}, + {15901,16070,15904 ,5471,726,726 ,0,0,0}, {16072,15905,15904 ,726,5470,726 ,0,0,0}, + {16072,15904,16070 ,726,726,726 ,0,0,0}, {16072,16075,15905 ,726,5471,5470 ,0,0,0}, + {17650,15948,15953 ,5468,5469,5470 ,0,0,0}, {17506,17518,17513 ,5468,5469,726 ,0,0,0}, + {16293,15956,16294 ,5468,5471,5469 ,0,0,0}, {15976,15973,17506 ,5469,5471,5468 ,0,0,0}, + {15937,17519,17518 ,5469,726,5469 ,0,0,0}, {17517,17519,17511 ,726,726,726 ,0,0,0}, + {17551,17548,17550 ,726,5471,726 ,0,0,0}, {17547,17651,17509 ,5471,5468,5471 ,0,0,0}, + {17510,17509,17651 ,5468,5471,5468 ,0,0,0}, {17549,17548,17551 ,5468,5471,726 ,0,0,0}, + {17549,17651,17547 ,5468,5468,5471 ,0,0,0}, {17550,17515,17514 ,726,5470,726 ,0,0,0}, + {17522,17521,17516 ,726,5469,5469 ,0,0,0}, {17541,17520,17542 ,5470,5471,726 ,0,0,0}, + {17520,17522,17542 ,5471,726,726 ,0,0,0}, {17538,17534,17536 ,726,726,5471 ,0,0,0}, + {17540,17539,17652 ,726,5470,726 ,0,0,0}, {17652,17541,17540 ,726,5470,726 ,0,0,0}, + {17538,17537,17534 ,726,5471,726 ,0,0,0}, {17539,17538,17652 ,5470,726,726 ,0,0,0}, + {17505,17536,17535 ,726,5471,5470 ,0,0,0}, {17420,17504,16057 ,726,726,5470 ,0,0,0}, + {16043,16041,17460 ,726,5470,5471 ,0,0,0}, {16052,17653,16053 ,726,726,726 ,0,0,0}, + {17421,16053,17653 ,726,726,726 ,0,0,0}, {17475,16047,17531 ,5471,5470,726 ,0,0,0}, + {17476,17653,16052 ,726,726,726 ,0,0,0}, {16047,17475,16049 ,5470,5471,726 ,0,0,0}, + {16046,17531,16047 ,5470,726,5470 ,0,0,0}, {17587,16040,16015 ,5471,5471,5471 ,0,0,0}, + {16015,16014,17586 ,5471,726,5471 ,0,0,0}, {17501,16040,17587 ,5471,5471,5471 ,0,0,0}, + {17654,17655,16017 ,5471,726,726 ,0,0,0}, {17462,16020,16023 ,726,5470,5470 ,0,0,0}, + {17655,16014,16017 ,726,726,726 ,0,0,0}, {16024,16029,17656 ,5470,726,726 ,0,0,0}, + {16024,17657,16023 ,5470,726,5470 ,0,0,0}, {17658,16029,16027 ,726,726,726 ,0,0,0}, + {15916,15918,17659 ,726,5471,5471 ,0,0,0}, {16003,17660,16005 ,5471,726,726 ,0,0,0}, + {17661,17662,17663 ,5471,726,726 ,0,0,0}, {15951,17661,17664 ,5471,5471,5471 ,0,0,0}, + {17533,15876,17665 ,726,5470,5469 ,0,0,0}, {16293,16296,17666 ,5468,5468,5470 ,0,0,0}, + {15932,17667,15933 ,726,726,5471 ,0,0,0}, {15951,17664,15953 ,5471,5471,5470 ,0,0,0}, + {16032,15913,16026 ,726,5470,5470 ,0,0,0}, {15994,17668,17669 ,5470,5471,726 ,0,0,0}, + {16036,15914,16032 ,726,5471,726 ,0,0,0}, {17670,17659,15918 ,5471,5471,5471 ,0,0,0}, + {17671,17672,16026 ,726,5471,5470 ,0,0,0}, {17658,17656,16029 ,726,726,726 ,0,0,0}, + {17656,17657,16024 ,726,726,5470 ,0,0,0}, {17657,17463,16023 ,726,726,5470 ,0,0,0}, + {16020,17654,16017 ,5470,5471,726 ,0,0,0}, {17654,16020,17462 ,5471,5470,726 ,0,0,0}, + {16011,17645,17628 ,5471,5471,726 ,0,0,0}, {17628,16013,16011 ,726,726,5471 ,0,0,0}, + {17655,17586,16014 ,726,5471,726 ,0,0,0}, {16041,16013,17460 ,5470,726,5471 ,0,0,0}, + {17500,16041,16040 ,726,5470,5471 ,0,0,0}, {17500,16013,16041 ,726,726,5470 ,0,0,0}, + {17460,16013,17628 ,5471,726,726 ,0,0,0}, {16011,16009,17645 ,5471,5470,5471 ,0,0,0}, + {16008,17646,17645 ,5471,726,5471 ,0,0,0}, {16005,17660,17646 ,726,726,726 ,0,0,0}, + {16002,17644,17647 ,726,726,726 ,0,0,0}, {16003,17647,17660 ,5471,726,726 ,0,0,0}, + {15983,15982,16111 ,726,5471,726 ,0,0,0}, {16002,15983,17644 ,726,726,726 ,0,0,0}, + {15986,15990,16112 ,5470,5471,726 ,0,0,0}, {15982,15986,16111 ,5471,5470,726 ,0,0,0}, + {15990,15989,16108 ,5471,5470,726 ,0,0,0}, {17669,17607,15992 ,726,5471,726 ,0,0,0}, + {16102,15989,17607 ,726,5470,5471 ,0,0,0}, {15999,17673,17674 ,726,726,726 ,0,0,0}, + {17668,15996,17674 ,5471,726,726 ,0,0,0}, {17675,17676,17677 ,5470,5470,5471 ,0,0,0}, + {15979,17582,15981 ,5468,5470,5483 ,0,0,0}, {16287,16286,15959 ,726,5468,5468 ,0,0,0}, + {15979,15977,17581 ,5468,5469,5470 ,0,0,0}, {16315,17279,17578 ,726,5468,5468 ,0,0,0}, + {16312,17580,17279 ,5469,726,5468 ,0,0,0}, {17578,17579,17299 ,5468,5468,5469 ,0,0,0}, + {17308,17579,17309 ,5476,5468,5471 ,0,0,0}, {17336,17339,17334 ,5468,5468,5475 ,0,0,0}, + {17338,17678,17564 ,5483,726,5468 ,0,0,0}, {17307,17564,17678 ,5475,5468,726 ,0,0,0}, + {17337,17339,17336 ,5486,5468,5468 ,0,0,0}, {17337,17678,17338 ,5486,726,5483 ,0,0,0}, + {17334,17311,17335 ,5475,5478,5485 ,0,0,0}, {17312,17323,17310 ,5469,5468,5477 ,0,0,0}, + {17316,17322,17314 ,726,726,5471 ,0,0,0}, {17322,17312,17314 ,726,5469,5471 ,0,0,0}, + {17566,17320,17567 ,5472,5480,5482 ,0,0,0}, {17321,17316,17315 ,5481,726,5469 ,0,0,0}, + {17320,17319,17567 ,5480,726,5482 ,0,0,0}, {17319,17321,17331 ,726,5481,5475 ,0,0,0}, + {17324,17566,17327 ,5475,5472,5468 ,0,0,0}, {17582,17325,15981 ,5470,5475,5483 ,0,0,0}, + {17506,15965,17583 ,5468,726,5468 ,0,0,0}, {15976,17508,15977 ,5469,5469,5469 ,0,0,0}, + {17581,15977,17508 ,5470,5469,5469 ,0,0,0}, {17679,17507,17506 ,5468,726,5468 ,0,0,0}, + {17508,15976,17506 ,5469,5469,5468 ,0,0,0}, {17506,15973,15971 ,5468,5471,5470 ,0,0,0}, + {17506,15970,15967 ,5468,5469,5471 ,0,0,0}, {17680,15939,17584 ,5469,5468,5469 ,0,0,0}, + {15939,15938,17585 ,5468,5471,5471 ,0,0,0}, {15964,15939,17680 ,5468,5468,5469 ,0,0,0}, + {17681,17682,15941 ,5470,5471,5468 ,0,0,0}, {17502,15944,15947 ,5470,726,5468 ,0,0,0}, + {17682,15938,15941 ,5471,5471,5468 ,0,0,0}, {16296,16298,17683 ,5468,5468,5468 ,0,0,0}, + {15910,16036,16035 ,5471,726,726 ,0,0,0}, {15948,17684,15947 ,5469,5469,5468 ,0,0,0}, + {17685,15927,15926 ,726,5471,726 ,0,0,0}, {17686,15932,15929 ,726,726,5470 ,0,0,0}, + {17687,15907,16035 ,726,5470,726 ,0,0,0}, {17688,15929,15927 ,726,5470,5471 ,0,0,0}, + {16293,15950,15956 ,5468,5469,5471 ,0,0,0}, {16296,17683,17666 ,5468,5468,5470 ,0,0,0}, + {15956,15960,16294 ,5471,726,5469 ,0,0,0}, {15959,16290,15960 ,5468,5468,726 ,0,0,0}, + {16294,15960,16290 ,5469,726,5468 ,0,0,0}, {15875,17577,17665 ,5469,5469,5469 ,0,0,0}, + {16300,15880,17689 ,5471,5470,726 ,0,0,0}, {15880,17576,15878 ,5470,5469,726 ,0,0,0}, + {15950,17690,15951 ,5469,5471,5471 ,0,0,0}, {17664,17650,15953 ,5471,5468,5470 ,0,0,0}, + {17650,17684,15948 ,5468,5469,5469 ,0,0,0}, {17684,17503,15947 ,5469,5468,5468 ,0,0,0}, + {15944,17681,15941 ,726,5470,5468 ,0,0,0}, {17681,15944,17502 ,5470,726,5470 ,0,0,0}, + {15935,17667,17691 ,726,726,5471 ,0,0,0}, {17691,15937,15935 ,5471,5469,726 ,0,0,0}, + {17682,17585,15938 ,5471,5471,5471 ,0,0,0}, {15937,17518,17506 ,5469,5469,5468 ,0,0,0}, + {17506,17583,15937 ,5468,5468,5469 ,0,0,0}, {17680,17583,15964 ,5469,5468,5468 ,0,0,0}, + {15937,17691,17519 ,5469,5471,726 ,0,0,0}, {15935,15933,17667 ,726,5471,726 ,0,0,0}, + {15932,17686,17667 ,726,726,726 ,0,0,0}, {15929,17688,17686 ,5470,726,726 ,0,0,0}, + {15926,17687,17685 ,726,726,726 ,0,0,0}, {15927,17685,17688 ,5471,726,726 ,0,0,0}, + {15907,15906,16035 ,5470,726,726 ,0,0,0}, {15926,15907,17687 ,726,5470,726 ,0,0,0}, + {15910,15914,16036 ,5471,5471,726 ,0,0,0}, {15906,15910,16035 ,726,5471,726 ,0,0,0}, + {15914,15913,16032 ,5471,5470,726 ,0,0,0}, {17659,17671,15916 ,5471,726,726 ,0,0,0}, + {17670,15920,17692 ,5471,726,726 ,0,0,0}, {17590,17692,17591 ,5471,726,5470 ,0,0,0}, + {15918,15920,17670 ,5471,726,5471 ,0,0,0}, {17664,17661,17663 ,5471,5471,726 ,0,0,0}, + {17658,16027,17693 ,726,726,5471 ,0,0,0}, {17604,16255,15860 ,726,5470,5470 ,0,0,0}, + {17658,17693,17675 ,726,5471,5470 ,0,0,0}, {15895,15893,16179 ,726,5470,5471 ,0,0,0}, + {15889,17570,15892 ,726,5470,726 ,0,0,0}, {17623,15892,17570 ,5471,726,5470 ,0,0,0}, + {16255,16254,15856 ,5470,5471,5471 ,0,0,0}, {16151,15887,16148 ,726,5471,726 ,0,0,0}, + {16151,17569,15887 ,726,726,5471 ,0,0,0}, {15882,16254,16141 ,5470,5471,726 ,0,0,0}, + {16141,16144,15882 ,726,726,5470 ,0,0,0}, {16255,15856,15860 ,5470,5471,5470 ,0,0,0}, + {17608,15860,15862 ,726,5470,726 ,0,0,0}, {15874,16330,15872 ,5471,5469,726 ,0,0,0}, + {17609,15862,15863 ,5470,726,5471 ,0,0,0}, {16227,15866,16224 ,726,5471,5470 ,0,0,0}, + {16227,17575,15866 ,726,5471,5471 ,0,0,0}, {16330,16217,15872 ,5469,5471,726 ,0,0,0}, + {16217,16220,15872 ,5471,5469,726 ,0,0,0}, {15874,15876,16331 ,5471,5470,5468 ,0,0,0}, + {17665,15876,15875 ,5469,5470,5469 ,0,0,0}, {17690,15950,17666 ,5471,5469,5470 ,0,0,0}, + {17577,15875,15878 ,5469,5469,726 ,0,0,0}, {16303,15880,16300 ,5469,5470,5471 ,0,0,0}, + {16303,17576,15880 ,5469,5469,5470 ,0,0,0}, {17666,15950,16293 ,5470,5469,5468 ,0,0,0}, + {17689,17683,16298 ,726,5468,5468 ,0,0,0}, {17689,16298,16300 ,726,5468,5471 ,0,0,0}, + {17690,17661,15951 ,5471,5471,5471 ,0,0,0}, {17590,17592,17662 ,5471,5471,726 ,0,0,0}, + {17663,17662,17592 ,726,726,5471 ,0,0,0}, {16027,16026,17672 ,726,5470,5471 ,0,0,0}, + {15923,17692,15920 ,726,726,726 ,0,0,0}, {15923,17591,17692 ,726,5470,726 ,0,0,0}, + {17671,16026,15913 ,726,5470,5470 ,0,0,0}, {15913,15916,17671 ,5470,726,726 ,0,0,0}, + {16027,17672,17693 ,726,5471,5471 ,0,0,0}, {17677,17676,17694 ,5471,5470,726 ,0,0,0}, + {17675,17693,17676 ,5470,5471,5470 ,0,0,0}, {17694,17674,17673 ,726,726,726 ,0,0,0}, + {17673,17677,17694 ,726,5471,726 ,0,0,0}, {17674,15996,15999 ,726,726,726 ,0,0,0}, + {17668,15994,15996 ,5471,5470,726 ,0,0,0}, {17669,15992,15994 ,726,726,5470 ,0,0,0}, + {16102,17607,17648 ,726,5471,726 ,0,0,0}, {17589,17695,17588 ,5471,5471,726 ,0,0,0}, + {16103,17648,17589 ,726,726,5471 ,0,0,0}, {17641,17695,17642 ,726,5471,726 ,0,0,0}, + {17589,17642,17695 ,5471,726,5471 ,0,0,0}, {17641,17640,17643 ,726,5470,726 ,0,0,0}, + {15905,17643,17640 ,5470,726,5470 ,0,0,0}, {17679,17506,17512 ,5468,5468,5468 ,0,0,0}, + {15971,15970,17506 ,5470,5469,5468 ,0,0,0}, {17469,17489,17483 ,726,726,5488 ,0,0,0}, + {17478,17630,17469 ,5488,726,726 ,0,0,0}, {17419,16089,16087 ,726,5471,726 ,0,0,0}, + {17594,17419,17474 ,726,726,726 ,0,0,0}, {17560,17559,17557 ,5469,5470,5468 ,0,0,0}, + {17560,17302,17558 ,5469,5468,5469 ,0,0,0}, {17446,17289,17288 ,5489,726,726 ,0,0,0}, + {16209,16207,17289 ,726,726,726 ,0,0,0}, {17696,17697,17698 ,5490,5491,5492 ,0,0,0}, + {17699,17700,17701 ,5493,5494,5495 ,0,0,0}, {17702,17700,17703 ,5496,5494,5497 ,0,0,0}, + {17704,17705,17706 ,5498,5499,5500 ,0,0,0}, {17707,17708,17709 ,5501,5502,5503 ,0,0,0}, + {17710,17711,17712 ,5504,5505,5506 ,0,0,0}, {17713,17714,17715 ,5507,5508,5509 ,0,0,0}, + {17326,17330,17710 ,5510,5511,5504 ,0,0,0}, {17716,17717,17718 ,5512,5513,5514 ,0,0,0}, + {17707,17712,17711 ,5501,5506,5505 ,0,0,0}, {17719,17720,17717 ,5515,5516,5513 ,0,0,0}, + {17721,17719,17717 ,5517,5515,5513 ,0,0,0}, {17721,17722,17719 ,5517,5518,5515 ,0,0,0}, + {17722,17721,17723 ,5518,5517,5519 ,0,0,0}, {17724,17720,17725 ,5520,5516,5521 ,0,0,0}, + {17726,17727,17728 ,5522,5523,5524 ,0,0,0}, {17717,17720,17724 ,5513,5516,5520 ,0,0,0}, + {17728,17727,17723 ,5524,5523,5519 ,0,0,0}, {17729,17726,17730 ,5525,5522,5526 ,0,0,0}, + {17731,17732,17733 ,5527,5528,5529 ,0,0,0}, {17731,17724,17725 ,5527,5520,5521 ,0,0,0}, + {17734,17735,17736 ,5530,5531,5532 ,0,0,0}, {17731,17725,17732 ,5527,5521,5528 ,0,0,0}, + {17732,17734,17733 ,5528,5530,5529 ,0,0,0}, {17737,17738,17736 ,5533,5534,5532 ,0,0,0}, + {17714,17739,17715 ,5508,5535,5509 ,0,0,0}, {17736,17735,17737 ,5532,5531,5533 ,0,0,0}, + {17740,17699,17741 ,5536,5493,5537 ,0,0,0}, {17735,17742,17737 ,5531,5538,5533 ,0,0,0}, + {17714,17718,17739 ,5508,5514,5535 ,0,0,0}, {17743,17718,17724 ,5539,5514,5520 ,0,0,0}, + {17744,17745,17746 ,5540,5541,5542 ,0,0,0}, {17747,17744,17748 ,5543,5540,5544 ,0,0,0}, + {17305,17322,17697 ,5545,5546,5491 ,0,0,0}, {17749,17750,17751 ,5547,5548,5549 ,0,0,0}, + {17305,17696,17306 ,5545,5490,726 ,0,0,0}, {17752,17306,17696 ,5550,726,5490 ,0,0,0}, + {17753,17738,17754 ,5551,5534,5552 ,0,0,0}, {17734,17736,17733 ,5530,5532,5529 ,0,0,0}, + {17736,17738,17753 ,5532,5534,5551 ,0,0,0}, {17754,17755,17753 ,5552,5553,5551 ,0,0,0}, + {17756,17733,17753 ,5554,5529,5551 ,0,0,0}, {17718,17743,17739 ,5514,5539,5535 ,0,0,0}, + {17756,17743,17731 ,5554,5539,5527 ,0,0,0}, {17721,17757,17723 ,5517,5555,5519 ,0,0,0}, + {17731,17743,17724 ,5527,5539,5520 ,0,0,0}, {17758,17759,17728 ,5556,5557,5524 ,0,0,0}, + {17717,17724,17718 ,5513,5520,5514 ,0,0,0}, {17757,17721,17716 ,5555,5517,5512 ,0,0,0}, + {17726,17728,17730 ,5522,5524,5526 ,0,0,0}, {17722,17723,17727 ,5518,5519,5523 ,0,0,0}, + {17723,17757,17758 ,5519,5555,5556 ,0,0,0}, {17760,17730,17728 ,5558,5526,5524 ,0,0,0}, + {17736,17753,17733 ,5532,5551,5529 ,0,0,0}, {17761,17755,17754 ,5559,5553,5552 ,0,0,0}, + {17761,17748,17755 ,5559,5544,5553 ,0,0,0}, {17733,17756,17731 ,5529,5554,5527 ,0,0,0}, + {17755,17762,17756 ,5553,5560,5554 ,0,0,0}, {17714,17703,17716 ,5508,5497,5512 ,0,0,0}, + {17762,17739,17743 ,5560,5535,5539 ,0,0,0}, {17699,17759,17758 ,5493,5557,5556 ,0,0,0}, + {17740,17759,17699 ,5536,5557,5493 ,0,0,0}, {17717,17716,17721 ,5513,5512,5517 ,0,0,0}, + {17718,17714,17716 ,5514,5508,5512 ,0,0,0}, {17723,17758,17728 ,5519,5556,5524 ,0,0,0}, + {17703,17700,17757 ,5497,5494,5555 ,0,0,0}, {17728,17759,17760 ,5524,5557,5558 ,0,0,0}, + {17758,17700,17699 ,5556,5494,5493 ,0,0,0}, {17763,17760,17759 ,5561,5558,5557 ,0,0,0}, + {17753,17755,17756 ,5551,5553,5554 ,0,0,0}, {17747,17748,17761 ,5543,5544,5559 ,0,0,0}, + {17764,17746,17765 ,5562,5542,5563 ,0,0,0}, {17756,17762,17743 ,5554,5560,5539 ,0,0,0}, + {17766,17762,17748 ,5564,5560,5544 ,0,0,0}, {17703,17714,17713 ,5497,5508,5507 ,0,0,0}, + {17766,17715,17739 ,5564,5509,5535 ,0,0,0}, {17767,17741,17701 ,5565,5537,5495 ,0,0,0}, + {17757,17700,17758 ,5555,5494,5556 ,0,0,0}, {17716,17703,17757 ,5512,5497,5555 ,0,0,0}, + {17703,17713,17702 ,5497,5507,5496 ,0,0,0}, {17740,17741,17768 ,5536,5537,5566 ,0,0,0}, + {17702,17701,17700 ,5496,5495,5494 ,0,0,0}, {17759,17740,17763 ,5557,5536,5561 ,0,0,0}, + {17699,17701,17741 ,5493,5495,5537 ,0,0,0}, {17769,17763,17740 ,5567,5561,5536 ,0,0,0}, + {17755,17748,17762 ,5553,5544,5560 ,0,0,0}, {17745,17744,17747 ,5541,5540,5543 ,0,0,0}, + {17715,17770,17713 ,5509,5568,5507 ,0,0,0}, {17762,17766,17739 ,5560,5564,5535 ,0,0,0}, + {17771,17766,17744 ,5569,5564,5540 ,0,0,0}, {17713,17772,17702 ,5507,5570,5496 ,0,0,0}, + {17771,17770,17715 ,5569,5568,5509 ,0,0,0}, {17702,17773,17701 ,5496,5571,5495 ,0,0,0}, + {17772,17713,17770 ,5570,5507,5568 ,0,0,0}, {17741,17704,17768 ,5537,5498,5566 ,0,0,0}, + {17773,17702,17772 ,5571,5496,5570 ,0,0,0}, {17774,17768,17706 ,5572,5566,5500 ,0,0,0}, + {17767,17701,17773 ,5565,5495,5571 ,0,0,0}, {17740,17768,17769 ,5536,5566,5567 ,0,0,0}, + {17741,17767,17704 ,5537,5565,5498 ,0,0,0}, {17774,17769,17768 ,5572,5567,5566 ,0,0,0}, + {17748,17744,17766 ,5544,5540,5564 ,0,0,0}, {17765,17746,17745 ,5563,5542,5541 ,0,0,0}, + {17770,17750,17772 ,5568,5548,5570 ,0,0,0}, {17766,17771,17715 ,5564,5569,5509 ,0,0,0}, + {17746,17775,17771 ,5542,5573,5569 ,0,0,0}, {17772,17749,17773 ,5570,5547,5571 ,0,0,0}, + {17775,17750,17770 ,5573,5548,5568 ,0,0,0}, {17773,17776,17767 ,5571,5574,5565 ,0,0,0}, + {17750,17749,17772 ,5548,5547,5570 ,0,0,0}, {17777,17704,17767 ,5575,5498,5565 ,0,0,0}, + {17776,17773,17749 ,5574,5571,5547 ,0,0,0}, {17778,17706,17709 ,5576,5500,5503 ,0,0,0}, + {17767,17776,17777 ,5565,5574,5575 ,0,0,0}, {17777,17705,17704 ,5575,5499,5498 ,0,0,0}, + {17774,17706,17778 ,5572,5500,5576 ,0,0,0}, {17768,17704,17706 ,5566,5498,5500 ,0,0,0}, + {17744,17746,17771 ,5540,5542,5569 ,0,0,0}, {17779,17764,17765 ,5577,5562,5563 ,0,0,0}, + {17780,17776,17749 ,5578,5574,5547 ,0,0,0}, {17771,17775,17770 ,5569,5573,5568 ,0,0,0}, + {17764,17698,17775 ,5562,5492,5573 ,0,0,0}, {17781,17777,17776 ,5579,5575,5574 ,0,0,0}, + {17698,17751,17750 ,5492,5549,5548 ,0,0,0}, {17782,17705,17777 ,5580,5499,5575 ,0,0,0}, + {17751,17780,17749 ,5549,5578,5547 ,0,0,0}, {17712,17707,17783 ,5506,5501,5581 ,0,0,0}, + {17780,17781,17776 ,5578,5579,5574 ,0,0,0}, {17709,17705,17784 ,5503,5499,5582 ,0,0,0}, + {17782,17777,17781 ,5580,5575,5579 ,0,0,0}, {17784,17705,17782 ,5582,5499,5580 ,0,0,0}, + {17778,17709,17708 ,5576,5503,5502 ,0,0,0}, {17706,17705,17709 ,5500,5499,5503 ,0,0,0}, + {17746,17764,17775 ,5542,5562,5573 ,0,0,0}, {17696,17779,17752 ,5490,5577,5550 ,0,0,0}, + {17697,17785,17751 ,5491,5583,5549 ,0,0,0}, {17775,17698,17750 ,5573,5492,5548 ,0,0,0}, + {17697,17751,17698 ,5491,5549,5492 ,0,0,0}, {17785,17786,17780 ,5583,5584,5578 ,0,0,0}, + {17785,17780,17751 ,5583,5578,5549 ,0,0,0}, {17786,17787,17781 ,5584,5585,5579 ,0,0,0}, + {17786,17781,17780 ,5584,5579,5578 ,0,0,0}, {17787,17788,17782 ,5585,5586,5580 ,0,0,0}, + {17787,17782,17781 ,5585,5580,5579 ,0,0,0}, {17788,17783,17784 ,5586,5581,5582 ,0,0,0}, + {17784,17782,17788 ,5582,5580,5586 ,0,0,0}, {17783,17707,17784 ,5581,5501,5582 ,0,0,0}, + {17708,17707,17711 ,5502,5501,5505 ,0,0,0}, {17709,17784,17707 ,5503,5582,5501 ,0,0,0}, + {17779,17696,17764 ,5577,5490,5562 ,0,0,0}, {17698,17764,17696 ,5492,5562,5490 ,0,0,0}, + {17785,17322,17316 ,5583,5546,5587 ,0,0,0}, {17305,17697,17696 ,5545,5491,5490 ,0,0,0}, + {17786,17316,17321 ,5584,5587,5588 ,0,0,0}, {17322,17785,17697 ,5546,5583,5491 ,0,0,0}, + {17787,17321,17320 ,5585,5588,5589 ,0,0,0}, {17316,17786,17785 ,5587,5584,5583 ,0,0,0}, + {17788,17320,17566 ,5586,5589,5590 ,0,0,0}, {17321,17787,17786 ,5588,5585,5584 ,0,0,0}, + {17783,17566,17324 ,5581,5590,5591 ,0,0,0}, {17320,17788,17787 ,5589,5586,5585 ,0,0,0}, + {17712,17324,17326 ,5506,5591,5510 ,0,0,0}, {17566,17783,17788 ,5590,5581,5586 ,0,0,0}, + {17326,17710,17712 ,5510,5504,5506 ,0,0,0}, {17324,17712,17783 ,5591,5506,5581 ,0,0,0}, + {17789,17790,17791 ,5592,5593,5594 ,0,0,0}, {17792,17793,17794 ,5595,5596,5597 ,0,0,0}, + {17790,17795,17791 ,5593,5598,5594 ,0,0,0}, {17796,17794,17793 ,5599,5597,5596 ,0,0,0}, + {17797,17798,17799 ,5600,5601,5602 ,0,0,0}, {17800,17801,17798 ,5603,5604,5601 ,0,0,0}, + {17802,17803,17804 ,5605,5606,5607 ,0,0,0}, {17805,17801,17800 ,5608,5604,5603 ,0,0,0}, + {17801,17799,17798 ,5604,5602,5601 ,0,0,0}, {17806,17798,17792 ,5609,5601,5595 ,0,0,0}, + {17807,17808,17809 ,5610,5611,5612 ,0,0,0}, {17810,17811,17812 ,5613,5614,5615 ,0,0,0}, + {17813,17808,17814 ,5616,5611,5617 ,0,0,0}, {17815,17816,17789 ,5618,5619,5592 ,0,0,0}, + {17803,17552,17520 ,5606,5620,5621 ,0,0,0}, {17817,17818,17819 ,5622,5623,5624 ,0,0,0}, + {17820,17554,17802 ,5625,5626,5605 ,0,0,0}, {17552,17802,17554 ,5620,5605,5626 ,0,0,0}, + {17821,17822,17823 ,5627,5628,5629 ,0,0,0}, {17795,17824,17791 ,5598,5630,5594 ,0,0,0}, + {17825,17826,17827 ,5631,5632,5633 ,0,0,0}, {17828,17829,17830 ,5634,5635,5636 ,0,0,0}, + {17819,17822,17831 ,5624,5628,5637 ,0,0,0}, {17832,17833,17834 ,5638,5639,5640 ,0,0,0}, + {17835,17789,17836 ,5641,5592,5642 ,0,0,0}, {17833,17828,17834 ,5639,5634,5640 ,0,0,0}, + {17815,17796,17793 ,5618,5599,5596 ,0,0,0}, {17543,17546,17832 ,5643,5644,5638 ,0,0,0}, + {17796,17815,17837 ,5599,5618,5645 ,0,0,0}, {17837,17815,17835 ,5645,5618,5641 ,0,0,0}, + {17838,17839,17835 ,5646,5647,5641 ,0,0,0}, {17815,17793,17816 ,5618,5596,5619 ,0,0,0}, + {17838,17840,17841 ,5646,5648,5649 ,0,0,0}, {17841,17839,17838 ,5649,5647,5646 ,0,0,0}, + {17842,17843,17844 ,5650,5651,5652 ,0,0,0}, {17843,17842,17840 ,5651,5650,5648 ,0,0,0}, + {17800,17798,17806 ,5603,5601,5609 ,0,0,0}, {17845,17797,17799 ,5653,5600,5602 ,0,0,0}, + {17845,17846,17797 ,5653,5654,5600 ,0,0,0}, {17806,17792,17794 ,5609,5595,5597 ,0,0,0}, + {17847,17792,17797 ,5655,5595,5600 ,0,0,0}, {17789,17816,17790 ,5592,5619,5593 ,0,0,0}, + {17847,17816,17793 ,5655,5619,5596 ,0,0,0}, {17838,17848,17840 ,5646,5656,5648 ,0,0,0}, + {17849,17843,17850 ,5657,5651,5658 ,0,0,0}, {17837,17835,17839 ,5645,5641,5647 ,0,0,0}, + {17835,17815,17789 ,5641,5618,5592 ,0,0,0}, {17841,17840,17842 ,5649,5648,5650 ,0,0,0}, + {17836,17848,17838 ,5642,5656,5646 ,0,0,0}, {17843,17851,17844 ,5651,5659,5652 ,0,0,0}, + {17840,17848,17850 ,5648,5656,5658 ,0,0,0}, {17852,17851,17843 ,5660,5659,5651 ,0,0,0}, + {17798,17797,17792 ,5601,5600,5595 ,0,0,0}, {17853,17846,17845 ,5661,5654,5653 ,0,0,0}, + {17853,17809,17846 ,5661,5612,5654 ,0,0,0}, {17792,17847,17793 ,5595,5655,5596 ,0,0,0}, + {17846,17854,17847 ,5654,5662,5655 ,0,0,0}, {17791,17823,17836 ,5594,5629,5642 ,0,0,0}, + {17854,17790,17816 ,5662,5593,5619 ,0,0,0}, {17819,17849,17850 ,5624,5657,5658 ,0,0,0}, + {17818,17849,17819 ,5623,5657,5624 ,0,0,0}, {17835,17836,17838 ,5641,5642,5646 ,0,0,0}, + {17789,17791,17836 ,5592,5594,5642 ,0,0,0}, {17840,17850,17843 ,5648,5658,5651 ,0,0,0}, + {17823,17822,17848 ,5629,5628,5656 ,0,0,0}, {17843,17849,17852 ,5651,5657,5660 ,0,0,0}, + {17850,17822,17819 ,5658,5628,5624 ,0,0,0}, {17855,17852,17849 ,5663,5660,5657 ,0,0,0}, + {17797,17846,17847 ,5600,5654,5655 ,0,0,0}, {17807,17809,17853 ,5610,5612,5661 ,0,0,0}, + {17856,17813,17857 ,5664,5616,5665 ,0,0,0}, {17847,17854,17816 ,5655,5662,5619 ,0,0,0}, + {17858,17854,17809 ,5666,5662,5612 ,0,0,0}, {17823,17791,17824 ,5629,5594,5630 ,0,0,0}, + {17858,17795,17790 ,5666,5598,5593 ,0,0,0}, {17859,17817,17831 ,5667,5622,5637 ,0,0,0}, + {17848,17822,17850 ,5656,5628,5658 ,0,0,0}, {17836,17823,17848 ,5642,5629,5656 ,0,0,0}, + {17823,17824,17821 ,5629,5630,5627 ,0,0,0}, {17818,17817,17860 ,5623,5622,5668 ,0,0,0}, + {17821,17831,17822 ,5627,5637,5628 ,0,0,0}, {17849,17818,17855 ,5657,5623,5663 ,0,0,0}, + {17819,17831,17817 ,5624,5637,5622 ,0,0,0}, {17861,17855,17818 ,5669,5663,5623 ,0,0,0}, + {17846,17809,17854 ,5654,5612,5662 ,0,0,0}, {17814,17808,17807 ,5617,5611,5610 ,0,0,0}, + {17795,17862,17824 ,5598,5670,5630 ,0,0,0}, {17854,17858,17790 ,5662,5666,5593 ,0,0,0}, + {17863,17858,17808 ,5671,5666,5611 ,0,0,0}, {17824,17864,17821 ,5630,5672,5627 ,0,0,0}, + {17863,17862,17795 ,5671,5670,5598 ,0,0,0}, {17821,17865,17831 ,5627,5673,5637 ,0,0,0}, + {17864,17824,17862 ,5672,5630,5670 ,0,0,0}, {17817,17826,17860 ,5622,5632,5668 ,0,0,0}, + {17865,17821,17864 ,5673,5627,5672 ,0,0,0}, {17866,17860,17825 ,5674,5668,5631 ,0,0,0}, + {17859,17831,17865 ,5667,5637,5673 ,0,0,0}, {17818,17860,17861 ,5623,5668,5669 ,0,0,0}, + {17817,17859,17826 ,5622,5667,5632 ,0,0,0}, {17866,17861,17860 ,5674,5669,5668 ,0,0,0}, + {17809,17808,17858 ,5612,5611,5666 ,0,0,0}, {17857,17813,17814 ,5665,5616,5617 ,0,0,0}, + {17862,17810,17864 ,5670,5613,5672 ,0,0,0}, {17858,17863,17795 ,5666,5671,5598 ,0,0,0}, + {17813,17867,17863 ,5616,5675,5671 ,0,0,0}, {17864,17812,17865 ,5672,5615,5673 ,0,0,0}, + {17867,17810,17862 ,5675,5613,5670 ,0,0,0}, {17865,17868,17859 ,5673,5676,5667 ,0,0,0}, + {17810,17812,17864 ,5613,5615,5672 ,0,0,0}, {17869,17826,17859 ,5677,5632,5667 ,0,0,0}, + {17868,17865,17812 ,5676,5673,5615 ,0,0,0}, {17870,17825,17830 ,5678,5631,5636 ,0,0,0}, + {17859,17868,17869 ,5667,5676,5677 ,0,0,0}, {17869,17827,17826 ,5677,5633,5632 ,0,0,0}, + {17866,17825,17870 ,5674,5631,5678 ,0,0,0}, {17860,17826,17825 ,5668,5632,5631 ,0,0,0}, + {17808,17813,17863 ,5611,5616,5671 ,0,0,0}, {17871,17856,17857 ,5679,5664,5665 ,0,0,0}, + {17872,17868,17812 ,5680,5676,5615 ,0,0,0}, {17863,17867,17862 ,5671,5675,5670 ,0,0,0}, + {17856,17804,17867 ,5664,5607,5675 ,0,0,0}, {17873,17869,17868 ,5681,5677,5676 ,0,0,0}, + {17804,17811,17810 ,5607,5614,5613 ,0,0,0}, {17874,17827,17869 ,5682,5633,5677 ,0,0,0}, + {17811,17872,17812 ,5614,5680,5615 ,0,0,0}, {17834,17828,17875 ,5640,5634,5683 ,0,0,0}, + {17872,17873,17868 ,5680,5681,5676 ,0,0,0}, {17830,17827,17876 ,5636,5633,5684 ,0,0,0}, + {17874,17869,17873 ,5682,5677,5681 ,0,0,0}, {17876,17827,17874 ,5684,5633,5682 ,0,0,0}, + {17870,17830,17829 ,5678,5636,5635 ,0,0,0}, {17825,17827,17830 ,5631,5633,5636 ,0,0,0}, + {17813,17856,17867 ,5616,5664,5675 ,0,0,0}, {17802,17871,17820 ,5605,5679,5625 ,0,0,0}, + {17803,17877,17811 ,5606,5685,5614 ,0,0,0}, {17867,17804,17810 ,5675,5607,5613 ,0,0,0}, + {17803,17811,17804 ,5606,5614,5607 ,0,0,0}, {17877,17878,17872 ,5685,5686,5680 ,0,0,0}, + {17877,17872,17811 ,5685,5680,5614 ,0,0,0}, {17878,17879,17873 ,5686,5687,5681 ,0,0,0}, + {17878,17873,17872 ,5686,5681,5680 ,0,0,0}, {17879,17880,17874 ,5687,5688,5682 ,0,0,0}, + {17879,17874,17873 ,5687,5682,5681 ,0,0,0}, {17880,17875,17876 ,5688,5683,5684 ,0,0,0}, + {17876,17874,17880 ,5684,5682,5688 ,0,0,0}, {17875,17828,17876 ,5683,5634,5684 ,0,0,0}, + {17829,17828,17833 ,5635,5634,5639 ,0,0,0}, {17830,17876,17828 ,5636,5684,5634 ,0,0,0}, + {17871,17802,17856 ,5679,5605,5664 ,0,0,0}, {17804,17856,17802 ,5607,5664,5605 ,0,0,0}, + {17877,17520,17541 ,5685,5621,5689 ,0,0,0}, {17552,17803,17802 ,5620,5606,5605 ,0,0,0}, + {17878,17541,17652 ,5686,5689,5690 ,0,0,0}, {17520,17877,17803 ,5621,5685,5606 ,0,0,0}, + {17879,17652,17538 ,5687,5690,5691 ,0,0,0}, {17541,17878,17877 ,5689,5686,5685 ,0,0,0}, + {17880,17538,17536 ,5688,5691,5692 ,0,0,0}, {17652,17879,17878 ,5690,5687,5686 ,0,0,0}, + {17875,17536,17505 ,5683,5692,5693 ,0,0,0}, {17538,17880,17879 ,5691,5688,5687 ,0,0,0}, + {17834,17505,17543 ,5640,5693,5643 ,0,0,0}, {17536,17875,17880 ,5692,5683,5688 ,0,0,0}, + {17543,17832,17834 ,5643,5638,5640 ,0,0,0}, {17505,17834,17875 ,5693,5640,5683 ,0,0,0}, + {17881,17882,17883 ,5694,5695,5696 ,0,0,0}, {17884,17885,17886 ,5697,5698,5699 ,0,0,0}, + {17883,17887,17888 ,5696,5700,5701 ,0,0,0}, {17887,17889,17888 ,5700,5702,5701 ,0,0,0}, + {17890,17891,17892 ,5703,5704,5705 ,0,0,0}, {17892,17893,17890 ,5705,5706,5703 ,0,0,0}, + {17894,17895,17896 ,5707,5708,5709 ,0,0,0}, {17897,17891,17898 ,5710,5704,5711 ,0,0,0}, + {17897,17892,17891 ,5710,5705,5704 ,0,0,0}, {17898,17899,17897 ,5711,5712,5710 ,0,0,0}, + {17900,17886,17901 ,5713,5699,5714 ,0,0,0}, {17902,17903,17904 ,5715,5716,5717 ,0,0,0}, + {17894,17468,17467 ,5707,5718,5719 ,0,0,0}, {17905,17906,17907 ,5720,5721,5722 ,0,0,0}, + {17908,17495,17896 ,5723,5724,5709 ,0,0,0}, {17909,17910,17903 ,5725,5726,5716 ,0,0,0}, + {17468,17896,17495 ,5718,5709,5724 ,0,0,0}, {17911,17912,17913 ,5727,5728,5729 ,0,0,0}, + {17914,17888,17889 ,5730,5701,5702 ,0,0,0}, {17915,17916,17917 ,5731,5732,5733 ,0,0,0}, + {17918,17919,17883 ,5734,5735,5696 ,0,0,0}, {17920,17921,17922 ,5736,5737,5738 ,0,0,0}, + {17913,17923,17924 ,5729,5739,5740 ,0,0,0}, {17925,17923,17926 ,5741,5739,5742 ,0,0,0}, + {17927,17928,17929 ,5743,5744,5745 ,0,0,0}, {17881,17885,17884 ,5694,5698,5697 ,0,0,0}, + {17928,17915,17929 ,5744,5731,5745 ,0,0,0}, {17919,17930,17881 ,5735,5746,5694 ,0,0,0}, + {17491,17496,17927 ,5747,5748,5743 ,0,0,0}, {17931,17932,17919 ,5749,5750,5735 ,0,0,0}, + {17930,17885,17881 ,5746,5698,5694 ,0,0,0}, {17931,17933,17934 ,5749,5751,5752 ,0,0,0}, + {17919,17932,17930 ,5735,5750,5746 ,0,0,0}, {17935,17936,17937 ,5753,5754,5755 ,0,0,0}, + {17932,17931,17934 ,5750,5749,5752 ,0,0,0}, {17938,17937,17939 ,5756,5755,5757 ,0,0,0}, + {17936,17935,17933 ,5754,5753,5751 ,0,0,0}, {17901,17891,17900 ,5714,5704,5713 ,0,0,0}, + {17891,17901,17898 ,5704,5714,5711 ,0,0,0}, {17893,17940,17890 ,5706,5758,5703 ,0,0,0}, + {17900,17884,17886 ,5713,5697,5699 ,0,0,0}, {17941,17900,17890 ,5759,5713,5703 ,0,0,0}, + {17883,17882,17887 ,5696,5695,5700 ,0,0,0}, {17941,17882,17884 ,5759,5695,5697 ,0,0,0}, + {17931,17942,17933 ,5749,5760,5751 ,0,0,0}, {17884,17882,17881 ,5697,5695,5694 ,0,0,0}, + {17943,17944,17936 ,5761,5762,5754 ,0,0,0}, {17919,17881,17883 ,5735,5694,5696 ,0,0,0}, + {17942,17931,17918 ,5760,5749,5734 ,0,0,0}, {17937,17936,17939 ,5755,5754,5757 ,0,0,0}, + {17934,17933,17935 ,5752,5751,5753 ,0,0,0}, {17933,17942,17943 ,5751,5760,5761 ,0,0,0}, + {17945,17939,17936 ,5763,5757,5754 ,0,0,0}, {17891,17890,17900 ,5704,5703,5713 ,0,0,0}, + {17946,17940,17893 ,5764,5758,5706 ,0,0,0}, {17946,17909,17940 ,5764,5725,5758 ,0,0,0}, + {17900,17941,17884 ,5713,5759,5697 ,0,0,0}, {17940,17947,17941 ,5758,5765,5759 ,0,0,0}, + {17888,17926,17918 ,5701,5742,5734 ,0,0,0}, {17947,17887,17882 ,5765,5700,5695 ,0,0,0}, + {17913,17944,17943 ,5729,5762,5761 ,0,0,0}, {17912,17944,17913 ,5728,5762,5729 ,0,0,0}, + {17919,17918,17931 ,5735,5734,5749 ,0,0,0}, {17883,17888,17918 ,5696,5701,5734 ,0,0,0}, + {17933,17943,17936 ,5751,5761,5754 ,0,0,0}, {17926,17923,17942 ,5742,5739,5760 ,0,0,0}, + {17936,17944,17945 ,5754,5762,5763 ,0,0,0}, {17943,17923,17913 ,5761,5739,5729 ,0,0,0}, + {17948,17945,17944 ,5766,5763,5762 ,0,0,0}, {17890,17940,17941 ,5703,5758,5759 ,0,0,0}, + {17910,17909,17946 ,5726,5725,5764 ,0,0,0}, {17949,17902,17950 ,5767,5715,5768 ,0,0,0}, + {17941,17947,17882 ,5759,5765,5695 ,0,0,0}, {17951,17947,17909 ,5769,5765,5725 ,0,0,0}, + {17926,17888,17914 ,5742,5701,5730 ,0,0,0}, {17951,17889,17887 ,5769,5702,5700 ,0,0,0}, + {17952,17911,17924 ,5770,5727,5740 ,0,0,0}, {17942,17923,17943 ,5760,5739,5761 ,0,0,0}, + {17918,17926,17942 ,5734,5742,5760 ,0,0,0}, {17926,17914,17925 ,5742,5730,5741 ,0,0,0}, + {17912,17911,17953 ,5728,5727,5771 ,0,0,0}, {17925,17924,17923 ,5741,5740,5739 ,0,0,0}, + {17944,17912,17948 ,5762,5728,5766 ,0,0,0}, {17913,17924,17911 ,5729,5740,5727 ,0,0,0}, + {17954,17948,17912 ,5772,5766,5728 ,0,0,0}, {17940,17909,17947 ,5758,5725,5765 ,0,0,0}, + {17904,17903,17910 ,5717,5716,5726 ,0,0,0}, {17889,17955,17914 ,5702,5773,5730 ,0,0,0}, + {17947,17951,17887 ,5765,5769,5700 ,0,0,0}, {17956,17951,17903 ,5774,5769,5716 ,0,0,0}, + {17914,17957,17925 ,5730,5775,5741 ,0,0,0}, {17956,17955,17889 ,5774,5773,5702 ,0,0,0}, + {17925,17958,17924 ,5741,5776,5740 ,0,0,0}, {17957,17914,17955 ,5775,5730,5773 ,0,0,0}, + {17911,17921,17953 ,5727,5737,5771 ,0,0,0}, {17958,17925,17957 ,5776,5741,5775 ,0,0,0}, + {17959,17953,17920 ,5777,5771,5736 ,0,0,0}, {17952,17924,17958 ,5770,5740,5776 ,0,0,0}, + {17912,17953,17954 ,5728,5771,5772 ,0,0,0}, {17911,17952,17921 ,5727,5770,5737 ,0,0,0}, + {17959,17954,17953 ,5777,5772,5771 ,0,0,0}, {17909,17903,17951 ,5725,5716,5769 ,0,0,0}, + {17950,17902,17904 ,5768,5715,5717 ,0,0,0}, {17955,17906,17957 ,5773,5721,5775 ,0,0,0}, + {17951,17956,17889 ,5769,5774,5702 ,0,0,0}, {17902,17960,17956 ,5715,5778,5774 ,0,0,0}, + {17957,17905,17958 ,5775,5720,5776 ,0,0,0}, {17960,17906,17955 ,5778,5721,5773 ,0,0,0}, + {17958,17961,17952 ,5776,5779,5770 ,0,0,0}, {17906,17905,17957 ,5721,5720,5775 ,0,0,0}, + {17962,17921,17952 ,5780,5737,5770 ,0,0,0}, {17961,17958,17905 ,5779,5776,5720 ,0,0,0}, + {17963,17920,17917 ,5781,5736,5733 ,0,0,0}, {17952,17961,17962 ,5770,5779,5780 ,0,0,0}, + {17962,17922,17921 ,5780,5738,5737 ,0,0,0}, {17959,17920,17963 ,5777,5736,5781 ,0,0,0}, + {17953,17921,17920 ,5771,5737,5736 ,0,0,0}, {17903,17902,17956 ,5716,5715,5774 ,0,0,0}, + {17964,17949,17950 ,5782,5767,5768 ,0,0,0}, {17965,17961,17905 ,5783,5779,5720 ,0,0,0}, + {17956,17960,17955 ,5774,5778,5773 ,0,0,0}, {17949,17895,17960 ,5767,5708,5778 ,0,0,0}, + {17966,17962,17961 ,5784,5780,5779 ,0,0,0}, {17895,17907,17906 ,5708,5722,5721 ,0,0,0}, + {17967,17922,17962 ,5785,5738,5780 ,0,0,0}, {17907,17965,17905 ,5722,5783,5720 ,0,0,0}, + {17929,17915,17968 ,5745,5731,5786 ,0,0,0}, {17965,17966,17961 ,5783,5784,5779 ,0,0,0}, + {17917,17922,17969 ,5733,5738,5787 ,0,0,0}, {17967,17962,17966 ,5785,5780,5784 ,0,0,0}, + {17969,17922,17967 ,5787,5738,5785 ,0,0,0}, {17963,17917,17916 ,5781,5733,5732 ,0,0,0}, + {17920,17922,17917 ,5736,5738,5733 ,0,0,0}, {17902,17949,17960 ,5715,5767,5778 ,0,0,0}, + {17896,17964,17908 ,5709,5782,5723 ,0,0,0}, {17894,17970,17907 ,5707,5788,5722 ,0,0,0}, + {17960,17895,17906 ,5778,5708,5721 ,0,0,0}, {17894,17907,17895 ,5707,5722,5708 ,0,0,0}, + {17970,17971,17965 ,5788,5789,5783 ,0,0,0}, {17970,17965,17907 ,5788,5783,5722 ,0,0,0}, + {17971,17972,17966 ,5789,5790,5784 ,0,0,0}, {17971,17966,17965 ,5789,5784,5783 ,0,0,0}, + {17972,17973,17967 ,5790,5791,5785 ,0,0,0}, {17972,17967,17966 ,5790,5785,5784 ,0,0,0}, + {17973,17968,17969 ,5791,5786,5787 ,0,0,0}, {17969,17967,17973 ,5787,5785,5791 ,0,0,0}, + {17968,17915,17969 ,5786,5731,5787 ,0,0,0}, {17916,17915,17928 ,5732,5731,5744 ,0,0,0}, + {17917,17969,17915 ,5733,5787,5731 ,0,0,0}, {17964,17896,17949 ,5782,5709,5767 ,0,0,0}, + {17895,17949,17896 ,5708,5767,5709 ,0,0,0}, {17970,17467,17482 ,5788,5719,5792 ,0,0,0}, + {17468,17894,17896 ,5718,5707,5709 ,0,0,0}, {17971,17482,17485 ,5789,5792,5793 ,0,0,0}, + {17467,17970,17894 ,5719,5788,5707 ,0,0,0}, {17972,17485,17486 ,5790,5793,5794 ,0,0,0}, + {17482,17971,17970 ,5792,5789,5788 ,0,0,0}, {17973,17486,17525 ,5791,5794,5795 ,0,0,0}, + {17485,17972,17971 ,5793,5790,5789 ,0,0,0}, {17968,17525,17466 ,5786,5795,5796 ,0,0,0}, + {17486,17973,17972 ,5794,5791,5790 ,0,0,0}, {17929,17466,17491 ,5745,5796,5747 ,0,0,0}, + {17525,17968,17973 ,5795,5786,5791 ,0,0,0}, {17491,17927,17929 ,5747,5743,5745 ,0,0,0}, + {17466,17929,17968 ,5796,5745,5786 ,0,0,0}, {17974,17975,17976 ,5797,5798,5799 ,0,0,0}, + {17977,16891,16892 ,5800,5801,5802 ,0,0,0}, {17976,17978,17979 ,5799,5803,5804 ,0,0,0}, + {17978,17980,17979 ,5803,5805,5804 ,0,0,0}, {17981,17982,17983 ,5806,5807,5808 ,0,0,0}, + {17983,17984,17981 ,5808,5809,5806 ,0,0,0}, {17985,17986,17987 ,5810,5811,5812 ,0,0,0}, + {17988,17982,16897 ,5813,5807,5814 ,0,0,0}, {17988,17983,17982 ,5813,5808,5807 ,0,0,0}, + {16897,16898,17988 ,5814,5815,5813 ,0,0,0}, {17989,16892,16895 ,5816,5802,5817 ,0,0,0}, + {17990,17991,17992 ,5818,5819,5820 ,0,0,0}, {17985,17424,17423 ,5810,5821,5822 ,0,0,0}, + {17993,17994,17995 ,5823,5824,5825 ,0,0,0}, {17996,17431,17987 ,5826,5827,5812 ,0,0,0}, + {17997,17998,17991 ,5828,5829,5819 ,0,0,0}, {17424,17987,17431 ,5821,5812,5827 ,0,0,0}, + {17999,18000,18001 ,5830,5831,5832 ,0,0,0}, {18002,17979,17980 ,5833,5804,5805 ,0,0,0}, + {18003,18004,18005 ,5834,5835,5836 ,0,0,0}, {18006,18007,17976 ,5837,5838,5799 ,0,0,0}, + {18008,18009,18010 ,5839,5840,5841 ,0,0,0}, {18001,18011,18012 ,5832,5842,5843 ,0,0,0}, + {18013,18011,18014 ,5844,5842,5845 ,0,0,0}, {18015,18016,18017 ,5846,5847,5848 ,0,0,0}, + {17974,16891,17977 ,5797,5801,5800 ,0,0,0}, {18016,18003,18017 ,5847,5834,5848 ,0,0,0}, + {18007,16889,17974 ,5838,5849,5797 ,0,0,0}, {17447,17454,18015 ,5850,5851,5846 ,0,0,0}, + {18018,16887,18007 ,5852,5853,5838 ,0,0,0}, {16889,16891,17974 ,5849,5801,5797 ,0,0,0}, + {18018,18019,16884 ,5852,5854,5855 ,0,0,0}, {18007,16887,16889 ,5838,5853,5849 ,0,0,0}, + {16882,18020,16883 ,5856,5857,5858 ,0,0,0}, {16887,18018,16884 ,5853,5852,5855 ,0,0,0}, + {16877,16883,18021 ,5067,5858,5859 ,0,0,0}, {18020,16882,18019 ,5857,5856,5854 ,0,0,0}, + {16895,17982,17989 ,5817,5807,5816 ,0,0,0}, {17982,16895,16897 ,5807,5817,5814 ,0,0,0}, + {17984,18022,17981 ,5809,5860,5806 ,0,0,0}, {17989,17977,16892 ,5816,5800,5802 ,0,0,0}, + {18023,17989,17981 ,5861,5816,5806 ,0,0,0}, {17976,17975,17978 ,5799,5798,5803 ,0,0,0}, + {18023,17975,17977 ,5861,5798,5800 ,0,0,0}, {18018,18024,18019 ,5852,5862,5854 ,0,0,0}, + {17977,17975,17974 ,5800,5798,5797 ,0,0,0}, {18025,18026,18020 ,5863,5864,5857 ,0,0,0}, + {18007,17974,17976 ,5838,5797,5799 ,0,0,0}, {18024,18018,18006 ,5862,5852,5837 ,0,0,0}, + {16883,18020,18021 ,5858,5857,5859 ,0,0,0}, {16884,18019,16882 ,5855,5854,5856 ,0,0,0}, + {18019,18024,18025 ,5854,5862,5863 ,0,0,0}, {18027,18021,18020 ,5865,5859,5857 ,0,0,0}, + {17982,17981,17989 ,5807,5806,5816 ,0,0,0}, {18028,18022,17984 ,5866,5860,5809 ,0,0,0}, + {18028,17997,18022 ,5866,5828,5860 ,0,0,0}, {17989,18023,17977 ,5816,5861,5800 ,0,0,0}, + {18022,18029,18023 ,5860,5867,5861 ,0,0,0}, {17979,18014,18006 ,5804,5845,5837 ,0,0,0}, + {18029,17978,17975 ,5867,5803,5798 ,0,0,0}, {18001,18026,18025 ,5832,5864,5863 ,0,0,0}, + {18000,18026,18001 ,5831,5864,5832 ,0,0,0}, {18007,18006,18018 ,5838,5837,5852 ,0,0,0}, + {17976,17979,18006 ,5799,5804,5837 ,0,0,0}, {18019,18025,18020 ,5854,5863,5857 ,0,0,0}, + {18014,18011,18024 ,5845,5842,5862 ,0,0,0}, {18020,18026,18027 ,5857,5864,5865 ,0,0,0}, + {18025,18011,18001 ,5863,5842,5832 ,0,0,0}, {18030,18027,18026 ,5868,5865,5864 ,0,0,0}, + {17981,18022,18023 ,5806,5860,5861 ,0,0,0}, {17998,17997,18028 ,5829,5828,5866 ,0,0,0}, + {18031,17990,18032 ,5869,5818,5870 ,0,0,0}, {18023,18029,17975 ,5861,5867,5798 ,0,0,0}, + {18033,18029,17997 ,5871,5867,5828 ,0,0,0}, {18014,17979,18002 ,5845,5804,5833 ,0,0,0}, + {18033,17980,17978 ,5871,5805,5803 ,0,0,0}, {18034,17999,18012 ,5872,5830,5843 ,0,0,0}, + {18024,18011,18025 ,5862,5842,5863 ,0,0,0}, {18006,18014,18024 ,5837,5845,5862 ,0,0,0}, + {18014,18002,18013 ,5845,5833,5844 ,0,0,0}, {18000,17999,18035 ,5831,5830,5873 ,0,0,0}, + {18013,18012,18011 ,5844,5843,5842 ,0,0,0}, {18026,18000,18030 ,5864,5831,5868 ,0,0,0}, + {18001,18012,17999 ,5832,5843,5830 ,0,0,0}, {18036,18030,18000 ,5874,5868,5831 ,0,0,0}, + {18022,17997,18029 ,5860,5828,5867 ,0,0,0}, {17992,17991,17998 ,5820,5819,5829 ,0,0,0}, + {17980,18037,18002 ,5805,5875,5833 ,0,0,0}, {18029,18033,17978 ,5867,5871,5803 ,0,0,0}, + {18038,18033,17991 ,5876,5871,5819 ,0,0,0}, {18002,18039,18013 ,5833,5877,5844 ,0,0,0}, + {18038,18037,17980 ,5876,5875,5805 ,0,0,0}, {18013,18040,18012 ,5844,5878,5843 ,0,0,0}, + {18039,18002,18037 ,5877,5833,5875 ,0,0,0}, {17999,18009,18035 ,5830,5840,5873 ,0,0,0}, + {18040,18013,18039 ,5878,5844,5877 ,0,0,0}, {18041,18035,18008 ,5879,5873,5839 ,0,0,0}, + {18034,18012,18040 ,5872,5843,5878 ,0,0,0}, {18000,18035,18036 ,5831,5873,5874 ,0,0,0}, + {17999,18034,18009 ,5830,5872,5840 ,0,0,0}, {18041,18036,18035 ,5879,5874,5873 ,0,0,0}, + {17997,17991,18033 ,5828,5819,5871 ,0,0,0}, {18032,17990,17992 ,5870,5818,5820 ,0,0,0}, + {18037,17994,18039 ,5875,5824,5877 ,0,0,0}, {18033,18038,17980 ,5871,5876,5805 ,0,0,0}, + {17990,18042,18038 ,5818,5880,5876 ,0,0,0}, {18039,17993,18040 ,5877,5823,5878 ,0,0,0}, + {18042,17994,18037 ,5880,5824,5875 ,0,0,0}, {18040,18043,18034 ,5878,5881,5872 ,0,0,0}, + {17994,17993,18039 ,5824,5823,5877 ,0,0,0}, {18044,18009,18034 ,5882,5840,5872 ,0,0,0}, + {18043,18040,17993 ,5881,5878,5823 ,0,0,0}, {18045,18008,18005 ,5883,5839,5836 ,0,0,0}, + {18034,18043,18044 ,5872,5881,5882 ,0,0,0}, {18044,18010,18009 ,5882,5841,5840 ,0,0,0}, + {18041,18008,18045 ,5879,5839,5883 ,0,0,0}, {18035,18009,18008 ,5873,5840,5839 ,0,0,0}, + {17991,17990,18038 ,5819,5818,5876 ,0,0,0}, {18046,18031,18032 ,5884,5869,5870 ,0,0,0}, + {18047,18043,17993 ,5885,5881,5823 ,0,0,0}, {18038,18042,18037 ,5876,5880,5875 ,0,0,0}, + {18031,17986,18042 ,5869,5811,5880 ,0,0,0}, {18048,18044,18043 ,5886,5882,5881 ,0,0,0}, + {17986,17995,17994 ,5811,5825,5824 ,0,0,0}, {18049,18010,18044 ,5887,5841,5882 ,0,0,0}, + {17995,18047,17993 ,5825,5885,5823 ,0,0,0}, {18017,18003,18050 ,5848,5834,5888 ,0,0,0}, + {18047,18048,18043 ,5885,5886,5881 ,0,0,0}, {18005,18010,18051 ,5836,5841,5889 ,0,0,0}, + {18049,18044,18048 ,5887,5882,5886 ,0,0,0}, {18051,18010,18049 ,5889,5841,5887 ,0,0,0}, + {18045,18005,18004 ,5883,5836,5835 ,0,0,0}, {18008,18010,18005 ,5839,5841,5836 ,0,0,0}, + {17990,18031,18042 ,5818,5869,5880 ,0,0,0}, {17987,18046,17996 ,5812,5884,5826 ,0,0,0}, + {17985,18052,17995 ,5810,5890,5825 ,0,0,0}, {18042,17986,17994 ,5880,5811,5824 ,0,0,0}, + {17985,17995,17986 ,5810,5825,5811 ,0,0,0}, {18052,18053,18047 ,5890,5891,5885 ,0,0,0}, + {18052,18047,17995 ,5890,5885,5825 ,0,0,0}, {18053,18054,18048 ,5891,5892,5886 ,0,0,0}, + {18053,18048,18047 ,5891,5886,5885 ,0,0,0}, {18054,18055,18049 ,5892,5893,5887 ,0,0,0}, + {18054,18049,18048 ,5892,5887,5886 ,0,0,0}, {18055,18050,18051 ,5893,5888,5889 ,0,0,0}, + {18051,18049,18055 ,5889,5887,5893 ,0,0,0}, {18050,18003,18051 ,5888,5834,5889 ,0,0,0}, + {18004,18003,18016 ,5835,5834,5847 ,0,0,0}, {18005,18051,18003 ,5836,5889,5834 ,0,0,0}, + {18046,17987,18031 ,5884,5812,5869 ,0,0,0}, {17986,18031,17987 ,5811,5869,5812 ,0,0,0}, + {18052,17423,17441 ,5890,5822,5894 ,0,0,0}, {17424,17985,17987 ,5821,5810,5812 ,0,0,0}, + {18053,17441,17442 ,5891,5894,5895 ,0,0,0}, {17423,18052,17985 ,5822,5890,5810 ,0,0,0}, + {18054,17442,17444 ,5892,5895,5896 ,0,0,0}, {17441,18053,18052 ,5894,5891,5890 ,0,0,0}, + {18055,17444,17427 ,5893,5896,5897 ,0,0,0}, {17442,18054,18053 ,5895,5892,5891 ,0,0,0}, + {18050,17427,17448 ,5888,5897,5898 ,0,0,0}, {17444,18055,18054 ,5896,5893,5892 ,0,0,0}, + {18017,17448,17447 ,5848,5898,5850 ,0,0,0}, {17427,18050,18055 ,5897,5888,5893 ,0,0,0}, + {17447,18015,18017 ,5850,5846,5848 ,0,0,0}, {17448,18017,18050 ,5898,5848,5888 ,0,0,0}, + {18056,18057,18058 ,5899,5900,5901 ,0,0,0}, {18059,18060,16860 ,5902,5903,5904 ,0,0,0}, + {18057,18061,18058 ,5900,5905,5901 ,0,0,0}, {16855,16860,18060 ,5906,5904,5903 ,0,0,0}, + {18062,18063,18064 ,5907,5908,5909 ,0,0,0}, {16865,18065,18063 ,5910,5911,5908 ,0,0,0}, + {18066,18067,18068 ,5912,5913,5914 ,0,0,0}, {16863,18065,16865 ,5915,5911,5910 ,0,0,0}, + {18065,18064,18063 ,5911,5909,5908 ,0,0,0}, {16859,18063,18059 ,5916,5908,5902 ,0,0,0}, + {18069,18070,18071 ,5917,5918,5919 ,0,0,0}, {18072,18073,18074 ,5920,5921,5922 ,0,0,0}, + {18075,18070,18076 ,5923,5918,5924 ,0,0,0}, {18077,18078,18056 ,5925,5926,5899 ,0,0,0}, + {18067,17374,17293 ,5913,5927,5928 ,0,0,0}, {18079,18080,18081 ,5929,5930,5931 ,0,0,0}, + {18082,17404,18066 ,5932,5933,5912 ,0,0,0}, {17374,18066,17404 ,5927,5912,5933 ,0,0,0}, + {18083,18084,18085 ,5934,5935,5936 ,0,0,0}, {18061,18086,18058 ,5905,5937,5901 ,0,0,0}, + {18087,18088,18089 ,5938,5939,5940 ,0,0,0}, {18090,18091,18092 ,5941,5942,5943 ,0,0,0}, + {18081,18084,18093 ,5931,5935,5944 ,0,0,0}, {18094,18095,18096 ,5945,5946,5947 ,0,0,0}, + {18097,18056,18098 ,5948,5899,5949 ,0,0,0}, {18095,18090,18096 ,5946,5941,5947 ,0,0,0}, + {18077,16855,18060 ,5925,5906,5903 ,0,0,0}, {17403,17407,18094 ,5950,5951,5945 ,0,0,0}, + {16855,18077,16853 ,5906,5925,5952 ,0,0,0}, {16853,18077,18097 ,5952,5925,5948 ,0,0,0}, + {18099,16848,18097 ,5953,5954,5948 ,0,0,0}, {18077,18060,18078 ,5925,5903,5926 ,0,0,0}, + {18099,18100,16852 ,5953,5955,5956 ,0,0,0}, {16852,16848,18099 ,5956,5954,5953 ,0,0,0}, + {16844,18101,16846 ,5957,5958,5959 ,0,0,0}, {18101,16844,18100 ,5958,5957,5955 ,0,0,0}, + {16865,18063,16859 ,5910,5908,5916 ,0,0,0}, {18102,18062,18064 ,5960,5907,5909 ,0,0,0}, + {18102,18103,18062 ,5960,5961,5907 ,0,0,0}, {16859,18059,16860 ,5916,5902,5904 ,0,0,0}, + {18104,18059,18062 ,5962,5902,5907 ,0,0,0}, {18056,18078,18057 ,5899,5926,5900 ,0,0,0}, + {18104,18078,18060 ,5962,5926,5903 ,0,0,0}, {18099,18105,18100 ,5953,5963,5955 ,0,0,0}, + {18106,18101,18107 ,5964,5958,5965 ,0,0,0}, {16853,18097,16848 ,5952,5948,5954 ,0,0,0}, + {18097,18077,18056 ,5948,5925,5899 ,0,0,0}, {16852,18100,16844 ,5956,5955,5957 ,0,0,0}, + {18098,18105,18099 ,5949,5963,5953 ,0,0,0}, {18101,18108,16846 ,5958,5966,5959 ,0,0,0}, + {18100,18105,18107 ,5955,5963,5965 ,0,0,0}, {18109,18108,18101 ,5967,5966,5958 ,0,0,0}, + {18063,18062,18059 ,5908,5907,5902 ,0,0,0}, {18110,18103,18102 ,5968,5961,5960 ,0,0,0}, + {18110,18071,18103 ,5968,5919,5961 ,0,0,0}, {18059,18104,18060 ,5902,5962,5903 ,0,0,0}, + {18103,18111,18104 ,5961,5969,5962 ,0,0,0}, {18058,18085,18098 ,5901,5936,5949 ,0,0,0}, + {18111,18057,18078 ,5969,5900,5926 ,0,0,0}, {18081,18106,18107 ,5931,5964,5965 ,0,0,0}, + {18080,18106,18081 ,5930,5964,5931 ,0,0,0}, {18097,18098,18099 ,5948,5949,5953 ,0,0,0}, + {18056,18058,18098 ,5899,5901,5949 ,0,0,0}, {18100,18107,18101 ,5955,5965,5958 ,0,0,0}, + {18085,18084,18105 ,5936,5935,5963 ,0,0,0}, {18101,18106,18109 ,5958,5964,5967 ,0,0,0}, + {18107,18084,18081 ,5965,5935,5931 ,0,0,0}, {18112,18109,18106 ,5970,5967,5964 ,0,0,0}, + {18062,18103,18104 ,5907,5961,5962 ,0,0,0}, {18069,18071,18110 ,5917,5919,5968 ,0,0,0}, + {18113,18075,18114 ,5971,5923,5972 ,0,0,0}, {18104,18111,18078 ,5962,5969,5926 ,0,0,0}, + {18115,18111,18071 ,5973,5969,5919 ,0,0,0}, {18085,18058,18086 ,5936,5901,5937 ,0,0,0}, + {18115,18061,18057 ,5973,5905,5900 ,0,0,0}, {18116,18079,18093 ,5974,5929,5944 ,0,0,0}, + {18105,18084,18107 ,5963,5935,5965 ,0,0,0}, {18098,18085,18105 ,5949,5936,5963 ,0,0,0}, + {18085,18086,18083 ,5936,5937,5934 ,0,0,0}, {18080,18079,18117 ,5930,5929,5975 ,0,0,0}, + {18083,18093,18084 ,5934,5944,5935 ,0,0,0}, {18106,18080,18112 ,5964,5930,5970 ,0,0,0}, + {18081,18093,18079 ,5931,5944,5929 ,0,0,0}, {18118,18112,18080 ,5976,5970,5930 ,0,0,0}, + {18103,18071,18111 ,5961,5919,5969 ,0,0,0}, {18076,18070,18069 ,5924,5918,5917 ,0,0,0}, + {18061,18119,18086 ,5905,5977,5937 ,0,0,0}, {18111,18115,18057 ,5969,5973,5900 ,0,0,0}, + {18120,18115,18070 ,5978,5973,5918 ,0,0,0}, {18086,18121,18083 ,5937,5979,5934 ,0,0,0}, + {18120,18119,18061 ,5978,5977,5905 ,0,0,0}, {18083,18122,18093 ,5934,5980,5944 ,0,0,0}, + {18121,18086,18119 ,5979,5937,5977 ,0,0,0}, {18079,18088,18117 ,5929,5939,5975 ,0,0,0}, + {18122,18083,18121 ,5980,5934,5979 ,0,0,0}, {18123,18117,18087 ,5981,5975,5938 ,0,0,0}, + {18116,18093,18122 ,5974,5944,5980 ,0,0,0}, {18080,18117,18118 ,5930,5975,5976 ,0,0,0}, + {18079,18116,18088 ,5929,5974,5939 ,0,0,0}, {18123,18118,18117 ,5981,5976,5975 ,0,0,0}, + {18071,18070,18115 ,5919,5918,5973 ,0,0,0}, {18114,18075,18076 ,5972,5923,5924 ,0,0,0}, + {18119,18072,18121 ,5977,5920,5979 ,0,0,0}, {18115,18120,18061 ,5973,5978,5905 ,0,0,0}, + {18075,18124,18120 ,5923,5982,5978 ,0,0,0}, {18121,18074,18122 ,5979,5922,5980 ,0,0,0}, + {18124,18072,18119 ,5982,5920,5977 ,0,0,0}, {18122,18125,18116 ,5980,5983,5974 ,0,0,0}, + {18072,18074,18121 ,5920,5922,5979 ,0,0,0}, {18126,18088,18116 ,5984,5939,5974 ,0,0,0}, + {18125,18122,18074 ,5983,5980,5922 ,0,0,0}, {18127,18087,18092 ,5985,5938,5943 ,0,0,0}, + {18116,18125,18126 ,5974,5983,5984 ,0,0,0}, {18126,18089,18088 ,5984,5940,5939 ,0,0,0}, + {18123,18087,18127 ,5981,5938,5985 ,0,0,0}, {18117,18088,18087 ,5975,5939,5938 ,0,0,0}, + {18070,18075,18120 ,5918,5923,5978 ,0,0,0}, {18128,18113,18114 ,5986,5971,5972 ,0,0,0}, + {18129,18125,18074 ,5987,5983,5922 ,0,0,0}, {18120,18124,18119 ,5978,5982,5977 ,0,0,0}, + {18113,18068,18124 ,5971,5914,5982 ,0,0,0}, {18130,18126,18125 ,5988,5984,5983 ,0,0,0}, + {18068,18073,18072 ,5914,5921,5920 ,0,0,0}, {18131,18089,18126 ,5989,5940,5984 ,0,0,0}, + {18073,18129,18074 ,5921,5987,5922 ,0,0,0}, {18096,18090,18132 ,5947,5941,5990 ,0,0,0}, + {18129,18130,18125 ,5987,5988,5983 ,0,0,0}, {18092,18089,18133 ,5943,5940,5991 ,0,0,0}, + {18131,18126,18130 ,5989,5984,5988 ,0,0,0}, {18133,18089,18131 ,5991,5940,5989 ,0,0,0}, + {18127,18092,18091 ,5985,5943,5942 ,0,0,0}, {18087,18089,18092 ,5938,5940,5943 ,0,0,0}, + {18075,18113,18124 ,5923,5971,5982 ,0,0,0}, {18066,18128,18082 ,5912,5986,5932 ,0,0,0}, + {18067,18134,18073 ,5913,5992,5921 ,0,0,0}, {18124,18068,18072 ,5982,5914,5920 ,0,0,0}, + {18067,18073,18068 ,5913,5921,5914 ,0,0,0}, {18134,18135,18129 ,5992,5993,5987 ,0,0,0}, + {18134,18129,18073 ,5992,5987,5921 ,0,0,0}, {18135,18136,18130 ,5993,5994,5988 ,0,0,0}, + {18135,18130,18129 ,5993,5988,5987 ,0,0,0}, {18136,18137,18131 ,5994,5995,5989 ,0,0,0}, + {18136,18131,18130 ,5994,5989,5988 ,0,0,0}, {18137,18132,18133 ,5995,5990,5991 ,0,0,0}, + {18133,18131,18137 ,5991,5989,5995 ,0,0,0}, {18132,18090,18133 ,5990,5941,5991 ,0,0,0}, + {18091,18090,18095 ,5942,5941,5946 ,0,0,0}, {18092,18133,18090 ,5943,5991,5941 ,0,0,0}, + {18128,18066,18113 ,5986,5912,5971 ,0,0,0}, {18068,18113,18066 ,5914,5971,5912 ,0,0,0}, + {18134,17293,17393 ,5992,5928,5996 ,0,0,0}, {17374,18067,18066 ,5927,5913,5912 ,0,0,0}, + {18135,17393,17598 ,5993,5996,5997 ,0,0,0}, {17293,18134,18067 ,5928,5992,5913 ,0,0,0}, + {18136,17598,17400 ,5994,5997,5998 ,0,0,0}, {17393,18135,18134 ,5996,5993,5992 ,0,0,0}, + {18137,17400,17411 ,5995,5998,5999 ,0,0,0}, {17598,18136,18135 ,5997,5994,5993 ,0,0,0}, + {18132,17411,17397 ,5990,5999,6000 ,0,0,0}, {17400,18137,18136 ,5998,5995,5994 ,0,0,0}, + {18096,17397,17403 ,5947,6000,5950 ,0,0,0}, {17411,18132,18137 ,5999,5990,5995 ,0,0,0}, + {17403,18094,18096 ,5950,5945,5947 ,0,0,0}, {17397,18096,18132 ,6000,5947,5990 ,0,0,0}, + {18138,18139,18140 ,6001,6002,6003 ,0,0,0}, {18141,16828,16825 ,6004,6005,6006 ,0,0,0}, + {18140,18142,18143 ,6003,6007,6008 ,0,0,0}, {18142,18144,18143 ,6007,6009,6008 ,0,0,0}, + {18145,18146,18147 ,6010,6011,6012 ,0,0,0}, {18147,18148,18145 ,6012,6013,6010 ,0,0,0}, + {18149,18150,18151 ,6014,6015,6016 ,0,0,0}, {18152,18146,16831 ,6017,6011,6018 ,0,0,0}, + {18152,18147,18146 ,6017,6012,6011 ,0,0,0}, {16831,16830,18152 ,6018,5020,6017 ,0,0,0}, + {18153,16825,16833 ,6019,6006,6020 ,0,0,0}, {18154,18155,18156 ,6021,6022,6023 ,0,0,0}, + {18149,17348,17364 ,6014,6024,6025 ,0,0,0}, {18157,18158,18159 ,6026,6027,6028 ,0,0,0}, + {18160,17351,18151 ,6029,6030,6016 ,0,0,0}, {18161,18162,18155 ,6031,6032,6022 ,0,0,0}, + {17348,18151,17351 ,6024,6016,6030 ,0,0,0}, {18163,18164,18165 ,6033,6034,6035 ,0,0,0}, + {18166,18143,18144 ,6036,6008,6009 ,0,0,0}, {18167,18168,18169 ,6037,6038,6039 ,0,0,0}, + {18170,18171,18140 ,6040,6041,6003 ,0,0,0}, {18172,18173,18174 ,6042,6043,6044 ,0,0,0}, + {18165,18175,18176 ,6035,6045,6046 ,0,0,0}, {18177,18175,18178 ,6047,6045,6048 ,0,0,0}, + {18179,18180,18181 ,6049,6050,6051 ,0,0,0}, {18138,16828,18141 ,6001,6005,6004 ,0,0,0}, + {18180,18167,18181 ,6050,6037,6051 ,0,0,0}, {18171,16817,18138 ,6041,6052,6001 ,0,0,0}, + {17367,17369,18179 ,6053,6054,6049 ,0,0,0}, {18182,16818,18171 ,6055,6056,6041 ,0,0,0}, + {16817,16828,18138 ,6052,6005,6001 ,0,0,0}, {18182,18183,16820 ,6055,6057,6058 ,0,0,0}, + {18171,16818,16817 ,6041,6056,6052 ,0,0,0}, {16814,18184,16815 ,6059,6060,6061 ,0,0,0}, + {16818,18182,16820 ,6056,6055,6058 ,0,0,0}, {16806,16815,18185 ,6062,6061,6063 ,0,0,0}, + {18184,16814,18183 ,6060,6059,6057 ,0,0,0}, {16833,18146,18153 ,6020,6011,6019 ,0,0,0}, + {18146,16833,16831 ,6011,6020,6018 ,0,0,0}, {18148,18186,18145 ,6013,6064,6010 ,0,0,0}, + {18153,18141,16825 ,6019,6004,6006 ,0,0,0}, {18187,18153,18145 ,6065,6019,6010 ,0,0,0}, + {18140,18139,18142 ,6003,6002,6007 ,0,0,0}, {18187,18139,18141 ,6065,6002,6004 ,0,0,0}, + {18182,18188,18183 ,6055,6066,6057 ,0,0,0}, {18141,18139,18138 ,6004,6002,6001 ,0,0,0}, + {18189,18190,18184 ,6067,6068,6060 ,0,0,0}, {18171,18138,18140 ,6041,6001,6003 ,0,0,0}, + {18188,18182,18170 ,6066,6055,6040 ,0,0,0}, {16815,18184,18185 ,6061,6060,6063 ,0,0,0}, + {16820,18183,16814 ,6058,6057,6059 ,0,0,0}, {18183,18188,18189 ,6057,6066,6067 ,0,0,0}, + {18191,18185,18184 ,6069,6063,6060 ,0,0,0}, {18146,18145,18153 ,6011,6010,6019 ,0,0,0}, + {18192,18186,18148 ,6070,6064,6013 ,0,0,0}, {18192,18161,18186 ,6070,6031,6064 ,0,0,0}, + {18153,18187,18141 ,6019,6065,6004 ,0,0,0}, {18186,18193,18187 ,6064,6071,6065 ,0,0,0}, + {18143,18178,18170 ,6008,6048,6040 ,0,0,0}, {18193,18142,18139 ,6071,6007,6002 ,0,0,0}, + {18165,18190,18189 ,6035,6068,6067 ,0,0,0}, {18164,18190,18165 ,6034,6068,6035 ,0,0,0}, + {18171,18170,18182 ,6041,6040,6055 ,0,0,0}, {18140,18143,18170 ,6003,6008,6040 ,0,0,0}, + {18183,18189,18184 ,6057,6067,6060 ,0,0,0}, {18178,18175,18188 ,6048,6045,6066 ,0,0,0}, + {18184,18190,18191 ,6060,6068,6069 ,0,0,0}, {18189,18175,18165 ,6067,6045,6035 ,0,0,0}, + {18194,18191,18190 ,6072,6069,6068 ,0,0,0}, {18145,18186,18187 ,6010,6064,6065 ,0,0,0}, + {18162,18161,18192 ,6032,6031,6070 ,0,0,0}, {18195,18154,18196 ,6073,6021,6074 ,0,0,0}, + {18187,18193,18139 ,6065,6071,6002 ,0,0,0}, {18197,18193,18161 ,6075,6071,6031 ,0,0,0}, + {18178,18143,18166 ,6048,6008,6036 ,0,0,0}, {18197,18144,18142 ,6075,6009,6007 ,0,0,0}, + {18198,18163,18176 ,6076,6033,6046 ,0,0,0}, {18188,18175,18189 ,6066,6045,6067 ,0,0,0}, + {18170,18178,18188 ,6040,6048,6066 ,0,0,0}, {18178,18166,18177 ,6048,6036,6047 ,0,0,0}, + {18164,18163,18199 ,6034,6033,6077 ,0,0,0}, {18177,18176,18175 ,6047,6046,6045 ,0,0,0}, + {18190,18164,18194 ,6068,6034,6072 ,0,0,0}, {18165,18176,18163 ,6035,6046,6033 ,0,0,0}, + {18200,18194,18164 ,6078,6072,6034 ,0,0,0}, {18186,18161,18193 ,6064,6031,6071 ,0,0,0}, + {18156,18155,18162 ,6023,6022,6032 ,0,0,0}, {18144,18201,18166 ,6009,6079,6036 ,0,0,0}, + {18193,18197,18142 ,6071,6075,6007 ,0,0,0}, {18202,18197,18155 ,6080,6075,6022 ,0,0,0}, + {18166,18203,18177 ,6036,6081,6047 ,0,0,0}, {18202,18201,18144 ,6080,6079,6009 ,0,0,0}, + {18177,18204,18176 ,6047,6082,6046 ,0,0,0}, {18203,18166,18201 ,6081,6036,6079 ,0,0,0}, + {18163,18173,18199 ,6033,6043,6077 ,0,0,0}, {18204,18177,18203 ,6082,6047,6081 ,0,0,0}, + {18205,18199,18172 ,6083,6077,6042 ,0,0,0}, {18198,18176,18204 ,6076,6046,6082 ,0,0,0}, + {18164,18199,18200 ,6034,6077,6078 ,0,0,0}, {18163,18198,18173 ,6033,6076,6043 ,0,0,0}, + {18205,18200,18199 ,6083,6078,6077 ,0,0,0}, {18161,18155,18197 ,6031,6022,6075 ,0,0,0}, + {18196,18154,18156 ,6074,6021,6023 ,0,0,0}, {18201,18158,18203 ,6079,6027,6081 ,0,0,0}, + {18197,18202,18144 ,6075,6080,6009 ,0,0,0}, {18154,18206,18202 ,6021,6084,6080 ,0,0,0}, + {18203,18157,18204 ,6081,6026,6082 ,0,0,0}, {18206,18158,18201 ,6084,6027,6079 ,0,0,0}, + {18204,18207,18198 ,6082,6085,6076 ,0,0,0}, {18158,18157,18203 ,6027,6026,6081 ,0,0,0}, + {18208,18173,18198 ,6086,6043,6076 ,0,0,0}, {18207,18204,18157 ,6085,6082,6026 ,0,0,0}, + {18209,18172,18169 ,6087,6042,6039 ,0,0,0}, {18198,18207,18208 ,6076,6085,6086 ,0,0,0}, + {18208,18174,18173 ,6086,6044,6043 ,0,0,0}, {18205,18172,18209 ,6083,6042,6087 ,0,0,0}, + {18199,18173,18172 ,6077,6043,6042 ,0,0,0}, {18155,18154,18202 ,6022,6021,6080 ,0,0,0}, + {18210,18195,18196 ,6088,6073,6074 ,0,0,0}, {18211,18207,18157 ,6089,6085,6026 ,0,0,0}, + {18202,18206,18201 ,6080,6084,6079 ,0,0,0}, {18195,18150,18206 ,6073,6015,6084 ,0,0,0}, + {18212,18208,18207 ,6090,6086,6085 ,0,0,0}, {18150,18159,18158 ,6015,6028,6027 ,0,0,0}, + {18213,18174,18208 ,6091,6044,6086 ,0,0,0}, {18159,18211,18157 ,6028,6089,6026 ,0,0,0}, + {18181,18167,18214 ,6051,6037,6092 ,0,0,0}, {18211,18212,18207 ,6089,6090,6085 ,0,0,0}, + {18169,18174,18215 ,6039,6044,6093 ,0,0,0}, {18213,18208,18212 ,6091,6086,6090 ,0,0,0}, + {18215,18174,18213 ,6093,6044,6091 ,0,0,0}, {18209,18169,18168 ,6087,6039,6038 ,0,0,0}, + {18172,18174,18169 ,6042,6044,6039 ,0,0,0}, {18154,18195,18206 ,6021,6073,6084 ,0,0,0}, + {18151,18210,18160 ,6016,6088,6029 ,0,0,0}, {18149,18216,18159 ,6014,6094,6028 ,0,0,0}, + {18206,18150,18158 ,6084,6015,6027 ,0,0,0}, {18149,18159,18150 ,6014,6028,6015 ,0,0,0}, + {18216,18217,18211 ,6094,6095,6089 ,0,0,0}, {18216,18211,18159 ,6094,6089,6028 ,0,0,0}, + {18217,18218,18212 ,6095,6096,6090 ,0,0,0}, {18217,18212,18211 ,6095,6090,6089 ,0,0,0}, + {18218,18219,18213 ,6096,6097,6091 ,0,0,0}, {18218,18213,18212 ,6096,6091,6090 ,0,0,0}, + {18219,18214,18215 ,6097,6092,6093 ,0,0,0}, {18215,18213,18219 ,6093,6091,6097 ,0,0,0}, + {18214,18167,18215 ,6092,6037,6093 ,0,0,0}, {18168,18167,18180 ,6038,6037,6050 ,0,0,0}, + {18169,18215,18167 ,6039,6093,6037 ,0,0,0}, {18210,18151,18195 ,6088,6016,6073 ,0,0,0}, + {18150,18195,18151 ,6015,6073,6016 ,0,0,0}, {18216,17364,17358 ,6094,6025,6098 ,0,0,0}, + {17348,18149,18151 ,6024,6014,6016 ,0,0,0}, {18217,17358,17362 ,6095,6098,6099 ,0,0,0}, + {17364,18216,18149 ,6025,6094,6014 ,0,0,0}, {18218,17362,17361 ,6096,6099,6100 ,0,0,0}, + {17358,18217,18216 ,6098,6095,6094 ,0,0,0}, {18219,17361,17371 ,6097,6100,6101 ,0,0,0}, + {17362,18218,18217 ,6099,6096,6095 ,0,0,0}, {18214,17371,17333 ,6092,6101,6102 ,0,0,0}, + {17361,18219,18218 ,6100,6097,6096 ,0,0,0}, {18181,17333,17367 ,6051,6102,6053 ,0,0,0}, + {17371,18214,18219 ,6101,6092,6097 ,0,0,0}, {17367,18179,18181 ,6053,6049,6051 ,0,0,0}, + {17333,18181,18214 ,6102,6051,6092 ,0,0,0}, {18220,18221,18222 ,730,6103,6103 ,0,0,0}, + {16450,16392,16389 ,6103,730,730 ,0,0,0}, {18223,18221,18224 ,6104,6103,6105 ,0,0,0}, + {18223,18225,18226 ,6104,6106,6103 ,0,0,0}, {18227,18222,18228 ,6107,6103,6108 ,0,0,0}, + {18225,18229,18230 ,6106,6109,6110 ,0,0,0}, {18231,18232,18228 ,6103,6111,6108 ,0,0,0}, + {18230,18233,18234 ,6110,6112,6110 ,0,0,0}, {18235,18231,18236 ,6111,6103,6103 ,0,0,0}, + {18234,18237,18238 ,6110,6113,6112 ,0,0,0}, {18238,18239,18240 ,6112,6109,6110 ,0,0,0}, + {18240,18241,18242 ,6110,6106,6114 ,0,0,0}, {18236,18243,18244 ,6103,730,6115 ,0,0,0}, + {18245,18242,18246 ,6105,6114,6104 ,0,0,0}, {18247,18248,18249 ,6111,730,6111 ,0,0,0}, + {18250,18242,18245 ,6111,6114,6105 ,0,0,0}, {18249,18251,18252 ,6111,6110,6114 ,0,0,0}, + {18253,18254,18255 ,730,6114,6108 ,0,0,0}, {16398,16463,16465 ,6110,6111,6110 ,0,0,0}, + {18256,18257,18258 ,6115,730,6111 ,0,0,0}, {16462,16397,16460 ,730,730,6114 ,0,0,0}, + {18259,18260,16381 ,6111,6110,6110 ,0,0,0}, {16393,16456,16395 ,730,6114,6103 ,0,0,0}, + {16378,16428,16425 ,730,730,6114 ,0,0,0}, {16392,16451,16454 ,730,730,6103 ,0,0,0}, + {16422,16374,16423 ,6114,730,730 ,0,0,0}, {16448,16450,16389 ,730,6103,730 ,0,0,0}, + {16372,16416,16369 ,6103,6103,730 ,0,0,0}, {16442,16444,16383 ,730,730,730 ,0,0,0}, + {16410,16407,16368 ,730,730,730 ,0,0,0}, {16436,16382,16362 ,730,730,730 ,0,0,0}, + {16366,16405,16404 ,730,730,730 ,0,0,0}, {16366,16367,16405 ,730,730,730 ,0,0,0}, + {16368,16407,16367 ,730,730,730 ,0,0,0}, {16436,16362,16400 ,730,730,730 ,0,0,0}, + {16362,16366,16401 ,730,730,730 ,0,0,0}, {16411,16369,16413 ,6103,730,730 ,0,0,0}, + {16368,16369,16411 ,730,730,6103 ,0,0,0}, {16382,16439,16383 ,730,730,730 ,0,0,0}, + {16382,16438,16439 ,730,730,730 ,0,0,0}, {16372,16374,16419 ,6103,730,6103 ,0,0,0}, + {16372,16419,16417 ,6103,6103,730 ,0,0,0}, {16389,16387,16445 ,730,730,6103 ,0,0,0}, + {16444,16387,16383 ,730,730,730 ,0,0,0}, {16378,16425,16375 ,730,6114,6103 ,0,0,0}, + {16374,16375,16423 ,730,6103,730 ,0,0,0}, {16392,16450,16451 ,730,6103,730 ,0,0,0}, + {16431,16429,16381 ,6110,6111,6110 ,0,0,0}, {16378,16381,16429 ,730,6110,6111 ,0,0,0}, + {16393,16454,16456 ,730,6103,6114 ,0,0,0}, {16392,16454,16393 ,730,6103,730 ,0,0,0}, + {18258,18261,18259 ,6111,6111,6111 ,0,0,0}, {18262,18259,18261 ,6114,6111,6111 ,0,0,0}, + {16456,16457,16395 ,6114,730,6103 ,0,0,0}, {16395,16460,16397 ,6103,6114,730 ,0,0,0}, + {16457,16460,16395 ,730,6114,6103 ,0,0,0}, {16462,16463,16397 ,730,6111,730 ,0,0,0}, + {18263,18255,18254 ,6107,6108,6114 ,0,0,0}, {16398,16397,16463 ,6110,730,6111 ,0,0,0}, + {16465,18251,16398 ,6110,6110,6110 ,0,0,0}, {18254,18250,18264 ,6114,6111,730 ,0,0,0}, + {18265,18266,18253 ,6111,6110,730 ,0,0,0}, {18266,18256,18258 ,6110,6115,6111 ,0,0,0}, + {18239,18241,18240 ,6109,6106,6110 ,0,0,0}, {16448,16389,16445 ,730,730,6103 ,0,0,0}, + {16445,16387,16444 ,6103,730,730 ,0,0,0}, {16442,16383,16439 ,730,730,730 ,0,0,0}, + {16438,16382,16436 ,730,730,730 ,0,0,0}, {16400,16362,16401 ,730,730,730 ,0,0,0}, + {16401,16366,16404 ,730,730,730 ,0,0,0}, {16405,16367,16407 ,730,730,730 ,0,0,0}, + {16410,16368,16411 ,730,730,6103 ,0,0,0}, {16413,16369,16416 ,730,730,6103 ,0,0,0}, + {16416,16372,16417 ,6103,6103,730 ,0,0,0}, {16419,16374,16422 ,6103,730,6114 ,0,0,0}, + {16423,16375,16425 ,730,6103,6114 ,0,0,0}, {16428,16378,16429 ,730,730,6111 ,0,0,0}, + {16431,16381,18260 ,6110,6110,6110 ,0,0,0}, {18260,18259,18262 ,6110,6111,6114 ,0,0,0}, + {18261,18258,18257 ,6111,6111,730 ,0,0,0}, {18256,18266,18265 ,6115,6110,6111 ,0,0,0}, + {18267,18253,18255 ,6111,730,6108 ,0,0,0}, {18253,18267,18265 ,730,6111,6111 ,0,0,0}, + {18263,18254,18264 ,6107,6114,730 ,0,0,0}, {18264,18250,18245 ,730,6111,6105 ,0,0,0}, + {18246,18242,18241 ,6104,6114,6106 ,0,0,0}, {18240,18234,18238 ,6110,6110,6112 ,0,0,0}, + {18237,18234,18233 ,6113,6110,6112 ,0,0,0}, {18233,18230,18229 ,6112,6110,6109 ,0,0,0}, + {18225,18230,18226 ,6106,6110,6103 ,0,0,0}, {18223,18226,18221 ,6104,6103,6103 ,0,0,0}, + {18220,18224,18221 ,730,6105,6103 ,0,0,0}, {18227,18220,18222 ,6107,730,6103 ,0,0,0}, + {18231,18228,18222 ,6103,6108,6103 ,0,0,0}, {18231,18235,18232 ,6103,6111,6111 ,0,0,0}, + {18236,18244,18235 ,6103,6115,6111 ,0,0,0}, {18236,18248,18243 ,6103,730,730 ,0,0,0}, + {18247,18249,18252 ,6111,6111,6114 ,0,0,0}, {18243,18248,18247 ,730,730,6111 ,0,0,0}, + {18251,18249,16398 ,6110,6111,6110 ,0,0,0}, {16434,16402,18268 ,6116,6117,6118 ,0,0,0}, + {16437,18269,18270 ,6119,6120,6121 ,0,0,0}, {18271,18272,16589 ,6122,6123,6124 ,0,0,0}, + {16679,16449,16676 ,6125,6126,6127 ,0,0,0}, {16605,16604,17016 ,6128,6129,6130 ,0,0,0}, + {16535,16538,16459 ,6131,6132,6122 ,0,0,0}, {18273,16540,18274 ,6133,6134,6135 ,0,0,0}, + {18275,18276,18277 ,6136,6137,6138 ,0,0,0}, {16406,16486,16489 ,6122,6120,6139 ,0,0,0}, + {18272,16574,16579 ,6123,6140,6141 ,0,0,0}, {18278,16657,16659 ,6139,6142,6143 ,0,0,0}, + {16929,18279,16930 ,6144,6145,6146 ,0,0,0}, {16987,18280,16980 ,6147,6148,6149 ,0,0,0}, + {16507,18281,16510 ,6150,6144,6150 ,0,0,0}, {18282,16565,16964 ,6151,6134,6152 ,0,0,0}, + {18283,16466,18284 ,6145,6153,6154 ,0,0,0}, {18282,16964,18285 ,6151,6152,6155 ,0,0,0}, + {18286,16964,16963 ,6156,6152,6157 ,0,0,0}, {18287,18288,18289 ,6158,6144,6159 ,0,0,0}, + {18290,18291,18292 ,6160,6161,6162 ,0,0,0}, {16963,18293,18286 ,6157,6163,6156 ,0,0,0}, + {18294,18295,16963 ,6158,6164,6157 ,0,0,0}, {16969,18296,18294 ,6155,6165,6158 ,0,0,0}, + {18297,16974,18298 ,6166,6167,6116 ,0,0,0}, {16969,18294,16963 ,6155,6158,6157 ,0,0,0}, + {16981,18298,16974 ,6168,6116,6167 ,0,0,0}, {18289,18277,18276 ,6159,6138,6137 ,0,0,0}, + {18299,18300,18301 ,6122,6169,6170 ,0,0,0}, {18302,16969,16967 ,6171,6155,6172 ,0,0,0}, + {16967,18303,18302 ,6172,6118,6171 ,0,0,0}, {18304,18305,16977 ,6173,6174,6175 ,0,0,0}, + {16967,16966,18303 ,6172,6176,6118 ,0,0,0}, {16966,18305,18306 ,6176,6174,6177 ,0,0,0}, + {18307,16630,16629 ,6120,6146,6154 ,0,0,0}, {16966,16977,18305 ,6176,6175,6174 ,0,0,0}, + {18304,16977,16972 ,6173,6175,6178 ,0,0,0}, {18284,16468,18308 ,6154,6120,6145 ,0,0,0}, + {18309,18310,18311 ,6177,6179,6180 ,0,0,0}, {18312,18304,16972 ,6181,6173,6178 ,0,0,0}, + {18310,18313,18299 ,6179,6182,6122 ,0,0,0}, {18287,18314,18288 ,6158,6183,6144 ,0,0,0}, + {18301,18300,18315 ,6170,6169,6184 ,0,0,0}, {16981,16980,18316 ,6168,6149,6185 ,0,0,0}, + {18317,16414,18318 ,6186,6187,6119 ,0,0,0}, {16510,18319,16511 ,6150,6144,6188 ,0,0,0}, + {18320,16932,18321 ,6145,6144,6150 ,0,0,0}, {18314,16697,18322 ,6183,6189,6190 ,0,0,0}, + {16927,18323,18324 ,6154,6120,6127 ,0,0,0}, {16664,16663,17027 ,6191,6142,6192 ,0,0,0}, + {18269,16437,16435 ,6120,6119,6122 ,0,0,0}, {17021,16595,16594 ,6193,6194,6195 ,0,0,0}, + {16666,16922,16916 ,6196,6186,6197 ,0,0,0}, {16542,16464,16461 ,6196,6134,6138 ,0,0,0}, + {18272,16693,16688 ,6123,6198,6199 ,0,0,0}, {16459,16538,16461 ,6122,6132,6138 ,0,0,0}, + {16534,16535,16458 ,6157,6131,6137 ,0,0,0}, {16534,16458,16455 ,6157,6137,6131 ,0,0,0}, + {16453,16532,16455 ,6200,6143,6131 ,0,0,0}, {16441,16652,16670 ,6117,6201,6202 ,0,0,0}, + {18275,18325,18326 ,6136,6200,6156 ,0,0,0}, {16526,18327,16521 ,6118,6203,6132 ,0,0,0}, + {18328,16528,16530 ,6133,6204,6133 ,0,0,0}, {16458,16535,16459 ,6137,6131,6122 ,0,0,0}, + {16538,16542,16461 ,6132,6196,6138 ,0,0,0}, {16528,18329,16523 ,6204,6153,6201 ,0,0,0}, + {18330,16521,18327 ,6201,6132,6203 ,0,0,0}, {16443,16441,16670 ,6187,6117,6202 ,0,0,0}, + {16455,16532,16534 ,6131,6143,6157 ,0,0,0}, {16517,16947,16949 ,6132,6144,6205 ,0,0,0}, + {16530,16682,18328 ,6133,6201,6133 ,0,0,0}, {16453,16682,16532 ,6200,6201,6143 ,0,0,0}, + {16954,16516,16949 ,6206,6116,6205 ,0,0,0}, {16548,16954,16956 ,6207,6206,6204 ,0,0,0}, + {18331,18332,16522 ,6132,6119,6207 ,0,0,0}, {16947,16517,16521 ,6144,6132,6132 ,0,0,0}, + {16516,16954,16546 ,6116,6206,6121 ,0,0,0}, {16516,16517,16949 ,6116,6132,6205 ,0,0,0}, + {16957,16552,16956 ,6208,6207,6204 ,0,0,0}, {16548,16546,16954 ,6207,6121,6206 ,0,0,0}, + {16549,16548,16956 ,6209,6207,6204 ,0,0,0}, {16957,16959,16555 ,6208,6142,6196 ,0,0,0}, + {16552,16549,16956 ,6207,6209,6204 ,0,0,0}, {16554,16552,16957 ,6133,6207,6208 ,0,0,0}, + {16957,16555,16554 ,6208,6196,6133 ,0,0,0}, {16959,16558,16555 ,6142,6134,6196 ,0,0,0}, + {16962,16560,16959 ,6148,6131,6142 ,0,0,0}, {16959,16560,16558 ,6142,6131,6134 ,0,0,0}, + {16962,16561,16560 ,6148,6205,6131 ,0,0,0}, {16561,16962,16564 ,6205,6148,6204 ,0,0,0}, + {16962,16565,16564 ,6148,6134,6204 ,0,0,0}, {18286,18285,16964 ,6156,6155,6152 ,0,0,0}, + {18302,18296,16969 ,6171,6165,6155 ,0,0,0}, {18295,18293,16963 ,6164,6163,6157 ,0,0,0}, + {18303,16966,18306 ,6118,6176,6177 ,0,0,0}, {18297,18333,16972 ,6166,6210,6178 ,0,0,0}, + {18334,16986,18335 ,6157,6190,6211 ,0,0,0}, {18312,18336,18337 ,6181,6212,6182 ,0,0,0}, + {16578,18272,16579 ,6174,6123,6141 ,0,0,0}, {18338,18339,18272 ,6213,6214,6123 ,0,0,0}, + {17024,17021,16568 ,6215,6193,6216 ,0,0,0}, {16707,16709,16569 ,6217,6218,6219 ,0,0,0}, + {16594,16568,17021 ,6195,6216,6193 ,0,0,0}, {16599,16598,17013 ,6220,6221,6222 ,0,0,0}, + {16595,17020,16598 ,6194,6223,6221 ,0,0,0}, {17016,16604,16601 ,6130,6129,6181 ,0,0,0}, + {16601,17013,17016 ,6181,6222,6130 ,0,0,0}, {16610,17017,16611 ,6224,6225,6226 ,0,0,0}, + {16607,17016,17017 ,6227,6130,6225 ,0,0,0}, {16687,18272,16688 ,6212,6123,6199 ,0,0,0}, + {16618,18340,16619 ,6203,6228,6201 ,0,0,0}, {16709,16570,16569 ,6218,6229,6219 ,0,0,0}, + {18341,18342,18343 ,6230,6231,6232 ,0,0,0}, {16709,16710,16989 ,6218,6200,6233 ,0,0,0}, + {16610,16607,17017 ,6224,6227,6225 ,0,0,0}, {17017,16613,16611 ,6225,6234,6226 ,0,0,0}, + {16607,16605,17016 ,6227,6128,6130 ,0,0,0}, {16687,16686,18272 ,6212,6235,6123 ,0,0,0}, + {16599,17013,16601 ,6220,6222,6181 ,0,0,0}, {17020,17013,16598 ,6223,6222,6221 ,0,0,0}, + {17021,17020,16595 ,6193,6223,6194 ,0,0,0}, {16570,17024,16568 ,6229,6215,6216 ,0,0,0}, + {17024,16570,16989 ,6215,6229,6233 ,0,0,0}, {18339,16694,18272 ,6214,6236,6123 ,0,0,0}, + {16697,16694,18322 ,6189,6236,6190 ,0,0,0}, {18272,18344,18345 ,6123,6170,6214 ,0,0,0}, + {16586,18272,16582 ,6237,6123,6167 ,0,0,0}, {18271,18344,18272 ,6122,6170,6123 ,0,0,0}, + {16588,18346,18347 ,6238,6180,6179 ,0,0,0}, {18348,16625,18349 ,6197,6165,6196 ,0,0,0}, + {18350,16430,18351 ,6131,6122,6132 ,0,0,0}, {16593,18352,18346 ,6239,6240,6180 ,0,0,0}, + {18353,18354,18292 ,6171,6152,6162 ,0,0,0}, {16421,18355,16420 ,6204,6208,6126 ,0,0,0}, + {18356,18315,18357 ,6241,6184,6136 ,0,0,0}, {18358,16636,16639 ,6179,6179,6202 ,0,0,0}, + {16648,18355,16647 ,6127,6208,6242 ,0,0,0}, {16773,18359,18360 ,6156,6200,6136 ,0,0,0}, + {16776,16778,18361 ,6137,6135,6133 ,0,0,0}, {18362,18363,18364 ,6207,6133,6208 ,0,0,0}, + {16734,16767,16770 ,6196,6158,6159 ,0,0,0}, {16757,16727,16722 ,6181,6243,6139 ,0,0,0}, + {16741,16743,18365 ,6244,6245,6246 ,0,0,0}, {16720,18366,18367 ,6247,6190,6136 ,0,0,0}, + {18368,18342,18369 ,6248,6231,6170 ,0,0,0}, {18370,18371,16749 ,6152,6249,6250 ,0,0,0}, + {18372,18342,18368 ,6251,6231,6248 ,0,0,0}, {18373,18374,18375 ,6252,6253,6254 ,0,0,0}, + {18374,18341,18375 ,6253,6230,6254 ,0,0,0}, {18376,18377,18378 ,6255,6256,6257 ,0,0,0}, + {18379,18380,18381 ,6258,6259,6260 ,0,0,0}, {18374,18373,18381 ,6253,6252,6260 ,0,0,0}, + {18381,18380,18374 ,6260,6259,6253 ,0,0,0}, {18380,18379,18382 ,6259,6258,6261 ,0,0,0}, + {18383,18378,18384 ,6262,6257,6263 ,0,0,0}, {18382,18384,18380 ,6261,6263,6259 ,0,0,0}, + {18378,18377,18384 ,6257,6256,6263 ,0,0,0}, {18385,18386,18377 ,6264,6265,6256 ,0,0,0}, + {18382,18383,18384 ,6261,6262,6263 ,0,0,0}, {18376,18385,18377 ,6255,6264,6256 ,0,0,0}, + {18375,18341,18343 ,6254,6230,6232 ,0,0,0}, {18387,18388,16750 ,6138,6134,6266 ,0,0,0}, + {18343,18342,18372 ,6232,6231,6251 ,0,0,0}, {18369,18388,18387 ,6170,6134,6138 ,0,0,0}, + {18389,16743,16744 ,6267,6245,6268 ,0,0,0}, {16721,18367,18390 ,6167,6136,6199 ,0,0,0}, + {16738,16741,18366 ,6235,6244,6190 ,0,0,0}, {18391,16792,18392 ,6197,6164,6191 ,0,0,0}, + {16786,16785,18393 ,6171,6118,6269 ,0,0,0}, {16731,16728,16761 ,6270,6270,6174 ,0,0,0}, + {18391,16794,16792 ,6197,6163,6164 ,0,0,0}, {16766,16731,16761 ,6127,6270,6174 ,0,0,0}, + {18394,18326,18325 ,6137,6156,6200 ,0,0,0}, {18395,18396,18397 ,6213,6271,6169 ,0,0,0}, + {16755,16757,18398 ,6173,6181,6272 ,0,0,0}, {16797,16794,18391 ,6156,6163,6197 ,0,0,0}, + {18387,18399,18369 ,6138,6273,6170 ,0,0,0}, {18400,16798,16797 ,6201,6155,6156 ,0,0,0}, + {18400,16802,16800 ,6201,6134,6151 ,0,0,0}, {18401,18355,18402 ,6214,6208,6133 ,0,0,0}, + {18401,16415,16418 ,6214,6208,6117 ,0,0,0}, {18403,18404,18405 ,6190,6214,6199 ,0,0,0}, + {16792,16791,18392 ,6164,6158,6191 ,0,0,0}, {16786,18393,18392 ,6171,6269,6191 ,0,0,0}, + {18406,18407,18408 ,6274,6118,6183 ,0,0,0}, {18409,18410,18411 ,6149,6275,6214 ,0,0,0}, + {18412,18368,18399 ,6243,6248,6273 ,0,0,0}, {18412,18399,18413 ,6243,6273,6276 ,0,0,0}, + {18411,18301,18315 ,6214,6170,6184 ,0,0,0}, {18299,18313,18300 ,6122,6182,6169 ,0,0,0}, + {18311,18414,18309 ,6180,6244,6177 ,0,0,0}, {18310,18309,18313 ,6179,6177,6182 ,0,0,0}, + {18287,18415,16698 ,6158,6127,6249 ,0,0,0}, {16593,18414,18352 ,6239,6244,6240 ,0,0,0}, + {18311,18352,18414 ,6180,6240,6244 ,0,0,0}, {16593,18346,16590 ,6239,6180,6277 ,0,0,0}, + {18287,16698,16697 ,6158,6249,6189 ,0,0,0}, {16589,16588,18347 ,6124,6238,6179 ,0,0,0}, + {16588,16590,18346 ,6238,6277,6180 ,0,0,0}, {16716,16984,16992 ,6278,6279,6280 ,0,0,0}, + {16984,18335,16986 ,6279,6211,6190 ,0,0,0}, {18271,16589,18347 ,6122,6124,6179 ,0,0,0}, + {18416,18272,18345 ,6275,6123,6214 ,0,0,0}, {16589,18272,16586 ,6124,6123,6237 ,0,0,0}, + {16990,16713,16992 ,6281,6282,6280 ,0,0,0}, {16700,18415,18417 ,6283,6127,6174 ,0,0,0}, + {16698,18415,16700 ,6249,6127,6283 ,0,0,0}, {18288,18277,18289 ,6144,6138,6159 ,0,0,0}, + {18275,18326,18276 ,6136,6156,6137 ,0,0,0}, {18394,18273,18274 ,6137,6133,6135 ,0,0,0}, + {18273,18394,18325 ,6133,6137,6200 ,0,0,0}, {18273,16464,16540 ,6133,6134,6134 ,0,0,0}, + {16947,18330,16945 ,6144,6201,6209 ,0,0,0}, {16540,16464,16542 ,6134,6134,6196 ,0,0,0}, + {16682,16453,16681 ,6201,6200,6158 ,0,0,0}, {16446,16443,16673 ,6208,6187,6284 ,0,0,0}, + {16679,16681,16452 ,6125,6158,6204 ,0,0,0}, {18418,16942,16943 ,6191,6165,6179 ,0,0,0}, + {16940,18419,16917 ,6142,6172,6197 ,0,0,0}, {16664,16922,16666 ,6191,6186,6196 ,0,0,0}, + {17027,16922,16664 ,6192,6186,6191 ,0,0,0}, {17027,16663,16925 ,6192,6142,6285 ,0,0,0}, + {18420,16660,16657 ,6192,6228,6142 ,0,0,0}, {16486,16406,16408 ,6120,6122,6119 ,0,0,0}, + {16409,16484,16408 ,6171,6202,6119 ,0,0,0}, {18421,16937,16935 ,6150,6144,6150 ,0,0,0}, + {18281,16507,16505 ,6144,6150,6187 ,0,0,0}, {16513,16511,18319 ,6150,6188,6144 ,0,0,0}, + {16505,18422,18281 ,6187,6144,6144 ,0,0,0}, {16479,18317,18423 ,6165,6186,6286 ,0,0,0}, + {18422,16501,18424 ,6144,6192,6144 ,0,0,0}, {16499,16498,18424 ,6145,6145,6144 ,0,0,0}, + {18425,18426,18355 ,6143,6133,6208 ,0,0,0}, {18307,18427,16630 ,6120,6176,6146 ,0,0,0}, + {18350,16427,16430 ,6131,6137,6122 ,0,0,0}, {16433,16778,16777 ,6134,6135,6134 ,0,0,0}, + {18349,16620,16619 ,6196,6139,6201 ,0,0,0}, {18348,16626,16623 ,6197,6286,6165 ,0,0,0}, + {18358,16639,18428 ,6179,6202,6139 ,0,0,0}, {16642,18428,16641 ,6203,6139,6228 ,0,0,0}, + {16776,18361,18359 ,6137,6133,6200 ,0,0,0}, {18359,16773,16776 ,6200,6156,6137 ,0,0,0}, + {18429,18430,18431 ,6209,6207,6166 ,0,0,0}, {18432,16771,18360 ,6138,6137,6136 ,0,0,0}, + {18427,16632,16630 ,6176,6191,6146 ,0,0,0}, {18433,18434,18435 ,6186,6228,6287 ,0,0,0}, + {16626,18348,18307 ,6286,6197,6120 ,0,0,0}, {16626,18307,16629 ,6286,6120,6154 ,0,0,0}, + {16625,18348,16623 ,6165,6197,6165 ,0,0,0}, {16620,18349,16625 ,6139,6196,6165 ,0,0,0}, + {18340,16618,16636 ,6228,6203,6179 ,0,0,0}, {18340,18349,16619 ,6228,6196,6201 ,0,0,0}, + {16424,18355,16421 ,6200,6208,6204 ,0,0,0}, {18358,18340,16636 ,6179,6228,6179 ,0,0,0}, + {18436,18428,16642 ,6133,6139,6203 ,0,0,0}, {16641,18428,16639 ,6228,6139,6202 ,0,0,0}, + {16424,16426,18355 ,6200,6131,6208 ,0,0,0}, {18355,18437,16647 ,6208,6207,6242 ,0,0,0}, + {16432,16777,18438 ,6138,6134,6196 ,0,0,0}, {18355,16426,16427 ,6208,6131,6137 ,0,0,0}, + {18355,16418,16420 ,6208,6117,6126 ,0,0,0}, {16415,18401,18318 ,6208,6214,6119 ,0,0,0}, + {18355,18401,16418 ,6208,6214,6117 ,0,0,0}, {18283,16495,16466 ,6145,6120,6153 ,0,0,0}, + {18439,18440,16470 ,6201,6121,6288 ,0,0,0}, {16414,16415,18318 ,6187,6208,6119 ,0,0,0}, + {18441,16472,16474 ,6139,6192,6131 ,0,0,0}, {18308,16470,18440 ,6145,6288,6121 ,0,0,0}, + {16505,16504,18422 ,6187,6145,6144 ,0,0,0}, {16504,16501,18422 ,6145,6192,6144 ,0,0,0}, + {16498,16495,18283 ,6145,6120,6145 ,0,0,0}, {18440,18442,18308 ,6121,6289,6145 ,0,0,0}, + {18433,18442,18443 ,6186,6289,6191 ,0,0,0}, {18440,18443,18442 ,6121,6191,6289 ,0,0,0}, + {18433,18435,18427 ,6186,6287,6176 ,0,0,0}, {18433,18443,18434 ,6186,6191,6228 ,0,0,0}, + {16632,18427,18435 ,6191,6176,6287 ,0,0,0}, {18444,16435,16434 ,6202,6122,6116 ,0,0,0}, + {18445,18446,16915 ,6165,6191,6187 ,0,0,0}, {18447,16943,16945 ,6126,6179,6209 ,0,0,0}, + {18448,18323,16925 ,6154,6120,6285 ,0,0,0}, {16652,16441,18449 ,6201,6117,6120 ,0,0,0}, + {18450,18451,16654 ,6197,6201,6207 ,0,0,0}, {18270,18449,16440 ,6121,6120,6171 ,0,0,0}, + {16403,16491,16490 ,6116,6120,6201 ,0,0,0}, {18270,16440,16437 ,6121,6171,6119 ,0,0,0}, + {16443,16670,16673 ,6187,6202,6284 ,0,0,0}, {16673,16675,16446 ,6284,6140,6208 ,0,0,0}, + {16447,16675,16676 ,6117,6140,6127 ,0,0,0}, {16447,16676,16449 ,6117,6127,6126 ,0,0,0}, + {16449,16679,16452 ,6126,6125,6204 ,0,0,0}, {16453,16452,16681 ,6200,6204,6158 ,0,0,0}, + {16530,16532,16682 ,6133,6143,6201 ,0,0,0}, {16526,16522,18332 ,6118,6207,6119 ,0,0,0}, + {16528,18328,18329 ,6204,6133,6153 ,0,0,0}, {18331,16522,16523 ,6132,6207,6201 ,0,0,0}, + {18331,16523,18329 ,6132,6201,6153 ,0,0,0}, {18327,16526,18332 ,6203,6118,6119 ,0,0,0}, + {16521,18330,16947 ,6132,6201,6144 ,0,0,0}, {18447,16945,18330 ,6126,6209,6201 ,0,0,0}, + {18452,16942,18418 ,6242,6165,6191 ,0,0,0}, {18418,16943,18447 ,6191,6179,6126 ,0,0,0}, + {16940,18452,18453 ,6142,6242,6197 ,0,0,0}, {18452,16940,16942 ,6242,6142,6165 ,0,0,0}, + {18419,18445,16917 ,6172,6165,6197 ,0,0,0}, {18453,18419,16940 ,6197,6172,6142 ,0,0,0}, + {16915,18446,16916 ,6187,6191,6197 ,0,0,0}, {16917,18445,16915 ,6197,6165,6187 ,0,0,0}, + {16666,16916,18454 ,6196,6197,6202 ,0,0,0}, {16916,18446,18454 ,6197,6191,6202 ,0,0,0}, + {18314,18287,16697 ,6183,6158,6189 ,0,0,0}, {18417,18455,18456 ,6174,6118,6273 ,0,0,0}, + {16691,18272,16694 ,6290,6123,6236 ,0,0,0}, {18339,18322,16694 ,6214,6190,6236 ,0,0,0}, + {16691,16693,18272 ,6290,6198,6123 ,0,0,0}, {16583,18272,16578 ,6152,6123,6174 ,0,0,0}, + {16704,16707,16575 ,6124,6217,6291 ,0,0,0}, {16686,16574,18272 ,6235,6140,6123 ,0,0,0}, + {16704,16575,16574 ,6124,6291,6140 ,0,0,0}, {16704,16574,16686 ,6124,6140,6235 ,0,0,0}, + {16707,16569,16575 ,6217,6219,6291 ,0,0,0}, {16709,16989,16570 ,6218,6233,6229 ,0,0,0}, + {16710,16713,16990 ,6200,6282,6281 ,0,0,0}, {16710,16990,16989 ,6200,6281,6233 ,0,0,0}, + {16715,16716,16992 ,6269,6278,6280 ,0,0,0}, {16713,16715,16992 ,6282,6269,6280 ,0,0,0}, + {16984,16716,18457 ,6279,6278,6292 ,0,0,0}, {18457,18335,16984 ,6292,6211,6279 ,0,0,0}, + {18458,16986,18334 ,6293,6190,6157 ,0,0,0}, {16987,18458,18459 ,6147,6293,6266 ,0,0,0}, + {18458,16987,16986 ,6293,6147,6190 ,0,0,0}, {18280,18460,16980 ,6148,6273,6149 ,0,0,0}, + {18459,18280,16987 ,6266,6148,6147 ,0,0,0}, {18316,18461,16981 ,6185,6294,6168 ,0,0,0}, + {18460,18316,16980 ,6273,6185,6149 ,0,0,0}, {16972,16974,18297 ,6178,6167,6166 ,0,0,0}, + {18461,18298,16981 ,6294,6116,6168 ,0,0,0}, {18333,18312,16972 ,6210,6181,6178 ,0,0,0}, + {18337,18336,18455 ,6182,6212,6118 ,0,0,0}, {18333,18336,18312 ,6210,6212,6181 ,0,0,0}, + {18417,18456,16700 ,6174,6273,6283 ,0,0,0}, {18455,18336,18456 ,6118,6212,6273 ,0,0,0}, + {16722,18390,18398 ,6139,6199,6272 ,0,0,0}, {16753,18462,16782 ,6174,6295,6177 ,0,0,0}, + {18353,18412,18413 ,6171,6243,6276 ,0,0,0}, {16788,16786,18392 ,6165,6171,6191 ,0,0,0}, + {18462,16753,18463 ,6295,6174,6162 ,0,0,0}, {18398,16757,16722 ,6272,6181,6139 ,0,0,0}, + {16721,18390,16722 ,6167,6199,6139 ,0,0,0}, {16720,18367,16721 ,6247,6136,6167 ,0,0,0}, + {16738,18366,16720 ,6235,6190,6247 ,0,0,0}, {18365,18366,16741 ,6246,6190,6244 ,0,0,0}, + {18389,18365,16743 ,6267,6246,6245 ,0,0,0}, {16744,16747,18371 ,6268,6185,6249 ,0,0,0}, + {18371,18389,16744 ,6249,6267,6268 ,0,0,0}, {16750,18370,16749 ,6266,6152,6250 ,0,0,0}, + {16749,18371,16747 ,6250,6249,6185 ,0,0,0}, {16750,18388,18370 ,6266,6134,6152 ,0,0,0}, + {18368,18369,18399 ,6248,6170,6273 ,0,0,0}, {18356,18464,18315 ,6241,6296,6184 ,0,0,0}, + {18353,18413,18354 ,6171,6276,6152 ,0,0,0}, {18356,18357,18465 ,6241,6136,6200 ,0,0,0}, + {18465,18291,18290 ,6200,6161,6160 ,0,0,0}, {18290,18292,18354 ,6160,6162,6152 ,0,0,0}, + {18465,18357,18291 ,6200,6136,6161 ,0,0,0}, {18464,18409,18411 ,6296,6149,6214 ,0,0,0}, + {18411,18315,18464 ,6214,6184,6296 ,0,0,0}, {18396,18410,18409 ,6271,6275,6149 ,0,0,0}, + {18397,18404,18395 ,6169,6214,6213 ,0,0,0}, {18396,18395,18410 ,6271,6213,6275 ,0,0,0}, + {18405,18406,18403 ,6199,6274,6190 ,0,0,0}, {18397,18405,18404 ,6169,6199,6214 ,0,0,0}, + {18408,18407,18466 ,6183,6118,6144 ,0,0,0}, {18403,18406,18408 ,6190,6274,6183 ,0,0,0}, + {16734,18466,18407 ,6196,6144,6118 ,0,0,0}, {16409,16412,16483 ,6171,6117,6139 ,0,0,0}, + {18319,16515,16513 ,6144,6150,6150 ,0,0,0}, {18319,16510,18281 ,6144,6150,6144 ,0,0,0}, + {16480,16483,16412 ,6197,6139,6117 ,0,0,0}, {16414,18317,16480 ,6187,6186,6197 ,0,0,0}, + {18283,18424,16498 ,6145,6144,6145 ,0,0,0}, {16501,16499,18424 ,6192,6145,6144 ,0,0,0}, + {16468,16470,18308 ,6120,6288,6145 ,0,0,0}, {16466,16468,18284 ,6153,6120,6154 ,0,0,0}, + {16474,16479,18423 ,6131,6165,6286 ,0,0,0}, {16476,18467,18439 ,6144,6242,6201 ,0,0,0}, + {18439,16470,16476 ,6201,6288,6144 ,0,0,0}, {18423,18441,16474 ,6286,6139,6131 ,0,0,0}, + {16472,18441,18467 ,6192,6139,6242 ,0,0,0}, {16472,18467,16476 ,6192,6242,6144 ,0,0,0}, + {16479,16480,18317 ,6165,6197,6186 ,0,0,0}, {16412,16414,16480 ,6117,6187,6197 ,0,0,0}, + {16409,16483,16484 ,6171,6139,6202 ,0,0,0}, {16408,16484,16486 ,6119,6202,6120 ,0,0,0}, + {16491,16403,16489 ,6120,6116,6139 ,0,0,0}, {16406,16489,16403 ,6122,6139,6116 ,0,0,0}, + {16403,16490,16402 ,6116,6201,6117 ,0,0,0}, {16435,18444,18269 ,6122,6202,6120 ,0,0,0}, + {16402,16490,18268 ,6117,6201,6118 ,0,0,0}, {18444,16434,18268 ,6202,6116,6118 ,0,0,0}, + {18449,16441,16440 ,6120,6117,6171 ,0,0,0}, {18450,16653,18449 ,6197,6197,6120 ,0,0,0}, + {16652,18449,16653 ,6201,6120,6197 ,0,0,0}, {16660,18468,16663 ,6228,6145,6142 ,0,0,0}, + {16659,16654,18451 ,6143,6207,6201 ,0,0,0}, {16654,16653,18450 ,6207,6197,6197 ,0,0,0}, + {18420,16657,18278 ,6192,6142,6139 ,0,0,0}, {18278,16659,18451 ,6139,6143,6201 ,0,0,0}, + {16660,18420,18468 ,6228,6192,6145 ,0,0,0}, {18448,16925,16663 ,6154,6285,6142 ,0,0,0}, + {18448,16663,18468 ,6154,6142,6145 ,0,0,0}, {18323,16927,16925 ,6120,6154,6285 ,0,0,0}, + {16929,18324,18469 ,6144,6127,6187 ,0,0,0}, {18324,16929,16927 ,6127,6144,6154 ,0,0,0}, + {18469,18279,16929 ,6187,6145,6144 ,0,0,0}, {16930,18470,18321 ,6146,6145,6150 ,0,0,0}, + {18279,18470,16930 ,6145,6145,6146 ,0,0,0}, {16930,18321,16932 ,6146,6150,6144 ,0,0,0}, + {16935,16932,18471 ,6150,6144,6146 ,0,0,0}, {18320,18471,16932 ,6145,6146,6144 ,0,0,0}, + {16935,18472,18421 ,6150,6144,6150 ,0,0,0}, {16935,18471,18472 ,6150,6146,6144 ,0,0,0}, + {18473,16937,18474 ,6150,6144,6150 ,0,0,0}, {16937,18421,18474 ,6144,6150,6150 ,0,0,0}, + {16515,16937,18473 ,6150,6144,6150 ,0,0,0}, {18475,18476,18477 ,6131,6203,6207 ,0,0,0}, + {18432,18466,16770 ,6138,6144,6159 ,0,0,0}, {18400,16797,18391 ,6201,6156,6197 ,0,0,0}, + {18400,16800,16798 ,6201,6151,6155 ,0,0,0}, {18466,16734,16770 ,6144,6196,6159 ,0,0,0}, + {16755,18463,16753 ,6173,6162,6174 ,0,0,0}, {16782,18462,16785 ,6177,6295,6118 ,0,0,0}, + {16791,16788,18392 ,6158,6165,6191 ,0,0,0}, {18462,18393,16785 ,6295,6269,6118 ,0,0,0}, + {18463,16755,18398 ,6162,6173,6272 ,0,0,0}, {16757,16763,16727 ,6181,6182,6243 ,0,0,0}, + {16766,16767,16732 ,6127,6158,6297 ,0,0,0}, {16759,16725,16763 ,6118,6155,6182 ,0,0,0}, + {16727,16763,16725 ,6243,6182,6155 ,0,0,0}, {16759,16761,16728 ,6118,6174,6270 ,0,0,0}, + {16728,16725,16759 ,6270,6155,6118 ,0,0,0}, {16731,16766,16732 ,6270,6127,6297 ,0,0,0}, + {16734,16732,16767 ,6196,6297,6158 ,0,0,0}, {18432,16770,16771 ,6138,6159,6137 ,0,0,0}, + {18360,16771,16773 ,6136,6137,6156 ,0,0,0}, {18478,18479,18480 ,6205,6132,6116 ,0,0,0}, + {18479,18436,18481 ,6132,6133,6132 ,0,0,0}, {16427,18350,18355 ,6137,6131,6208 ,0,0,0}, + {18361,16778,16433 ,6133,6135,6134 ,0,0,0}, {16432,18438,18351 ,6138,6196,6132 ,0,0,0}, + {16432,16433,16777 ,6138,6134,6134 ,0,0,0}, {18351,16430,16432 ,6132,6122,6138 ,0,0,0}, + {18355,18350,18482 ,6208,6131,6157 ,0,0,0}, {18482,18425,18355 ,6157,6143,6208 ,0,0,0}, + {18481,16645,18483 ,6132,6172,6118 ,0,0,0}, {18484,18485,18355 ,6204,6201,6208 ,0,0,0}, + {18355,18486,18487 ,6208,6172,6214 ,0,0,0}, {18355,18485,18437 ,6208,6201,6207 ,0,0,0}, + {18486,18355,16648 ,6172,6208,6127 ,0,0,0}, {16647,18437,16645 ,6242,6207,6172 ,0,0,0}, + {18483,16645,18437 ,6118,6172,6207 ,0,0,0}, {18481,18436,16642 ,6132,6133,6203 ,0,0,0}, + {16642,16645,18481 ,6203,6172,6132 ,0,0,0}, {18479,18478,18436 ,6132,6205,6133 ,0,0,0}, + {18429,18480,18488 ,6209,6116,6121 ,0,0,0}, {18480,18429,18478 ,6116,6209,6205 ,0,0,0}, + {18488,18430,18429 ,6121,6207,6209 ,0,0,0}, {18431,18489,18362 ,6166,6209,6207 ,0,0,0}, + {18430,18489,18431 ,6207,6209,6166 ,0,0,0}, {18431,18362,18364 ,6166,6207,6208 ,0,0,0}, + {18477,18364,18490 ,6207,6208,6196 ,0,0,0}, {18363,18490,18364 ,6133,6196,6208 ,0,0,0}, + {18477,18491,18475 ,6207,6134,6131 ,0,0,0}, {18477,18490,18491 ,6207,6196,6134 ,0,0,0}, + {18492,18476,18493 ,6204,6203,6205 ,0,0,0}, {18476,18475,18493 ,6203,6131,6205 ,0,0,0}, + {16802,18476,18492 ,6134,6203,6204 ,0,0,0}, {18272,16583,16582 ,6123,6152,6167 ,0,0,0}, + {18272,18416,18338 ,6123,6275,6213 ,0,0,0}, {16675,16447,16446 ,6140,6117,6208 ,0,0,0}, + {18355,18426,18484 ,6208,6133,6204 ,0,0,0}, {18355,18487,18402 ,6208,6214,6133 ,0,0,0}, + {18494,17178,17177 ,6298,6299,6299 ,0,0,0}, {17183,18495,17184 ,6298,6298,6300 ,0,0,0}, + {18496,18497,16875 ,6301,6302,6302 ,0,0,0}, {17177,17174,18498 ,6299,6300,6303 ,0,0,0}, + {16872,18499,18500 ,6304,6304,6305 ,0,0,0}, {17168,18501,17171 ,6301,6299,6306 ,0,0,0}, + {16870,18502,18503 ,6305,6307,6308 ,0,0,0}, {18504,17165,17162 ,6298,6298,6309 ,0,0,0}, + {18505,16858,18506 ,6310,6311,6312 ,0,0,0}, {18507,18508,16864 ,6308,6313,6314 ,0,0,0}, + {16854,17278,18509 ,6315,6316,6317 ,0,0,0}, {18509,18510,16861 ,6317,6318,6319 ,0,0,0}, + {16849,17273,17275 ,6320,6321,6322 ,0,0,0}, {17233,16816,17231 ,6299,6303,6323 ,0,0,0}, + {17237,17239,16819 ,6324,6298,6306 ,0,0,0}, {16839,17263,17264 ,6325,6326,6327 ,0,0,0}, + {17240,17243,16827 ,6298,6328,6324 ,0,0,0}, {17255,17257,16836 ,6301,6329,6330 ,0,0,0}, + {17255,16910,17252 ,6301,6324,6331 ,0,0,0}, {16829,17249,17251 ,6332,6328,6333 ,0,0,0}, + {17249,16832,17246 ,6328,6334,6335 ,0,0,0}, {17258,16909,17257 ,6336,6298,6329 ,0,0,0}, + {17252,16837,17251 ,6331,6337,6333 ,0,0,0}, {16838,17261,17263 ,6338,6339,6326 ,0,0,0}, + {17258,17261,16841 ,6336,6339,6324 ,0,0,0}, {17243,17245,16823 ,6328,6328,6299 ,0,0,0}, + {17245,17246,16824 ,6328,6335,6340 ,0,0,0}, {16845,17267,17269 ,6341,6342,6343 ,0,0,0}, + {16847,17264,17267 ,6344,6327,6342 ,0,0,0}, {17269,17270,16843 ,6343,6345,6346 ,0,0,0}, + {17239,17240,16826 ,6298,6298,6347 ,0,0,0}, {17234,17237,16822 ,6348,6324,6316 ,0,0,0}, + {16851,17270,17273 ,6349,6345,6321 ,0,0,0}, {16850,17275,17276 ,6350,6322,6351 ,0,0,0}, + {16821,17234,16822 ,6324,6348,6316 ,0,0,0}, {16807,17228,16808 ,6300,6352,6353 ,0,0,0}, + {16856,17276,17278 ,6354,6351,6316 ,0,0,0}, {16804,17222,16805 ,6355,6299,6298 ,0,0,0}, + {17227,16813,17225 ,6299,6356,6357 ,0,0,0}, {18507,16866,18505 ,6308,6358,6310 ,0,0,0}, + {18510,18506,16857 ,6318,6312,6359 ,0,0,0}, {17160,17159,18511 ,6316,6306,6360 ,0,0,0}, + {18511,17159,16810 ,6360,6306,6299 ,0,0,0}, {18511,18512,17160 ,6360,6298,6316 ,0,0,0}, + {18508,18502,16862 ,6313,6307,6304 ,0,0,0}, {16869,18503,18513 ,6336,6308,6311 ,0,0,0}, + {16816,17233,16821 ,6303,6299,6324 ,0,0,0}, {18513,18499,16874 ,6311,6304,6314 ,0,0,0}, + {17168,17166,18514 ,6301,6300,6340 ,0,0,0}, {18515,17166,17165 ,6301,6300,6298 ,0,0,0}, + {18516,18496,16879 ,6301,6301,6333 ,0,0,0}, {16873,18500,18516 ,6361,6305,6301 ,0,0,0}, + {18517,17174,17172 ,6300,6300,6357 ,0,0,0}, {17171,18518,17172 ,6306,6355,6357 ,0,0,0}, + {18519,18520,16880 ,6353,6311,6301 ,0,0,0}, {16876,18497,18519 ,6362,6302,6353 ,0,0,0}, + {17180,17178,18521 ,6300,6299,6300 ,0,0,0}, {16881,18520,18522 ,6300,6311,6363 ,0,0,0}, + {16885,18522,18523 ,6301,6363,6353 ,0,0,0}, {16886,18523,18524 ,6300,6353,6328 ,0,0,0}, + {17180,18525,17183 ,6300,6300,6298 ,0,0,0}, {18526,16888,18524 ,6303,6352,6328 ,0,0,0}, + {18526,18527,16890 ,6303,6352,6340 ,0,0,0}, {18528,17186,17184 ,6299,6316,6300 ,0,0,0}, + {18529,16893,18527 ,6300,6340,6352 ,0,0,0}, {18530,17189,17186 ,6298,6364,6316 ,0,0,0}, + {16894,18529,18531 ,6316,6300,6306 ,0,0,0}, {18532,17190,17189 ,6364,6298,6364 ,0,0,0}, + {18531,18533,16896 ,6306,6340,6340 ,0,0,0}, {18534,17192,17190 ,6300,6300,6298 ,0,0,0}, + {18535,16899,18533 ,6323,6340,6340 ,0,0,0}, {18536,17195,17192 ,6298,6300,6300 ,0,0,0}, + {16901,18535,18537 ,6300,6323,6340 ,0,0,0}, {18538,17196,17195 ,6364,6300,6300 ,0,0,0}, + {18537,18539,16900 ,6340,6303,6303 ,0,0,0}, {18540,17198,17196 ,6300,6365,6300 ,0,0,0}, + {18541,16902,18539 ,6300,6300,6303 ,0,0,0}, {18542,17201,17198 ,6366,6300,6365 ,0,0,0}, + {16905,18541,18543 ,6300,6300,6316 ,0,0,0}, {18544,17202,17201 ,6367,6367,6300 ,0,0,0}, + {18543,18545,16906 ,6316,6300,6300 ,0,0,0}, {18546,17204,17202 ,6300,6300,6367 ,0,0,0}, + {18547,16906,18548 ,6301,6300,6300 ,0,0,0}, {18549,17207,17204 ,6368,6300,6300 ,0,0,0}, + {18550,18547,18551 ,6300,6301,6300 ,0,0,0}, {18552,17208,17207 ,6369,6367,6300 ,0,0,0}, + {18553,18550,18554 ,6316,6300,6300 ,0,0,0}, {17208,18555,17210 ,6367,6367,6300 ,0,0,0}, + {17213,17210,18556 ,6364,6300,6370 ,0,0,0}, {18557,17216,17214 ,6300,6316,6300 ,0,0,0}, + {18558,18553,18559 ,6300,6316,6316 ,0,0,0}, {18560,18561,18562 ,6300,6371,6300 ,0,0,0}, + {18563,18564,18565 ,6306,6300,6303 ,0,0,0}, {18566,18567,18568 ,6369,6300,6367 ,0,0,0}, + {18569,18570,18571 ,6301,6301,6300 ,0,0,0}, {18572,18573,18574 ,6300,6369,6367 ,0,0,0}, + {18575,18576,18577 ,6316,6316,6300 ,0,0,0}, {18578,18579,18580 ,6364,6300,6300 ,0,0,0}, + {18581,18572,18582 ,6364,6300,6316 ,0,0,0}, {18583,18584,18585 ,6300,6364,6316 ,0,0,0}, + {18580,18586,18585 ,6300,6316,6316 ,0,0,0}, {18587,18588,18589 ,6364,6372,6364 ,0,0,0}, + {18588,18581,18590 ,6372,6364,6300 ,0,0,0}, {18575,18584,18591 ,6316,6364,6367 ,0,0,0}, + {18592,18578,18587 ,6370,6364,6364 ,0,0,0}, {18568,18593,18594 ,6367,6367,6316 ,0,0,0}, + {18595,18573,18594 ,6316,6369,6316 ,0,0,0}, {18596,18569,18597 ,6306,6301,6303 ,0,0,0}, + {18597,18577,18598 ,6303,6300,6340 ,0,0,0}, {18599,18600,18562 ,6371,6300,6300 ,0,0,0}, + {18601,18566,18600 ,6300,6369,6300 ,0,0,0}, {18602,18563,18603 ,6300,6306,6300 ,0,0,0}, + {18602,18603,18571 ,6300,6300,6300 ,0,0,0}, {18604,18605,17216 ,6300,6300,6316 ,0,0,0}, + {18560,18605,18606 ,6300,6300,6316 ,0,0,0}, {18558,18607,18608 ,6300,6303,6301 ,0,0,0}, + {18564,18608,18609 ,6300,6301,6301 ,0,0,0}, {17214,17213,18610 ,6300,6364,6369 ,0,0,0}, + {17159,17158,16810 ,6306,6298,6299 ,0,0,0}, {16810,17158,17221 ,6299,6298,6340 ,0,0,0}, + {18512,18504,17162 ,6298,6298,6309 ,0,0,0}, {18512,17162,17160 ,6298,6309,6316 ,0,0,0}, + {18504,18515,17165 ,6298,6301,6298 ,0,0,0}, {18515,18514,17166 ,6301,6340,6300 ,0,0,0}, + {18514,18501,17168 ,6340,6299,6301 ,0,0,0}, {18501,18518,17171 ,6299,6355,6306 ,0,0,0}, + {18518,18517,17172 ,6355,6300,6357 ,0,0,0}, {18517,18498,17174 ,6300,6303,6300 ,0,0,0}, + {18498,18494,17177 ,6303,6298,6299 ,0,0,0}, {18494,18521,17178 ,6298,6300,6299 ,0,0,0}, + {18521,18525,17180 ,6300,6300,6300 ,0,0,0}, {18525,18495,17183 ,6300,6298,6298 ,0,0,0}, + {18495,18528,17184 ,6298,6299,6300 ,0,0,0}, {18528,18530,17186 ,6299,6298,6316 ,0,0,0}, + {18530,18532,17189 ,6298,6364,6364 ,0,0,0}, {18532,18534,17190 ,6364,6300,6298 ,0,0,0}, + {18534,18536,17192 ,6300,6298,6300 ,0,0,0}, {18536,18538,17195 ,6298,6364,6300 ,0,0,0}, + {18538,18540,17196 ,6364,6300,6300 ,0,0,0}, {18540,18542,17198 ,6300,6366,6365 ,0,0,0}, + {18542,18544,17201 ,6366,6367,6300 ,0,0,0}, {18544,18546,17202 ,6367,6300,6367 ,0,0,0}, + {18546,18549,17204 ,6300,6368,6300 ,0,0,0}, {18549,18552,17207 ,6368,6369,6300 ,0,0,0}, + {18552,18555,17208 ,6369,6367,6367 ,0,0,0}, {18555,18556,17210 ,6367,6370,6300 ,0,0,0}, + {18556,18610,17213 ,6370,6369,6364 ,0,0,0}, {18610,18557,17214 ,6369,6300,6300 ,0,0,0}, + {18557,18604,17216 ,6300,6300,6316 ,0,0,0}, {18604,18606,18605 ,6300,6316,6300 ,0,0,0}, + {18606,18561,18560 ,6316,6371,6300 ,0,0,0}, {18561,18599,18562 ,6371,6371,6300 ,0,0,0}, + {18599,18601,18600 ,6371,6300,6300 ,0,0,0}, {18601,18567,18566 ,6300,6300,6369 ,0,0,0}, + {18567,18593,18568 ,6300,6367,6367 ,0,0,0}, {18593,18595,18594 ,6367,6316,6316 ,0,0,0}, + {18595,18574,18573 ,6316,6367,6369 ,0,0,0}, {18574,18582,18572 ,6367,6316,6300 ,0,0,0}, + {18582,18590,18581 ,6316,6300,6364 ,0,0,0}, {18590,18589,18588 ,6300,6364,6372 ,0,0,0}, + {18589,18592,18587 ,6364,6370,6364 ,0,0,0}, {18592,18579,18578 ,6370,6300,6364 ,0,0,0}, + {18579,18586,18580 ,6300,6316,6300 ,0,0,0}, {18586,18583,18585 ,6316,6300,6316 ,0,0,0}, + {18583,18591,18584 ,6300,6367,6364 ,0,0,0}, {18591,18576,18575 ,6367,6316,6316 ,0,0,0}, + {18576,18598,18577 ,6316,6340,6300 ,0,0,0}, {18598,18596,18597 ,6340,6306,6303 ,0,0,0}, + {18596,18570,18569 ,6306,6301,6301 ,0,0,0}, {18570,18602,18571 ,6301,6300,6300 ,0,0,0}, + {18563,18565,18603 ,6306,6303,6300 ,0,0,0}, {18564,18609,18565 ,6300,6301,6303 ,0,0,0}, + {18608,18607,18609 ,6301,6303,6301 ,0,0,0}, {18558,18559,18607 ,6300,6316,6303 ,0,0,0}, + {18553,18554,18559 ,6316,6300,6316 ,0,0,0}, {18550,18551,18554 ,6300,6300,6300 ,0,0,0}, + {18547,18548,18551 ,6301,6300,6300 ,0,0,0}, {16906,18545,18548 ,6300,6300,6300 ,0,0,0}, + {16906,16905,18543 ,6300,6300,6316 ,0,0,0}, {16905,16902,18541 ,6300,6300,6300 ,0,0,0}, + {16902,16900,18539 ,6300,6303,6303 ,0,0,0}, {16900,16901,18537 ,6303,6300,6340 ,0,0,0}, + {16901,16899,18535 ,6300,6340,6323 ,0,0,0}, {16899,16896,18533 ,6340,6340,6340 ,0,0,0}, + {16896,16894,18531 ,6340,6316,6306 ,0,0,0}, {16894,16893,18529 ,6316,6340,6300 ,0,0,0}, + {16893,16890,18527 ,6340,6340,6352 ,0,0,0}, {16890,16888,18526 ,6340,6352,6303 ,0,0,0}, + {16888,16886,18524 ,6352,6300,6328 ,0,0,0}, {16886,16885,18523 ,6300,6301,6353 ,0,0,0}, + {16885,16881,18522 ,6301,6300,6363 ,0,0,0}, {16881,16880,18520 ,6300,6301,6311 ,0,0,0}, + {16880,16876,18519 ,6301,6362,6353 ,0,0,0}, {16876,16875,18497 ,6362,6302,6302 ,0,0,0}, + {16875,16879,18496 ,6302,6333,6301 ,0,0,0}, {16879,16873,18516 ,6333,6361,6301 ,0,0,0}, + {16873,16872,18500 ,6361,6304,6305 ,0,0,0}, {16872,16874,18499 ,6304,6314,6304 ,0,0,0}, + {16874,16869,18513 ,6314,6336,6311 ,0,0,0}, {16869,16870,18503 ,6336,6305,6308 ,0,0,0}, + {16870,16862,18502 ,6305,6304,6307 ,0,0,0}, {16862,16864,18508 ,6304,6314,6313 ,0,0,0}, + {16864,16866,18507 ,6314,6358,6308 ,0,0,0}, {16866,16858,18505 ,6358,6311,6310 ,0,0,0}, + {16858,16857,18506 ,6311,6359,6312 ,0,0,0}, {16857,16861,18510 ,6359,6319,6318 ,0,0,0}, + {16861,16854,18509 ,6319,6315,6317 ,0,0,0}, {16854,16856,17278 ,6315,6354,6316 ,0,0,0}, + {16856,16850,17276 ,6354,6350,6351 ,0,0,0}, {16850,16849,17275 ,6350,6320,6322 ,0,0,0}, + {16849,16851,17273 ,6320,6349,6321 ,0,0,0}, {16851,16843,17270 ,6349,6346,6345 ,0,0,0}, + {16843,16845,17269 ,6346,6341,6343 ,0,0,0}, {16845,16847,17267 ,6341,6344,6342 ,0,0,0}, + {16847,16839,17264 ,6344,6325,6327 ,0,0,0}, {16839,16838,17263 ,6325,6338,6326 ,0,0,0}, + {16838,16841,17261 ,6338,6324,6339 ,0,0,0}, {16841,16909,17258 ,6324,6298,6336 ,0,0,0}, + {16909,16836,17257 ,6298,6330,6329 ,0,0,0}, {16836,16910,17255 ,6330,6324,6301 ,0,0,0}, + {16910,16837,17252 ,6324,6337,6331 ,0,0,0}, {16837,16829,17251 ,6337,6332,6333 ,0,0,0}, + {16829,16832,17249 ,6332,6334,6328 ,0,0,0}, {16832,16824,17246 ,6334,6340,6335 ,0,0,0}, + {16824,16823,17245 ,6340,6299,6328 ,0,0,0}, {16823,16827,17243 ,6299,6324,6328 ,0,0,0}, + {16827,16826,17240 ,6324,6347,6298 ,0,0,0}, {16826,16819,17239 ,6347,6306,6298 ,0,0,0}, + {16819,16822,17237 ,6306,6316,6324 ,0,0,0}, {16821,17233,17234 ,6324,6299,6348 ,0,0,0}, + {16808,17231,16816 ,6353,6323,6303 ,0,0,0}, {16807,17227,17228 ,6300,6299,6352 ,0,0,0}, + {16808,17228,17231 ,6353,6352,6323 ,0,0,0}, {16813,16805,17225 ,6356,6298,6357 ,0,0,0}, + {16807,16813,17227 ,6300,6356,6299 ,0,0,0}, {17222,16804,17221 ,6299,6355,6340 ,0,0,0}, + {17225,16805,17222 ,6357,6298,6299 ,0,0,0}, {16810,17221,16804 ,6299,6340,6355 ,0,0,0}, + {18605,17218,17216 ,6373,6374,6375 ,0,0,0}, {18611,18612,18600 ,6376,6377,6378 ,0,0,0}, + {18562,18613,18560 ,6379,6380,6381 ,0,0,0}, {18594,18573,18614 ,6382,6383,6384 ,0,0,0}, + {18566,18568,18615 ,6385,6386,6387 ,0,0,0}, {18616,18617,18588 ,6388,6389,6390 ,0,0,0}, + {18618,18619,18572 ,6391,6392,6393 ,0,0,0}, {18580,18585,18620 ,6394,6395,6396 ,0,0,0}, + {18587,18578,18621 ,6397,6398,6399 ,0,0,0}, {18622,18623,18577 ,6400,6401,6402 ,0,0,0}, + {18624,18625,18584 ,6403,6404,6405 ,0,0,0}, {18571,18603,18626 ,6406,6407,6408 ,0,0,0}, + {18597,18569,18627 ,6409,6410,6411 ,0,0,0}, {18628,18629,18607 ,6412,6413,6414 ,0,0,0}, + {18630,18631,18565 ,6415,6416,6417 ,0,0,0}, {18632,18551,18633 ,6418,6419,6420 ,0,0,0}, + {18559,18554,18634 ,6421,6422,6423 ,0,0,0}, {18543,18635,18636 ,6424,6425,6426 ,0,0,0}, + {18545,18637,18548 ,6427,6428,6429 ,0,0,0}, {18638,18639,18537 ,6430,6431,6432 ,0,0,0}, + {18640,18541,18539 ,6433,6434,6435 ,0,0,0}, {18641,18533,18531 ,6436,6437,6438 ,0,0,0}, + {18535,18533,18642 ,6439,6437,6440 ,0,0,0}, {18643,18527,18644 ,6441,6442,6443 ,0,0,0}, + {18529,18643,18645 ,6444,6441,6445 ,0,0,0}, {18524,18523,18646 ,6446,6447,6448 ,0,0,0}, + {18526,18647,18644 ,6449,6450,6443 ,0,0,0}, {18522,18520,18648 ,6451,6452,6453 ,0,0,0}, + {18522,18649,18523 ,6451,6454,6447 ,0,0,0}, {18519,18497,18650 ,6455,6456,6457 ,0,0,0}, + {18519,18651,18520 ,6455,6458,6452 ,0,0,0}, {18652,18497,18496 ,6459,6456,6460 ,0,0,0}, + {18497,18652,18650 ,6456,6459,6457 ,0,0,0}, {18516,18653,18496 ,6461,6462,6460 ,0,0,0}, + {18652,18496,18653 ,6459,6460,6462 ,0,0,0}, {18516,18500,18654 ,6461,6463,6464 ,0,0,0}, + {18654,18653,18516 ,6464,6462,6461 ,0,0,0}, {18655,18500,18499 ,6465,6463,6466 ,0,0,0}, + {18500,18655,18654 ,6463,6465,6464 ,0,0,0}, {18513,18656,18499 ,6467,6468,6466 ,0,0,0}, + {18655,18499,18656 ,6465,6466,6468 ,0,0,0}, {18513,18503,18657 ,6467,6469,6470 ,0,0,0}, + {18657,18656,18513 ,6470,6468,6467 ,0,0,0}, {18658,18503,18502 ,6471,6469,6472 ,0,0,0}, + {18503,18658,18657 ,6469,6471,6470 ,0,0,0}, {18508,18659,18502 ,6473,6474,6472 ,0,0,0}, + {18658,18502,18659 ,6471,6472,6474 ,0,0,0}, {18508,18507,18660 ,6473,6475,6476 ,0,0,0}, + {18660,18659,18508 ,6476,6474,6473 ,0,0,0}, {18661,18507,18505 ,6477,6475,6478 ,0,0,0}, + {18507,18661,18660 ,6475,6477,6476 ,0,0,0}, {18506,18662,18505 ,6479,6480,6478 ,0,0,0}, + {18661,18505,18662 ,6477,6478,6480 ,0,0,0}, {18506,18510,18663 ,6479,6481,6482 ,0,0,0}, + {18663,18662,18506 ,6482,6480,6479 ,0,0,0}, {18664,18510,18509 ,6483,6481,6484 ,0,0,0}, + {18510,18664,18663 ,6481,6483,6482 ,0,0,0}, {17278,18665,18509 ,6485,6486,6484 ,0,0,0}, + {18664,18509,18665 ,6483,6484,6486 ,0,0,0}, {17277,18665,17278 ,6487,6486,6485 ,0,0,0}, + {18651,18648,18520 ,6458,6453,6452 ,0,0,0}, {18519,18650,18651 ,6455,6457,6458 ,0,0,0}, + {18649,18646,18523 ,6454,6448,6447 ,0,0,0}, {18522,18648,18649 ,6451,6453,6454 ,0,0,0}, + {18526,18524,18647 ,6449,6446,6450 ,0,0,0}, {18524,18646,18647 ,6446,6448,6450 ,0,0,0}, + {18527,18643,18529 ,6442,6441,6444 ,0,0,0}, {18527,18526,18644 ,6442,6449,6443 ,0,0,0}, + {18641,18531,18645 ,6436,6438,6445 ,0,0,0}, {18531,18529,18645 ,6438,6444,6445 ,0,0,0}, + {18535,18642,18638 ,6439,6440,6430 ,0,0,0}, {18642,18533,18641 ,6440,6437,6436 ,0,0,0}, + {18639,18539,18537 ,6431,6435,6432 ,0,0,0}, {18638,18537,18535 ,6430,6432,6439 ,0,0,0}, + {18640,18635,18541 ,6433,6425,6434 ,0,0,0}, {18639,18640,18539 ,6431,6433,6435 ,0,0,0}, + {18543,18636,18545 ,6424,6426,6427 ,0,0,0}, {18541,18635,18543 ,6434,6425,6424 ,0,0,0}, + {18548,18637,18633 ,6429,6428,6420 ,0,0,0}, {18545,18636,18637 ,6427,6426,6428 ,0,0,0}, + {18554,18551,18632 ,6422,6419,6418 ,0,0,0}, {18551,18548,18633 ,6419,6429,6420 ,0,0,0}, + {18628,18559,18634 ,6412,6421,6423 ,0,0,0}, {18634,18554,18632 ,6423,6422,6418 ,0,0,0}, + {18629,18609,18607 ,6413,6488,6414 ,0,0,0}, {18628,18607,18559 ,6412,6414,6421 ,0,0,0}, + {18565,18609,18630 ,6417,6488,6415 ,0,0,0}, {18629,18630,18609 ,6413,6415,6488 ,0,0,0}, + {18603,18631,18626 ,6407,6416,6408 ,0,0,0}, {18565,18631,18603 ,6417,6416,6407 ,0,0,0}, + {18569,18571,18666 ,6410,6406,6489 ,0,0,0}, {18571,18626,18666 ,6406,6408,6489 ,0,0,0}, + {18622,18597,18627 ,6400,6409,6411 ,0,0,0}, {18627,18569,18666 ,6411,6410,6489 ,0,0,0}, + {18623,18575,18577 ,6401,6490,6402 ,0,0,0}, {18622,18577,18597 ,6400,6402,6409 ,0,0,0}, + {18584,18575,18624 ,6405,6490,6403 ,0,0,0}, {18623,18624,18575 ,6401,6403,6490 ,0,0,0}, + {18585,18625,18620 ,6395,6404,6396 ,0,0,0}, {18584,18625,18585 ,6405,6404,6395 ,0,0,0}, + {18578,18580,18667 ,6398,6394,6491 ,0,0,0}, {18580,18620,18667 ,6394,6396,6491 ,0,0,0}, + {18616,18587,18621 ,6388,6397,6399 ,0,0,0}, {18621,18578,18667 ,6399,6398,6491 ,0,0,0}, + {18617,18581,18588 ,6389,6492,6390 ,0,0,0}, {18616,18588,18587 ,6388,6390,6397 ,0,0,0}, + {18572,18581,18618 ,6393,6492,6391 ,0,0,0}, {18617,18618,18581 ,6389,6391,6492 ,0,0,0}, + {18573,18619,18614 ,6383,6392,6384 ,0,0,0}, {18572,18619,18573 ,6393,6392,6383 ,0,0,0}, + {18568,18594,18668 ,6386,6382,6493 ,0,0,0}, {18594,18614,18668 ,6382,6384,6493 ,0,0,0}, + {18611,18566,18615 ,6376,6385,6387 ,0,0,0}, {18615,18568,18668 ,6387,6386,6493 ,0,0,0}, + {18612,18562,18600 ,6377,6379,6378 ,0,0,0}, {18611,18600,18566 ,6376,6378,6385 ,0,0,0}, + {18613,18669,18560 ,6380,6494,6381 ,0,0,0}, {18612,18613,18562 ,6377,6380,6379 ,0,0,0}, + {17218,18605,18669 ,6374,6373,6494 ,0,0,0}, {18560,18669,18605 ,6381,6494,6373 ,0,0,0}, + {17229,17115,17230 ,6495,6495,6496 ,0,0,0}, {17236,17235,17121 ,6497,6496,6496 ,0,0,0}, + {18624,18623,18670 ,6498,6499,6500 ,0,0,0}, {17112,17229,17226 ,6501,6495,6501 ,0,0,0}, + {18621,18667,18671 ,6502,6503,6503 ,0,0,0}, {17223,17106,17109 ,6496,6504,6501 ,0,0,0}, + {18672,18614,18619 ,6498,6505,6506 ,0,0,0}, {17048,17157,17161 ,6507,6495,6495 ,0,0,0}, + {17058,17056,17170 ,6508,6509,6504 ,0,0,0}, {18673,18612,18611 ,6510,6511,6512 ,0,0,0}, + {17217,17100,17098 ,6513,6500,6514 ,0,0,0}, {17218,17100,17217 ,6515,6500,6513 ,0,0,0}, + {17212,17215,17099 ,6516,6517,6518 ,0,0,0}, {17179,17181,17064 ,6519,6520,6497 ,0,0,0}, + {17185,17187,17070 ,6521,6522,6523 ,0,0,0}, {17209,17092,17091 ,6524,6525,6526 ,0,0,0}, + {17188,17074,17073 ,6527,6500,6498 ,0,0,0}, {17205,17086,17203 ,6528,6522,6529 ,0,0,0}, + {17203,17085,17200 ,6529,6530,6531 ,0,0,0}, {17080,17197,17082 ,6532,6533,6502 ,0,0,0}, + {17194,17080,17079 ,6534,6532,6495 ,0,0,0}, {17206,17088,17205 ,6535,6502,6528 ,0,0,0}, + {17199,17200,17082 ,6533,6531,6502 ,0,0,0}, {17209,17091,17206 ,6524,6526,6535 ,0,0,0}, + {17088,17206,17091 ,6502,6535,6526 ,0,0,0}, {17191,17076,17074 ,6503,6514,6500 ,0,0,0}, + {17079,17076,17193 ,6495,6514,6530 ,0,0,0}, {17097,17092,17211 ,6536,6525,6537 ,0,0,0}, + {17092,17209,17211 ,6525,6524,6537 ,0,0,0}, {17097,17211,17212 ,6536,6537,6516 ,0,0,0}, + {17188,17073,17187 ,6527,6498,6522 ,0,0,0}, {17185,17068,17182 ,6521,6501,6509 ,0,0,0}, + {17212,17099,17097 ,6516,6518,6536 ,0,0,0}, {17099,17215,17098 ,6518,6517,6514 ,0,0,0}, + {17182,17067,17181 ,6509,6500,6520 ,0,0,0}, {17062,17176,17064 ,6508,6509,6497 ,0,0,0}, + {17217,17098,17215 ,6513,6514,6517 ,0,0,0}, {17058,17173,17061 ,6508,6508,6495 ,0,0,0}, + {17061,17175,17062 ,6495,6530,6508 ,0,0,0}, {18674,18613,18675 ,6538,6539,6540 ,0,0,0}, + {18669,17100,17218 ,6541,6500,6515 ,0,0,0}, {17169,17055,17167 ,6495,6496,6542 ,0,0,0}, + {17056,17055,17169 ,6509,6496,6495 ,0,0,0}, {17163,17164,17050 ,6542,6504,6507 ,0,0,0}, + {18668,18614,18676 ,6543,6505,6500 ,0,0,0}, {18677,18618,18678 ,6503,6533,6500 ,0,0,0}, + {17161,17163,17049 ,6495,6542,6495 ,0,0,0}, {18679,18678,18616 ,6508,6500,6538 ,0,0,0}, + {17106,17220,17105 ,6504,6542,6501 ,0,0,0}, {17048,17105,17219 ,6507,6501,6495 ,0,0,0}, + {18625,18680,18681 ,6527,6530,6498 ,0,0,0}, {18667,18620,18682 ,6503,6527,6499 ,0,0,0}, + {17112,17226,17111 ,6501,6501,6544 ,0,0,0}, {17224,17109,17111 ,6504,6501,6544 ,0,0,0}, + {18627,18683,18684 ,6508,6530,6544 ,0,0,0}, {18685,18622,18684 ,6498,6500,6544 ,0,0,0}, + {17117,17232,17230 ,6495,6495,6496 ,0,0,0}, {18666,18626,18683 ,6523,6504,6530 ,0,0,0}, + {18631,18686,18626 ,6500,6504,6504 ,0,0,0}, {18631,18630,18687 ,6500,6522,6500 ,0,0,0}, + {17235,17232,17118 ,6496,6495,6496 ,0,0,0}, {18688,18630,18629 ,6515,6522,6504 ,0,0,0}, + {18628,18689,18629 ,6508,6500,6504 ,0,0,0}, {17238,17121,17123 ,6495,6496,6508 ,0,0,0}, + {18689,18628,18690 ,6500,6508,6498 ,0,0,0}, {17241,17123,17124 ,6504,6508,6507 ,0,0,0}, + {18691,18690,18634 ,6515,6498,6545 ,0,0,0}, {17242,17124,17127 ,6507,6507,6495 ,0,0,0}, + {18692,18691,18632 ,6498,6515,6504 ,0,0,0}, {17244,17127,17129 ,6504,6495,6495 ,0,0,0}, + {18693,18692,18633 ,6504,6498,6504 ,0,0,0}, {17129,17130,17247 ,6495,6504,6504 ,0,0,0}, + {18694,18693,18637 ,6504,6504,6498 ,0,0,0}, {17248,17247,17130 ,6504,6504,6504 ,0,0,0}, + {18694,18636,18635 ,6504,6504,6504 ,0,0,0}, {17250,17248,17133 ,6546,6504,6504 ,0,0,0}, + {18695,18635,18640 ,6508,6504,6504 ,0,0,0}, {17253,17250,17135 ,6507,6546,6504 ,0,0,0}, + {18696,18640,18639 ,6508,6504,6508 ,0,0,0}, {17254,17253,17136 ,6547,6507,6548 ,0,0,0}, + {18697,18639,18638 ,6498,6508,6498 ,0,0,0}, {17256,17254,17139 ,6546,6547,6548 ,0,0,0}, + {18698,18638,18642 ,6504,6498,6498 ,0,0,0}, {17141,17259,17139 ,6549,6547,6548 ,0,0,0}, + {18642,18699,18698 ,6498,6504,6504 ,0,0,0}, {17260,17141,17142 ,6549,6549,6550 ,0,0,0}, + {18699,18641,18700 ,6504,6504,6498 ,0,0,0}, {17142,17145,17262 ,6550,6549,6504 ,0,0,0}, + {17265,17145,17147 ,6549,6549,6545 ,0,0,0}, {17268,17266,17149 ,6549,6504,6504 ,0,0,0}, + {18700,18645,18701 ,6498,6504,6504 ,0,0,0}, {17274,17272,17154 ,6551,6504,6515 ,0,0,0}, + {18646,18702,18647 ,6504,6508,6515 ,0,0,0}, {18703,18664,18704 ,6504,6545,6515 ,0,0,0}, + {18705,18648,18651 ,6508,6552,6504 ,0,0,0}, {18661,18706,18707 ,6553,6504,6554 ,0,0,0}, + {18708,18709,18652 ,6555,6504,6515 ,0,0,0}, {18656,18657,18710 ,6504,6504,6504 ,0,0,0}, + {18661,18707,18660 ,6553,6554,6504 ,0,0,0}, {18654,18711,18712 ,6504,6504,6515 ,0,0,0}, + {18710,18711,18655 ,6504,6504,6515 ,0,0,0}, {18659,18713,18658 ,6548,6504,6504 ,0,0,0}, + {18659,18660,18714 ,6548,6504,6549 ,0,0,0}, {18708,18653,18712 ,6555,6504,6515 ,0,0,0}, + {18715,18657,18658 ,6504,6504,6504 ,0,0,0}, {18716,18663,18703 ,6504,6548,6504 ,0,0,0}, + {18706,18662,18716 ,6504,6548,6504 ,0,0,0}, {18650,18717,18651 ,6504,6544,6504 ,0,0,0}, + {18650,18709,18717 ,6504,6504,6544 ,0,0,0}, {17277,17274,17156 ,6515,6551,6554 ,0,0,0}, + {17156,18704,18665 ,6554,6515,6545 ,0,0,0}, {18649,18718,18646 ,6515,6504,6504 ,0,0,0}, + {18719,18649,18648 ,6508,6515,6552 ,0,0,0}, {17271,17268,17148 ,6504,6549,6549 ,0,0,0}, + {17151,17272,17271 ,6545,6504,6504 ,0,0,0}, {18643,18720,18701 ,6508,6498,6504 ,0,0,0}, + {18702,18720,18644 ,6508,6498,6498 ,0,0,0}, {17266,17147,17149 ,6504,6545,6504 ,0,0,0}, + {17164,17167,17052 ,6504,6542,6504 ,0,0,0}, {18721,18615,18722 ,6556,6557,6558 ,0,0,0}, + {18670,18623,18685 ,6500,6499,6498 ,0,0,0}, {17086,17205,17088 ,6522,6528,6502 ,0,0,0}, + {17085,17203,17086 ,6530,6529,6522 ,0,0,0}, {17082,17200,17085 ,6502,6531,6530 ,0,0,0}, + {17082,17197,17199 ,6502,6533,6533 ,0,0,0}, {17080,17194,17197 ,6532,6534,6533 ,0,0,0}, + {17079,17193,17194 ,6495,6530,6534 ,0,0,0}, {17076,17191,17193 ,6514,6503,6530 ,0,0,0}, + {17074,17188,17191 ,6500,6527,6503 ,0,0,0}, {17070,17187,17073 ,6523,6522,6498 ,0,0,0}, + {17068,17185,17070 ,6501,6521,6523 ,0,0,0}, {17067,17182,17068 ,6500,6509,6501 ,0,0,0}, + {17064,17181,17067 ,6497,6520,6500 ,0,0,0}, {17064,17176,17179 ,6497,6509,6519 ,0,0,0}, + {17062,17175,17176 ,6508,6530,6509 ,0,0,0}, {17061,17173,17175 ,6495,6508,6530 ,0,0,0}, + {17058,17170,17173 ,6508,6504,6508 ,0,0,0}, {17056,17169,17170 ,6509,6495,6504 ,0,0,0}, + {17052,17167,17055 ,6504,6542,6496 ,0,0,0}, {17050,17164,17052 ,6507,6504,6504 ,0,0,0}, + {17049,17163,17050 ,6495,6542,6507 ,0,0,0}, {17048,17161,17049 ,6507,6495,6495 ,0,0,0}, + {17048,17219,17157 ,6507,6495,6495 ,0,0,0}, {17105,17220,17219 ,6501,6542,6495 ,0,0,0}, + {17106,17223,17220 ,6504,6496,6542 ,0,0,0}, {17109,17224,17223 ,6501,6504,6496 ,0,0,0}, + {17111,17226,17224 ,6544,6501,6504 ,0,0,0}, {17115,17229,17112 ,6495,6495,6501 ,0,0,0}, + {17117,17230,17115 ,6495,6496,6495 ,0,0,0}, {17118,17232,17117 ,6496,6495,6495 ,0,0,0}, + {17121,17235,17118 ,6496,6496,6496 ,0,0,0}, {17121,17238,17236 ,6496,6495,6497 ,0,0,0}, + {17123,17241,17238 ,6508,6504,6495 ,0,0,0}, {17124,17242,17241 ,6507,6507,6504 ,0,0,0}, + {17127,17244,17242 ,6495,6504,6507 ,0,0,0}, {17129,17247,17244 ,6495,6504,6504 ,0,0,0}, + {17133,17248,17130 ,6504,6504,6504 ,0,0,0}, {17135,17250,17133 ,6504,6546,6504 ,0,0,0}, + {17136,17253,17135 ,6548,6507,6504 ,0,0,0}, {17139,17254,17136 ,6548,6547,6548 ,0,0,0}, + {17139,17259,17256 ,6548,6547,6546 ,0,0,0}, {17141,17260,17259 ,6549,6549,6547 ,0,0,0}, + {17142,17262,17260 ,6550,6504,6549 ,0,0,0}, {17145,17265,17262 ,6549,6549,6504 ,0,0,0}, + {17147,17266,17265 ,6545,6504,6549 ,0,0,0}, {17148,17268,17149 ,6549,6549,6504 ,0,0,0}, + {17151,17271,17148 ,6545,6504,6549 ,0,0,0}, {17154,17272,17151 ,6515,6504,6545 ,0,0,0}, + {17156,17274,17154 ,6554,6551,6515 ,0,0,0}, {17156,18665,17277 ,6554,6545,6515 ,0,0,0}, + {18704,18664,18665 ,6515,6545,6545 ,0,0,0}, {18703,18663,18664 ,6504,6548,6545 ,0,0,0}, + {18716,18662,18663 ,6504,6548,6548 ,0,0,0}, {18706,18661,18662 ,6504,6553,6548 ,0,0,0}, + {18714,18660,18707 ,6549,6504,6554 ,0,0,0}, {18713,18659,18714 ,6504,6548,6549 ,0,0,0}, + {18715,18658,18713 ,6504,6504,6504 ,0,0,0}, {18710,18657,18715 ,6504,6504,6504 ,0,0,0}, + {18710,18655,18656 ,6504,6515,6504 ,0,0,0}, {18711,18654,18655 ,6504,6504,6515 ,0,0,0}, + {18712,18653,18654 ,6515,6504,6504 ,0,0,0}, {18708,18652,18653 ,6555,6515,6504 ,0,0,0}, + {18709,18650,18652 ,6504,6504,6515 ,0,0,0}, {18705,18651,18717 ,6508,6504,6544 ,0,0,0}, + {18719,18648,18705 ,6508,6552,6508 ,0,0,0}, {18718,18649,18719 ,6504,6515,6508 ,0,0,0}, + {18702,18646,18718 ,6508,6504,6504 ,0,0,0}, {18702,18644,18647 ,6508,6498,6515 ,0,0,0}, + {18720,18643,18644 ,6498,6508,6498 ,0,0,0}, {18701,18645,18643 ,6504,6504,6508 ,0,0,0}, + {18700,18641,18645 ,6498,6504,6504 ,0,0,0}, {18699,18642,18641 ,6504,6498,6504 ,0,0,0}, + {18697,18638,18698 ,6498,6498,6504 ,0,0,0}, {18696,18639,18697 ,6508,6508,6498 ,0,0,0}, + {18695,18640,18696 ,6508,6504,6508 ,0,0,0}, {18694,18635,18695 ,6504,6504,6508 ,0,0,0}, + {18694,18637,18636 ,6504,6498,6504 ,0,0,0}, {18693,18633,18637 ,6504,6504,6498 ,0,0,0}, + {18692,18632,18633 ,6498,6504,6504 ,0,0,0}, {18691,18634,18632 ,6515,6545,6504 ,0,0,0}, + {18690,18628,18634 ,6498,6508,6545 ,0,0,0}, {18688,18629,18689 ,6515,6504,6500 ,0,0,0}, + {18687,18630,18688 ,6500,6522,6515 ,0,0,0}, {18686,18631,18687 ,6504,6500,6500 ,0,0,0}, + {18683,18626,18686 ,6530,6504,6504 ,0,0,0}, {18683,18627,18666 ,6530,6508,6523 ,0,0,0}, + {18684,18622,18627 ,6544,6500,6508 ,0,0,0}, {18685,18623,18622 ,6498,6499,6500 ,0,0,0}, + {18680,18624,18670 ,6530,6498,6500 ,0,0,0}, {18681,18620,18625 ,6498,6527,6527 ,0,0,0}, + {18680,18625,18624 ,6530,6527,6498 ,0,0,0}, {18682,18671,18667 ,6499,6503,6503 ,0,0,0}, + {18681,18682,18620 ,6498,6499,6527 ,0,0,0}, {18671,18679,18621 ,6503,6508,6502 ,0,0,0}, + {18616,18678,18617 ,6538,6500,6559 ,0,0,0}, {18621,18679,18616 ,6502,6508,6538 ,0,0,0}, + {18619,18618,18677 ,6506,6533,6503 ,0,0,0}, {18618,18617,18678 ,6533,6559,6500 ,0,0,0}, + {18676,18614,18672 ,6500,6505,6498 ,0,0,0}, {18672,18619,18677 ,6498,6506,6503 ,0,0,0}, + {18722,18668,18676 ,6558,6543,6500 ,0,0,0}, {18721,18611,18615 ,6556,6512,6557 ,0,0,0}, + {18722,18615,18668 ,6558,6557,6543 ,0,0,0}, {18673,18675,18612 ,6510,6540,6511 ,0,0,0}, + {18721,18673,18611 ,6556,6510,6512 ,0,0,0}, {18613,18674,18669 ,6539,6538,6541 ,0,0,0}, + {18612,18675,18613 ,6511,6540,6539 ,0,0,0}, {17100,18669,18674 ,6500,6541,6538 ,0,0,0}, + {18674,17102,17100 ,6560,6561,6562 ,0,0,0}, {18721,18723,18673 ,6563,6564,6565 ,0,0,0}, + {18675,18724,18725 ,6566,6567,6568 ,0,0,0}, {18672,18677,18726 ,6569,6570,6571 ,0,0,0}, + {18722,18676,18727 ,6572,6573,6574 ,0,0,0}, {18728,18729,18671 ,6575,6576,6577 ,0,0,0}, + {18730,18731,18678 ,6578,6579,6580 ,0,0,0}, {18680,18670,18732 ,6581,6582,6583 ,0,0,0}, + {18682,18681,18733 ,6584,6585,6586 ,0,0,0}, {18734,18735,18683 ,6587,6588,6589 ,0,0,0}, + {18736,18685,18684 ,6590,6591,6592 ,0,0,0}, {18688,18689,18737 ,6593,6594,6595 ,0,0,0}, + {18687,18738,18739 ,6596,6597,6598 ,0,0,0}, {18740,18741,18692 ,6599,6600,6601 ,0,0,0}, + {18742,18743,18690 ,6602,6603,6604 ,0,0,0}, {18744,18695,18745 ,6605,6606,6607 ,0,0,0}, + {18693,18694,18746 ,6608,6609,6610 ,0,0,0}, {18697,18698,18747 ,6611,6612,6613 ,0,0,0}, + {18697,18748,18696 ,6611,6614,6615 ,0,0,0}, {18701,18749,18700 ,6616,6617,6618 ,0,0,0}, + {18750,18751,18699 ,6619,6620,6621 ,0,0,0}, {18702,18752,18720 ,6622,6623,6624 ,0,0,0}, + {18753,18701,18720 ,6625,6616,6624 ,0,0,0}, {18754,18755,18719 ,6626,6627,6628 ,0,0,0}, + {18756,18718,18755 ,6629,6630,6627 ,0,0,0}, {18757,18758,18717 ,6631,6632,6633 ,0,0,0}, + {18754,18705,18758 ,6626,6634,6632 ,0,0,0}, {18708,18759,18709 ,6635,6636,6637 ,0,0,0}, + {18757,18709,18759 ,6631,6637,6636 ,0,0,0}, {18708,18712,18760 ,6635,6638,6639 ,0,0,0}, + {18760,18759,18708 ,6639,6636,6635 ,0,0,0}, {18761,18712,18711 ,6640,6638,6641 ,0,0,0}, + {18712,18761,18760 ,6638,6640,6639 ,0,0,0}, {18710,18762,18711 ,6642,6643,6641 ,0,0,0}, + {18761,18711,18762 ,6640,6641,6643 ,0,0,0}, {18710,18715,18763 ,6642,6644,6645 ,0,0,0}, + {18763,18762,18710 ,6645,6643,6642 ,0,0,0}, {18764,18715,18713 ,6646,6644,6647 ,0,0,0}, + {18715,18764,18763 ,6644,6646,6645 ,0,0,0}, {18714,18765,18713 ,6648,6649,6647 ,0,0,0}, + {18764,18713,18765 ,6646,6647,6649 ,0,0,0}, {18714,18707,18766 ,6648,6650,6651 ,0,0,0}, + {18766,18765,18714 ,6651,6649,6648 ,0,0,0}, {18767,18707,18706 ,6652,6650,6653 ,0,0,0}, + {18707,18767,18766 ,6650,6652,6651 ,0,0,0}, {18706,18768,18769 ,6653,6654,6655 ,0,0,0}, + {18767,18706,18769 ,6652,6653,6655 ,0,0,0}, {18768,18716,18770 ,6654,6656,6657 ,0,0,0}, + {18716,18768,18706 ,6656,6654,6653 ,0,0,0}, {18770,18703,18704 ,6657,6658,6659 ,0,0,0}, + {18716,18703,18770 ,6656,6658,6657 ,0,0,0}, {17156,18771,18704 ,6660,6661,6659 ,0,0,0}, + {18770,18704,18771 ,6657,6659,6661 ,0,0,0}, {17155,18771,17156 ,6660,6661,6660 ,0,0,0}, + {18705,18717,18758 ,6634,6633,6632 ,0,0,0}, {18757,18717,18709 ,6631,6633,6637 ,0,0,0}, + {18718,18719,18755 ,6630,6628,6627 ,0,0,0}, {18754,18719,18705 ,6626,6628,6634 ,0,0,0}, + {18756,18752,18702 ,6629,6623,6622 ,0,0,0}, {18756,18702,18718 ,6629,6622,6630 ,0,0,0}, + {18749,18701,18753 ,6617,6616,6625 ,0,0,0}, {18752,18753,18720 ,6623,6625,6624 ,0,0,0}, + {18700,18750,18699 ,6618,6619,6621 ,0,0,0}, {18749,18750,18700 ,6617,6619,6618 ,0,0,0}, + {18698,18751,18747 ,6612,6620,6613 ,0,0,0}, {18699,18751,18698 ,6621,6620,6612 ,0,0,0}, + {18748,18745,18696 ,6614,6607,6615 ,0,0,0}, {18697,18747,18748 ,6611,6613,6614 ,0,0,0}, + {18694,18695,18744 ,6609,6606,6605 ,0,0,0}, {18695,18696,18745 ,6606,6615,6607 ,0,0,0}, + {18740,18693,18746 ,6599,6608,6610 ,0,0,0}, {18746,18694,18744 ,6610,6609,6605 ,0,0,0}, + {18741,18691,18692 ,6600,6662,6601 ,0,0,0}, {18740,18692,18693 ,6599,6601,6608 ,0,0,0}, + {18690,18691,18742 ,6604,6662,6602 ,0,0,0}, {18741,18742,18691 ,6600,6602,6662 ,0,0,0}, + {18689,18743,18737 ,6594,6603,6595 ,0,0,0}, {18690,18743,18689 ,6604,6603,6594 ,0,0,0}, + {18687,18688,18738 ,6596,6593,6597 ,0,0,0}, {18688,18737,18738 ,6593,6595,6597 ,0,0,0}, + {18734,18686,18739 ,6587,6663,6598 ,0,0,0}, {18686,18687,18739 ,6663,6596,6598 ,0,0,0}, + {18735,18684,18683 ,6588,6592,6589 ,0,0,0}, {18734,18683,18686 ,6587,6589,6663 ,0,0,0}, + {18736,18772,18685 ,6590,6664,6591 ,0,0,0}, {18735,18736,18684 ,6588,6590,6592 ,0,0,0}, + {18732,18670,18772 ,6583,6582,6664 ,0,0,0}, {18685,18772,18670 ,6591,6664,6582 ,0,0,0}, + {18681,18680,18773 ,6585,6581,6665 ,0,0,0}, {18680,18732,18773 ,6581,6583,6665 ,0,0,0}, + {18728,18682,18733 ,6575,6584,6586 ,0,0,0}, {18733,18681,18773 ,6586,6585,6665 ,0,0,0}, + {18729,18679,18671 ,6576,6666,6577 ,0,0,0}, {18728,18671,18682 ,6575,6577,6584 ,0,0,0}, + {18678,18679,18730 ,6580,6666,6578 ,0,0,0}, {18729,18730,18679 ,6576,6578,6666 ,0,0,0}, + {18677,18731,18726 ,6570,6579,6571 ,0,0,0}, {18678,18731,18677 ,6580,6579,6570 ,0,0,0}, + {18676,18672,18774 ,6573,6569,6667 ,0,0,0}, {18672,18726,18774 ,6569,6571,6667 ,0,0,0}, + {18723,18722,18727 ,6564,6572,6574 ,0,0,0}, {18727,18676,18774 ,6574,6573,6667 ,0,0,0}, + {18723,18724,18673 ,6564,6567,6565 ,0,0,0}, {18723,18721,18722 ,6564,6563,6572 ,0,0,0}, + {18725,18775,18675 ,6568,6668,6566 ,0,0,0}, {18673,18724,18675 ,6565,6567,6566 ,0,0,0}, + {17102,18674,18775 ,6561,6560,6668 ,0,0,0}, {18675,18775,18674 ,6566,6668,6560 ,0,0,0}, + {17066,17069,16973 ,6669,6670,6671 ,0,0,0}, {18728,18733,18776 ,6672,6671,6671 ,0,0,0}, + {16979,17075,16988 ,6673,6674,6671 ,0,0,0}, {17069,17071,16982 ,6670,6669,6675 ,0,0,0}, + {17081,17011,16983 ,6670,6676,6677 ,0,0,0}, {18777,18778,18746 ,6324,6298,6672 ,0,0,0}, + {18779,18738,18737 ,6671,6672,6671 ,0,0,0}, {18780,18781,18742 ,6672,6671,6671 ,0,0,0}, + {17094,17005,17001 ,6678,6671,6679 ,0,0,0}, {18739,18738,18782 ,6671,6672,6680 ,0,0,0}, + {17007,17101,17009 ,6679,6671,6671 ,0,0,0}, {18783,18784,18736 ,6672,6672,6672 ,0,0,0}, + {18785,18786,18723 ,6672,6681,6672 ,0,0,0}, {18775,18725,18787 ,6671,6681,6672 ,0,0,0}, + {18788,18730,18729 ,6672,6672,6681 ,0,0,0}, {18726,18789,18790 ,6672,6672,6672 ,0,0,0}, + {18791,18774,18790 ,6672,6671,6672 ,0,0,0}, {18728,18792,18729 ,6672,6671,6681 ,0,0,0}, + {18731,18788,18789 ,6672,6672,6672 ,0,0,0}, {18785,18727,18791 ,6672,6672,6672 ,0,0,0}, + {18793,18794,18773 ,6671,6672,6672 ,0,0,0}, {18725,18724,18795 ,6681,6671,6671 ,0,0,0}, + {18732,18796,18793 ,6671,6681,6671 ,0,0,0}, {17102,18775,17009 ,6671,6671,6671 ,0,0,0}, + {18772,18784,18796 ,6672,6672,6681 ,0,0,0}, {17005,17095,17006 ,6671,6682,6672 ,0,0,0}, + {17007,17006,17096 ,6679,6672,6298 ,0,0,0}, {18739,18797,18734 ,6671,6671,6672 ,0,0,0}, + {18797,18783,18735 ,6671,6672,6672 ,0,0,0}, {17089,17090,16997 ,6672,6681,6670 ,0,0,0}, + {17001,17003,17093 ,6679,6669,6669 ,0,0,0}, {18781,18798,18743 ,6671,6672,6671 ,0,0,0}, + {17087,17089,16999 ,6671,6672,6681 ,0,0,0}, {16994,17011,17083 ,6669,6676,6298 ,0,0,0}, + {16994,17084,17087 ,6669,6669,6671 ,0,0,0}, {18799,18740,18778 ,6672,6671,6298 ,0,0,0}, + {18799,18780,18741 ,6672,6672,6672 ,0,0,0}, {17077,16985,16988 ,6683,6669,6671 ,0,0,0}, + {16983,16985,17078 ,6677,6669,6684 ,0,0,0}, {18748,18800,18745 ,6671,6685,6686 ,0,0,0}, + {18777,18744,18745 ,6324,6687,6686 ,0,0,0}, {18748,18747,18801 ,6671,6688,6688 ,0,0,0}, + {17071,17072,16978 ,6669,6689,6684 ,0,0,0}, {18802,18803,18750 ,6672,6690,6671 ,0,0,0}, + {18803,18804,18751 ,6690,6686,6690 ,0,0,0}, {18805,18802,18749 ,6691,6672,6691 ,0,0,0}, + {16973,16976,17065 ,6671,6692,6672 ,0,0,0}, {16975,17063,16976 ,6693,6673,6692 ,0,0,0}, + {16968,17060,16975 ,6672,6689,6693 ,0,0,0}, {18753,18806,18805 ,6686,6690,6691 ,0,0,0}, + {17059,16968,16971 ,6694,6672,6695 ,0,0,0}, {18752,18807,18806 ,6690,6691,6690 ,0,0,0}, + {16971,16970,17057 ,6695,6696,6697 ,0,0,0}, {18807,18756,18755 ,6691,6672,6688 ,0,0,0}, + {16965,17053,17054 ,6698,6699,6700 ,0,0,0}, {18808,18809,18754 ,6672,6688,6688 ,0,0,0}, + {18758,18757,18810 ,6688,6691,6701 ,0,0,0}, {18811,18759,18760 ,6686,6672,6671 ,0,0,0}, + {17051,17053,16913 ,6676,6699,6702 ,0,0,0}, {18761,18812,18813 ,6672,6671,6671 ,0,0,0}, + {17051,16912,17047 ,6676,6687,6703 ,0,0,0}, {18814,18762,18763 ,6686,6704,6672 ,0,0,0}, + {16912,16960,17103 ,6687,6705,6676 ,0,0,0}, {18765,18815,18764 ,6686,6706,6672 ,0,0,0}, + {17046,17104,16960 ,6698,6699,6705 ,0,0,0}, {17108,16951,16950 ,6697,6707,6708 ,0,0,0}, + {17107,17046,16951 ,6709,6698,6707 ,0,0,0}, {18816,18768,18770 ,6690,6671,6701 ,0,0,0}, + {16950,17044,17110 ,6708,6672,6694 ,0,0,0}, {18771,16938,18817 ,6690,6690,6686 ,0,0,0}, + {17114,17113,17042 ,6673,6689,6710 ,0,0,0}, {16936,16938,17153 ,6711,6690,6690 ,0,0,0}, + {17116,17114,17040 ,6686,6673,6692 ,0,0,0}, {17150,16934,17152 ,6712,6713,6685 ,0,0,0}, + {17035,17036,17122 ,6714,6684,6669 ,0,0,0}, {17146,16931,16933 ,6715,6716,6717 ,0,0,0}, + {17031,17128,17030 ,6718,6719,6691 ,0,0,0}, {17134,17132,16919 ,6298,6670,6676 ,0,0,0}, + {17140,16924,16926 ,6686,6704,6720 ,0,0,0}, {16926,16928,17143 ,6720,6669,6715 ,0,0,0}, + {17134,16921,17137 ,6298,6718,6669 ,0,0,0}, {16921,16924,17138 ,6718,6704,6691 ,0,0,0}, + {18809,18755,18754 ,6688,6688,6688 ,0,0,0}, {17029,17132,17131 ,6676,6670,6684 ,0,0,0}, + {17146,17144,16931 ,6715,6669,6716 ,0,0,0}, {16933,16934,17150 ,6717,6713,6712 ,0,0,0}, + {16933,17150,17146 ,6717,6712,6715 ,0,0,0}, {17034,17125,17036 ,6673,6721,6684 ,0,0,0}, + {17034,17030,17126 ,6673,6691,6670 ,0,0,0}, {16936,17153,17152 ,6711,6690,6685 ,0,0,0}, + {16936,17152,16934 ,6711,6685,6713 ,0,0,0}, {17039,17119,17116 ,6691,6669,6686 ,0,0,0}, + {17120,17039,17035 ,6720,6691,6714 ,0,0,0}, {17155,17153,16938 ,6671,6690,6690 ,0,0,0}, + {18769,18818,18819 ,6686,6722,6688 ,0,0,0}, {18766,18767,18820 ,6691,6723,6706 ,0,0,0}, + {17144,17143,16928 ,6669,6715,6669 ,0,0,0}, {17144,16928,16931 ,6669,6669,6716 ,0,0,0}, + {17143,17140,16926 ,6715,6686,6720 ,0,0,0}, {17140,17138,16924 ,6686,6691,6704 ,0,0,0}, + {17138,17137,16921 ,6691,6669,6718 ,0,0,0}, {17134,16919,16921 ,6298,6676,6718 ,0,0,0}, + {17132,17029,16919 ,6670,6676,6676 ,0,0,0}, {17131,17128,17031 ,6684,6719,6718 ,0,0,0}, + {17131,17031,17029 ,6684,6718,6676 ,0,0,0}, {17128,17126,17030 ,6719,6670,6691 ,0,0,0}, + {17126,17125,17034 ,6670,6721,6673 ,0,0,0}, {17125,17122,17036 ,6721,6669,6684 ,0,0,0}, + {17122,17120,17035 ,6669,6720,6714 ,0,0,0}, {17120,17119,17039 ,6720,6669,6691 ,0,0,0}, + {17116,17040,17039 ,6686,6692,6691 ,0,0,0}, {17114,17042,17040 ,6673,6710,6692 ,0,0,0}, + {17113,17110,17044 ,6689,6694,6672 ,0,0,0}, {17113,17044,17042 ,6689,6672,6710 ,0,0,0}, + {17110,17108,16950 ,6694,6697,6708 ,0,0,0}, {17108,17107,16951 ,6697,6709,6707 ,0,0,0}, + {17107,17104,17046 ,6709,6699,6698 ,0,0,0}, {17104,17103,16960 ,6699,6676,6705 ,0,0,0}, + {17103,17047,16912 ,6676,6703,6687 ,0,0,0}, {17051,16913,16912 ,6676,6702,6687 ,0,0,0}, + {17053,16965,16913 ,6699,6698,6702 ,0,0,0}, {17054,17057,16970 ,6700,6697,6696 ,0,0,0}, + {17054,16970,16965 ,6700,6696,6698 ,0,0,0}, {17057,17059,16971 ,6697,6694,6695 ,0,0,0}, + {17059,17060,16968 ,6694,6689,6672 ,0,0,0}, {17060,17063,16975 ,6689,6673,6693 ,0,0,0}, + {17063,17065,16976 ,6673,6672,6692 ,0,0,0}, {17065,17066,16973 ,6672,6669,6671 ,0,0,0}, + {17069,16982,16973 ,6670,6675,6671 ,0,0,0}, {17071,16978,16982 ,6669,6684,6675 ,0,0,0}, + {17072,17075,16979 ,6689,6674,6673 ,0,0,0}, {17072,16979,16978 ,6689,6673,6684 ,0,0,0}, + {17075,17077,16988 ,6674,6683,6671 ,0,0,0}, {17077,17078,16985 ,6683,6684,6669 ,0,0,0}, + {17078,17081,16983 ,6684,6670,6677 ,0,0,0}, {17081,17083,17011 ,6670,6298,6676 ,0,0,0}, + {17083,17084,16994 ,6298,6669,6669 ,0,0,0}, {17087,16999,16994 ,6671,6681,6669 ,0,0,0}, + {17089,16997,16999 ,6672,6670,6681 ,0,0,0}, {17090,17093,17003 ,6681,6669,6669 ,0,0,0}, + {17090,17003,16997 ,6681,6669,6670 ,0,0,0}, {17093,17094,17001 ,6669,6678,6679 ,0,0,0}, + {17094,17095,17005 ,6678,6682,6671 ,0,0,0}, {17095,17096,17006 ,6682,6298,6672 ,0,0,0}, + {17096,17101,17007 ,6298,6671,6679 ,0,0,0}, {17101,17102,17009 ,6671,6671,6671 ,0,0,0}, + {18775,18787,17009 ,6671,6672,6671 ,0,0,0}, {18725,18795,18787 ,6681,6671,6672 ,0,0,0}, + {18724,18723,18786 ,6671,6672,6681 ,0,0,0}, {18724,18786,18795 ,6671,6681,6671 ,0,0,0}, + {18723,18727,18785 ,6672,6672,6672 ,0,0,0}, {18727,18774,18791 ,6672,6671,6672 ,0,0,0}, + {18774,18726,18790 ,6671,6672,6672 ,0,0,0}, {18726,18731,18789 ,6672,6672,6672 ,0,0,0}, + {18731,18730,18788 ,6672,6672,6672 ,0,0,0}, {18729,18792,18788 ,6681,6671,6672 ,0,0,0}, + {18728,18776,18792 ,6672,6671,6671 ,0,0,0}, {18733,18773,18794 ,6671,6672,6672 ,0,0,0}, + {18733,18794,18776 ,6671,6672,6671 ,0,0,0}, {18773,18732,18793 ,6672,6671,6671 ,0,0,0}, + {18732,18772,18796 ,6671,6672,6681 ,0,0,0}, {18772,18736,18784 ,6672,6672,6672 ,0,0,0}, + {18736,18735,18783 ,6672,6672,6672 ,0,0,0}, {18735,18734,18797 ,6672,6672,6671 ,0,0,0}, + {18739,18782,18797 ,6671,6680,6671 ,0,0,0}, {18738,18779,18782 ,6672,6671,6680 ,0,0,0}, + {18737,18743,18798 ,6671,6671,6672 ,0,0,0}, {18737,18798,18779 ,6671,6672,6671 ,0,0,0}, + {18743,18742,18781 ,6671,6671,6671 ,0,0,0}, {18742,18741,18780 ,6671,6672,6672 ,0,0,0}, + {18741,18740,18799 ,6672,6671,6672 ,0,0,0}, {18740,18746,18778 ,6671,6672,6298 ,0,0,0}, + {18746,18744,18777 ,6672,6687,6324 ,0,0,0}, {18745,18800,18777 ,6686,6685,6324 ,0,0,0}, + {18748,18801,18800 ,6671,6688,6685 ,0,0,0}, {18747,18751,18804 ,6688,6690,6686 ,0,0,0}, + {18747,18804,18801 ,6688,6686,6688 ,0,0,0}, {18751,18750,18803 ,6690,6671,6690 ,0,0,0}, + {18750,18749,18802 ,6671,6691,6672 ,0,0,0}, {18749,18753,18805 ,6691,6686,6691 ,0,0,0}, + {18753,18752,18806 ,6686,6690,6690 ,0,0,0}, {18752,18756,18807 ,6690,6672,6691 ,0,0,0}, + {18755,18809,18807 ,6688,6688,6691 ,0,0,0}, {18758,18808,18754 ,6688,6672,6688 ,0,0,0}, + {18757,18821,18810 ,6691,6691,6701 ,0,0,0}, {18758,18810,18808 ,6688,6701,6672 ,0,0,0}, + {18811,18821,18759 ,6686,6691,6672 ,0,0,0}, {18757,18759,18821 ,6691,6672,6691 ,0,0,0}, + {18811,18760,18813 ,6686,6671,6671 ,0,0,0}, {18812,18761,18762 ,6671,6672,6704 ,0,0,0}, + {18813,18760,18761 ,6671,6671,6672 ,0,0,0}, {18814,18763,18764 ,6686,6672,6672 ,0,0,0}, + {18814,18812,18762 ,6686,6671,6704 ,0,0,0}, {18822,18815,18765 ,6688,6706,6686 ,0,0,0}, + {18815,18814,18764 ,6706,6686,6672 ,0,0,0}, {18822,18766,18820 ,6688,6691,6706 ,0,0,0}, + {18766,18822,18765 ,6691,6688,6686 ,0,0,0}, {18767,18819,18820 ,6723,6688,6706 ,0,0,0}, + {18769,18768,18818 ,6686,6671,6722 ,0,0,0}, {18767,18769,18819 ,6723,6686,6688 ,0,0,0}, + {18816,18770,18817 ,6690,6701,6686 ,0,0,0}, {18818,18768,18816 ,6722,6671,6690 ,0,0,0}, + {16938,18771,17155 ,6690,6690,6671 ,0,0,0}, {18817,18770,18771 ,6686,6701,6690 ,0,0,0}, + {18817,16515,18319 ,6724,6725,6726 ,0,0,0}, {18281,18818,18816 ,6727,6728,6729 ,0,0,0}, + {18820,18283,18822 ,6730,6731,6732 ,0,0,0}, {18424,18819,18422 ,6733,6734,6735 ,0,0,0}, + {18823,18433,18824 ,6736,6737,6738 ,0,0,0}, {18308,18823,18825 ,6739,6736,6736 ,0,0,0}, + {18349,18826,18827 ,6740,6741,6742 ,0,0,0}, {18348,18828,18307 ,6743,6744,6745 ,0,0,0}, + {18431,18829,18830 ,6746,6747,6748 ,0,0,0}, {18478,18831,18436 ,6749,6750,6751 ,0,0,0}, + {18832,18833,18476 ,6752,6753,6754 ,0,0,0}, {18829,18364,18477 ,6747,6755,6756 ,0,0,0}, + {18799,18400,18391 ,6757,6758,6759 ,0,0,0}, {16802,18400,18832 ,6760,6758,6752 ,0,0,0}, + {18781,18393,18798 ,6761,6762,6763 ,0,0,0}, {18392,18781,18780 ,6764,6761,6765 ,0,0,0}, + {18463,18398,18782 ,6766,6767,6768 ,0,0,0}, {18463,18779,18462 ,6766,6769,6770 ,0,0,0}, + {18797,18390,18783 ,6771,6772,6773 ,0,0,0}, {18390,18797,18398 ,6772,6771,6767 ,0,0,0}, + {18784,18783,18367 ,6774,6773,6775 ,0,0,0}, {18390,18367,18783 ,6772,6775,6773 ,0,0,0}, + {18365,18796,18366 ,6776,6777,6778 ,0,0,0}, {18784,18367,18366 ,6774,6775,6778 ,0,0,0}, + {18371,18794,18389 ,6779,6780,6781 ,0,0,0}, {18793,18365,18389 ,6782,6776,6781 ,0,0,0}, + {18370,18792,18776 ,6783,6784,6785 ,0,0,0}, {18789,18788,18834 ,6786,6787,6788 ,0,0,0}, + {18834,18388,18835 ,6788,6789,6788 ,0,0,0}, {18788,18792,18388 ,6787,6784,6789 ,0,0,0}, + {18836,18369,18342 ,6790,6791,6792 ,0,0,0}, {18369,18836,18835 ,6791,6790,6788 ,0,0,0}, + {18341,18837,18342 ,6793,6794,6792 ,0,0,0}, {18836,18342,18837 ,6790,6792,6794 ,0,0,0}, + {18341,18374,18838 ,6793,6795,6796 ,0,0,0}, {18838,18837,18341 ,6796,6794,6793 ,0,0,0}, + {18839,18374,18380 ,6797,6795,6798 ,0,0,0}, {18374,18839,18838 ,6795,6797,6796 ,0,0,0}, + {18384,18840,18380 ,6799,6800,6798 ,0,0,0}, {18839,18380,18840 ,6797,6798,6800 ,0,0,0}, + {18384,18377,18841 ,6799,6801,6802 ,0,0,0}, {18841,18840,18384 ,6802,6800,6799 ,0,0,0}, + {18842,18377,18386 ,6803,6801,6804 ,0,0,0}, {18377,18842,18841 ,6801,6803,6802 ,0,0,0}, + {16616,17019,18386 ,6805,6806,6804 ,0,0,0}, {18842,18386,17019 ,6803,6804,6806 ,0,0,0}, + {18786,18843,18844 ,6807,6808,6809 ,0,0,0}, {18788,18388,18834 ,6787,6789,6788 ,0,0,0}, + {18835,18388,18369 ,6788,6789,6791 ,0,0,0}, {18370,18388,18792 ,6783,6789,6784 ,0,0,0}, + {18371,18370,18776 ,6779,6783,6785 ,0,0,0}, {18776,18794,18371 ,6785,6780,6779 ,0,0,0}, + {18389,18794,18793 ,6781,6780,6782 ,0,0,0}, {18365,18793,18796 ,6776,6782,6777 ,0,0,0}, + {18796,18784,18366 ,6777,6774,6778 ,0,0,0}, {18834,18845,18789 ,6788,6810,6786 ,0,0,0}, + {18843,18786,18785 ,6808,6807,6811 ,0,0,0}, {18845,18790,18789 ,6810,6812,6786 ,0,0,0}, + {18844,18846,18795 ,6809,6813,6814 ,0,0,0}, {18795,18786,18844 ,6814,6807,6809 ,0,0,0}, + {18795,18847,18787 ,6814,6815,6816 ,0,0,0}, {18847,18795,18846 ,6815,6814,6813 ,0,0,0}, + {17009,18787,17010 ,6817,6816,6818 ,0,0,0}, {18847,17010,18787 ,6815,6818,6816 ,0,0,0}, + {18785,18848,18843 ,6811,6819,6808 ,0,0,0}, {18398,18797,18782 ,6767,6771,6768 ,0,0,0}, + {18848,18785,18791 ,6819,6811,6820 ,0,0,0}, {18849,18848,18791 ,6821,6819,6820 ,0,0,0}, + {18790,18845,18849 ,6812,6810,6821 ,0,0,0}, {18790,18849,18791 ,6812,6821,6820 ,0,0,0}, + {18782,18779,18463 ,6768,6769,6766 ,0,0,0}, {18429,18830,18831 ,6822,6748,6750 ,0,0,0}, + {18462,18798,18393 ,6770,6763,6762 ,0,0,0}, {18798,18462,18779 ,6763,6770,6769 ,0,0,0}, + {18781,18392,18393 ,6761,6764,6762 ,0,0,0}, {18391,18392,18780 ,6759,6764,6765 ,0,0,0}, + {18778,18400,18799 ,6823,6758,6757 ,0,0,0}, {18780,18799,18391 ,6765,6757,6759 ,0,0,0}, + {16802,18832,18476 ,6760,6752,6754 ,0,0,0}, {18778,18832,18400 ,6823,6752,6758 ,0,0,0}, + {18829,18431,18364 ,6747,6746,6755 ,0,0,0}, {18833,18829,18477 ,6753,6747,6756 ,0,0,0}, + {18831,18478,18429 ,6750,6749,6822 ,0,0,0}, {18850,18428,18851 ,6824,6825,6826 ,0,0,0}, + {18831,18851,18436 ,6750,6826,6751 ,0,0,0}, {18850,18826,18358 ,6824,6741,6827 ,0,0,0}, + {18428,18850,18358 ,6825,6824,6827 ,0,0,0}, {18827,18828,18348 ,6742,6744,6743 ,0,0,0}, + {18358,18826,18340 ,6827,6741,6828 ,0,0,0}, {18821,18811,18852 ,6829,6830,6831 ,0,0,0}, + {18812,18814,18825 ,6832,6833,6736 ,0,0,0}, {18828,18824,18427 ,6744,6738,6834 ,0,0,0}, + {18816,18319,18281 ,6729,6726,6727 ,0,0,0}, {18820,18819,18424 ,6730,6734,6733 ,0,0,0}, + {18284,18308,18815 ,6835,6739,6836 ,0,0,0}, {18442,18823,18308 ,6837,6736,6739 ,0,0,0}, + {18822,18284,18815 ,6732,6835,6836 ,0,0,0}, {18424,18283,18820 ,6733,6731,6730 ,0,0,0}, + {18822,18283,18284 ,6732,6731,6835 ,0,0,0}, {18818,18422,18819 ,6728,6735,6734 ,0,0,0}, + {18422,18818,18281 ,6735,6728,6727 ,0,0,0}, {18319,18816,18817 ,6726,6729,6724 ,0,0,0}, + {16515,18817,16938 ,6725,6724,6838 ,0,0,0}, {18800,18853,18777 ,6839,6840,6841 ,0,0,0}, + {18778,18777,18853 ,6823,6841,6840 ,0,0,0}, {18853,18800,18854 ,6840,6839,6842 ,0,0,0}, + {18778,18853,18832 ,6823,6840,6752 ,0,0,0}, {18855,18854,18801 ,6843,6842,6844 ,0,0,0}, + {18477,18476,18833 ,6756,6754,6753 ,0,0,0}, {18803,18855,18804 ,6845,6843,6846 ,0,0,0}, + {18803,18856,18855 ,6845,6847,6843 ,0,0,0}, {18857,18856,18802 ,6848,6847,6849 ,0,0,0}, + {18429,18431,18830 ,6822,6746,6748 ,0,0,0}, {18806,18857,18805 ,6850,6848,6851 ,0,0,0}, + {18806,18858,18857 ,6850,6852,6848 ,0,0,0}, {18859,18858,18807 ,6853,6852,6854 ,0,0,0}, + {18428,18436,18851 ,6825,6751,6826 ,0,0,0}, {18809,18860,18859 ,6855,6856,6853 ,0,0,0}, + {18808,18860,18809 ,6857,6856,6855 ,0,0,0}, {18861,18860,18810 ,6858,6856,6859 ,0,0,0}, + {18349,18340,18826 ,6740,6828,6741 ,0,0,0}, {18852,18861,18821 ,6831,6858,6829 ,0,0,0}, + {18348,18349,18827 ,6743,6740,6742 ,0,0,0}, {18862,18852,18813 ,6860,6831,6861 ,0,0,0}, + {18427,18307,18828 ,6834,6745,6744 ,0,0,0}, {18825,18862,18812 ,6736,6860,6832 ,0,0,0}, + {18433,18427,18824 ,6737,6834,6738 ,0,0,0}, {18815,18308,18825 ,6836,6739,6736 ,0,0,0}, + {18433,18823,18442 ,6737,6736,6837 ,0,0,0}, {18815,18825,18814 ,6836,6736,6833 ,0,0,0}, + {18813,18812,18862 ,6861,6832,6860 ,0,0,0}, {18811,18813,18852 ,6830,6861,6831 ,0,0,0}, + {18810,18821,18861 ,6859,6829,6858 ,0,0,0}, {18808,18810,18860 ,6857,6859,6856 ,0,0,0}, + {18807,18809,18859 ,6854,6855,6853 ,0,0,0}, {18806,18807,18858 ,6850,6854,6852 ,0,0,0}, + {18802,18805,18857 ,6849,6851,6848 ,0,0,0}, {18803,18802,18856 ,6845,6849,6847 ,0,0,0}, + {18801,18804,18855 ,6844,6846,6843 ,0,0,0}, {18800,18801,18854 ,6839,6844,6842 ,0,0,0}, + {18863,16810,16811 ,6862,6863,6864 ,0,0,0}, {18515,18504,17742 ,6865,6866,6867 ,0,0,0}, + {18864,18512,18511 ,6868,6869,6870 ,0,0,0}, {18514,17735,18501 ,6871,6872,6873 ,0,0,0}, + {17720,18494,18498 ,6874,6875,6876 ,0,0,0}, {17732,18517,18518 ,6877,6878,6879 ,0,0,0}, + {18528,17727,17726 ,6880,6881,6882 ,0,0,0}, {18525,17719,17722 ,6883,6884,6885 ,0,0,0}, + {18865,18538,18536 ,6886,6887,6888 ,0,0,0}, {18866,18532,17729 ,6889,6890,5525 ,0,0,0}, + {18549,18546,17805 ,6891,6892,6893 ,0,0,0}, {18542,18867,18868 ,6894,6895,6896 ,0,0,0}, + {18556,17794,18610 ,6897,6898,6899 ,0,0,0}, {18552,17800,18555 ,6900,6901,6902 ,0,0,0}, + {17841,18561,17839 ,6903,6904,6905 ,0,0,0}, {18604,18557,17837 ,6906,6907,6908 ,0,0,0}, + {18593,18869,18595 ,6909,6910,6911 ,0,0,0}, {18601,17842,18567 ,6912,6913,6914 ,0,0,0}, + {18870,18582,18574 ,6915,6916,6917 ,0,0,0}, {18592,18871,18579 ,6918,6919,6920 ,0,0,0}, + {18872,18589,18590 ,6921,6922,6923 ,0,0,0}, {17898,17901,18583 ,6924,6925,6926 ,0,0,0}, + {17898,18586,17899 ,6924,6927,5712 ,0,0,0}, {17886,17885,18576 ,6928,6929,6930 ,0,0,0}, + {17886,18591,17901 ,6928,6931,6925 ,0,0,0}, {18596,18598,17885 ,6932,6933,6929 ,0,0,0}, + {17885,18598,18576 ,6929,6933,6930 ,0,0,0}, {18596,17885,17930 ,6932,6929,6934 ,0,0,0}, + {17930,17932,18570 ,6934,6935,6936 ,0,0,0}, {18570,18596,17930 ,6936,6932,6934 ,0,0,0}, + {18602,17932,17934 ,6937,6935,6938 ,0,0,0}, {17932,18602,18570 ,6935,6937,6936 ,0,0,0}, + {18602,17934,18563 ,6937,6938,6939 ,0,0,0}, {17935,18564,18563 ,6940,6941,6939 ,0,0,0}, + {18563,17934,17935 ,6939,6938,6940 ,0,0,0}, {18564,17937,18608 ,6941,6942,6943 ,0,0,0}, + {17937,18564,17935 ,6942,6941,6940 ,0,0,0}, {18558,18608,17938 ,6944,6943,6945 ,0,0,0}, + {17937,17938,18608 ,6942,6945,6943 ,0,0,0}, {17938,18873,18553 ,6945,6946,6947 ,0,0,0}, + {18553,18558,17938 ,6947,6944,6945 ,0,0,0}, {18550,18873,18874 ,6948,6946,6949 ,0,0,0}, + {18873,18550,18553 ,6946,6948,6947 ,0,0,0}, {18875,18547,18874 ,6950,6951,6949 ,0,0,0}, + {18550,18874,18547 ,6948,6949,6951 ,0,0,0}, {18875,16908,16906 ,6950,126,3135 ,0,0,0}, + {16906,18547,18875 ,3135,6951,6950 ,0,0,0}, {17901,18591,18583 ,6925,6931,6926 ,0,0,0}, + {17886,18576,18591 ,6928,6930,6931 ,0,0,0}, {18586,18579,17899 ,6927,6920,5712 ,0,0,0}, + {17898,18583,18586 ,6924,6926,6927 ,0,0,0}, {18871,18592,18589 ,6919,6918,6922 ,0,0,0}, + {18871,17899,18579 ,6919,5712,6920 ,0,0,0}, {18872,18590,18582 ,6921,6923,6916 ,0,0,0}, + {18872,18871,18589 ,6921,6919,6922 ,0,0,0}, {18869,18870,18574 ,6910,6915,6917 ,0,0,0}, + {18870,18872,18582 ,6915,6921,6916 ,0,0,0}, {17844,18869,18593 ,6952,6910,6909 ,0,0,0}, + {18595,18869,18574 ,6911,6910,6917 ,0,0,0}, {17844,18567,17842 ,6952,6914,6913 ,0,0,0}, + {18567,17844,18593 ,6914,6952,6909 ,0,0,0}, {18599,17841,17842 ,6953,6903,6913 ,0,0,0}, + {18599,17842,18601 ,6953,6913,6912 ,0,0,0}, {18561,18606,17839 ,6904,6954,6905 ,0,0,0}, + {18599,18561,17841 ,6953,6904,6903 ,0,0,0}, {18604,17837,18606 ,6906,6908,6954 ,0,0,0}, + {17839,18606,17837 ,6905,6954,6908 ,0,0,0}, {17796,18557,18610 ,6955,6907,6899 ,0,0,0}, + {17837,18557,17796 ,6908,6907,6955 ,0,0,0}, {17806,17794,18556 ,6956,6898,6897 ,0,0,0}, + {17794,17796,18610 ,6898,6955,6899 ,0,0,0}, {17806,18555,17800 ,6956,6902,6901 ,0,0,0}, + {18555,17806,18556 ,6902,6956,6897 ,0,0,0}, {18549,17805,17800 ,6891,6893,6901 ,0,0,0}, + {18549,17800,18552 ,6891,6901,6900 ,0,0,0}, {18546,18544,18868 ,6892,6957,6896 ,0,0,0}, + {18546,18868,17805 ,6892,6896,6893 ,0,0,0}, {18542,18540,18867 ,6894,6958,6895 ,0,0,0}, + {18544,18542,18868 ,6957,6894,6896 ,0,0,0}, {18538,18865,18540 ,6887,6886,6958 ,0,0,0}, + {18867,18540,18865 ,6895,6958,6886 ,0,0,0}, {18866,18536,18534 ,6889,6888,6959 ,0,0,0}, + {18865,18536,18866 ,6886,6888,6889 ,0,0,0}, {17729,18532,18530 ,5525,6890,6960 ,0,0,0}, + {18866,18534,18532 ,6889,6959,6890 ,0,0,0}, {18530,18528,17726 ,6960,6880,6882 ,0,0,0}, + {17726,17729,18530 ,6882,5525,6960 ,0,0,0}, {18495,17722,17727 ,6961,6885,6881 ,0,0,0}, + {18495,17727,18528 ,6961,6881,6880 ,0,0,0}, {18525,18521,17719 ,6883,6962,6884 ,0,0,0}, + {18495,18525,17722 ,6961,6883,6885 ,0,0,0}, {17720,17719,18494 ,6874,6884,6875 ,0,0,0}, + {18521,18494,17719 ,6962,6875,6884 ,0,0,0}, {17725,18498,18517 ,6963,6876,6878 ,0,0,0}, + {17720,18498,17725 ,6874,6876,6963 ,0,0,0}, {17734,17732,18518 ,6964,6877,6879 ,0,0,0}, + {17732,17725,18517 ,6877,6963,6878 ,0,0,0}, {17734,18501,17735 ,6964,6873,6872 ,0,0,0}, + {18501,17734,18518 ,6873,6964,6879 ,0,0,0}, {18514,18515,17742 ,6871,6865,6867 ,0,0,0}, + {18514,17742,17735 ,6871,6867,6872 ,0,0,0}, {18504,18512,18876 ,6866,6869,6965 ,0,0,0}, + {18504,18876,17742 ,6866,6965,6867 ,0,0,0}, {18864,18511,18863 ,6868,6870,6862 ,0,0,0}, + {18876,18512,18864 ,6965,6869,6868 ,0,0,0}, {16810,18863,18511 ,6863,6862,6870 ,0,0,0}, + {16780,18877,18438 ,6966,6967,6968 ,0,0,0}, {18878,18482,18879 ,6969,6970,6971 ,0,0,0}, + {18350,18351,18880 ,6972,6973,6974 ,0,0,0}, {18484,18881,18485 ,6975,6976,6977 ,0,0,0}, + {18882,18883,18426 ,6978,6979,6980 ,0,0,0}, {18884,18481,18885 ,6981,6982,6983 ,0,0,0}, + {18483,18437,18886 ,6984,6985,6986 ,0,0,0}, {18488,18887,18888 ,6987,6988,6989 ,0,0,0}, + {18479,18889,18480 ,6990,6991,6992 ,0,0,0}, {18489,18890,18362 ,6993,6994,6995 ,0,0,0}, + {18891,18489,18430 ,6996,6993,6997 ,0,0,0}, {18363,18892,18490 ,6998,6999,7000 ,0,0,0}, + {18893,18363,18362 ,7001,6998,6995 ,0,0,0}, {18491,18490,18894 ,7002,7000,7003 ,0,0,0}, + {18892,18894,18490 ,6999,7003,7000 ,0,0,0}, {18895,18475,18491 ,7004,7005,7002 ,0,0,0}, + {18491,18894,18895 ,7002,7003,7004 ,0,0,0}, {18475,18896,18493 ,7005,7006,7007 ,0,0,0}, + {18896,18475,18895 ,7006,7005,7004 ,0,0,0}, {18492,18493,18897 ,7008,7007,7009 ,0,0,0}, + {18896,18897,18493 ,7006,7009,7007 ,0,0,0}, {18898,16802,18492 ,7010,82,7008 ,0,0,0}, + {18492,18897,18898 ,7008,7009,7010 ,0,0,0}, {16801,16802,18898 ,7011,82,7010 ,0,0,0}, + {18430,18888,18891 ,6997,6989,6996 ,0,0,0}, {18890,18893,18362 ,6994,7001,6995 ,0,0,0}, + {18893,18892,18363 ,7001,6999,6998 ,0,0,0}, {18890,18489,18891 ,6994,6993,6996 ,0,0,0}, + {18887,18488,18480 ,6988,6987,6992 ,0,0,0}, {18888,18430,18488 ,6989,6997,6987 ,0,0,0}, + {18480,18889,18887 ,6992,6991,6988 ,0,0,0}, {18884,18889,18479 ,6981,6991,6990 ,0,0,0}, + {18899,18485,18881 ,7012,6977,6976 ,0,0,0}, {18483,18885,18481 ,6984,6983,6982 ,0,0,0}, + {18479,18481,18884 ,6990,6982,6981 ,0,0,0}, {18437,18485,18899 ,6985,6977,7012 ,0,0,0}, + {18437,18899,18886 ,6985,7012,6986 ,0,0,0}, {18885,18483,18886 ,6983,6984,6986 ,0,0,0}, + {18482,18350,18879 ,6970,6972,6971 ,0,0,0}, {18881,18484,18883 ,6976,6975,6979 ,0,0,0}, + {18882,18426,18425 ,6978,6980,7013 ,0,0,0}, {18426,18883,18484 ,6980,6979,6975 ,0,0,0}, + {18425,18482,18878 ,7013,6970,6969 ,0,0,0}, {18425,18878,18882 ,7013,6969,6978 ,0,0,0}, + {18351,18877,18880 ,6973,6967,6974 ,0,0,0}, {18879,18350,18880 ,6971,6972,6974 ,0,0,0}, + {16780,18438,16777 ,6966,6968,7014 ,0,0,0}, {18877,18351,18438 ,6967,6973,6968 ,0,0,0}, + {18899,16795,18886 ,730,730,730 ,0,0,0}, {18894,18892,18890 ,730,730,730 ,0,0,0}, + {18892,18893,18890 ,730,730,730 ,0,0,0}, {18890,18891,18895 ,730,730,730 ,0,0,0}, + {18895,18894,18890 ,730,730,730 ,0,0,0}, {18896,18891,18888 ,730,730,730 ,0,0,0}, + {18891,18896,18895 ,730,730,730 ,0,0,0}, {18887,18897,18888 ,730,730,730 ,0,0,0}, + {18896,18888,18897 ,730,730,730 ,0,0,0}, {18898,18887,16801 ,730,730,730 ,0,0,0}, + {18898,18897,18887 ,730,730,730 ,0,0,0}, {18889,18884,16799 ,730,730,730 ,0,0,0}, + {18887,18889,16801 ,730,730,730 ,0,0,0}, {18881,16790,16793 ,730,730,7015 ,0,0,0}, + {16796,16799,18885 ,730,730,730 ,0,0,0}, {18878,16784,16787 ,7016,7015,7017 ,0,0,0}, + {18883,16787,16789 ,730,7017,7017 ,0,0,0}, {16781,16783,18880 ,730,730,730 ,0,0,0}, + {16780,16756,16758 ,730,730,730 ,0,0,0}, {16754,16781,18877 ,7015,730,730 ,0,0,0}, + {16760,16774,16772 ,730,730,7017 ,0,0,0}, {16756,16775,16762 ,730,7017,7015 ,0,0,0}, + {16768,16764,16769 ,730,730,730 ,0,0,0}, {16764,16772,16769 ,730,7017,730 ,0,0,0}, + {16765,16764,16768 ,730,730,730 ,0,0,0}, {16760,16762,16774 ,730,7015,730 ,0,0,0}, + {16764,16760,16772 ,730,730,7017 ,0,0,0}, {16775,16756,16779 ,7017,730,730 ,0,0,0}, + {16774,16762,16775 ,730,7015,7017 ,0,0,0}, {16780,16779,16756 ,730,730,730 ,0,0,0}, + {18877,16758,16754 ,730,730,7015 ,0,0,0}, {18877,16780,16758 ,730,730,730 ,0,0,0}, + {16783,18879,18880 ,730,7016,730 ,0,0,0}, {18880,18877,16781 ,730,730,730 ,0,0,0}, + {18878,18879,16784 ,7016,7016,7015 ,0,0,0}, {16783,16784,18879 ,730,7015,7016 ,0,0,0}, + {16787,18883,18882 ,7017,730,730 ,0,0,0}, {16787,18882,18878 ,7017,730,7016 ,0,0,0}, + {16789,16790,18881 ,7017,730,730 ,0,0,0}, {18883,16789,18881 ,730,7017,730 ,0,0,0}, + {16793,16795,18899 ,7015,730,730 ,0,0,0}, {18881,16793,18899 ,730,7015,730 ,0,0,0}, + {18886,16796,18885 ,730,730,730 ,0,0,0}, {18886,16795,16796 ,730,730,730 ,0,0,0}, + {18889,16799,16801 ,730,730,730 ,0,0,0}, {18884,18885,16799 ,730,730,730 ,0,0,0}, + {18900,18901,16752 ,7018,7019,7020 ,0,0,0}, {16752,18902,18900 ,7020,7021,7018 ,0,0,0}, + {16752,16735,18902 ,7020,7022,7021 ,0,0,0}, {16752,18903,18904 ,7020,7023,7024 ,0,0,0}, + {18901,18903,16752 ,7019,7023,7020 ,0,0,0}, {16752,18905,18906 ,7020,7025,7026 ,0,0,0}, + {18904,18905,16752 ,7024,7025,7020 ,0,0,0}, {18906,18907,16752 ,7026,7027,7020 ,0,0,0}, + {18908,16752,18909 ,7028,7020,7029 ,0,0,0}, {16752,18907,18909 ,7020,7027,7029 ,0,0,0}, + {18910,16752,18911 ,7030,7020,7031 ,0,0,0}, {16752,18908,18911 ,7020,7028,7031 ,0,0,0}, + {18912,16752,18913 ,7032,7020,7033 ,0,0,0}, {16752,18910,18913 ,7020,7030,7033 ,0,0,0}, + {16751,16752,18912 ,7034,7020,7032 ,0,0,0}, {16734,18407,18902 ,7035,7036,7037 ,0,0,0}, + {18904,18903,18397 ,7038,7039,7040 ,0,0,0}, {18901,18900,18406 ,7041,7042,7043 ,0,0,0}, + {18906,18464,18907 ,7044,7045,7046 ,0,0,0}, {18396,18409,18905 ,7047,7048,7049 ,0,0,0}, + {18465,18290,18908 ,7050,7051,7052 ,0,0,0}, {18465,18909,18356 ,7050,7053,7054 ,0,0,0}, + {18354,18413,18910 ,7055,7056,7057 ,0,0,0}, {18910,18911,18354 ,7057,7058,7055 ,0,0,0}, + {18913,18413,18399 ,7059,7056,7060 ,0,0,0}, {18413,18913,18910 ,7056,7059,7057 ,0,0,0}, + {18387,18912,18399 ,7061,7062,7060 ,0,0,0}, {18913,18399,18912 ,7059,7060,7062 ,0,0,0}, + {18387,16750,16751 ,7061,7063,4910 ,0,0,0}, {16751,18912,18387 ,4910,7062,7061 ,0,0,0}, + {18464,18906,18409 ,7045,7044,7048 ,0,0,0}, {18290,18911,18908 ,7051,7058,7052 ,0,0,0}, + {18354,18911,18290 ,7055,7058,7051 ,0,0,0}, {18397,18903,18405 ,7040,7039,7064 ,0,0,0}, + {18356,18909,18907 ,7054,7053,7046 ,0,0,0}, {18465,18908,18909 ,7050,7052,7053 ,0,0,0}, + {18464,18356,18907 ,7045,7054,7046 ,0,0,0}, {18905,18409,18906 ,7049,7048,7044 ,0,0,0}, + {18904,18397,18396 ,7038,7040,7047 ,0,0,0}, {18396,18905,18904 ,7047,7049,7038 ,0,0,0}, + {18900,18407,18406 ,7042,7036,7043 ,0,0,0}, {18405,18901,18406 ,7064,7041,7043 ,0,0,0}, + {18903,18901,18405 ,7039,7041,7064 ,0,0,0}, {16734,18902,16735 ,7035,7037,4929 ,0,0,0}, + {18407,18900,18902 ,7036,7042,7037 ,0,0,0}, {18914,18915,16718 ,7018,7019,7065 ,0,0,0}, + {16718,18916,18914 ,7065,7021,7018 ,0,0,0}, {16718,16701,18916 ,7065,7066,7021 ,0,0,0}, + {16718,18917,18918 ,7065,7023,7024 ,0,0,0}, {18915,18917,16718 ,7019,7023,7065 ,0,0,0}, + {16718,18919,18920 ,7065,7025,7026 ,0,0,0}, {18918,18919,16718 ,7024,7025,7065 ,0,0,0}, + {18920,18921,16718 ,7026,7027,7065 ,0,0,0}, {18922,16718,18923 ,7028,7065,7029 ,0,0,0}, + {16718,18921,18923 ,7065,7027,7029 ,0,0,0}, {18924,16718,18925 ,7030,7065,7031 ,0,0,0}, + {16718,18922,18925 ,7065,7028,7031 ,0,0,0}, {18926,16718,18927 ,7032,7065,7033 ,0,0,0}, + {16718,18924,18927 ,7065,7030,7033 ,0,0,0}, {16717,16718,18926 ,7067,7065,7032 ,0,0,0}, + {16700,18456,18916 ,7068,7069,7070 ,0,0,0}, {18918,18917,18297 ,7071,7072,7073 ,0,0,0}, + {18915,18914,18336 ,7074,7075,7076 ,0,0,0}, {18920,18316,18921 ,7077,7078,7079 ,0,0,0}, + {18298,18461,18919 ,7047,7080,7081 ,0,0,0}, {18280,18459,18922 ,7082,7083,7084 ,0,0,0}, + {18280,18923,18460 ,7082,7085,7086 ,0,0,0}, {18458,18334,18924 ,7087,7088,7089 ,0,0,0}, + {18924,18925,18458 ,7089,7090,7087 ,0,0,0}, {18927,18334,18335 ,7091,7088,7092 ,0,0,0}, + {18334,18927,18924 ,7088,7091,7089 ,0,0,0}, {18457,18926,18335 ,7093,7094,7092 ,0,0,0}, + {18927,18335,18926 ,7091,7092,7094 ,0,0,0}, {18457,16716,16717 ,7093,4831,4942 ,0,0,0}, + {16717,18926,18457 ,4942,7094,7093 ,0,0,0}, {18316,18920,18461 ,7078,7077,7080 ,0,0,0}, + {18459,18925,18922 ,7083,7090,7084 ,0,0,0}, {18458,18925,18459 ,7087,7090,7083 ,0,0,0}, + {18297,18917,18333 ,7073,7072,7095 ,0,0,0}, {18460,18923,18921 ,7086,7085,7079 ,0,0,0}, + {18280,18922,18923 ,7082,7084,7085 ,0,0,0}, {18316,18460,18921 ,7078,7086,7079 ,0,0,0}, + {18919,18461,18920 ,7081,7080,7077 ,0,0,0}, {18918,18297,18298 ,7071,7073,7047 ,0,0,0}, + {18298,18919,18918 ,7047,7081,7071 ,0,0,0}, {18914,18456,18336 ,7075,7069,7076 ,0,0,0}, + {18333,18915,18336 ,7095,7074,7076 ,0,0,0}, {18917,18915,18333 ,7072,7074,7095 ,0,0,0}, + {16700,18916,16701 ,7068,7070,4899 ,0,0,0}, {18456,18914,18916 ,7069,7075,7070 ,0,0,0}, + {18928,18929,16684 ,7018,7019,7065 ,0,0,0}, {16684,18930,18928 ,7065,7021,7018 ,0,0,0}, + {16684,16667,18930 ,7065,7096,7021 ,0,0,0}, {16684,18931,18932 ,7065,7023,7024 ,0,0,0}, + {18929,18931,16684 ,7019,7023,7065 ,0,0,0}, {16684,18933,18934 ,7065,7025,7026 ,0,0,0}, + {18932,18933,16684 ,7024,7025,7065 ,0,0,0}, {18934,18935,16684 ,7026,7027,7065 ,0,0,0}, + {18936,16684,18937 ,7028,7065,7029 ,0,0,0}, {16684,18935,18937 ,7065,7027,7029 ,0,0,0}, + {18938,16684,18939 ,7030,7065,7031 ,0,0,0}, {16684,18936,18939 ,7065,7028,7031 ,0,0,0}, + {18940,16684,18941 ,7032,7065,7033 ,0,0,0}, {16684,18938,18941 ,7065,7030,7033 ,0,0,0}, + {16683,16684,18940 ,7097,7065,7032 ,0,0,0}, {16666,18454,18930 ,7098,7099,7100 ,0,0,0}, + {18932,18931,18419 ,7101,7102,7103 ,0,0,0}, {18929,18928,18446 ,7104,7105,7076 ,0,0,0}, + {18934,18418,18935 ,7106,7107,7108 ,0,0,0}, {18453,18452,18933 ,7109,7110,7111 ,0,0,0}, + {18330,18327,18936 ,7112,7113,7114 ,0,0,0}, {18330,18937,18447 ,7112,7115,7116 ,0,0,0}, + {18332,18331,18938 ,7117,7118,7119 ,0,0,0}, {18938,18939,18332 ,7119,7120,7117 ,0,0,0}, + {18941,18331,18329 ,7121,7118,7122 ,0,0,0}, {18331,18941,18938 ,7118,7121,7119 ,0,0,0}, + {18328,18940,18329 ,7123,7124,7122 ,0,0,0}, {18941,18329,18940 ,7121,7122,7124 ,0,0,0}, + {18328,16682,16683 ,7123,4831,4831 ,0,0,0}, {16683,18940,18328 ,4831,7124,7123 ,0,0,0}, + {18418,18934,18452 ,7107,7106,7110 ,0,0,0}, {18327,18939,18936 ,7113,7120,7114 ,0,0,0}, + {18332,18939,18327 ,7117,7120,7113 ,0,0,0}, {18419,18931,18445 ,7103,7102,7125 ,0,0,0}, + {18447,18937,18935 ,7116,7115,7108 ,0,0,0}, {18330,18936,18937 ,7112,7114,7115 ,0,0,0}, + {18418,18447,18935 ,7107,7116,7108 ,0,0,0}, {18933,18452,18934 ,7111,7110,7106 ,0,0,0}, + {18932,18419,18453 ,7101,7103,7109 ,0,0,0}, {18453,18933,18932 ,7109,7111,7101 ,0,0,0}, + {18928,18454,18446 ,7105,7099,7076 ,0,0,0}, {18445,18929,18446 ,7125,7104,7076 ,0,0,0}, + {18931,18929,18445 ,7102,7104,7125 ,0,0,0}, {16666,18930,16667 ,7098,7100,4865 ,0,0,0}, + {18454,18928,18930 ,7099,7105,7100 ,0,0,0}, {18942,18943,16650 ,7018,7019,7126 ,0,0,0}, + {16650,18944,18942 ,7126,7021,7018 ,0,0,0}, {16650,16633,18944 ,7126,7127,7021 ,0,0,0}, + {16650,18945,18946 ,7126,7023,7024 ,0,0,0}, {18943,18945,16650 ,7019,7023,7126 ,0,0,0}, + {16650,18947,18948 ,7126,7025,7026 ,0,0,0}, {18946,18947,16650 ,7024,7025,7126 ,0,0,0}, + {18948,18949,16650 ,7026,7027,7126 ,0,0,0}, {18950,16650,18951 ,7028,7126,7029 ,0,0,0}, + {16650,18949,18951 ,7126,7027,7029 ,0,0,0}, {18952,16650,18953 ,7030,7126,7031 ,0,0,0}, + {16650,18950,18953 ,7126,7028,7031 ,0,0,0}, {18954,16650,18955 ,7032,7126,7033 ,0,0,0}, + {16650,18952,18955 ,7126,7030,7033 ,0,0,0}, {16649,16650,18954 ,7128,7126,7032 ,0,0,0}, + {16632,18435,18944 ,7129,7099,7130 ,0,0,0}, {18946,18945,18440 ,7131,7132,7133 ,0,0,0}, + {18943,18942,18434 ,7041,7075,7134 ,0,0,0}, {18948,18441,18949 ,7135,7107,7136 ,0,0,0}, + {18439,18467,18947 ,7137,7138,7139 ,0,0,0}, {18317,18318,18950 ,7140,7141,7142 ,0,0,0}, + {18317,18951,18423 ,7140,7143,7144 ,0,0,0}, {18401,18402,18952 ,7145,7146,7147 ,0,0,0}, + {18952,18953,18401 ,7147,7148,7145 ,0,0,0}, {18955,18402,18487 ,7149,7146,7150 ,0,0,0}, + {18402,18955,18952 ,7146,7149,7147 ,0,0,0}, {18486,18954,18487 ,7151,7152,7150 ,0,0,0}, + {18955,18487,18954 ,7149,7150,7152 ,0,0,0}, {18486,16648,16649 ,7151,7153,4831 ,0,0,0}, + {16649,18954,18486 ,4831,7152,7151 ,0,0,0}, {18441,18948,18467 ,7107,7135,7138 ,0,0,0}, + {18318,18953,18950 ,7141,7148,7142 ,0,0,0}, {18401,18953,18318 ,7145,7148,7141 ,0,0,0}, + {18440,18945,18443 ,7133,7132,7154 ,0,0,0}, {18423,18951,18949 ,7144,7143,7136 ,0,0,0}, + {18317,18950,18951 ,7140,7142,7143 ,0,0,0}, {18441,18423,18949 ,7107,7144,7136 ,0,0,0}, + {18947,18467,18948 ,7139,7138,7135 ,0,0,0}, {18946,18440,18439 ,7131,7133,7137 ,0,0,0}, + {18439,18947,18946 ,7137,7139,7131 ,0,0,0}, {18942,18435,18434 ,7075,7099,7134 ,0,0,0}, + {18443,18943,18434 ,7154,7041,7134 ,0,0,0}, {18945,18943,18443 ,7132,7041,7154 ,0,0,0}, + {16632,18944,16633 ,7129,7130,4929 ,0,0,0}, {18435,18942,18944 ,7099,7075,7130 ,0,0,0}, + {16593,16592,18956 ,4777,21,7155 ,0,0,0}, {18300,18313,18957 ,7156,7157,7158 ,0,0,0}, + {18309,18958,18959 ,7159,7160,7161 ,0,0,0}, {18960,18961,18291 ,7162,7163,7164 ,0,0,0}, + {18962,18357,18315 ,7165,7166,7167 ,0,0,0}, {18368,18412,18963 ,7168,7169,7170 ,0,0,0}, + {18353,18964,18965 ,7171,7172,7173 ,0,0,0}, {18343,18966,18375 ,7174,7175,7176 ,0,0,0}, + {18967,18968,18372 ,7177,7178,7179 ,0,0,0}, {18969,18970,18381 ,7180,7181,7182 ,0,0,0}, + {18971,18373,18375 ,7183,7184,7176 ,0,0,0}, {18972,18973,18382 ,7185,7186,7187 ,0,0,0}, + {18972,18379,18970 ,7185,7188,7181 ,0,0,0}, {18383,18973,18974 ,7189,7186,7190 ,0,0,0}, + {18973,18383,18382 ,7186,7189,7187 ,0,0,0}, {18975,18378,18974 ,7191,7192,7190 ,0,0,0}, + {18383,18974,18378 ,7189,7190,7192 ,0,0,0}, {18975,18976,18376 ,7191,7193,7194 ,0,0,0}, + {18376,18378,18975 ,7194,7192,7191 ,0,0,0}, {18385,18976,18977 ,7195,7193,7196 ,0,0,0}, + {18976,18385,18376 ,7193,7195,7194 ,0,0,0}, {16615,18386,18977 ,7197,7198,7196 ,0,0,0}, + {18385,18977,18386 ,7195,7196,7198 ,0,0,0}, {16616,18386,16615 ,7199,7198,7197 ,0,0,0}, + {18343,18968,18966 ,7174,7178,7175 ,0,0,0}, {18379,18381,18970 ,7188,7182,7181 ,0,0,0}, + {18972,18382,18379 ,7185,7187,7188 ,0,0,0}, {18373,18971,18969 ,7184,7183,7180 ,0,0,0}, + {18969,18381,18373 ,7180,7182,7184 ,0,0,0}, {18971,18375,18966 ,7183,7176,7175 ,0,0,0}, + {18968,18343,18372 ,7178,7174,7179 ,0,0,0}, {18368,18963,18967 ,7168,7170,7177 ,0,0,0}, + {18368,18967,18372 ,7168,7177,7179 ,0,0,0}, {18357,18960,18291 ,7166,7162,7164 ,0,0,0}, + {18965,18412,18353 ,7173,7169,7171 ,0,0,0}, {18412,18965,18963 ,7169,7173,7170 ,0,0,0}, + {18292,18291,18961 ,7200,7164,7163 ,0,0,0}, {18353,18292,18964 ,7171,7200,7172 ,0,0,0}, + {18964,18292,18961 ,7172,7200,7163 ,0,0,0}, {18962,18960,18357 ,7165,7162,7166 ,0,0,0}, + {18978,18962,18315 ,7201,7165,7167 ,0,0,0}, {18300,18957,18978 ,7156,7158,7201 ,0,0,0}, + {18300,18978,18315 ,7156,7201,7167 ,0,0,0}, {18414,18956,18958 ,7202,7155,7160 ,0,0,0}, + {18959,18313,18309 ,7161,7157,7159 ,0,0,0}, {18313,18959,18957 ,7157,7161,7158 ,0,0,0}, + {18414,18958,18309 ,7202,7160,7159 ,0,0,0}, {18956,18414,16593 ,7155,7202,4777 ,0,0,0}, + {16581,18969,16584 ,730,7015,730 ,0,0,0}, {18959,18958,18964 ,730,730,730 ,0,0,0}, + {16591,16587,18968 ,730,730,730 ,0,0,0}, {16585,18971,18966 ,730,730,7015 ,0,0,0}, + {18965,18964,18958 ,730,730,730 ,0,0,0}, {16592,18967,18956 ,730,730,730 ,0,0,0}, + {18962,18978,18957 ,730,730,730 ,0,0,0}, {18957,18959,18961 ,730,730,730 ,0,0,0}, + {18957,18961,18960 ,730,730,730 ,0,0,0}, {18962,18957,18960 ,730,730,730 ,0,0,0}, + {18958,18956,18965 ,730,730,730 ,0,0,0}, {18961,18959,18964 ,730,730,730 ,0,0,0}, + {18956,18963,18965 ,730,730,730 ,0,0,0}, {18967,16592,18968 ,730,730,730 ,0,0,0}, + {18963,18956,18967 ,730,730,730 ,0,0,0}, {18968,16587,18966 ,730,730,7015 ,0,0,0}, + {18968,16592,16591 ,730,730,730 ,0,0,0}, {18971,16585,16584 ,730,730,730 ,0,0,0}, + {18966,16587,16585 ,7015,730,730 ,0,0,0}, {18970,18969,16581 ,730,7015,730 ,0,0,0}, + {18969,18971,16584 ,7015,730,730 ,0,0,0}, {18972,16581,16580 ,7015,730,730 ,0,0,0}, + {16581,18972,18970 ,730,7015,730 ,0,0,0}, {18972,16580,18973 ,7015,730,730 ,0,0,0}, + {16573,18973,16577 ,730,730,730 ,0,0,0}, {18973,16580,16577 ,730,730,730 ,0,0,0}, + {16573,16572,18974 ,730,730,7015 ,0,0,0}, {18974,18973,16573 ,7015,730,730 ,0,0,0}, + {18974,16572,18975 ,7015,730,7015 ,0,0,0}, {16576,18976,18975 ,730,730,7015 ,0,0,0}, + {18975,16572,16576 ,7015,730,730 ,0,0,0}, {18976,16571,18977 ,730,730,7015 ,0,0,0}, + {16571,18976,16576 ,730,730,730 ,0,0,0}, {16567,16615,16571 ,730,7015,730 ,0,0,0}, + {18977,16571,16615 ,7015,730,7015 ,0,0,0}, {16614,16596,16612 ,7015,7015,730 ,0,0,0}, + {16567,16566,16614 ,730,730,7015 ,0,0,0}, {16608,16603,16606 ,7015,7015,7015 ,0,0,0}, + {16600,16609,16597 ,7015,7015,730 ,0,0,0}, {16608,16600,16602 ,7015,7015,7015 ,0,0,0}, + {16603,16608,16602 ,7015,7015,7015 ,0,0,0}, {16612,16597,16609 ,730,730,7015 ,0,0,0}, + {16609,16600,16608 ,7015,7015,7015 ,0,0,0}, {16614,16566,16596 ,7015,730,7015 ,0,0,0}, + {16612,16596,16597 ,730,7015,730 ,0,0,0}, {16614,16615,16567 ,7015,7015,730 ,0,0,0}, + {16543,18274,18979 ,126,7203,7204 ,0,0,0}, {18980,18981,18276 ,7205,7206,7207 ,0,0,0}, + {18326,18982,18394 ,7208,7209,7210 ,0,0,0}, {18415,18417,18983 ,7211,7212,7213 ,0,0,0}, + {18984,18287,18985 ,7214,7215,7216 ,0,0,0}, {18986,18987,18312 ,7217,7218,7219 ,0,0,0}, + {18337,18988,18455 ,7220,7221,7222 ,0,0,0}, {18306,18989,18990 ,7223,7224,7225 ,0,0,0}, + {18304,18305,18991 ,7226,7227,7228 ,0,0,0}, {18302,18296,18992 ,7229,7230,7231 ,0,0,0}, + {18993,18303,18302 ,7232,7233,7229 ,0,0,0}, {18294,18295,18994 ,7234,7235,7236 ,0,0,0}, + {18995,18296,18294 ,7237,7230,7234 ,0,0,0}, {18293,18996,18295 ,7238,7239,7235 ,0,0,0}, + {18994,18295,18996 ,7236,7235,7239 ,0,0,0}, {18997,18293,18286 ,7240,7238,7241 ,0,0,0}, + {18293,18997,18996 ,7238,7240,7239 ,0,0,0}, {18286,18285,18998 ,7241,7242,7243 ,0,0,0}, + {18998,18997,18286 ,7243,7240,7241 ,0,0,0}, {18282,18999,18285 ,7244,7245,7242 ,0,0,0}, + {18998,18285,18999 ,7243,7242,7245 ,0,0,0}, {19000,18282,16565 ,7246,7244,82 ,0,0,0}, + {18282,19000,18999 ,7244,7246,7245 ,0,0,0}, {16563,19000,16565 ,7011,7246,82 ,0,0,0}, + {18303,18993,18989 ,7233,7232,7224 ,0,0,0}, {18992,18296,18995 ,7231,7230,7237 ,0,0,0}, + {18995,18294,18994 ,7237,7234,7236 ,0,0,0}, {18992,18993,18302 ,7231,7232,7229 ,0,0,0}, + {18990,18305,18306 ,7225,7227,7223 ,0,0,0}, {18989,18306,18303 ,7224,7223,7233 ,0,0,0}, + {18305,18990,18991 ,7227,7225,7228 ,0,0,0}, {18986,18304,18991 ,7217,7226,7228 ,0,0,0}, + {19001,18983,18417 ,7247,7213,7212 ,0,0,0}, {18337,18312,18987 ,7220,7219,7218 ,0,0,0}, + {18304,18986,18312 ,7226,7217,7219 ,0,0,0}, {18455,19001,18417 ,7222,7247,7212 ,0,0,0}, + {18455,18988,19001 ,7222,7221,7247 ,0,0,0}, {18987,18988,18337 ,7218,7221,7220 ,0,0,0}, + {18276,18981,18326 ,7207,7206,7208 ,0,0,0}, {18983,18985,18415 ,7213,7216,7211 ,0,0,0}, + {18984,18289,18287 ,7214,7248,7215 ,0,0,0}, {18287,18415,18985 ,7215,7211,7216 ,0,0,0}, + {18289,18980,18276 ,7248,7205,7207 ,0,0,0}, {18289,18984,18980 ,7248,7214,7205 ,0,0,0}, + {18394,18982,18979 ,7210,7209,7204 ,0,0,0}, {18981,18982,18326 ,7206,7209,7208 ,0,0,0}, + {16543,16540,18274 ,126,4726,7203 ,0,0,0}, {18979,18274,18394 ,7204,7203,7210 ,0,0,0}, + {18994,18992,18995 ,7249,7250,7251 ,0,0,0}, {16545,18981,16547 ,726,726,7252 ,0,0,0}, + {18997,18992,18996 ,7253,7250,7253 ,0,0,0}, {18992,18994,18996 ,7250,7249,7253 ,0,0,0}, + {18993,18997,18998 ,7254,7253,7249 ,0,0,0}, {18997,18993,18992 ,7253,7254,7250 ,0,0,0}, + {18998,18999,18989 ,7249,7249,7255 ,0,0,0}, {18989,18993,18998 ,7255,7254,7249 ,0,0,0}, + {18999,18990,18989 ,7249,7256,7255 ,0,0,0}, {19000,16563,18990 ,7257,7257,7256 ,0,0,0}, + {19000,18990,18999 ,7257,7256,7249 ,0,0,0}, {18991,16562,18986 ,7258,726,7259 ,0,0,0}, + {18990,16563,18991 ,7256,7257,7258 ,0,0,0}, {19001,18988,16557 ,7260,7254,7257 ,0,0,0}, + {16559,18987,16562 ,7252,7261,726 ,0,0,0}, {16550,18985,16551 ,726,7262,7252 ,0,0,0}, + {16556,16553,18983 ,726,7252,7263 ,0,0,0}, {18982,16545,16544 ,7253,726,726 ,0,0,0}, + {18980,16550,16547 ,726,726,7252 ,0,0,0}, {16543,16520,16519 ,726,726,726 ,0,0,0}, + {16518,18979,16544 ,7264,7253,726 ,0,0,0}, {16524,16536,16537 ,726,7257,726 ,0,0,0}, + {16519,16525,16539 ,726,7264,726 ,0,0,0}, {16531,16533,16527 ,7257,726,7257 ,0,0,0}, + {16533,16536,16527 ,726,7257,7257 ,0,0,0}, {16531,16527,16529 ,7257,7257,7257 ,0,0,0}, + {16537,16525,16524 ,726,7264,726 ,0,0,0}, {16536,16524,16527 ,7257,726,7257 ,0,0,0}, + {16541,16519,16539 ,726,726,726 ,0,0,0}, {16539,16525,16537 ,726,7264,726 ,0,0,0}, + {16520,16543,18979 ,726,726,7253 ,0,0,0}, {16519,16541,16543 ,726,726,726 ,0,0,0}, + {16544,18979,18982 ,726,7253,7253 ,0,0,0}, {16520,18979,16518 ,726,7253,7264 ,0,0,0}, + {16547,18981,18980 ,7252,726,726 ,0,0,0}, {18981,16545,18982 ,726,726,7253 ,0,0,0}, + {18985,16550,18984 ,7262,726,7262 ,0,0,0}, {18984,16550,18980 ,7262,726,726 ,0,0,0}, + {16553,16551,18983 ,7252,7252,7263 ,0,0,0}, {16551,18985,18983 ,7252,7262,7263 ,0,0,0}, + {18983,19001,16556 ,7263,7260,726 ,0,0,0}, {16559,16557,18988 ,7252,7257,7254 ,0,0,0}, + {16557,16556,19001 ,7257,726,7260 ,0,0,0}, {16562,18987,18986 ,726,7261,7259 ,0,0,0}, + {16559,18988,18987 ,7252,7254,7261 ,0,0,0}, {16562,18991,16563 ,726,7258,7257 ,0,0,0}, + {16493,19002,18268 ,4799,7265,7266 ,0,0,0}, {19003,18270,19004 ,7267,7268,7269 ,0,0,0}, + {18269,18444,19005 ,7270,7271,7272 ,0,0,0}, {18451,19006,18278 ,7273,7274,7275 ,0,0,0}, + {19007,19008,18450 ,7276,7277,7278 ,0,0,0}, {19009,18448,19010 ,7279,7280,7281 ,0,0,0}, + {18468,18420,19011 ,7282,7283,7284 ,0,0,0}, {18469,19012,19013 ,7285,7286,7287 ,0,0,0}, + {18323,19014,18324 ,7288,7289,7290 ,0,0,0}, {18470,19015,18321 ,7291,7292,7293 ,0,0,0}, + {19016,18470,18279 ,7294,7291,7295 ,0,0,0}, {18320,19017,18471 ,7296,7297,7298 ,0,0,0}, + {19018,18320,18321 ,7299,7296,7293 ,0,0,0}, {18472,18471,19019 ,7300,7298,7301 ,0,0,0}, + {19017,19019,18471 ,7297,7301,7298 ,0,0,0}, {19020,18421,18472 ,7302,7303,7300 ,0,0,0}, + {18472,19019,19020 ,7300,7301,7302 ,0,0,0}, {18421,19021,18474 ,7303,7304,7305 ,0,0,0}, + {19021,18421,19020 ,7304,7303,7302 ,0,0,0}, {18473,18474,19022 ,7306,7305,7307 ,0,0,0}, + {19021,19022,18474 ,7304,7307,7305 ,0,0,0}, {19023,16515,18473 ,7308,21,7306 ,0,0,0}, + {18473,19022,19023 ,7306,7307,7308 ,0,0,0}, {16514,16515,19023 ,7309,21,7308 ,0,0,0}, + {18279,19013,19016 ,7295,7287,7294 ,0,0,0}, {19015,19018,18321 ,7292,7299,7293 ,0,0,0}, + {19018,19017,18320 ,7299,7297,7296 ,0,0,0}, {19015,18470,19016 ,7292,7291,7294 ,0,0,0}, + {19012,18469,18324 ,7286,7285,7290 ,0,0,0}, {19013,18279,18469 ,7287,7295,7285 ,0,0,0}, + {18324,19014,19012 ,7290,7289,7286 ,0,0,0}, {19009,19014,18323 ,7279,7289,7288 ,0,0,0}, + {19024,18278,19006 ,7310,7275,7274 ,0,0,0}, {18468,19010,18448 ,7282,7281,7280 ,0,0,0}, + {18323,18448,19009 ,7288,7280,7279 ,0,0,0}, {18420,18278,19024 ,7283,7275,7310 ,0,0,0}, + {18420,19024,19011 ,7283,7310,7284 ,0,0,0}, {19010,18468,19011 ,7281,7282,7284 ,0,0,0}, + {18270,18269,19004 ,7268,7270,7269 ,0,0,0}, {19006,18451,19008 ,7274,7273,7277 ,0,0,0}, + {19007,18450,18449 ,7276,7278,7311 ,0,0,0}, {18450,19008,18451 ,7278,7277,7273 ,0,0,0}, + {18449,18270,19003 ,7311,7268,7267 ,0,0,0}, {18449,19003,19007 ,7311,7267,7276 ,0,0,0}, + {18444,19002,19005 ,7271,7265,7272 ,0,0,0}, {19004,18269,19005 ,7269,7270,7272 ,0,0,0}, + {16493,18268,16490 ,4799,7266,7199 ,0,0,0}, {19002,18444,18268 ,7265,7271,7266 ,0,0,0}, + {19015,16485,16482 ,730,7312,6103 ,0,0,0}, {16478,19019,16481 ,7313,730,730 ,0,0,0}, + {16488,19012,16492 ,7314,7015,7315 ,0,0,0}, {19016,19013,16487 ,730,730,7316 ,0,0,0}, + {19011,19005,19010 ,730,7317,7313 ,0,0,0}, {19014,19002,16493 ,730,7318,7319 ,0,0,0}, + {19003,19004,19024 ,7320,7316,7316 ,0,0,0}, {19006,19008,19003 ,7320,6103,7320 ,0,0,0}, + {19007,19003,19008 ,6111,7320,6103 ,0,0,0}, {19011,19024,19004 ,730,7316,7316 ,0,0,0}, + {19024,19006,19003 ,7316,7320,7320 ,0,0,0}, {19002,19010,19005 ,7318,7313,7317 ,0,0,0}, + {19005,19011,19004 ,7317,730,7316 ,0,0,0}, {19014,19009,19002 ,730,7316,7318 ,0,0,0}, + {19002,19009,19010 ,7318,7316,7313 ,0,0,0}, {16492,19012,16493 ,7315,7015,7319 ,0,0,0}, + {16493,19012,19014 ,7319,7015,730 ,0,0,0}, {16487,19013,16488 ,7316,730,7314 ,0,0,0}, + {16488,19013,19012 ,7314,730,7015 ,0,0,0}, {19016,16487,16485 ,730,7316,7312 ,0,0,0}, + {16482,19018,19015 ,6103,7017,730 ,0,0,0}, {16485,19015,19016 ,7312,730,730 ,0,0,0}, + {19018,16482,19017 ,7017,6103,7017 ,0,0,0}, {16481,19019,19017 ,730,730,7017 ,0,0,0}, + {19017,16482,16481 ,7017,6103,730 ,0,0,0}, {19019,16478,16477 ,730,7313,730 ,0,0,0}, + {16477,16473,19020 ,730,7316,730 ,0,0,0}, {19020,19019,16477 ,730,730,730 ,0,0,0}, + {19021,16473,16475 ,7016,7316,7313 ,0,0,0}, {16473,19021,19020 ,7316,7016,730 ,0,0,0}, + {16469,19022,16475 ,7015,730,7313 ,0,0,0}, {19021,16475,19022 ,7016,7313,730 ,0,0,0}, + {19023,16469,16514 ,730,7015,730 ,0,0,0}, {19023,19022,16469 ,730,730,7015 ,0,0,0}, + {16469,16471,16514 ,7015,7015,730 ,0,0,0}, {16512,16494,16509 ,730,730,730 ,0,0,0}, + {16471,16467,16512 ,7015,730,730 ,0,0,0}, {16506,16502,16503 ,730,730,7017 ,0,0,0}, + {16497,16508,16496 ,7015,7016,730 ,0,0,0}, {16506,16497,16500 ,730,7015,730 ,0,0,0}, + {16502,16506,16500 ,730,730,730 ,0,0,0}, {16509,16496,16508 ,730,730,7016 ,0,0,0}, + {16508,16497,16506 ,7016,7015,730 ,0,0,0}, {16512,16467,16494 ,730,730,730 ,0,0,0}, + {16509,16494,16496 ,730,730,730 ,0,0,0}, {16512,16514,16471 ,730,730,7015 ,0,0,0}, + {17025,19025,19026 ,7321,1711,7322 ,0,0,0}, {17015,17012,19027 ,7323,7324,7325 ,0,0,0}, + {19028,17014,17023 ,7326,7327,7328 ,0,0,0}, {18841,19029,18840 ,7329,7330,7331 ,0,0,0}, + {19030,19031,17019 ,7332,7333,7334 ,0,0,0}, {18838,19032,18837 ,7335,7336,7337 ,0,0,0}, + {19032,18839,19033 ,7336,7338,7339 ,0,0,0}, {18836,18837,19034 ,7340,7337,7341 ,0,0,0}, + {19032,19034,18837 ,7336,7341,7337 ,0,0,0}, {19035,18835,18836 ,1359,1359,7340 ,0,0,0}, + {18836,19034,19035 ,7340,7341,1359 ,0,0,0}, {19033,18839,18840 ,7339,7338,7331 ,0,0,0}, + {19032,18838,18839 ,7336,7335,7338 ,0,0,0}, {19029,18841,18842 ,7330,7329,7342 ,0,0,0}, + {19029,19033,18840 ,7330,7339,7331 ,0,0,0}, {18842,17019,19031 ,7342,7334,7333 ,0,0,0}, + {19031,19029,18842 ,7333,7330,7342 ,0,0,0}, {17018,19027,19030 ,7343,7325,7332 ,0,0,0}, + {17018,19030,17019 ,7343,7332,7334 ,0,0,0}, {17012,19036,19027 ,7324,7344,7325 ,0,0,0}, + {17018,17015,19027 ,7343,7323,7325 ,0,0,0}, {19028,19036,17014 ,7326,7344,7327 ,0,0,0}, + {17012,17014,19036 ,7324,7327,7344 ,0,0,0}, {19028,17022,19026 ,7326,7345,7322 ,0,0,0}, + {17023,17022,19028 ,7328,7345,7326 ,0,0,0}, {19025,17025,16991 ,1711,7321,1711 ,0,0,0}, + {19026,17022,17025 ,7322,7345,7321 ,0,0,0}, {19025,16993,19037 ,2197,7346,7346 ,0,0,0}, + {16993,19025,16991 ,7346,2197,2197 ,0,0,0}, {19038,19039,18845 ,1435,7347,7348 ,0,0,0}, + {18846,18844,19040 ,7349,7350,7351 ,0,0,0}, {18843,18848,19041 ,7352,7353,7354 ,0,0,0}, + {17004,19042,17002 ,7355,7356,7357 ,0,0,0}, {19043,19044,17010 ,7358,7359,7360 ,0,0,0}, + {16998,19045,16996 ,7361,7362,7363 ,0,0,0}, {16998,17000,19045 ,7361,7364,7362 ,0,0,0}, + {16995,16996,19046 ,7365,7363,7366 ,0,0,0}, {19045,19046,16996 ,7362,7366,7363 ,0,0,0}, + {19037,16993,16995 ,1790,1790,7365 ,0,0,0}, {16995,19046,19037 ,7365,7366,1790 ,0,0,0}, + {17002,19047,17000 ,7357,7367,7364 ,0,0,0}, {19045,17000,19047 ,7362,7364,7367 ,0,0,0}, + {18843,19048,18844 ,7352,7368,7350 ,0,0,0}, {17004,17008,19042 ,7355,7369,7356 ,0,0,0}, + {19042,19047,17002 ,7356,7367,7357 ,0,0,0}, {17008,17010,19044 ,7369,7360,7359 ,0,0,0}, + {19044,19042,17008 ,7359,7356,7369 ,0,0,0}, {19043,17010,18847 ,7358,7360,7370 ,0,0,0}, + {19040,18847,18846 ,7351,7370,7349 ,0,0,0}, {18847,19040,19043 ,7370,7351,7358 ,0,0,0}, + {19048,19040,18844 ,7368,7351,7350 ,0,0,0}, {19041,18849,19039 ,7354,7371,7347 ,0,0,0}, + {18849,19041,18848 ,7371,7354,7353 ,0,0,0}, {19048,18843,19041 ,7368,7352,7354 ,0,0,0}, + {19038,18845,18834 ,1435,7348,1435 ,0,0,0}, {19039,18849,18845 ,7347,7371,7348 ,0,0,0}, + {18834,19035,19038 ,1398,7372,1398 ,0,0,0}, {19035,18834,18835 ,7372,1398,7372 ,0,0,0}, + {19035,19039,19038 ,7373,730,730 ,0,0,0}, {19036,19045,19047 ,730,730,730 ,0,0,0}, + {19033,19040,19048 ,7374,7375,7375 ,0,0,0}, {19048,19041,19032 ,7375,730,7373 ,0,0,0}, + {19031,19044,19043 ,7375,7375,7375 ,0,0,0}, {19043,19040,19029 ,7375,7375,730 ,0,0,0}, + {19047,19042,19027 ,730,730,7376 ,0,0,0}, {19042,19044,19030 ,730,7375,7375 ,0,0,0}, + {19026,19046,19028 ,730,730,730 ,0,0,0}, {19045,19028,19046 ,730,730,730 ,0,0,0}, + {19026,19025,19037 ,730,730,730 ,0,0,0}, {19037,19046,19026 ,730,730,730 ,0,0,0}, + {19047,19027,19036 ,730,7376,730 ,0,0,0}, {19045,19036,19028 ,730,730,730 ,0,0,0}, + {19042,19030,19027 ,730,7375,7376 ,0,0,0}, {19044,19031,19030 ,7375,7375,7375 ,0,0,0}, + {19043,19029,19031 ,7375,730,7375 ,0,0,0}, {19040,19033,19029 ,7375,7374,730 ,0,0,0}, + {19048,19032,19033 ,7375,7373,7374 ,0,0,0}, {19041,19034,19032 ,730,730,7373 ,0,0,0}, + {19035,19034,19039 ,7373,730,730 ,0,0,0}, {19041,19039,19034 ,730,730,730 ,0,0,0}, + {19049,16923,19050 ,7377,1435,1435 ,0,0,0}, {19051,16939,19052 ,7378,7379,7379 ,0,0,0}, + {19053,16914,16918 ,7380,7380,7377 ,0,0,0}, {16946,19054,19055 ,7381,7381,7382 ,0,0,0}, + {16941,19056,16944 ,7378,7383,7383 ,0,0,0}, {16953,19057,16955 ,7384,7385,7385 ,0,0,0}, + {19058,16953,16948 ,7384,7384,7382 ,0,0,0}, {16958,16955,19059 ,7386,7385,7386 ,0,0,0}, + {19057,19059,16955 ,7385,7386,7385 ,0,0,0}, {19060,16961,16958 ,7387,7388,7386 ,0,0,0}, + {16958,19059,19060 ,7386,7386,7387 ,0,0,0}, {19055,19058,16948 ,7382,7384,7382 ,0,0,0}, + {19058,19057,16953 ,7384,7385,7384 ,0,0,0}, {16944,19054,16946 ,7383,7381,7381 ,0,0,0}, + {16946,19055,16948 ,7381,7382,7382 ,0,0,0}, {16941,19051,19056 ,7378,7378,7383 ,0,0,0}, + {16944,19056,19054 ,7383,7383,7381 ,0,0,0}, {16939,16914,19052 ,7379,7380,7379 ,0,0,0}, + {16941,16939,19051 ,7378,7379,7378 ,0,0,0}, {19053,16918,19049 ,7380,7377,7377 ,0,0,0}, + {19052,16914,19053 ,7379,7380,7380 ,0,0,0}, {16923,19049,16918 ,1435,7377,7377 ,0,0,0}, + {19050,16920,19061 ,1398,1398,1398 ,0,0,0}, {16920,19050,16923 ,1398,1398,1398 ,0,0,0}, + {19062,19063,17045 ,7389,7390,7390 ,0,0,0}, {19064,17041,19065 ,7391,7391,7392 ,0,0,0}, + {17043,16952,19066 ,7392,7393,7393 ,0,0,0}, {17033,19067,19068 ,7394,7395,7394 ,0,0,0}, + {17038,19069,17037 ,7396,7396,7395 ,0,0,0}, {17028,19070,19071 ,7397,7398,7397 ,0,0,0}, + {19070,17028,17032 ,7398,7397,7398 ,0,0,0}, {19072,17026,19071 ,7399,7399,7397 ,0,0,0}, + {17028,19071,17026 ,7397,7397,7399 ,0,0,0}, {19072,19061,16920 ,7399,1359,1359 ,0,0,0}, + {16920,17026,19072 ,1359,7399,7399 ,0,0,0}, {19065,17043,19066 ,7392,7392,7393 ,0,0,0}, + {17032,17033,19068 ,7398,7394,7394 ,0,0,0}, {19068,19070,17032 ,7394,7398,7398 ,0,0,0}, + {19067,17033,17037 ,7395,7394,7395 ,0,0,0}, {19064,19069,17038 ,7391,7396,7396 ,0,0,0}, + {17037,19069,19067 ,7395,7396,7395 ,0,0,0}, {17043,19065,17041 ,7392,7392,7391 ,0,0,0}, + {17038,17041,19064 ,7396,7391,7391 ,0,0,0}, {17045,19063,16952 ,7390,7390,7393 ,0,0,0}, + {16952,19063,19066 ,7393,7390,7393 ,0,0,0}, {19062,17045,16911 ,7389,7390,7400 ,0,0,0}, + {19060,19062,16911 ,7401,7402,7402 ,0,0,0}, {19060,16911,16961 ,7401,7402,7401 ,0,0,0}, + {19072,19053,19049 ,7403,7403,7404 ,0,0,0}, {19058,19066,19057 ,7375,7375,730 ,0,0,0}, + {19054,19064,19055 ,7375,730,730 ,0,0,0}, {19065,19058,19055 ,730,7375,730 ,0,0,0}, + {19051,19067,19056 ,7373,7375,7373 ,0,0,0}, {19069,19054,19056 ,730,7375,7373 ,0,0,0}, + {19052,19071,19070 ,7405,7406,730 ,0,0,0}, {19068,19051,19052 ,7373,7373,7405 ,0,0,0}, + {19072,19071,19053 ,7403,7406,7403 ,0,0,0}, {19049,19050,19061 ,7404,730,7407 ,0,0,0}, + {19061,19072,19049 ,7407,7403,7404 ,0,0,0}, {19071,19052,19053 ,7406,7405,7403 ,0,0,0}, + {19068,19052,19070 ,7373,7405,730 ,0,0,0}, {19067,19051,19068 ,7375,7373,7373 ,0,0,0}, + {19069,19056,19067 ,730,7373,7375 ,0,0,0}, {19064,19054,19069 ,730,7375,730 ,0,0,0}, + {19065,19055,19064 ,730,730,730 ,0,0,0}, {19066,19058,19065 ,7375,7375,730 ,0,0,0}, + {19063,19057,19066 ,730,730,7375 ,0,0,0}, {19059,19063,19062 ,7373,730,730 ,0,0,0}, + {19063,19059,19057 ,730,7373,730 ,0,0,0}, {19059,19062,19060 ,7373,730,7405 ,0,0,0}, + {19073,18832,19074 ,7408,7409,7410 ,0,0,0}, {19075,18830,19076 ,7411,7412,7412 ,0,0,0}, + {19077,18829,18833 ,7413,7413,7408 ,0,0,0}, {18850,19078,19079 ,7414,7414,7415 ,0,0,0}, + {18831,19080,18851 ,7411,7416,7416 ,0,0,0}, {18827,19081,18828 ,7417,7418,7418 ,0,0,0}, + {19082,18827,18826 ,7417,7417,7415 ,0,0,0}, {18824,18828,19083 ,7419,7418,7419 ,0,0,0}, + {19081,19083,18828 ,7418,7419,7418 ,0,0,0}, {19084,18823,18824 ,1790,1790,7419 ,0,0,0}, + {18824,19083,19084 ,7419,7419,1790 ,0,0,0}, {19079,19082,18826 ,7415,7417,7415 ,0,0,0}, + {19082,19081,18827 ,7417,7418,7417 ,0,0,0}, {18851,19078,18850 ,7416,7414,7414 ,0,0,0}, + {18850,19079,18826 ,7414,7415,7415 ,0,0,0}, {18831,19075,19080 ,7411,7411,7416 ,0,0,0}, + {18851,19080,19078 ,7416,7416,7414 ,0,0,0}, {18830,18829,19076 ,7412,7413,7412 ,0,0,0}, + {18831,18830,19075 ,7411,7412,7411 ,0,0,0}, {19077,18833,19073 ,7413,7408,7408 ,0,0,0}, + {19076,18829,19077 ,7412,7413,7413 ,0,0,0}, {18832,19073,18833 ,7409,7408,7408 ,0,0,0}, + {18853,19085,19074 ,7420,7420,7421 ,0,0,0}, {18853,19074,18832 ,7420,7421,7421 ,0,0,0}, + {19086,19087,18862 ,1711,7422,7422 ,0,0,0}, {19088,18860,19089 ,7423,7423,7424 ,0,0,0}, + {18861,18852,19090 ,7424,7425,7425 ,0,0,0}, {18857,19091,19092 ,7426,7427,7426 ,0,0,0}, + {18859,19093,18858 ,7428,7428,7427 ,0,0,0}, {18855,19094,19095 ,7429,7430,7429 ,0,0,0}, + {19094,18855,18856 ,7430,7429,7430 ,0,0,0}, {19096,18854,19095 ,7431,7431,7429 ,0,0,0}, + {18855,19095,18854 ,7429,7429,7431 ,0,0,0}, {19096,19085,18853 ,7431,7432,82 ,0,0,0}, + {18853,18854,19096 ,82,7431,7431 ,0,0,0}, {19089,18861,19090 ,7424,7424,7425 ,0,0,0}, + {18856,18857,19092 ,7430,7426,7426 ,0,0,0}, {19092,19094,18856 ,7426,7430,7430 ,0,0,0}, + {19091,18857,18858 ,7427,7426,7427 ,0,0,0}, {19088,19093,18859 ,7423,7428,7428 ,0,0,0}, + {18858,19093,19091 ,7427,7428,7427 ,0,0,0}, {18861,19089,18860 ,7424,7424,7423 ,0,0,0}, + {18859,18860,19088 ,7428,7423,7423 ,0,0,0}, {18862,19087,18852 ,7422,7422,7425 ,0,0,0}, + {18852,19087,19090 ,7425,7422,7425 ,0,0,0}, {19086,18862,18825 ,1711,7422,1711 ,0,0,0}, + {18825,19084,19086 ,2197,2197,2197 ,0,0,0}, {19084,18825,18823 ,2197,2197,2197 ,0,0,0}, + {19084,19087,19086 ,7433,730,730 ,0,0,0}, {19075,19076,19092 ,7375,7375,730 ,0,0,0}, + {19079,19089,19082 ,730,730,730 ,0,0,0}, {19089,19090,19081 ,730,7376,730 ,0,0,0}, + {19080,19093,19078 ,730,730,7376 ,0,0,0}, {19088,19079,19078 ,730,730,7376 ,0,0,0}, + {19091,19080,19075 ,7376,730,7375 ,0,0,0}, {19095,19077,19073 ,7375,7376,7376 ,0,0,0}, + {19076,19077,19094 ,7375,7376,7375 ,0,0,0}, {19074,19096,19073 ,7374,7376,7376 ,0,0,0}, + {19095,19073,19096 ,7375,7376,7376 ,0,0,0}, {19085,19096,19074 ,730,7376,7374 ,0,0,0}, + {19094,19077,19095 ,7375,7376,7375 ,0,0,0}, {19092,19076,19094 ,730,7375,7375 ,0,0,0}, + {19091,19075,19092 ,7376,7375,730 ,0,0,0}, {19093,19080,19091 ,730,730,7376 ,0,0,0}, + {19088,19078,19093 ,730,7376,730 ,0,0,0}, {19089,19079,19088 ,730,730,730 ,0,0,0}, + {19089,19081,19082 ,730,730,730 ,0,0,0}, {19090,19083,19081 ,7376,7433,730 ,0,0,0}, + {19084,19083,19087 ,7433,7433,730 ,0,0,0}, {19090,19087,19083 ,7376,730,7433 ,0,0,0}, + {18260,16433,16431 ,7434,4326,7435 ,0,0,0}, {18432,18360,18257 ,7436,7437,7438 ,0,0,0}, + {18261,18359,18262 ,7439,7440,7441 ,0,0,0}, {18267,18255,18403 ,7442,7443,7444 ,0,0,0}, + {18265,18408,18466 ,7445,7446,7447 ,0,0,0}, {18411,18410,18245 ,7448,7449,7450 ,0,0,0}, + {18395,18263,18264 ,7451,7452,7453 ,0,0,0}, {18239,18238,18310 ,7454,7455,7456 ,0,0,0}, + {18241,18299,18301 ,7457,7458,7459 ,0,0,0}, {18229,18346,18233 ,7460,7461,7462 ,0,0,0}, + {18352,18311,18237 ,7463,7464,7465 ,0,0,0}, {18344,18271,18223 ,7466,7467,7468 ,0,0,0}, + {18347,18225,18271 ,7469,7470,7467 ,0,0,0}, {18416,18220,18227 ,7471,7472,7473 ,0,0,0}, + {18224,18220,18345 ,7474,7472,7475 ,0,0,0}, {18339,18228,18232 ,7476,7477,7478 ,0,0,0}, + {18227,18228,18338 ,7473,7477,7479 ,0,0,0}, {18235,18322,18232 ,7480,7481,7478 ,0,0,0}, + {18339,18232,18322 ,7476,7478,7481 ,0,0,0}, {18235,18244,18314 ,7480,7482,7483 ,0,0,0}, + {18314,18322,18235 ,7483,7481,7480 ,0,0,0}, {18288,18244,18243 ,7484,7482,7485 ,0,0,0}, + {18244,18288,18314 ,7482,7484,7483 ,0,0,0}, {18247,18277,18243 ,7486,7487,7485 ,0,0,0}, + {18288,18243,18277 ,7484,7485,7487 ,0,0,0}, {18247,18252,18275 ,7486,7488,7489 ,0,0,0}, + {18275,18277,18247 ,7489,7487,7486 ,0,0,0}, {18325,18252,18251 ,7490,7488,7491 ,0,0,0}, + {18252,18325,18275 ,7488,7490,7489 ,0,0,0}, {16465,18273,18251 ,82,7492,7491 ,0,0,0}, + {18325,18251,18273 ,7490,7491,7492 ,0,0,0}, {16464,18273,16465 ,82,7492,82 ,0,0,0}, + {18338,18416,18227 ,7479,7471,7473 ,0,0,0}, {18338,18228,18339 ,7479,7477,7476 ,0,0,0}, + {18224,18345,18344 ,7474,7475,7466 ,0,0,0}, {18345,18220,18416 ,7475,7472,7471 ,0,0,0}, + {18271,18225,18223 ,7467,7470,7468 ,0,0,0}, {18344,18223,18224 ,7466,7468,7474 ,0,0,0}, + {18347,18346,18229 ,7469,7461,7460 ,0,0,0}, {18347,18229,18225 ,7469,7460,7470 ,0,0,0}, + {18233,18352,18237 ,7462,7463,7465 ,0,0,0}, {18346,18352,18233 ,7461,7463,7462 ,0,0,0}, + {18238,18311,18310 ,7455,7464,7456 ,0,0,0}, {18237,18311,18238 ,7465,7464,7455 ,0,0,0}, + {18241,18239,18299 ,7457,7454,7458 ,0,0,0}, {18239,18310,18299 ,7454,7456,7458 ,0,0,0}, + {18411,18246,18301 ,7448,7493,7459 ,0,0,0}, {18246,18241,18301 ,7493,7457,7459 ,0,0,0}, + {18410,18264,18245 ,7449,7453,7450 ,0,0,0}, {18411,18245,18246 ,7448,7450,7493 ,0,0,0}, + {18395,18404,18263 ,7451,7494,7452 ,0,0,0}, {18410,18395,18264 ,7449,7451,7453 ,0,0,0}, + {18403,18255,18404 ,7444,7443,7494 ,0,0,0}, {18263,18404,18255 ,7452,7494,7443 ,0,0,0}, + {18265,18267,18408 ,7445,7442,7446 ,0,0,0}, {18267,18403,18408 ,7442,7444,7446 ,0,0,0}, + {18432,18256,18466 ,7436,7495,7447 ,0,0,0}, {18256,18265,18466 ,7495,7445,7447 ,0,0,0}, + {18360,18261,18257 ,7437,7439,7438 ,0,0,0}, {18432,18257,18256 ,7436,7438,7495 ,0,0,0}, + {18359,18361,18262 ,7440,7496,7441 ,0,0,0}, {18360,18359,18261 ,7437,7440,7439 ,0,0,0}, + {16433,18260,18361 ,4326,7434,7496 ,0,0,0}, {18262,18361,18260 ,7441,7496,7434 ,0,0,0}, + {19097,16381,16380 ,7497,763,7498 ,0,0,0}, {19098,18253,19099 ,7499,7500,7501 ,0,0,0}, + {19100,18266,18258 ,7502,7503,7504 ,0,0,0}, {19101,19102,18242 ,7505,7506,7507 ,0,0,0}, + {19103,19104,18250 ,7508,7509,7510 ,0,0,0}, {19105,18230,19106 ,7511,7512,7513 ,0,0,0}, + {18234,19107,19106 ,7514,7515,7513 ,0,0,0}, {19108,18222,19109 ,7516,7517,7518 ,0,0,0}, + {18221,19105,19109 ,7519,7511,7518 ,0,0,0}, {19110,18236,18231 ,7520,7521,7522 ,0,0,0}, + {18231,19108,19110 ,7522,7516,7520 ,0,0,0}, {18236,19111,18248 ,7521,7523,7524 ,0,0,0}, + {19111,18236,19110 ,7523,7521,7520 ,0,0,0}, {18249,18248,19112 ,7525,7524,7526 ,0,0,0}, + {19111,19112,18248 ,7523,7526,7524 ,0,0,0}, {16399,18249,19113 ,761,7525,7527 ,0,0,0}, + {18249,19112,19113 ,7525,7526,7527 ,0,0,0}, {16398,18249,16399 ,761,7525,761 ,0,0,0}, + {18221,19109,18222 ,7519,7518,7517 ,0,0,0}, {18231,18222,19108 ,7522,7517,7516 ,0,0,0}, + {18226,18230,19105 ,7528,7512,7511 ,0,0,0}, {18221,18226,19105 ,7519,7528,7511 ,0,0,0}, + {18240,19107,18234 ,7529,7515,7514 ,0,0,0}, {18230,18234,19106 ,7512,7514,7513 ,0,0,0}, + {18242,19102,18240 ,7507,7506,7529 ,0,0,0}, {19107,18240,19102 ,7515,7529,7506 ,0,0,0}, + {18250,19104,18242 ,7510,7509,7507 ,0,0,0}, {19104,19101,18242 ,7509,7505,7507 ,0,0,0}, + {18254,19098,19103 ,7530,7499,7508 ,0,0,0}, {18254,19103,18250 ,7530,7508,7510 ,0,0,0}, + {18253,18266,19099 ,7500,7503,7501 ,0,0,0}, {18254,18253,19098 ,7530,7500,7499 ,0,0,0}, + {19100,18258,19097 ,7502,7504,7497 ,0,0,0}, {19099,18266,19100 ,7501,7503,7502 ,0,0,0}, + {16381,19097,18259 ,763,7497,7531 ,0,0,0}, {19097,18258,18259 ,7497,7504,7531 ,0,0,0}, + {19112,19111,19110 ,7015,7532,7017 ,0,0,0}, {16385,19099,19100 ,7016,7015,7015 ,0,0,0}, + {19105,19108,19109 ,7533,7534,7535 ,0,0,0}, {19110,19105,19112 ,7017,7533,7015 ,0,0,0}, + {19112,19105,19113 ,7015,7533,7016 ,0,0,0}, {19105,19110,19108 ,7533,7017,7534 ,0,0,0}, + {19106,19113,19105 ,7536,7016,7533 ,0,0,0}, {19113,19107,16399 ,7016,730,7015 ,0,0,0}, + {19107,19113,19106 ,730,7016,7536 ,0,0,0}, {19104,16394,19101 ,7535,730,7320 ,0,0,0}, + {19107,19102,16399 ,730,6104,7015 ,0,0,0}, {19098,16388,19103 ,730,730,7534 ,0,0,0}, + {16391,19104,19103 ,7537,7535,7534 ,0,0,0}, {19097,16380,16384 ,7016,7015,730 ,0,0,0}, + {19100,16386,16385 ,7015,730,7016 ,0,0,0}, {16377,16365,16379 ,730,730,730 ,0,0,0}, + {16379,16363,16380 ,730,7016,7015 ,0,0,0}, {16376,16373,16377 ,730,730,730 ,0,0,0}, + {16365,16371,16370 ,730,7016,7016 ,0,0,0}, {16373,16365,16377 ,730,730,730 ,0,0,0}, + {16365,16364,16379 ,730,730,730 ,0,0,0}, {16365,16373,16371 ,730,730,7016 ,0,0,0}, + {16363,16384,16380 ,7016,730,7015 ,0,0,0}, {16364,16363,16379 ,730,7016,730 ,0,0,0}, + {16386,19100,16384 ,730,7015,730 ,0,0,0}, {16384,19100,19097 ,730,7015,7016 ,0,0,0}, + {16385,16388,19099 ,7016,730,7015 ,0,0,0}, {19103,16388,16390 ,7534,730,7537 ,0,0,0}, + {19099,16388,19098 ,7015,730,730 ,0,0,0}, {19103,16390,16391 ,7534,7537,7537 ,0,0,0}, + {16394,19102,19101 ,730,6104,7320 ,0,0,0}, {19104,16391,16394 ,7535,7537,730 ,0,0,0}, + {16399,19102,16396 ,7015,6104,730 ,0,0,0}, {16394,16396,19102 ,730,730,6104 ,0,0,0}, + {17308,17307,19114 ,7538,7539,7540 ,0,0,0}, {19115,17299,17308 ,7541,7542,7538 ,0,0,0}, + {19115,19116,17299 ,7541,82,7542 ,0,0,0}, {19114,19115,17308 ,7540,7541,7538 ,0,0,0}, + {17307,17678,19117 ,7539,7543,7544 ,0,0,0}, {17337,17336,19118 ,7545,7546,7547 ,0,0,0}, + {19119,19117,17678 ,7548,7544,7543 ,0,0,0}, {17678,17337,19119 ,7543,7545,7548 ,0,0,0}, + {19118,19119,17337 ,7547,7548,7545 ,0,0,0}, {17307,19117,19114 ,7539,7544,7540 ,0,0,0}, + {19118,17336,19120 ,7547,7546,7549 ,0,0,0}, {17335,19121,19120 ,7550,7551,7549 ,0,0,0}, + {19120,17336,17335 ,7549,7546,7550 ,0,0,0}, {19121,17335,17310 ,7551,7550,7552 ,0,0,0}, + {17323,19122,17310 ,7553,7554,7552 ,0,0,0}, {17323,17313,19123 ,7553,7555,7556 ,0,0,0}, + {17323,19123,19122 ,7553,7556,7554 ,0,0,0}, {19124,17304,19125 ,7557,7558,7559 ,0,0,0}, + {19123,17313,19124 ,7556,7555,7557 ,0,0,0}, {19124,17313,17304 ,7557,7555,7558 ,0,0,0}, + {17304,17306,19125 ,7558,7559,7559 ,0,0,0}, {19121,17310,19122 ,7551,7552,7554 ,0,0,0}, + {17300,19116,19126 ,7560,82,7561 ,0,0,0}, {19116,17300,17299 ,82,7560,7542 ,0,0,0}, + {19127,17342,19126 ,7562,7563,7561 ,0,0,0}, {17300,19126,17342 ,7560,7561,7563 ,0,0,0}, + {19127,19128,17556 ,7562,7564,7565 ,0,0,0}, {17556,17342,19127 ,7565,7563,7562 ,0,0,0}, + {17381,19128,19129 ,7566,7564,7567 ,0,0,0}, {19128,17381,17556 ,7564,7566,7565 ,0,0,0}, + {19130,17382,19129 ,7568,7569,7567 ,0,0,0}, {17381,19129,17382 ,7566,7567,7569 ,0,0,0}, + {19130,19131,17378 ,7568,7570,7571 ,0,0,0}, {17378,17382,19130 ,7571,7569,7568 ,0,0,0}, + {17346,19131,19132 ,7572,7570,7573 ,0,0,0}, {19131,17346,17378 ,7570,7572,7571 ,0,0,0}, + {19133,17365,19132 ,7574,7575,7573 ,0,0,0}, {17346,19132,17365 ,7572,7573,7575 ,0,0,0}, + {19133,19134,17366 ,7574,7576,7577 ,0,0,0}, {17366,17365,19133 ,7577,7575,7574 ,0,0,0}, + {17368,19134,19135 ,7578,7576,7579 ,0,0,0}, {19134,17368,17366 ,7576,7578,7577 ,0,0,0}, + {17368,19135,17369 ,7578,7579,7580 ,0,0,0}, {17369,19135,19136 ,7580,7579,7580 ,0,0,0}, + {18194,18200,19136 ,7581,7581,7581 ,0,0,0}, {19136,16806,18185 ,7581,7581,7581 ,0,0,0}, + {18185,18191,19136 ,7581,7581,7581 ,0,0,0}, {18205,19136,18200 ,7581,7581,7581 ,0,0,0}, + {18191,18194,19136 ,7581,7581,7581 ,0,0,0}, {18209,18168,19136 ,7581,7581,7581 ,0,0,0}, + {18209,19136,18205 ,7581,7581,7581 ,0,0,0}, {18168,18180,19136 ,7581,7581,7581 ,0,0,0}, + {17369,19136,18179 ,7581,7581,7581 ,0,0,0}, {18180,18179,19136 ,7581,7581,7581 ,0,0,0}, + {19125,17306,17752 ,7582,7582,7582 ,0,0,0}, {17752,17779,19125 ,7582,7582,7582 ,0,0,0}, + {19125,17765,17745 ,7582,7582,7582 ,0,0,0}, {17779,17765,19125 ,7582,7582,7582 ,0,0,0}, + {19125,17747,17761 ,7582,7582,7582 ,0,0,0}, {17745,17747,19125 ,7582,7582,7582 ,0,0,0}, + {19125,17754,17738 ,7582,7582,7582 ,0,0,0}, {17761,17754,19125 ,7582,7582,7582 ,0,0,0}, + {17742,19125,17737 ,7582,7582,7582 ,0,0,0}, {17738,17737,19125 ,7582,7582,7582 ,0,0,0}, + {19133,16811,16809 ,726,726,726 ,0,0,0}, {19126,19116,16811 ,726,726,726 ,0,0,0}, + {19135,19134,16809 ,726,726,726 ,0,0,0}, {16809,19134,19133 ,726,726,726 ,0,0,0}, + {16809,16803,19136 ,726,726,726 ,0,0,0}, {19136,19135,16809 ,726,726,726 ,0,0,0}, + {16812,16806,19136 ,7583,7583,726 ,0,0,0}, {16812,19136,16803 ,7583,726,726 ,0,0,0}, + {19133,19132,16811 ,726,726,726 ,0,0,0}, {16811,19131,19130 ,726,726,726 ,0,0,0}, + {19132,19131,16811 ,726,726,726 ,0,0,0}, {16811,19129,19128 ,726,726,726 ,0,0,0}, + {19130,19129,16811 ,726,726,726 ,0,0,0}, {16811,19127,19126 ,726,726,726 ,0,0,0}, + {19128,19127,16811 ,726,726,726 ,0,0,0}, {19115,16811,19116 ,726,726,726 ,0,0,0}, + {19114,19117,16811 ,726,726,726 ,0,0,0}, {19114,16811,19115 ,726,726,726 ,0,0,0}, + {19119,19118,16811 ,726,726,726 ,0,0,0}, {19119,16811,19117 ,726,726,726 ,0,0,0}, + {19120,19121,16811 ,726,726,726 ,0,0,0}, {19120,16811,19118 ,726,726,726 ,0,0,0}, + {19122,19123,16811 ,726,726,726 ,0,0,0}, {19122,16811,19121 ,726,726,726 ,0,0,0}, + {16811,19123,18863 ,726,726,726 ,0,0,0}, {19125,18863,19124 ,726,726,726 ,0,0,0}, + {18863,19123,19124 ,726,726,726 ,0,0,0}, {18864,18863,19125 ,726,726,726 ,0,0,0}, + {17742,18876,19125 ,7583,726,726 ,0,0,0}, {18864,19125,18876 ,726,726,726 ,0,0,0}, + {16341,19137,17595 ,7584,7585,7586 ,0,0,0}, {19138,17568,19139 ,7587,7588,7589 ,0,0,0}, + {17606,17528,19140 ,7590,7591,7592 ,0,0,0}, {17295,19141,17557 ,7593,7594,7595 ,0,0,0}, + {19142,19143,17298 ,4334,7596,7597 ,0,0,0}, {19144,17303,19145 ,7598,7599,7600 ,0,0,0}, + {17302,17560,19146 ,7601,7602,7603 ,0,0,0}, {17360,17352,19147 ,7604,7605,7606 ,0,0,0}, + {17356,19148,17352 ,7607,7608,7605 ,0,0,0}, {17357,19149,19150 ,7609,7610,7611 ,0,0,0}, + {17360,19151,17359 ,7604,7612,7613 ,0,0,0}, {19152,17370,19150 ,7614,7615,7611 ,0,0,0}, + {17357,19150,17370 ,7609,7611,7615 ,0,0,0}, {19152,19153,17363 ,7614,7616,7617 ,0,0,0}, + {17363,17370,19152 ,7617,7615,7614 ,0,0,0}, {17372,19153,19154 ,7618,7616,7619 ,0,0,0}, + {19153,17372,17363 ,7616,7618,7617 ,0,0,0}, {19155,17332,19154 ,7620,7621,7619 ,0,0,0}, + {17372,19154,17332 ,7618,7619,7621 ,0,0,0}, {19155,16360,16361 ,7620,7622,4289 ,0,0,0}, + {16361,17332,19155 ,4289,7621,7620 ,0,0,0}, {19147,17352,19148 ,7606,7605,7608 ,0,0,0}, + {19149,17359,19151 ,7610,7613,7612 ,0,0,0}, {17359,19149,17357 ,7613,7610,7609 ,0,0,0}, + {19147,19151,17360 ,7606,7612,7604 ,0,0,0}, {19144,19148,17356 ,7598,7608,7607 ,0,0,0}, + {17302,19146,19145 ,7601,7603,7600 ,0,0,0}, {17302,19145,17303 ,7601,7600,7599 ,0,0,0}, + {17356,17303,19144 ,7607,7599,7598 ,0,0,0}, {17560,19156,19146 ,7602,7623,7603 ,0,0,0}, + {19156,17560,17557 ,7623,7602,7595 ,0,0,0}, {19143,19141,17295 ,7596,7594,7593 ,0,0,0}, + {19141,19156,17557 ,7594,7623,7595 ,0,0,0}, {17298,19143,17295 ,7597,7596,7593 ,0,0,0}, + {17596,19138,19142 ,7624,7587,4334 ,0,0,0}, {17596,19142,17298 ,7624,4334,7597 ,0,0,0}, + {17568,17606,19139 ,7588,7590,7589 ,0,0,0}, {17596,17568,19138 ,7624,7588,7587 ,0,0,0}, + {17528,19137,19140 ,7591,7585,7592 ,0,0,0}, {19139,17606,19140 ,7589,7590,7592 ,0,0,0}, + {16341,17595,16339 ,7584,7586,4535 ,0,0,0}, {19137,17528,17595 ,7585,7591,7586 ,0,0,0}, + {19143,16352,19141 ,726,7625,726 ,0,0,0}, {19152,19150,19153 ,726,726,726 ,0,0,0}, + {19155,19154,19153 ,726,726,726 ,0,0,0}, {19151,19147,19149 ,726,726,726 ,0,0,0}, + {19153,19150,19147 ,726,726,726 ,0,0,0}, {19153,19147,19148 ,726,726,726 ,0,0,0}, + {19149,19147,19150 ,726,726,726 ,0,0,0}, {19148,19144,19155 ,726,726,726 ,0,0,0}, + {19155,19153,19148 ,726,726,726 ,0,0,0}, {19144,19145,16358 ,726,726,7626 ,0,0,0}, + {19144,16360,19155 ,726,726,726 ,0,0,0}, {19156,16354,16355 ,726,726,726 ,0,0,0}, + {16355,16358,19146 ,726,7626,726 ,0,0,0}, {19139,16343,16346 ,726,7627,726 ,0,0,0}, + {16348,16349,19142 ,726,7625,726 ,0,0,0}, {19140,16342,16343 ,7626,7627,7627 ,0,0,0}, + {16338,16323,16322 ,7626,7625,726 ,0,0,0}, {16341,16322,19137 ,726,726,726 ,0,0,0}, + {16334,16325,16335 ,726,7627,7625 ,0,0,0}, {16325,16334,16332 ,7627,726,726 ,0,0,0}, + {16334,16335,16329 ,726,7625,7627 ,0,0,0}, {16335,16338,16337 ,7625,7626,7628 ,0,0,0}, + {16325,16323,16335 ,7627,7625,7625 ,0,0,0}, {16325,16332,16326 ,7627,726,726 ,0,0,0}, + {16341,16338,16322 ,726,7626,726 ,0,0,0}, {16338,16335,16323 ,7626,7625,7625 ,0,0,0}, + {16320,19137,16322 ,726,726,726 ,0,0,0}, {19140,19137,16342 ,7626,726,7627 ,0,0,0}, + {16320,16342,19137 ,726,7627,726 ,0,0,0}, {19139,16346,19138 ,726,726,726 ,0,0,0}, + {16343,19139,19140 ,7627,726,7626 ,0,0,0}, {16348,19142,19138 ,726,726,726 ,0,0,0}, + {19138,16346,16348 ,726,726,726 ,0,0,0}, {16349,16352,19143 ,7625,7625,726 ,0,0,0}, + {19142,16349,19143 ,726,7625,726 ,0,0,0}, {19141,16354,19156 ,726,726,726 ,0,0,0}, + {19141,16352,16354 ,726,7625,726 ,0,0,0}, {16358,19145,19146 ,7626,726,726 ,0,0,0}, + {19146,19156,16355 ,726,726,726 ,0,0,0}, {16358,16360,19144 ,7626,726,726 ,0,0,0}, + {16302,19157,17576 ,4303,7629,7630 ,0,0,0}, {17499,17533,19158 ,7631,7632,7633 ,0,0,0}, + {17665,17577,19159 ,7634,7635,7636 ,0,0,0}, {17561,19160,17562 ,7637,7638,7639 ,0,0,0}, + {19161,19162,17498 ,7640,7641,7642 ,0,0,0}, {19163,19164,17343 ,7643,7644,7645 ,0,0,0}, + {19163,17563,19165 ,7643,7646,7647 ,0,0,0}, {19166,19167,17341 ,7648,7649,7650 ,0,0,0}, + {17341,17340,19166 ,7650,7651,7648 ,0,0,0}, {17524,19167,19168 ,7652,7649,7653 ,0,0,0}, + {19167,17524,17341 ,7649,7652,7650 ,0,0,0}, {19169,17523,19168 ,7654,7655,7653 ,0,0,0}, + {17524,19168,17523 ,7652,7653,7655 ,0,0,0}, {19169,16316,16317 ,7654,126,7656 ,0,0,0}, + {16317,17523,19169 ,7656,7655,7654 ,0,0,0}, {19160,17561,19162 ,7638,7637,7641 ,0,0,0}, + {19164,17340,17343 ,7644,7651,7645 ,0,0,0}, {19166,17340,19164 ,7648,7651,7644 ,0,0,0}, + {19158,17533,19170 ,7633,7632,7657 ,0,0,0}, {19165,17563,17562 ,7647,7646,7639 ,0,0,0}, + {19163,17343,17563 ,7643,7645,7646 ,0,0,0}, {19160,19165,17562 ,7638,7647,7639 ,0,0,0}, + {17498,19162,17561 ,7642,7641,7637 ,0,0,0}, {17499,19158,19161 ,7631,7633,7640 ,0,0,0}, + {19161,17498,17499 ,7640,7642,7631 ,0,0,0}, {17577,19157,19159 ,7635,7629,7636 ,0,0,0}, + {19170,17665,19159 ,7657,7634,7636 ,0,0,0}, {17533,17665,19170 ,7632,7634,7657 ,0,0,0}, + {16302,17576,16303 ,4303,7630,82 ,0,0,0}, {19157,17577,17576 ,7629,7635,7630 ,0,0,0}, + {19164,19163,16299 ,726,7658,7659 ,0,0,0}, {19157,19162,19158 ,7660,7661,726 ,0,0,0}, + {19157,19160,19162 ,7660,7661,7661 ,0,0,0}, {16301,19165,16302 ,7659,726,726 ,0,0,0}, + {19161,19158,19162 ,7661,726,7661 ,0,0,0}, {19159,19157,19158 ,7659,7660,726 ,0,0,0}, + {19160,19157,16302 ,7661,7660,726 ,0,0,0}, {19170,19159,19158 ,726,7659,726 ,0,0,0}, + {19160,16302,19165 ,7661,726,726 ,0,0,0}, {16299,19163,16301 ,7659,7658,7659 ,0,0,0}, + {16301,19163,19165 ,7659,7658,726 ,0,0,0}, {16297,19166,19164 ,726,5488,726 ,0,0,0}, + {16299,16297,19164 ,7659,726,726 ,0,0,0}, {16295,19166,16297 ,726,5488,726 ,0,0,0}, + {16295,19167,19166 ,726,7662,5488 ,0,0,0}, {19168,19167,16292 ,5471,7662,7661 ,0,0,0}, + {16295,16292,19167 ,726,7661,7662 ,0,0,0}, {16291,19168,16292 ,726,5471,7661 ,0,0,0}, + {19169,16291,16289 ,7663,726,7661 ,0,0,0}, {16291,19169,19168 ,726,7663,5471 ,0,0,0}, + {16288,16316,16289 ,7658,726,7661 ,0,0,0}, {19169,16289,16316 ,7663,7661,726 ,0,0,0}, + {16308,16304,16305 ,7658,7664,726 ,0,0,0}, {16308,16314,16304 ,7658,7665,7664 ,0,0,0}, + {16311,16308,16310 ,7666,7658,7667 ,0,0,0}, {16311,16314,16308 ,7666,7665,7658 ,0,0,0}, + {16316,16288,16314 ,726,7658,7665 ,0,0,0}, {16304,16314,16288 ,7664,7665,7658 ,0,0,0}, + {19171,16842,19172 ,726,726,726 ,0,0,0}, {16842,19173,19172 ,726,726,726 ,0,0,0}, + {19174,19175,16842 ,726,726,726 ,0,0,0}, {16842,19171,19174 ,726,726,726 ,0,0,0}, + {19176,19177,16842 ,726,726,726 ,0,0,0}, {19176,16842,19175 ,726,726,726 ,0,0,0}, + {16834,19178,19179 ,7583,726,7661 ,0,0,0}, {16842,19180,19181 ,726,726,726 ,0,0,0}, + {16834,19182,19183 ,7583,7658,7661 ,0,0,0}, {19184,16834,19185 ,726,7583,726 ,0,0,0}, + {19186,19187,16834 ,726,726,7583 ,0,0,0}, {19188,19185,16834 ,726,726,7583 ,0,0,0}, + {16834,19184,19189 ,7583,726,5489 ,0,0,0}, {19186,16834,19190 ,726,7583,7583 ,0,0,0}, + {16834,19187,19188 ,7583,726,726 ,0,0,0}, {16834,19191,19182 ,7583,726,7658 ,0,0,0}, + {19183,19190,16834 ,7661,7583,7583 ,0,0,0}, {19181,19178,16834 ,726,726,7583 ,0,0,0}, + {19191,16834,19179 ,726,7583,7661 ,0,0,0}, {16842,19177,19180 ,726,726,726 ,0,0,0}, + {16842,19181,16834 ,726,726,7583 ,0,0,0}, {16835,19189,16830 ,726,5489,7668 ,0,0,0}, + {19189,16835,16834 ,5489,726,7583 ,0,0,0}, {19173,16842,19192 ,726,726,726 ,0,0,0}, + {19193,16842,16840 ,726,726,726 ,0,0,0}, {16842,19193,19192 ,726,726,726 ,0,0,0}, + {19193,16840,16846 ,726,726,726 ,0,0,0}, {17296,17559,19191 ,7669,7670,7671 ,0,0,0}, + {19179,17297,17296 ,7672,7673,7669 ,0,0,0}, {19179,19178,17297 ,7672,7673,7673 ,0,0,0}, + {19191,19179,17296 ,7671,7672,7669 ,0,0,0}, {17559,17558,19182 ,7670,7674,7675 ,0,0,0}, + {17301,17355,19190 ,7676,7677,7678 ,0,0,0}, {19183,19182,17558 ,7679,7675,7674 ,0,0,0}, + {17558,17301,19183 ,7674,7676,7679 ,0,0,0}, {19190,19183,17301 ,7678,7679,7676 ,0,0,0}, + {17559,19182,19191 ,7670,7675,7671 ,0,0,0}, {19190,17355,19186 ,7678,7677,7680 ,0,0,0}, + {17354,19187,19186 ,7681,7682,7680 ,0,0,0}, {19186,17355,17354 ,7680,7677,7681 ,0,0,0}, + {19187,17354,17353 ,7682,7681,7683 ,0,0,0}, {17347,19188,17353 ,7684,7685,7683 ,0,0,0}, + {17347,17349,19185 ,7684,7686,7687 ,0,0,0}, {17347,19185,19188 ,7684,7687,7685 ,0,0,0}, + {19184,17350,19189 ,7688,7689,7690 ,0,0,0}, {19185,17349,19184 ,7687,7686,7688 ,0,0,0}, + {19184,17349,17350 ,7688,7686,7689 ,0,0,0}, {17350,17351,19189 ,7689,7690,7690 ,0,0,0}, + {19187,17353,19188 ,7682,7683,7685 ,0,0,0}, {17344,19178,19181 ,7691,7673,7692 ,0,0,0}, + {19178,17344,17297 ,7673,7691,7673 ,0,0,0}, {19180,17345,19181 ,7693,7694,7692 ,0,0,0}, + {17344,19181,17345 ,7691,7692,7694 ,0,0,0}, {19180,19177,17376 ,7693,7695,7696 ,0,0,0}, + {17376,17345,19180 ,7696,7694,7693 ,0,0,0}, {17377,19177,19176 ,7697,7695,7698 ,0,0,0}, + {19177,17377,17376 ,7695,7697,7696 ,0,0,0}, {19175,17599,19176 ,7699,7700,7698 ,0,0,0}, + {17377,19176,17599 ,7697,7698,7700 ,0,0,0}, {19175,19174,17380 ,7699,7701,7702 ,0,0,0}, + {17380,17599,19175 ,7702,7700,7699 ,0,0,0}, {17379,19174,19171 ,7703,7701,7704 ,0,0,0}, + {19174,17379,17380 ,7701,7703,7702 ,0,0,0}, {19172,17402,19171 ,7705,7706,7704 ,0,0,0}, + {17379,19171,17402 ,7703,7704,7706 ,0,0,0}, {19172,19173,17405 ,7705,7707,7708 ,0,0,0}, + {17405,17402,19172 ,7708,7706,7705 ,0,0,0}, {17406,19173,19192 ,7709,7707,7710 ,0,0,0}, + {19173,17406,17405 ,7707,7709,7708 ,0,0,0}, {17406,19192,17407 ,7709,7710,7711 ,0,0,0}, + {17407,19192,19193 ,7711,7710,7711 ,0,0,0}, {18108,19193,16846 ,7712,7712,7712 ,0,0,0}, + {19193,18109,18112 ,7712,7712,7712 ,0,0,0}, {18108,18109,19193 ,7712,7712,7712 ,0,0,0}, + {19193,18118,18123 ,7712,7712,7712 ,0,0,0}, {18112,18118,19193 ,7712,7712,7712 ,0,0,0}, + {19193,18127,18091 ,7712,7712,7712 ,0,0,0}, {18123,18127,19193 ,7712,7712,7712 ,0,0,0}, + {19193,18095,18094 ,7712,7712,7712 ,0,0,0}, {18091,18095,19193 ,7712,7712,7712 ,0,0,0}, + {19193,18094,17407 ,7712,7712,7712 ,0,0,0}, {18160,19189,17351 ,7713,7713,7713 ,0,0,0}, + {18160,18210,19189 ,7713,7713,7713 ,0,0,0}, {19189,18210,18196 ,7713,7713,7713 ,0,0,0}, + {18156,18162,19189 ,7713,7713,7713 ,0,0,0}, {18156,19189,18196 ,7713,7713,7713 ,0,0,0}, + {18162,18192,19189 ,7713,7713,7713 ,0,0,0}, {19189,18148,18147 ,7713,7713,7713 ,0,0,0}, + {18192,18148,19189 ,7713,7713,7713 ,0,0,0}, {16830,19189,18152 ,7713,7713,7713 ,0,0,0}, + {18147,18152,19189 ,7713,7713,7713 ,0,0,0}, {16265,19194,17614 ,1435,7714,7715 ,0,0,0}, + {19195,17605,19196 ,7716,7717,7718 ,0,0,0}, {17624,17613,19197 ,7719,7720,7721 ,0,0,0}, + {17285,19198,17386 ,7722,7723,7724 ,0,0,0}, {19199,19200,17627 ,7725,7726,7727 ,0,0,0}, + {19201,17408,19202 ,7728,7729,7730 ,0,0,0}, {17410,17387,19203 ,7731,7732,7733 ,0,0,0}, + {17292,17391,19204 ,7734,7735,7736 ,0,0,0}, {17396,19205,17391 ,7737,7738,7735 ,0,0,0}, + {17392,19206,19207 ,7739,7740,7741 ,0,0,0}, {17292,19208,17394 ,7734,7742,7743 ,0,0,0}, + {19209,17401,19207 ,7744,7745,7741 ,0,0,0}, {17392,19207,17401 ,7739,7741,7745 ,0,0,0}, + {19209,19210,17399 ,7744,7746,7747 ,0,0,0}, {17399,17401,19209 ,7747,7745,7744 ,0,0,0}, + {17412,19210,19211 ,7748,7746,7749 ,0,0,0}, {19210,17412,17399 ,7746,7748,7747 ,0,0,0}, + {19212,17398,19211 ,7750,7751,7749 ,0,0,0}, {17412,19211,17398 ,7748,7749,7751 ,0,0,0}, + {19212,16284,16285 ,7750,1359,1359 ,0,0,0}, {16285,17398,19212 ,1359,7751,7750 ,0,0,0}, + {19204,17391,19205 ,7736,7735,7738 ,0,0,0}, {19206,17394,19208 ,7740,7743,7742 ,0,0,0}, + {17394,19206,17392 ,7743,7740,7739 ,0,0,0}, {19204,19208,17292 ,7736,7742,7734 ,0,0,0}, + {19201,19205,17396 ,7728,7738,7737 ,0,0,0}, {17410,19203,19202 ,7731,7733,7730 ,0,0,0}, + {17410,19202,17408 ,7731,7730,7729 ,0,0,0}, {17396,17408,19201 ,7737,7729,7728 ,0,0,0}, + {17387,19213,19203 ,7732,7752,7733 ,0,0,0}, {19213,17387,17386 ,7752,7732,7724 ,0,0,0}, + {19200,19198,17285 ,7726,7723,7722 ,0,0,0}, {19198,19213,17386 ,7723,7752,7724 ,0,0,0}, + {17627,19200,17285 ,7727,7726,7722 ,0,0,0}, {17615,19195,19199 ,7753,7716,7725 ,0,0,0}, + {17615,19199,17627 ,7753,7725,7727 ,0,0,0}, {17605,17624,19196 ,7717,7719,7718 ,0,0,0}, + {17615,17605,19195 ,7753,7717,7716 ,0,0,0}, {17613,19194,19197 ,7720,7714,7721 ,0,0,0}, + {19196,17624,19197 ,7718,7719,7721 ,0,0,0}, {16265,17614,16263 ,1435,7715,1435 ,0,0,0}, + {19194,17613,17614 ,7714,7720,7715 ,0,0,0}, {19212,19211,19210 ,726,7628,7628 ,0,0,0}, + {16267,19207,16266 ,7627,7628,726 ,0,0,0}, {16246,16244,19208 ,7754,7625,7626 ,0,0,0}, + {19207,19206,16266 ,7628,726,726 ,0,0,0}, {16249,19201,16250 ,7755,726,7756 ,0,0,0}, + {16246,19208,19204 ,7754,7626,7626 ,0,0,0}, {19203,19213,16258 ,726,7628,7757 ,0,0,0}, + {19203,16256,19202 ,726,7758,7626 ,0,0,0}, {16259,16253,19198 ,7759,7760,7628 ,0,0,0}, + {19195,19196,19197 ,7625,7754,726 ,0,0,0}, {16262,16259,19200 ,7628,7759,7627 ,0,0,0}, + {16265,16262,19194 ,7628,7628,7761 ,0,0,0}, {19194,19195,19197 ,7761,7625,726 ,0,0,0}, + {16262,19199,19195 ,7628,7628,7625 ,0,0,0}, {19194,16262,19195 ,7761,7628,7625 ,0,0,0}, + {16262,16261,16259 ,7628,7762,7759 ,0,0,0}, {16262,19200,19199 ,7628,7627,7628 ,0,0,0}, + {16258,19198,16253 ,7757,7628,7760 ,0,0,0}, {19198,19200,16259 ,7628,7627,7759 ,0,0,0}, + {16258,19213,19198 ,7757,7628,7628 ,0,0,0}, {19202,16256,16250 ,7626,7758,7756 ,0,0,0}, + {16258,16256,19203 ,7757,7758,726 ,0,0,0}, {19205,19201,16249 ,7628,726,7755 ,0,0,0}, + {19201,19202,16250 ,726,7626,7756 ,0,0,0}, {19205,16247,19204 ,7628,7628,7626 ,0,0,0}, + {16247,19205,16249 ,7628,7628,7755 ,0,0,0}, {19206,19208,16244 ,726,7626,7625 ,0,0,0}, + {16247,16246,19204 ,7628,7754,7626 ,0,0,0}, {16270,19207,16267 ,7625,7628,7627 ,0,0,0}, + {16244,16266,19206 ,7625,726,726 ,0,0,0}, {19210,19209,16270 ,7628,7628,7625 ,0,0,0}, + {16270,19209,19207 ,7625,7628,7628 ,0,0,0}, {16272,19212,19210 ,7628,726,7628 ,0,0,0}, + {19210,16270,16272 ,7628,7625,7628 ,0,0,0}, {16272,16273,19212 ,7628,7628,726 ,0,0,0}, + {16276,16279,16282 ,7628,7628,7628 ,0,0,0}, {16273,16276,19212 ,7628,7628,726 ,0,0,0}, + {16282,19212,16276 ,7628,726,7628 ,0,0,0}, {16276,16278,16279 ,7628,726,7628 ,0,0,0}, + {19212,16282,16284 ,726,7628,7628 ,0,0,0}, {16226,19214,17575 ,1435,7763,7764 ,0,0,0}, + {17602,17604,19215 ,7765,7766,7767 ,0,0,0}, {17608,17609,19216 ,7768,7769,7770 ,0,0,0}, + {17574,19217,17573 ,7771,7772,7773 ,0,0,0}, {19218,19219,17603 ,7774,4221,7775 ,0,0,0}, + {19220,19221,17601 ,7776,7777,7778 ,0,0,0}, {19220,17600,19222 ,7776,7779,7780 ,0,0,0}, + {19223,19224,17417 ,7781,7782,7783 ,0,0,0}, {17417,17416,19223 ,7783,7784,7781 ,0,0,0}, + {17291,19224,19225 ,7785,7782,7786 ,0,0,0}, {19224,17291,17417 ,7782,7785,7783 ,0,0,0}, + {19226,17290,19225 ,7787,7788,7786 ,0,0,0}, {17291,19225,17290 ,7785,7786,7788 ,0,0,0}, + {19226,16240,16241 ,7787,1359,1359 ,0,0,0}, {16241,17290,19226 ,1359,7788,7787 ,0,0,0}, + {19217,17574,19219 ,7772,7771,4221 ,0,0,0}, {19221,17416,17601 ,7777,7784,7778 ,0,0,0}, + {19223,17416,19221 ,7781,7784,7777 ,0,0,0}, {19215,17604,19227 ,7767,7766,4227 ,0,0,0}, + {19222,17600,17573 ,7780,7779,7773 ,0,0,0}, {19220,17601,17600 ,7776,7778,7779 ,0,0,0}, + {19217,19222,17573 ,7772,7780,7773 ,0,0,0}, {17603,19219,17574 ,7775,4221,7771 ,0,0,0}, + {17602,19215,19218 ,7765,7767,7774 ,0,0,0}, {19218,17603,17602 ,7774,7775,7765 ,0,0,0}, + {17609,19214,19216 ,7769,7763,7770 ,0,0,0}, {19227,17608,19216 ,4227,7768,7770 ,0,0,0}, + {17604,17608,19227 ,7766,7768,4227 ,0,0,0}, {16226,17575,16227 ,1435,7764,1435 ,0,0,0}, + {19214,17609,17575 ,7763,7769,7764 ,0,0,0}, {16225,16234,16226 ,726,5471,7661 ,0,0,0}, + {19217,19220,19222 ,726,726,726 ,0,0,0}, {19223,19221,19220 ,7658,726,726 ,0,0,0}, + {19220,19217,19223 ,726,726,7658 ,0,0,0}, {19223,19219,19224 ,7658,726,7658 ,0,0,0}, + {19219,19223,19217 ,726,7658,726 ,0,0,0}, {19225,19224,19218 ,7658,7658,726 ,0,0,0}, + {19219,19218,19224 ,726,726,7658 ,0,0,0}, {19215,19226,19225 ,7658,7661,7658 ,0,0,0}, + {19225,19218,19215 ,7658,726,7658 ,0,0,0}, {19226,19227,16240 ,7661,7661,7664 ,0,0,0}, + {19227,19226,19215 ,7661,7661,7658 ,0,0,0}, {19227,19216,16240 ,7661,726,7664 ,0,0,0}, + {19216,19214,16238 ,726,726,7662 ,0,0,0}, {16232,16225,16223 ,7789,726,7658 ,0,0,0}, + {16213,16212,16219 ,5488,7668,7661 ,0,0,0}, {16229,16221,16228 ,7790,7664,7791 ,0,0,0}, + {16213,16219,16215 ,5488,7661,7792 ,0,0,0}, {16216,16215,16219 ,5488,7792,7661 ,0,0,0}, + {16221,16219,16228 ,7664,7661,7791 ,0,0,0}, {16228,16219,16212 ,7791,7661,7668 ,0,0,0}, + {16221,16229,16223 ,7664,7790,7658 ,0,0,0}, {16234,16225,16232 ,5471,726,7789 ,0,0,0}, + {16232,16223,16229 ,7789,7658,7790 ,0,0,0}, {16226,16235,19214 ,7661,7583,726 ,0,0,0}, + {16226,16234,16235 ,7661,5471,7583 ,0,0,0}, {19216,16238,16240 ,726,7662,7664 ,0,0,0}, + {16235,16238,19214 ,7583,7662,726 ,0,0,0}, {19228,16871,19229 ,7583,726,726 ,0,0,0}, + {19230,16867,19231 ,7668,726,5470 ,0,0,0}, {19230,19232,16867 ,7668,726,726 ,0,0,0}, + {16867,19233,19231 ,726,726,5470 ,0,0,0}, {19232,19234,16867 ,726,5489,726 ,0,0,0}, + {16867,19235,19236 ,726,7793,7794 ,0,0,0}, {19234,19235,16867 ,5489,7793,726 ,0,0,0}, + {16871,19237,16867 ,726,5470,726 ,0,0,0}, {19237,19233,16867 ,5470,726,726 ,0,0,0}, + {19238,19237,16871 ,726,5470,726 ,0,0,0}, {19239,16867,19236 ,7795,726,7794 ,0,0,0}, + {16871,19240,19238 ,726,5488,726 ,0,0,0}, {19239,19241,16867 ,7795,726,726 ,0,0,0}, + {19242,16867,19243 ,5485,726,7796 ,0,0,0}, {16867,19241,19243 ,726,726,7796 ,0,0,0}, + {16871,19244,19240 ,726,7583,5488 ,0,0,0}, {19245,16867,19242 ,7583,726,5485 ,0,0,0}, + {16871,19246,19244 ,726,726,7583 ,0,0,0}, {16871,19247,19248 ,726,5488,7583 ,0,0,0}, + {16871,19248,19246 ,726,7583,726 ,0,0,0}, {16868,19245,16863 ,5489,7583,7797 ,0,0,0}, + {16871,19228,19247 ,726,7583,5488 ,0,0,0}, {19245,16868,16867 ,7583,5489,726 ,0,0,0}, + {19229,16871,19249 ,726,726,7583 ,0,0,0}, {19250,16871,16878 ,726,726,726 ,0,0,0}, + {16871,19250,19249 ,726,726,7583 ,0,0,0}, {19250,16878,16877 ,726,726,726 ,0,0,0}, + {17286,17388,19230 ,7798,7799,7800 ,0,0,0}, {19231,17284,17286 ,7801,7802,7798 ,0,0,0}, + {19231,19233,17284 ,7801,7802,7802 ,0,0,0}, {19230,19231,17286 ,7800,7801,7798 ,0,0,0}, + {17388,17597,19232 ,7799,7803,7804 ,0,0,0}, {17409,17395,19235 ,7805,7806,7807 ,0,0,0}, + {19234,19232,17597 ,7808,7804,7803 ,0,0,0}, {17597,17409,19234 ,7803,7805,7808 ,0,0,0}, + {19235,19234,17409 ,7807,7808,7805 ,0,0,0}, {17388,19232,19230 ,7799,7804,7800 ,0,0,0}, + {19235,17395,19236 ,7807,7806,7809 ,0,0,0}, {17390,19239,19236 ,7810,7811,7809 ,0,0,0}, + {19236,17395,17390 ,7809,7806,7810 ,0,0,0}, {19239,17390,17389 ,7811,7810,7812 ,0,0,0}, + {17294,19241,17389 ,7813,7814,7812 ,0,0,0}, {17294,17373,19243 ,7813,7815,7816 ,0,0,0}, + {17294,19243,19241 ,7813,7816,7814 ,0,0,0}, {19242,17375,19245 ,7817,7818,7819 ,0,0,0}, + {19243,17373,19242 ,7816,7815,7817 ,0,0,0}, {19242,17373,17375 ,7817,7815,7818 ,0,0,0}, + {17375,17404,19245 ,7818,7819,7819 ,0,0,0}, {19239,17389,19241 ,7811,7812,7814 ,0,0,0}, + {17418,19233,19237 ,7820,7802,7821 ,0,0,0}, {19233,17418,17284 ,7802,7820,7802 ,0,0,0}, + {19238,17422,19237 ,7822,7823,7821 ,0,0,0}, {17418,19237,17422 ,7820,7821,7823 ,0,0,0}, + {19238,19240,17383 ,7822,7824,7825 ,0,0,0}, {17383,17422,19238 ,7825,7823,7822 ,0,0,0}, + {17384,19240,19244 ,7826,7824,7827 ,0,0,0}, {19240,17384,17383 ,7824,7826,7825 ,0,0,0}, + {19246,17459,19244 ,7828,7829,7827 ,0,0,0}, {17384,19244,17459 ,7826,7827,7829 ,0,0,0}, + {19246,19248,17287 ,7828,7830,7831 ,0,0,0}, {17287,17459,19246 ,7831,7829,7828 ,0,0,0}, + {17288,19248,19247 ,7832,7830,7833 ,0,0,0}, {19248,17288,17287 ,7830,7832,7831 ,0,0,0}, + {19228,17446,19247 ,7834,7835,7833 ,0,0,0}, {17288,19247,17446 ,7832,7833,7835 ,0,0,0}, + {19228,19229,17449 ,7834,7836,7837 ,0,0,0}, {17449,17446,19228 ,7837,7835,7834 ,0,0,0}, + {17453,19229,19249 ,7838,7836,7839 ,0,0,0}, {19229,17453,17449 ,7836,7838,7837 ,0,0,0}, + {17453,19249,17454 ,7838,7839,7840 ,0,0,0}, {17454,19249,19250 ,7840,7839,7840 ,0,0,0}, + {18021,19250,16877 ,7841,7841,7841 ,0,0,0}, {19250,18027,18030 ,7841,7841,7841 ,0,0,0}, + {18021,18027,19250 ,7841,7841,7841 ,0,0,0}, {19250,18036,18041 ,7841,7841,7841 ,0,0,0}, + {18030,18036,19250 ,7841,7841,7841 ,0,0,0}, {19250,18045,18004 ,7841,7841,7841 ,0,0,0}, + {18041,18045,19250 ,7841,7841,7841 ,0,0,0}, {19250,18016,18015 ,7841,7841,7841 ,0,0,0}, + {18004,18016,19250 ,7841,7841,7841 ,0,0,0}, {19250,18015,17454 ,7841,7841,7841 ,0,0,0}, + {18082,19245,17404 ,7842,7842,7842 ,0,0,0}, {18082,18128,19245 ,7842,7842,7842 ,0,0,0}, + {19245,18128,18114 ,7842,7842,7842 ,0,0,0}, {18076,18069,19245 ,7842,7842,7842 ,0,0,0}, + {18076,19245,18114 ,7842,7842,7842 ,0,0,0}, {18069,18110,19245 ,7842,7842,7842 ,0,0,0}, + {19245,18102,18064 ,7842,7842,7842 ,0,0,0}, {18110,18102,19245 ,7842,7842,7842 ,0,0,0}, + {16863,19245,18065 ,7842,7842,7842 ,0,0,0}, {18064,18065,19245 ,7842,7842,7842 ,0,0,0}, + {16189,19251,17639 ,1790,7843,4204 ,0,0,0}, {19252,17636,19253 ,7844,4198,4199 ,0,0,0}, + {17625,17638,19254 ,7845,7846,7847 ,0,0,0}, {17616,19255,17434 ,7848,7849,7850 ,0,0,0}, + {19256,19257,17649 ,7851,7852,7853 ,0,0,0}, {19258,17413,19259 ,7854,7855,7856 ,0,0,0}, + {17415,17432,19260 ,7857,7858,7859 ,0,0,0}, {17281,17280,19261 ,7860,7861,7862 ,0,0,0}, + {17436,19262,17280 ,7863,7864,7861 ,0,0,0}, {17440,19263,19264 ,7865,7866,7867 ,0,0,0}, + {17281,19265,17439 ,7860,7868,7869 ,0,0,0}, {19266,17445,19264 ,7870,7871,7867 ,0,0,0}, + {17440,19264,17445 ,7865,7867,7871 ,0,0,0}, {19266,19267,17443 ,7870,7872,7873 ,0,0,0}, + {17443,17445,19266 ,7873,7871,7870 ,0,0,0}, {17428,19267,19268 ,7874,7872,7875 ,0,0,0}, + {19267,17428,17443 ,7872,7874,7873 ,0,0,0}, {19269,17426,19268 ,7876,7877,7875 ,0,0,0}, + {17428,19268,17426 ,7874,7875,7877 ,0,0,0}, {19269,16208,16209 ,7876,1711,1711 ,0,0,0}, + {16209,17426,19269 ,1711,7877,7876 ,0,0,0}, {19261,17280,19262 ,7862,7861,7864 ,0,0,0}, + {19263,17439,19265 ,7866,7869,7868 ,0,0,0}, {17439,19263,17440 ,7869,7866,7865 ,0,0,0}, + {19261,19265,17281 ,7862,7868,7860 ,0,0,0}, {19258,19262,17436 ,7854,7864,7863 ,0,0,0}, + {17415,19260,19259 ,7857,7859,7856 ,0,0,0}, {17415,19259,17413 ,7857,7856,7855 ,0,0,0}, + {17436,17413,19258 ,7863,7855,7854 ,0,0,0}, {17432,19270,19260 ,7858,7878,7859 ,0,0,0}, + {19270,17432,17434 ,7878,7858,7850 ,0,0,0}, {19257,19255,17616 ,7852,7849,7848 ,0,0,0}, + {19255,19270,17434 ,7849,7878,7850 ,0,0,0}, {17649,19257,17616 ,7853,7852,7848 ,0,0,0}, + {17637,19252,19256 ,7879,7844,7851 ,0,0,0}, {17637,19256,17649 ,7879,7851,7853 ,0,0,0}, + {17636,17625,19253 ,4198,7845,4199 ,0,0,0}, {17637,17636,19252 ,7879,4198,7844 ,0,0,0}, + {17638,19251,19254 ,7846,7843,7847 ,0,0,0}, {19253,17625,19254 ,4199,7845,7847 ,0,0,0}, + {16189,17639,16187 ,1790,4204,1790 ,0,0,0}, {19251,17638,17639 ,7843,7846,4204 ,0,0,0}, + {19261,19262,19256 ,726,7880,7881 ,0,0,0}, {19251,19266,19264 ,7882,7627,7625 ,0,0,0}, + {19257,19258,19255 ,7883,7758,726 ,0,0,0}, {19270,19255,19258 ,7884,726,7758 ,0,0,0}, + {19259,19260,19270 ,7880,7761,7884 ,0,0,0}, {19258,19257,19262 ,7758,7883,7880 ,0,0,0}, + {19259,19270,19258 ,7880,7884,7758 ,0,0,0}, {19261,19256,19252 ,726,7881,7885 ,0,0,0}, + {19262,19257,19256 ,7880,7883,7881 ,0,0,0}, {19252,19253,19265 ,7885,7886,7758 ,0,0,0}, + {19265,19261,19252 ,7758,726,7885 ,0,0,0}, {19263,19253,19254 ,726,7886,7887 ,0,0,0}, + {19253,19263,19265 ,7886,726,7758 ,0,0,0}, {19264,19263,19254 ,7625,726,7887 ,0,0,0}, + {16189,19266,19251 ,7758,7627,7882 ,0,0,0}, {19251,19264,19254 ,7882,7625,7887 ,0,0,0}, + {19267,16189,16186 ,7627,7758,7755 ,0,0,0}, {16189,19267,19266 ,7758,7627,7627 ,0,0,0}, + {16185,19268,16186 ,7625,726,7755 ,0,0,0}, {19267,16186,19268 ,7627,7755,726 ,0,0,0}, + {16185,16183,19269 ,7625,7761,726 ,0,0,0}, {19269,19268,16185 ,726,726,7625 ,0,0,0}, + {16208,16183,16177 ,7627,7761,7625 ,0,0,0}, {16183,16208,19269 ,7761,7627,726 ,0,0,0}, + {16174,16202,16180 ,726,7627,7625 ,0,0,0}, {16182,16206,16177 ,7880,726,7625 ,0,0,0}, + {16200,16173,16197 ,7625,726,726 ,0,0,0}, {16194,16170,16191 ,7627,7625,7625 ,0,0,0}, + {16196,16197,16171 ,726,726,7625 ,0,0,0}, {16191,16168,16190 ,7625,7625,726 ,0,0,0}, + {16170,16194,16196 ,7625,7627,726 ,0,0,0}, {16171,16170,16196 ,7625,7625,726 ,0,0,0}, + {16191,16170,16168 ,7625,7625,7625 ,0,0,0}, {16174,16173,16200 ,726,726,7625 ,0,0,0}, + {16171,16197,16173 ,7625,726,726 ,0,0,0}, {16203,16180,16202 ,726,7625,7627 ,0,0,0}, + {16202,16174,16200 ,7627,726,7625 ,0,0,0}, {16182,16203,16206 ,7880,726,726 ,0,0,0}, + {16203,16182,16180 ,726,7880,7625 ,0,0,0}, {16206,16208,16177 ,726,7627,7625 ,0,0,0}, + {16150,19271,17569 ,1790,7888,7889 ,0,0,0}, {17621,17610,19272 ,7890,7891,7892 ,0,0,0}, + {17623,17570,19273 ,7893,7894,7895 ,0,0,0}, {17611,19274,17612 ,7896,7897,4137 ,0,0,0}, + {19275,19276,17622 ,7898,7899,7900 ,0,0,0}, {19277,19278,17620 ,7901,7902,7903 ,0,0,0}, + {19277,17619,19279 ,7901,7904,7905 ,0,0,0}, {19280,19281,17455 ,7906,7907,7908 ,0,0,0}, + {17455,17456,19280 ,7908,7909,7906 ,0,0,0}, {17618,19281,19282 ,7910,7907,7911 ,0,0,0}, + {19281,17618,17455 ,7907,7910,7908 ,0,0,0}, {19283,17429,19282 ,7912,7913,7911 ,0,0,0}, + {17618,19282,17429 ,7910,7911,7913 ,0,0,0}, {19283,16164,16165 ,7912,1711,1711 ,0,0,0}, + {16165,17429,19283 ,1711,7913,7912 ,0,0,0}, {19274,17611,19276 ,7897,7896,7899 ,0,0,0}, + {19278,17456,17620 ,7902,7909,7903 ,0,0,0}, {19280,17456,19278 ,7906,7909,7902 ,0,0,0}, + {19272,17610,19284 ,7892,7891,7914 ,0,0,0}, {19279,17619,17612 ,7905,7904,4137 ,0,0,0}, + {19277,17620,17619 ,7901,7903,7904 ,0,0,0}, {19274,19279,17612 ,7897,7905,4137 ,0,0,0}, + {17622,19276,17611 ,7900,7899,7896 ,0,0,0}, {17621,19272,19275 ,7890,7892,7898 ,0,0,0}, + {19275,17622,17621 ,7898,7900,7890 ,0,0,0}, {17570,19271,19273 ,7894,7888,7895 ,0,0,0}, + {19284,17623,19273 ,7914,7893,7895 ,0,0,0}, {17610,17623,19284 ,7891,7893,7914 ,0,0,0}, + {16150,17569,16151 ,1790,7889,1790 ,0,0,0}, {19271,17570,17569 ,7888,7894,7889 ,0,0,0}, + {19277,16158,19278 ,726,7658,726 ,0,0,0}, {19282,19281,16162 ,726,726,7660 ,0,0,0}, + {16164,19283,19282 ,726,7660,726 ,0,0,0}, {19277,19279,16156 ,726,726,7658 ,0,0,0}, + {16159,16162,19280 ,7660,7660,7659 ,0,0,0}, {19276,19275,16136 ,7659,726,7661 ,0,0,0}, + {19276,16152,19274 ,7659,726,726 ,0,0,0}, {16139,16137,19272 ,7915,7916,726 ,0,0,0}, + {19271,16145,16143 ,7658,7917,5475 ,0,0,0}, {19273,16140,19284 ,7658,726,7659 ,0,0,0}, + {16150,16149,16145 ,7918,7918,7917 ,0,0,0}, {16147,16145,16149 ,7661,7917,7918 ,0,0,0}, + {19273,19271,16143 ,7658,7658,5475 ,0,0,0}, {19271,16150,16145 ,7658,7918,7917 ,0,0,0}, + {16140,19273,16143 ,726,7658,5475 ,0,0,0}, {19284,16140,16139 ,7659,726,7915 ,0,0,0}, + {19272,16137,19275 ,726,7916,726 ,0,0,0}, {19284,16139,19272 ,7659,7915,726 ,0,0,0}, + {19276,16136,16152 ,7659,7661,726 ,0,0,0}, {19275,16137,16136 ,726,7916,7661 ,0,0,0}, + {16153,19279,19274 ,7664,726,726 ,0,0,0}, {16152,16153,19274 ,726,7664,726 ,0,0,0}, + {16158,19277,16156 ,7658,726,7658 ,0,0,0}, {16156,19279,16153 ,7658,726,7664 ,0,0,0}, + {19278,16159,19280 ,726,7660,7659 ,0,0,0}, {19278,16158,16159 ,726,7658,7660 ,0,0,0}, + {19282,16162,16164 ,726,7660,726 ,0,0,0}, {19281,19280,16162 ,726,7659,7660 ,0,0,0}, + {16908,19285,19286 ,726,5469,7919 ,0,0,0}, {19287,16908,19288 ,7920,726,7921 ,0,0,0}, + {16908,19287,19285 ,726,7920,5469 ,0,0,0}, {16908,19289,19288 ,726,726,7921 ,0,0,0}, + {19290,16908,19286 ,7922,726,7919 ,0,0,0}, {19289,16908,19291 ,726,726,7920 ,0,0,0}, + {19290,19292,16908 ,7922,7923,726 ,0,0,0}, {16908,19293,19294 ,726,7924,7925 ,0,0,0}, + {19294,19295,16908 ,7925,7926,726 ,0,0,0}, {19292,19293,16908 ,7923,7924,726 ,0,0,0}, + {19296,19297,16908 ,5472,7927,726 ,0,0,0}, {19296,16908,19295 ,5472,726,7926 ,0,0,0}, + {19298,19299,16908 ,7928,7929,726 ,0,0,0}, {19298,16908,19297 ,7928,726,7927 ,0,0,0}, + {19300,19301,16908 ,726,5489,726 ,0,0,0}, {19300,16908,19299 ,726,726,7929 ,0,0,0}, + {16908,19302,16907 ,726,5488,7583 ,0,0,0}, {19302,16908,19301 ,5488,726,5489 ,0,0,0}, + {16907,19303,19304 ,7583,5470,5489 ,0,0,0}, {19302,19303,16907 ,5488,5470,7583 ,0,0,0}, + {16903,16904,19304 ,5489,5488,5489 ,0,0,0}, {16907,19304,16904 ,7583,5489,5488 ,0,0,0}, + {16898,16903,19304 ,5489,5489,5489 ,0,0,0}, {16908,18875,19291 ,726,5489,7920 ,0,0,0}, + {18875,19305,19306 ,5489,5470,5488 ,0,0,0}, {19291,18875,19306 ,7920,5489,5488 ,0,0,0}, + {19307,18875,18874 ,5489,5489,726 ,0,0,0}, {18875,19307,19305 ,5489,5489,5470 ,0,0,0}, + {17938,19307,18873 ,5489,5489,7583 ,0,0,0}, {18874,18873,19307 ,726,7583,5489 ,0,0,0}, + {17472,17433,19295 ,7930,7931,7932 ,0,0,0}, {19294,17474,17472 ,7933,7934,7930 ,0,0,0}, + {19294,19293,17474 ,7933,7935,7934 ,0,0,0}, {19295,19294,17472 ,7932,7933,7930 ,0,0,0}, + {17433,17617,19296 ,7931,7936,7937 ,0,0,0}, {17414,17435,19298 ,7938,7939,7940 ,0,0,0}, + {19297,19296,17617 ,7941,7937,7936 ,0,0,0}, {17617,17414,19297 ,7936,7938,7941 ,0,0,0}, + {19298,19297,17414 ,7940,7941,7938 ,0,0,0}, {17433,19296,19295 ,7931,7937,7932 ,0,0,0}, + {19298,17435,19299 ,7940,7939,7942 ,0,0,0}, {17437,19300,19299 ,7943,7944,7942 ,0,0,0}, + {19299,17435,17437 ,7942,7939,7943 ,0,0,0}, {19300,17437,17282 ,7944,7943,7945 ,0,0,0}, + {17425,19301,17282 ,7946,7947,7945 ,0,0,0}, {17425,17438,19302 ,7946,7948,7949 ,0,0,0}, + {17425,19302,19301 ,7946,7949,7947 ,0,0,0}, {19303,17430,19304 ,7950,7951,7952 ,0,0,0}, + {19302,17438,19303 ,7949,7948,7950 ,0,0,0}, {19303,17438,17430 ,7950,7948,7951 ,0,0,0}, + {17430,17431,19304 ,7951,7952,7952 ,0,0,0}, {19300,17282,19301 ,7944,7945,7947 ,0,0,0}, + {17594,19293,19292 ,7953,7935,7954 ,0,0,0}, {19293,17594,17474 ,7935,7953,7934 ,0,0,0}, + {19290,17473,19292 ,7955,7956,7954 ,0,0,0}, {17594,19292,17473 ,7953,7954,7956 ,0,0,0}, + {19290,19286,17457 ,7955,7957,7958 ,0,0,0}, {17457,17473,19290 ,7958,7956,7955 ,0,0,0}, + {17458,19286,19285 ,7959,7957,7960 ,0,0,0}, {19286,17458,17457 ,7957,7959,7958 ,0,0,0}, + {19287,17631,19285 ,7961,7962,7960 ,0,0,0}, {17458,19285,17631 ,7959,7960,7962 ,0,0,0}, + {19287,19288,17571 ,7961,7963,7964 ,0,0,0}, {17571,17631,19287 ,7964,7962,7961 ,0,0,0}, + {17572,19288,19289 ,7965,7963,7966 ,0,0,0}, {19288,17572,17571 ,7963,7965,7964 ,0,0,0}, + {19291,17465,19289 ,7967,7968,7966 ,0,0,0}, {17572,19289,17465 ,7965,7966,7968 ,0,0,0}, + {19291,19306,17493 ,7967,7969,7970 ,0,0,0}, {17493,17465,19291 ,7970,7968,7967 ,0,0,0}, + {17494,19306,19305 ,7971,7969,7972 ,0,0,0}, {19306,17494,17493 ,7969,7971,7970 ,0,0,0}, + {17494,19305,17496 ,7971,7972,7973 ,0,0,0}, {17496,19305,19307 ,7973,7972,7973 ,0,0,0}, + {17948,17954,19307 ,7974,7974,7974 ,0,0,0}, {19307,17938,17939 ,7974,7974,7974 ,0,0,0}, + {17939,17945,19307 ,7974,7974,7974 ,0,0,0}, {17959,19307,17954 ,7974,7974,7974 ,0,0,0}, + {17945,17948,19307 ,7974,7974,7974 ,0,0,0}, {17963,17916,19307 ,7974,7974,7974 ,0,0,0}, + {17963,19307,17959 ,7974,7974,7974 ,0,0,0}, {17916,17928,19307 ,7974,7974,7974 ,0,0,0}, + {17496,19307,17927 ,7974,7974,7974 ,0,0,0}, {17928,17927,19307 ,7974,7974,7974 ,0,0,0}, + {19304,17431,17996 ,7975,7975,7975 ,0,0,0}, {17996,18046,19304 ,7975,7975,7975 ,0,0,0}, + {19304,18032,17992 ,7975,7975,7975 ,0,0,0}, {18046,18032,19304 ,7975,7975,7975 ,0,0,0}, + {19304,17998,18028 ,7975,7975,7975 ,0,0,0}, {17992,17998,19304 ,7975,7975,7975 ,0,0,0}, + {19304,17984,17983 ,7975,7975,7975 ,0,0,0}, {18028,17984,19304 ,7975,7975,7975 ,0,0,0}, + {16898,19304,17988 ,7975,7975,7975 ,0,0,0}, {17983,17988,19304 ,7975,7975,7975 ,0,0,0}, + {16113,19308,17644 ,126,7976,7977 ,0,0,0}, {19309,17646,19310 ,7978,7979,7980 ,0,0,0}, + {17660,17647,19311 ,7981,7982,7983 ,0,0,0}, {17461,19312,17452 ,7984,7985,7986 ,0,0,0}, + {19313,19314,17628 ,7987,7988,7989 ,0,0,0}, {19315,17479,19316 ,7990,7991,7992 ,0,0,0}, + {17497,17464,19317 ,7993,7994,7995 ,0,0,0}, {17489,17490,19318 ,7996,7997,7998 ,0,0,0}, + {17480,19319,17490 ,7999,8000,7997 ,0,0,0}, {17481,19320,19321 ,8001,8002,8003 ,0,0,0}, + {17489,19322,17483 ,7996,8004,8005 ,0,0,0}, {19323,17484,19321 ,8006,8007,8003 ,0,0,0}, + {17481,19321,17484 ,8001,8003,8007 ,0,0,0}, {19323,19324,17487 ,8006,8008,8009 ,0,0,0}, + {17487,17484,19323 ,8009,8007,8006 ,0,0,0}, {17526,19324,19325 ,8010,8008,8011 ,0,0,0}, + {19324,17526,17487 ,8008,8010,8009 ,0,0,0}, {19326,17488,19325 ,8012,8013,8011 ,0,0,0}, + {17526,19325,17488 ,8010,8011,8013 ,0,0,0}, {19326,16132,16133 ,8012,8014,4346 ,0,0,0}, + {16133,17488,19326 ,4346,8013,8012 ,0,0,0}, {19318,17490,19319 ,7998,7997,8000 ,0,0,0}, + {19320,17483,19322 ,8002,8005,8004 ,0,0,0}, {17483,19320,17481 ,8005,8002,8001 ,0,0,0}, + {19318,19322,17489 ,7998,8004,7996 ,0,0,0}, {19315,19319,17480 ,7990,8000,7999 ,0,0,0}, + {17497,19317,19316 ,7993,7995,7992 ,0,0,0}, {17497,19316,17479 ,7993,7992,7991 ,0,0,0}, + {17480,17479,19315 ,7999,7991,7990 ,0,0,0}, {17464,19327,19317 ,7994,8015,7995 ,0,0,0}, + {19327,17464,17452 ,8015,7994,7986 ,0,0,0}, {19314,19312,17461 ,7988,7985,7984 ,0,0,0}, + {19312,19327,17452 ,7985,8015,7986 ,0,0,0}, {17628,19314,17461 ,7989,7988,7984 ,0,0,0}, + {17645,19309,19313 ,8016,7978,7987 ,0,0,0}, {17645,19313,17628 ,8016,7987,7989 ,0,0,0}, + {17646,17660,19310 ,7979,7981,7980 ,0,0,0}, {17645,17646,19309 ,8016,7979,7978 ,0,0,0}, + {17647,19308,19311 ,7982,7976,7983 ,0,0,0}, {19310,17660,19311 ,7980,7981,7983 ,0,0,0}, + {16113,17644,16111 ,126,7977,4289 ,0,0,0}, {19308,17647,17644 ,7976,7982,7977 ,0,0,0}, + {19326,19325,19324 ,7625,7880,7758 ,0,0,0}, {16118,19309,19310 ,7626,7880,726 ,0,0,0}, + {19324,19321,19318 ,7758,8017,8018 ,0,0,0}, {19324,19323,19321 ,7758,7758,8017 ,0,0,0}, + {19320,19318,19321 ,8017,8018,8017 ,0,0,0}, {19320,19322,19318 ,8017,7758,8018 ,0,0,0}, + {19319,19324,19318 ,8019,7758,8018 ,0,0,0}, {19319,19315,19326 ,8019,7884,7625 ,0,0,0}, + {19326,19324,19319 ,7625,7758,8019 ,0,0,0}, {19315,19316,16130 ,7884,8020,7625 ,0,0,0}, + {19315,16132,19326 ,7884,7625,7625 ,0,0,0}, {19327,16126,16127 ,8021,7625,726 ,0,0,0}, + {16127,16130,19317 ,726,7625,7257 ,0,0,0}, {16120,16121,19313 ,726,726,8017 ,0,0,0}, + {16124,19312,19314 ,7625,8022,7761 ,0,0,0}, {16115,19311,16114 ,7626,726,7626 ,0,0,0}, + {19310,16115,16118 ,726,7626,7626 ,0,0,0}, {16110,16095,16094 ,7625,726,726 ,0,0,0}, + {16113,16094,19308 ,7625,726,7625 ,0,0,0}, {16106,16097,16107 ,726,726,7625 ,0,0,0}, + {16097,16106,16104 ,726,726,726 ,0,0,0}, {16101,16106,16107 ,7625,726,7625 ,0,0,0}, + {16109,16107,16110 ,7625,7625,7625 ,0,0,0}, {16107,16097,16095 ,7625,726,726 ,0,0,0}, + {16098,16097,16104 ,726,726,726 ,0,0,0}, {16094,16113,16110 ,726,7625,7625 ,0,0,0}, + {16095,16110,16107 ,726,7625,7625 ,0,0,0}, {19308,16092,16114 ,7625,726,7626 ,0,0,0}, + {16092,19308,16094 ,726,7625,726 ,0,0,0}, {19311,16115,19310 ,726,7626,726 ,0,0,0}, + {19308,16114,19311 ,7625,7626,726 ,0,0,0}, {16118,16120,19309 ,7626,726,7880 ,0,0,0}, + {19313,16121,19314 ,8017,726,7761 ,0,0,0}, {19309,16120,19313 ,7880,726,8017 ,0,0,0}, + {19314,16121,16124 ,7761,726,7625 ,0,0,0}, {19312,16126,19327 ,8022,7625,8021 ,0,0,0}, + {19312,16124,16126 ,8022,7625,7625 ,0,0,0}, {16130,19316,19317 ,7625,8020,7257 ,0,0,0}, + {19317,19327,16127 ,7257,8021,726 ,0,0,0}, {16130,16132,19315 ,7625,7625,7884 ,0,0,0}, + {16074,19328,17643 ,8023,8024,8025 ,0,0,0}, {17385,17588,19329 ,8026,8027,8028 ,0,0,0}, + {17695,17641,19330 ,8029,8030,8031 ,0,0,0}, {17634,19331,17626 ,8032,8033,8034 ,0,0,0}, + {19332,19333,17593 ,8035,8036,8037 ,0,0,0}, {19334,19335,17633 ,8038,8039,8040 ,0,0,0}, + {19334,17635,19336 ,8038,8041,8042 ,0,0,0}, {19337,19338,17632 ,8043,8044,8045 ,0,0,0}, + {17632,17532,19337 ,8045,8046,8043 ,0,0,0}, {17529,19338,19339 ,8047,8044,8048 ,0,0,0}, + {19338,17529,17632 ,8044,8047,8045 ,0,0,0}, {19340,17530,19339 ,8049,8050,8048 ,0,0,0}, + {17529,19339,17530 ,8047,8048,8050 ,0,0,0}, {19340,16088,16089 ,8049,82,82 ,0,0,0}, + {16089,17530,19340 ,82,8050,8049 ,0,0,0}, {19331,17634,19333 ,8033,8032,8036 ,0,0,0}, + {19335,17532,17633 ,8039,8046,8040 ,0,0,0}, {19337,17532,19335 ,8043,8046,8039 ,0,0,0}, + {19329,17588,19341 ,8028,8027,8051 ,0,0,0}, {19336,17635,17626 ,8042,8041,8034 ,0,0,0}, + {19334,17633,17635 ,8038,8040,8041 ,0,0,0}, {19331,19336,17626 ,8033,8042,8034 ,0,0,0}, + {17593,19333,17634 ,8037,8036,8032 ,0,0,0}, {17385,19329,19332 ,8026,8028,8035 ,0,0,0}, + {19332,17593,17385 ,8035,8037,8026 ,0,0,0}, {17641,19328,19330 ,8030,8024,8031 ,0,0,0}, + {19341,17695,19330 ,8051,8029,8031 ,0,0,0}, {17588,17695,19341 ,8027,8029,8051 ,0,0,0}, + {16074,17643,16075 ,8023,8025,8052 ,0,0,0}, {19328,17641,17643 ,8024,8030,8025 ,0,0,0}, + {19334,16071,19335 ,726,726,726 ,0,0,0}, {19338,16067,16064 ,726,7661,726 ,0,0,0}, + {19331,19333,19328 ,726,7660,726 ,0,0,0}, {19336,16074,16073 ,726,726,726 ,0,0,0}, + {19330,19328,19329 ,7661,726,726 ,0,0,0}, {19329,19341,19330 ,726,7658,7661 ,0,0,0}, + {19329,19333,19332 ,726,7660,726 ,0,0,0}, {19328,16074,19331 ,726,726,726 ,0,0,0}, + {19333,19329,19328 ,7660,726,726 ,0,0,0}, {19336,16073,19334 ,726,726,726 ,0,0,0}, + {19331,16074,19336 ,726,726,726 ,0,0,0}, {19334,16073,16071 ,726,726,726 ,0,0,0}, + {19335,16069,19337 ,726,7658,726 ,0,0,0}, {19335,16071,16069 ,726,726,7658 ,0,0,0}, + {19338,19337,16067 ,726,726,7661 ,0,0,0}, {16069,16067,19337 ,7658,7661,726 ,0,0,0}, + {19338,16064,19339 ,726,726,726 ,0,0,0}, {16063,19340,19339 ,726,726,726 ,0,0,0}, + {19339,16064,16063 ,726,726,726 ,0,0,0}, {19340,16061,16088 ,726,726,726 ,0,0,0}, + {16061,19340,16063 ,726,726,726 ,0,0,0}, {16061,16060,16088 ,726,726,726 ,0,0,0}, + {16080,16076,16077 ,7659,726,726 ,0,0,0}, {16080,16086,16076 ,7659,726,726 ,0,0,0}, + {16083,16080,16082 ,726,7659,726 ,0,0,0}, {16083,16086,16080 ,726,726,7659 ,0,0,0}, + {16088,16060,16086 ,726,726,726 ,0,0,0}, {16076,16086,16060 ,726,726,726 ,0,0,0}, + {19342,19343,18870 ,726,8053,7583 ,0,0,0}, {18872,19344,18871 ,726,726,726 ,0,0,0}, + {19343,19345,18870 ,8053,7922,7583 ,0,0,0}, {19342,18870,19346 ,726,7583,5472 ,0,0,0}, + {18870,19347,19348 ,7583,7664,5488 ,0,0,0}, {19345,19347,18870 ,7922,7664,7583 ,0,0,0}, + {19349,19350,18870 ,7920,726,7583 ,0,0,0}, {19348,19351,18870 ,5488,5471,7583 ,0,0,0}, + {19352,19353,18872 ,7664,7583,726 ,0,0,0}, {18872,19354,19355 ,726,5488,7664 ,0,0,0}, + {19356,18872,19357 ,726,726,726 ,0,0,0}, {19358,19359,18872 ,7664,7664,726 ,0,0,0}, + {19360,19357,18872 ,726,726,726 ,0,0,0}, {18872,19356,19344 ,726,726,726 ,0,0,0}, + {19358,18872,19361 ,7664,726,7664 ,0,0,0}, {18872,19359,19360 ,726,7664,726 ,0,0,0}, + {18872,19353,19361 ,726,7583,7664 ,0,0,0}, {18872,19355,19362 ,726,7664,726 ,0,0,0}, + {18872,19362,19352 ,726,726,7664 ,0,0,0}, {19350,18872,18870 ,726,726,7583 ,0,0,0}, + {19350,19354,18872 ,726,5488,726 ,0,0,0}, {18870,19351,19349 ,7583,5471,7920 ,0,0,0}, + {17899,18871,19344 ,726,726,726 ,0,0,0}, {19346,18870,19363 ,5472,7583,7793 ,0,0,0}, + {19364,18870,18869 ,5471,7583,7664 ,0,0,0}, {18870,19364,19363 ,7583,5471,7793 ,0,0,0}, + {19364,18869,17844 ,5471,7664,7920 ,0,0,0}, {17451,17450,19362 ,8054,8055,8056 ,0,0,0}, + {19355,17460,17451 ,8057,8058,8054 ,0,0,0}, {19355,19354,17460 ,8057,8058,8058 ,0,0,0}, + {19362,19355,17451 ,8056,8057,8054 ,0,0,0}, {17450,17629,19352 ,8055,8059,8060 ,0,0,0}, + {17527,17471,19361 ,8061,8062,8063 ,0,0,0}, {19353,19352,17629 ,8064,8060,8059 ,0,0,0}, + {17629,17527,19353 ,8059,8061,8064 ,0,0,0}, {19361,19353,17527 ,8063,8064,8061 ,0,0,0}, + {17450,19352,19362 ,8055,8060,8056 ,0,0,0}, {19361,17471,19358 ,8063,8062,8065 ,0,0,0}, + {17470,19359,19358 ,8066,8067,8065 ,0,0,0}, {19358,17471,17470 ,8065,8062,8066 ,0,0,0}, + {19359,17470,17630 ,8067,8066,8068 ,0,0,0}, {17478,19360,17630 ,8069,8070,8068 ,0,0,0}, + {17478,17477,19357 ,8069,8071,8072 ,0,0,0}, {17478,19357,19360 ,8069,8072,8070 ,0,0,0}, + {19356,17492,19344 ,8073,8074,8075 ,0,0,0}, {19357,17477,19356 ,8072,8071,8073 ,0,0,0}, + {19356,17477,17492 ,8073,8071,8074 ,0,0,0}, {17492,17495,19344 ,8074,8075,8075 ,0,0,0}, + {19359,17630,19360 ,8067,8068,8070 ,0,0,0}, {17283,19354,19350 ,8076,8058,8077 ,0,0,0}, + {19354,17283,17460 ,8058,8076,8058 ,0,0,0}, {19349,17531,19350 ,8078,8079,8077 ,0,0,0}, + {17283,19350,17531 ,8076,8077,8079 ,0,0,0}, {19349,19351,17475 ,8078,8080,8081 ,0,0,0}, + {17475,17531,19349 ,8081,8079,8078 ,0,0,0}, {17476,19351,19348 ,8082,8080,8083 ,0,0,0}, + {19351,17476,17475 ,8080,8082,8081 ,0,0,0}, {19347,17653,19348 ,8084,8085,8083 ,0,0,0}, + {17476,19348,17653 ,8082,8083,8085 ,0,0,0}, {19347,19345,17421 ,8084,8086,8087 ,0,0,0}, + {17421,17653,19347 ,8087,8085,8084 ,0,0,0}, {17420,19345,19343 ,8088,8086,8089 ,0,0,0}, + {19345,17420,17421 ,8086,8088,8087 ,0,0,0}, {19342,17504,19343 ,8090,8091,8089 ,0,0,0}, + {17420,19343,17504 ,8088,8089,8091 ,0,0,0}, {19342,19346,17544 ,8090,8092,8093 ,0,0,0}, + {17544,17504,19342 ,8093,8091,8090 ,0,0,0}, {17545,19346,19363 ,8094,8092,8095 ,0,0,0}, + {19346,17545,17544 ,8092,8094,8093 ,0,0,0}, {17545,19363,17546 ,8094,8095,8096 ,0,0,0}, + {17546,19363,19364 ,8096,8095,8096 ,0,0,0}, {17851,19364,17844 ,8097,8098,8097 ,0,0,0}, + {19364,17852,17855 ,8098,8097,8098 ,0,0,0}, {17851,17852,19364 ,8097,8097,8098 ,0,0,0}, + {19364,17861,17866 ,8098,8098,8097 ,0,0,0}, {17855,17861,19364 ,8098,8098,8098 ,0,0,0}, + {19364,17870,17829 ,8098,8098,8097 ,0,0,0}, {17866,17870,19364 ,8097,8098,8098 ,0,0,0}, + {19364,17833,17832 ,8098,8097,8097 ,0,0,0}, {17829,17833,19364 ,8097,8097,8098 ,0,0,0}, + {19364,17832,17546 ,8098,8097,8098 ,0,0,0}, {17908,19344,17495 ,8099,8099,8099 ,0,0,0}, + {17908,17964,19344 ,8099,8099,8099 ,0,0,0}, {19344,17964,17950 ,8099,8099,8099 ,0,0,0}, + {17904,17910,19344 ,8099,8099,8099 ,0,0,0}, {17904,19344,17950 ,8099,8099,8099 ,0,0,0}, + {17910,17946,19344 ,8099,8099,8099 ,0,0,0}, {19344,17893,17892 ,8099,8099,8099 ,0,0,0}, + {17946,17893,19344 ,8099,8099,8099 ,0,0,0}, {17899,19344,17897 ,8099,8099,8099 ,0,0,0}, + {17892,17897,19344 ,8099,8099,8099 ,0,0,0}, {16037,19365,17687 ,1359,8100,4482 ,0,0,0}, + {19366,17686,19367 ,4475,8101,8102 ,0,0,0}, {17688,17685,19368 ,8103,8104,4478 ,0,0,0}, + {17519,19369,17511 ,8105,8106,8107 ,0,0,0}, {19370,19371,17691 ,4472,8108,8109 ,0,0,0}, + {19372,17548,19373 ,8110,8111,8112 ,0,0,0}, {17547,17509,19374 ,8113,8114,8115 ,0,0,0}, + {17522,17515,19375 ,8116,8117,8118 ,0,0,0}, {17550,19376,17515 ,8119,8120,8117 ,0,0,0}, + {17540,19377,19378 ,8121,8122,8123 ,0,0,0}, {17522,19379,17542 ,8116,8124,8125 ,0,0,0}, + {19380,17539,19378 ,8126,8127,8123 ,0,0,0}, {17540,19378,17539 ,8121,8123,8127 ,0,0,0}, + {19380,19381,17537 ,8126,8128,8129 ,0,0,0}, {17537,17539,19380 ,8129,8127,8126 ,0,0,0}, + {17534,19381,19382 ,8130,8128,8131 ,0,0,0}, {19381,17534,17537 ,8128,8130,8129 ,0,0,0}, + {19383,17535,19382 ,8132,8133,8131 ,0,0,0}, {17534,19382,17535 ,8130,8131,8133 ,0,0,0}, + {19383,16056,16057 ,8132,1435,1435 ,0,0,0}, {16057,17535,19383 ,1435,8133,8132 ,0,0,0}, + {19375,17515,19376 ,8118,8117,8120 ,0,0,0}, {19377,17542,19379 ,8122,8125,8124 ,0,0,0}, + {17542,19377,17540 ,8125,8122,8121 ,0,0,0}, {19375,19379,17522 ,8118,8124,8116 ,0,0,0}, + {19372,19376,17550 ,8110,8120,8119 ,0,0,0}, {17547,19374,19373 ,8113,8115,8112 ,0,0,0}, + {17547,19373,17548 ,8113,8112,8111 ,0,0,0}, {17550,17548,19372 ,8119,8111,8110 ,0,0,0}, + {17509,19384,19374 ,8114,8134,8115 ,0,0,0}, {19384,17509,17511 ,8134,8114,8107 ,0,0,0}, + {19371,19369,17519 ,8108,8106,8105 ,0,0,0}, {19369,19384,17511 ,8106,8134,8107 ,0,0,0}, + {17691,19371,17519 ,8109,8108,8105 ,0,0,0}, {17667,19366,19370 ,4474,4475,4472 ,0,0,0}, + {17667,19370,17691 ,4474,4472,8109 ,0,0,0}, {17686,17688,19367 ,8101,8103,8102 ,0,0,0}, + {17667,17686,19366 ,4474,8101,4475 ,0,0,0}, {17685,19365,19368 ,8104,8100,4478 ,0,0,0}, + {19367,17688,19368 ,8102,8103,4478 ,0,0,0}, {16037,17687,16035 ,1359,4482,1359 ,0,0,0}, + {19365,17685,17687 ,8100,8104,4482 ,0,0,0}, {16031,19369,19371 ,726,726,726 ,0,0,0}, + {19377,16038,19378 ,726,7626,7758 ,0,0,0}, {19383,19382,19381 ,7625,7625,726 ,0,0,0}, + {19379,19375,16018 ,8135,7628,7626 ,0,0,0}, {16018,16016,19379 ,7626,7626,8135 ,0,0,0}, + {16028,19373,19374 ,726,7627,726 ,0,0,0}, {16021,19372,16022 ,726,7628,726 ,0,0,0}, + {16025,19369,16031 ,726,726,726 ,0,0,0}, {19374,19384,16030 ,726,726,726 ,0,0,0}, + {19366,19367,19368 ,7628,7628,726 ,0,0,0}, {16034,16031,19371 ,726,726,726 ,0,0,0}, + {16037,16034,19365 ,726,726,726 ,0,0,0}, {19365,19366,19368 ,726,7628,726 ,0,0,0}, + {19365,16034,19366 ,726,726,7628 ,0,0,0}, {19371,19370,16034 ,726,726,726 ,0,0,0}, + {16034,19370,19366 ,726,726,7628 ,0,0,0}, {19369,16025,16030 ,726,726,726 ,0,0,0}, + {16034,16033,16031 ,726,726,726 ,0,0,0}, {16030,16028,19374 ,726,726,726 ,0,0,0}, + {16030,19384,19369 ,726,726,726 ,0,0,0}, {19372,19373,16022 ,7628,7627,726 ,0,0,0}, + {16022,19373,16028 ,726,7627,726 ,0,0,0}, {16019,19376,16021 ,726,726,726 ,0,0,0}, + {16021,19376,19372 ,726,726,7628 ,0,0,0}, {16019,16018,19375 ,726,7626,7628 ,0,0,0}, + {19375,19376,16019 ,7628,726,726 ,0,0,0}, {16016,16038,19377 ,7626,7626,726 ,0,0,0}, + {16016,19377,19379 ,7626,726,8135 ,0,0,0}, {16039,19378,16038 ,7626,7758,7626 ,0,0,0}, + {19380,19378,16042 ,8135,7758,7628 ,0,0,0}, {16039,16042,19378 ,7626,7628,7758 ,0,0,0}, + {16042,16044,19381 ,7628,726,726 ,0,0,0}, {19381,19380,16042 ,726,8135,7628 ,0,0,0}, + {19383,16044,16045 ,7625,726,7626 ,0,0,0}, {16044,19383,19381 ,726,7625,726 ,0,0,0}, + {16048,16051,16054 ,7626,726,7626 ,0,0,0}, {16045,16048,19383 ,7626,7626,7625 ,0,0,0}, + {16054,19383,16048 ,7626,7625,7626 ,0,0,0}, {16048,16050,16051 ,7626,7627,726 ,0,0,0}, + {19383,16054,16056 ,7625,7626,8135 ,0,0,0}, {15998,19385,17673 ,1359,8136,8137 ,0,0,0}, + {17656,17658,19386 ,8138,8139,8140 ,0,0,0}, {17675,17677,19387 ,8141,8142,8143 ,0,0,0}, + {17463,19388,17462 ,8144,8145,8146 ,0,0,0}, {19389,19390,17657 ,8147,8148,8149 ,0,0,0}, + {19391,19392,17655 ,8150,8151,8152 ,0,0,0}, {19391,17654,19393 ,8150,8153,8154 ,0,0,0}, + {19394,19395,17587 ,8155,8156,8157 ,0,0,0}, {17587,17586,19394 ,8157,8158,8155 ,0,0,0}, + {17501,19395,19396 ,8159,8156,8160 ,0,0,0}, {19395,17501,17587 ,8156,8159,8157 ,0,0,0}, + {19397,17500,19396 ,8161,8162,8160 ,0,0,0}, {17501,19396,17500 ,8159,8160,8162 ,0,0,0}, + {19397,16012,16013 ,8161,1435,1435 ,0,0,0}, {16013,17500,19397 ,1435,8162,8161 ,0,0,0}, + {19388,17463,19390 ,8145,8144,8148 ,0,0,0}, {19392,17586,17655 ,8151,8158,8152 ,0,0,0}, + {19394,17586,19392 ,8155,8158,8151 ,0,0,0}, {19386,17658,19398 ,8140,8139,8163 ,0,0,0}, + {19393,17654,17462 ,8154,8153,8146 ,0,0,0}, {19391,17655,17654 ,8150,8152,8153 ,0,0,0}, + {19388,19393,17462 ,8145,8154,8146 ,0,0,0}, {17657,19390,17463 ,8149,8148,8144 ,0,0,0}, + {17656,19386,19389 ,8138,8140,8147 ,0,0,0}, {19389,17657,17656 ,8147,8149,8138 ,0,0,0}, + {17677,19385,19387 ,8142,8136,8143 ,0,0,0}, {19398,17675,19387 ,8163,8141,8143 ,0,0,0}, + {17658,17675,19398 ,8139,8141,8163 ,0,0,0}, {15998,17673,15999 ,1359,8137,1359 ,0,0,0}, + {19385,17677,17673 ,8136,8142,8137 ,0,0,0}, {19395,19390,19389 ,726,7661,7661 ,0,0,0}, + {19391,19393,19394 ,7661,7658,726 ,0,0,0}, {19394,19392,19391 ,726,726,7661 ,0,0,0}, + {19388,19390,19394 ,7658,7661,726 ,0,0,0}, {19388,19394,19393 ,7658,726,7658 ,0,0,0}, + {19389,19396,19395 ,7661,726,726 ,0,0,0}, {19390,19395,19394 ,7661,726,726 ,0,0,0}, + {19396,19389,19386 ,726,7661,7658 ,0,0,0}, {19386,19398,19397 ,7658,7661,726 ,0,0,0}, + {19397,19396,19386 ,726,726,7658 ,0,0,0}, {16012,19398,19387 ,726,7661,7658 ,0,0,0}, + {19398,16012,19397 ,7661,726,726 ,0,0,0}, {15997,16006,15998 ,7658,726,726 ,0,0,0}, + {19385,16010,19387 ,7658,7660,7658 ,0,0,0}, {16004,15997,15995 ,726,7658,726 ,0,0,0}, + {15985,15984,15991 ,726,726,726 ,0,0,0}, {16001,15993,16000 ,726,726,726 ,0,0,0}, + {15991,15988,15987 ,726,726,726 ,0,0,0}, {15991,15984,16000 ,726,726,726 ,0,0,0}, + {15985,15991,15987 ,726,726,726 ,0,0,0}, {15995,15993,16001 ,726,726,726 ,0,0,0}, + {15993,15991,16000 ,726,726,726 ,0,0,0}, {16006,15997,16004 ,726,7658,726 ,0,0,0}, + {16004,15995,16001 ,726,726,726 ,0,0,0}, {15998,16007,19385 ,726,726,7658 ,0,0,0}, + {15998,16006,16007 ,726,726,726 ,0,0,0}, {19387,16010,16012 ,7658,7660,726 ,0,0,0}, + {16007,16010,19385 ,726,7660,7658 ,0,0,0}, {19399,19400,18867 ,726,726,7664 ,0,0,0}, + {19401,19399,18867 ,726,726,7664 ,0,0,0}, {19401,18867,19402 ,726,7664,726 ,0,0,0}, + {19403,18867,19400 ,726,7664,726 ,0,0,0}, {19404,19405,18867 ,726,726,7664 ,0,0,0}, + {19404,18867,19403 ,726,7664,726 ,0,0,0}, {19406,18867,18865 ,726,7664,726 ,0,0,0}, + {19402,18867,19406 ,726,7664,726 ,0,0,0}, {19407,18867,19405 ,726,7664,726 ,0,0,0}, + {18867,19407,19408 ,7664,726,726 ,0,0,0}, {19406,18865,19409 ,726,726,726 ,0,0,0}, + {19410,18867,19408 ,726,7664,726 ,0,0,0}, {19411,19409,18865 ,7583,726,726 ,0,0,0}, + {18865,19412,19411 ,726,7664,7583 ,0,0,0}, {18867,19410,19413 ,7664,726,726 ,0,0,0}, + {18867,19413,19414 ,7664,726,726 ,0,0,0}, {19415,19412,18865 ,726,7664,726 ,0,0,0}, + {19416,19417,18865 ,726,726,726 ,0,0,0}, {19417,19415,18865 ,726,726,726 ,0,0,0}, + {19418,18865,19419 ,726,726,726 ,0,0,0}, {19418,19416,18865 ,726,726,726 ,0,0,0}, + {18868,19414,17805 ,7664,726,726 ,0,0,0}, {19414,18868,18867 ,726,7664,7664 ,0,0,0}, + {19419,18865,19420 ,726,726,726 ,0,0,0}, {19421,18865,18866 ,726,726,7664 ,0,0,0}, + {18865,19421,19420 ,726,726,726 ,0,0,0}, {19421,18866,17729 ,726,7664,5488 ,0,0,0}, + {17517,17510,19399 ,8164,8165,8166 ,0,0,0}, {19401,17518,17517 ,8167,8168,8164 ,0,0,0}, + {19401,19402,17518 ,8167,8168,8168 ,0,0,0}, {19399,19401,17517 ,8166,8167,8164 ,0,0,0}, + {17510,17651,19400 ,8165,8169,8170 ,0,0,0}, {17549,17551,19404 ,8171,8172,8173 ,0,0,0}, + {19403,19400,17651 ,8174,8170,8169 ,0,0,0}, {17651,17549,19403 ,8169,8171,8174 ,0,0,0}, + {19404,19403,17549 ,8173,8174,8171 ,0,0,0}, {17510,19400,19399 ,8165,8170,8166 ,0,0,0}, + {19404,17551,19405 ,8173,8172,8175 ,0,0,0}, {17514,19407,19405 ,8176,8177,8175 ,0,0,0}, + {19405,17551,17514 ,8175,8172,8176 ,0,0,0}, {19407,17514,17516 ,8177,8176,8178 ,0,0,0}, + {17521,19408,17516 ,8179,8180,8178 ,0,0,0}, {17521,17553,19410 ,8179,8181,8182 ,0,0,0}, + {17521,19410,19408 ,8179,8182,8180 ,0,0,0}, {19413,17555,19414 ,8183,8184,8185 ,0,0,0}, + {19410,17553,19413 ,8182,8181,8183 ,0,0,0}, {19413,17553,17555 ,8183,8181,8184 ,0,0,0}, + {17555,17554,19414 ,8184,8185,8185 ,0,0,0}, {19407,17516,19408 ,8177,8178,8180 ,0,0,0}, + {17513,19402,19406 ,8186,8168,8187 ,0,0,0}, {19402,17513,17518 ,8168,8186,8168 ,0,0,0}, + {19409,17512,19406 ,8188,8189,8187 ,0,0,0}, {17513,19406,17512 ,8186,8187,8189 ,0,0,0}, + {19409,19411,17679 ,8188,8190,8191 ,0,0,0}, {17679,17512,19409 ,8191,8189,8188 ,0,0,0}, + {17507,19411,19412 ,8192,8190,8193 ,0,0,0}, {19411,17507,17679 ,8190,8192,8191 ,0,0,0}, + {19415,17508,19412 ,8194,8195,8193 ,0,0,0}, {17507,19412,17508 ,8192,8193,8195 ,0,0,0}, + {19415,19417,17581 ,8194,8196,8197 ,0,0,0}, {17581,17508,19415 ,8197,8195,8194 ,0,0,0}, + {17582,19417,19416 ,8198,8196,8199 ,0,0,0}, {19417,17582,17581 ,8196,8198,8197 ,0,0,0}, + {19418,17325,19416 ,8200,8201,8199 ,0,0,0}, {17582,19416,17325 ,8198,8199,8201 ,0,0,0}, + {19418,19419,17328 ,8200,8202,8203 ,0,0,0}, {17328,17325,19418 ,8203,8201,8200 ,0,0,0}, + {17329,19419,19420 ,8204,8202,8205 ,0,0,0}, {19419,17329,17328 ,8202,8204,8203 ,0,0,0}, + {17329,19420,17330 ,8204,8205,8206 ,0,0,0}, {17330,19420,19421 ,8206,8205,8206 ,0,0,0}, + {17730,19421,17729 ,8207,8207,8207 ,0,0,0}, {19421,17760,17763 ,8207,8207,8207 ,0,0,0}, + {17730,17760,19421 ,8207,8207,8207 ,0,0,0}, {19421,17769,17774 ,8207,8207,8207 ,0,0,0}, + {17763,17769,19421 ,8207,8207,8207 ,0,0,0}, {19421,17778,17708 ,8207,8207,8207 ,0,0,0}, + {17774,17778,19421 ,8207,8207,8207 ,0,0,0}, {19421,17711,17710 ,8207,8207,8207 ,0,0,0}, + {17708,17711,19421 ,8207,8207,8207 ,0,0,0}, {19421,17710,17330 ,8207,8207,8207 ,0,0,0}, + {17820,19414,17554 ,8208,8208,8208 ,0,0,0}, {17820,17871,19414 ,8208,8208,8208 ,0,0,0}, + {19414,17871,17857 ,8208,8208,8208 ,0,0,0}, {17814,17807,19414 ,8208,8208,8208 ,0,0,0}, + {17814,19414,17857 ,8208,8208,8208 ,0,0,0}, {17807,17853,19414 ,8208,8208,8208 ,0,0,0}, + {19414,17845,17799 ,8208,8208,8208 ,0,0,0}, {17853,17845,19414 ,8208,8208,8208 ,0,0,0}, + {17805,19414,17801 ,8208,8208,8208 ,0,0,0}, {17799,17801,19414 ,8208,8208,8208 ,0,0,0}, + {15961,19422,17317 ,1711,8209,4414 ,0,0,0}, {19423,17580,19424 ,8210,8211,8212 ,0,0,0}, + {17565,17318,19425 ,8213,8214,4410 ,0,0,0}, {17579,19426,17309 ,4402,8215,8216 ,0,0,0}, + {19427,19428,17578 ,8217,8218,8219 ,0,0,0}, {19429,17339,19430 ,8220,8221,8222 ,0,0,0}, + {17338,17564,19431 ,8223,8224,8225 ,0,0,0}, {17312,17311,19432 ,8226,8227,8228 ,0,0,0}, + {17334,19433,17311 ,8229,8230,8227 ,0,0,0}, {17315,19434,19435 ,8231,8232,8233 ,0,0,0}, + {17312,19436,17314 ,8226,8234,8235 ,0,0,0}, {19437,17331,19435 ,8236,8237,8233 ,0,0,0}, + {17315,19435,17331 ,8231,8233,8237 ,0,0,0}, {19437,19438,17319 ,8236,8238,8239 ,0,0,0}, + {17319,17331,19437 ,8239,8237,8236 ,0,0,0}, {17567,19438,19439 ,8240,8238,8241 ,0,0,0}, + {19438,17567,17319 ,8238,8240,8239 ,0,0,0}, {19440,17327,19439 ,8242,8243,8241 ,0,0,0}, + {17567,19439,17327 ,8240,8241,8243 ,0,0,0}, {19440,15980,15981 ,8242,1790,1790 ,0,0,0}, + {15981,17327,19440 ,1790,8243,8242 ,0,0,0}, {19432,17311,19433 ,8228,8227,8230 ,0,0,0}, + {19434,17314,19436 ,8232,8235,8234 ,0,0,0}, {17314,19434,17315 ,8235,8232,8231 ,0,0,0}, + {19432,19436,17312 ,8228,8234,8226 ,0,0,0}, {19429,19433,17334 ,8220,8230,8229 ,0,0,0}, + {17338,19431,19430 ,8223,8225,8222 ,0,0,0}, {17338,19430,17339 ,8223,8222,8221 ,0,0,0}, + {17334,17339,19429 ,8229,8221,8220 ,0,0,0}, {17564,19441,19431 ,8224,8244,8225 ,0,0,0}, + {19441,17564,17309 ,8244,8224,8216 ,0,0,0}, {19428,19426,17579 ,8218,8215,4402 ,0,0,0}, + {19426,19441,17309 ,8215,8244,8216 ,0,0,0}, {17578,19428,17579 ,8219,8218,4402 ,0,0,0}, + {17279,19423,19427 ,8245,8210,8217 ,0,0,0}, {17279,19427,17578 ,8245,8217,8219 ,0,0,0}, + {17580,17565,19424 ,8211,8213,8212 ,0,0,0}, {17279,17580,19423 ,8245,8211,8210 ,0,0,0}, + {17318,19422,19425 ,8214,8209,4410 ,0,0,0}, {19424,17565,19425 ,8212,8213,4410 ,0,0,0}, + {15961,17317,15959 ,1711,4414,1711 ,0,0,0}, {19422,17318,17317 ,8209,8214,4414 ,0,0,0}, + {19427,19432,19433 ,726,726,7626 ,0,0,0}, {19441,19430,19431 ,726,726,726 ,0,0,0}, + {19429,19441,19426 ,726,726,726 ,0,0,0}, {19428,19429,19426 ,726,726,726 ,0,0,0}, + {19428,19433,19429 ,726,7626,726 ,0,0,0}, {19441,19429,19430 ,726,726,726 ,0,0,0}, + {19428,19427,19433 ,726,726,7626 ,0,0,0}, {19423,19436,19432 ,726,726,726 ,0,0,0}, + {19427,19423,19432 ,726,726,726 ,0,0,0}, {19436,19424,19434 ,726,726,7626 ,0,0,0}, + {19424,19436,19423 ,726,726,726 ,0,0,0}, {19435,19434,19425 ,7628,7626,726 ,0,0,0}, + {19424,19425,19434 ,726,726,7626 ,0,0,0}, {19422,19437,19435 ,726,726,7628 ,0,0,0}, + {19435,19425,19422 ,7628,726,726 ,0,0,0}, {19437,15961,19438 ,726,726,726 ,0,0,0}, + {15961,19437,19422 ,726,726,726 ,0,0,0}, {19439,19438,15958 ,7625,726,726 ,0,0,0}, + {15961,15958,19438 ,726,726,726 ,0,0,0}, {19439,15958,15957 ,7625,726,726 ,0,0,0}, + {19440,19439,15957 ,726,7625,726 ,0,0,0}, {15957,15955,19440 ,726,726,726 ,0,0,0}, + {15949,15980,15955 ,726,726,726 ,0,0,0}, {19440,15955,15980 ,726,726,726 ,0,0,0}, + {15952,15946,15974 ,726,726,7625 ,0,0,0}, {15949,15954,15978 ,726,726,726 ,0,0,0}, + {15943,15968,15969 ,7626,726,726 ,0,0,0}, {15969,15972,15945 ,726,726,726 ,0,0,0}, + {15968,15942,15966 ,726,7625,7625 ,0,0,0}, {15942,15963,15966 ,7625,726,7625 ,0,0,0}, + {15940,15963,15942 ,726,726,7625 ,0,0,0}, {15940,15962,15963 ,726,726,726 ,0,0,0}, + {15945,15943,15969 ,726,7626,726 ,0,0,0}, {15942,15968,15943 ,7625,726,7626 ,0,0,0}, + {15972,15974,15946 ,726,7625,726 ,0,0,0}, {15945,15972,15946 ,726,726,726 ,0,0,0}, + {15952,15975,15954 ,726,726,726 ,0,0,0}, {15952,15974,15975 ,726,7625,726 ,0,0,0}, + {15949,15978,15980 ,726,726,726 ,0,0,0}, {15975,15978,15954 ,726,726,726 ,0,0,0}, + {15922,19442,17591 ,1711,8246,8247 ,0,0,0}, {17650,17664,19443 ,8248,8249,8250 ,0,0,0}, + {17663,17592,19444 ,8251,8252,8253 ,0,0,0}, {17503,19445,17502 ,8254,8255,8256 ,0,0,0}, + {19446,19447,17684 ,8257,8258,8259 ,0,0,0}, {19448,19449,17682 ,8260,8261,8262 ,0,0,0}, + {19448,17681,19450 ,8260,8263,8264 ,0,0,0}, {19451,19452,17584 ,8265,8266,8267 ,0,0,0}, + {17584,17585,19451 ,8267,8268,8265 ,0,0,0}, {17680,19452,19453 ,8269,8266,8270 ,0,0,0}, + {19452,17680,17584 ,8266,8269,8267 ,0,0,0}, {19454,17583,19453 ,8271,8272,8270 ,0,0,0}, + {17680,19453,17583 ,8269,8270,8272 ,0,0,0}, {19454,15936,15937 ,8271,1790,1790 ,0,0,0}, + {15937,17583,19454 ,1790,8272,8271 ,0,0,0}, {19445,17503,19447 ,8255,8254,8258 ,0,0,0}, + {19449,17585,17682 ,8261,8268,8262 ,0,0,0}, {19451,17585,19449 ,8265,8268,8261 ,0,0,0}, + {19443,17664,19455 ,8250,8249,8273 ,0,0,0}, {19450,17681,17502 ,8264,8263,8256 ,0,0,0}, + {19448,17682,17681 ,8260,8262,8263 ,0,0,0}, {19445,19450,17502 ,8255,8264,8256 ,0,0,0}, + {17684,19447,17503 ,8259,8258,8254 ,0,0,0}, {17650,19443,19446 ,8248,8250,8257 ,0,0,0}, + {19446,17684,17650 ,8257,8259,8248 ,0,0,0}, {17592,19442,19444 ,8252,8246,8253 ,0,0,0}, + {19455,17663,19444 ,8273,8251,8253 ,0,0,0}, {17664,17663,19455 ,8249,8251,8273 ,0,0,0}, + {15922,17591,15923 ,1711,8247,1711 ,0,0,0}, {19442,17592,17591 ,8246,8252,8247 ,0,0,0}, + {15936,19454,19453 ,726,7658,726 ,0,0,0}, {19455,15911,19443 ,726,726,726 ,0,0,0}, + {15934,19453,19452 ,7660,726,7660 ,0,0,0}, {19448,15930,19449 ,7660,726,7660 ,0,0,0}, + {15931,15934,19451 ,7660,7660,7583 ,0,0,0}, {15924,19445,19447 ,7660,7661,7661 ,0,0,0}, + {15928,19448,19450 ,726,7660,7658 ,0,0,0}, {15909,19443,15911 ,726,726,726 ,0,0,0}, + {19447,19446,15908 ,7661,726,726 ,0,0,0}, {19442,15917,15915 ,726,726,726 ,0,0,0}, + {19444,15912,19455 ,726,726,726 ,0,0,0}, {15922,15921,15917 ,726,726,726 ,0,0,0}, + {15919,15917,15921 ,726,726,726 ,0,0,0}, {15917,19442,15922 ,726,726,726 ,0,0,0}, + {19444,15915,15912 ,726,726,726 ,0,0,0}, {19444,19442,15915 ,726,726,726 ,0,0,0}, + {19446,19443,15909 ,726,726,726 ,0,0,0}, {15911,19455,15912 ,726,726,726 ,0,0,0}, + {15908,15924,19447 ,726,7660,7661 ,0,0,0}, {15909,15908,19446 ,726,726,726 ,0,0,0}, + {19450,19445,15925 ,7658,7661,7659 ,0,0,0}, {15925,19445,15924 ,7659,7661,7660 ,0,0,0}, + {15928,19450,15925 ,726,7658,7659 ,0,0,0}, {15931,19449,15930 ,7660,7660,726 ,0,0,0}, + {19448,15928,15930 ,7660,726,726 ,0,0,0}, {15934,19452,19451 ,7660,7660,7583 ,0,0,0}, + {15931,19451,19449 ,7660,7583,7660 ,0,0,0}, {15934,15936,19453 ,7660,726,726 ,0,0,0}, + {17689,15881,19456 ,8274,8275,8276 ,0,0,0}, {17690,17666,19457 ,8277,8278,8279 ,0,0,0}, + {19458,17666,17683 ,8280,8278,8281 ,0,0,0}, {19459,19460,17590 ,8282,8283,8284 ,0,0,0}, + {19461,17662,17661 ,8285,8286,8287 ,0,0,0}, {17671,17659,19462 ,8288,8289,8290 ,0,0,0}, + {17670,19463,19464 ,8291,8292,8293 ,0,0,0}, {17693,19465,17676 ,8294,8295,8296 ,0,0,0}, + {19466,19467,17672 ,1631,8297,1631 ,0,0,0}, {19468,19469,17674 ,8298,8299,8300 ,0,0,0}, + {19468,17694,19470 ,8298,8301,8302 ,0,0,0}, {19471,19472,17669 ,8303,8304,8305 ,0,0,0}, + {19471,17668,19469 ,8303,8306,8299 ,0,0,0}, {17607,19472,19473 ,8307,8304,8308 ,0,0,0}, + {19472,17607,17669 ,8304,8307,8305 ,0,0,0}, {19474,17648,19473 ,8309,8310,8308 ,0,0,0}, + {17607,19473,17648 ,8307,8308,8310 ,0,0,0}, {17589,19474,17642 ,8311,8309,8312 ,0,0,0}, + {17589,17648,19474 ,8311,8310,8309 ,0,0,0}, {17640,17642,19475 ,8313,8312,8314 ,0,0,0}, + {19474,19475,17642 ,8309,8314,8312 ,0,0,0}, {19476,15905,17640 ,8315,126,8313 ,0,0,0}, + {17640,19475,19476 ,8313,8314,8315 ,0,0,0}, {15903,15905,19476 ,126,126,8315 ,0,0,0}, + {17668,17674,19469 ,8306,8300,8299 ,0,0,0}, {19471,17669,17668 ,8303,8305,8306 ,0,0,0}, + {17694,17676,19470 ,8301,8296,8302 ,0,0,0}, {19468,17674,17694 ,8298,8300,8301 ,0,0,0}, + {19467,19465,17693 ,8297,8295,8294 ,0,0,0}, {19465,19470,17676 ,8295,8302,8296 ,0,0,0}, + {17671,19466,17672 ,8288,1631,1631 ,0,0,0}, {17672,19467,17693 ,1631,8297,8294 ,0,0,0}, + {17659,19464,19462 ,8289,8293,8290 ,0,0,0}, {17671,19462,19466 ,8288,8290,1631 ,0,0,0}, + {17670,17692,19463 ,8291,8316,8292 ,0,0,0}, {17659,17670,19464 ,8289,8291,8293 ,0,0,0}, + {17590,19460,17692 ,8284,8283,8316 ,0,0,0}, {19463,17692,19460 ,8292,8316,8283 ,0,0,0}, + {19461,19459,17662 ,8285,8282,8286 ,0,0,0}, {19459,17590,17662 ,8282,8284,8286 ,0,0,0}, + {17690,19477,17661 ,8277,8317,8287 ,0,0,0}, {19477,19461,17661 ,8317,8285,8287 ,0,0,0}, + {17666,19478,19457 ,8278,8318,8279 ,0,0,0}, {17690,19457,19477 ,8277,8279,8317 ,0,0,0}, + {19458,17683,19456 ,8280,8281,8276 ,0,0,0}, {19478,17666,19458 ,8318,8278,8280 ,0,0,0}, + {15881,17689,15880 ,8275,8274,4114 ,0,0,0}, {19456,17683,17689 ,8276,8281,8274 ,0,0,0}, + {19468,19479,19469 ,726,726,726 ,0,0,0}, {19480,15854,19476 ,726,726,726 ,0,0,0}, + {19481,19472,19482 ,726,726,726 ,0,0,0}, {15885,15839,15838 ,726,726,7661 ,0,0,0}, + {15894,15896,15848 ,726,726,726 ,0,0,0}, {19483,19475,19474 ,726,726,726 ,0,0,0}, + {15899,15902,15853 ,726,726,726 ,0,0,0}, {15903,15854,15902 ,726,726,726 ,0,0,0}, + {15851,15849,15900 ,7658,726,726 ,0,0,0}, {15899,15853,15851 ,726,726,7658 ,0,0,0}, + {19483,19480,19475 ,726,726,726 ,0,0,0}, {15896,15897,15849 ,726,726,726 ,0,0,0}, + {15894,15848,15845 ,726,726,726 ,0,0,0}, {15890,15843,15888 ,726,726,726 ,0,0,0}, + {15891,15845,15843 ,726,726,726 ,0,0,0}, {15839,15885,15888 ,726,726,726 ,0,0,0}, + {19481,19474,19473 ,726,726,726 ,0,0,0}, {19469,19484,19471 ,726,7661,726 ,0,0,0}, + {19471,19484,19482 ,726,7661,726 ,0,0,0}, {15818,15858,15857 ,7658,726,7658 ,0,0,0}, + {15884,15838,15818 ,726,7661,7658 ,0,0,0}, {19485,19479,19470 ,726,726,726 ,0,0,0}, + {15858,15822,15859 ,726,7658,726 ,0,0,0}, {15861,15823,15824 ,7661,7658,726 ,0,0,0}, + {19465,19467,19486 ,726,7661,726 ,0,0,0}, {19465,19486,19485 ,726,726,726 ,0,0,0}, + {19467,19466,19487 ,7661,7658,7658 ,0,0,0}, {15865,15864,15824 ,726,726,726 ,0,0,0}, + {15828,15867,15825 ,726,7583,726 ,0,0,0}, {19488,19489,19464 ,726,726,726 ,0,0,0}, + {19489,19487,19462 ,726,7658,726 ,0,0,0}, {15877,15831,15834 ,7664,726,7664 ,0,0,0}, + {19488,19464,19463 ,726,726,7661 ,0,0,0}, {19490,19463,19460 ,726,7661,7664 ,0,0,0}, + {15837,15881,15879 ,726,726,7664 ,0,0,0}, {19491,19456,15837 ,7664,726,726 ,0,0,0}, + {19490,19459,19492 ,726,7583,726 ,0,0,0}, {19458,19493,19478 ,7664,7664,726 ,0,0,0}, + {15859,15822,15823 ,726,7658,7658 ,0,0,0}, {19457,19478,19494 ,7664,726,7664 ,0,0,0}, + {19493,19494,19478 ,7664,7664,726 ,0,0,0}, {19458,19456,19491 ,7664,726,7664 ,0,0,0}, + {19458,19491,19493 ,7664,7664,7664 ,0,0,0}, {19495,19492,19461 ,7664,726,7583 ,0,0,0}, + {19495,19461,19477 ,7664,7583,7664 ,0,0,0}, {15881,15837,19456 ,726,726,726 ,0,0,0}, + {15830,15831,15873 ,726,726,726 ,0,0,0}, {15828,15830,15870 ,726,726,7664 ,0,0,0}, + {19495,19477,19494 ,7664,7664,7664 ,0,0,0}, {19477,19457,19494 ,7664,7664,7664 ,0,0,0}, + {19459,19461,19492 ,7583,7583,726 ,0,0,0}, {19460,19459,19490 ,7664,7583,726 ,0,0,0}, + {19488,19463,19490 ,726,7661,726 ,0,0,0}, {19462,19464,19489 ,726,726,726 ,0,0,0}, + {19466,19462,19487 ,7658,726,7658 ,0,0,0}, {19486,19467,19487 ,726,7661,7658 ,0,0,0}, + {19470,19465,19485 ,726,726,726 ,0,0,0}, {19468,19470,19479 ,726,726,726 ,0,0,0}, + {19484,19469,19479 ,7661,726,726 ,0,0,0}, {19472,19471,19482 ,726,726,726 ,0,0,0}, + {19473,19472,19481 ,726,726,726 ,0,0,0}, {19483,19474,19481 ,726,726,726 ,0,0,0}, + {19476,19475,19480 ,726,726,726 ,0,0,0}, {15903,19476,15854 ,726,726,726 ,0,0,0}, + {15853,15902,15854 ,726,726,726 ,0,0,0}, {15900,15899,15851 ,726,726,7658 ,0,0,0}, + {15897,15900,15849 ,726,726,726 ,0,0,0}, {15848,15896,15849 ,726,726,726 ,0,0,0}, + {15891,15894,15845 ,726,726,726 ,0,0,0}, {15890,15891,15843 ,726,726,726 ,0,0,0}, + {15839,15888,15843 ,726,726,726 ,0,0,0}, {15884,15885,15838 ,726,726,7661 ,0,0,0}, + {15857,15884,15818 ,7658,726,7658 ,0,0,0}, {15822,15858,15818 ,7658,726,7658 ,0,0,0}, + {15864,15861,15824 ,726,7661,726 ,0,0,0}, {15861,15859,15823 ,7661,726,7658 ,0,0,0}, + {15825,15865,15824 ,726,726,726 ,0,0,0}, {15828,15870,15867 ,726,7664,7583 ,0,0,0}, + {15825,15867,15865 ,726,7583,726 ,0,0,0}, {15830,15871,15870 ,726,7664,7664 ,0,0,0}, + {15873,15831,15877 ,726,726,7664 ,0,0,0}, {15871,15830,15873 ,7664,726,726 ,0,0,0}, + {15877,15834,15879 ,7664,7664,7664 ,0,0,0}, {15837,15879,15834 ,726,7664,7664 ,0,0,0}, + {19496,19497,15821 ,726,726,726 ,0,0,0}, {15840,15842,15850 ,726,726,726 ,0,0,0}, + {15819,15840,15855 ,726,726,726 ,0,0,0}, {15821,15820,19496 ,726,726,726 ,0,0,0}, + {15846,15847,15850 ,726,726,726 ,0,0,0}, {15841,15844,15842 ,726,726,726 ,0,0,0}, + {15846,15850,15844 ,726,726,726 ,0,0,0}, {15842,15844,15850 ,726,726,726 ,0,0,0}, + {15850,15852,15840 ,726,726,726 ,0,0,0}, {19496,15819,15855 ,726,726,726 ,0,0,0}, + {15855,15840,15852 ,726,726,726 ,0,0,0}, {15821,19497,19498 ,726,726,726 ,0,0,0}, + {19496,15820,15819 ,726,726,726 ,0,0,0}, {15826,19498,19499 ,726,726,726 ,0,0,0}, + {19498,15826,15821 ,726,726,726 ,0,0,0}, {19499,15829,15827 ,726,726,7658 ,0,0,0}, + {15826,19499,15827 ,726,726,7658 ,0,0,0}, {19500,15829,19499 ,726,726,726 ,0,0,0}, + {15829,19501,15832 ,726,726,7661 ,0,0,0}, {19501,15829,19500 ,726,726,726 ,0,0,0}, + {19501,19502,15832 ,726,726,7661 ,0,0,0}, {15833,19502,15835 ,726,726,7661 ,0,0,0}, + {15833,15832,19502 ,726,7661,726 ,0,0,0}, {15835,19503,19504 ,7661,726,726 ,0,0,0}, + {19502,19503,15835 ,726,726,7661 ,0,0,0}, {19505,15836,19504 ,726,7658,726 ,0,0,0}, + {15835,19504,15836 ,7661,726,7658 ,0,0,0}, {19506,19507,19508 ,726,726,7660 ,0,0,0}, + {19508,19509,19506 ,7660,726,726 ,0,0,0}, {19507,19510,19511 ,726,726,7658 ,0,0,0}, + {19507,19505,19508 ,726,726,7660 ,0,0,0}, {19507,19512,19505 ,726,7661,726 ,0,0,0}, + {19507,19506,19510 ,726,726,726 ,0,0,0}, {19505,19512,15836 ,726,7661,7658 ,0,0,0}, + {19512,15837,15836 ,8319,81,8320 ,0,0,0}, {19510,19495,19511 ,8321,8322,8323 ,0,0,0}, + {19507,19494,19493 ,8324,8325,8326 ,0,0,0}, {19508,19505,19488 ,8327,8328,8329 ,0,0,0}, + {19506,19509,19490 ,8330,8331,8332 ,0,0,0}, {19502,19486,19503 ,8333,8334,8335 ,0,0,0}, + {19487,19504,19503 ,8336,8337,8335 ,0,0,0}, {19500,19484,19501 ,7530,8338,8339 ,0,0,0}, + {19479,19502,19501 ,8340,8333,8339 ,0,0,0}, {19499,19481,19482 ,8341,8342,8343 ,0,0,0}, + {19482,19500,19499 ,8343,7530,8341 ,0,0,0}, {19481,19498,19483 ,8342,8344,8345 ,0,0,0}, + {19498,19481,19499 ,8344,8342,8341 ,0,0,0}, {19480,19483,19497 ,8346,8345,8347 ,0,0,0}, + {19498,19497,19483 ,8344,8347,8345 ,0,0,0}, {15855,19480,19496 ,96,8346,8348 ,0,0,0}, + {19480,19497,19496 ,8346,8347,8348 ,0,0,0}, {15854,19480,15855 ,96,8346,96 ,0,0,0}, + {19479,19501,19484 ,8340,8339,8338 ,0,0,0}, {19482,19484,19500 ,8343,8338,7530 ,0,0,0}, + {19485,19486,19502 ,8349,8334,8333 ,0,0,0}, {19479,19485,19502 ,8340,8349,8333 ,0,0,0}, + {19489,19504,19487 ,8350,8337,8336 ,0,0,0}, {19486,19487,19503 ,8334,8336,8335 ,0,0,0}, + {19488,19505,19489 ,8329,8328,8350 ,0,0,0}, {19504,19489,19505 ,8337,8350,8328 ,0,0,0}, + {19490,19509,19488 ,8332,8331,8329 ,0,0,0}, {19509,19508,19488 ,8331,8327,8329 ,0,0,0}, + {19492,19510,19506 ,7516,8321,8330 ,0,0,0}, {19492,19506,19490 ,7516,8330,8332 ,0,0,0}, + {19495,19494,19511 ,8322,8325,8323 ,0,0,0}, {19492,19495,19510 ,7516,8322,8321 ,0,0,0}, + {19507,19493,19512 ,8324,8326,8319 ,0,0,0}, {19511,19494,19507 ,8323,8325,8324 ,0,0,0}, + {15837,19512,19491 ,81,8319,8351 ,0,0,0}, {19512,19493,19491 ,8319,8326,8351 ,0,0,0} +// X-Ufo 8ZollPropeller.prt + , {19513,19514,19515 ,8352,8353,8354 ,0,0,0}, {19513,19516,19517 ,8352,8355,8356 ,0,0,0}, + {19517,19514,19513 ,8356,8353,8352 ,0,0,0}, {19518,19516,19519 ,8357,8355,8358 ,0,0,0}, + {19516,19518,19517 ,8355,8357,8356 ,0,0,0}, {19520,19521,19522 ,8359,8360,8361 ,0,0,0}, + {19518,19519,19521 ,8357,8358,8360 ,0,0,0}, {19523,19524,19520 ,8362,3877,8359 ,0,0,0}, + {19523,19525,19524 ,8362,4346,3877 ,0,0,0}, {19523,19520,19522 ,8362,8359,8361 ,0,0,0}, + {19521,19519,19522 ,8360,8358,8361 ,0,0,0}, {19526,19515,19514 ,8363,8354,8353 ,0,0,0}, + {19527,19526,19528 ,8364,8363,8365 ,0,0,0}, {19526,19527,19515 ,8363,8364,8354 ,0,0,0}, + {19529,19530,19528 ,8366,8367,8365 ,0,0,0}, {19527,19528,19530 ,8364,8365,8367 ,0,0,0}, + {19529,19531,19532 ,8366,8368,8369 ,0,0,0}, {19532,19530,19529 ,8369,8367,8366 ,0,0,0}, + {19533,19531,19534 ,8370,8368,8371 ,0,0,0}, {19531,19533,19532 ,8368,8370,8369 ,0,0,0}, + {19533,19534,19535 ,8370,8371,8372 ,0,0,0}, {19536,19537,19538 ,8357,8373,8374 ,0,0,0}, + {19536,19539,19537 ,8357,8356,8373 ,0,0,0}, {19536,19538,19540 ,8357,8374,8360 ,0,0,0}, + {19540,19541,19542 ,8360,8375,8359 ,0,0,0}, {19541,19540,19538 ,8375,8360,8374 ,0,0,0}, + {19543,19542,19541 ,8376,8359,8375 ,0,0,0}, {19544,19537,19539 ,8377,8373,8356 ,0,0,0}, + {19543,19545,19546 ,8376,81,5000 ,0,0,0}, {19546,19542,19543 ,5000,8359,8376 ,0,0,0}, + {19544,19539,19547 ,8377,8356,8378 ,0,0,0}, {19547,19548,19544 ,8378,8379,8377 ,0,0,0}, + {19549,19548,19550 ,8380,8379,8363 ,0,0,0}, {19547,19550,19548 ,8378,8363,8379 ,0,0,0}, + {19551,19552,19549 ,8365,8381,8380 ,0,0,0}, {19549,19550,19551 ,8380,8363,8365 ,0,0,0}, + {19553,19554,19552 ,8366,8368,8381 ,0,0,0}, {19553,19552,19551 ,8366,8381,8365 ,0,0,0}, + {19555,19554,19556 ,8382,8368,8383 ,0,0,0}, {19554,19555,19552 ,8368,8382,8381 ,0,0,0}, + {19555,19556,19557 ,8382,8383,8384 ,0,0,0}, {19558,19559,8402 ,8385,8386,8387 ,0,0,0}, + {19560,19561,19562 ,8388,8389,8390 ,0,0,0}, {19563,19558,8402 ,8391,8385,8387 ,0,0,0}, + {19560,19562,19564 ,8388,8390,8392 ,0,0,0}, {19561,19560,19563 ,8389,8388,8391 ,0,0,0}, + {19561,19563,8402 ,8389,8391,8387 ,0,0,0}, {19565,19566,19567 ,8393,878,8394 ,0,0,0}, + {19567,19564,19568 ,8394,8392,8395 ,0,0,0}, {19565,19567,19568 ,8393,8394,8395 ,0,0,0}, + {19566,19565,19569 ,878,8393,8396 ,0,0,0}, {19568,19564,19562 ,8395,8392,8390 ,0,0,0}, + {19558,19570,19559 ,8385,8363,8386 ,0,0,0}, {19571,19570,19572 ,8397,8363,8398 ,0,0,0}, + {19570,19571,19559 ,8363,8397,8386 ,0,0,0}, {19573,19574,19572 ,8399,8400,8398 ,0,0,0}, + {19571,19572,19574 ,8397,8398,8400 ,0,0,0}, {19573,19575,19576 ,8399,8401,8402 ,0,0,0}, + {19576,19574,19573 ,8402,8400,8399 ,0,0,0}, {19577,19575,19578 ,8403,8401,126 ,0,0,0}, + {19575,19577,19576 ,8401,8403,8402 ,0,0,0}, {19579,19580,19581 ,8404,8405,8406 ,0,0,0}, + {19581,19580,19582 ,8406,8405,8407 ,0,0,0}, {19583,19580,19579 ,8408,8405,8404 ,0,0,0}, + {19584,19581,19582 ,8409,8406,8407 ,0,0,0}, {19583,19579,19585 ,8408,8404,8410 ,0,0,0}, + {19585,19586,19587 ,8410,8411,8412 ,0,0,0}, {19586,19585,19579 ,8411,8410,8404 ,0,0,0}, + {19584,19582,19588 ,8409,8407,8413 ,0,0,0}, {19589,19590,19587 ,8414,8415,8412 ,0,0,0}, + {19587,19586,19589 ,8412,8411,8414 ,0,0,0}, {19590,19591,19592 ,8415,5000,4114 ,0,0,0}, + {19593,19590,19589 ,8416,8415,8414 ,0,0,0}, {19593,19591,19590 ,8416,5000,8415 ,0,0,0}, + {19582,19594,19588 ,8407,8417,8413 ,0,0,0}, {19594,19595,19596 ,8417,8418,8419 ,0,0,0}, + {19596,19588,19594 ,8419,8413,8417 ,0,0,0}, {19597,19595,19598 ,8420,8418,8421 ,0,0,0}, + {19595,19597,19596 ,8418,8420,8419 ,0,0,0}, {19599,19600,19598 ,8422,8423,8421 ,0,0,0}, + {19597,19598,19600 ,8420,8421,8423 ,0,0,0}, {19599,19601,19602 ,8422,8424,8425 ,0,0,0}, + {19602,19600,19599 ,8425,8423,8422 ,0,0,0}, {19603,19601,19604 ,8426,8424,8427 ,0,0,0}, + {19601,19603,19602 ,8424,8426,8425 ,0,0,0}, {19603,19604,19605 ,8426,8427,8428 ,0,0,0}, + {19605,19604,4818 ,8428,8427,8429 ,0,0,0}, {19606,19607,19608 ,8430,8431,8432 ,0,0,0}, + {19609,19610,19611 ,8433,8434,8435 ,0,0,0}, {19612,19613,19614 ,8436,8437,8438 ,0,0,0}, + {19615,19616,19617 ,8439,8440,8441 ,0,0,0}, {19618,19619,19620 ,8442,8443,8444 ,0,0,0}, + {19620,19535,19618 ,8444,8445,8442 ,0,0,0}, {19621,19622,19623 ,8446,8447,8448 ,0,0,0}, + {19600,19624,19597 ,8449,8450,8451 ,0,0,0}, {19625,19623,19626 ,8452,8448,8453 ,0,0,0}, + {19627,19628,19629 ,8454,8455,8456 ,0,0,0}, {19630,19631,19632 ,8457,8458,8459 ,0,0,0}, + {19633,19634,19635 ,8460,8461,8462 ,0,0,0}, {19636,19624,19629 ,8463,8450,8456 ,0,0,0}, + {19637,19549,19552 ,8464,8465,8466 ,0,0,0}, {19638,19639,19635 ,8467,8468,8462 ,0,0,0}, + {19640,19641,19642 ,8469,8470,8471 ,0,0,0}, {19643,19644,19640 ,8472,8473,8469 ,0,0,0}, + {19645,19646,19643 ,8474,8475,8472 ,0,0,0}, {19647,19643,19646 ,8476,8472,8475 ,0,0,0}, + {19648,19646,19645 ,8477,8475,8474 ,0,0,0}, {19649,19650,19651 ,8478,8479,8480 ,0,0,0}, + {19652,19637,19641 ,8481,8464,8470 ,0,0,0}, {19653,19654,19649 ,8482,8483,8478 ,0,0,0}, + {19603,19605,19629 ,8484,8485,8456 ,0,0,0}, {19631,19655,19632 ,8458,8486,8459 ,0,0,0}, + {19622,19656,19623 ,8447,8487,8448 ,0,0,0}, {19657,19658,19659 ,8488,8489,8490 ,0,0,0}, + {19581,19660,19579 ,8491,8492,8493 ,0,0,0}, {19617,19656,19661 ,8441,8487,8494 ,0,0,0}, + {19662,19532,19663 ,8495,8496,8497 ,0,0,0}, {19664,19665,19615 ,8498,8499,8439 ,0,0,0}, + {19610,19666,19667 ,8434,8500,8501 ,0,0,0}, {19668,19669,19670 ,8502,8503,8504 ,0,0,0}, + {19609,19611,19671 ,8433,8435,8505 ,0,0,0}, {19607,19606,19672 ,8431,8430,8506 ,0,0,0}, + {19673,19611,19668 ,8507,8435,8502 ,0,0,0}, {19674,19675,19676 ,8508,8509,8510 ,0,0,0}, + {19675,19672,19606 ,8509,8506,8430 ,0,0,0}, {19515,19677,19513 ,8511,8512,8513 ,0,0,0}, + {19678,19608,19679 ,8514,8432,8515 ,0,0,0}, {19609,19680,19681 ,8433,8516,8517 ,0,0,0}, + {19665,19591,19682 ,8499,8518,8519 ,0,0,0}, {19668,19611,19610 ,8502,8435,8434 ,0,0,0}, + {19668,19667,19683 ,8502,8501,8520 ,0,0,0}, {19610,19667,19668 ,8434,8501,8502 ,0,0,0}, + {19684,19685,19613 ,8521,8522,8437 ,0,0,0}, {19673,19612,19686 ,8507,8436,8523 ,0,0,0}, + {19608,19523,19522 ,8432,8524,8525 ,0,0,0}, {19687,19685,19684 ,8526,8522,8521 ,0,0,0}, + {19607,19687,19684 ,8431,8526,8521 ,0,0,0}, {19675,19606,19676 ,8509,8430,8510 ,0,0,0}, + {19672,19687,19607 ,8506,8526,8431 ,0,0,0}, {19679,19608,19522 ,8515,8432,8525 ,0,0,0}, + {19608,19678,19688 ,8432,8514,8527 ,0,0,0}, {19677,19679,19513 ,8512,8515,8513 ,0,0,0}, + {19679,19677,19678 ,8515,8512,8514 ,0,0,0}, {19527,19662,19515 ,8528,8495,8511 ,0,0,0}, + {19532,19662,19530 ,8496,8495,8529 ,0,0,0}, {19662,19677,19515 ,8495,8512,8511 ,0,0,0}, + {19663,19689,19662 ,8497,8530,8495 ,0,0,0}, {19533,19663,19532 ,8531,8497,8496 ,0,0,0}, + {19663,19535,19620 ,8497,8445,8444 ,0,0,0}, {19584,19690,19660 ,8532,8533,8492 ,0,0,0}, + {19691,19626,19623 ,8534,8453,8448 ,0,0,0}, {19631,19692,19693 ,8458,8535,8536 ,0,0,0}, + {19543,19692,19545 ,8537,8535,8538 ,0,0,0}, {19691,19694,19695 ,8534,8539,8540 ,0,0,0}, + {19625,19621,19623 ,8452,8446,8448 ,0,0,0}, {19581,19584,19660 ,8491,8532,8492 ,0,0,0}, + {19622,19696,19656 ,8447,8541,8487 ,0,0,0}, {19623,19656,19697 ,8448,8487,8542 ,0,0,0}, + {19656,19617,19616 ,8487,8441,8440 ,0,0,0}, {19665,19616,19615 ,8499,8440,8439 ,0,0,0}, + {19656,19616,19698 ,8487,8440,8543 ,0,0,0}, {19699,19682,19657 ,8544,8519,8488 ,0,0,0}, + {19665,19700,19616 ,8499,8545,8440 ,0,0,0}, {19610,19681,19620 ,8434,8517,8444 ,0,0,0}, + {19680,19700,19699 ,8516,8545,8544 ,0,0,0}, {19659,19663,19620 ,8490,8497,8444 ,0,0,0}, + {19620,19619,19610 ,8444,8443,8434 ,0,0,0}, {19659,19701,19663 ,8490,8546,8497 ,0,0,0}, + {19702,19659,19658 ,8547,8490,8489 ,0,0,0}, {19660,19703,19658 ,8492,8548,8489 ,0,0,0}, + {19660,19690,19704 ,8492,8533,8549 ,0,0,0}, {19584,19588,19690 ,8532,8550,8533 ,0,0,0}, + {19588,19596,19690 ,8550,8551,8533 ,0,0,0}, {19690,19624,19705 ,8533,8450,8552 ,0,0,0}, + {19600,19629,19624 ,8449,8456,8450 ,0,0,0}, {19602,19629,19600 ,8553,8456,8449 ,0,0,0}, + {19629,19602,19603 ,8456,8553,8484 ,0,0,0}, {19690,19597,19624 ,8533,8451,8450 ,0,0,0}, + {19605,19627,19629 ,8485,8454,8456 ,0,0,0}, {19706,19692,19707 ,8554,8535,8555 ,0,0,0}, + {19654,19653,19708 ,8483,8482,8556 ,0,0,0}, {19709,19640,19649 ,8557,8469,8478 ,0,0,0}, + {19649,19640,19710 ,8478,8469,8558 ,0,0,0}, {19710,19650,19649 ,8558,8479,8478 ,0,0,0}, + {19649,19654,19709 ,8478,8483,8557 ,0,0,0}, {19711,19636,19628 ,8559,8463,8455 ,0,0,0}, + {19655,19654,19708 ,8486,8483,8556 ,0,0,0}, {19655,19708,19712 ,8486,8556,8560 ,0,0,0}, + {19632,19655,19713 ,8459,8486,8561 ,0,0,0}, {19630,19545,19631 ,8457,8538,8458 ,0,0,0}, + {19714,19691,19693 ,8562,8534,8536 ,0,0,0}, {19692,19631,19545 ,8535,8458,8538 ,0,0,0}, + {19627,19605,19715 ,8454,8485,8563 ,0,0,0}, {19626,19627,19716 ,8453,8454,8564 ,0,0,0}, + {19706,19628,19714 ,8554,8455,8562 ,0,0,0}, {19706,19717,19711 ,8554,8565,8559 ,0,0,0}, + {19718,19548,19549 ,8566,8567,8465 ,0,0,0}, {19718,19544,19548 ,8566,8568,8567 ,0,0,0}, + {19719,19718,19639 ,8569,8566,8468 ,0,0,0}, {19717,19707,19719 ,8565,8555,8569 ,0,0,0}, + {19549,19637,19718 ,8465,8464,8566 ,0,0,0}, {19557,19642,19641 ,8570,8471,8470 ,0,0,0}, + {19684,19720,19607 ,8521,8571,8431 ,0,0,0}, {19614,19613,19685 ,8438,8437,8522 ,0,0,0}, + {19673,19721,19613 ,8507,8572,8437 ,0,0,0}, {19525,19523,19720 ,8573,8524,8571 ,0,0,0}, + {19721,19720,19684 ,8572,8571,8521 ,0,0,0}, {19720,19523,19608 ,8571,8524,8432 ,0,0,0}, + {19607,19720,19608 ,8431,8571,8432 ,0,0,0}, {19688,19676,19606 ,8527,8510,8430 ,0,0,0}, + {19612,19673,19613 ,8436,8507,8437 ,0,0,0}, {19686,19671,19611 ,8523,8505,8435 ,0,0,0}, + {19720,19722,19723 ,8571,8574,8575 ,0,0,0}, {19613,19721,19684 ,8437,8572,8521 ,0,0,0}, + {19670,19721,19668 ,8504,8572,8502 ,0,0,0}, {19525,19720,19723 ,8573,8571,8575 ,0,0,0}, + {19522,19519,19679 ,8525,8576,8515 ,0,0,0}, {19688,19606,19608 ,8527,8430,8432 ,0,0,0}, + {19686,19611,19673 ,8523,8435,8507 ,0,0,0}, {19671,19724,19609 ,8505,8577,8433 ,0,0,0}, + {19669,19668,19683 ,8503,8502,8520 ,0,0,0}, {19673,19668,19721 ,8507,8502,8572 ,0,0,0}, + {19722,19721,19670 ,8574,8572,8504 ,0,0,0}, {19721,19722,19720 ,8572,8574,8571 ,0,0,0}, + {19519,19516,19679 ,8576,8578,8515 ,0,0,0}, {19679,19516,19513 ,8515,8578,8513 ,0,0,0}, + {19725,19680,19724 ,8579,8516,8577 ,0,0,0}, {19725,19726,19700 ,8579,8580,8545 ,0,0,0}, + {19666,19610,19727 ,8500,8434,8581 ,0,0,0}, {19619,19727,19610 ,8443,8581,8434 ,0,0,0}, + {19677,19662,19689 ,8512,8495,8530 ,0,0,0}, {19527,19530,19662 ,8528,8529,8495 ,0,0,0}, + {19680,19609,19724 ,8516,8433,8577 ,0,0,0}, {19728,19591,19665 ,8582,8518,8499 ,0,0,0}, + {19620,19681,19657 ,8444,8517,8488 ,0,0,0}, {19609,19681,19610 ,8433,8517,8434 ,0,0,0}, + {19657,19681,19699 ,8488,8517,8544 ,0,0,0}, {19535,19663,19533 ,8445,8497,8531 ,0,0,0}, + {19620,19657,19659 ,8444,8488,8490 ,0,0,0}, {19663,19701,19689 ,8497,8546,8530 ,0,0,0}, + {19725,19700,19680 ,8579,8545,8516 ,0,0,0}, {19729,19700,19726 ,8583,8545,8580 ,0,0,0}, + {19591,19593,19682 ,8518,8584,8519 ,0,0,0}, {19680,19699,19681 ,8516,8544,8517 ,0,0,0}, + {19665,19682,19699 ,8499,8519,8544 ,0,0,0}, {19579,19660,19586 ,8493,8492,8585 ,0,0,0}, + {19658,19657,19682 ,8489,8488,8519 ,0,0,0}, {19701,19659,19702 ,8546,8490,8547 ,0,0,0}, + {19700,19729,19616 ,8545,8583,8440 ,0,0,0}, {19698,19616,19729 ,8543,8440,8583 ,0,0,0}, + {19728,19665,19664 ,8582,8499,8498 ,0,0,0}, {19700,19665,19699 ,8545,8499,8544 ,0,0,0}, + {19593,19589,19682 ,8584,8586,8519 ,0,0,0}, {19682,19589,19586 ,8519,8586,8585 ,0,0,0}, + {19586,19658,19682 ,8585,8489,8519 ,0,0,0}, {19702,19658,19703 ,8547,8489,8548 ,0,0,0}, + {19656,19698,19697 ,8487,8543,8542 ,0,0,0}, {19696,19661,19656 ,8541,8494,8487 ,0,0,0}, + {19703,19660,19704 ,8548,8492,8549 ,0,0,0}, {19586,19660,19658 ,8585,8492,8489 ,0,0,0}, + {19697,19694,19623 ,8542,8539,8448 ,0,0,0}, {19623,19694,19691 ,8448,8539,8534 ,0,0,0}, + {19597,19690,19596 ,8451,8533,8551 ,0,0,0}, {19690,19705,19704 ,8533,8552,8549 ,0,0,0}, + {19691,19627,19626 ,8534,8454,8453 ,0,0,0}, {19695,19730,19693 ,8540,8587,8536 ,0,0,0}, + {19541,19692,19543 ,8588,8535,8537 ,0,0,0}, {19716,19627,19715 ,8564,8454,8563 ,0,0,0}, + {19714,19627,19691 ,8562,8454,8534 ,0,0,0}, {19731,19624,19636 ,8589,8450,8463 ,0,0,0}, + {19629,19628,19636 ,8456,8455,8463 ,0,0,0}, {19705,19624,19731 ,8552,8450,8589 ,0,0,0}, + {19695,19693,19691 ,8540,8536,8534 ,0,0,0}, {19730,19732,19631 ,8587,8590,8458 ,0,0,0}, + {19537,19707,19538 ,8591,8555,8592 ,0,0,0}, {19627,19714,19628 ,8454,8562,8455 ,0,0,0}, + {19714,19693,19692 ,8562,8536,8535 ,0,0,0}, {19636,19733,19734 ,8463,8593,8594 ,0,0,0}, + {19628,19706,19711 ,8455,8554,8559 ,0,0,0}, {19731,19636,19734 ,8589,8463,8594 ,0,0,0}, + {19730,19631,19693 ,8587,8458,8536 ,0,0,0}, {19732,19655,19631 ,8590,8486,8458 ,0,0,0}, + {19707,19541,19538 ,8555,8588,8592 ,0,0,0}, {19714,19692,19706 ,8562,8535,8554 ,0,0,0}, + {19692,19541,19707 ,8535,8588,8555 ,0,0,0}, {19711,19735,19733 ,8559,8595,8593 ,0,0,0}, + {19706,19707,19717 ,8554,8555,8565 ,0,0,0}, {19733,19636,19711 ,8593,8463,8559 ,0,0,0}, + {19654,19655,19732 ,8483,8486,8590 ,0,0,0}, {19712,19713,19655 ,8560,8561,8486 ,0,0,0}, + {19718,19537,19544 ,8566,8591,8568 ,0,0,0}, {19717,19736,19735 ,8565,8596,8595 ,0,0,0}, + {19707,19718,19719 ,8555,8566,8569 ,0,0,0}, {19735,19711,19717 ,8595,8559,8565 ,0,0,0}, + {19649,19651,19653 ,8478,8480,8482 ,0,0,0}, {19709,19737,19640 ,8557,8597,8469 ,0,0,0}, + {19552,19555,19641 ,8466,8598,8470 ,0,0,0}, {19552,19641,19637 ,8466,8470,8464 ,0,0,0}, + {19719,19638,19736 ,8569,8467,8596 ,0,0,0}, {19718,19707,19537 ,8566,8555,8591 ,0,0,0}, + {19718,19637,19639 ,8566,8464,8468 ,0,0,0}, {19736,19717,19719 ,8596,8565,8569 ,0,0,0}, + {19640,19642,19710 ,8469,8471,8558 ,0,0,0}, {19737,19645,19643 ,8597,8474,8472 ,0,0,0}, + {19738,19634,19633 ,8599,8461,8460 ,0,0,0}, {19557,19641,19555 ,8570,8470,8598 ,0,0,0}, + {19641,19644,19652 ,8470,8473,8481 ,0,0,0}, {19633,19639,19637 ,8460,8468,8464 ,0,0,0}, + {19652,19633,19637 ,8481,8460,8464 ,0,0,0}, {19638,19719,19639 ,8467,8569,8468 ,0,0,0}, + {19737,19643,19640 ,8597,8472,8469 ,0,0,0}, {19640,19644,19641 ,8469,8473,8470 ,0,0,0}, + {19647,19739,19644 ,8476,8600,8473 ,0,0,0}, {19643,19647,19644 ,8472,8476,8473 ,0,0,0}, + {19739,19738,19652 ,8600,8599,8481 ,0,0,0}, {19644,19739,19652 ,8473,8600,8481 ,0,0,0}, + {19738,19633,19652 ,8599,8460,8481 ,0,0,0}, {19635,19639,19633 ,8462,8468,8460 ,0,0,0}, + {19740,19741,19742 ,8601,8602,8603 ,0,0,0}, {19743,19744,19741 ,8604,8605,8602 ,0,0,0}, + {19745,19746,19747 ,8606,8607,8608 ,0,0,0}, {19748,19749,19750 ,8609,8610,8611 ,0,0,0}, + {19751,19752,19753 ,8612,8613,8614 ,0,0,0}, {19754,19755,19756 ,8615,8616,8617 ,0,0,0}, + {19757,19758,19759 ,8618,8619,8620 ,0,0,0}, {19760,19761,19762 ,8621,8622,8623 ,0,0,0}, + {19763,19764,19765 ,8624,8625,8626 ,0,0,0}, {19766,19767,19768 ,8627,8628,8629 ,0,0,0}, + {19769,19770,19763 ,8630,8631,8624 ,0,0,0}, {19763,19765,19769 ,8624,8626,8630 ,0,0,0}, + {19770,19771,19772 ,8631,8632,8633 ,0,0,0}, {19771,19770,19769 ,8632,8631,8630 ,0,0,0}, + {19773,19772,19774 ,8634,8633,8635 ,0,0,0}, {19771,19774,19772 ,8632,8635,8633 ,0,0,0}, + {19775,19776,19773 ,8636,8637,8634 ,0,0,0}, {19773,19774,19775 ,8634,8635,8636 ,0,0,0}, + {19777,19776,19775 ,8638,8637,8636 ,0,0,0}, {19764,19768,19765 ,8625,8629,8626 ,0,0,0}, + {19766,19758,19767 ,8627,8619,8628 ,0,0,0}, {19764,19766,19768 ,8625,8627,8629 ,0,0,0}, + {19757,19759,19760 ,8618,8620,8621 ,0,0,0}, {19767,19758,19757 ,8628,8619,8618 ,0,0,0}, + {19762,19761,19753 ,8623,8622,8614 ,0,0,0}, {19760,19759,19761 ,8621,8620,8622 ,0,0,0}, + {19755,19752,19751 ,8616,8613,8612 ,0,0,0}, {19752,19762,19753 ,8613,8623,8614 ,0,0,0}, + {19778,19754,19756 ,8639,8615,8617 ,0,0,0}, {19756,19755,19751 ,8617,8616,8612 ,0,0,0}, + {19745,19778,19746 ,8606,8639,8607 ,0,0,0}, {19778,19745,19754 ,8639,8606,8615 ,0,0,0}, + {19747,19748,19750 ,8608,8609,8611 ,0,0,0}, {19746,19748,19747 ,8607,8609,8608 ,0,0,0}, + {19743,19749,19744 ,8604,8610,8605 ,0,0,0}, {19750,19749,19743 ,8611,8610,8604 ,0,0,0}, + {19742,19779,19740 ,8603,8640,8601 ,0,0,0}, {19741,19744,19742 ,8602,8605,8603 ,0,0,0}, + {19780,19781,19741 ,8641,8642,8643 ,0,0,0}, {19782,19743,19781 ,8644,8645,8642 ,0,0,0}, + {19754,19745,19783 ,8646,8647,8648 ,0,0,0}, {19747,19750,19784 ,8649,8650,8651 ,0,0,0}, + {19752,19785,19762 ,8652,8653,8654 ,0,0,0}, {19786,19787,19755 ,8655,8656,8657 ,0,0,0}, + {19788,19767,19757 ,8658,8659,8660 ,0,0,0}, {19789,19760,19790 ,8661,8662,8663 ,0,0,0}, + {19769,19765,19791 ,8664,8665,8666 ,0,0,0}, {19768,19792,19793 ,8667,8668,8669 ,0,0,0}, + {19794,19771,19769 ,8670,8671,8664 ,0,0,0}, {19769,19791,19794 ,8664,8666,8670 ,0,0,0}, + {19771,19795,19774 ,8671,8672,8673 ,0,0,0}, {19795,19771,19794 ,8672,8671,8670 ,0,0,0}, + {19775,19774,19796 ,8674,8673,8675 ,0,0,0}, {19795,19796,19774 ,8672,8675,8673 ,0,0,0}, + {19797,19777,19775 ,8676,8638,8674 ,0,0,0}, {19775,19796,19797 ,8674,8675,8676 ,0,0,0}, + {19798,19777,19797 ,8677,8638,8676 ,0,0,0}, {19765,19793,19791 ,8665,8669,8666 ,0,0,0}, + {19768,19767,19792 ,8667,8659,8668 ,0,0,0}, {19765,19768,19793 ,8665,8667,8669 ,0,0,0}, + {19788,19757,19789 ,8658,8660,8661 ,0,0,0}, {19792,19767,19788 ,8668,8659,8658 ,0,0,0}, + {19790,19760,19762 ,8663,8662,8654 ,0,0,0}, {19789,19757,19760 ,8661,8660,8662 ,0,0,0}, + {19787,19785,19752 ,8656,8653,8652 ,0,0,0}, {19785,19790,19762 ,8653,8663,8654 ,0,0,0}, + {19754,19786,19755 ,8646,8655,8657 ,0,0,0}, {19755,19787,19752 ,8657,8656,8652 ,0,0,0}, + {19745,19799,19783 ,8647,8678,8648 ,0,0,0}, {19754,19783,19786 ,8646,8648,8655 ,0,0,0}, + {19784,19799,19747 ,8651,8678,8649 ,0,0,0}, {19745,19747,19799 ,8647,8649,8678 ,0,0,0}, + {19782,19750,19743 ,8644,8650,8645 ,0,0,0}, {19784,19750,19782 ,8651,8650,8644 ,0,0,0}, + {19741,19740,19780 ,8643,8601,8641 ,0,0,0}, {19781,19743,19741 ,8642,8645,8643 ,0,0,0}, + {19800,19801,19781 ,8679,8680,8681 ,0,0,0}, {19784,19782,19802 ,8651,8644,8682 ,0,0,0}, + {19786,19783,19803 ,8683,8684,8685 ,0,0,0}, {19799,19804,19805 ,8678,8686,8687 ,0,0,0}, + {19785,19806,19790 ,8688,8689,8690 ,0,0,0}, {19807,19808,19787 ,8691,8692,8693 ,0,0,0}, + {19809,19792,19810 ,8694,8695,8696 ,0,0,0}, {19788,19789,19811 ,8697,8698,8699 ,0,0,0}, + {19794,19791,19812 ,8700,8701,8702 ,0,0,0}, {19793,19813,19791 ,8703,8704,8701 ,0,0,0}, + {19814,19795,19794 ,8705,8706,8700 ,0,0,0}, {19794,19812,19814 ,8700,8702,8705 ,0,0,0}, + {19795,19815,19796 ,8706,8707,8675 ,0,0,0}, {19815,19795,19814 ,8707,8706,8705 ,0,0,0}, + {19797,19796,19816 ,8708,8675,8709 ,0,0,0}, {19815,19816,19796 ,8707,8709,8675 ,0,0,0}, + {19816,19817,19798 ,8709,8710,8677 ,0,0,0}, {19798,19797,19816 ,8677,8708,8709 ,0,0,0}, + {19812,19791,19813 ,8702,8701,8704 ,0,0,0}, {19793,19792,19809 ,8703,8695,8694 ,0,0,0}, + {19793,19809,19813 ,8703,8694,8704 ,0,0,0}, {19810,19788,19811 ,8696,8697,8699 ,0,0,0}, + {19792,19788,19810 ,8695,8697,8696 ,0,0,0}, {19818,19789,19790 ,8711,8698,8690 ,0,0,0}, + {19811,19789,19818 ,8699,8698,8711 ,0,0,0}, {19808,19806,19785 ,8692,8689,8688 ,0,0,0}, + {19806,19818,19790 ,8689,8711,8690 ,0,0,0}, {19786,19807,19787 ,8683,8691,8693 ,0,0,0}, + {19787,19808,19785 ,8693,8692,8688 ,0,0,0}, {19783,19805,19803 ,8684,8687,8685 ,0,0,0}, + {19786,19803,19807 ,8683,8685,8691 ,0,0,0}, {19799,19784,19804 ,8678,8651,8686 ,0,0,0}, + {19783,19799,19805 ,8684,8678,8687 ,0,0,0}, {19802,19782,19801 ,8682,8644,8680 ,0,0,0}, + {19804,19784,19802 ,8686,8651,8682 ,0,0,0}, {19800,19781,19780 ,8679,8681,8641 ,0,0,0}, + {19801,19782,19781 ,8680,8644,8681 ,0,0,0}, {19819,19820,19801 ,8712,8713,8714 ,0,0,0}, + {19804,19802,19821 ,8715,8716,8717 ,0,0,0}, {19807,19803,19822 ,8718,8719,8720 ,0,0,0}, + {19805,19804,19823 ,8721,8715,8722 ,0,0,0}, {19806,19824,19818 ,8723,8724,8725 ,0,0,0}, + {19825,19826,19808 ,8726,8727,8728 ,0,0,0}, {19827,19809,19810 ,8729,8730,8731 ,0,0,0}, + {19828,19811,19829 ,8732,8733,8734 ,0,0,0}, {19830,19812,19831 ,8735,8736,8737 ,0,0,0}, + {19813,19832,19831 ,8738,8739,8737 ,0,0,0}, {19830,19833,19814 ,8735,8740,8741 ,0,0,0}, + {19814,19812,19830 ,8741,8736,8735 ,0,0,0}, {19815,19833,19834 ,8742,8740,8743 ,0,0,0}, + {19833,19815,19814 ,8740,8742,8741 ,0,0,0}, {19835,19816,19834 ,8744,8745,8743 ,0,0,0}, + {19815,19834,19816 ,8742,8743,8745 ,0,0,0}, {19835,19836,19817 ,8744,8746,8710 ,0,0,0}, + {19817,19816,19835 ,8710,8745,8744 ,0,0,0}, {19831,19812,19813 ,8737,8736,8738 ,0,0,0}, + {19832,19809,19827 ,8739,8730,8729 ,0,0,0}, {19813,19809,19832 ,8738,8730,8739 ,0,0,0}, + {19828,19810,19811 ,8732,8731,8733 ,0,0,0}, {19827,19810,19828 ,8729,8731,8732 ,0,0,0}, + {19824,19829,19818 ,8724,8734,8725 ,0,0,0}, {19829,19811,19818 ,8734,8733,8725 ,0,0,0}, + {19808,19826,19806 ,8728,8727,8723 ,0,0,0}, {19826,19824,19806 ,8727,8724,8723 ,0,0,0}, + {19807,19822,19825 ,8718,8720,8726 ,0,0,0}, {19807,19825,19808 ,8718,8726,8728 ,0,0,0}, + {19803,19805,19837 ,8719,8721,8747 ,0,0,0}, {19803,19837,19822 ,8719,8747,8720 ,0,0,0}, + {19823,19804,19821 ,8722,8715,8717 ,0,0,0}, {19837,19805,19823 ,8747,8721,8722 ,0,0,0}, + {19820,19802,19801 ,8713,8716,8714 ,0,0,0}, {19821,19802,19820 ,8717,8716,8713 ,0,0,0}, + {19819,19801,19800 ,8712,8714,8679 ,0,0,0}, {19834,19838,19839 ,8748,8749,8750 ,0,0,0}, + {19836,19835,19840 ,8746,8751,8752 ,0,0,0}, {19841,19831,19842 ,8753,8754,8755 ,0,0,0}, + {19830,19843,19833 ,8756,8757,8758 ,0,0,0}, {19829,19844,19828 ,8759,8760,8761 ,0,0,0}, + {19827,19845,19832 ,8762,8763,8764 ,0,0,0}, {19846,19826,19825 ,8765,8766,8767 ,0,0,0}, + {19847,19824,19848 ,8768,8769,8770 ,0,0,0}, {19849,19837,19850 ,8771,8772,8773 ,0,0,0}, + {19822,19849,19851 ,8774,8771,8775 ,0,0,0}, {19852,19850,19823 ,8776,8773,8777 ,0,0,0}, + {19837,19823,19850 ,8772,8777,8773 ,0,0,0}, {19821,19853,19852 ,8778,8779,8776 ,0,0,0}, + {19852,19823,19821 ,8776,8777,8778 ,0,0,0}, {19853,19820,19854 ,8779,8780,8781 ,0,0,0}, + {19820,19853,19821 ,8780,8779,8778 ,0,0,0}, {19851,19825,19822 ,8775,8767,8774 ,0,0,0}, + {19854,19820,19819 ,8781,8780,8782 ,0,0,0}, {19849,19822,19837 ,8771,8774,8772 ,0,0,0}, + {19846,19848,19826 ,8765,8770,8766 ,0,0,0}, {19851,19846,19825 ,8775,8765,8767 ,0,0,0}, + {19824,19847,19829 ,8769,8768,8759 ,0,0,0}, {19826,19848,19824 ,8766,8770,8769 ,0,0,0}, + {19828,19844,19855 ,8761,8760,8783 ,0,0,0}, {19829,19847,19844 ,8759,8768,8760 ,0,0,0}, + {19855,19845,19827 ,8783,8763,8762 ,0,0,0}, {19827,19828,19855 ,8762,8761,8783 ,0,0,0}, + {19842,19831,19832 ,8755,8754,8764 ,0,0,0}, {19842,19832,19845 ,8755,8764,8763 ,0,0,0}, + {19841,19843,19830 ,8753,8757,8756 ,0,0,0}, {19841,19830,19831 ,8753,8756,8754 ,0,0,0}, + {19833,19838,19834 ,8758,8749,8748 ,0,0,0}, {19843,19838,19833 ,8757,8749,8758 ,0,0,0}, + {19835,19839,19840 ,8751,8750,8752 ,0,0,0}, {19834,19839,19835 ,8748,8750,8751 ,0,0,0}, + {19836,19840,19856 ,8746,8752,8784 ,0,0,0}, {19857,19858,19859 ,8785,8786,8787 ,0,0,0}, + {19860,19861,19862 ,8788,8789,8790 ,0,0,0}, {19861,19863,19864 ,8789,8791,8792 ,0,0,0}, + {19864,19862,19861 ,8792,8790,8789 ,0,0,0}, {19861,19859,19865 ,8789,8787,8793 ,0,0,0}, + {19863,19866,19864 ,8791,8794,8792 ,0,0,0}, {19867,19868,19869 ,8795,8796,8797 ,0,0,0}, + {19819,19858,19854 ,8782,8786,8798 ,0,0,0}, {19870,19871,19872 ,8799,8800,8801 ,0,0,0}, + {19850,19852,19873 ,8802,8803,8804 ,0,0,0}, {19874,19875,19876 ,8805,8806,8807 ,0,0,0}, + {19851,19877,19846 ,8808,8809,8810 ,0,0,0}, {19878,19879,19845 ,8811,8812,8813 ,0,0,0}, + {19880,19881,19876 ,8814,8815,8807 ,0,0,0}, {19882,19883,19884 ,8816,8817,8818 ,0,0,0}, + {19885,19879,19886 ,8819,8812,8820 ,0,0,0}, {19839,19883,19840 ,8821,8817,8822 ,0,0,0}, + {19840,19887,19856 ,8822,8823,8824 ,0,0,0}, {19888,19889,19884 ,8825,8826,8818 ,0,0,0}, + {19840,19883,19887 ,8822,8817,8823 ,0,0,0}, {19890,19882,19891 ,8827,8816,8828 ,0,0,0}, + {19888,19884,19838 ,8825,8818,8829 ,0,0,0}, {19888,19892,19893 ,8825,8830,8831 ,0,0,0}, + {19843,19892,19888 ,8832,8830,8825 ,0,0,0}, {19842,19879,19885 ,8833,8812,8819 ,0,0,0}, + {19892,19885,19894 ,8830,8819,8834 ,0,0,0}, {19892,19841,19885 ,8830,8835,8819 ,0,0,0}, + {19895,19878,19881 ,8836,8811,8815 ,0,0,0}, {19896,19879,19878 ,8837,8812,8811 ,0,0,0}, + {19881,19844,19847 ,8815,8838,8839 ,0,0,0}, {19881,19878,19855 ,8815,8811,8840 ,0,0,0}, + {19846,19874,19848 ,8810,8805,8841 ,0,0,0}, {19848,19876,19847 ,8841,8807,8839 ,0,0,0}, + {19870,19897,19877 ,8799,8842,8809 ,0,0,0}, {19877,19898,19874 ,8809,8843,8805 ,0,0,0}, + {19849,19850,19871 ,8844,8802,8800 ,0,0,0}, {19851,19849,19870 ,8808,8844,8799 ,0,0,0}, + {19868,19899,19873 ,8796,8845,8804 ,0,0,0}, {19872,19871,19899 ,8801,8800,8845 ,0,0,0}, + {19900,19853,19854 ,8846,8847,8798 ,0,0,0}, {19869,19852,19853 ,8797,8803,8847 ,0,0,0}, + {19901,19865,19859 ,8848,8793,8787 ,0,0,0}, {19900,19857,19867 ,8846,8785,8795 ,0,0,0}, + {19859,19858,19901 ,8787,8786,8848 ,0,0,0}, {19863,19861,19865 ,8791,8789,8793 ,0,0,0}, + {19902,19860,19862 ,8849,8788,8790 ,0,0,0}, {19903,19860,19902 ,8850,8788,8849 ,0,0,0}, + {19858,19819,19901 ,8786,8782,8848 ,0,0,0}, {19859,19860,19857 ,8787,8788,8785 ,0,0,0}, + {19854,19858,19900 ,8798,8786,8846 ,0,0,0}, {19861,19860,19859 ,8789,8788,8787 ,0,0,0}, + {19904,19903,19902 ,8851,8850,8849 ,0,0,0}, {19905,19903,19904 ,8852,8850,8851 ,0,0,0}, + {19858,19857,19900 ,8786,8785,8846 ,0,0,0}, {19857,19903,19867 ,8785,8850,8795 ,0,0,0}, + {19853,19900,19869 ,8847,8846,8797 ,0,0,0}, {19860,19903,19857 ,8788,8850,8785 ,0,0,0}, + {19906,19905,19904 ,8853,8852,8851 ,0,0,0}, {19907,19905,19906 ,8854,8852,8853 ,0,0,0}, + {19900,19867,19869 ,8846,8795,8797 ,0,0,0}, {19867,19905,19868 ,8795,8852,8796 ,0,0,0}, + {19852,19869,19873 ,8803,8797,8804 ,0,0,0}, {19903,19905,19867 ,8850,8852,8795 ,0,0,0}, + {19908,19907,19906 ,8855,8854,8853 ,0,0,0}, {19909,19907,19908 ,8856,8854,8855 ,0,0,0}, + {19869,19868,19873 ,8797,8796,8804 ,0,0,0}, {19868,19907,19899 ,8796,8854,8845 ,0,0,0}, + {19850,19873,19871 ,8802,8804,8800 ,0,0,0}, {19905,19907,19868 ,8852,8854,8796 ,0,0,0}, + {19910,19909,19908 ,8857,8856,8855 ,0,0,0}, {19911,19909,19910 ,8858,8856,8857 ,0,0,0}, + {19873,19899,19871 ,8804,8845,8800 ,0,0,0}, {19899,19909,19872 ,8845,8856,8801 ,0,0,0}, + {19849,19871,19870 ,8844,8800,8799 ,0,0,0}, {19907,19909,19899 ,8854,8856,8845 ,0,0,0}, + {19912,19911,19910 ,8859,8858,8857 ,0,0,0}, {19913,19914,19891 ,8860,8861,8828 ,0,0,0}, + {19915,19911,19912 ,8862,8858,8859 ,0,0,0}, {19872,19911,19897 ,8801,8858,8842 ,0,0,0}, + {19851,19870,19877 ,8808,8799,8809 ,0,0,0}, {19909,19911,19872 ,8856,8858,8801 ,0,0,0}, + {19916,19915,19912 ,8863,8862,8859 ,0,0,0}, {19917,19918,19915 ,8864,8865,8862 ,0,0,0}, + {19872,19897,19870 ,8801,8842,8799 ,0,0,0}, {19897,19915,19898 ,8842,8862,8843 ,0,0,0}, + {19846,19877,19874 ,8810,8809,8805 ,0,0,0}, {19911,19915,19897 ,8858,8862,8842 ,0,0,0}, + {19916,19917,19915 ,8863,8864,8862 ,0,0,0}, {19919,19920,19918 ,8866,8867,8865 ,0,0,0}, + {19897,19898,19877 ,8842,8843,8809 ,0,0,0}, {19898,19918,19875 ,8843,8865,8806 ,0,0,0}, + {19848,19874,19876 ,8841,8805,8807 ,0,0,0}, {19915,19918,19898 ,8862,8865,8843 ,0,0,0}, + {19917,19919,19918 ,8864,8866,8865 ,0,0,0}, {19921,19922,19920 ,8868,8869,8867 ,0,0,0}, + {19898,19875,19874 ,8843,8806,8805 ,0,0,0}, {19920,19880,19875 ,8867,8814,8806 ,0,0,0}, + {19847,19876,19881 ,8839,8807,8815 ,0,0,0}, {19918,19920,19875 ,8865,8867,8806 ,0,0,0}, + {19919,19921,19920 ,8866,8868,8867 ,0,0,0}, {19922,19923,19924 ,8869,8870,8871 ,0,0,0}, + {19875,19880,19876 ,8806,8814,8807 ,0,0,0}, {19922,19895,19880 ,8869,8836,8814 ,0,0,0}, + {19855,19844,19881 ,8840,8838,8815 ,0,0,0}, {19920,19922,19880 ,8867,8869,8814 ,0,0,0}, + {19921,19923,19922 ,8868,8870,8869 ,0,0,0}, {19924,19925,19926 ,8871,8872,8873 ,0,0,0}, + {19880,19895,19881 ,8814,8836,8815 ,0,0,0}, {19924,19896,19895 ,8871,8837,8836 ,0,0,0}, + {19845,19855,19878 ,8813,8840,8811 ,0,0,0}, {19922,19924,19895 ,8869,8871,8836 ,0,0,0}, + {19923,19925,19924 ,8870,8872,8871 ,0,0,0}, {19926,19927,19928 ,8873,8874,8875 ,0,0,0}, + {19895,19896,19878 ,8836,8837,8811 ,0,0,0}, {19926,19886,19896 ,8873,8820,8837 ,0,0,0}, + {19842,19845,19879 ,8833,8813,8812 ,0,0,0}, {19924,19926,19896 ,8871,8873,8837 ,0,0,0}, + {19925,19927,19926 ,8872,8874,8873 ,0,0,0}, {19928,19929,19930 ,8875,8876,8877 ,0,0,0}, + {19896,19886,19879 ,8837,8820,8812 ,0,0,0}, {19928,19894,19886 ,8875,8834,8820 ,0,0,0}, + {19841,19842,19885 ,8835,8833,8819 ,0,0,0}, {19926,19928,19886 ,8873,8875,8820 ,0,0,0}, + {19927,19929,19928 ,8874,8876,8875 ,0,0,0}, {19930,19931,19932 ,8877,8878,8879 ,0,0,0}, + {19886,19894,19885 ,8820,8834,8819 ,0,0,0}, {19930,19893,19894 ,8877,8831,8834 ,0,0,0}, + {19843,19841,19892 ,8832,8835,8830 ,0,0,0}, {19928,19930,19894 ,8875,8877,8834 ,0,0,0}, + {19929,19931,19930 ,8876,8878,8877 ,0,0,0}, {19891,19932,19913 ,8828,8879,8860 ,0,0,0}, + {19894,19893,19892 ,8834,8831,8830 ,0,0,0}, {19893,19932,19889 ,8831,8879,8826 ,0,0,0}, + {19838,19843,19888 ,8829,8832,8825 ,0,0,0}, {19930,19932,19893 ,8877,8879,8831 ,0,0,0}, + {19931,19913,19932 ,8878,8860,8879 ,0,0,0}, {19839,19884,19883 ,8821,8818,8817 ,0,0,0}, + {19893,19889,19888 ,8831,8826,8825 ,0,0,0}, {19891,19882,19889 ,8828,8816,8826 ,0,0,0}, + {19839,19838,19884 ,8821,8829,8818 ,0,0,0}, {19891,19889,19932 ,8828,8826,8879 ,0,0,0}, + {19914,19890,19891 ,8861,8827,8828 ,0,0,0}, {19933,19882,19890 ,8880,8816,8827 ,0,0,0}, + {19889,19882,19884 ,8826,8816,8818 ,0,0,0}, {19882,19933,19883 ,8816,8880,8817 ,0,0,0}, + {19887,19883,19933 ,8823,8817,8880 ,0,0,0}, {19934,19935,19864 ,8881,8882,8883 ,0,0,0}, + {19902,19862,19936 ,8884,8885,8886 ,0,0,0}, {19908,19906,19937 ,8887,8888,8889 ,0,0,0}, + {19904,19938,19939 ,8890,8891,8892 ,0,0,0}, {19940,19941,19916 ,8893,8894,8895 ,0,0,0}, + {19942,19943,19910 ,8896,8897,8898 ,0,0,0}, {19944,19921,19945 ,8899,8900,8901 ,0,0,0}, + {19919,19917,19946 ,8902,8903,8904 ,0,0,0}, {19927,19925,19947 ,8905,8906,8907 ,0,0,0}, + {19923,19948,19925 ,8908,8909,8906 ,0,0,0}, {19949,19929,19927 ,8910,8911,8905 ,0,0,0}, + {19927,19947,19949 ,8905,8907,8910 ,0,0,0}, {19929,19950,19931 ,8911,8912,8913 ,0,0,0}, + {19950,19929,19949 ,8912,8911,8910 ,0,0,0}, {19913,19931,19951 ,8914,8913,8915 ,0,0,0}, + {19950,19951,19931 ,8912,8915,8913 ,0,0,0}, {19951,19952,19914 ,8915,8916,8861 ,0,0,0}, + {19914,19913,19951 ,8861,8914,8915 ,0,0,0}, {19947,19925,19948 ,8907,8906,8909 ,0,0,0}, + {19923,19921,19944 ,8908,8900,8899 ,0,0,0}, {19923,19944,19948 ,8908,8899,8909 ,0,0,0}, + {19945,19919,19946 ,8901,8902,8904 ,0,0,0}, {19921,19919,19945 ,8900,8902,8901 ,0,0,0}, + {19941,19917,19916 ,8894,8903,8895 ,0,0,0}, {19946,19917,19941 ,8904,8903,8894 ,0,0,0}, + {19943,19940,19912 ,8897,8893,8917 ,0,0,0}, {19940,19916,19912 ,8893,8895,8917 ,0,0,0}, + {19908,19942,19910 ,8887,8896,8898 ,0,0,0}, {19910,19943,19912 ,8898,8897,8917 ,0,0,0}, + {19906,19939,19937 ,8888,8892,8889 ,0,0,0}, {19908,19937,19942 ,8887,8889,8896 ,0,0,0}, + {19904,19902,19938 ,8890,8884,8891 ,0,0,0}, {19906,19904,19939 ,8888,8890,8892 ,0,0,0}, + {19936,19862,19935 ,8886,8885,8882 ,0,0,0}, {19938,19902,19936 ,8891,8884,8886 ,0,0,0}, + {19934,19864,19866 ,8881,8883,8918 ,0,0,0}, {19935,19862,19864 ,8882,8885,8883 ,0,0,0}, + {19953,19954,19935 ,8919,8920,8921 ,0,0,0}, {19936,19935,19955 ,8922,8921,8923 ,0,0,0}, + {19937,19939,19956 ,8924,8925,8926 ,0,0,0}, {19938,19957,19958 ,8927,8928,8929 ,0,0,0}, + {19943,19959,19940 ,8930,8931,8932 ,0,0,0}, {19960,19961,19942 ,8933,8934,8935 ,0,0,0}, + {19962,19945,19946 ,8936,8937,8938 ,0,0,0}, {19963,19941,19964 ,8939,8940,8941 ,0,0,0}, + {19947,19948,19965 ,8942,8943,8944 ,0,0,0}, {19944,19966,19967 ,8945,8946,8947 ,0,0,0}, + {19968,19949,19947 ,8948,8949,8942 ,0,0,0}, {19947,19965,19968 ,8942,8944,8948 ,0,0,0}, + {19949,19969,19950 ,8949,8950,8951 ,0,0,0}, {19969,19949,19968 ,8950,8949,8948 ,0,0,0}, + {19951,19950,19970 ,8952,8951,8953 ,0,0,0}, {19969,19970,19950 ,8950,8953,8951 ,0,0,0}, + {19971,19952,19951 ,8954,8916,8952 ,0,0,0}, {19951,19970,19971 ,8952,8953,8954 ,0,0,0}, + {19972,19952,19971 ,8955,8916,8954 ,0,0,0}, {19948,19967,19965 ,8943,8947,8944 ,0,0,0}, + {19944,19945,19966 ,8945,8937,8946 ,0,0,0}, {19948,19944,19967 ,8943,8945,8947 ,0,0,0}, + {19962,19946,19963 ,8936,8938,8939 ,0,0,0}, {19966,19945,19962 ,8946,8937,8936 ,0,0,0}, + {19964,19941,19940 ,8941,8940,8932 ,0,0,0}, {19963,19946,19941 ,8939,8938,8940 ,0,0,0}, + {19961,19959,19943 ,8934,8931,8930 ,0,0,0}, {19959,19964,19940 ,8931,8941,8932 ,0,0,0}, + {19937,19960,19942 ,8924,8933,8935 ,0,0,0}, {19942,19961,19943 ,8935,8934,8930 ,0,0,0}, + {19939,19958,19956 ,8925,8929,8926 ,0,0,0}, {19937,19956,19960 ,8924,8926,8933 ,0,0,0}, + {19938,19936,19957 ,8927,8922,8928 ,0,0,0}, {19939,19938,19958 ,8925,8927,8929 ,0,0,0}, + {19955,19935,19954 ,8923,8921,8920 ,0,0,0}, {19957,19936,19955 ,8928,8922,8923 ,0,0,0}, + {19953,19935,19934 ,8919,8921,8881 ,0,0,0}, {19973,19974,19954 ,8956,8957,8958 ,0,0,0}, + {19975,19955,19974 ,8959,8923,8957 ,0,0,0}, {19960,19956,19976 ,8960,8961,8962 ,0,0,0}, + {19958,19957,19977 ,8929,8928,8963 ,0,0,0}, {19959,19978,19964 ,8964,8965,8966 ,0,0,0}, + {19979,19980,19961 ,8967,8968,8969 ,0,0,0}, {19981,19966,19962 ,8970,8971,8972 ,0,0,0}, + {19982,19963,19983 ,8973,8974,8975 ,0,0,0}, {19968,19965,19984 ,8948,8944,8976 ,0,0,0}, + {19967,19985,19986 ,8977,8978,8979 ,0,0,0}, {19987,19969,19968 ,8980,8950,8948 ,0,0,0}, + {19968,19984,19987 ,8948,8976,8980 ,0,0,0}, {19969,19988,19970 ,8950,8981,8953 ,0,0,0}, + {19988,19969,19987 ,8981,8950,8980 ,0,0,0}, {19971,19970,19989 ,8982,8953,8983 ,0,0,0}, + {19988,19989,19970 ,8981,8983,8953 ,0,0,0}, {19990,19972,19971 ,8984,8955,8982 ,0,0,0}, + {19971,19989,19990 ,8982,8983,8984 ,0,0,0}, {19991,19972,19990 ,8985,8955,8984 ,0,0,0}, + {19965,19986,19984 ,8944,8979,8976 ,0,0,0}, {19967,19966,19985 ,8977,8971,8978 ,0,0,0}, + {19965,19967,19986 ,8944,8977,8979 ,0,0,0}, {19981,19962,19982 ,8970,8972,8973 ,0,0,0}, + {19985,19966,19981 ,8978,8971,8970 ,0,0,0}, {19983,19963,19964 ,8975,8974,8966 ,0,0,0}, + {19982,19962,19963 ,8973,8972,8974 ,0,0,0}, {19980,19978,19959 ,8968,8965,8964 ,0,0,0}, + {19978,19983,19964 ,8965,8975,8966 ,0,0,0}, {19960,19979,19961 ,8960,8967,8969 ,0,0,0}, + {19961,19980,19959 ,8969,8968,8964 ,0,0,0}, {19956,19992,19976 ,8961,8986,8962 ,0,0,0}, + {19960,19976,19979 ,8960,8962,8967 ,0,0,0}, {19977,19992,19958 ,8963,8986,8929 ,0,0,0}, + {19956,19958,19992 ,8961,8929,8986 ,0,0,0}, {19975,19957,19955 ,8959,8928,8923 ,0,0,0}, + {19977,19957,19975 ,8963,8928,8959 ,0,0,0}, {19954,19953,19973 ,8958,8919,8956 ,0,0,0}, + {19974,19955,19954 ,8957,8923,8958 ,0,0,0}, {19993,19994,19974 ,8987,8988,8989 ,0,0,0}, + {19995,19975,19994 ,8990,8991,8988 ,0,0,0}, {19979,19976,19996 ,8992,8993,8994 ,0,0,0}, + {19992,19977,19997 ,8995,8996,8997 ,0,0,0}, {19978,19998,19983 ,8998,8999,9000 ,0,0,0}, + {19999,20000,19980 ,9001,9002,9003 ,0,0,0}, {20001,19985,19981 ,9004,9005,9006 ,0,0,0}, + {20002,19982,20003 ,9007,9008,9009 ,0,0,0}, {20004,19984,20005 ,9010,9011,9012 ,0,0,0}, + {19986,19985,20006 ,9013,9005,9014 ,0,0,0}, {20007,19988,19987 ,9015,9016,9017 ,0,0,0}, + {19987,20004,20007 ,9017,9010,9015 ,0,0,0}, {19988,20008,19989 ,9016,9018,9019 ,0,0,0}, + {20008,19988,20007 ,9018,9016,9015 ,0,0,0}, {19990,19989,20009 ,9020,9019,9021 ,0,0,0}, + {20008,20009,19989 ,9018,9021,9019 ,0,0,0}, {20010,19991,19990 ,9022,8985,9020 ,0,0,0}, + {19990,20009,20010 ,9020,9021,9022 ,0,0,0}, {20011,19991,20010 ,9023,8985,9022 ,0,0,0}, + {20004,19987,19984 ,9010,9017,9011 ,0,0,0}, {20005,19986,20006 ,9012,9013,9014 ,0,0,0}, + {19984,19986,20005 ,9011,9013,9012 ,0,0,0}, {19981,20002,20001 ,9006,9007,9004 ,0,0,0}, + {20006,19985,20001 ,9014,9005,9004 ,0,0,0}, {20003,19982,19983 ,9009,9008,9000 ,0,0,0}, + {20002,19981,19982 ,9007,9006,9008 ,0,0,0}, {20000,19998,19978 ,9002,8999,8998 ,0,0,0}, + {19998,20003,19983 ,8999,9009,9000 ,0,0,0}, {19979,19999,19980 ,8992,9001,9003 ,0,0,0}, + {19980,20000,19978 ,9003,9002,8998 ,0,0,0}, {19976,20012,19996 ,8993,9024,8994 ,0,0,0}, + {19979,19996,19999 ,8992,8994,9001 ,0,0,0}, {19997,20012,19992 ,8997,9024,8995 ,0,0,0}, + {19976,19992,20012 ,8993,8995,9024 ,0,0,0}, {19995,19977,19975 ,8990,8996,8991 ,0,0,0}, + {19997,19977,19995 ,8997,8996,8990 ,0,0,0}, {19974,19973,19993 ,8989,8956,8987 ,0,0,0}, + {19994,19975,19974 ,8988,8991,8989 ,0,0,0}, {20013,19993,20014 ,9025,8987,9026 ,0,0,0}, + {20015,19997,20016 ,9027,9028,9029 ,0,0,0}, {20017,19995,19994 ,9030,9031,9032 ,0,0,0}, + {19999,20018,20000 ,9033,9034,9035 ,0,0,0}, {20012,20019,19996 ,9036,9037,9038 ,0,0,0}, + {20020,20002,20003 ,9039,9040,9041 ,0,0,0}, {20021,19998,20022 ,9042,9043,9044 ,0,0,0}, + {20023,20006,20024 ,9045,9046,9047 ,0,0,0}, {20001,20025,20024 ,9048,9049,9047 ,0,0,0}, + {20007,20004,20026 ,9050,9051,9052 ,0,0,0}, {20005,20027,20004 ,9053,9054,9051 ,0,0,0}, + {20028,20008,20007 ,9055,9056,9050 ,0,0,0}, {20007,20026,20028 ,9050,9052,9055 ,0,0,0}, + {20008,20029,20009 ,9056,9057,9058 ,0,0,0}, {20029,20008,20028 ,9057,9056,9055 ,0,0,0}, + {20010,20009,20030 ,9059,9058,9060 ,0,0,0}, {20029,20030,20009 ,9057,9060,9058 ,0,0,0}, + {20031,20011,20010 ,9061,9023,9059 ,0,0,0}, {20010,20030,20031 ,9059,9060,9061 ,0,0,0}, + {20023,20027,20005 ,9045,9054,9053 ,0,0,0}, {20004,20027,20026 ,9051,9054,9052 ,0,0,0}, + {20006,20001,20024 ,9046,9048,9047 ,0,0,0}, {20005,20006,20023 ,9053,9046,9045 ,0,0,0}, + {20025,20002,20020 ,9049,9040,9039 ,0,0,0}, {20001,20002,20025 ,9048,9040,9049 ,0,0,0}, + {20021,20003,19998 ,9042,9041,9043 ,0,0,0}, {20020,20003,20021 ,9039,9041,9042 ,0,0,0}, + {20018,20022,20000 ,9034,9044,9035 ,0,0,0}, {20022,19998,20000 ,9044,9043,9035 ,0,0,0}, + {19996,20032,19999 ,9038,9062,9033 ,0,0,0}, {20032,20018,19999 ,9062,9034,9033 ,0,0,0}, + {20012,20015,20019 ,9036,9027,9037 ,0,0,0}, {19996,20019,20032 ,9038,9037,9062 ,0,0,0}, + {19997,19995,20016 ,9028,9031,9029 ,0,0,0}, {20012,19997,20015 ,9036,9028,9027 ,0,0,0}, + {20017,19994,20013 ,9030,9032,9025 ,0,0,0}, {20016,19995,20017 ,9029,9031,9030 ,0,0,0}, + {19993,20013,19994 ,8987,9025,9032 ,0,0,0}, {20020,20021,20033 ,9063,9064,9065 ,0,0,0}, + {20034,20021,20022 ,9066,9064,9067 ,0,0,0}, {20021,20034,20033 ,9064,9066,9065 ,0,0,0}, + {20018,20035,20022 ,9068,9069,9067 ,0,0,0}, {20034,20022,20035 ,9066,9067,9069 ,0,0,0}, + {20018,20032,20036 ,9068,9070,9071 ,0,0,0}, {20036,20035,20018 ,9071,9069,9068 ,0,0,0}, + {20037,20032,20019 ,9072,9070,9073 ,0,0,0}, {20032,20037,20036 ,9070,9072,9071 ,0,0,0}, + {20015,20038,20019 ,9074,9075,9073 ,0,0,0}, {20037,20019,20038 ,9072,9073,9075 ,0,0,0}, + {20015,20016,20039 ,9074,9076,9077 ,0,0,0}, {20039,20038,20015 ,9077,9075,9074 ,0,0,0}, + {20040,20016,20017 ,9078,9076,9079 ,0,0,0}, {20016,20040,20039 ,9076,9078,9077 ,0,0,0}, + {20013,20041,20017 ,9080,9081,9079 ,0,0,0}, {20040,20017,20041 ,9078,9079,9081 ,0,0,0}, + {20014,20042,20041 ,9082,9083,9081 ,0,0,0}, {20041,20013,20014 ,9081,9080,9082 ,0,0,0}, + {20020,20033,20043 ,9063,9065,9084 ,0,0,0}, {20043,20044,20025 ,9084,9085,9086 ,0,0,0}, + {20025,20020,20043 ,9086,9063,9084 ,0,0,0}, {20024,20044,20045 ,9087,9085,9088 ,0,0,0}, + {20044,20024,20025 ,9085,9087,9086 ,0,0,0}, {20046,20023,20045 ,9089,9090,9088 ,0,0,0}, + {20024,20045,20023 ,9087,9088,9090 ,0,0,0}, {20046,20047,20027 ,9089,9091,9092 ,0,0,0}, + {20027,20023,20046 ,9092,9090,9089 ,0,0,0}, {20026,20047,20048 ,9093,9091,9094 ,0,0,0}, + {20047,20026,20027 ,9091,9093,9092 ,0,0,0}, {20049,20028,20048 ,9095,9096,9094 ,0,0,0}, + {20026,20048,20028 ,9093,9094,9096 ,0,0,0}, {20049,20050,20029 ,9095,9097,9098 ,0,0,0}, + {20029,20028,20049 ,9098,9096,9095 ,0,0,0}, {20030,20050,20051 ,9099,9097,9100 ,0,0,0}, + {20050,20030,20029 ,9097,9099,9098 ,0,0,0}, {20030,20051,20031 ,9099,9100,9101 ,0,0,0}, + {20052,20042,20053 ,9102,9103,9104 ,0,0,0}, {20054,20038,20055 ,9105,9106,9107 ,0,0,0}, + {20052,20056,20040 ,9102,9108,9109 ,0,0,0}, {20035,20057,20058 ,9110,9111,9112 ,0,0,0}, + {20037,20059,20036 ,9113,9114,9115 ,0,0,0}, {20060,20061,20043 ,9116,9117,9118 ,0,0,0}, + {20062,20033,20034 ,9119,9120,9121 ,0,0,0}, {20063,20046,20064 ,9122,9123,9124 ,0,0,0}, + {20045,20044,20065 ,9125,9126,9127 ,0,0,0}, {20066,20048,20047 ,9128,9129,9130 ,0,0,0}, + {20047,20063,20066 ,9130,9122,9128 ,0,0,0}, {20048,20067,20049 ,9129,9131,9132 ,0,0,0}, + {20067,20048,20066 ,9131,9129,9128 ,0,0,0}, {20050,20049,20068 ,9133,9132,9134 ,0,0,0}, + {20067,20068,20049 ,9131,9134,9132 ,0,0,0}, {20069,20051,20050 ,9135,9100,9133 ,0,0,0}, + {20050,20068,20069 ,9133,9134,9135 ,0,0,0}, {20046,20045,20064 ,9123,9125,9124 ,0,0,0}, + {20047,20046,20063 ,9130,9123,9122 ,0,0,0}, {20065,20044,20061 ,9127,9126,9117 ,0,0,0}, + {20064,20045,20065 ,9124,9125,9127 ,0,0,0}, {20060,20043,20033 ,9116,9118,9120 ,0,0,0}, + {20061,20044,20043 ,9117,9126,9118 ,0,0,0}, {20058,20062,20034 ,9112,9119,9121 ,0,0,0}, + {20062,20060,20033 ,9119,9116,9120 ,0,0,0}, {20036,20057,20035 ,9115,9111,9110 ,0,0,0}, + {20035,20058,20034 ,9110,9112,9121 ,0,0,0}, {20037,20054,20059 ,9113,9105,9114 ,0,0,0}, + {20036,20059,20057 ,9115,9114,9111 ,0,0,0}, {20038,20039,20055 ,9106,9136,9107 ,0,0,0}, + {20037,20038,20054 ,9113,9106,9105 ,0,0,0}, {20040,20056,20039 ,9109,9108,9136 ,0,0,0}, + {20055,20039,20056 ,9107,9136,9108 ,0,0,0}, {20052,20041,20042 ,9102,9137,9103 ,0,0,0}, + {20052,20040,20041 ,9102,9109,9137 ,0,0,0}, {20070,20053,20071 ,9138,9139,9140 ,0,0,0}, + {20072,20055,20073 ,9141,9142,9143 ,0,0,0}, {20074,20056,20052 ,9144,9145,9146 ,0,0,0}, + {20057,20075,20058 ,9147,9148,9149 ,0,0,0}, {20054,20076,20059 ,9150,9151,9152 ,0,0,0}, + {20077,20078,20060 ,9153,9154,9155 ,0,0,0}, {20077,20062,20079 ,9153,9156,9157 ,0,0,0}, + {20080,20064,20081 ,9158,9159,9160 ,0,0,0}, {20065,20061,20082 ,9161,9162,9163 ,0,0,0}, + {20083,20066,20063 ,9164,9165,9166 ,0,0,0}, {20063,20080,20083 ,9166,9158,9164 ,0,0,0}, + {20066,20084,20067 ,9165,9167,9168 ,0,0,0}, {20084,20066,20083 ,9167,9165,9164 ,0,0,0}, + {20068,20067,20085 ,9169,9168,9170 ,0,0,0}, {20084,20085,20067 ,9167,9170,9168 ,0,0,0}, + {20086,20069,20068 ,9171,9172,9169 ,0,0,0}, {20068,20085,20086 ,9169,9170,9171 ,0,0,0}, + {20064,20065,20081 ,9159,9161,9160 ,0,0,0}, {20063,20064,20080 ,9166,9159,9158 ,0,0,0}, + {20082,20061,20078 ,9163,9162,9154 ,0,0,0}, {20081,20065,20082 ,9160,9161,9163 ,0,0,0}, + {20077,20060,20062 ,9153,9155,9156 ,0,0,0}, {20078,20061,20060 ,9154,9162,9155 ,0,0,0}, + {20075,20079,20058 ,9148,9157,9149 ,0,0,0}, {20079,20062,20058 ,9157,9156,9149 ,0,0,0}, + {20059,20087,20057 ,9152,9173,9147 ,0,0,0}, {20087,20075,20057 ,9173,9148,9147 ,0,0,0}, + {20054,20072,20076 ,9150,9141,9151 ,0,0,0}, {20059,20076,20087 ,9152,9151,9173 ,0,0,0}, + {20055,20056,20073 ,9142,9145,9143 ,0,0,0}, {20054,20055,20072 ,9150,9142,9141 ,0,0,0}, + {20074,20052,20070 ,9144,9146,9138 ,0,0,0}, {20073,20056,20074 ,9143,9145,9144 ,0,0,0}, + {20053,20070,20052 ,9139,9138,9146 ,0,0,0}, {20088,20071,20089 ,9174,9175,9176 ,0,0,0}, + {20090,20073,20091 ,9177,9178,9179 ,0,0,0}, {20092,20074,20070 ,9180,9181,9182 ,0,0,0}, + {20087,20093,20094 ,9183,9184,9185 ,0,0,0}, {20072,20095,20076 ,9186,9187,9188 ,0,0,0}, + {20096,20097,20077 ,9189,9190,9191 ,0,0,0}, {20096,20079,20098 ,9189,9192,9193 ,0,0,0}, + {20099,20081,20100 ,9194,9195,9196 ,0,0,0}, {20082,20078,20101 ,9197,9198,9199 ,0,0,0}, + {20102,20083,20080 ,9200,9201,9202 ,0,0,0}, {20080,20099,20102 ,9202,9194,9200 ,0,0,0}, + {20083,20103,20084 ,9201,9203,9204 ,0,0,0}, {20103,20083,20102 ,9203,9201,9200 ,0,0,0}, + {20085,20084,20104 ,9205,9204,9206 ,0,0,0}, {20103,20104,20084 ,9203,9206,9204 ,0,0,0}, + {20105,20086,20085 ,9207,9208,9205 ,0,0,0}, {20085,20104,20105 ,9205,9206,9207 ,0,0,0}, + {20081,20082,20100 ,9195,9197,9196 ,0,0,0}, {20080,20081,20099 ,9202,9195,9194 ,0,0,0}, + {20101,20078,20097 ,9199,9198,9190 ,0,0,0}, {20100,20082,20101 ,9196,9197,9199 ,0,0,0}, + {20096,20077,20079 ,9189,9191,9192 ,0,0,0}, {20097,20078,20077 ,9190,9198,9191 ,0,0,0}, + {20094,20098,20075 ,9185,9193,9209 ,0,0,0}, {20098,20079,20075 ,9193,9192,9209 ,0,0,0}, + {20076,20093,20087 ,9188,9184,9183 ,0,0,0}, {20087,20094,20075 ,9183,9185,9209 ,0,0,0}, + {20072,20090,20095 ,9186,9177,9187 ,0,0,0}, {20076,20095,20093 ,9188,9187,9184 ,0,0,0}, + {20073,20074,20091 ,9178,9181,9179 ,0,0,0}, {20072,20073,20090 ,9186,9178,9177 ,0,0,0}, + {20092,20070,20088 ,9180,9182,9174 ,0,0,0}, {20091,20074,20092 ,9179,9181,9180 ,0,0,0}, + {20071,20088,20070 ,9175,9174,9182 ,0,0,0}, {19676,20089,19674 ,9210,9211,9212 ,0,0,0}, + {19677,20091,19678 ,9213,9214,9215 ,0,0,0}, {19688,20092,20088 ,9216,9217,9218 ,0,0,0}, + {20093,19701,19702 ,9219,9220,9221 ,0,0,0}, {20090,19689,20095 ,9222,9223,9224 ,0,0,0}, + {19704,19705,20096 ,9225,9226,9227 ,0,0,0}, {19703,20098,20094 ,9228,9229,9230 ,0,0,0}, + {19734,20100,20101 ,9231,9232,9233 ,0,0,0}, {19731,20097,19705 ,9234,9235,9226 ,0,0,0}, + {19735,20102,20099 ,9236,9237,9238 ,0,0,0}, {20099,19733,19735 ,9238,9239,9236 ,0,0,0}, + {20102,19736,20103 ,9237,9240,9241 ,0,0,0}, {19736,20102,19735 ,9240,9237,9236 ,0,0,0}, + {20103,19638,19635 ,9241,9242,9243 ,0,0,0}, {19736,19638,20103 ,9240,9242,9241 ,0,0,0}, + {19634,20104,19635 ,8461,9244,9243 ,0,0,0}, {20103,19635,20104 ,9241,9243,9244 ,0,0,0}, + {20105,20104,19634 ,9207,9244,8461 ,0,0,0}, {19733,20100,19734 ,9239,9232,9231 ,0,0,0}, + {20099,20100,19733 ,9238,9232,9239 ,0,0,0}, {19731,20101,20097 ,9234,9233,9235 ,0,0,0}, + {19734,20101,19731 ,9231,9233,9234 ,0,0,0}, {20096,20098,19704 ,9227,9229,9225 ,0,0,0}, + {19705,20097,20096 ,9226,9235,9227 ,0,0,0}, {19702,19703,20094 ,9221,9228,9230 ,0,0,0}, + {19703,19704,20098 ,9228,9225,9229 ,0,0,0}, {20095,19701,20093 ,9224,9220,9219 ,0,0,0}, + {20093,19702,20094 ,9219,9221,9230 ,0,0,0}, {20090,19677,19689 ,9222,9213,9223 ,0,0,0}, + {20095,19689,19701 ,9224,9223,9220 ,0,0,0}, {20091,20092,19678 ,9214,9217,9215 ,0,0,0}, + {20090,20091,19677 ,9222,9214,9213 ,0,0,0}, {19688,20088,19676 ,9216,9218,9210 ,0,0,0}, + {19678,20092,19688 ,9215,9217,9216 ,0,0,0}, {20089,19676,20088 ,9211,9210,9218 ,0,0,0}, + {20106,19614,20107 ,9245,8438,9246 ,0,0,0}, {20108,19724,19671 ,9247,9248,9249 ,0,0,0}, + {20109,19686,19612 ,9250,9251,9252 ,0,0,0}, {19729,20110,20111 ,9253,9254,9255 ,0,0,0}, + {19725,20112,19726 ,9256,9257,9258 ,0,0,0}, {20113,20114,19694 ,9259,9260,9261 ,0,0,0}, + {20115,19697,19698 ,9262,9263,9264 ,0,0,0}, {20116,19732,20117 ,9265,9266,9267 ,0,0,0}, + {19730,19695,20118 ,9268,9269,9270 ,0,0,0}, {20119,19709,19654 ,9271,9272,9273 ,0,0,0}, + {19654,20116,20119 ,9273,9265,9271 ,0,0,0}, {19709,20120,19737 ,9272,9274,9275 ,0,0,0}, + {20120,19709,20119 ,9274,9272,9271 ,0,0,0}, {19645,19737,20121 ,9276,9275,9277 ,0,0,0}, + {20120,20121,19737 ,9274,9277,9275 ,0,0,0}, {20122,19648,19645 ,9278,9279,9276 ,0,0,0}, + {19645,20121,20122 ,9276,9277,9278 ,0,0,0}, {19732,19730,20117 ,9266,9268,9267 ,0,0,0}, + {19654,19732,20116 ,9273,9266,9265 ,0,0,0}, {20118,19695,20114 ,9270,9269,9260 ,0,0,0}, + {20117,19730,20118 ,9267,9268,9270 ,0,0,0}, {20113,19694,19697 ,9259,9261,9263 ,0,0,0}, + {20114,19695,19694 ,9260,9269,9261 ,0,0,0}, {20111,20115,19698 ,9255,9262,9264 ,0,0,0}, + {20115,20113,19697 ,9262,9259,9263 ,0,0,0}, {19726,20110,19729 ,9258,9254,9253 ,0,0,0}, + {19729,20111,19698 ,9253,9255,9264 ,0,0,0}, {19725,20123,20112 ,9256,9280,9257 ,0,0,0}, + {19726,20112,20110 ,9258,9257,9254 ,0,0,0}, {20108,20123,19724 ,9247,9280,9248 ,0,0,0}, + {19725,19724,20123 ,9256,9248,9280 ,0,0,0}, {20109,19671,19686 ,9250,9249,9251 ,0,0,0}, + {20108,19671,20109 ,9247,9249,9250 ,0,0,0}, {20106,19612,19614 ,9245,9252,8438 ,0,0,0}, + {20109,19612,20106 ,9250,9252,9245 ,0,0,0}, {20124,20107,20125 ,9281,9246,9282 ,0,0,0}, + {20126,20108,20127 ,9283,9284,9285 ,0,0,0}, {20128,20109,20106 ,9286,9287,9288 ,0,0,0}, + {20110,20129,20130 ,9289,9290,9291 ,0,0,0}, {20123,20131,20112 ,9292,9293,9294 ,0,0,0}, + {20132,20114,20113 ,9295,9296,9297 ,0,0,0}, {20133,20115,20134 ,9298,9299,9300 ,0,0,0}, + {20135,20117,20136 ,9301,9302,9303 ,0,0,0}, {20118,20114,20137 ,9304,9296,9305 ,0,0,0}, + {20138,20119,20116 ,9306,9307,9308 ,0,0,0}, {20116,20135,20138 ,9308,9301,9306 ,0,0,0}, + {20119,20139,20120 ,9307,9309,9310 ,0,0,0}, {20139,20119,20138 ,9309,9307,9306 ,0,0,0}, + {20121,20120,20140 ,9311,9310,9312 ,0,0,0}, {20139,20140,20120 ,9309,9312,9310 ,0,0,0}, + {20141,20122,20121 ,9313,9314,9311 ,0,0,0}, {20121,20140,20141 ,9311,9312,9313 ,0,0,0}, + {20117,20118,20136 ,9302,9304,9303 ,0,0,0}, {20116,20117,20135 ,9308,9302,9301 ,0,0,0}, + {20137,20114,20132 ,9305,9296,9295 ,0,0,0}, {20136,20118,20137 ,9303,9304,9305 ,0,0,0}, + {20133,20113,20115 ,9298,9297,9299 ,0,0,0}, {20132,20113,20133 ,9295,9297,9298 ,0,0,0}, + {20130,20134,20111 ,9291,9300,9315 ,0,0,0}, {20134,20115,20111 ,9300,9299,9315 ,0,0,0}, + {20112,20129,20110 ,9294,9290,9289 ,0,0,0}, {20110,20130,20111 ,9289,9291,9315 ,0,0,0}, + {20123,20126,20131 ,9292,9283,9293 ,0,0,0}, {20112,20131,20129 ,9294,9293,9290 ,0,0,0}, + {20108,20109,20127 ,9284,9287,9285 ,0,0,0}, {20123,20108,20126 ,9292,9284,9283 ,0,0,0}, + {20128,20106,20124 ,9286,9288,9281 ,0,0,0}, {20127,20109,20128 ,9285,9287,9286 ,0,0,0}, + {20107,20124,20106 ,9246,9281,9288 ,0,0,0}, {20142,20125,20143 ,9316,9282,9317 ,0,0,0}, + {20144,20127,20145 ,9318,9319,9320 ,0,0,0}, {20146,20128,20124 ,9321,9322,9323 ,0,0,0}, + {20129,20147,20130 ,9324,9325,9326 ,0,0,0}, {20126,20148,20131 ,9327,9328,9329 ,0,0,0}, + {20149,20132,20133 ,9330,9331,9332 ,0,0,0}, {20150,20134,20151 ,9333,9334,9335 ,0,0,0}, + {20152,20136,20153 ,9336,9337,9338 ,0,0,0}, {20137,20132,20154 ,9339,9331,9340 ,0,0,0}, + {20155,20138,20135 ,9341,9342,9343 ,0,0,0}, {20135,20152,20155 ,9343,9336,9341 ,0,0,0}, + {20138,20156,20139 ,9342,9344,9345 ,0,0,0}, {20156,20138,20155 ,9344,9342,9341 ,0,0,0}, + {20140,20139,20157 ,9346,9345,9347 ,0,0,0}, {20156,20157,20139 ,9344,9347,9345 ,0,0,0}, + {20158,20141,20140 ,9348,9349,9346 ,0,0,0}, {20140,20157,20158 ,9346,9347,9348 ,0,0,0}, + {20136,20137,20153 ,9337,9339,9338 ,0,0,0}, {20135,20136,20152 ,9343,9337,9336 ,0,0,0}, + {20154,20132,20149 ,9340,9331,9330 ,0,0,0}, {20153,20137,20154 ,9338,9339,9340 ,0,0,0}, + {20150,20133,20134 ,9333,9332,9334 ,0,0,0}, {20149,20133,20150 ,9330,9332,9333 ,0,0,0}, + {20147,20151,20130 ,9325,9335,9326 ,0,0,0}, {20151,20134,20130 ,9335,9334,9326 ,0,0,0}, + {20131,20159,20129 ,9329,9350,9324 ,0,0,0}, {20159,20147,20129 ,9350,9325,9324 ,0,0,0}, + {20126,20144,20148 ,9327,9318,9328 ,0,0,0}, {20131,20148,20159 ,9329,9328,9350 ,0,0,0}, + {20127,20128,20145 ,9319,9322,9320 ,0,0,0}, {20126,20127,20144 ,9327,9319,9318 ,0,0,0}, + {20146,20124,20142 ,9321,9323,9316 ,0,0,0}, {20145,20128,20146 ,9320,9322,9321 ,0,0,0}, + {20125,20142,20124 ,9282,9316,9323 ,0,0,0}, {19742,20160,19779 ,9351,9352,8640 ,0,0,0}, + {19748,20161,19749 ,9353,9354,9355 ,0,0,0}, {19744,20162,20163 ,9356,9357,9358 ,0,0,0}, + {20164,19756,20165 ,9359,9360,9361 ,0,0,0}, {20166,19746,20167 ,9362,9363,9364 ,0,0,0}, + {19761,20168,20169 ,9365,9366,9367 ,0,0,0}, {19753,20170,19751 ,9368,9369,9370 ,0,0,0}, + {20171,20172,19766 ,9371,9372,9373 ,0,0,0}, {20173,19759,19758 ,9374,9375,9376 ,0,0,0}, + {20174,20175,19763 ,9377,9378,9379 ,0,0,0}, {19764,19763,20175 ,9380,9379,9378 ,0,0,0}, + {19770,20176,20174 ,9381,9382,9377 ,0,0,0}, {20174,19763,19770 ,9377,9379,9381 ,0,0,0}, + {20176,19772,20177 ,9382,9383,9384 ,0,0,0}, {19772,20176,19770 ,9383,9382,9381 ,0,0,0}, + {20178,20177,19773 ,9385,9384,9386 ,0,0,0}, {19772,19773,20177 ,9383,9386,9384 ,0,0,0}, + {19776,20179,20178 ,8637,9387,9385 ,0,0,0}, {20178,19773,19776 ,9385,9386,8637 ,0,0,0}, + {19766,19764,20171 ,9373,9380,9371 ,0,0,0}, {20171,19764,20175 ,9371,9380,9378 ,0,0,0}, + {20172,20173,19758 ,9372,9374,9376 ,0,0,0}, {20172,19758,19766 ,9372,9376,9373 ,0,0,0}, + {19759,20168,19761 ,9375,9366,9365 ,0,0,0}, {20173,20168,19759 ,9374,9366,9375 ,0,0,0}, + {19753,20169,20170 ,9368,9367,9369 ,0,0,0}, {19761,20169,19753 ,9365,9367,9368 ,0,0,0}, + {19756,19751,20165 ,9360,9370,9361 ,0,0,0}, {19751,20170,20165 ,9370,9369,9361 ,0,0,0}, + {20167,19778,20164 ,9364,9388,9359 ,0,0,0}, {19778,19756,20164 ,9388,9360,9359 ,0,0,0}, + {20166,19748,19746 ,9362,9353,9363 ,0,0,0}, {20167,19746,19778 ,9364,9363,9388 ,0,0,0}, + {20161,20162,19749 ,9354,9357,9355 ,0,0,0}, {20166,20161,19748 ,9362,9354,9353 ,0,0,0}, + {19744,20163,19742 ,9356,9358,9351 ,0,0,0}, {19749,20162,19744 ,9355,9357,9356 ,0,0,0}, + {20160,19742,20163 ,9352,9351,9358 ,0,0,0}, {20180,20143,20181 ,9389,9317,9390 ,0,0,0}, + {20182,20145,20183 ,9391,9392,9393 ,0,0,0}, {20184,20146,20142 ,9394,9395,9396 ,0,0,0}, + {20159,20185,20186 ,9397,9398,9399 ,0,0,0}, {20144,20187,20148 ,9400,9401,9402 ,0,0,0}, + {20188,20189,20150 ,9403,9404,9405 ,0,0,0}, {20190,20151,20147 ,9406,9407,9408 ,0,0,0}, + {20191,20153,20154 ,9409,9410,9411 ,0,0,0}, {20154,20149,20192 ,9411,9412,9413 ,0,0,0}, + {20193,20155,20152 ,9414,9415,9416 ,0,0,0}, {20152,20194,20193 ,9416,9417,9414 ,0,0,0}, + {20155,20195,20156 ,9415,9418,9419 ,0,0,0}, {20195,20155,20193 ,9418,9415,9414 ,0,0,0}, + {20157,20156,20196 ,9420,9419,9421 ,0,0,0}, {20195,20196,20156 ,9418,9421,9419 ,0,0,0}, + {20197,20157,20198 ,9422,9420,9423 ,0,0,0}, {20157,20196,20198 ,9420,9421,9423 ,0,0,0}, + {20158,20157,20197 ,9424,9420,9422 ,0,0,0}, {20194,20153,20191 ,9417,9410,9409 ,0,0,0}, + {20152,20153,20194 ,9416,9410,9417 ,0,0,0}, {20149,20189,20192 ,9412,9404,9413 ,0,0,0}, + {20191,20154,20192 ,9409,9411,9413 ,0,0,0}, {20188,20150,20151 ,9403,9405,9407 ,0,0,0}, + {20189,20149,20150 ,9404,9412,9405 ,0,0,0}, {20186,20190,20147 ,9399,9406,9408 ,0,0,0}, + {20190,20188,20151 ,9406,9403,9407 ,0,0,0}, {20148,20185,20159 ,9402,9398,9397 ,0,0,0}, + {20159,20186,20147 ,9397,9399,9408 ,0,0,0}, {20144,20182,20187 ,9400,9391,9401 ,0,0,0}, + {20148,20187,20185 ,9402,9401,9398 ,0,0,0}, {20145,20146,20183 ,9392,9395,9393 ,0,0,0}, + {20144,20145,20182 ,9400,9392,9391 ,0,0,0}, {20184,20142,20180 ,9394,9396,9389 ,0,0,0}, + {20183,20146,20184 ,9393,9395,9394 ,0,0,0}, {20143,20180,20142 ,9317,9389,9396 ,0,0,0}, + {20163,20181,20160 ,9425,9390,9426 ,0,0,0}, {20166,20183,20161 ,9427,9428,9429 ,0,0,0}, + {20162,20184,20180 ,9430,9431,9432 ,0,0,0}, {20185,20164,20165 ,9433,9434,9435 ,0,0,0}, + {20182,20167,20187 ,9436,9437,9438 ,0,0,0}, {20169,20168,20188 ,9439,9440,9441 ,0,0,0}, + {20170,20190,20186 ,9442,9443,9444 ,0,0,0}, {20171,20191,20172 ,9445,9446,9447 ,0,0,0}, + {20192,20189,20173 ,9448,9449,9450 ,0,0,0}, {20174,20193,20175 ,9451,9452,9453 ,0,0,0}, + {20194,20171,20175 ,9454,9445,9453 ,0,0,0}, {20174,20176,20195 ,9451,9455,9456 ,0,0,0}, + {20195,20193,20174 ,9456,9452,9451 ,0,0,0}, {20196,20176,20177 ,9457,9455,9458 ,0,0,0}, + {20176,20196,20195 ,9455,9457,9456 ,0,0,0}, {20178,20198,20177 ,9459,9460,9458 ,0,0,0}, + {20196,20177,20198 ,9457,9458,9460 ,0,0,0}, {20179,20197,20198 ,9461,9422,9460 ,0,0,0}, + {20198,20178,20179 ,9460,9459,9461 ,0,0,0}, {20191,20171,20194 ,9446,9445,9454 ,0,0,0}, + {20193,20194,20175 ,9452,9454,9453 ,0,0,0}, {20172,20192,20173 ,9447,9448,9450 ,0,0,0}, + {20191,20192,20172 ,9446,9448,9447 ,0,0,0}, {20168,20189,20188 ,9440,9449,9441 ,0,0,0}, + {20173,20189,20168 ,9450,9449,9440 ,0,0,0}, {20170,20169,20190 ,9442,9439,9443 ,0,0,0}, + {20169,20188,20190 ,9439,9441,9443 ,0,0,0}, {20185,20165,20186 ,9433,9435,9444 ,0,0,0}, + {20165,20170,20186 ,9435,9442,9444 ,0,0,0}, {20187,20167,20164 ,9438,9437,9434 ,0,0,0}, + {20187,20164,20185 ,9438,9434,9433 ,0,0,0}, {20182,20183,20166 ,9436,9428,9427 ,0,0,0}, + {20182,20166,20167 ,9436,9427,9437 ,0,0,0}, {20161,20184,20162 ,9429,9431,9430 ,0,0,0}, + {20183,20184,20161 ,9428,9431,9429 ,0,0,0}, {20163,20180,20181 ,9425,9432,9390 ,0,0,0}, + {20162,20180,20163 ,9430,9432,9425 ,0,0,0}, {19866,20199,20200 ,9462,9463,9464 ,0,0,0}, + {19865,20201,19863 ,9465,9466,9467 ,0,0,0}, {20199,19866,20202 ,9463,9462,9468 ,0,0,0}, + {20200,20203,19866 ,9464,9462,9462 ,0,0,0}, {20202,19866,19863 ,9468,9462,9467 ,0,0,0}, + {20204,20202,19863 ,9469,9468,9467 ,0,0,0}, {20204,19863,20201 ,9469,9467,9466 ,0,0,0}, + {19901,19819,20205 ,9470,9471,9472 ,0,0,0}, {19901,20206,20207 ,9470,9473,9474 ,0,0,0}, + {20205,20206,19901 ,9472,9473,9470 ,0,0,0}, {19865,20207,20208 ,9465,9474,9475 ,0,0,0}, + {19865,19901,20207 ,9465,9470,9474 ,0,0,0}, {19865,20209,20210 ,9465,9476,9477 ,0,0,0}, + {20208,20209,19865 ,9475,9476,9465 ,0,0,0}, {19865,20211,20212 ,9465,9478,9479 ,0,0,0}, + {20210,20211,19865 ,9477,9478,9465 ,0,0,0}, {20201,19865,20213 ,9466,9465,9480 ,0,0,0}, + {20212,20213,19865 ,9479,9480,9465 ,0,0,0}, {20214,19687,20215 ,9481,9482,9483 ,0,0,0}, + {19687,20216,20217 ,9482,9484,9485 ,0,0,0}, {20217,19685,19687 ,9485,9486,9482 ,0,0,0}, + {19687,20214,20216 ,9482,9481,9484 ,0,0,0}, {19685,20218,20219 ,9486,9487,9488 ,0,0,0}, + {19685,20217,20218 ,9486,9485,9487 ,0,0,0}, {19687,20220,20215 ,9482,9489,9483 ,0,0,0}, + {19685,20219,19614 ,9486,9488,9490 ,0,0,0}, {20221,19687,19672 ,9491,9482,9492 ,0,0,0}, + {19687,20221,20220 ,9482,9491,9489 ,0,0,0}, {19674,20222,20223 ,9493,9493,9494 ,0,0,0}, + {20224,20225,19675 ,9495,9496,9497 ,0,0,0}, {20226,20227,19674 ,9498,9499,9493 ,0,0,0}, + {20226,19674,20223 ,9498,9493,9494 ,0,0,0}, {19674,20228,19675 ,9493,9500,9497 ,0,0,0}, + {20228,19674,20227 ,9500,9493,9499 ,0,0,0}, {20229,19675,20225 ,9501,9497,9496 ,0,0,0}, + {20228,20224,19675 ,9500,9495,9497 ,0,0,0}, {20221,19672,20229 ,9491,9492,9501 ,0,0,0}, + {20229,19672,19675 ,9501,9492,9497 ,0,0,0}, {20222,19674,20230 ,9502,9503,9504 ,0,0,0}, + {20071,20230,20089 ,9505,9504,9506 ,0,0,0}, {20071,20053,20230 ,9505,9507,9504 ,0,0,0}, + {20230,20053,20042 ,9504,9507,9508 ,0,0,0}, {20042,20014,20230 ,9508,9509,9504 ,0,0,0}, + {20230,19674,20089 ,9504,9503,9506 ,0,0,0}, {20231,20229,20232 ,9510,9511,4303 ,0,0,0}, + {20231,20233,20221 ,9510,82,9512 ,0,0,0}, {20221,20229,20231 ,9512,9511,9510 ,0,0,0}, + {20234,20235,20236 ,9513,9514,9515 ,0,0,0}, {20235,20237,20236 ,9514,9516,9515 ,0,0,0}, + {20235,20234,20238 ,9514,9513,9517 ,0,0,0}, {20216,20239,20238 ,9518,9519,9517 ,0,0,0}, + {20234,20216,20238 ,9513,9518,9517 ,0,0,0}, {20214,20239,20216 ,9520,9519,9518 ,0,0,0}, + {20239,20214,20240 ,9519,9520,9521 ,0,0,0}, {20215,20241,20240 ,9522,9523,9521 ,0,0,0}, + {20240,20214,20215 ,9521,9520,9522 ,0,0,0}, {20241,20220,20242 ,9523,9524,9525 ,0,0,0}, + {20220,20241,20215 ,9524,9523,9522 ,0,0,0}, {20233,20242,20221 ,9526,9525,9527 ,0,0,0}, + {20220,20221,20242 ,9524,9527,9525 ,0,0,0}, {20227,20243,20244 ,9528,9529,9530 ,0,0,0}, + {20232,20229,20225 ,9531,9532,9533 ,0,0,0}, {20225,20224,20245 ,9533,9534,9535 ,0,0,0}, + {20246,20228,20244 ,9536,9537,9530 ,0,0,0}, {20245,20224,20246 ,9535,9534,9536 ,0,0,0}, + {20225,20245,20232 ,9533,9535,9531 ,0,0,0}, {20224,20228,20246 ,9534,9537,9536 ,0,0,0}, + {20228,20227,20244 ,9537,9528,9530 ,0,0,0}, {20243,20227,20226 ,9529,9528,9538 ,0,0,0}, + {20226,20223,20247 ,9538,9539,9540 ,0,0,0}, {20247,20243,20226 ,9540,9529,9538 ,0,0,0}, + {20248,20223,20222 ,9541,9539,9542 ,0,0,0}, {20223,20248,20247 ,9539,9541,9540 ,0,0,0}, + {20248,20222,20230 ,9541,9542,9542 ,0,0,0}, {20203,20249,20250 ,9543,9543,9544 ,0,0,0}, + {20203,20250,20251 ,9543,9544,9543 ,0,0,0}, {20252,20203,20251 ,9543,9543,9543 ,0,0,0}, + {20243,20247,20203 ,9543,9543,9543 ,0,0,0}, {20243,20203,20252 ,9543,9543,9543 ,0,0,0}, + {20203,20248,20230 ,9543,9543,9544 ,0,0,0}, {20247,20248,20203 ,9543,9543,9543 ,0,0,0}, + {20203,20230,19866 ,9543,9544,9543 ,0,0,0}, {20230,19993,19973 ,9544,9543,9543 ,0,0,0}, + {20230,20014,19993 ,9544,9544,9543 ,0,0,0}, {19973,19953,20230 ,9543,9544,9544 ,0,0,0}, + {19866,20230,19934 ,9543,9544,9543 ,0,0,0}, {20230,19953,19934 ,9544,9544,9543 ,0,0,0}, + {19779,20160,20253 ,9545,9546,9547 ,0,0,0}, {20205,20254,20206 ,9548,9549,9550 ,0,0,0}, + {20255,20254,19780 ,9551,9549,9552 ,0,0,0}, {20256,20237,20257 ,9553,9554,9555 ,0,0,0}, + {20258,20256,20257 ,9556,9553,9555 ,0,0,0}, {20259,20260,20261 ,9557,9558,9559 ,0,0,0}, + {20260,20258,20261 ,9558,9556,9559 ,0,0,0}, {20254,19800,19780 ,9549,9560,9552 ,0,0,0}, + {20255,19780,19740 ,9551,9552,9561 ,0,0,0}, {20259,20207,20206 ,9557,9562,9550 ,0,0,0}, + {19819,19800,20205 ,9563,9560,9548 ,0,0,0}, {19779,20255,19740 ,9545,9551,9561 ,0,0,0}, + {20253,20262,20255 ,9547,9564,9551 ,0,0,0}, {20255,19779,20253 ,9551,9545,9547 ,0,0,0}, + {20262,20256,20258 ,9564,9553,9556 ,0,0,0}, {20260,20259,20206 ,9558,9557,9550 ,0,0,0}, + {20258,20260,20255 ,9556,9558,9551 ,0,0,0}, {20205,19800,20254 ,9548,9560,9549 ,0,0,0}, + {20258,20255,20262 ,9556,9551,9564 ,0,0,0}, {20257,20261,20258 ,9555,9559,9556 ,0,0,0}, + {20206,20254,20260 ,9550,9549,9558 ,0,0,0}, {20255,20260,20254 ,9551,9558,9549 ,0,0,0}, + {20263,20264,20265 ,9565,9566,9567 ,0,0,0}, {20266,20267,20268 ,9568,9569,9570 ,0,0,0}, + {20269,20270,20271 ,9571,9572,9573 ,0,0,0}, {20237,20235,20272 ,9574,9575,9576 ,0,0,0}, + {20273,20274,20211 ,9577,9578,9579 ,0,0,0}, {20275,20276,20277 ,9580,9581,9582 ,0,0,0}, + {20278,20279,20264 ,9583,9584,9566 ,0,0,0}, {20201,20213,20279 ,9585,9586,9584 ,0,0,0}, + {20280,20242,20233 ,9587,9588,9589 ,0,0,0}, {20263,20265,20280 ,9565,9567,9587 ,0,0,0}, + {20201,20279,20278 ,9585,9584,9583 ,0,0,0}, {20268,20265,20264 ,9570,9567,9566 ,0,0,0}, + {20213,20281,20279 ,9586,9590,9584 ,0,0,0}, {20274,20281,20212 ,9578,9590,9591 ,0,0,0}, + {20282,20273,20277 ,9592,9577,9582 ,0,0,0}, {20283,20271,20267 ,9593,9573,9569 ,0,0,0}, + {20208,20259,20275 ,9594,9595,9580 ,0,0,0}, {20270,20282,20272 ,9572,9592,9576 ,0,0,0}, + {20207,20259,20208 ,9596,9595,9594 ,0,0,0}, {20275,20259,20261 ,9580,9595,9597 ,0,0,0}, + {20212,20281,20213 ,9591,9590,9586 ,0,0,0}, {20212,20211,20274 ,9591,9579,9578 ,0,0,0}, + {20280,20265,20242 ,9587,9567,9588 ,0,0,0}, {20278,20264,20263 ,9583,9566,9565 ,0,0,0}, + {20268,20264,20266 ,9570,9566,9568 ,0,0,0}, {20241,20242,20265 ,9598,9588,9567 ,0,0,0}, + {20266,20279,20281 ,9568,9584,9590 ,0,0,0}, {20257,20237,20272 ,9599,9574,9576 ,0,0,0}, + {20265,20268,20241 ,9567,9570,9598 ,0,0,0}, {20279,20266,20264 ,9584,9568,9566 ,0,0,0}, + {20267,20266,20283 ,9569,9568,9593 ,0,0,0}, {20240,20241,20268 ,9600,9598,9570 ,0,0,0}, + {20274,20283,20281 ,9578,9593,9590 ,0,0,0}, {20210,20273,20211 ,9601,9577,9579 ,0,0,0}, + {20268,20267,20240 ,9570,9569,9600 ,0,0,0}, {20281,20283,20266 ,9590,9593,9568 ,0,0,0}, + {20271,20283,20269 ,9573,9593,9571 ,0,0,0}, {20239,20240,20267 ,9602,9600,9569 ,0,0,0}, + {20273,20269,20274 ,9577,9571,9578 ,0,0,0}, {20209,20277,20210 ,9603,9582,9601 ,0,0,0}, + {20271,20238,20239 ,9573,9604,9602 ,0,0,0}, {20274,20269,20283 ,9578,9571,9593 ,0,0,0}, + {20269,20282,20270 ,9571,9592,9572 ,0,0,0}, {20239,20267,20271 ,9602,9569,9573 ,0,0,0}, + {20210,20277,20273 ,9601,9582,9577 ,0,0,0}, {20275,20209,20208 ,9580,9603,9594 ,0,0,0}, + {20270,20235,20238 ,9572,9575,9604 ,0,0,0}, {20273,20282,20269 ,9577,9592,9571 ,0,0,0}, + {20276,20272,20282 ,9581,9576,9592 ,0,0,0}, {20238,20271,20270 ,9604,9573,9572 ,0,0,0}, + {20209,20275,20277 ,9603,9580,9582 ,0,0,0}, {20277,20276,20282 ,9582,9581,9592 ,0,0,0}, + {20261,20257,20276 ,9597,9599,9581 ,0,0,0}, {20275,20261,20276 ,9580,9597,9581 ,0,0,0}, + {20257,20272,20276 ,9599,9576,9581 ,0,0,0}, {20235,20270,20272 ,9575,9572,9576 ,0,0,0}, + {20280,20231,20284 ,9605,9606,9607 ,0,0,0}, {20204,20285,20202 ,9608,9609,9468 ,0,0,0}, + {20284,20231,20286 ,9607,9606,9610 ,0,0,0}, {20231,20232,20286 ,9606,82,9610 ,0,0,0}, + {20284,20287,20285 ,9607,9611,9609 ,0,0,0}, {20280,20233,20231 ,9605,82,9606 ,0,0,0}, + {20285,20287,20202 ,9609,9611,9468 ,0,0,0}, {20278,20285,20204 ,9612,9609,9608 ,0,0,0}, + {20201,20278,20204 ,9613,9612,9608 ,0,0,0}, {20278,20263,20285 ,9612,9614,9609 ,0,0,0}, + {20263,20280,20284 ,9614,9605,9607 ,0,0,0}, {20263,20284,20285 ,9614,9607,9609 ,0,0,0}, + {20287,20284,20286 ,9611,9607,9610 ,0,0,0}, {20252,20251,20244 ,9615,9616,9617 ,0,0,0}, + {20286,20232,20245 ,9618,82,9619 ,0,0,0}, {20245,20246,20288 ,9619,9620,9621 ,0,0,0}, + {20245,20288,20286 ,9619,9621,9618 ,0,0,0}, {20243,20252,20244 ,9622,9615,9617 ,0,0,0}, + {20250,20249,20289 ,9623,9624,9625 ,0,0,0}, {20289,20290,20250 ,9625,9626,9623 ,0,0,0}, + {20287,20288,20291 ,9627,9621,9628 ,0,0,0}, {20291,20288,20290 ,9628,9621,9626 ,0,0,0}, + {20249,20203,20200 ,9624,9629,9630 ,0,0,0}, {20287,20291,20202 ,9627,9628,9631 ,0,0,0}, + {20200,20291,20289 ,9630,9628,9625 ,0,0,0}, {20286,20288,20287 ,9618,9621,9627 ,0,0,0}, + {20200,20199,20291 ,9630,9632,9628 ,0,0,0}, {20291,20199,20202 ,9628,9632,9631 ,0,0,0}, + {20288,20246,20290 ,9621,9620,9626 ,0,0,0}, {20244,20290,20246 ,9617,9626,9620 ,0,0,0}, + {20200,20289,20249 ,9630,9625,9624 ,0,0,0}, {20291,20290,20289 ,9628,9626,9625 ,0,0,0}, + {20251,20290,20244 ,9616,9626,9617 ,0,0,0}, {20251,20250,20290 ,9616,9623,9626 ,0,0,0}, + {20125,20292,20293 ,9633,9634,9635 ,0,0,0}, {20237,20256,20294 ,9636,9637,9638 ,0,0,0}, + {20295,20294,20256 ,9639,9638,9637 ,0,0,0}, {20125,20293,20143 ,9633,9635,9640 ,0,0,0}, + {20293,20292,20295 ,9635,9634,9639 ,0,0,0}, {20253,20160,20181 ,9641,9642,9643 ,0,0,0}, + {20143,20293,20181 ,9640,9635,9643 ,0,0,0}, {20219,20292,20107 ,9644,9634,9645 ,0,0,0}, + {20296,20219,20218 ,9646,9644,9647 ,0,0,0}, {20292,20125,20107 ,9634,9633,9645 ,0,0,0}, + {20294,20234,20236 ,9638,9648,9649 ,0,0,0}, {20294,20296,20297 ,9638,9646,9650 ,0,0,0}, + {20107,19614,20219 ,9645,9651,9644 ,0,0,0}, {20234,20297,20216 ,9648,9650,9652 ,0,0,0}, + {20297,20234,20294 ,9650,9648,9638 ,0,0,0}, {20293,20253,20181 ,9635,9641,9643 ,0,0,0}, + {20292,20296,20295 ,9634,9646,9639 ,0,0,0}, {20262,20253,20293 ,9653,9641,9635 ,0,0,0}, + {20219,20296,20292 ,9644,9646,9634 ,0,0,0}, {20297,20218,20217 ,9650,9647,9654 ,0,0,0}, + {20256,20262,20295 ,9637,9653,9639 ,0,0,0}, {20293,20295,20262 ,9635,9639,9653 ,0,0,0}, + {20218,20297,20296 ,9647,9650,9646 ,0,0,0}, {20216,20297,20217 ,9652,9650,9654 ,0,0,0}, + {20294,20236,20237 ,9638,9649,9636 ,0,0,0}, {20296,20294,20295 ,9646,9638,9639 ,0,0,0}, + {20298,19739,20299 ,9655,9656,9657 ,0,0,0}, {19739,20300,20301 ,9656,9658,9659 ,0,0,0}, + {20301,19738,19739 ,9659,9660,9656 ,0,0,0}, {19739,20298,20300 ,9656,9655,9658 ,0,0,0}, + {19738,20302,20303 ,9660,9661,9662 ,0,0,0}, {19738,20301,20302 ,9660,9659,9661 ,0,0,0}, + {19739,20304,20299 ,9656,9663,9657 ,0,0,0}, {19738,20303,19634 ,9660,9662,9664 ,0,0,0}, + {20305,19739,19647 ,9665,9656,9666 ,0,0,0}, {19739,20305,20304 ,9656,9665,9663 ,0,0,0}, + {19648,20306,20307 ,9667,9667,9668 ,0,0,0}, {20308,20309,19646 ,9669,9670,9671 ,0,0,0}, + {20310,20311,19648 ,9672,9673,9667 ,0,0,0}, {20310,19648,20307 ,9672,9667,9668 ,0,0,0}, + {19648,20312,19646 ,9667,9674,9671 ,0,0,0}, {20312,19648,20311 ,9674,9667,9673 ,0,0,0}, + {20313,19646,20309 ,9675,9671,9670 ,0,0,0}, {20312,20308,19646 ,9674,9669,9671 ,0,0,0}, + {20305,19647,20313 ,9665,9666,9675 ,0,0,0}, {20313,19647,19646 ,9675,9666,9671 ,0,0,0}, + {19856,20314,20315 ,9676,9677,9678 ,0,0,0}, {19933,20316,19887 ,9679,9680,9681 ,0,0,0}, + {20314,19856,20317 ,9677,9676,9682 ,0,0,0}, {20315,20318,19856 ,9678,9676,9676 ,0,0,0}, + {20317,19856,19887 ,9682,9676,9681 ,0,0,0}, {20319,20317,19887 ,9683,9682,9681 ,0,0,0}, + {20319,19887,20316 ,9683,9681,9680 ,0,0,0}, {19890,19914,20320 ,9684,9685,9686 ,0,0,0}, + {19890,20321,20322 ,9684,9687,9688 ,0,0,0}, {20320,20321,19890 ,9686,9687,9684 ,0,0,0}, + {19933,20322,20323 ,9679,9688,9689 ,0,0,0}, {19933,19890,20322 ,9679,9684,9688 ,0,0,0}, + {19933,20324,20325 ,9679,9690,9691 ,0,0,0}, {20323,20324,19933 ,9689,9690,9679 ,0,0,0}, + {19933,20326,20327 ,9679,9692,9693 ,0,0,0}, {20325,20326,19933 ,9691,9692,9679 ,0,0,0}, + {20316,19933,20328 ,9680,9679,9694 ,0,0,0}, {20327,20328,19933 ,9693,9694,9679 ,0,0,0}, + {20197,20306,20158 ,9695,9696,9695 ,0,0,0}, {19648,20122,20306 ,9695,9695,9696 ,0,0,0}, + {20179,20329,20306 ,9695,9696,9696 ,0,0,0}, {20306,20197,20179 ,9696,9695,9695 ,0,0,0}, + {20141,20158,20306 ,9695,9695,9696 ,0,0,0}, {20141,20306,20122 ,9695,9696,9695 ,0,0,0}, + {20330,20331,20305 ,126,126,126 ,0,0,0}, {20313,20332,20330 ,9697,126,126 ,0,0,0}, + {20330,20305,20313 ,126,126,9697 ,0,0,0}, {20333,20334,20335 ,9698,9699,9700 ,0,0,0}, + {20334,20336,20335 ,9699,9701,9700 ,0,0,0}, {20334,20333,20337 ,9699,9698,9702 ,0,0,0}, + {20300,20338,20337 ,9703,9704,9702 ,0,0,0}, {20333,20300,20337 ,9698,9703,9702 ,0,0,0}, + {20298,20338,20300 ,9705,9704,9703 ,0,0,0}, {20338,20298,20339 ,9704,9705,9706 ,0,0,0}, + {20299,20340,20339 ,9707,9708,9706 ,0,0,0}, {20339,20298,20299 ,9706,9705,9707 ,0,0,0}, + {20340,20304,20341 ,9708,9709,9710 ,0,0,0}, {20304,20340,20299 ,9709,9708,9707 ,0,0,0}, + {20331,20341,20305 ,9711,9710,9712 ,0,0,0}, {20304,20305,20341 ,9709,9712,9710 ,0,0,0}, + {20342,20343,20311 ,9713,9714,9715 ,0,0,0}, {20344,20312,20343 ,9716,9717,9714 ,0,0,0}, + {20313,20309,20332 ,126,9718,126 ,0,0,0}, {20308,20345,20309 ,9719,9720,9718 ,0,0,0}, + {20308,20344,20345 ,9719,9716,9720 ,0,0,0}, {20345,20332,20309 ,9720,126,9718 ,0,0,0}, + {20312,20344,20308 ,9717,9716,9719 ,0,0,0}, {20312,20311,20343 ,9717,9715,9714 ,0,0,0}, + {20342,20311,20310 ,9713,9715,9721 ,0,0,0}, {20310,20307,20346 ,9721,9722,9723 ,0,0,0}, + {20346,20342,20310 ,9723,9713,9721 ,0,0,0}, {20347,20307,20306 ,9724,9722,9725 ,0,0,0}, + {20307,20347,20346 ,9722,9724,9723 ,0,0,0}, {20347,20306,20329 ,9724,9725,9725 ,0,0,0}, + {19817,20329,19798 ,9726,9727,9728 ,0,0,0}, {20348,20318,20349 ,9729,9730,9731 ,0,0,0}, + {20318,20342,20346 ,9730,9732,9733 ,0,0,0}, {20346,20347,20318 ,9733,9734,9730 ,0,0,0}, + {20348,20350,20318 ,9729,9735,9730 ,0,0,0}, {20318,20351,20342 ,9730,9736,9732 ,0,0,0}, + {20350,20351,20318 ,9735,9736,9730 ,0,0,0}, {20329,19856,20318 ,9727,9737,9730 ,0,0,0}, + {20347,20329,20318 ,9734,9727,9730 ,0,0,0}, {20329,19836,19856 ,9727,9738,9737 ,0,0,0}, + {19836,20329,19817 ,9738,9727,9726 ,0,0,0}, {20329,19776,19777 ,9727,9739,9740 ,0,0,0}, + {20329,20179,19776 ,9727,9727,9739 ,0,0,0}, {19777,19798,20329 ,9740,9728,9727 ,0,0,0}, + {20011,20031,20352 ,9741,9742,9743 ,0,0,0}, {20320,20353,20321 ,9744,9745,9746 ,0,0,0}, + {20354,20353,19972 ,9747,9745,9748 ,0,0,0}, {20355,20336,20356 ,9749,9750,9751 ,0,0,0}, + {20357,20355,20356 ,9752,9749,9751 ,0,0,0}, {20358,20359,20360 ,9753,9754,9755 ,0,0,0}, + {20359,20357,20360 ,9754,9752,9755 ,0,0,0}, {20353,19952,19972 ,9745,9756,9748 ,0,0,0}, + {20354,19972,19991 ,9747,9748,9757 ,0,0,0}, {20358,20322,20321 ,9753,9758,9746 ,0,0,0}, + {19914,19952,20320 ,9759,9756,9744 ,0,0,0}, {20011,20354,19991 ,9741,9747,9757 ,0,0,0}, + {20352,20361,20354 ,9743,9760,9747 ,0,0,0}, {20354,20011,20352 ,9747,9741,9743 ,0,0,0}, + {20361,20355,20357 ,9760,9749,9752 ,0,0,0}, {20359,20358,20321 ,9754,9753,9746 ,0,0,0}, + {20357,20359,20354 ,9752,9754,9747 ,0,0,0}, {20320,19952,20353 ,9744,9756,9745 ,0,0,0}, + {20357,20354,20361 ,9752,9747,9760 ,0,0,0}, {20356,20360,20357 ,9751,9755,9752 ,0,0,0}, + {20321,20353,20359 ,9746,9745,9754 ,0,0,0}, {20354,20359,20353 ,9747,9754,9745 ,0,0,0}, + {20362,20363,20364 ,9761,9762,9763 ,0,0,0}, {20338,20365,20366 ,9764,9765,9766 ,0,0,0}, + {20338,20339,20365 ,9764,9767,9765 ,0,0,0}, {20356,20334,20367 ,9768,9769,9770 ,0,0,0}, + {20368,20326,20369 ,9771,9772,9773 ,0,0,0}, {20356,20336,20334 ,9768,9774,9769 ,0,0,0}, + {20370,20371,20372 ,9775,9776,9777 ,0,0,0}, {20340,20373,20374 ,9778,9779,9780 ,0,0,0}, + {20331,20371,20375 ,126,9776,9781 ,0,0,0}, {20370,20376,20375 ,9775,9782,9781 ,0,0,0}, + {20328,20327,20377 ,9783,9784,9785 ,0,0,0}, {20327,20368,20377 ,9784,9771,9785 ,0,0,0}, + {20378,20379,20362 ,9786,9787,9761 ,0,0,0}, {20368,20369,20376 ,9771,9773,9782 ,0,0,0}, + {20380,20316,20328 ,9788,9789,9783 ,0,0,0}, {20337,20366,20367 ,9790,9766,9770 ,0,0,0}, + {20340,20374,20339 ,9778,9780,9767 ,0,0,0}, {20367,20364,20360 ,9770,9763,9791 ,0,0,0}, + {20360,20364,20358 ,9791,9763,9792 ,0,0,0}, {20358,20363,20322 ,9792,9762,9793 ,0,0,0}, + {20356,20367,20360 ,9768,9770,9791 ,0,0,0}, {20334,20337,20367 ,9769,9790,9770 ,0,0,0}, + {20363,20358,20364 ,9762,9792,9763 ,0,0,0}, {20363,20379,20323 ,9762,9787,9794 ,0,0,0}, + {20364,20366,20362 ,9763,9766,9761 ,0,0,0}, {20322,20363,20323 ,9793,9762,9794 ,0,0,0}, + {20367,20366,20364 ,9770,9766,9763 ,0,0,0}, {20337,20338,20366 ,9790,9764,9766 ,0,0,0}, + {20379,20363,20362 ,9787,9762,9761 ,0,0,0}, {20379,20381,20324 ,9787,9795,9796 ,0,0,0}, + {20362,20365,20378 ,9761,9765,9786 ,0,0,0}, {20323,20379,20324 ,9794,9787,9796 ,0,0,0}, + {20366,20365,20362 ,9766,9765,9761 ,0,0,0}, {20374,20365,20339 ,9780,9765,9767 ,0,0,0}, + {20381,20379,20378 ,9795,9787,9786 ,0,0,0}, {20381,20369,20325 ,9795,9773,9797 ,0,0,0}, + {20374,20382,20378 ,9780,9798,9786 ,0,0,0}, {20324,20381,20325 ,9796,9795,9797 ,0,0,0}, + {20374,20378,20365 ,9780,9786,9765 ,0,0,0}, {20341,20373,20340 ,9799,9779,9778 ,0,0,0}, + {20369,20381,20382 ,9773,9795,9798 ,0,0,0}, {20378,20382,20381 ,9786,9798,9795 ,0,0,0}, + {20373,20376,20382 ,9779,9782,9798 ,0,0,0}, {20325,20369,20326 ,9797,9773,9772 ,0,0,0}, + {20374,20373,20382 ,9780,9779,9798 ,0,0,0}, {20331,20375,20341 ,126,9781,9799 ,0,0,0}, + {20377,20368,20370 ,9785,9771,9775 ,0,0,0}, {20382,20376,20369 ,9798,9782,9773 ,0,0,0}, + {20376,20370,20368 ,9782,9775,9771 ,0,0,0}, {20326,20368,20327 ,9772,9771,9784 ,0,0,0}, + {20373,20341,20375 ,9779,9799,9781 ,0,0,0}, {20376,20373,20375 ,9782,9779,9781 ,0,0,0}, + {20377,20372,20380 ,9785,9777,9788 ,0,0,0}, {20371,20370,20375 ,9776,9775,9781 ,0,0,0}, + {20380,20328,20377 ,9788,9783,9785 ,0,0,0}, {20372,20377,20370 ,9777,9785,9775 ,0,0,0}, + {20371,20330,20383 ,9800,9801,9802 ,0,0,0}, {20319,20384,20317 ,9803,9804,9682 ,0,0,0}, + {20383,20330,20385 ,9802,9801,9805 ,0,0,0}, {20330,20332,20385 ,9801,126,9805 ,0,0,0}, + {20383,20386,20384 ,9802,9806,9804 ,0,0,0}, {20371,20331,20330 ,9800,126,9801 ,0,0,0}, + {20384,20386,20317 ,9804,9806,9682 ,0,0,0}, {20380,20384,20319 ,9807,9804,9803 ,0,0,0}, + {20316,20380,20319 ,9808,9807,9803 ,0,0,0}, {20380,20372,20384 ,9807,9809,9804 ,0,0,0}, + {20372,20371,20383 ,9809,9800,9802 ,0,0,0}, {20372,20383,20384 ,9809,9802,9804 ,0,0,0}, + {20386,20383,20385 ,9806,9802,9805 ,0,0,0}, {20351,20350,20343 ,9810,9811,9812 ,0,0,0}, + {20385,20332,20345 ,9813,126,9814 ,0,0,0}, {20345,20344,20387 ,9814,9815,9816 ,0,0,0}, + {20345,20387,20385 ,9814,9816,9813 ,0,0,0}, {20342,20351,20343 ,9817,9810,9812 ,0,0,0}, + {20348,20349,20388 ,9818,9819,9820 ,0,0,0}, {20388,20389,20348 ,9820,9821,9818 ,0,0,0}, + {20386,20387,20390 ,9822,9816,9823 ,0,0,0}, {20390,20387,20389 ,9823,9816,9821 ,0,0,0}, + {20349,20318,20315 ,9819,9824,9825 ,0,0,0}, {20386,20390,20317 ,9822,9823,9826 ,0,0,0}, + {20315,20390,20388 ,9825,9823,9820 ,0,0,0}, {20385,20387,20386 ,9813,9816,9822 ,0,0,0}, + {20315,20314,20390 ,9825,9827,9823 ,0,0,0}, {20390,20314,20317 ,9823,9827,9826 ,0,0,0}, + {20387,20344,20389 ,9816,9815,9821 ,0,0,0}, {20343,20389,20344 ,9812,9821,9815 ,0,0,0}, + {20315,20388,20349 ,9825,9820,9819 ,0,0,0}, {20390,20389,20388 ,9823,9821,9820 ,0,0,0}, + {20350,20389,20343 ,9811,9821,9812 ,0,0,0}, {20350,20348,20389 ,9811,9818,9821 ,0,0,0}, + {20391,20086,20392 ,9828,9829,9830 ,0,0,0}, {20105,19634,20303 ,9831,9832,9833 ,0,0,0}, + {20333,20393,20300 ,9834,9835,9836 ,0,0,0}, {20394,20355,20395 ,9837,9838,9839 ,0,0,0}, + {20355,20394,20335 ,9838,9837,9840 ,0,0,0}, {20335,20336,20355 ,9840,9841,9838 ,0,0,0}, + {20361,20395,20355 ,9842,9839,9838 ,0,0,0}, {20391,20069,20086 ,9828,9843,9829 ,0,0,0}, + {20335,20394,20333 ,9840,9837,9834 ,0,0,0}, {20393,20395,20396 ,9835,9839,9844 ,0,0,0}, + {20352,20031,20051 ,9845,9846,9847 ,0,0,0}, {20069,20391,20051 ,9843,9828,9847 ,0,0,0}, + {20396,20302,20301 ,9844,9848,9849 ,0,0,0}, {20392,20105,20303 ,9830,9831,9833 ,0,0,0}, + {20394,20395,20393 ,9837,9839,9835 ,0,0,0}, {20396,20301,20393 ,9844,9849,9835 ,0,0,0}, + {20300,20393,20301 ,9836,9835,9849 ,0,0,0}, {20333,20394,20393 ,9834,9837,9835 ,0,0,0}, + {20391,20361,20352 ,9828,9842,9845 ,0,0,0}, {20396,20391,20392 ,9844,9828,9830 ,0,0,0}, + {20396,20395,20391 ,9844,9839,9828 ,0,0,0}, {20302,20396,20392 ,9848,9844,9830 ,0,0,0}, + {20361,20391,20395 ,9842,9828,9839 ,0,0,0}, {20051,20391,20352 ,9847,9828,9845 ,0,0,0}, + {20105,20392,20086 ,9831,9830,9829 ,0,0,0}, {20392,20303,20302 ,9830,9833,9848 ,0,0,0}, + {19728,19592,19591 ,9850,9851,8275 ,0,0,0}, {20397,20398,19617 ,9852,9853,9854 ,0,0,0}, + {19664,20399,20400 ,9855,9856,9857 ,0,0,0}, {19622,19621,20401 ,9858,9859,9860 ,0,0,0}, + {19661,19696,20402 ,9861,9862,9863 ,0,0,0}, {19625,19626,20403 ,9864,9865,9866 ,0,0,0}, + {19625,20404,19621 ,9864,9867,9859 ,0,0,0}, {20405,19716,20406 ,9868,9869,9870 ,0,0,0}, + {19716,20405,19626 ,9869,9868,9865 ,0,0,0}, {20407,20406,19715 ,9871,9870,9872 ,0,0,0}, + {19716,19715,20406 ,9869,9872,9870 ,0,0,0}, {19605,4818,20407 ,126,126,9871 ,0,0,0}, + {20407,19715,19605 ,9871,9872,126 ,0,0,0}, {20403,20404,19625 ,9866,9867,9864 ,0,0,0}, + {19626,20405,20403 ,9865,9868,9866 ,0,0,0}, {20401,20402,19622 ,9860,9863,9858 ,0,0,0}, + {19621,20404,20401 ,9859,9867,9860 ,0,0,0}, {20397,19661,20402 ,9852,9861,9863 ,0,0,0}, + {19696,19622,20402 ,9862,9858,9863 ,0,0,0}, {20398,19615,19617 ,9853,9873,9854 ,0,0,0}, + {20397,19617,19661 ,9852,9854,9861 ,0,0,0}, {19664,19615,20399 ,9855,9873,9856 ,0,0,0}, + {20398,20399,19615 ,9853,9856,9873 ,0,0,0}, {19728,20400,20408 ,9850,9857,9874 ,0,0,0}, + {19664,20400,19728 ,9855,9857,9850 ,0,0,0}, {19592,19728,20408 ,9851,9850,9874 ,0,0,0}, + {20399,19571,19574 ,730,730,730 ,0,0,0}, {19587,20409,19585 ,730,730,730 ,0,0,0}, + {19587,19590,20410 ,730,730,730 ,0,0,0}, {19583,19585,20411 ,730,730,730 ,0,0,0}, + {19590,19577,20410 ,730,730,730 ,0,0,0}, {20409,19587,20410 ,730,730,730 ,0,0,0}, + {19577,19590,19592 ,730,730,730 ,0,0,0}, {19583,20412,19580 ,730,730,730 ,0,0,0}, + {20408,19577,19592 ,730,730,730 ,0,0,0}, {19559,19571,20397 ,730,730,730 ,0,0,0}, + {19594,19582,20413 ,730,730,730 ,0,0,0}, {20414,19595,19594 ,730,730,730 ,0,0,0}, + {8402,19559,20402 ,730,730,730 ,0,0,0}, {19561,20401,20404 ,730,730,730 ,0,0,0}, + {20415,19598,19595 ,730,730,730 ,0,0,0}, {19598,20416,19599 ,730,730,730 ,0,0,0}, + {19601,19599,20417 ,730,730,730 ,0,0,0}, {20404,19562,19561 ,730,730,730 ,0,0,0}, + {19562,20403,20405 ,730,730,730 ,0,0,0}, {19569,20407,4818 ,730,730,730 ,0,0,0}, + {4818,19604,19569 ,730,730,730 ,0,0,0}, {19601,20418,19604 ,730,730,730 ,0,0,0}, + {20406,19568,20405 ,730,730,730 ,0,0,0}, {19582,19580,20413 ,730,730,730 ,0,0,0}, + {19574,19576,20400 ,730,730,730 ,0,0,0}, {20402,20401,8402 ,730,730,730 ,0,0,0}, + {20409,20411,19585 ,730,730,730 ,0,0,0}, {20411,20412,19583 ,730,730,730 ,0,0,0}, + {20412,20413,19580 ,730,730,730 ,0,0,0}, {20413,20414,19594 ,730,730,730 ,0,0,0}, + {20414,20415,19595 ,730,730,730 ,0,0,0}, {20415,20416,19598 ,730,730,730 ,0,0,0}, + {20416,20417,19599 ,730,730,730 ,0,0,0}, {20417,20418,19601 ,730,730,730 ,0,0,0}, + {20418,19569,19604 ,730,730,730 ,0,0,0}, {19569,19565,20407 ,730,730,730 ,0,0,0}, + {19565,19568,20406 ,730,730,730 ,0,0,0}, {19565,20406,20407 ,730,730,730 ,0,0,0}, + {19568,19562,20405 ,730,730,730 ,0,0,0}, {20403,19562,20404 ,730,730,730 ,0,0,0}, + {19561,8402,20401 ,730,730,730 ,0,0,0}, {19559,20397,20402 ,730,730,730 ,0,0,0}, + {19571,20398,20397 ,730,730,730 ,0,0,0}, {20399,19574,20400 ,730,730,730 ,0,0,0}, + {20398,19571,20399 ,730,730,730 ,0,0,0}, {20400,19576,20408 ,730,730,730 ,0,0,0}, + {19577,20408,19576 ,730,730,730 ,0,0,0}, {19575,20419,20420 ,730,730,9875 ,0,0,0}, + {20421,20420,20422 ,730,9875,730 ,0,0,0}, {20421,20422,20423 ,730,730,9875 ,0,0,0}, + {20424,20420,20421 ,730,9875,730 ,0,0,0}, {20424,19578,20420 ,730,730,9875 ,0,0,0}, + {20423,20422,20425 ,9875,730,9876 ,0,0,0}, {19575,20420,19578 ,730,9875,730 ,0,0,0}, + {20419,19573,20426 ,730,730,9876 ,0,0,0}, {20419,19575,19573 ,730,730,730 ,0,0,0}, + {20426,19573,20427 ,9876,730,730 ,0,0,0}, {20427,19573,19572 ,730,730,9876 ,0,0,0}, + {20427,19572,19570 ,730,9876,730 ,0,0,0}, {20428,19570,19558 ,9877,730,9876 ,0,0,0}, + {19570,20428,20427 ,730,9877,730 ,0,0,0}, {19566,20428,19563 ,730,9877,730 ,0,0,0}, + {19558,19563,20428 ,9876,730,9877 ,0,0,0}, {19567,19560,19564 ,9876,730,9878 ,0,0,0}, + {19563,19560,19567 ,730,730,9876 ,0,0,0}, {19567,19566,19563 ,9876,730,730 ,0,0,0}, + {19569,20418,20428 ,9879,9880,9881 ,0,0,0}, {20420,20419,20415 ,9882,9883,9884 ,0,0,0}, + {20426,20427,20417 ,9885,9886,9887 ,0,0,0}, {20425,20413,20412 ,9888,9889,9890 ,0,0,0}, + {20414,20413,20422 ,9891,9889,9892 ,0,0,0}, {20421,20411,20409 ,9893,9894,9895 ,0,0,0}, + {20411,20421,20423 ,9894,9893,9896 ,0,0,0}, {20410,20424,20409 ,9897,9898,9895 ,0,0,0}, + {20421,20409,20424 ,9893,9895,9898 ,0,0,0}, {20410,19577,19578 ,9897,96,96 ,0,0,0}, + {19578,20424,20410 ,96,9898,9897 ,0,0,0}, {20425,20412,20423 ,9888,9890,9896 ,0,0,0}, + {20412,20411,20423 ,9890,9894,9896 ,0,0,0}, {20415,20414,20420 ,9884,9891,9882 ,0,0,0}, + {20414,20422,20420 ,9891,9892,9882 ,0,0,0}, {20422,20413,20425 ,9892,9889,9888 ,0,0,0}, + {20427,20428,20418 ,9886,9881,9880 ,0,0,0}, {20416,20415,20419 ,9899,9884,9883 ,0,0,0}, + {20418,20417,20427 ,9880,9887,9886 ,0,0,0}, {20416,20426,20417 ,9899,9885,9887 ,0,0,0}, + {20419,20426,20416 ,9883,9885,9899 ,0,0,0}, {20428,19566,19569 ,9881,761,9879 ,0,0,0}, + {19630,19546,19545 ,9900,82,9901 ,0,0,0}, {20429,20430,19712 ,9902,9903,9904 ,0,0,0}, + {19713,20431,19632 ,9905,9906,9907 ,0,0,0}, {20432,19651,20433 ,9908,9909,9910 ,0,0,0}, + {19708,19653,20434 ,9911,9912,9913 ,0,0,0}, {20435,19650,19710 ,9914,9915,9916 ,0,0,0}, + {19650,20435,20433 ,9915,9914,9910 ,0,0,0}, {19642,20436,19710 ,9917,9918,9916 ,0,0,0}, + {20435,19710,20436 ,9914,9916,9918 ,0,0,0}, {19642,19557,19556 ,9917,2619,3135 ,0,0,0}, + {19556,20436,19642 ,3135,9918,9917 ,0,0,0}, {19651,20432,19653 ,9909,9908,9912 ,0,0,0}, + {19651,19650,20433 ,9909,9915,9910 ,0,0,0}, {20429,19708,20434 ,9902,9911,9913 ,0,0,0}, + {20434,19653,20432 ,9913,9912,9908 ,0,0,0}, {20430,19713,19712 ,9903,9905,9904 ,0,0,0}, + {20429,19712,19708 ,9902,9904,9911 ,0,0,0}, {20431,20437,19632 ,9906,9919,9907 ,0,0,0}, + {20430,20431,19713 ,9903,9906,9905 ,0,0,0}, {19546,19630,20437 ,82,9900,9919 ,0,0,0}, + {19632,20437,19630 ,9907,9919,9900 ,0,0,0}, {19553,20429,19554 ,730,730,730 ,0,0,0}, + {19550,20431,19551 ,730,730,730 ,0,0,0}, {19556,20434,20432 ,730,730,730 ,0,0,0}, + {20436,20432,20433 ,730,730,730 ,0,0,0}, {20435,20436,20433 ,730,730,730 ,0,0,0}, + {19554,20434,19556 ,730,730,730 ,0,0,0}, {19556,20432,20436 ,730,730,730 ,0,0,0}, + {19554,20429,20434 ,730,730,730 ,0,0,0}, {19553,20430,20429 ,730,730,730 ,0,0,0}, + {19553,19551,20431 ,730,730,730 ,0,0,0}, {20431,20430,19553 ,730,730,730 ,0,0,0}, + {20437,20431,19550 ,730,730,730 ,0,0,0}, {20437,19547,19546 ,730,730,730 ,0,0,0}, + {19547,20437,19550 ,730,730,730 ,0,0,0}, {19546,19547,19539 ,730,730,730 ,0,0,0}, + {19542,19536,19540 ,730,730,730 ,0,0,0}, {19539,19536,19542 ,730,730,730 ,0,0,0}, + {19542,19546,19539 ,730,730,730 ,0,0,0}, {19723,19524,19525 ,9920,9921,9922 ,0,0,0}, + {20438,20439,19669 ,9902,9903,9923 ,0,0,0}, {19670,20440,19722 ,9924,9906,9925 ,0,0,0}, + {20441,19667,19666 ,9908,9926,9927 ,0,0,0}, {19683,19667,20442 ,9928,9926,8336 ,0,0,0}, + {20443,19727,19619 ,9914,9929,9930 ,0,0,0}, {19666,19727,20444 ,9927,9929,9910 ,0,0,0}, + {19618,20445,19619 ,9931,9918,9930 ,0,0,0}, {20443,19619,20445 ,9914,9930,9918 ,0,0,0}, + {19618,19535,19534 ,9931,96,9932 ,0,0,0}, {19534,20445,19618 ,9932,9918,9931 ,0,0,0}, + {20441,19666,20444 ,9908,9927,9910 ,0,0,0}, {20444,19727,20443 ,9910,9929,9914 ,0,0,0}, + {19683,20442,20438 ,9928,8336,9902 ,0,0,0}, {20442,19667,20441 ,8336,9926,9908 ,0,0,0}, + {20439,19670,19669 ,9903,9924,9923 ,0,0,0}, {20438,19669,19683 ,9902,9923,9928 ,0,0,0}, + {20440,20446,19722 ,9906,9919,9925 ,0,0,0}, {20439,20440,19670 ,9903,9906,9924 ,0,0,0}, + {19524,19723,20446 ,9921,9920,9919 ,0,0,0}, {19722,20446,19723 ,9925,9919,9920 ,0,0,0}, + {19529,20438,19531 ,730,730,730 ,0,0,0}, {19526,20440,19528 ,730,730,730 ,0,0,0}, + {19534,20442,20441 ,730,730,730 ,0,0,0}, {20445,20441,20444 ,730,730,730 ,0,0,0}, + {20443,20445,20444 ,730,730,730 ,0,0,0}, {19531,20442,19534 ,730,730,730 ,0,0,0}, + {19534,20441,20445 ,730,730,730 ,0,0,0}, {19531,20438,20442 ,730,730,730 ,0,0,0}, + {19529,20439,20438 ,730,730,730 ,0,0,0}, {19529,19528,20440 ,730,730,730 ,0,0,0}, + {20440,20439,19529 ,730,730,730 ,0,0,0}, {20446,20440,19526 ,730,730,730 ,0,0,0}, + {20446,19514,19524 ,730,730,730 ,0,0,0}, {19514,20446,19526 ,730,730,730 ,0,0,0}, + {19524,19514,19517 ,730,730,730 ,0,0,0}, {19520,19518,19521 ,730,730,730 ,0,0,0}, + {19517,19518,19520 ,730,730,730 ,0,0,0}, {19520,19524,19517 ,730,730,730 ,0,0,0} +// X-Ufo 8ZollPropeller.prt + , {20447,20448,20449 ,9933,9934,9935 ,0,0,0}, {20447,20450,20451 ,9933,9936,9937 ,0,0,0}, + {20451,20448,20447 ,9937,9934,9933 ,0,0,0}, {20452,20450,20453 ,9938,9936,9939 ,0,0,0}, + {20450,20452,20451 ,9936,9938,9937 ,0,0,0}, {20454,20455,20456 ,9940,9941,9942 ,0,0,0}, + {20452,20453,20455 ,9938,9939,9941 ,0,0,0}, {20457,20458,20454 ,9943,2394,9940 ,0,0,0}, + {20457,20459,20458 ,9943,9944,2394 ,0,0,0}, {20457,20454,20456 ,9943,9940,9942 ,0,0,0}, + {20455,20453,20456 ,9941,9939,9942 ,0,0,0}, {20460,20449,20448 ,9945,9935,9934 ,0,0,0}, + {20461,20460,20462 ,9946,9945,9947 ,0,0,0}, {20460,20461,20449 ,9945,9946,9935 ,0,0,0}, + {20463,20464,20462 ,9948,9949,9947 ,0,0,0}, {20461,20462,20464 ,9946,9947,9949 ,0,0,0}, + {20463,20465,20466 ,9948,9950,9951 ,0,0,0}, {20466,20464,20463 ,9951,9949,9948 ,0,0,0}, + {20467,20465,20468 ,9952,9950,9953 ,0,0,0}, {20465,20467,20466 ,9950,9952,9951 ,0,0,0}, + {20467,20468,20469 ,9952,9953,9954 ,0,0,0}, {20470,20471,20472 ,9938,9955,9956 ,0,0,0}, + {20470,20473,20471 ,9938,9937,9955 ,0,0,0}, {20470,20472,20474 ,9938,9956,9941 ,0,0,0}, + {20474,20475,20476 ,9941,9957,9940 ,0,0,0}, {20475,20474,20472 ,9957,9941,9956 ,0,0,0}, + {20477,20476,20475 ,9958,9940,9957 ,0,0,0}, {20478,20471,20473 ,9959,9955,9937 ,0,0,0}, + {20477,20479,20480 ,9958,9960,9961 ,0,0,0}, {20480,20476,20477 ,9961,9940,9958 ,0,0,0}, + {20478,20473,20481 ,9959,9937,9962 ,0,0,0}, {20481,20482,20478 ,9962,9963,9959 ,0,0,0}, + {20483,20482,20484 ,9964,9963,9945 ,0,0,0}, {20481,20484,20482 ,9962,9945,9963 ,0,0,0}, + {20485,20486,20483 ,9947,9965,9964 ,0,0,0}, {20483,20484,20485 ,9964,9945,9947 ,0,0,0}, + {20487,20488,20486 ,9948,9950,9965 ,0,0,0}, {20487,20486,20485 ,9948,9965,9947 ,0,0,0}, + {20489,20488,20490 ,9966,9950,9967 ,0,0,0}, {20488,20489,20486 ,9950,9966,9965 ,0,0,0}, + {20489,20490,20491 ,9966,9967,9968 ,0,0,0}, {20492,20493,8447 ,9969,9970,9971 ,0,0,0}, + {20494,20495,20496 ,9972,9973,9974 ,0,0,0}, {20497,20492,8447 ,9975,9969,9971 ,0,0,0}, + {20494,20496,20498 ,9972,9974,9976 ,0,0,0}, {20495,20494,20497 ,9973,9972,9975 ,0,0,0}, + {20495,20497,8447 ,9973,9975,9971 ,0,0,0}, {20499,20500,20501 ,9977,9978,9979 ,0,0,0}, + {20501,20498,20502 ,9979,9976,9980 ,0,0,0}, {20499,20501,20502 ,9977,9979,9980 ,0,0,0}, + {20500,20499,20503 ,9978,9977,9981 ,0,0,0}, {20502,20498,20496 ,9980,9976,9974 ,0,0,0}, + {20492,20504,20493 ,9969,9945,9970 ,0,0,0}, {20505,20504,20506 ,9982,9945,9983 ,0,0,0}, + {20504,20505,20493 ,9945,9982,9970 ,0,0,0}, {20507,20508,20506 ,9984,9985,9983 ,0,0,0}, + {20505,20506,20508 ,9982,9983,9985 ,0,0,0}, {20507,20509,20510 ,9984,9986,9987 ,0,0,0}, + {20510,20508,20507 ,9987,9985,9984 ,0,0,0}, {20511,20509,20512 ,9988,9986,21 ,0,0,0}, + {20509,20511,20510 ,9986,9988,9987 ,0,0,0}, {20513,20514,20515 ,9989,9990,9991 ,0,0,0}, + {20515,20514,20516 ,9991,9990,9992 ,0,0,0}, {20517,20514,20513 ,9993,9990,9989 ,0,0,0}, + {20518,20515,20516 ,9994,9991,9992 ,0,0,0}, {20517,20513,20519 ,9993,9989,9995 ,0,0,0}, + {20519,20520,20521 ,9995,9996,9997 ,0,0,0}, {20520,20519,20513 ,9996,9995,9989 ,0,0,0}, + {20518,20516,20522 ,9994,9992,9998 ,0,0,0}, {20523,20524,20521 ,9999,10000,9997 ,0,0,0}, + {20521,20520,20523 ,9997,9996,9999 ,0,0,0}, {20524,20525,20526 ,10000,9961,10001 ,0,0,0}, + {20527,20524,20523 ,10002,10000,9999 ,0,0,0}, {20527,20525,20524 ,10002,9961,10000 ,0,0,0}, + {20516,20528,20522 ,9992,10003,9998 ,0,0,0}, {20528,20529,20530 ,10003,10004,10005 ,0,0,0}, + {20530,20522,20528 ,10005,9998,10003 ,0,0,0}, {20531,20529,20532 ,10006,10004,10007 ,0,0,0}, + {20529,20531,20530 ,10004,10006,10005 ,0,0,0}, {20533,20534,20532 ,10008,10009,10007 ,0,0,0}, + {20531,20532,20534 ,10006,10007,10009 ,0,0,0}, {20533,20535,20536 ,10008,10010,10011 ,0,0,0}, + {20536,20534,20533 ,10011,10009,10008 ,0,0,0}, {20537,20535,20538 ,10012,10010,10013 ,0,0,0}, + {20535,20537,20536 ,10010,10012,10011 ,0,0,0}, {20537,20538,20539 ,10012,10013,10014 ,0,0,0}, + {20539,20538,20540 ,10014,10013,10015 ,0,0,0}, {20541,20542,20543 ,10016,10017,10018 ,0,0,0}, + {20544,20545,20546 ,10019,10020,10021 ,0,0,0}, {20547,20548,20549 ,10022,10023,10024 ,0,0,0}, + {20550,20551,20552 ,10025,10026,10027 ,0,0,0}, {20553,20554,20555 ,10028,10029,10030 ,0,0,0}, + {20555,20469,20553 ,10030,10031,10028 ,0,0,0}, {20556,20557,20558 ,10032,10033,10034 ,0,0,0}, + {20534,20559,20531 ,10035,10036,10037 ,0,0,0}, {20560,20558,20561 ,10038,10034,10039 ,0,0,0}, + {20562,20563,20564 ,10040,10041,10042 ,0,0,0}, {20565,20566,20567 ,10043,10044,10045 ,0,0,0}, + {20568,20569,20570 ,10046,10047,10048 ,0,0,0}, {20571,20559,20564 ,10049,10036,10042 ,0,0,0}, + {20572,20483,20486 ,10050,10051,10052 ,0,0,0}, {20573,20574,20570 ,10053,10054,10048 ,0,0,0}, + {20575,20576,20577 ,10055,10056,10057 ,0,0,0}, {20578,20579,20575 ,10058,10059,10055 ,0,0,0}, + {20580,20581,20578 ,10060,10061,10058 ,0,0,0}, {20582,20578,20581 ,10062,10058,10061 ,0,0,0}, + {20583,20581,20580 ,10063,10061,10060 ,0,0,0}, {20584,20585,20586 ,10064,10065,10066 ,0,0,0}, + {20587,20572,20576 ,10067,10050,10056 ,0,0,0}, {20588,20589,20584 ,10068,10069,10064 ,0,0,0}, + {20537,20539,20564 ,10070,10071,10042 ,0,0,0}, {20566,20590,20567 ,10044,10072,10045 ,0,0,0}, + {20557,20591,20558 ,10033,10073,10034 ,0,0,0}, {20592,20593,20594 ,10074,10075,10076 ,0,0,0}, + {20515,20595,20513 ,10077,10078,10079 ,0,0,0}, {20552,20591,20596 ,10027,10073,10080 ,0,0,0}, + {20597,20466,20598 ,10081,10082,10083 ,0,0,0}, {20599,20600,20550 ,10084,10085,10025 ,0,0,0}, + {20545,20601,20602 ,10020,10086,10087 ,0,0,0}, {20603,20604,20605 ,10088,10089,10090 ,0,0,0}, + {20544,20546,20606 ,10019,10021,10091 ,0,0,0}, {20542,20541,20607 ,10017,10016,10092 ,0,0,0}, + {20608,20546,20603 ,10093,10021,10088 ,0,0,0}, {20609,20610,20611 ,10094,10095,10096 ,0,0,0}, + {20610,20607,20541 ,10095,10092,10016 ,0,0,0}, {20449,20612,20447 ,10097,10098,10099 ,0,0,0}, + {20613,20543,20614 ,10100,10018,10101 ,0,0,0}, {20544,20615,20616 ,10019,10102,10103 ,0,0,0}, + {20600,20525,20617 ,10085,10104,10105 ,0,0,0}, {20603,20546,20545 ,10088,10021,10020 ,0,0,0}, + {20603,20602,20618 ,10088,10087,10106 ,0,0,0}, {20545,20602,20603 ,10020,10087,10088 ,0,0,0}, + {20619,20620,20548 ,10107,10108,10023 ,0,0,0}, {20608,20547,20621 ,10093,10022,10109 ,0,0,0}, + {20543,20457,20456 ,10018,10110,10111 ,0,0,0}, {20622,20620,20619 ,10112,10108,10107 ,0,0,0}, + {20542,20622,20619 ,10017,10112,10107 ,0,0,0}, {20610,20541,20611 ,10095,10016,10096 ,0,0,0}, + {20607,20622,20542 ,10092,10112,10017 ,0,0,0}, {20614,20543,20456 ,10101,10018,10111 ,0,0,0}, + {20543,20613,20623 ,10018,10100,10113 ,0,0,0}, {20612,20614,20447 ,10098,10101,10099 ,0,0,0}, + {20614,20612,20613 ,10101,10098,10100 ,0,0,0}, {20461,20597,20449 ,10114,10081,10097 ,0,0,0}, + {20466,20597,20464 ,10082,10081,10115 ,0,0,0}, {20597,20612,20449 ,10081,10098,10097 ,0,0,0}, + {20598,20624,20597 ,10083,10116,10081 ,0,0,0}, {20467,20598,20466 ,10117,10083,10082 ,0,0,0}, + {20598,20469,20555 ,10083,10031,10030 ,0,0,0}, {20518,20625,20595 ,10118,10119,10078 ,0,0,0}, + {20626,20561,20558 ,10120,10039,10034 ,0,0,0}, {20566,20627,20628 ,10044,10121,10122 ,0,0,0}, + {20477,20627,20479 ,10123,10121,10124 ,0,0,0}, {20626,20629,20630 ,10120,10125,10126 ,0,0,0}, + {20560,20556,20558 ,10038,10032,10034 ,0,0,0}, {20515,20518,20595 ,10077,10118,10078 ,0,0,0}, + {20557,20631,20591 ,10033,10127,10073 ,0,0,0}, {20558,20591,20632 ,10034,10073,10128 ,0,0,0}, + {20591,20552,20551 ,10073,10027,10026 ,0,0,0}, {20600,20551,20550 ,10085,10026,10025 ,0,0,0}, + {20591,20551,20633 ,10073,10026,10129 ,0,0,0}, {20634,20617,20592 ,10130,10105,10074 ,0,0,0}, + {20600,20635,20551 ,10085,10131,10026 ,0,0,0}, {20545,20616,20555 ,10020,10103,10030 ,0,0,0}, + {20615,20635,20634 ,10102,10131,10130 ,0,0,0}, {20594,20598,20555 ,10076,10083,10030 ,0,0,0}, + {20555,20554,20545 ,10030,10029,10020 ,0,0,0}, {20594,20636,20598 ,10076,10132,10083 ,0,0,0}, + {20637,20594,20593 ,10133,10076,10075 ,0,0,0}, {20595,20638,20593 ,10078,10134,10075 ,0,0,0}, + {20595,20625,20639 ,10078,10119,10135 ,0,0,0}, {20518,20522,20625 ,10118,10136,10119 ,0,0,0}, + {20522,20530,20625 ,10136,10137,10119 ,0,0,0}, {20625,20559,20640 ,10119,10036,10138 ,0,0,0}, + {20534,20564,20559 ,10035,10042,10036 ,0,0,0}, {20536,20564,20534 ,10139,10042,10035 ,0,0,0}, + {20564,20536,20537 ,10042,10139,10070 ,0,0,0}, {20625,20531,20559 ,10119,10037,10036 ,0,0,0}, + {20539,20562,20564 ,10071,10040,10042 ,0,0,0}, {20641,20627,20642 ,10140,10121,10141 ,0,0,0}, + {20589,20588,20643 ,10069,10068,10142 ,0,0,0}, {20644,20575,20584 ,10143,10055,10064 ,0,0,0}, + {20584,20575,20645 ,10064,10055,10144 ,0,0,0}, {20645,20585,20584 ,10144,10065,10064 ,0,0,0}, + {20584,20589,20644 ,10064,10069,10143 ,0,0,0}, {20646,20571,20563 ,10145,10049,10041 ,0,0,0}, + {20590,20589,20643 ,10072,10069,10142 ,0,0,0}, {20590,20643,20647 ,10072,10142,10146 ,0,0,0}, + {20567,20590,20648 ,10045,10072,10147 ,0,0,0}, {20565,20479,20566 ,10043,10124,10044 ,0,0,0}, + {20649,20626,20628 ,10148,10120,10122 ,0,0,0}, {20627,20566,20479 ,10121,10044,10124 ,0,0,0}, + {20562,20539,20650 ,10040,10071,10149 ,0,0,0}, {20561,20562,20651 ,10039,10040,10150 ,0,0,0}, + {20641,20563,20649 ,10140,10041,10148 ,0,0,0}, {20641,20652,20646 ,10140,10151,10145 ,0,0,0}, + {20653,20482,20483 ,10152,10153,10051 ,0,0,0}, {20653,20478,20482 ,10152,10154,10153 ,0,0,0}, + {20654,20653,20574 ,10155,10152,10054 ,0,0,0}, {20652,20642,20654 ,10151,10141,10155 ,0,0,0}, + {20483,20572,20653 ,10051,10050,10152 ,0,0,0}, {20491,20577,20576 ,10156,10057,10056 ,0,0,0}, + {20619,20655,20542 ,10107,10157,10017 ,0,0,0}, {20549,20548,20620 ,10024,10023,10108 ,0,0,0}, + {20608,20656,20548 ,10093,10158,10023 ,0,0,0}, {20459,20457,20655 ,10159,10110,10157 ,0,0,0}, + {20656,20655,20619 ,10158,10157,10107 ,0,0,0}, {20655,20457,20543 ,10157,10110,10018 ,0,0,0}, + {20542,20655,20543 ,10017,10157,10018 ,0,0,0}, {20623,20611,20541 ,10113,10096,10016 ,0,0,0}, + {20547,20608,20548 ,10022,10093,10023 ,0,0,0}, {20621,20606,20546 ,10109,10091,10021 ,0,0,0}, + {20655,20657,20658 ,10157,10160,10161 ,0,0,0}, {20548,20656,20619 ,10023,10158,10107 ,0,0,0}, + {20605,20656,20603 ,10090,10158,10088 ,0,0,0}, {20459,20655,20658 ,10159,10157,10161 ,0,0,0}, + {20456,20453,20614 ,10111,10162,10101 ,0,0,0}, {20623,20541,20543 ,10113,10016,10018 ,0,0,0}, + {20621,20546,20608 ,10109,10021,10093 ,0,0,0}, {20606,20659,20544 ,10091,10163,10019 ,0,0,0}, + {20604,20603,20618 ,10089,10088,10106 ,0,0,0}, {20608,20603,20656 ,10093,10088,10158 ,0,0,0}, + {20657,20656,20605 ,10160,10158,10090 ,0,0,0}, {20656,20657,20655 ,10158,10160,10157 ,0,0,0}, + {20453,20450,20614 ,10162,10164,10101 ,0,0,0}, {20614,20450,20447 ,10101,10164,10099 ,0,0,0}, + {20660,20615,20659 ,10165,10102,10163 ,0,0,0}, {20660,20661,20635 ,10165,10166,10131 ,0,0,0}, + {20601,20545,20662 ,10086,10020,10167 ,0,0,0}, {20554,20662,20545 ,10029,10167,10020 ,0,0,0}, + {20612,20597,20624 ,10098,10081,10116 ,0,0,0}, {20461,20464,20597 ,10114,10115,10081 ,0,0,0}, + {20615,20544,20659 ,10102,10019,10163 ,0,0,0}, {20663,20525,20600 ,10168,10104,10085 ,0,0,0}, + {20555,20616,20592 ,10030,10103,10074 ,0,0,0}, {20544,20616,20545 ,10019,10103,10020 ,0,0,0}, + {20592,20616,20634 ,10074,10103,10130 ,0,0,0}, {20469,20598,20467 ,10031,10083,10117 ,0,0,0}, + {20555,20592,20594 ,10030,10074,10076 ,0,0,0}, {20598,20636,20624 ,10083,10132,10116 ,0,0,0}, + {20660,20635,20615 ,10165,10131,10102 ,0,0,0}, {20664,20635,20661 ,10169,10131,10166 ,0,0,0}, + {20525,20527,20617 ,10104,10170,10105 ,0,0,0}, {20615,20634,20616 ,10102,10130,10103 ,0,0,0}, + {20600,20617,20634 ,10085,10105,10130 ,0,0,0}, {20513,20595,20520 ,10079,10078,10171 ,0,0,0}, + {20593,20592,20617 ,10075,10074,10105 ,0,0,0}, {20636,20594,20637 ,10132,10076,10133 ,0,0,0}, + {20635,20664,20551 ,10131,10169,10026 ,0,0,0}, {20633,20551,20664 ,10129,10026,10169 ,0,0,0}, + {20663,20600,20599 ,10168,10085,10084 ,0,0,0}, {20635,20600,20634 ,10131,10085,10130 ,0,0,0}, + {20527,20523,20617 ,10170,10172,10105 ,0,0,0}, {20617,20523,20520 ,10105,10172,10171 ,0,0,0}, + {20520,20593,20617 ,10171,10075,10105 ,0,0,0}, {20637,20593,20638 ,10133,10075,10134 ,0,0,0}, + {20591,20633,20632 ,10073,10129,10128 ,0,0,0}, {20631,20596,20591 ,10127,10080,10073 ,0,0,0}, + {20638,20595,20639 ,10134,10078,10135 ,0,0,0}, {20520,20595,20593 ,10171,10078,10075 ,0,0,0}, + {20632,20629,20558 ,10128,10125,10034 ,0,0,0}, {20558,20629,20626 ,10034,10125,10120 ,0,0,0}, + {20531,20625,20530 ,10037,10119,10137 ,0,0,0}, {20625,20640,20639 ,10119,10138,10135 ,0,0,0}, + {20626,20562,20561 ,10120,10040,10039 ,0,0,0}, {20630,20665,20628 ,10126,10173,10122 ,0,0,0}, + {20475,20627,20477 ,10174,10121,10123 ,0,0,0}, {20651,20562,20650 ,10150,10040,10149 ,0,0,0}, + {20649,20562,20626 ,10148,10040,10120 ,0,0,0}, {20666,20559,20571 ,10175,10036,10049 ,0,0,0}, + {20564,20563,20571 ,10042,10041,10049 ,0,0,0}, {20640,20559,20666 ,10138,10036,10175 ,0,0,0}, + {20630,20628,20626 ,10126,10122,10120 ,0,0,0}, {20665,20667,20566 ,10173,10176,10044 ,0,0,0}, + {20471,20642,20472 ,10177,10141,10178 ,0,0,0}, {20562,20649,20563 ,10040,10148,10041 ,0,0,0}, + {20649,20628,20627 ,10148,10122,10121 ,0,0,0}, {20571,20668,20669 ,10049,10179,10180 ,0,0,0}, + {20563,20641,20646 ,10041,10140,10145 ,0,0,0}, {20666,20571,20669 ,10175,10049,10180 ,0,0,0}, + {20665,20566,20628 ,10173,10044,10122 ,0,0,0}, {20667,20590,20566 ,10176,10072,10044 ,0,0,0}, + {20642,20475,20472 ,10141,10174,10178 ,0,0,0}, {20649,20627,20641 ,10148,10121,10140 ,0,0,0}, + {20627,20475,20642 ,10121,10174,10141 ,0,0,0}, {20646,20670,20668 ,10145,10181,10179 ,0,0,0}, + {20641,20642,20652 ,10140,10141,10151 ,0,0,0}, {20668,20571,20646 ,10179,10049,10145 ,0,0,0}, + {20589,20590,20667 ,10069,10072,10176 ,0,0,0}, {20647,20648,20590 ,10146,10147,10072 ,0,0,0}, + {20653,20471,20478 ,10152,10177,10154 ,0,0,0}, {20652,20671,20670 ,10151,10182,10181 ,0,0,0}, + {20642,20653,20654 ,10141,10152,10155 ,0,0,0}, {20670,20646,20652 ,10181,10145,10151 ,0,0,0}, + {20584,20586,20588 ,10064,10066,10068 ,0,0,0}, {20644,20672,20575 ,10143,10183,10055 ,0,0,0}, + {20486,20489,20576 ,10052,10184,10056 ,0,0,0}, {20486,20576,20572 ,10052,10056,10050 ,0,0,0}, + {20654,20573,20671 ,10155,10053,10182 ,0,0,0}, {20653,20642,20471 ,10152,10141,10177 ,0,0,0}, + {20653,20572,20574 ,10152,10050,10054 ,0,0,0}, {20671,20652,20654 ,10182,10151,10155 ,0,0,0}, + {20575,20577,20645 ,10055,10057,10144 ,0,0,0}, {20672,20580,20578 ,10183,10060,10058 ,0,0,0}, + {20673,20569,20568 ,10185,10047,10046 ,0,0,0}, {20491,20576,20489 ,10156,10056,10184 ,0,0,0}, + {20576,20579,20587 ,10056,10059,10067 ,0,0,0}, {20568,20574,20572 ,10046,10054,10050 ,0,0,0}, + {20587,20568,20572 ,10067,10046,10050 ,0,0,0}, {20573,20654,20574 ,10053,10155,10054 ,0,0,0}, + {20672,20578,20575 ,10183,10058,10055 ,0,0,0}, {20575,20579,20576 ,10055,10059,10056 ,0,0,0}, + {20582,20674,20579 ,10062,10186,10059 ,0,0,0}, {20578,20582,20579 ,10058,10062,10059 ,0,0,0}, + {20674,20673,20587 ,10186,10185,10067 ,0,0,0}, {20579,20674,20587 ,10059,10186,10067 ,0,0,0}, + {20673,20568,20587 ,10185,10046,10067 ,0,0,0}, {20570,20574,20568 ,10048,10054,10046 ,0,0,0}, + {20675,20676,20677 ,10187,10188,10189 ,0,0,0}, {20678,20679,20676 ,10190,10191,10188 ,0,0,0}, + {20680,20681,20682 ,10192,10193,10194 ,0,0,0}, {20683,20684,20685 ,10195,10196,10197 ,0,0,0}, + {20686,20687,20688 ,10198,10199,10200 ,0,0,0}, {20689,20690,20691 ,10201,10202,10203 ,0,0,0}, + {20692,20693,20694 ,10204,10205,10206 ,0,0,0}, {20695,20696,20697 ,10207,10208,10209 ,0,0,0}, + {20698,20699,20700 ,10210,10211,10212 ,0,0,0}, {20701,20702,20703 ,10213,10214,10215 ,0,0,0}, + {20704,20705,20698 ,10216,10217,10210 ,0,0,0}, {20698,20700,20704 ,10210,10212,10216 ,0,0,0}, + {20705,20706,20707 ,10217,10218,10219 ,0,0,0}, {20706,20705,20704 ,10218,10217,10216 ,0,0,0}, + {20708,20707,20709 ,10220,10219,10221 ,0,0,0}, {20706,20709,20707 ,10218,10221,10219 ,0,0,0}, + {20710,20711,20708 ,10222,10223,10220 ,0,0,0}, {20708,20709,20710 ,10220,10221,10222 ,0,0,0}, + {20712,20711,20710 ,10224,10223,10222 ,0,0,0}, {20699,20703,20700 ,10211,10215,10212 ,0,0,0}, + {20701,20693,20702 ,10213,10205,10214 ,0,0,0}, {20699,20701,20703 ,10211,10213,10215 ,0,0,0}, + {20692,20694,20695 ,10204,10206,10207 ,0,0,0}, {20702,20693,20692 ,10214,10205,10204 ,0,0,0}, + {20697,20696,20688 ,10209,10208,10200 ,0,0,0}, {20695,20694,20696 ,10207,10206,10208 ,0,0,0}, + {20690,20687,20686 ,10202,10199,10198 ,0,0,0}, {20687,20697,20688 ,10199,10209,10200 ,0,0,0}, + {20713,20689,20691 ,10225,10201,10203 ,0,0,0}, {20691,20690,20686 ,10203,10202,10198 ,0,0,0}, + {20680,20713,20681 ,10192,10225,10193 ,0,0,0}, {20713,20680,20689 ,10225,10192,10201 ,0,0,0}, + {20682,20683,20685 ,10194,10195,10197 ,0,0,0}, {20681,20683,20682 ,10193,10195,10194 ,0,0,0}, + {20678,20684,20679 ,10190,10196,10191 ,0,0,0}, {20685,20684,20678 ,10197,10196,10190 ,0,0,0}, + {20677,20714,20675 ,10189,10226,10187 ,0,0,0}, {20676,20679,20677 ,10188,10191,10189 ,0,0,0}, + {20715,20716,20676 ,10227,10228,10229 ,0,0,0}, {20717,20678,20716 ,10230,10231,10228 ,0,0,0}, + {20689,20680,20718 ,10232,10233,10234 ,0,0,0}, {20682,20685,20719 ,10235,10236,10237 ,0,0,0}, + {20687,20720,20697 ,10238,10239,10240 ,0,0,0}, {20721,20722,20690 ,10241,10242,10243 ,0,0,0}, + {20723,20702,20692 ,10244,10245,10246 ,0,0,0}, {20724,20695,20725 ,10247,10248,10249 ,0,0,0}, + {20704,20700,20726 ,10250,10251,10252 ,0,0,0}, {20703,20727,20728 ,10253,10254,10255 ,0,0,0}, + {20729,20706,20704 ,10256,10257,10250 ,0,0,0}, {20704,20726,20729 ,10250,10252,10256 ,0,0,0}, + {20706,20730,20709 ,10257,10258,10259 ,0,0,0}, {20730,20706,20729 ,10258,10257,10256 ,0,0,0}, + {20710,20709,20731 ,10260,10259,10261 ,0,0,0}, {20730,20731,20709 ,10258,10261,10259 ,0,0,0}, + {20732,20712,20710 ,10262,10224,10260 ,0,0,0}, {20710,20731,20732 ,10260,10261,10262 ,0,0,0}, + {20733,20712,20732 ,10263,10224,10262 ,0,0,0}, {20700,20728,20726 ,10251,10255,10252 ,0,0,0}, + {20703,20702,20727 ,10253,10245,10254 ,0,0,0}, {20700,20703,20728 ,10251,10253,10255 ,0,0,0}, + {20723,20692,20724 ,10244,10246,10247 ,0,0,0}, {20727,20702,20723 ,10254,10245,10244 ,0,0,0}, + {20725,20695,20697 ,10249,10248,10240 ,0,0,0}, {20724,20692,20695 ,10247,10246,10248 ,0,0,0}, + {20722,20720,20687 ,10242,10239,10238 ,0,0,0}, {20720,20725,20697 ,10239,10249,10240 ,0,0,0}, + {20689,20721,20690 ,10232,10241,10243 ,0,0,0}, {20690,20722,20687 ,10243,10242,10238 ,0,0,0}, + {20680,20734,20718 ,10233,10264,10234 ,0,0,0}, {20689,20718,20721 ,10232,10234,10241 ,0,0,0}, + {20719,20734,20682 ,10237,10264,10235 ,0,0,0}, {20680,20682,20734 ,10233,10235,10264 ,0,0,0}, + {20717,20685,20678 ,10230,10236,10231 ,0,0,0}, {20719,20685,20717 ,10237,10236,10230 ,0,0,0}, + {20676,20675,20715 ,10229,10187,10227 ,0,0,0}, {20716,20678,20676 ,10228,10231,10229 ,0,0,0}, + {20735,20736,20716 ,10265,10266,10267 ,0,0,0}, {20719,20717,20737 ,10237,10230,10268 ,0,0,0}, + {20721,20718,20738 ,10269,10270,10271 ,0,0,0}, {20734,20739,20740 ,10264,10272,10273 ,0,0,0}, + {20720,20741,20725 ,10274,10275,10276 ,0,0,0}, {20742,20743,20722 ,10277,10278,10279 ,0,0,0}, + {20744,20727,20745 ,10280,10281,10282 ,0,0,0}, {20723,20724,20746 ,10283,10284,10285 ,0,0,0}, + {20729,20726,20747 ,10286,10287,10288 ,0,0,0}, {20728,20748,20726 ,10289,10290,10287 ,0,0,0}, + {20749,20730,20729 ,10291,10292,10286 ,0,0,0}, {20729,20747,20749 ,10286,10288,10291 ,0,0,0}, + {20730,20750,20731 ,10292,10293,10261 ,0,0,0}, {20750,20730,20749 ,10293,10292,10291 ,0,0,0}, + {20732,20731,20751 ,10294,10261,10295 ,0,0,0}, {20750,20751,20731 ,10293,10295,10261 ,0,0,0}, + {20751,20752,20733 ,10295,10296,10263 ,0,0,0}, {20733,20732,20751 ,10263,10294,10295 ,0,0,0}, + {20747,20726,20748 ,10288,10287,10290 ,0,0,0}, {20728,20727,20744 ,10289,10281,10280 ,0,0,0}, + {20728,20744,20748 ,10289,10280,10290 ,0,0,0}, {20745,20723,20746 ,10282,10283,10285 ,0,0,0}, + {20727,20723,20745 ,10281,10283,10282 ,0,0,0}, {20753,20724,20725 ,10297,10284,10276 ,0,0,0}, + {20746,20724,20753 ,10285,10284,10297 ,0,0,0}, {20743,20741,20720 ,10278,10275,10274 ,0,0,0}, + {20741,20753,20725 ,10275,10297,10276 ,0,0,0}, {20721,20742,20722 ,10269,10277,10279 ,0,0,0}, + {20722,20743,20720 ,10279,10278,10274 ,0,0,0}, {20718,20740,20738 ,10270,10273,10271 ,0,0,0}, + {20721,20738,20742 ,10269,10271,10277 ,0,0,0}, {20734,20719,20739 ,10264,10237,10272 ,0,0,0}, + {20718,20734,20740 ,10270,10264,10273 ,0,0,0}, {20737,20717,20736 ,10268,10230,10266 ,0,0,0}, + {20739,20719,20737 ,10272,10237,10268 ,0,0,0}, {20735,20716,20715 ,10265,10267,10227 ,0,0,0}, + {20736,20717,20716 ,10266,10230,10267 ,0,0,0}, {20754,20755,20736 ,10298,10299,10300 ,0,0,0}, + {20739,20737,20756 ,10301,10302,10303 ,0,0,0}, {20742,20738,20757 ,10304,10305,10306 ,0,0,0}, + {20740,20739,20758 ,10307,10301,10308 ,0,0,0}, {20741,20759,20753 ,10309,10310,10311 ,0,0,0}, + {20760,20761,20743 ,10312,10313,10314 ,0,0,0}, {20762,20744,20745 ,10315,10316,10317 ,0,0,0}, + {20763,20746,20764 ,10318,10319,10320 ,0,0,0}, {20765,20747,20766 ,10321,10322,10323 ,0,0,0}, + {20748,20767,20766 ,10324,10325,10323 ,0,0,0}, {20765,20768,20749 ,10321,10326,10327 ,0,0,0}, + {20749,20747,20765 ,10327,10322,10321 ,0,0,0}, {20750,20768,20769 ,10328,10326,10329 ,0,0,0}, + {20768,20750,20749 ,10326,10328,10327 ,0,0,0}, {20770,20751,20769 ,10330,10331,10329 ,0,0,0}, + {20750,20769,20751 ,10328,10329,10331 ,0,0,0}, {20770,20771,20752 ,10330,10332,10296 ,0,0,0}, + {20752,20751,20770 ,10296,10331,10330 ,0,0,0}, {20766,20747,20748 ,10323,10322,10324 ,0,0,0}, + {20767,20744,20762 ,10325,10316,10315 ,0,0,0}, {20748,20744,20767 ,10324,10316,10325 ,0,0,0}, + {20763,20745,20746 ,10318,10317,10319 ,0,0,0}, {20762,20745,20763 ,10315,10317,10318 ,0,0,0}, + {20759,20764,20753 ,10310,10320,10311 ,0,0,0}, {20764,20746,20753 ,10320,10319,10311 ,0,0,0}, + {20743,20761,20741 ,10314,10313,10309 ,0,0,0}, {20761,20759,20741 ,10313,10310,10309 ,0,0,0}, + {20742,20757,20760 ,10304,10306,10312 ,0,0,0}, {20742,20760,20743 ,10304,10312,10314 ,0,0,0}, + {20738,20740,20772 ,10305,10307,10333 ,0,0,0}, {20738,20772,20757 ,10305,10333,10306 ,0,0,0}, + {20758,20739,20756 ,10308,10301,10303 ,0,0,0}, {20772,20740,20758 ,10333,10307,10308 ,0,0,0}, + {20755,20737,20736 ,10299,10302,10300 ,0,0,0}, {20756,20737,20755 ,10303,10302,10299 ,0,0,0}, + {20754,20736,20735 ,10298,10300,10265 ,0,0,0}, {20769,20773,20774 ,10334,10335,10336 ,0,0,0}, + {20771,20770,20775 ,10332,10337,10338 ,0,0,0}, {20776,20766,20777 ,10339,10340,10341 ,0,0,0}, + {20765,20778,20768 ,10342,10343,10344 ,0,0,0}, {20764,20779,20763 ,10345,10346,10347 ,0,0,0}, + {20762,20780,20767 ,10348,10349,10350 ,0,0,0}, {20781,20761,20760 ,10351,10352,10353 ,0,0,0}, + {20782,20759,20783 ,10354,10355,10356 ,0,0,0}, {20784,20772,20785 ,10357,10358,10359 ,0,0,0}, + {20757,20784,20786 ,10360,10357,10361 ,0,0,0}, {20787,20785,20758 ,10362,10359,10363 ,0,0,0}, + {20772,20758,20785 ,10358,10363,10359 ,0,0,0}, {20756,20788,20787 ,10364,10365,10362 ,0,0,0}, + {20787,20758,20756 ,10362,10363,10364 ,0,0,0}, {20788,20755,20789 ,10365,10366,10367 ,0,0,0}, + {20755,20788,20756 ,10366,10365,10364 ,0,0,0}, {20786,20760,20757 ,10361,10353,10360 ,0,0,0}, + {20789,20755,20754 ,10367,10366,10368 ,0,0,0}, {20784,20757,20772 ,10357,10360,10358 ,0,0,0}, + {20781,20783,20761 ,10351,10356,10352 ,0,0,0}, {20786,20781,20760 ,10361,10351,10353 ,0,0,0}, + {20759,20782,20764 ,10355,10354,10345 ,0,0,0}, {20761,20783,20759 ,10352,10356,10355 ,0,0,0}, + {20763,20779,20790 ,10347,10346,10369 ,0,0,0}, {20764,20782,20779 ,10345,10354,10346 ,0,0,0}, + {20790,20780,20762 ,10369,10349,10348 ,0,0,0}, {20762,20763,20790 ,10348,10347,10369 ,0,0,0}, + {20777,20766,20767 ,10341,10340,10350 ,0,0,0}, {20777,20767,20780 ,10341,10350,10349 ,0,0,0}, + {20776,20778,20765 ,10339,10343,10342 ,0,0,0}, {20776,20765,20766 ,10339,10342,10340 ,0,0,0}, + {20768,20773,20769 ,10344,10335,10334 ,0,0,0}, {20778,20773,20768 ,10343,10335,10344 ,0,0,0}, + {20770,20774,20775 ,10337,10336,10338 ,0,0,0}, {20769,20774,20770 ,10334,10336,10337 ,0,0,0}, + {20771,20775,20791 ,10332,10338,10370 ,0,0,0}, {20792,20793,20794 ,10371,10372,10373 ,0,0,0}, + {20795,20796,20797 ,10374,10375,10376 ,0,0,0}, {20796,20798,20799 ,10375,10377,10378 ,0,0,0}, + {20799,20797,20796 ,10378,10376,10375 ,0,0,0}, {20796,20794,20800 ,10375,10373,10379 ,0,0,0}, + {20798,20801,20799 ,10377,10380,10378 ,0,0,0}, {20802,20803,20804 ,10381,10382,10383 ,0,0,0}, + {20754,20793,20789 ,10368,10372,10384 ,0,0,0}, {20805,20806,20807 ,10385,10386,10387 ,0,0,0}, + {20785,20787,20808 ,10388,10389,10390 ,0,0,0}, {20809,20810,20811 ,10391,10392,10393 ,0,0,0}, + {20786,20812,20781 ,10394,10395,10396 ,0,0,0}, {20813,20814,20780 ,10397,10398,10399 ,0,0,0}, + {20815,20816,20811 ,10400,10401,10393 ,0,0,0}, {20817,20818,20819 ,10402,10403,10404 ,0,0,0}, + {20820,20814,20821 ,10405,10398,10406 ,0,0,0}, {20774,20818,20775 ,10407,10403,10408 ,0,0,0}, + {20775,20822,20791 ,10408,10409,10410 ,0,0,0}, {20823,20824,20819 ,10411,10412,10404 ,0,0,0}, + {20775,20818,20822 ,10408,10403,10409 ,0,0,0}, {20825,20817,20826 ,10413,10402,10414 ,0,0,0}, + {20823,20819,20773 ,10411,10404,10415 ,0,0,0}, {20823,20827,20828 ,10411,10416,10417 ,0,0,0}, + {20778,20827,20823 ,10418,10416,10411 ,0,0,0}, {20777,20814,20820 ,10419,10398,10405 ,0,0,0}, + {20827,20820,20829 ,10416,10405,10420 ,0,0,0}, {20827,20776,20820 ,10416,10421,10405 ,0,0,0}, + {20830,20813,20816 ,10422,10397,10401 ,0,0,0}, {20831,20814,20813 ,10423,10398,10397 ,0,0,0}, + {20816,20779,20782 ,10401,10424,10425 ,0,0,0}, {20816,20813,20790 ,10401,10397,10426 ,0,0,0}, + {20781,20809,20783 ,10396,10391,10427 ,0,0,0}, {20783,20811,20782 ,10427,10393,10425 ,0,0,0}, + {20805,20832,20812 ,10385,10428,10395 ,0,0,0}, {20812,20833,20809 ,10395,10429,10391 ,0,0,0}, + {20784,20785,20806 ,10430,10388,10386 ,0,0,0}, {20786,20784,20805 ,10394,10430,10385 ,0,0,0}, + {20803,20834,20808 ,10382,10431,10390 ,0,0,0}, {20807,20806,20834 ,10387,10386,10431 ,0,0,0}, + {20835,20788,20789 ,10432,10433,10384 ,0,0,0}, {20804,20787,20788 ,10383,10389,10433 ,0,0,0}, + {20836,20800,20794 ,10434,10379,10373 ,0,0,0}, {20835,20792,20802 ,10432,10371,10381 ,0,0,0}, + {20794,20793,20836 ,10373,10372,10434 ,0,0,0}, {20798,20796,20800 ,10377,10375,10379 ,0,0,0}, + {20837,20795,20797 ,10435,10374,10376 ,0,0,0}, {20838,20795,20837 ,10436,10374,10435 ,0,0,0}, + {20793,20754,20836 ,10372,10368,10434 ,0,0,0}, {20794,20795,20792 ,10373,10374,10371 ,0,0,0}, + {20789,20793,20835 ,10384,10372,10432 ,0,0,0}, {20796,20795,20794 ,10375,10374,10373 ,0,0,0}, + {20839,20838,20837 ,10437,10436,10435 ,0,0,0}, {20840,20838,20839 ,10438,10436,10437 ,0,0,0}, + {20793,20792,20835 ,10372,10371,10432 ,0,0,0}, {20792,20838,20802 ,10371,10436,10381 ,0,0,0}, + {20788,20835,20804 ,10433,10432,10383 ,0,0,0}, {20795,20838,20792 ,10374,10436,10371 ,0,0,0}, + {20841,20840,20839 ,10439,10438,10437 ,0,0,0}, {20842,20840,20841 ,10440,10438,10439 ,0,0,0}, + {20835,20802,20804 ,10432,10381,10383 ,0,0,0}, {20802,20840,20803 ,10381,10438,10382 ,0,0,0}, + {20787,20804,20808 ,10389,10383,10390 ,0,0,0}, {20838,20840,20802 ,10436,10438,10381 ,0,0,0}, + {20843,20842,20841 ,10441,10440,10439 ,0,0,0}, {20844,20842,20843 ,10442,10440,10441 ,0,0,0}, + {20804,20803,20808 ,10383,10382,10390 ,0,0,0}, {20803,20842,20834 ,10382,10440,10431 ,0,0,0}, + {20785,20808,20806 ,10388,10390,10386 ,0,0,0}, {20840,20842,20803 ,10438,10440,10382 ,0,0,0}, + {20845,20844,20843 ,10443,10442,10441 ,0,0,0}, {20846,20844,20845 ,10444,10442,10443 ,0,0,0}, + {20808,20834,20806 ,10390,10431,10386 ,0,0,0}, {20834,20844,20807 ,10431,10442,10387 ,0,0,0}, + {20784,20806,20805 ,10430,10386,10385 ,0,0,0}, {20842,20844,20834 ,10440,10442,10431 ,0,0,0}, + {20847,20846,20845 ,10445,10444,10443 ,0,0,0}, {20848,20849,20826 ,10446,10447,10414 ,0,0,0}, + {20850,20846,20847 ,10448,10444,10445 ,0,0,0}, {20807,20846,20832 ,10387,10444,10428 ,0,0,0}, + {20786,20805,20812 ,10394,10385,10395 ,0,0,0}, {20844,20846,20807 ,10442,10444,10387 ,0,0,0}, + {20851,20850,20847 ,10449,10448,10445 ,0,0,0}, {20852,20853,20850 ,10450,10451,10448 ,0,0,0}, + {20807,20832,20805 ,10387,10428,10385 ,0,0,0}, {20832,20850,20833 ,10428,10448,10429 ,0,0,0}, + {20781,20812,20809 ,10396,10395,10391 ,0,0,0}, {20846,20850,20832 ,10444,10448,10428 ,0,0,0}, + {20851,20852,20850 ,10449,10450,10448 ,0,0,0}, {20854,20855,20853 ,10452,10453,10451 ,0,0,0}, + {20832,20833,20812 ,10428,10429,10395 ,0,0,0}, {20833,20853,20810 ,10429,10451,10392 ,0,0,0}, + {20783,20809,20811 ,10427,10391,10393 ,0,0,0}, {20850,20853,20833 ,10448,10451,10429 ,0,0,0}, + {20852,20854,20853 ,10450,10452,10451 ,0,0,0}, {20856,20857,20855 ,10454,10455,10453 ,0,0,0}, + {20833,20810,20809 ,10429,10392,10391 ,0,0,0}, {20855,20815,20810 ,10453,10400,10392 ,0,0,0}, + {20782,20811,20816 ,10425,10393,10401 ,0,0,0}, {20853,20855,20810 ,10451,10453,10392 ,0,0,0}, + {20854,20856,20855 ,10452,10454,10453 ,0,0,0}, {20857,20858,20859 ,10455,10456,10457 ,0,0,0}, + {20810,20815,20811 ,10392,10400,10393 ,0,0,0}, {20857,20830,20815 ,10455,10422,10400 ,0,0,0}, + {20790,20779,20816 ,10426,10424,10401 ,0,0,0}, {20855,20857,20815 ,10453,10455,10400 ,0,0,0}, + {20856,20858,20857 ,10454,10456,10455 ,0,0,0}, {20859,20860,20861 ,10457,10458,10459 ,0,0,0}, + {20815,20830,20816 ,10400,10422,10401 ,0,0,0}, {20859,20831,20830 ,10457,10423,10422 ,0,0,0}, + {20780,20790,20813 ,10399,10426,10397 ,0,0,0}, {20857,20859,20830 ,10455,10457,10422 ,0,0,0}, + {20858,20860,20859 ,10456,10458,10457 ,0,0,0}, {20861,20862,20863 ,10459,10460,10461 ,0,0,0}, + {20830,20831,20813 ,10422,10423,10397 ,0,0,0}, {20861,20821,20831 ,10459,10406,10423 ,0,0,0}, + {20777,20780,20814 ,10419,10399,10398 ,0,0,0}, {20859,20861,20831 ,10457,10459,10423 ,0,0,0}, + {20860,20862,20861 ,10458,10460,10459 ,0,0,0}, {20863,20864,20865 ,10461,10462,10463 ,0,0,0}, + {20831,20821,20814 ,10423,10406,10398 ,0,0,0}, {20863,20829,20821 ,10461,10420,10406 ,0,0,0}, + {20776,20777,20820 ,10421,10419,10405 ,0,0,0}, {20861,20863,20821 ,10459,10461,10406 ,0,0,0}, + {20862,20864,20863 ,10460,10462,10461 ,0,0,0}, {20865,20866,20867 ,10463,10464,10465 ,0,0,0}, + {20821,20829,20820 ,10406,10420,10405 ,0,0,0}, {20865,20828,20829 ,10463,10417,10420 ,0,0,0}, + {20778,20776,20827 ,10418,10421,10416 ,0,0,0}, {20863,20865,20829 ,10461,10463,10420 ,0,0,0}, + {20864,20866,20865 ,10462,10464,10463 ,0,0,0}, {20826,20867,20848 ,10414,10465,10446 ,0,0,0}, + {20829,20828,20827 ,10420,10417,10416 ,0,0,0}, {20828,20867,20824 ,10417,10465,10412 ,0,0,0}, + {20773,20778,20823 ,10415,10418,10411 ,0,0,0}, {20865,20867,20828 ,10463,10465,10417 ,0,0,0}, + {20866,20848,20867 ,10464,10446,10465 ,0,0,0}, {20774,20819,20818 ,10407,10404,10403 ,0,0,0}, + {20828,20824,20823 ,10417,10412,10411 ,0,0,0}, {20826,20817,20824 ,10414,10402,10412 ,0,0,0}, + {20774,20773,20819 ,10407,10415,10404 ,0,0,0}, {20826,20824,20867 ,10414,10412,10465 ,0,0,0}, + {20849,20825,20826 ,10447,10413,10414 ,0,0,0}, {20868,20817,20825 ,10466,10402,10413 ,0,0,0}, + {20824,20817,20819 ,10412,10402,10404 ,0,0,0}, {20817,20868,20818 ,10402,10466,10403 ,0,0,0}, + {20822,20818,20868 ,10409,10403,10466 ,0,0,0}, {20869,20870,20799 ,10467,10468,10469 ,0,0,0}, + {20837,20797,20871 ,10470,10471,10472 ,0,0,0}, {20843,20841,20872 ,10473,10474,10475 ,0,0,0}, + {20839,20873,20874 ,10476,10477,10478 ,0,0,0}, {20875,20876,20851 ,10479,10480,10481 ,0,0,0}, + {20877,20878,20845 ,10482,10483,10484 ,0,0,0}, {20879,20856,20880 ,10485,10486,10487 ,0,0,0}, + {20854,20852,20881 ,10488,10489,10490 ,0,0,0}, {20862,20860,20882 ,10491,10492,10493 ,0,0,0}, + {20858,20883,20860 ,10494,10495,10492 ,0,0,0}, {20884,20864,20862 ,10496,10497,10491 ,0,0,0}, + {20862,20882,20884 ,10491,10493,10496 ,0,0,0}, {20864,20885,20866 ,10497,10498,10499 ,0,0,0}, + {20885,20864,20884 ,10498,10497,10496 ,0,0,0}, {20848,20866,20886 ,10500,10499,10501 ,0,0,0}, + {20885,20886,20866 ,10498,10501,10499 ,0,0,0}, {20886,20887,20849 ,10501,10502,10447 ,0,0,0}, + {20849,20848,20886 ,10447,10500,10501 ,0,0,0}, {20882,20860,20883 ,10493,10492,10495 ,0,0,0}, + {20858,20856,20879 ,10494,10486,10485 ,0,0,0}, {20858,20879,20883 ,10494,10485,10495 ,0,0,0}, + {20880,20854,20881 ,10487,10488,10490 ,0,0,0}, {20856,20854,20880 ,10486,10488,10487 ,0,0,0}, + {20876,20852,20851 ,10480,10489,10481 ,0,0,0}, {20881,20852,20876 ,10490,10489,10480 ,0,0,0}, + {20878,20875,20847 ,10483,10479,10503 ,0,0,0}, {20875,20851,20847 ,10479,10481,10503 ,0,0,0}, + {20843,20877,20845 ,10473,10482,10484 ,0,0,0}, {20845,20878,20847 ,10484,10483,10503 ,0,0,0}, + {20841,20874,20872 ,10474,10478,10475 ,0,0,0}, {20843,20872,20877 ,10473,10475,10482 ,0,0,0}, + {20839,20837,20873 ,10476,10470,10477 ,0,0,0}, {20841,20839,20874 ,10474,10476,10478 ,0,0,0}, + {20871,20797,20870 ,10472,10471,10468 ,0,0,0}, {20873,20837,20871 ,10477,10470,10472 ,0,0,0}, + {20869,20799,20801 ,10467,10469,10504 ,0,0,0}, {20870,20797,20799 ,10468,10471,10469 ,0,0,0}, + {20888,20889,20870 ,10505,10506,10507 ,0,0,0}, {20871,20870,20890 ,10508,10507,10509 ,0,0,0}, + {20872,20874,20891 ,10510,10511,10512 ,0,0,0}, {20873,20892,20893 ,10513,10514,10515 ,0,0,0}, + {20878,20894,20875 ,10516,10517,10518 ,0,0,0}, {20895,20896,20877 ,10519,10520,10521 ,0,0,0}, + {20897,20880,20881 ,10522,10523,10524 ,0,0,0}, {20898,20876,20899 ,10525,10526,10527 ,0,0,0}, + {20882,20883,20900 ,10528,10529,10530 ,0,0,0}, {20879,20901,20902 ,10531,10532,10533 ,0,0,0}, + {20903,20884,20882 ,10534,10535,10528 ,0,0,0}, {20882,20900,20903 ,10528,10530,10534 ,0,0,0}, + {20884,20904,20885 ,10535,10536,10537 ,0,0,0}, {20904,20884,20903 ,10536,10535,10534 ,0,0,0}, + {20886,20885,20905 ,10538,10537,10539 ,0,0,0}, {20904,20905,20885 ,10536,10539,10537 ,0,0,0}, + {20906,20887,20886 ,10540,10502,10538 ,0,0,0}, {20886,20905,20906 ,10538,10539,10540 ,0,0,0}, + {20907,20887,20906 ,10541,10502,10540 ,0,0,0}, {20883,20902,20900 ,10529,10533,10530 ,0,0,0}, + {20879,20880,20901 ,10531,10523,10532 ,0,0,0}, {20883,20879,20902 ,10529,10531,10533 ,0,0,0}, + {20897,20881,20898 ,10522,10524,10525 ,0,0,0}, {20901,20880,20897 ,10532,10523,10522 ,0,0,0}, + {20899,20876,20875 ,10527,10526,10518 ,0,0,0}, {20898,20881,20876 ,10525,10524,10526 ,0,0,0}, + {20896,20894,20878 ,10520,10517,10516 ,0,0,0}, {20894,20899,20875 ,10517,10527,10518 ,0,0,0}, + {20872,20895,20877 ,10510,10519,10521 ,0,0,0}, {20877,20896,20878 ,10521,10520,10516 ,0,0,0}, + {20874,20893,20891 ,10511,10515,10512 ,0,0,0}, {20872,20891,20895 ,10510,10512,10519 ,0,0,0}, + {20873,20871,20892 ,10513,10508,10514 ,0,0,0}, {20874,20873,20893 ,10511,10513,10515 ,0,0,0}, + {20890,20870,20889 ,10509,10507,10506 ,0,0,0}, {20892,20871,20890 ,10514,10508,10509 ,0,0,0}, + {20888,20870,20869 ,10505,10507,10467 ,0,0,0}, {20908,20909,20889 ,10542,10543,10544 ,0,0,0}, + {20910,20890,20909 ,10545,10509,10543 ,0,0,0}, {20895,20891,20911 ,10546,10547,10548 ,0,0,0}, + {20893,20892,20912 ,10515,10514,10549 ,0,0,0}, {20894,20913,20899 ,10550,10551,10552 ,0,0,0}, + {20914,20915,20896 ,10553,10554,10555 ,0,0,0}, {20916,20901,20897 ,10556,10557,10558 ,0,0,0}, + {20917,20898,20918 ,10559,10560,10561 ,0,0,0}, {20903,20900,20919 ,10534,10530,10562 ,0,0,0}, + {20902,20920,20921 ,10563,10564,10565 ,0,0,0}, {20922,20904,20903 ,10566,10536,10534 ,0,0,0}, + {20903,20919,20922 ,10534,10562,10566 ,0,0,0}, {20904,20923,20905 ,10536,10567,10539 ,0,0,0}, + {20923,20904,20922 ,10567,10536,10566 ,0,0,0}, {20906,20905,20924 ,10568,10539,10569 ,0,0,0}, + {20923,20924,20905 ,10567,10569,10539 ,0,0,0}, {20925,20907,20906 ,10570,10541,10568 ,0,0,0}, + {20906,20924,20925 ,10568,10569,10570 ,0,0,0}, {20926,20907,20925 ,10571,10541,10570 ,0,0,0}, + {20900,20921,20919 ,10530,10565,10562 ,0,0,0}, {20902,20901,20920 ,10563,10557,10564 ,0,0,0}, + {20900,20902,20921 ,10530,10563,10565 ,0,0,0}, {20916,20897,20917 ,10556,10558,10559 ,0,0,0}, + {20920,20901,20916 ,10564,10557,10556 ,0,0,0}, {20918,20898,20899 ,10561,10560,10552 ,0,0,0}, + {20917,20897,20898 ,10559,10558,10560 ,0,0,0}, {20915,20913,20894 ,10554,10551,10550 ,0,0,0}, + {20913,20918,20899 ,10551,10561,10552 ,0,0,0}, {20895,20914,20896 ,10546,10553,10555 ,0,0,0}, + {20896,20915,20894 ,10555,10554,10550 ,0,0,0}, {20891,20927,20911 ,10547,10572,10548 ,0,0,0}, + {20895,20911,20914 ,10546,10548,10553 ,0,0,0}, {20912,20927,20893 ,10549,10572,10515 ,0,0,0}, + {20891,20893,20927 ,10547,10515,10572 ,0,0,0}, {20910,20892,20890 ,10545,10514,10509 ,0,0,0}, + {20912,20892,20910 ,10549,10514,10545 ,0,0,0}, {20889,20888,20908 ,10544,10505,10542 ,0,0,0}, + {20909,20890,20889 ,10543,10509,10544 ,0,0,0}, {20928,20929,20909 ,10573,10574,10575 ,0,0,0}, + {20930,20910,20929 ,10576,10577,10574 ,0,0,0}, {20914,20911,20931 ,10578,10579,10580 ,0,0,0}, + {20927,20912,20932 ,10581,10582,10583 ,0,0,0}, {20913,20933,20918 ,10584,10585,10586 ,0,0,0}, + {20934,20935,20915 ,10587,10588,10589 ,0,0,0}, {20936,20920,20916 ,10590,10591,10592 ,0,0,0}, + {20937,20917,20938 ,10593,10594,10595 ,0,0,0}, {20939,20919,20940 ,10596,10597,10598 ,0,0,0}, + {20921,20920,20941 ,10599,10591,10600 ,0,0,0}, {20942,20923,20922 ,10601,10602,10603 ,0,0,0}, + {20922,20939,20942 ,10603,10596,10601 ,0,0,0}, {20923,20943,20924 ,10602,10604,10605 ,0,0,0}, + {20943,20923,20942 ,10604,10602,10601 ,0,0,0}, {20925,20924,20944 ,10606,10605,10607 ,0,0,0}, + {20943,20944,20924 ,10604,10607,10605 ,0,0,0}, {20945,20926,20925 ,10608,10571,10606 ,0,0,0}, + {20925,20944,20945 ,10606,10607,10608 ,0,0,0}, {20946,20926,20945 ,10609,10571,10608 ,0,0,0}, + {20939,20922,20919 ,10596,10603,10597 ,0,0,0}, {20940,20921,20941 ,10598,10599,10600 ,0,0,0}, + {20919,20921,20940 ,10597,10599,10598 ,0,0,0}, {20916,20937,20936 ,10592,10593,10590 ,0,0,0}, + {20941,20920,20936 ,10600,10591,10590 ,0,0,0}, {20938,20917,20918 ,10595,10594,10586 ,0,0,0}, + {20937,20916,20917 ,10593,10592,10594 ,0,0,0}, {20935,20933,20913 ,10588,10585,10584 ,0,0,0}, + {20933,20938,20918 ,10585,10595,10586 ,0,0,0}, {20914,20934,20915 ,10578,10587,10589 ,0,0,0}, + {20915,20935,20913 ,10589,10588,10584 ,0,0,0}, {20911,20947,20931 ,10579,10610,10580 ,0,0,0}, + {20914,20931,20934 ,10578,10580,10587 ,0,0,0}, {20932,20947,20927 ,10583,10610,10581 ,0,0,0}, + {20911,20927,20947 ,10579,10581,10610 ,0,0,0}, {20930,20912,20910 ,10576,10582,10577 ,0,0,0}, + {20932,20912,20930 ,10583,10582,10576 ,0,0,0}, {20909,20908,20928 ,10575,10542,10573 ,0,0,0}, + {20929,20910,20909 ,10574,10577,10575 ,0,0,0}, {20948,20928,20949 ,10611,10573,10612 ,0,0,0}, + {20950,20932,20951 ,10613,10614,10615 ,0,0,0}, {20952,20930,20929 ,10616,10617,10618 ,0,0,0}, + {20934,20953,20935 ,10619,10620,10621 ,0,0,0}, {20947,20954,20931 ,10622,10623,10624 ,0,0,0}, + {20955,20937,20938 ,10625,10626,10627 ,0,0,0}, {20956,20933,20957 ,10628,10629,10630 ,0,0,0}, + {20958,20941,20959 ,10631,10632,10633 ,0,0,0}, {20936,20960,20959 ,10634,10635,10633 ,0,0,0}, + {20942,20939,20961 ,10636,10637,10638 ,0,0,0}, {20940,20962,20939 ,10639,10640,10637 ,0,0,0}, + {20963,20943,20942 ,10641,10642,10636 ,0,0,0}, {20942,20961,20963 ,10636,10638,10641 ,0,0,0}, + {20943,20964,20944 ,10642,10643,10644 ,0,0,0}, {20964,20943,20963 ,10643,10642,10641 ,0,0,0}, + {20945,20944,20965 ,10645,10644,10646 ,0,0,0}, {20964,20965,20944 ,10643,10646,10644 ,0,0,0}, + {20966,20946,20945 ,10647,10609,10645 ,0,0,0}, {20945,20965,20966 ,10645,10646,10647 ,0,0,0}, + {20958,20962,20940 ,10631,10640,10639 ,0,0,0}, {20939,20962,20961 ,10637,10640,10638 ,0,0,0}, + {20941,20936,20959 ,10632,10634,10633 ,0,0,0}, {20940,20941,20958 ,10639,10632,10631 ,0,0,0}, + {20960,20937,20955 ,10635,10626,10625 ,0,0,0}, {20936,20937,20960 ,10634,10626,10635 ,0,0,0}, + {20956,20938,20933 ,10628,10627,10629 ,0,0,0}, {20955,20938,20956 ,10625,10627,10628 ,0,0,0}, + {20953,20957,20935 ,10620,10630,10621 ,0,0,0}, {20957,20933,20935 ,10630,10629,10621 ,0,0,0}, + {20931,20967,20934 ,10624,10648,10619 ,0,0,0}, {20967,20953,20934 ,10648,10620,10619 ,0,0,0}, + {20947,20950,20954 ,10622,10613,10623 ,0,0,0}, {20931,20954,20967 ,10624,10623,10648 ,0,0,0}, + {20932,20930,20951 ,10614,10617,10615 ,0,0,0}, {20947,20932,20950 ,10622,10614,10613 ,0,0,0}, + {20952,20929,20948 ,10616,10618,10611 ,0,0,0}, {20951,20930,20952 ,10615,10617,10616 ,0,0,0}, + {20928,20948,20929 ,10573,10611,10618 ,0,0,0}, {20955,20956,20968 ,10649,10650,10651 ,0,0,0}, + {20969,20956,20957 ,10652,10650,10653 ,0,0,0}, {20956,20969,20968 ,10650,10652,10651 ,0,0,0}, + {20953,20970,20957 ,10654,10655,10653 ,0,0,0}, {20969,20957,20970 ,10652,10653,10655 ,0,0,0}, + {20953,20967,20971 ,10654,10656,10657 ,0,0,0}, {20971,20970,20953 ,10657,10655,10654 ,0,0,0}, + {20972,20967,20954 ,10658,10656,10659 ,0,0,0}, {20967,20972,20971 ,10656,10658,10657 ,0,0,0}, + {20950,20973,20954 ,10660,10661,10659 ,0,0,0}, {20972,20954,20973 ,10658,10659,10661 ,0,0,0}, + {20950,20951,20974 ,10660,10662,10663 ,0,0,0}, {20974,20973,20950 ,10663,10661,10660 ,0,0,0}, + {20975,20951,20952 ,10664,10662,10665 ,0,0,0}, {20951,20975,20974 ,10662,10664,10663 ,0,0,0}, + {20948,20976,20952 ,10666,10667,10665 ,0,0,0}, {20975,20952,20976 ,10664,10665,10667 ,0,0,0}, + {20949,20977,20976 ,10668,10669,10667 ,0,0,0}, {20976,20948,20949 ,10667,10666,10668 ,0,0,0}, + {20955,20968,20978 ,10649,10651,10670 ,0,0,0}, {20978,20979,20960 ,10670,10671,10672 ,0,0,0}, + {20960,20955,20978 ,10672,10649,10670 ,0,0,0}, {20959,20979,20980 ,10673,10671,10674 ,0,0,0}, + {20979,20959,20960 ,10671,10673,10672 ,0,0,0}, {20981,20958,20980 ,10675,10676,10674 ,0,0,0}, + {20959,20980,20958 ,10673,10674,10676 ,0,0,0}, {20981,20982,20962 ,10675,10677,10678 ,0,0,0}, + {20962,20958,20981 ,10678,10676,10675 ,0,0,0}, {20961,20982,20983 ,10679,10677,10680 ,0,0,0}, + {20982,20961,20962 ,10677,10679,10678 ,0,0,0}, {20984,20963,20983 ,10681,10682,10680 ,0,0,0}, + {20961,20983,20963 ,10679,10680,10682 ,0,0,0}, {20984,20985,20964 ,10681,10683,10684 ,0,0,0}, + {20964,20963,20984 ,10684,10682,10681 ,0,0,0}, {20965,20985,20986 ,10685,10683,10686 ,0,0,0}, + {20985,20965,20964 ,10683,10685,10684 ,0,0,0}, {20965,20986,20966 ,10685,10686,10687 ,0,0,0}, + {20987,20977,20988 ,10688,10689,10690 ,0,0,0}, {20989,20973,20990 ,10691,10692,10693 ,0,0,0}, + {20987,20991,20975 ,10688,10694,10695 ,0,0,0}, {20970,20992,20993 ,10696,10697,10698 ,0,0,0}, + {20972,20994,20971 ,10699,10700,10701 ,0,0,0}, {20995,20996,20978 ,10702,10703,10704 ,0,0,0}, + {20997,20968,20969 ,10705,10706,10707 ,0,0,0}, {20998,20981,20999 ,10708,10709,10710 ,0,0,0}, + {20980,20979,21000 ,10711,10712,10713 ,0,0,0}, {21001,20983,20982 ,10714,10715,10716 ,0,0,0}, + {20982,20998,21001 ,10716,10708,10714 ,0,0,0}, {20983,21002,20984 ,10715,10717,10718 ,0,0,0}, + {21002,20983,21001 ,10717,10715,10714 ,0,0,0}, {20985,20984,21003 ,10719,10718,10720 ,0,0,0}, + {21002,21003,20984 ,10717,10720,10718 ,0,0,0}, {21004,20986,20985 ,10721,10686,10719 ,0,0,0}, + {20985,21003,21004 ,10719,10720,10721 ,0,0,0}, {20981,20980,20999 ,10709,10711,10710 ,0,0,0}, + {20982,20981,20998 ,10716,10709,10708 ,0,0,0}, {21000,20979,20996 ,10713,10712,10703 ,0,0,0}, + {20999,20980,21000 ,10710,10711,10713 ,0,0,0}, {20995,20978,20968 ,10702,10704,10706 ,0,0,0}, + {20996,20979,20978 ,10703,10712,10704 ,0,0,0}, {20993,20997,20969 ,10698,10705,10707 ,0,0,0}, + {20997,20995,20968 ,10705,10702,10706 ,0,0,0}, {20971,20992,20970 ,10701,10697,10696 ,0,0,0}, + {20970,20993,20969 ,10696,10698,10707 ,0,0,0}, {20972,20989,20994 ,10699,10691,10700 ,0,0,0}, + {20971,20994,20992 ,10701,10700,10697 ,0,0,0}, {20973,20974,20990 ,10692,10722,10693 ,0,0,0}, + {20972,20973,20989 ,10699,10692,10691 ,0,0,0}, {20975,20991,20974 ,10695,10694,10722 ,0,0,0}, + {20990,20974,20991 ,10693,10722,10694 ,0,0,0}, {20987,20976,20977 ,10688,10723,10689 ,0,0,0}, + {20987,20975,20976 ,10688,10695,10723 ,0,0,0}, {21005,20988,21006 ,10724,10725,10726 ,0,0,0}, + {21007,20990,21008 ,10727,10728,10729 ,0,0,0}, {21009,20991,20987 ,10730,10731,10732 ,0,0,0}, + {20992,21010,20993 ,10733,10734,10735 ,0,0,0}, {20989,21011,20994 ,10736,10737,10738 ,0,0,0}, + {21012,21013,20995 ,10739,10740,10741 ,0,0,0}, {21012,20997,21014 ,10739,10742,10743 ,0,0,0}, + {21015,20999,21016 ,10744,10745,10746 ,0,0,0}, {21000,20996,21017 ,10747,10748,10749 ,0,0,0}, + {21018,21001,20998 ,10750,10751,10752 ,0,0,0}, {20998,21015,21018 ,10752,10744,10750 ,0,0,0}, + {21001,21019,21002 ,10751,10753,10754 ,0,0,0}, {21019,21001,21018 ,10753,10751,10750 ,0,0,0}, + {21003,21002,21020 ,10755,10754,10756 ,0,0,0}, {21019,21020,21002 ,10753,10756,10754 ,0,0,0}, + {21021,21004,21003 ,10757,10758,10755 ,0,0,0}, {21003,21020,21021 ,10755,10756,10757 ,0,0,0}, + {20999,21000,21016 ,10745,10747,10746 ,0,0,0}, {20998,20999,21015 ,10752,10745,10744 ,0,0,0}, + {21017,20996,21013 ,10749,10748,10740 ,0,0,0}, {21016,21000,21017 ,10746,10747,10749 ,0,0,0}, + {21012,20995,20997 ,10739,10741,10742 ,0,0,0}, {21013,20996,20995 ,10740,10748,10741 ,0,0,0}, + {21010,21014,20993 ,10734,10743,10735 ,0,0,0}, {21014,20997,20993 ,10743,10742,10735 ,0,0,0}, + {20994,21022,20992 ,10738,10759,10733 ,0,0,0}, {21022,21010,20992 ,10759,10734,10733 ,0,0,0}, + {20989,21007,21011 ,10736,10727,10737 ,0,0,0}, {20994,21011,21022 ,10738,10737,10759 ,0,0,0}, + {20990,20991,21008 ,10728,10731,10729 ,0,0,0}, {20989,20990,21007 ,10736,10728,10727 ,0,0,0}, + {21009,20987,21005 ,10730,10732,10724 ,0,0,0}, {21008,20991,21009 ,10729,10731,10730 ,0,0,0}, + {20988,21005,20987 ,10725,10724,10732 ,0,0,0}, {21023,21006,21024 ,10760,10761,10762 ,0,0,0}, + {21025,21008,21026 ,10763,10764,10765 ,0,0,0}, {21027,21009,21005 ,10766,10767,10768 ,0,0,0}, + {21022,21028,21029 ,10769,10770,10771 ,0,0,0}, {21007,21030,21011 ,10772,10773,10774 ,0,0,0}, + {21031,21032,21012 ,10775,10776,10777 ,0,0,0}, {21031,21014,21033 ,10775,10778,10779 ,0,0,0}, + {21034,21016,21035 ,10780,10781,10782 ,0,0,0}, {21017,21013,21036 ,10783,10784,10785 ,0,0,0}, + {21037,21018,21015 ,10786,10787,10788 ,0,0,0}, {21015,21034,21037 ,10788,10780,10786 ,0,0,0}, + {21018,21038,21019 ,10787,10789,10790 ,0,0,0}, {21038,21018,21037 ,10789,10787,10786 ,0,0,0}, + {21020,21019,21039 ,10791,10790,10792 ,0,0,0}, {21038,21039,21019 ,10789,10792,10790 ,0,0,0}, + {21040,21021,21020 ,10793,10794,10791 ,0,0,0}, {21020,21039,21040 ,10791,10792,10793 ,0,0,0}, + {21016,21017,21035 ,10781,10783,10782 ,0,0,0}, {21015,21016,21034 ,10788,10781,10780 ,0,0,0}, + {21036,21013,21032 ,10785,10784,10776 ,0,0,0}, {21035,21017,21036 ,10782,10783,10785 ,0,0,0}, + {21031,21012,21014 ,10775,10777,10778 ,0,0,0}, {21032,21013,21012 ,10776,10784,10777 ,0,0,0}, + {21029,21033,21010 ,10771,10779,10795 ,0,0,0}, {21033,21014,21010 ,10779,10778,10795 ,0,0,0}, + {21011,21028,21022 ,10774,10770,10769 ,0,0,0}, {21022,21029,21010 ,10769,10771,10795 ,0,0,0}, + {21007,21025,21030 ,10772,10763,10773 ,0,0,0}, {21011,21030,21028 ,10774,10773,10770 ,0,0,0}, + {21008,21009,21026 ,10764,10767,10765 ,0,0,0}, {21007,21008,21025 ,10772,10764,10763 ,0,0,0}, + {21027,21005,21023 ,10766,10768,10760 ,0,0,0}, {21026,21009,21027 ,10765,10767,10766 ,0,0,0}, + {21006,21023,21005 ,10761,10760,10768 ,0,0,0}, {20611,21024,20609 ,10796,10797,10798 ,0,0,0}, + {20612,21026,20613 ,10799,10800,10801 ,0,0,0}, {20623,21027,21023 ,10802,10803,10804 ,0,0,0}, + {21028,20636,20637 ,10805,10806,10807 ,0,0,0}, {21025,20624,21030 ,10808,10809,10810 ,0,0,0}, + {20639,20640,21031 ,10811,10812,10813 ,0,0,0}, {20638,21033,21029 ,10814,10815,10816 ,0,0,0}, + {20669,21035,21036 ,10817,10818,10819 ,0,0,0}, {20666,21032,20640 ,10820,10821,10812 ,0,0,0}, + {20670,21037,21034 ,10822,10823,10824 ,0,0,0}, {21034,20668,20670 ,10824,10825,10822 ,0,0,0}, + {21037,20671,21038 ,10823,10826,10827 ,0,0,0}, {20671,21037,20670 ,10826,10823,10822 ,0,0,0}, + {21038,20573,20570 ,10827,10828,10829 ,0,0,0}, {20671,20573,21038 ,10826,10828,10827 ,0,0,0}, + {20569,21039,20570 ,10047,10830,10829 ,0,0,0}, {21038,20570,21039 ,10827,10829,10830 ,0,0,0}, + {21040,21039,20569 ,10793,10830,10047 ,0,0,0}, {20668,21035,20669 ,10825,10818,10817 ,0,0,0}, + {21034,21035,20668 ,10824,10818,10825 ,0,0,0}, {20666,21036,21032 ,10820,10819,10821 ,0,0,0}, + {20669,21036,20666 ,10817,10819,10820 ,0,0,0}, {21031,21033,20639 ,10813,10815,10811 ,0,0,0}, + {20640,21032,21031 ,10812,10821,10813 ,0,0,0}, {20637,20638,21029 ,10807,10814,10816 ,0,0,0}, + {20638,20639,21033 ,10814,10811,10815 ,0,0,0}, {21030,20636,21028 ,10810,10806,10805 ,0,0,0}, + {21028,20637,21029 ,10805,10807,10816 ,0,0,0}, {21025,20612,20624 ,10808,10799,10809 ,0,0,0}, + {21030,20624,20636 ,10810,10809,10806 ,0,0,0}, {21026,21027,20613 ,10800,10803,10801 ,0,0,0}, + {21025,21026,20612 ,10808,10800,10799 ,0,0,0}, {20623,21023,20611 ,10802,10804,10796 ,0,0,0}, + {20613,21027,20623 ,10801,10803,10802 ,0,0,0}, {21024,20611,21023 ,10797,10796,10804 ,0,0,0}, + {21041,20549,21042 ,10831,10024,10832 ,0,0,0}, {21043,20659,20606 ,10833,10834,10835 ,0,0,0}, + {21044,20621,20547 ,10836,10837,10838 ,0,0,0}, {20664,21045,21046 ,10839,10840,10841 ,0,0,0}, + {20660,21047,20661 ,10842,10843,10844 ,0,0,0}, {21048,21049,20629 ,10845,10846,10847 ,0,0,0}, + {21050,20632,20633 ,10848,10849,10850 ,0,0,0}, {21051,20667,21052 ,10851,10852,10853 ,0,0,0}, + {20665,20630,21053 ,10854,10855,10856 ,0,0,0}, {21054,20644,20589 ,10857,10858,10859 ,0,0,0}, + {20589,21051,21054 ,10859,10851,10857 ,0,0,0}, {20644,21055,20672 ,10858,10860,10861 ,0,0,0}, + {21055,20644,21054 ,10860,10858,10857 ,0,0,0}, {20580,20672,21056 ,10862,10861,10863 ,0,0,0}, + {21055,21056,20672 ,10860,10863,10861 ,0,0,0}, {21057,20583,20580 ,10864,10865,10862 ,0,0,0}, + {20580,21056,21057 ,10862,10863,10864 ,0,0,0}, {20667,20665,21052 ,10852,10854,10853 ,0,0,0}, + {20589,20667,21051 ,10859,10852,10851 ,0,0,0}, {21053,20630,21049 ,10856,10855,10846 ,0,0,0}, + {21052,20665,21053 ,10853,10854,10856 ,0,0,0}, {21048,20629,20632 ,10845,10847,10849 ,0,0,0}, + {21049,20630,20629 ,10846,10855,10847 ,0,0,0}, {21046,21050,20633 ,10841,10848,10850 ,0,0,0}, + {21050,21048,20632 ,10848,10845,10849 ,0,0,0}, {20661,21045,20664 ,10844,10840,10839 ,0,0,0}, + {20664,21046,20633 ,10839,10841,10850 ,0,0,0}, {20660,21058,21047 ,10842,10866,10843 ,0,0,0}, + {20661,21047,21045 ,10844,10843,10840 ,0,0,0}, {21043,21058,20659 ,10833,10866,10834 ,0,0,0}, + {20660,20659,21058 ,10842,10834,10866 ,0,0,0}, {21044,20606,20621 ,10836,10835,10837 ,0,0,0}, + {21043,20606,21044 ,10833,10835,10836 ,0,0,0}, {21041,20547,20549 ,10831,10838,10024 ,0,0,0}, + {21044,20547,21041 ,10836,10838,10831 ,0,0,0}, {21059,21042,21060 ,10867,10832,10868 ,0,0,0}, + {21061,21043,21062 ,10869,10870,10871 ,0,0,0}, {21063,21044,21041 ,10872,10873,10874 ,0,0,0}, + {21045,21064,21065 ,10875,10876,10877 ,0,0,0}, {21058,21066,21047 ,10878,10879,10880 ,0,0,0}, + {21067,21049,21048 ,10881,10882,10883 ,0,0,0}, {21068,21050,21069 ,10884,10885,10886 ,0,0,0}, + {21070,21052,21071 ,10887,10888,10889 ,0,0,0}, {21053,21049,21072 ,10890,10882,10891 ,0,0,0}, + {21073,21054,21051 ,10892,10893,10894 ,0,0,0}, {21051,21070,21073 ,10894,10887,10892 ,0,0,0}, + {21054,21074,21055 ,10893,10895,10896 ,0,0,0}, {21074,21054,21073 ,10895,10893,10892 ,0,0,0}, + {21056,21055,21075 ,10897,10896,10898 ,0,0,0}, {21074,21075,21055 ,10895,10898,10896 ,0,0,0}, + {21076,21057,21056 ,10899,10900,10897 ,0,0,0}, {21056,21075,21076 ,10897,10898,10899 ,0,0,0}, + {21052,21053,21071 ,10888,10890,10889 ,0,0,0}, {21051,21052,21070 ,10894,10888,10887 ,0,0,0}, + {21072,21049,21067 ,10891,10882,10881 ,0,0,0}, {21071,21053,21072 ,10889,10890,10891 ,0,0,0}, + {21068,21048,21050 ,10884,10883,10885 ,0,0,0}, {21067,21048,21068 ,10881,10883,10884 ,0,0,0}, + {21065,21069,21046 ,10877,10886,10901 ,0,0,0}, {21069,21050,21046 ,10886,10885,10901 ,0,0,0}, + {21047,21064,21045 ,10880,10876,10875 ,0,0,0}, {21045,21065,21046 ,10875,10877,10901 ,0,0,0}, + {21058,21061,21066 ,10878,10869,10879 ,0,0,0}, {21047,21066,21064 ,10880,10879,10876 ,0,0,0}, + {21043,21044,21062 ,10870,10873,10871 ,0,0,0}, {21058,21043,21061 ,10878,10870,10869 ,0,0,0}, + {21063,21041,21059 ,10872,10874,10867 ,0,0,0}, {21062,21044,21063 ,10871,10873,10872 ,0,0,0}, + {21042,21059,21041 ,10832,10867,10874 ,0,0,0}, {21077,21060,21078 ,10902,10868,10903 ,0,0,0}, + {21079,21062,21080 ,10904,10905,10906 ,0,0,0}, {21081,21063,21059 ,10907,10908,10909 ,0,0,0}, + {21064,21082,21065 ,10910,10911,10912 ,0,0,0}, {21061,21083,21066 ,10913,10914,10915 ,0,0,0}, + {21084,21067,21068 ,10916,10917,10918 ,0,0,0}, {21085,21069,21086 ,10919,10920,10921 ,0,0,0}, + {21087,21071,21088 ,10922,10923,10924 ,0,0,0}, {21072,21067,21089 ,10925,10917,10926 ,0,0,0}, + {21090,21073,21070 ,10927,10928,10929 ,0,0,0}, {21070,21087,21090 ,10929,10922,10927 ,0,0,0}, + {21073,21091,21074 ,10928,10930,10931 ,0,0,0}, {21091,21073,21090 ,10930,10928,10927 ,0,0,0}, + {21075,21074,21092 ,10932,10931,10933 ,0,0,0}, {21091,21092,21074 ,10930,10933,10931 ,0,0,0}, + {21093,21076,21075 ,10934,10935,10932 ,0,0,0}, {21075,21092,21093 ,10932,10933,10934 ,0,0,0}, + {21071,21072,21088 ,10923,10925,10924 ,0,0,0}, {21070,21071,21087 ,10929,10923,10922 ,0,0,0}, + {21089,21067,21084 ,10926,10917,10916 ,0,0,0}, {21088,21072,21089 ,10924,10925,10926 ,0,0,0}, + {21085,21068,21069 ,10919,10918,10920 ,0,0,0}, {21084,21068,21085 ,10916,10918,10919 ,0,0,0}, + {21082,21086,21065 ,10911,10921,10912 ,0,0,0}, {21086,21069,21065 ,10921,10920,10912 ,0,0,0}, + {21066,21094,21064 ,10915,10936,10910 ,0,0,0}, {21094,21082,21064 ,10936,10911,10910 ,0,0,0}, + {21061,21079,21083 ,10913,10904,10914 ,0,0,0}, {21066,21083,21094 ,10915,10914,10936 ,0,0,0}, + {21062,21063,21080 ,10905,10908,10906 ,0,0,0}, {21061,21062,21079 ,10913,10905,10904 ,0,0,0}, + {21081,21059,21077 ,10907,10909,10902 ,0,0,0}, {21080,21063,21081 ,10906,10908,10907 ,0,0,0}, + {21060,21077,21059 ,10868,10902,10909 ,0,0,0}, {20677,21095,20714 ,10937,10938,10226 ,0,0,0}, + {20683,21096,20684 ,10939,10940,10941 ,0,0,0}, {20679,21097,21098 ,10942,10943,10944 ,0,0,0}, + {21099,20691,21100 ,10945,10946,10947 ,0,0,0}, {21101,20681,21102 ,10948,10949,10950 ,0,0,0}, + {20696,21103,21104 ,10951,10952,10953 ,0,0,0}, {20688,21105,20686 ,10954,10955,10956 ,0,0,0}, + {21106,21107,20701 ,10957,10958,10959 ,0,0,0}, {21108,20694,20693 ,10960,10961,10962 ,0,0,0}, + {21109,21110,20698 ,10963,10964,10965 ,0,0,0}, {20699,20698,21110 ,10966,10965,10964 ,0,0,0}, + {20705,21111,21109 ,10967,10968,10963 ,0,0,0}, {21109,20698,20705 ,10963,10965,10967 ,0,0,0}, + {21111,20707,21112 ,10968,10969,10970 ,0,0,0}, {20707,21111,20705 ,10969,10968,10967 ,0,0,0}, + {21113,21112,20708 ,10971,10970,10972 ,0,0,0}, {20707,20708,21112 ,10969,10972,10970 ,0,0,0}, + {20711,21114,21113 ,10223,10973,10971 ,0,0,0}, {21113,20708,20711 ,10971,10972,10223 ,0,0,0}, + {20701,20699,21106 ,10959,10966,10957 ,0,0,0}, {21106,20699,21110 ,10957,10966,10964 ,0,0,0}, + {21107,21108,20693 ,10958,10960,10962 ,0,0,0}, {21107,20693,20701 ,10958,10962,10959 ,0,0,0}, + {20694,21103,20696 ,10961,10952,10951 ,0,0,0}, {21108,21103,20694 ,10960,10952,10961 ,0,0,0}, + {20688,21104,21105 ,10954,10953,10955 ,0,0,0}, {20696,21104,20688 ,10951,10953,10954 ,0,0,0}, + {20691,20686,21100 ,10946,10956,10947 ,0,0,0}, {20686,21105,21100 ,10956,10955,10947 ,0,0,0}, + {21102,20713,21099 ,10950,10974,10945 ,0,0,0}, {20713,20691,21099 ,10974,10946,10945 ,0,0,0}, + {21101,20683,20681 ,10948,10939,10949 ,0,0,0}, {21102,20681,20713 ,10950,10949,10974 ,0,0,0}, + {21096,21097,20684 ,10940,10943,10941 ,0,0,0}, {21101,21096,20683 ,10948,10940,10939 ,0,0,0}, + {20679,21098,20677 ,10942,10944,10937 ,0,0,0}, {20684,21097,20679 ,10941,10943,10942 ,0,0,0}, + {21095,20677,21098 ,10938,10937,10944 ,0,0,0}, {21115,21078,21116 ,10975,10903,10976 ,0,0,0}, + {21117,21080,21118 ,10977,10978,10979 ,0,0,0}, {21119,21081,21077 ,10980,10981,10982 ,0,0,0}, + {21094,21120,21121 ,10983,10984,10985 ,0,0,0}, {21079,21122,21083 ,10986,10987,10988 ,0,0,0}, + {21123,21124,21085 ,10989,10990,10991 ,0,0,0}, {21125,21086,21082 ,10992,10993,10994 ,0,0,0}, + {21126,21088,21089 ,10995,10996,10997 ,0,0,0}, {21089,21084,21127 ,10997,10998,10999 ,0,0,0}, + {21128,21090,21087 ,11000,11001,11002 ,0,0,0}, {21087,21129,21128 ,11002,11003,11000 ,0,0,0}, + {21090,21130,21091 ,11001,11004,11005 ,0,0,0}, {21130,21090,21128 ,11004,11001,11000 ,0,0,0}, + {21092,21091,21131 ,11006,11005,11007 ,0,0,0}, {21130,21131,21091 ,11004,11007,11005 ,0,0,0}, + {21132,21092,21133 ,11008,11006,11009 ,0,0,0}, {21092,21131,21133 ,11006,11007,11009 ,0,0,0}, + {21093,21092,21132 ,11010,11006,11008 ,0,0,0}, {21129,21088,21126 ,11003,10996,10995 ,0,0,0}, + {21087,21088,21129 ,11002,10996,11003 ,0,0,0}, {21084,21124,21127 ,10998,10990,10999 ,0,0,0}, + {21126,21089,21127 ,10995,10997,10999 ,0,0,0}, {21123,21085,21086 ,10989,10991,10993 ,0,0,0}, + {21124,21084,21085 ,10990,10998,10991 ,0,0,0}, {21121,21125,21082 ,10985,10992,10994 ,0,0,0}, + {21125,21123,21086 ,10992,10989,10993 ,0,0,0}, {21083,21120,21094 ,10988,10984,10983 ,0,0,0}, + {21094,21121,21082 ,10983,10985,10994 ,0,0,0}, {21079,21117,21122 ,10986,10977,10987 ,0,0,0}, + {21083,21122,21120 ,10988,10987,10984 ,0,0,0}, {21080,21081,21118 ,10978,10981,10979 ,0,0,0}, + {21079,21080,21117 ,10986,10978,10977 ,0,0,0}, {21119,21077,21115 ,10980,10982,10975 ,0,0,0}, + {21118,21081,21119 ,10979,10981,10980 ,0,0,0}, {21078,21115,21077 ,10903,10975,10982 ,0,0,0}, + {21098,21116,21095 ,11011,10976,11012 ,0,0,0}, {21101,21118,21096 ,11013,11014,11015 ,0,0,0}, + {21097,21119,21115 ,11016,11017,11018 ,0,0,0}, {21120,21099,21100 ,11019,11020,11021 ,0,0,0}, + {21117,21102,21122 ,11022,11023,11024 ,0,0,0}, {21104,21103,21123 ,11025,11026,11027 ,0,0,0}, + {21105,21125,21121 ,11028,11029,11030 ,0,0,0}, {21106,21126,21107 ,11031,11032,11033 ,0,0,0}, + {21127,21124,21108 ,11034,11035,11036 ,0,0,0}, {21109,21128,21110 ,11037,11038,11039 ,0,0,0}, + {21129,21106,21110 ,11040,11031,11039 ,0,0,0}, {21109,21111,21130 ,11037,11041,11042 ,0,0,0}, + {21130,21128,21109 ,11042,11038,11037 ,0,0,0}, {21131,21111,21112 ,11043,11041,11044 ,0,0,0}, + {21111,21131,21130 ,11041,11043,11042 ,0,0,0}, {21113,21133,21112 ,11045,11046,11044 ,0,0,0}, + {21131,21112,21133 ,11043,11044,11046 ,0,0,0}, {21114,21132,21133 ,11047,11008,11046 ,0,0,0}, + {21133,21113,21114 ,11046,11045,11047 ,0,0,0}, {21126,21106,21129 ,11032,11031,11040 ,0,0,0}, + {21128,21129,21110 ,11038,11040,11039 ,0,0,0}, {21107,21127,21108 ,11033,11034,11036 ,0,0,0}, + {21126,21127,21107 ,11032,11034,11033 ,0,0,0}, {21103,21124,21123 ,11026,11035,11027 ,0,0,0}, + {21108,21124,21103 ,11036,11035,11026 ,0,0,0}, {21105,21104,21125 ,11028,11025,11029 ,0,0,0}, + {21104,21123,21125 ,11025,11027,11029 ,0,0,0}, {21120,21100,21121 ,11019,11021,11030 ,0,0,0}, + {21100,21105,21121 ,11021,11028,11030 ,0,0,0}, {21122,21102,21099 ,11024,11023,11020 ,0,0,0}, + {21122,21099,21120 ,11024,11020,11019 ,0,0,0}, {21117,21118,21101 ,11022,11014,11013 ,0,0,0}, + {21117,21101,21102 ,11022,11013,11023 ,0,0,0}, {21096,21119,21097 ,11015,11017,11016 ,0,0,0}, + {21118,21119,21096 ,11014,11017,11015 ,0,0,0}, {21098,21115,21116 ,11011,11018,10976 ,0,0,0}, + {21097,21115,21098 ,11016,11018,11011 ,0,0,0}, {20801,21134,21135 ,11048,11049,11050 ,0,0,0}, + {20800,21136,20798 ,11051,11052,11053 ,0,0,0}, {21134,20801,21137 ,11049,11048,11054 ,0,0,0}, + {21135,21138,20801 ,11050,11048,11048 ,0,0,0}, {21137,20801,20798 ,11054,11048,11053 ,0,0,0}, + {21139,21137,20798 ,11055,11054,11053 ,0,0,0}, {21139,20798,21136 ,11055,11053,11052 ,0,0,0}, + {20836,20754,21140 ,11056,11057,11058 ,0,0,0}, {20836,21141,21142 ,11056,11059,11060 ,0,0,0}, + {21140,21141,20836 ,11058,11059,11056 ,0,0,0}, {20800,21142,21143 ,11051,11060,11061 ,0,0,0}, + {20800,20836,21142 ,11051,11056,11060 ,0,0,0}, {20800,21144,21145 ,11051,11062,11063 ,0,0,0}, + {21143,21144,20800 ,11061,11062,11051 ,0,0,0}, {20800,21146,21147 ,11051,11064,11065 ,0,0,0}, + {21145,21146,20800 ,11063,11064,11051 ,0,0,0}, {21136,20800,21148 ,11052,11051,11066 ,0,0,0}, + {21147,21148,20800 ,11065,11066,11051 ,0,0,0}, {21149,20622,21150 ,11067,11068,11069 ,0,0,0}, + {20622,21151,21152 ,11068,11070,11071 ,0,0,0}, {21152,20620,20622 ,11071,11072,11068 ,0,0,0}, + {20622,21149,21151 ,11068,11067,11070 ,0,0,0}, {20620,21153,21154 ,11072,11073,11074 ,0,0,0}, + {20620,21152,21153 ,11072,11071,11073 ,0,0,0}, {20622,21155,21150 ,11068,11075,11069 ,0,0,0}, + {20620,21154,20549 ,11072,11074,11076 ,0,0,0}, {21156,20622,20607 ,11077,11068,11078 ,0,0,0}, + {20622,21156,21155 ,11068,11077,11075 ,0,0,0}, {20609,21157,21158 ,11079,11079,11080 ,0,0,0}, + {21159,21160,20610 ,11081,11082,11083 ,0,0,0}, {21161,21162,20609 ,11084,11085,11079 ,0,0,0}, + {21161,20609,21158 ,11084,11079,11080 ,0,0,0}, {20609,21163,20610 ,11079,11086,11083 ,0,0,0}, + {21163,20609,21162 ,11086,11079,11085 ,0,0,0}, {21164,20610,21160 ,11087,11083,11082 ,0,0,0}, + {21163,21159,20610 ,11086,11081,11083 ,0,0,0}, {21156,20607,21164 ,11077,11078,11087 ,0,0,0}, + {21164,20607,20610 ,11087,11078,11083 ,0,0,0}, {21157,20609,21165 ,11088,11089,11090 ,0,0,0}, + {21006,21165,21024 ,11091,11090,11092 ,0,0,0}, {21006,20988,21165 ,11091,11093,11090 ,0,0,0}, + {21165,20988,20977 ,11090,11093,11094 ,0,0,0}, {20977,20949,21165 ,11094,11095,11090 ,0,0,0}, + {21165,20609,21024 ,11090,11089,11092 ,0,0,0}, {21166,21164,21167 ,11096,11097,11098 ,0,0,0}, + {21166,21168,21156 ,11096,324,11099 ,0,0,0}, {21156,21164,21166 ,11099,11097,11096 ,0,0,0}, + {21169,21170,21171 ,11100,11101,11102 ,0,0,0}, {21170,21172,21171 ,11101,11103,11102 ,0,0,0}, + {21170,21169,21173 ,11101,11100,11104 ,0,0,0}, {21151,21174,21173 ,11105,11106,11104 ,0,0,0}, + {21169,21151,21173 ,11100,11105,11104 ,0,0,0}, {21149,21174,21151 ,11107,11106,11105 ,0,0,0}, + {21174,21149,21175 ,11106,11107,11108 ,0,0,0}, {21150,21176,21175 ,11109,11110,11108 ,0,0,0}, + {21175,21149,21150 ,11108,11107,11109 ,0,0,0}, {21176,21155,21177 ,11110,11111,11112 ,0,0,0}, + {21155,21176,21150 ,11111,11110,11109 ,0,0,0}, {21168,21177,21156 ,11113,11112,11114 ,0,0,0}, + {21155,21156,21177 ,11111,11114,11112 ,0,0,0}, {21162,21178,21179 ,11115,11116,11117 ,0,0,0}, + {21167,21164,21160 ,11118,11119,11120 ,0,0,0}, {21160,21159,21180 ,11120,11121,11122 ,0,0,0}, + {21181,21163,21179 ,11123,11124,11117 ,0,0,0}, {21180,21159,21181 ,11122,11121,11123 ,0,0,0}, + {21160,21180,21167 ,11120,11122,11118 ,0,0,0}, {21159,21163,21181 ,11121,11124,11123 ,0,0,0}, + {21163,21162,21179 ,11124,11115,11117 ,0,0,0}, {21178,21162,21161 ,11116,11115,11125 ,0,0,0}, + {21161,21158,21182 ,11125,11126,11127 ,0,0,0}, {21182,21178,21161 ,11127,11116,11125 ,0,0,0}, + {21183,21158,21157 ,11128,11126,11129 ,0,0,0}, {21158,21183,21182 ,11126,11128,11127 ,0,0,0}, + {21183,21157,21165 ,11128,11129,11129 ,0,0,0}, {21138,21184,21185 ,11130,11130,11131 ,0,0,0}, + {21138,21185,21186 ,11130,11131,11130 ,0,0,0}, {21187,21138,21186 ,11130,11130,11130 ,0,0,0}, + {21178,21182,21138 ,11130,11130,11130 ,0,0,0}, {21178,21138,21187 ,11130,11130,11130 ,0,0,0}, + {21138,21183,21165 ,11130,11130,11131 ,0,0,0}, {21182,21183,21138 ,11130,11130,11130 ,0,0,0}, + {21138,21165,20801 ,11130,11131,11130 ,0,0,0}, {21165,20928,20908 ,11131,11130,11130 ,0,0,0}, + {21165,20949,20928 ,11131,11131,11130 ,0,0,0}, {20908,20888,21165 ,11130,11131,11131 ,0,0,0}, + {20801,21165,20869 ,11130,11131,11130 ,0,0,0}, {21165,20888,20869 ,11131,11131,11130 ,0,0,0}, + {20714,21095,21188 ,11132,11133,11134 ,0,0,0}, {21140,21189,21141 ,11135,11136,11137 ,0,0,0}, + {21190,21189,20715 ,11138,11136,11139 ,0,0,0}, {21191,21172,21192 ,11140,11141,11142 ,0,0,0}, + {21193,21191,21192 ,11143,11140,11142 ,0,0,0}, {21194,21195,21196 ,11144,11145,11146 ,0,0,0}, + {21195,21193,21196 ,11145,11143,11146 ,0,0,0}, {21189,20735,20715 ,11136,11147,11139 ,0,0,0}, + {21190,20715,20675 ,11138,11139,11148 ,0,0,0}, {21194,21142,21141 ,11144,11149,11137 ,0,0,0}, + {20754,20735,21140 ,11150,11147,11135 ,0,0,0}, {20714,21190,20675 ,11132,11138,11148 ,0,0,0}, + {21188,21197,21190 ,11134,11151,11138 ,0,0,0}, {21190,20714,21188 ,11138,11132,11134 ,0,0,0}, + {21197,21191,21193 ,11151,11140,11143 ,0,0,0}, {21195,21194,21141 ,11145,11144,11137 ,0,0,0}, + {21193,21195,21190 ,11143,11145,11138 ,0,0,0}, {21140,20735,21189 ,11135,11147,11136 ,0,0,0}, + {21193,21190,21197 ,11143,11138,11151 ,0,0,0}, {21192,21196,21193 ,11142,11146,11143 ,0,0,0}, + {21141,21189,21195 ,11137,11136,11145 ,0,0,0}, {21190,21195,21189 ,11138,11145,11136 ,0,0,0}, + {21198,21199,21200 ,11152,11153,11154 ,0,0,0}, {21201,21202,21203 ,11155,11156,11157 ,0,0,0}, + {21204,21205,21206 ,11158,11159,11160 ,0,0,0}, {21172,21170,21207 ,11161,11162,11163 ,0,0,0}, + {21208,21209,21146 ,11164,11165,11166 ,0,0,0}, {21210,21211,21212 ,11167,11168,11169 ,0,0,0}, + {21213,21214,21199 ,11170,11171,11153 ,0,0,0}, {21136,21148,21214 ,11172,11173,11171 ,0,0,0}, + {21215,21177,21168 ,11174,11175,11176 ,0,0,0}, {21198,21200,21215 ,11152,11154,11174 ,0,0,0}, + {21136,21214,21213 ,11172,11171,11170 ,0,0,0}, {21203,21200,21199 ,11157,11154,11153 ,0,0,0}, + {21148,21216,21214 ,11173,11177,11171 ,0,0,0}, {21209,21216,21147 ,11165,11177,11178 ,0,0,0}, + {21217,21208,21212 ,11179,11164,11169 ,0,0,0}, {21218,21206,21202 ,11180,11160,11156 ,0,0,0}, + {21143,21194,21210 ,11181,11182,11167 ,0,0,0}, {21205,21217,21207 ,11159,11179,11163 ,0,0,0}, + {21142,21194,21143 ,11183,11182,11181 ,0,0,0}, {21210,21194,21196 ,11167,11182,11184 ,0,0,0}, + {21147,21216,21148 ,11178,11177,11173 ,0,0,0}, {21147,21146,21209 ,11178,11166,11165 ,0,0,0}, + {21215,21200,21177 ,11174,11154,11175 ,0,0,0}, {21213,21199,21198 ,11170,11153,11152 ,0,0,0}, + {21203,21199,21201 ,11157,11153,11155 ,0,0,0}, {21176,21177,21200 ,11185,11175,11154 ,0,0,0}, + {21201,21214,21216 ,11155,11171,11177 ,0,0,0}, {21192,21172,21207 ,11186,11161,11163 ,0,0,0}, + {21200,21203,21176 ,11154,11157,11185 ,0,0,0}, {21214,21201,21199 ,11171,11155,11153 ,0,0,0}, + {21202,21201,21218 ,11156,11155,11180 ,0,0,0}, {21175,21176,21203 ,11187,11185,11157 ,0,0,0}, + {21209,21218,21216 ,11165,11180,11177 ,0,0,0}, {21145,21208,21146 ,11188,11164,11166 ,0,0,0}, + {21203,21202,21175 ,11157,11156,11187 ,0,0,0}, {21216,21218,21201 ,11177,11180,11155 ,0,0,0}, + {21206,21218,21204 ,11160,11180,11158 ,0,0,0}, {21174,21175,21202 ,11189,11187,11156 ,0,0,0}, + {21208,21204,21209 ,11164,11158,11165 ,0,0,0}, {21144,21212,21145 ,11190,11169,11188 ,0,0,0}, + {21206,21173,21174 ,11160,11191,11189 ,0,0,0}, {21209,21204,21218 ,11165,11158,11180 ,0,0,0}, + {21204,21217,21205 ,11158,11179,11159 ,0,0,0}, {21174,21202,21206 ,11189,11156,11160 ,0,0,0}, + {21145,21212,21208 ,11188,11169,11164 ,0,0,0}, {21210,21144,21143 ,11167,11190,11181 ,0,0,0}, + {21205,21170,21173 ,11159,11162,11191 ,0,0,0}, {21208,21217,21204 ,11164,11179,11158 ,0,0,0}, + {21211,21207,21217 ,11168,11163,11179 ,0,0,0}, {21173,21206,21205 ,11191,11160,11159 ,0,0,0}, + {21144,21210,21212 ,11190,11167,11169 ,0,0,0}, {21212,21211,21217 ,11169,11168,11179 ,0,0,0}, + {21196,21192,21211 ,11184,11186,11168 ,0,0,0}, {21210,21196,21211 ,11167,11184,11168 ,0,0,0}, + {21192,21207,21211 ,11186,11163,11168 ,0,0,0}, {21170,21205,21207 ,11162,11159,11163 ,0,0,0}, + {21215,21166,21219 ,11192,11193,11194 ,0,0,0}, {21139,21220,21137 ,11195,11196,11054 ,0,0,0}, + {21219,21166,21221 ,11194,11193,11197 ,0,0,0}, {21166,21167,21221 ,11193,324,11197 ,0,0,0}, + {21219,21222,21220 ,11194,11198,11196 ,0,0,0}, {21215,21168,21166 ,11192,324,11193 ,0,0,0}, + {21220,21222,21137 ,11196,11198,11054 ,0,0,0}, {21213,21220,21139 ,11199,11196,11195 ,0,0,0}, + {21136,21213,21139 ,11200,11199,11195 ,0,0,0}, {21213,21198,21220 ,11199,11201,11196 ,0,0,0}, + {21198,21215,21219 ,11201,11192,11194 ,0,0,0}, {21198,21219,21220 ,11201,11194,11196 ,0,0,0}, + {21222,21219,21221 ,11198,11194,11197 ,0,0,0}, {21187,21186,21179 ,11202,11203,11204 ,0,0,0}, + {21221,21167,21180 ,11205,324,11206 ,0,0,0}, {21180,21181,21223 ,11206,11207,11208 ,0,0,0}, + {21180,21223,21221 ,11206,11208,11205 ,0,0,0}, {21178,21187,21179 ,11209,11202,11204 ,0,0,0}, + {21185,21184,21224 ,11210,11211,11212 ,0,0,0}, {21224,21225,21185 ,11212,11213,11210 ,0,0,0}, + {21222,21223,21226 ,11214,11208,11215 ,0,0,0}, {21226,21223,21225 ,11215,11208,11213 ,0,0,0}, + {21184,21138,21135 ,11211,11216,11217 ,0,0,0}, {21222,21226,21137 ,11214,11215,11218 ,0,0,0}, + {21135,21226,21224 ,11217,11215,11212 ,0,0,0}, {21221,21223,21222 ,11205,11208,11214 ,0,0,0}, + {21135,21134,21226 ,11217,11219,11215 ,0,0,0}, {21226,21134,21137 ,11215,11219,11218 ,0,0,0}, + {21223,21181,21225 ,11208,11207,11213 ,0,0,0}, {21179,21225,21181 ,11204,11213,11207 ,0,0,0}, + {21135,21224,21184 ,11217,11212,11211 ,0,0,0}, {21226,21225,21224 ,11215,11213,11212 ,0,0,0}, + {21186,21225,21179 ,11203,11213,11204 ,0,0,0}, {21186,21185,21225 ,11203,11210,11213 ,0,0,0}, + {21060,21227,21228 ,11220,11221,11222 ,0,0,0}, {21172,21191,21229 ,11223,11224,11225 ,0,0,0}, + {21230,21229,21191 ,11226,11225,11224 ,0,0,0}, {21060,21228,21078 ,11220,11222,11227 ,0,0,0}, + {21228,21227,21230 ,11222,11221,11226 ,0,0,0}, {21188,21095,21116 ,11228,11229,11230 ,0,0,0}, + {21078,21228,21116 ,11227,11222,11230 ,0,0,0}, {21154,21227,21042 ,11231,11221,11232 ,0,0,0}, + {21231,21154,21153 ,11233,11231,11234 ,0,0,0}, {21227,21060,21042 ,11221,11220,11232 ,0,0,0}, + {21229,21169,21171 ,11225,11235,11236 ,0,0,0}, {21229,21231,21232 ,11225,11233,11237 ,0,0,0}, + {21042,20549,21154 ,11232,11238,11231 ,0,0,0}, {21169,21232,21151 ,11235,11237,11239 ,0,0,0}, + {21232,21169,21229 ,11237,11235,11225 ,0,0,0}, {21228,21188,21116 ,11222,11228,11230 ,0,0,0}, + {21227,21231,21230 ,11221,11233,11226 ,0,0,0}, {21197,21188,21228 ,11240,11228,11222 ,0,0,0}, + {21154,21231,21227 ,11231,11233,11221 ,0,0,0}, {21232,21153,21152 ,11237,11234,11241 ,0,0,0}, + {21191,21197,21230 ,11224,11240,11226 ,0,0,0}, {21228,21230,21197 ,11222,11226,11240 ,0,0,0}, + {21153,21232,21231 ,11234,11237,11233 ,0,0,0}, {21151,21232,21152 ,11239,11237,11241 ,0,0,0}, + {21229,21171,21172 ,11225,11236,11223 ,0,0,0}, {21231,21229,21230 ,11233,11225,11226 ,0,0,0}, + {21233,20674,21234 ,11242,11243,11244 ,0,0,0}, {20674,21235,21236 ,11243,11245,11246 ,0,0,0}, + {21236,20673,20674 ,11246,11247,11243 ,0,0,0}, {20674,21233,21235 ,11243,11242,11245 ,0,0,0}, + {20673,21237,21238 ,11247,11248,11249 ,0,0,0}, {20673,21236,21237 ,11247,11246,11248 ,0,0,0}, + {20674,21239,21234 ,11243,11250,11244 ,0,0,0}, {20673,21238,20569 ,11247,11249,11251 ,0,0,0}, + {21240,20674,20582 ,11252,11243,11253 ,0,0,0}, {20674,21240,21239 ,11243,11252,11250 ,0,0,0}, + {20583,21241,21242 ,11254,11254,11255 ,0,0,0}, {21243,21244,20581 ,11256,11257,11258 ,0,0,0}, + {21245,21246,20583 ,11259,11260,11254 ,0,0,0}, {21245,20583,21242 ,11259,11254,11255 ,0,0,0}, + {20583,21247,20581 ,11254,11261,11258 ,0,0,0}, {21247,20583,21246 ,11261,11254,11260 ,0,0,0}, + {21248,20581,21244 ,11262,11258,11257 ,0,0,0}, {21247,21243,20581 ,11261,11256,11258 ,0,0,0}, + {21240,20582,21248 ,11252,11253,11262 ,0,0,0}, {21248,20582,20581 ,11262,11253,11258 ,0,0,0}, + {20791,21249,21250 ,11263,11264,11265 ,0,0,0}, {20868,21251,20822 ,11266,11267,11268 ,0,0,0}, + {21249,20791,21252 ,11264,11263,11269 ,0,0,0}, {21250,21253,20791 ,11265,11263,11263 ,0,0,0}, + {21252,20791,20822 ,11269,11263,11268 ,0,0,0}, {21254,21252,20822 ,11270,11269,11268 ,0,0,0}, + {21254,20822,21251 ,11270,11268,11267 ,0,0,0}, {20825,20849,21255 ,11271,11272,11273 ,0,0,0}, + {20825,21256,21257 ,11271,11274,11275 ,0,0,0}, {21255,21256,20825 ,11273,11274,11271 ,0,0,0}, + {20868,21257,21258 ,11266,11275,11276 ,0,0,0}, {20868,20825,21257 ,11266,11271,11275 ,0,0,0}, + {20868,21259,21260 ,11266,11277,11278 ,0,0,0}, {21258,21259,20868 ,11276,11277,11266 ,0,0,0}, + {20868,21261,21262 ,11266,11279,11280 ,0,0,0}, {21260,21261,20868 ,11278,11279,11266 ,0,0,0}, + {21251,20868,21263 ,11267,11266,11281 ,0,0,0}, {21262,21263,20868 ,11280,11281,11266 ,0,0,0}, + {21132,21241,21093 ,11282,11283,11282 ,0,0,0}, {20583,21057,21241 ,11282,11282,11283 ,0,0,0}, + {21114,21264,21241 ,11282,11283,11283 ,0,0,0}, {21241,21132,21114 ,11283,11282,11282 ,0,0,0}, + {21076,21093,21241 ,11282,11282,11283 ,0,0,0}, {21076,21241,21057 ,11282,11283,11282 ,0,0,0}, + {21265,21266,21240 ,21,21,21 ,0,0,0}, {21248,21267,21265 ,11284,21,21 ,0,0,0}, + {21265,21240,21248 ,21,21,11284 ,0,0,0}, {21268,21269,21270 ,11285,11286,11287 ,0,0,0}, + {21269,21271,21270 ,11286,11288,11287 ,0,0,0}, {21269,21268,21272 ,11286,11285,11289 ,0,0,0}, + {21235,21273,21272 ,11290,11291,11289 ,0,0,0}, {21268,21235,21272 ,11285,11290,11289 ,0,0,0}, + {21233,21273,21235 ,11292,11291,11290 ,0,0,0}, {21273,21233,21274 ,11291,11292,11293 ,0,0,0}, + {21234,21275,21274 ,11294,11295,11293 ,0,0,0}, {21274,21233,21234 ,11293,11292,11294 ,0,0,0}, + {21275,21239,21276 ,11295,11296,11297 ,0,0,0}, {21239,21275,21234 ,11296,11295,11294 ,0,0,0}, + {21266,21276,21240 ,11298,11297,11299 ,0,0,0}, {21239,21240,21276 ,11296,11299,11297 ,0,0,0}, + {21277,21278,21246 ,11300,11301,11302 ,0,0,0}, {21279,21247,21278 ,11303,11304,11301 ,0,0,0}, + {21248,21244,21267 ,21,11305,21 ,0,0,0}, {21243,21280,21244 ,11306,11307,11305 ,0,0,0}, + {21243,21279,21280 ,11306,11303,11307 ,0,0,0}, {21280,21267,21244 ,11307,21,11305 ,0,0,0}, + {21247,21279,21243 ,11304,11303,11306 ,0,0,0}, {21247,21246,21278 ,11304,11302,11301 ,0,0,0}, + {21277,21246,21245 ,11300,11302,11308 ,0,0,0}, {21245,21242,21281 ,11308,11309,11310 ,0,0,0}, + {21281,21277,21245 ,11310,11300,11308 ,0,0,0}, {21282,21242,21241 ,11311,11309,11312 ,0,0,0}, + {21242,21282,21281 ,11309,11311,11310 ,0,0,0}, {21282,21241,21264 ,11311,11312,11312 ,0,0,0}, + {20752,21264,20733 ,11313,11314,11315 ,0,0,0}, {21283,21253,21284 ,11316,11317,11318 ,0,0,0}, + {21253,21277,21281 ,11317,11319,11320 ,0,0,0}, {21281,21282,21253 ,11320,11321,11317 ,0,0,0}, + {21283,21285,21253 ,11316,11322,11317 ,0,0,0}, {21253,21286,21277 ,11317,11323,11319 ,0,0,0}, + {21285,21286,21253 ,11322,11323,11317 ,0,0,0}, {21264,20791,21253 ,11314,11324,11317 ,0,0,0}, + {21282,21264,21253 ,11321,11314,11317 ,0,0,0}, {21264,20771,20791 ,11314,11325,11324 ,0,0,0}, + {20771,21264,20752 ,11325,11314,11313 ,0,0,0}, {21264,20711,20712 ,11314,11326,11327 ,0,0,0}, + {21264,21114,20711 ,11314,11314,11326 ,0,0,0}, {20712,20733,21264 ,11327,11315,11314 ,0,0,0}, + {20946,20966,21287 ,11328,11329,11330 ,0,0,0}, {21255,21288,21256 ,11331,11332,11333 ,0,0,0}, + {21289,21288,20907 ,11334,11332,11335 ,0,0,0}, {21290,21271,21291 ,11336,11337,11338 ,0,0,0}, + {21292,21290,21291 ,11339,11336,11338 ,0,0,0}, {21293,21294,21295 ,11340,11341,11342 ,0,0,0}, + {21294,21292,21295 ,11341,11339,11342 ,0,0,0}, {21288,20887,20907 ,11332,11343,11335 ,0,0,0}, + {21289,20907,20926 ,11334,11335,11344 ,0,0,0}, {21293,21257,21256 ,11340,11345,11333 ,0,0,0}, + {20849,20887,21255 ,11346,11343,11331 ,0,0,0}, {20946,21289,20926 ,11328,11334,11344 ,0,0,0}, + {21287,21296,21289 ,11330,11347,11334 ,0,0,0}, {21289,20946,21287 ,11334,11328,11330 ,0,0,0}, + {21296,21290,21292 ,11347,11336,11339 ,0,0,0}, {21294,21293,21256 ,11341,11340,11333 ,0,0,0}, + {21292,21294,21289 ,11339,11341,11334 ,0,0,0}, {21255,20887,21288 ,11331,11343,11332 ,0,0,0}, + {21292,21289,21296 ,11339,11334,11347 ,0,0,0}, {21291,21295,21292 ,11338,11342,11339 ,0,0,0}, + {21256,21288,21294 ,11333,11332,11341 ,0,0,0}, {21289,21294,21288 ,11334,11341,11332 ,0,0,0}, + {21297,21298,21299 ,11348,11349,11350 ,0,0,0}, {21273,21300,21301 ,11351,11352,11353 ,0,0,0}, + {21273,21274,21300 ,11351,11354,11352 ,0,0,0}, {21291,21269,21302 ,11355,11356,11357 ,0,0,0}, + {21303,21261,21304 ,11358,11359,11360 ,0,0,0}, {21291,21271,21269 ,11355,11361,11356 ,0,0,0}, + {21305,21306,21307 ,11362,11363,11364 ,0,0,0}, {21275,21308,21309 ,11365,11366,11367 ,0,0,0}, + {21266,21306,21310 ,21,11363,11368 ,0,0,0}, {21305,21311,21310 ,11362,11369,11368 ,0,0,0}, + {21263,21262,21312 ,11370,11371,11372 ,0,0,0}, {21262,21303,21312 ,11371,11358,11372 ,0,0,0}, + {21313,21314,21297 ,11373,11374,11348 ,0,0,0}, {21303,21304,21311 ,11358,11360,11369 ,0,0,0}, + {21315,21251,21263 ,11375,11376,11370 ,0,0,0}, {21272,21301,21302 ,11377,11353,11357 ,0,0,0}, + {21275,21309,21274 ,11365,11367,11354 ,0,0,0}, {21302,21299,21295 ,11357,11350,11378 ,0,0,0}, + {21295,21299,21293 ,11378,11350,11379 ,0,0,0}, {21293,21298,21257 ,11379,11349,11380 ,0,0,0}, + {21291,21302,21295 ,11355,11357,11378 ,0,0,0}, {21269,21272,21302 ,11356,11377,11357 ,0,0,0}, + {21298,21293,21299 ,11349,11379,11350 ,0,0,0}, {21298,21314,21258 ,11349,11374,11381 ,0,0,0}, + {21299,21301,21297 ,11350,11353,11348 ,0,0,0}, {21257,21298,21258 ,11380,11349,11381 ,0,0,0}, + {21302,21301,21299 ,11357,11353,11350 ,0,0,0}, {21272,21273,21301 ,11377,11351,11353 ,0,0,0}, + {21314,21298,21297 ,11374,11349,11348 ,0,0,0}, {21314,21316,21259 ,11374,11382,11383 ,0,0,0}, + {21297,21300,21313 ,11348,11352,11373 ,0,0,0}, {21258,21314,21259 ,11381,11374,11383 ,0,0,0}, + {21301,21300,21297 ,11353,11352,11348 ,0,0,0}, {21309,21300,21274 ,11367,11352,11354 ,0,0,0}, + {21316,21314,21313 ,11382,11374,11373 ,0,0,0}, {21316,21304,21260 ,11382,11360,11384 ,0,0,0}, + {21309,21317,21313 ,11367,11385,11373 ,0,0,0}, {21259,21316,21260 ,11383,11382,11384 ,0,0,0}, + {21309,21313,21300 ,11367,11373,11352 ,0,0,0}, {21276,21308,21275 ,11386,11366,11365 ,0,0,0}, + {21304,21316,21317 ,11360,11382,11385 ,0,0,0}, {21313,21317,21316 ,11373,11385,11382 ,0,0,0}, + {21308,21311,21317 ,11366,11369,11385 ,0,0,0}, {21260,21304,21261 ,11384,11360,11359 ,0,0,0}, + {21309,21308,21317 ,11367,11366,11385 ,0,0,0}, {21266,21310,21276 ,21,11368,11386 ,0,0,0}, + {21312,21303,21305 ,11372,11358,11362 ,0,0,0}, {21317,21311,21304 ,11385,11369,11360 ,0,0,0}, + {21311,21305,21303 ,11369,11362,11358 ,0,0,0}, {21261,21303,21262 ,11359,11358,11371 ,0,0,0}, + {21308,21276,21310 ,11366,11386,11368 ,0,0,0}, {21311,21308,21310 ,11369,11366,11368 ,0,0,0}, + {21312,21307,21315 ,11372,11364,11375 ,0,0,0}, {21306,21305,21310 ,11363,11362,11368 ,0,0,0}, + {21315,21263,21312 ,11375,11370,11372 ,0,0,0}, {21307,21312,21305 ,11364,11372,11362 ,0,0,0}, + {21306,21265,21318 ,11387,11388,11389 ,0,0,0}, {21254,21319,21252 ,11390,11391,11269 ,0,0,0}, + {21318,21265,21320 ,11389,11388,11392 ,0,0,0}, {21265,21267,21320 ,11388,21,11392 ,0,0,0}, + {21318,21321,21319 ,11389,11393,11391 ,0,0,0}, {21306,21266,21265 ,11387,21,11388 ,0,0,0}, + {21319,21321,21252 ,11391,11393,11269 ,0,0,0}, {21315,21319,21254 ,11394,11391,11390 ,0,0,0}, + {21251,21315,21254 ,11395,11394,11390 ,0,0,0}, {21315,21307,21319 ,11394,11396,11391 ,0,0,0}, + {21307,21306,21318 ,11396,11387,11389 ,0,0,0}, {21307,21318,21319 ,11396,11389,11391 ,0,0,0}, + {21321,21318,21320 ,11393,11389,11392 ,0,0,0}, {21286,21285,21278 ,11397,11398,11399 ,0,0,0}, + {21320,21267,21280 ,11400,21,11401 ,0,0,0}, {21280,21279,21322 ,11401,11402,11403 ,0,0,0}, + {21280,21322,21320 ,11401,11403,11400 ,0,0,0}, {21277,21286,21278 ,11404,11397,11399 ,0,0,0}, + {21283,21284,21323 ,11405,11406,11407 ,0,0,0}, {21323,21324,21283 ,11407,11408,11405 ,0,0,0}, + {21321,21322,21325 ,11409,11403,11410 ,0,0,0}, {21325,21322,21324 ,11410,11403,11408 ,0,0,0}, + {21284,21253,21250 ,11406,11411,11412 ,0,0,0}, {21321,21325,21252 ,11409,11410,11413 ,0,0,0}, + {21250,21325,21323 ,11412,11410,11407 ,0,0,0}, {21320,21322,21321 ,11400,11403,11409 ,0,0,0}, + {21250,21249,21325 ,11412,11414,11410 ,0,0,0}, {21325,21249,21252 ,11410,11414,11413 ,0,0,0}, + {21322,21279,21324 ,11403,11402,11408 ,0,0,0}, {21278,21324,21279 ,11399,11408,11402 ,0,0,0}, + {21250,21323,21284 ,11412,11407,11406 ,0,0,0}, {21325,21324,21323 ,11410,11408,11407 ,0,0,0}, + {21285,21324,21278 ,11398,11408,11399 ,0,0,0}, {21285,21283,21324 ,11398,11405,11408 ,0,0,0}, + {21326,21021,21327 ,11415,11416,11417 ,0,0,0}, {21040,20569,21238 ,11418,11419,11420 ,0,0,0}, + {21268,21328,21235 ,11421,11422,11423 ,0,0,0}, {21329,21290,21330 ,11424,11425,11426 ,0,0,0}, + {21290,21329,21270 ,11425,11424,11427 ,0,0,0}, {21270,21271,21290 ,11427,11428,11425 ,0,0,0}, + {21296,21330,21290 ,11429,11426,11425 ,0,0,0}, {21326,21004,21021 ,11415,11430,11416 ,0,0,0}, + {21270,21329,21268 ,11427,11424,11421 ,0,0,0}, {21328,21330,21331 ,11422,11426,11431 ,0,0,0}, + {21287,20966,20986 ,11432,11433,11434 ,0,0,0}, {21004,21326,20986 ,11430,11415,11434 ,0,0,0}, + {21331,21237,21236 ,11431,11435,11436 ,0,0,0}, {21327,21040,21238 ,11417,11418,11420 ,0,0,0}, + {21329,21330,21328 ,11424,11426,11422 ,0,0,0}, {21331,21236,21328 ,11431,11436,11422 ,0,0,0}, + {21235,21328,21236 ,11423,11422,11436 ,0,0,0}, {21268,21329,21328 ,11421,11424,11422 ,0,0,0}, + {21326,21296,21287 ,11415,11429,11432 ,0,0,0}, {21331,21326,21327 ,11431,11415,11417 ,0,0,0}, + {21331,21330,21326 ,11431,11426,11415 ,0,0,0}, {21237,21331,21327 ,11435,11431,11417 ,0,0,0}, + {21296,21326,21330 ,11429,11415,11426 ,0,0,0}, {20986,21326,21287 ,11434,11415,11432 ,0,0,0}, + {21040,21327,21021 ,11418,11417,11416 ,0,0,0}, {21327,21238,21237 ,11417,11420,11435 ,0,0,0}, + {20663,20526,20525 ,11437,11438,11439 ,0,0,0}, {21332,21333,20552 ,11440,11441,11442 ,0,0,0}, + {20599,21334,21335 ,11443,11444,11445 ,0,0,0}, {20557,20556,21336 ,11446,11447,11448 ,0,0,0}, + {20596,20631,21337 ,11449,11450,11451 ,0,0,0}, {20560,20561,21338 ,11452,11453,11454 ,0,0,0}, + {20560,21339,20556 ,11452,11455,11447 ,0,0,0}, {21340,20651,21341 ,11456,11457,11458 ,0,0,0}, + {20651,21340,20561 ,11457,11456,11453 ,0,0,0}, {21342,21341,20650 ,11459,11458,11460 ,0,0,0}, + {20651,20650,21341 ,11457,11460,11458 ,0,0,0}, {20539,20540,21342 ,21,21,11459 ,0,0,0}, + {21342,20650,20539 ,11459,11460,21 ,0,0,0}, {21338,21339,20560 ,11454,11455,11452 ,0,0,0}, + {20561,21340,21338 ,11453,11456,11454 ,0,0,0}, {21336,21337,20557 ,11448,11451,11446 ,0,0,0}, + {20556,21339,21336 ,11447,11455,11448 ,0,0,0}, {21332,20596,21337 ,11440,11449,11451 ,0,0,0}, + {20631,20557,21337 ,11450,11446,11451 ,0,0,0}, {21333,20550,20552 ,11441,11461,11442 ,0,0,0}, + {21332,20552,20596 ,11440,11442,11449 ,0,0,0}, {20599,20550,21334 ,11443,11461,11444 ,0,0,0}, + {21333,21334,20550 ,11441,11444,11461 ,0,0,0}, {20663,21335,21343 ,11437,11445,11462 ,0,0,0}, + {20599,21335,20663 ,11443,11445,11437 ,0,0,0}, {20526,20663,21343 ,11438,11437,11462 ,0,0,0}, + {21334,20505,20508 ,730,730,730 ,0,0,0}, {20521,21344,20519 ,730,730,730 ,0,0,0}, + {20521,20524,21345 ,730,730,730 ,0,0,0}, {20517,20519,21346 ,730,730,730 ,0,0,0}, + {20524,20511,21345 ,730,730,730 ,0,0,0}, {21344,20521,21345 ,730,730,730 ,0,0,0}, + {20511,20524,20526 ,730,730,730 ,0,0,0}, {20517,21347,20514 ,730,730,730 ,0,0,0}, + {21343,20511,20526 ,730,730,730 ,0,0,0}, {20493,20505,21332 ,730,730,730 ,0,0,0}, + {20528,20516,21348 ,730,730,730 ,0,0,0}, {21349,20529,20528 ,730,730,730 ,0,0,0}, + {8447,20493,21337 ,730,730,730 ,0,0,0}, {20495,21336,21339 ,730,730,730 ,0,0,0}, + {21350,20532,20529 ,730,730,730 ,0,0,0}, {20532,21351,20533 ,730,730,730 ,0,0,0}, + {20535,20533,21352 ,730,730,730 ,0,0,0}, {21339,20496,20495 ,730,730,730 ,0,0,0}, + {20496,21338,21340 ,730,730,730 ,0,0,0}, {20503,21342,20540 ,730,730,730 ,0,0,0}, + {20540,20538,20503 ,730,730,730 ,0,0,0}, {20535,21353,20538 ,730,730,730 ,0,0,0}, + {21341,20502,21340 ,730,730,730 ,0,0,0}, {20516,20514,21348 ,730,730,730 ,0,0,0}, + {20508,20510,21335 ,730,730,730 ,0,0,0}, {21337,21336,8447 ,730,730,730 ,0,0,0}, + {21344,21346,20519 ,730,730,730 ,0,0,0}, {21346,21347,20517 ,730,730,730 ,0,0,0}, + {21347,21348,20514 ,730,730,730 ,0,0,0}, {21348,21349,20528 ,730,730,730 ,0,0,0}, + {21349,21350,20529 ,730,730,730 ,0,0,0}, {21350,21351,20532 ,730,730,730 ,0,0,0}, + {21351,21352,20533 ,730,730,730 ,0,0,0}, {21352,21353,20535 ,730,730,730 ,0,0,0}, + {21353,20503,20538 ,730,730,730 ,0,0,0}, {20503,20499,21342 ,730,730,730 ,0,0,0}, + {20499,20502,21341 ,730,730,730 ,0,0,0}, {20499,21341,21342 ,730,730,730 ,0,0,0}, + {20502,20496,21340 ,730,730,730 ,0,0,0}, {21338,20496,21339 ,730,730,730 ,0,0,0}, + {20495,8447,21336 ,730,730,730 ,0,0,0}, {20493,21332,21337 ,730,730,730 ,0,0,0}, + {20505,21333,21332 ,730,730,730 ,0,0,0}, {21334,20508,21335 ,730,730,730 ,0,0,0}, + {21333,20505,21334 ,730,730,730 ,0,0,0}, {21335,20510,21343 ,730,730,730 ,0,0,0}, + {20511,21343,20510 ,730,730,730 ,0,0,0}, {20509,21354,21355 ,730,730,11463 ,0,0,0}, + {21356,21355,21357 ,730,11463,730 ,0,0,0}, {21356,21357,21358 ,730,730,11463 ,0,0,0}, + {21359,21355,21356 ,730,11463,730 ,0,0,0}, {21359,20512,21355 ,730,730,11463 ,0,0,0}, + {21358,21357,21360 ,11463,730,11464 ,0,0,0}, {20509,21355,20512 ,730,11463,730 ,0,0,0}, + {21354,20507,21361 ,730,730,11464 ,0,0,0}, {21354,20509,20507 ,730,730,730 ,0,0,0}, + {21361,20507,21362 ,11464,730,730 ,0,0,0}, {21362,20507,20506 ,730,730,11464 ,0,0,0}, + {21362,20506,20504 ,730,11464,730 ,0,0,0}, {21363,20504,20492 ,11465,730,11464 ,0,0,0}, + {20504,21363,21362 ,730,11465,730 ,0,0,0}, {20500,21363,20497 ,730,11465,730 ,0,0,0}, + {20492,20497,21363 ,11464,730,11465 ,0,0,0}, {20501,20494,20498 ,11464,730,11466 ,0,0,0}, + {20497,20494,20501 ,730,730,11464 ,0,0,0}, {20501,20500,20497 ,11464,730,730 ,0,0,0}, + {20503,21353,21363 ,11467,11468,11469 ,0,0,0}, {21355,21354,21350 ,11470,11471,11472 ,0,0,0}, + {21361,21362,21352 ,11473,11474,11475 ,0,0,0}, {21360,21348,21347 ,11476,11477,11478 ,0,0,0}, + {21349,21348,21357 ,11479,11477,11480 ,0,0,0}, {21356,21346,21344 ,11481,11482,11483 ,0,0,0}, + {21346,21356,21358 ,11482,11481,11484 ,0,0,0}, {21345,21359,21344 ,11485,11486,11483 ,0,0,0}, + {21356,21344,21359 ,11481,11483,11486 ,0,0,0}, {21345,20511,20512 ,11485,11487,11487 ,0,0,0}, + {20512,21359,21345 ,11487,11486,11485 ,0,0,0}, {21360,21347,21358 ,11476,11478,11484 ,0,0,0}, + {21347,21346,21358 ,11478,11482,11484 ,0,0,0}, {21350,21349,21355 ,11472,11479,11470 ,0,0,0}, + {21349,21357,21355 ,11479,11480,11470 ,0,0,0}, {21357,21348,21360 ,11480,11477,11476 ,0,0,0}, + {21362,21363,21353 ,11474,11469,11468 ,0,0,0}, {21351,21350,21354 ,11488,11472,11471 ,0,0,0}, + {21353,21352,21362 ,11468,11475,11474 ,0,0,0}, {21351,21361,21352 ,11488,11473,11475 ,0,0,0}, + {21354,21361,21351 ,11471,11473,11488 ,0,0,0}, {21363,20500,20503 ,11469,11489,11467 ,0,0,0}, + {20565,20480,20479 ,11490,324,11491 ,0,0,0}, {21364,21365,20647 ,11492,11493,11494 ,0,0,0}, + {20648,21366,20567 ,11495,11496,11497 ,0,0,0}, {21367,20586,21368 ,11498,11499,11500 ,0,0,0}, + {20643,20588,21369 ,11501,11502,11503 ,0,0,0}, {21370,20585,20645 ,11504,11505,11506 ,0,0,0}, + {20585,21370,21368 ,11505,11504,11500 ,0,0,0}, {20577,21371,20645 ,11507,11508,11506 ,0,0,0}, + {21370,20645,21371 ,11504,11506,11508 ,0,0,0}, {20577,20491,20490 ,11507,1095,1631 ,0,0,0}, + {20490,21371,20577 ,1631,11508,11507 ,0,0,0}, {20586,21367,20588 ,11499,11498,11502 ,0,0,0}, + {20586,20585,21368 ,11499,11505,11500 ,0,0,0}, {21364,20643,21369 ,11492,11501,11503 ,0,0,0}, + {21369,20588,21367 ,11503,11502,11498 ,0,0,0}, {21365,20648,20647 ,11493,11495,11494 ,0,0,0}, + {21364,20647,20643 ,11492,11494,11501 ,0,0,0}, {21366,21372,20567 ,11496,11509,11497 ,0,0,0}, + {21365,21366,20648 ,11493,11496,11495 ,0,0,0}, {20480,20565,21372 ,324,11490,11509 ,0,0,0}, + {20567,21372,20565 ,11497,11509,11490 ,0,0,0}, {20487,21364,20488 ,730,730,730 ,0,0,0}, + {20484,21366,20485 ,730,730,730 ,0,0,0}, {20490,21369,21367 ,730,730,730 ,0,0,0}, + {21371,21367,21368 ,730,730,730 ,0,0,0}, {21370,21371,21368 ,730,730,730 ,0,0,0}, + {20488,21369,20490 ,730,730,730 ,0,0,0}, {20490,21367,21371 ,730,730,730 ,0,0,0}, + {20488,21364,21369 ,730,730,730 ,0,0,0}, {20487,21365,21364 ,730,730,730 ,0,0,0}, + {20487,20485,21366 ,730,730,730 ,0,0,0}, {21366,21365,20487 ,730,730,730 ,0,0,0}, + {21372,21366,20484 ,730,730,730 ,0,0,0}, {21372,20481,20480 ,730,730,730 ,0,0,0}, + {20481,21372,20484 ,730,730,730 ,0,0,0}, {20480,20481,20473 ,730,730,730 ,0,0,0}, + {20476,20470,20474 ,730,730,730 ,0,0,0}, {20473,20470,20476 ,730,730,730 ,0,0,0}, + {20476,20480,20473 ,730,730,730 ,0,0,0}, {20658,20458,20459 ,11510,11511,11512 ,0,0,0}, + {21373,21374,20604 ,11492,11493,11513 ,0,0,0}, {20605,21375,20657 ,11514,11496,11515 ,0,0,0}, + {21376,20602,20601 ,11498,11516,11517 ,0,0,0}, {20618,20602,21377 ,11518,11516,11519 ,0,0,0}, + {21378,20662,20554 ,11504,11520,11521 ,0,0,0}, {20601,20662,21379 ,11517,11520,11500 ,0,0,0}, + {20553,21380,20554 ,11522,11508,11521 ,0,0,0}, {21378,20554,21380 ,11504,11521,11508 ,0,0,0}, + {20553,20469,20468 ,11522,11487,11523 ,0,0,0}, {20468,21380,20553 ,11523,11508,11522 ,0,0,0}, + {21376,20601,21379 ,11498,11517,11500 ,0,0,0}, {21379,20662,21378 ,11500,11520,11504 ,0,0,0}, + {20618,21377,21373 ,11518,11519,11492 ,0,0,0}, {21377,20602,21376 ,11519,11516,11498 ,0,0,0}, + {21374,20605,20604 ,11493,11514,11513 ,0,0,0}, {21373,20604,20618 ,11492,11513,11518 ,0,0,0}, + {21375,21381,20657 ,11496,11509,11515 ,0,0,0}, {21374,21375,20605 ,11493,11496,11514 ,0,0,0}, + {20458,20658,21381 ,11511,11510,11509 ,0,0,0}, {20657,21381,20658 ,11515,11509,11510 ,0,0,0}, + {20463,21373,20465 ,730,730,730 ,0,0,0}, {20460,21375,20462 ,730,730,730 ,0,0,0}, + {20468,21377,21376 ,730,730,730 ,0,0,0}, {21380,21376,21379 ,730,730,730 ,0,0,0}, + {21378,21380,21379 ,730,730,730 ,0,0,0}, {20465,21377,20468 ,730,730,730 ,0,0,0}, + {20468,21376,21380 ,730,730,730 ,0,0,0}, {20465,21373,21377 ,730,730,730 ,0,0,0}, + {20463,21374,21373 ,730,730,730 ,0,0,0}, {20463,20462,21375 ,730,730,730 ,0,0,0}, + {21375,21374,20463 ,730,730,730 ,0,0,0}, {21381,21375,20460 ,730,730,730 ,0,0,0}, + {21381,20448,20458 ,730,730,730 ,0,0,0}, {20448,21381,20460 ,730,730,730 ,0,0,0}, + {20458,20448,20451 ,730,730,730 ,0,0,0}, {20454,20452,20455 ,730,730,730 ,0,0,0}, + {20451,20452,20454 ,730,730,730 ,0,0,0}, {20454,20458,20451 ,730,730,730 ,0,0,0} +// X-Ufo 8ZollPropeller.prt + , {21382,21383,21384 ,8352,8353,8354 ,0,0,0}, {21382,21385,21386 ,8352,8355,8356 ,0,0,0}, + {21386,21383,21382 ,8356,8353,8352 ,0,0,0}, {21387,21385,21388 ,8357,8355,8358 ,0,0,0}, + {21385,21387,21386 ,8355,8357,8356 ,0,0,0}, {21389,21390,21391 ,8359,8360,8361 ,0,0,0}, + {21387,21388,21390 ,8357,8358,8360 ,0,0,0}, {21392,21393,21389 ,8362,3877,8359 ,0,0,0}, + {21392,21394,21393 ,8362,4346,3877 ,0,0,0}, {21392,21389,21391 ,8362,8359,8361 ,0,0,0}, + {21390,21388,21391 ,8360,8358,8361 ,0,0,0}, {21395,21384,21383 ,8363,8354,8353 ,0,0,0}, + {21396,21395,21397 ,8364,8363,8365 ,0,0,0}, {21395,21396,21384 ,8363,8364,8354 ,0,0,0}, + {21398,21399,21397 ,8366,8367,8365 ,0,0,0}, {21396,21397,21399 ,8364,8365,8367 ,0,0,0}, + {21398,21400,21401 ,8366,8368,8369 ,0,0,0}, {21401,21399,21398 ,8369,8367,8366 ,0,0,0}, + {21402,21400,21403 ,8370,8368,8371 ,0,0,0}, {21400,21402,21401 ,8368,8370,8369 ,0,0,0}, + {21402,21403,21404 ,8370,8371,8372 ,0,0,0}, {21405,21406,21407 ,8357,8373,8374 ,0,0,0}, + {21405,21408,21406 ,8357,8356,8373 ,0,0,0}, {21405,21407,21409 ,8357,8374,8360 ,0,0,0}, + {21409,21410,21411 ,8360,8375,8359 ,0,0,0}, {21410,21409,21407 ,8375,8360,8374 ,0,0,0}, + {21412,21411,21410 ,8376,8359,8375 ,0,0,0}, {21413,21406,21408 ,8377,8373,8356 ,0,0,0}, + {21412,21414,21415 ,8376,81,5000 ,0,0,0}, {21415,21411,21412 ,5000,8359,8376 ,0,0,0}, + {21413,21408,21416 ,8377,8356,8378 ,0,0,0}, {21416,21417,21413 ,8378,8379,8377 ,0,0,0}, + {21418,21417,21419 ,8380,8379,8363 ,0,0,0}, {21416,21419,21417 ,8378,8363,8379 ,0,0,0}, + {21420,21421,21418 ,8365,8381,8380 ,0,0,0}, {21418,21419,21420 ,8380,8363,8365 ,0,0,0}, + {21422,21423,21421 ,8366,8368,8381 ,0,0,0}, {21422,21421,21420 ,8366,8381,8365 ,0,0,0}, + {21424,21423,21425 ,8382,8368,8383 ,0,0,0}, {21423,21424,21421 ,8368,8382,8381 ,0,0,0}, + {21424,21425,21426 ,8382,8383,8384 ,0,0,0}, {21427,21428,15792 ,8385,8386,8387 ,0,0,0}, + {21429,21430,21431 ,8388,8389,8390 ,0,0,0}, {21432,21427,15792 ,8391,8385,8387 ,0,0,0}, + {21429,21431,21433 ,8388,8390,8392 ,0,0,0}, {21430,21429,21432 ,8389,8388,8391 ,0,0,0}, + {21430,21432,15792 ,8389,8391,8387 ,0,0,0}, {21434,21435,21436 ,8393,878,8394 ,0,0,0}, + {21436,21433,21437 ,8394,8392,8395 ,0,0,0}, {21434,21436,21437 ,8393,8394,8395 ,0,0,0}, + {21435,21434,21438 ,878,8393,8396 ,0,0,0}, {21437,21433,21431 ,8395,8392,8390 ,0,0,0}, + {21427,21439,21428 ,8385,8363,8386 ,0,0,0}, {21440,21439,21441 ,8397,8363,8398 ,0,0,0}, + {21439,21440,21428 ,8363,8397,8386 ,0,0,0}, {21442,21443,21441 ,8399,8400,8398 ,0,0,0}, + {21440,21441,21443 ,8397,8398,8400 ,0,0,0}, {21442,21444,21445 ,8399,8401,8402 ,0,0,0}, + {21445,21443,21442 ,8402,8400,8399 ,0,0,0}, {21446,21444,21447 ,8403,8401,126 ,0,0,0}, + {21444,21446,21445 ,8401,8403,8402 ,0,0,0}, {21448,21449,21450 ,8404,8405,8406 ,0,0,0}, + {21450,21449,21451 ,8406,8405,8407 ,0,0,0}, {21452,21449,21448 ,8408,8405,8404 ,0,0,0}, + {21453,21450,21451 ,8409,8406,8407 ,0,0,0}, {21452,21448,21454 ,8408,8404,8410 ,0,0,0}, + {21454,21455,21456 ,8410,8411,8412 ,0,0,0}, {21455,21454,21448 ,8411,8410,8404 ,0,0,0}, + {21453,21451,21457 ,8409,8407,8413 ,0,0,0}, {21458,21459,21456 ,8414,8415,8412 ,0,0,0}, + {21456,21455,21458 ,8412,8411,8414 ,0,0,0}, {21459,21460,21461 ,8415,5000,4114 ,0,0,0}, + {21462,21459,21458 ,8416,8415,8414 ,0,0,0}, {21462,21460,21459 ,8416,5000,8415 ,0,0,0}, + {21451,21463,21457 ,8407,8417,8413 ,0,0,0}, {21463,21464,21465 ,8417,8418,8419 ,0,0,0}, + {21465,21457,21463 ,8419,8413,8417 ,0,0,0}, {21466,21464,21467 ,8420,8418,8421 ,0,0,0}, + {21464,21466,21465 ,8418,8420,8419 ,0,0,0}, {21468,21469,21467 ,8422,8423,8421 ,0,0,0}, + {21466,21467,21469 ,8420,8421,8423 ,0,0,0}, {21468,21470,21471 ,8422,8424,8425 ,0,0,0}, + {21471,21469,21468 ,8425,8423,8422 ,0,0,0}, {21472,21470,21473 ,8426,8424,8427 ,0,0,0}, + {21470,21472,21471 ,8424,8426,8425 ,0,0,0}, {21472,21473,21474 ,8426,8427,8428 ,0,0,0}, + {21474,21473,21475 ,8428,8427,8429 ,0,0,0}, {21476,21477,21478 ,8430,8431,8432 ,0,0,0}, + {21479,21480,21481 ,8433,8434,8435 ,0,0,0}, {21482,21483,21484 ,8436,8437,8438 ,0,0,0}, + {21485,21486,21487 ,8439,8440,8441 ,0,0,0}, {21488,21489,21490 ,8442,8443,8444 ,0,0,0}, + {21490,21404,21488 ,8444,8445,8442 ,0,0,0}, {21491,21492,21493 ,8446,8447,8448 ,0,0,0}, + {21469,21494,21466 ,8449,8450,8451 ,0,0,0}, {21495,21493,21496 ,8452,8448,8453 ,0,0,0}, + {21497,21498,21499 ,8454,8455,8456 ,0,0,0}, {21500,21501,21502 ,8457,8458,8459 ,0,0,0}, + {21503,21504,21505 ,8460,8461,8462 ,0,0,0}, {21506,21494,21499 ,8463,8450,8456 ,0,0,0}, + {21507,21418,21421 ,8464,8465,8466 ,0,0,0}, {21508,21509,21505 ,8467,8468,8462 ,0,0,0}, + {21510,21511,21512 ,8469,8470,8471 ,0,0,0}, {21513,21514,21510 ,8472,8473,8469 ,0,0,0}, + {21515,21516,21513 ,8474,8475,8472 ,0,0,0}, {21517,21513,21516 ,8476,8472,8475 ,0,0,0}, + {21518,21516,21515 ,8477,8475,8474 ,0,0,0}, {21519,21520,21521 ,8478,8479,8480 ,0,0,0}, + {21522,21507,21511 ,8481,8464,8470 ,0,0,0}, {21523,21524,21519 ,8482,8483,8478 ,0,0,0}, + {21472,21474,21499 ,8484,8485,8456 ,0,0,0}, {21501,21525,21502 ,8458,8486,8459 ,0,0,0}, + {21492,21526,21493 ,8447,8487,8448 ,0,0,0}, {21527,21528,21529 ,8488,8489,8490 ,0,0,0}, + {21450,21530,21448 ,8491,8492,8493 ,0,0,0}, {21487,21526,21531 ,8441,8487,8494 ,0,0,0}, + {21532,21401,21533 ,8495,8496,8497 ,0,0,0}, {21534,21535,21485 ,8498,8499,8439 ,0,0,0}, + {21480,21536,21537 ,8434,8500,8501 ,0,0,0}, {21538,21539,21540 ,8502,8503,8504 ,0,0,0}, + {21479,21481,21541 ,8433,8435,8505 ,0,0,0}, {21477,21476,21542 ,8431,8430,8506 ,0,0,0}, + {21543,21481,21538 ,8507,8435,8502 ,0,0,0}, {21544,21545,21546 ,8508,8509,8510 ,0,0,0}, + {21545,21542,21476 ,8509,8506,8430 ,0,0,0}, {21384,21547,21382 ,8511,8512,8513 ,0,0,0}, + {21548,21478,21549 ,8514,8432,8515 ,0,0,0}, {21479,21550,21551 ,8433,8516,8517 ,0,0,0}, + {21535,21460,21552 ,8499,8518,8519 ,0,0,0}, {21538,21481,21480 ,8502,8435,8434 ,0,0,0}, + {21538,21537,21553 ,8502,8501,8520 ,0,0,0}, {21480,21537,21538 ,8434,8501,8502 ,0,0,0}, + {21554,21555,21483 ,8521,8522,8437 ,0,0,0}, {21543,21482,21556 ,8507,8436,8523 ,0,0,0}, + {21478,21392,21391 ,8432,8524,8525 ,0,0,0}, {21557,21555,21554 ,8526,8522,8521 ,0,0,0}, + {21477,21557,21554 ,8431,8526,8521 ,0,0,0}, {21545,21476,21546 ,8509,8430,8510 ,0,0,0}, + {21542,21557,21477 ,8506,8526,8431 ,0,0,0}, {21549,21478,21391 ,8515,8432,8525 ,0,0,0}, + {21478,21548,21558 ,8432,8514,8527 ,0,0,0}, {21547,21549,21382 ,8512,8515,8513 ,0,0,0}, + {21549,21547,21548 ,8515,8512,8514 ,0,0,0}, {21396,21532,21384 ,8528,8495,8511 ,0,0,0}, + {21401,21532,21399 ,8496,8495,8529 ,0,0,0}, {21532,21547,21384 ,8495,8512,8511 ,0,0,0}, + {21533,21559,21532 ,8497,8530,8495 ,0,0,0}, {21402,21533,21401 ,8531,8497,8496 ,0,0,0}, + {21533,21404,21490 ,8497,8445,8444 ,0,0,0}, {21453,21560,21530 ,8532,8533,8492 ,0,0,0}, + {21561,21496,21493 ,8534,8453,8448 ,0,0,0}, {21501,21562,21563 ,8458,8535,8536 ,0,0,0}, + {21412,21562,21414 ,8537,8535,8538 ,0,0,0}, {21561,21564,21565 ,8534,8539,8540 ,0,0,0}, + {21495,21491,21493 ,8452,8446,8448 ,0,0,0}, {21450,21453,21530 ,8491,8532,8492 ,0,0,0}, + {21492,21566,21526 ,8447,8541,8487 ,0,0,0}, {21493,21526,21567 ,8448,8487,8542 ,0,0,0}, + {21526,21487,21486 ,8487,8441,8440 ,0,0,0}, {21535,21486,21485 ,8499,8440,8439 ,0,0,0}, + {21526,21486,21568 ,8487,8440,8543 ,0,0,0}, {21569,21552,21527 ,8544,8519,8488 ,0,0,0}, + {21535,21570,21486 ,8499,8545,8440 ,0,0,0}, {21480,21551,21490 ,8434,8517,8444 ,0,0,0}, + {21550,21570,21569 ,8516,8545,8544 ,0,0,0}, {21529,21533,21490 ,8490,8497,8444 ,0,0,0}, + {21490,21489,21480 ,8444,8443,8434 ,0,0,0}, {21529,21571,21533 ,8490,8546,8497 ,0,0,0}, + {21572,21529,21528 ,8547,8490,8489 ,0,0,0}, {21530,21573,21528 ,8492,8548,8489 ,0,0,0}, + {21530,21560,21574 ,8492,8533,8549 ,0,0,0}, {21453,21457,21560 ,8532,8550,8533 ,0,0,0}, + {21457,21465,21560 ,8550,8551,8533 ,0,0,0}, {21560,21494,21575 ,8533,8450,8552 ,0,0,0}, + {21469,21499,21494 ,8449,8456,8450 ,0,0,0}, {21471,21499,21469 ,8553,8456,8449 ,0,0,0}, + {21499,21471,21472 ,8456,8553,8484 ,0,0,0}, {21560,21466,21494 ,8533,8451,8450 ,0,0,0}, + {21474,21497,21499 ,8485,8454,8456 ,0,0,0}, {21576,21562,21577 ,8554,8535,8555 ,0,0,0}, + {21524,21523,21578 ,8483,8482,8556 ,0,0,0}, {21579,21510,21519 ,8557,8469,8478 ,0,0,0}, + {21519,21510,21580 ,8478,8469,8558 ,0,0,0}, {21580,21520,21519 ,8558,8479,8478 ,0,0,0}, + {21519,21524,21579 ,8478,8483,8557 ,0,0,0}, {21581,21506,21498 ,8559,8463,8455 ,0,0,0}, + {21525,21524,21578 ,8486,8483,8556 ,0,0,0}, {21525,21578,21582 ,8486,8556,8560 ,0,0,0}, + {21502,21525,21583 ,8459,8486,8561 ,0,0,0}, {21500,21414,21501 ,8457,8538,8458 ,0,0,0}, + {21584,21561,21563 ,8562,8534,8536 ,0,0,0}, {21562,21501,21414 ,8535,8458,8538 ,0,0,0}, + {21497,21474,21585 ,8454,8485,8563 ,0,0,0}, {21496,21497,21586 ,8453,8454,8564 ,0,0,0}, + {21576,21498,21584 ,8554,8455,8562 ,0,0,0}, {21576,21587,21581 ,8554,8565,8559 ,0,0,0}, + {21588,21417,21418 ,8566,8567,8465 ,0,0,0}, {21588,21413,21417 ,8566,8568,8567 ,0,0,0}, + {21589,21588,21509 ,8569,8566,8468 ,0,0,0}, {21587,21577,21589 ,8565,8555,8569 ,0,0,0}, + {21418,21507,21588 ,8465,8464,8566 ,0,0,0}, {21426,21512,21511 ,8570,8471,8470 ,0,0,0}, + {21554,21590,21477 ,8521,8571,8431 ,0,0,0}, {21484,21483,21555 ,8438,8437,8522 ,0,0,0}, + {21543,21591,21483 ,8507,8572,8437 ,0,0,0}, {21394,21392,21590 ,8573,8524,8571 ,0,0,0}, + {21591,21590,21554 ,8572,8571,8521 ,0,0,0}, {21590,21392,21478 ,8571,8524,8432 ,0,0,0}, + {21477,21590,21478 ,8431,8571,8432 ,0,0,0}, {21558,21546,21476 ,8527,8510,8430 ,0,0,0}, + {21482,21543,21483 ,8436,8507,8437 ,0,0,0}, {21556,21541,21481 ,8523,8505,8435 ,0,0,0}, + {21590,21592,21593 ,8571,8574,8575 ,0,0,0}, {21483,21591,21554 ,8437,8572,8521 ,0,0,0}, + {21540,21591,21538 ,8504,8572,8502 ,0,0,0}, {21394,21590,21593 ,8573,8571,8575 ,0,0,0}, + {21391,21388,21549 ,8525,8576,8515 ,0,0,0}, {21558,21476,21478 ,8527,8430,8432 ,0,0,0}, + {21556,21481,21543 ,8523,8435,8507 ,0,0,0}, {21541,21594,21479 ,8505,8577,8433 ,0,0,0}, + {21539,21538,21553 ,8503,8502,8520 ,0,0,0}, {21543,21538,21591 ,8507,8502,8572 ,0,0,0}, + {21592,21591,21540 ,8574,8572,8504 ,0,0,0}, {21591,21592,21590 ,8572,8574,8571 ,0,0,0}, + {21388,21385,21549 ,8576,8578,8515 ,0,0,0}, {21549,21385,21382 ,8515,8578,8513 ,0,0,0}, + {21595,21550,21594 ,8579,8516,8577 ,0,0,0}, {21595,21596,21570 ,8579,8580,8545 ,0,0,0}, + {21536,21480,21597 ,8500,8434,8581 ,0,0,0}, {21489,21597,21480 ,8443,8581,8434 ,0,0,0}, + {21547,21532,21559 ,8512,8495,8530 ,0,0,0}, {21396,21399,21532 ,8528,8529,8495 ,0,0,0}, + {21550,21479,21594 ,8516,8433,8577 ,0,0,0}, {21598,21460,21535 ,8582,8518,8499 ,0,0,0}, + {21490,21551,21527 ,8444,8517,8488 ,0,0,0}, {21479,21551,21480 ,8433,8517,8434 ,0,0,0}, + {21527,21551,21569 ,8488,8517,8544 ,0,0,0}, {21404,21533,21402 ,8445,8497,8531 ,0,0,0}, + {21490,21527,21529 ,8444,8488,8490 ,0,0,0}, {21533,21571,21559 ,8497,8546,8530 ,0,0,0}, + {21595,21570,21550 ,8579,8545,8516 ,0,0,0}, {21599,21570,21596 ,8583,8545,8580 ,0,0,0}, + {21460,21462,21552 ,8518,8584,8519 ,0,0,0}, {21550,21569,21551 ,8516,8544,8517 ,0,0,0}, + {21535,21552,21569 ,8499,8519,8544 ,0,0,0}, {21448,21530,21455 ,8493,8492,8585 ,0,0,0}, + {21528,21527,21552 ,8489,8488,8519 ,0,0,0}, {21571,21529,21572 ,8546,8490,8547 ,0,0,0}, + {21570,21599,21486 ,8545,8583,8440 ,0,0,0}, {21568,21486,21599 ,8543,8440,8583 ,0,0,0}, + {21598,21535,21534 ,8582,8499,8498 ,0,0,0}, {21570,21535,21569 ,8545,8499,8544 ,0,0,0}, + {21462,21458,21552 ,8584,8586,8519 ,0,0,0}, {21552,21458,21455 ,8519,8586,8585 ,0,0,0}, + {21455,21528,21552 ,8585,8489,8519 ,0,0,0}, {21572,21528,21573 ,8547,8489,8548 ,0,0,0}, + {21526,21568,21567 ,8487,8543,8542 ,0,0,0}, {21566,21531,21526 ,8541,8494,8487 ,0,0,0}, + {21573,21530,21574 ,8548,8492,8549 ,0,0,0}, {21455,21530,21528 ,8585,8492,8489 ,0,0,0}, + {21567,21564,21493 ,8542,8539,8448 ,0,0,0}, {21493,21564,21561 ,8448,8539,8534 ,0,0,0}, + {21466,21560,21465 ,8451,8533,8551 ,0,0,0}, {21560,21575,21574 ,8533,8552,8549 ,0,0,0}, + {21561,21497,21496 ,8534,8454,8453 ,0,0,0}, {21565,21600,21563 ,8540,8587,8536 ,0,0,0}, + {21410,21562,21412 ,8588,8535,8537 ,0,0,0}, {21586,21497,21585 ,8564,8454,8563 ,0,0,0}, + {21584,21497,21561 ,8562,8454,8534 ,0,0,0}, {21601,21494,21506 ,8589,8450,8463 ,0,0,0}, + {21499,21498,21506 ,8456,8455,8463 ,0,0,0}, {21575,21494,21601 ,8552,8450,8589 ,0,0,0}, + {21565,21563,21561 ,8540,8536,8534 ,0,0,0}, {21600,21602,21501 ,8587,8590,8458 ,0,0,0}, + {21406,21577,21407 ,8591,8555,8592 ,0,0,0}, {21497,21584,21498 ,8454,8562,8455 ,0,0,0}, + {21584,21563,21562 ,8562,8536,8535 ,0,0,0}, {21506,21603,21604 ,8463,8593,8594 ,0,0,0}, + {21498,21576,21581 ,8455,8554,8559 ,0,0,0}, {21601,21506,21604 ,8589,8463,8594 ,0,0,0}, + {21600,21501,21563 ,8587,8458,8536 ,0,0,0}, {21602,21525,21501 ,8590,8486,8458 ,0,0,0}, + {21577,21410,21407 ,8555,8588,8592 ,0,0,0}, {21584,21562,21576 ,8562,8535,8554 ,0,0,0}, + {21562,21410,21577 ,8535,8588,8555 ,0,0,0}, {21581,21605,21603 ,8559,8595,8593 ,0,0,0}, + {21576,21577,21587 ,8554,8555,8565 ,0,0,0}, {21603,21506,21581 ,8593,8463,8559 ,0,0,0}, + {21524,21525,21602 ,8483,8486,8590 ,0,0,0}, {21582,21583,21525 ,8560,8561,8486 ,0,0,0}, + {21588,21406,21413 ,8566,8591,8568 ,0,0,0}, {21587,21606,21605 ,8565,8596,8595 ,0,0,0}, + {21577,21588,21589 ,8555,8566,8569 ,0,0,0}, {21605,21581,21587 ,8595,8559,8565 ,0,0,0}, + {21519,21521,21523 ,8478,8480,8482 ,0,0,0}, {21579,21607,21510 ,8557,8597,8469 ,0,0,0}, + {21421,21424,21511 ,8466,8598,8470 ,0,0,0}, {21421,21511,21507 ,8466,8470,8464 ,0,0,0}, + {21589,21508,21606 ,8569,8467,8596 ,0,0,0}, {21588,21577,21406 ,8566,8555,8591 ,0,0,0}, + {21588,21507,21509 ,8566,8464,8468 ,0,0,0}, {21606,21587,21589 ,8596,8565,8569 ,0,0,0}, + {21510,21512,21580 ,8469,8471,8558 ,0,0,0}, {21607,21515,21513 ,8597,8474,8472 ,0,0,0}, + {21608,21504,21503 ,8599,8461,8460 ,0,0,0}, {21426,21511,21424 ,8570,8470,8598 ,0,0,0}, + {21511,21514,21522 ,8470,8473,8481 ,0,0,0}, {21503,21509,21507 ,8460,8468,8464 ,0,0,0}, + {21522,21503,21507 ,8481,8460,8464 ,0,0,0}, {21508,21589,21509 ,8467,8569,8468 ,0,0,0}, + {21607,21513,21510 ,8597,8472,8469 ,0,0,0}, {21510,21514,21511 ,8469,8473,8470 ,0,0,0}, + {21517,21609,21514 ,8476,8600,8473 ,0,0,0}, {21513,21517,21514 ,8472,8476,8473 ,0,0,0}, + {21609,21608,21522 ,8600,8599,8481 ,0,0,0}, {21514,21609,21522 ,8473,8600,8481 ,0,0,0}, + {21608,21503,21522 ,8599,8460,8481 ,0,0,0}, {21505,21509,21503 ,8462,8468,8460 ,0,0,0}, + {21610,21611,21612 ,8601,8602,8603 ,0,0,0}, {21613,21614,21611 ,8604,8605,8602 ,0,0,0}, + {21615,21616,21617 ,8606,8607,8608 ,0,0,0}, {21618,21619,21620 ,8609,8610,8611 ,0,0,0}, + {21621,21622,21623 ,8612,8613,8614 ,0,0,0}, {21624,21625,21626 ,8615,8616,8617 ,0,0,0}, + {21627,21628,21629 ,8618,8619,8620 ,0,0,0}, {21630,21631,21632 ,8621,8622,8623 ,0,0,0}, + {21633,21634,21635 ,8624,8625,8626 ,0,0,0}, {21636,21637,21638 ,8627,8628,8629 ,0,0,0}, + {21639,21640,21633 ,8630,8631,8624 ,0,0,0}, {21633,21635,21639 ,8624,8626,8630 ,0,0,0}, + {21640,21641,21642 ,8631,8632,8633 ,0,0,0}, {21641,21640,21639 ,8632,8631,8630 ,0,0,0}, + {21643,21642,21644 ,8634,8633,8635 ,0,0,0}, {21641,21644,21642 ,8632,8635,8633 ,0,0,0}, + {21645,21646,21643 ,8636,8637,8634 ,0,0,0}, {21643,21644,21645 ,8634,8635,8636 ,0,0,0}, + {21647,21646,21645 ,8638,8637,8636 ,0,0,0}, {21634,21638,21635 ,8625,8629,8626 ,0,0,0}, + {21636,21628,21637 ,8627,8619,8628 ,0,0,0}, {21634,21636,21638 ,8625,8627,8629 ,0,0,0}, + {21627,21629,21630 ,8618,8620,8621 ,0,0,0}, {21637,21628,21627 ,8628,8619,8618 ,0,0,0}, + {21632,21631,21623 ,8623,8622,8614 ,0,0,0}, {21630,21629,21631 ,8621,8620,8622 ,0,0,0}, + {21625,21622,21621 ,8616,8613,8612 ,0,0,0}, {21622,21632,21623 ,8613,8623,8614 ,0,0,0}, + {21648,21624,21626 ,8639,8615,8617 ,0,0,0}, {21626,21625,21621 ,8617,8616,8612 ,0,0,0}, + {21615,21648,21616 ,8606,8639,8607 ,0,0,0}, {21648,21615,21624 ,8639,8606,8615 ,0,0,0}, + {21617,21618,21620 ,8608,8609,8611 ,0,0,0}, {21616,21618,21617 ,8607,8609,8608 ,0,0,0}, + {21613,21619,21614 ,8604,8610,8605 ,0,0,0}, {21620,21619,21613 ,8611,8610,8604 ,0,0,0}, + {21612,21649,21610 ,8603,8640,8601 ,0,0,0}, {21611,21614,21612 ,8602,8605,8603 ,0,0,0}, + {21650,21651,21611 ,8641,8642,8643 ,0,0,0}, {21652,21613,21651 ,8644,8645,8642 ,0,0,0}, + {21624,21615,21653 ,8646,8647,8648 ,0,0,0}, {21617,21620,21654 ,8649,8650,8651 ,0,0,0}, + {21622,21655,21632 ,8652,8653,8654 ,0,0,0}, {21656,21657,21625 ,8655,8656,8657 ,0,0,0}, + {21658,21637,21627 ,8658,8659,8660 ,0,0,0}, {21659,21630,21660 ,8661,8662,8663 ,0,0,0}, + {21639,21635,21661 ,8664,8665,8666 ,0,0,0}, {21638,21662,21663 ,8667,8668,8669 ,0,0,0}, + {21664,21641,21639 ,8670,8671,8664 ,0,0,0}, {21639,21661,21664 ,8664,8666,8670 ,0,0,0}, + {21641,21665,21644 ,8671,8672,8673 ,0,0,0}, {21665,21641,21664 ,8672,8671,8670 ,0,0,0}, + {21645,21644,21666 ,8674,8673,8675 ,0,0,0}, {21665,21666,21644 ,8672,8675,8673 ,0,0,0}, + {21667,21647,21645 ,8676,8638,8674 ,0,0,0}, {21645,21666,21667 ,8674,8675,8676 ,0,0,0}, + {21668,21647,21667 ,8677,8638,8676 ,0,0,0}, {21635,21663,21661 ,8665,8669,8666 ,0,0,0}, + {21638,21637,21662 ,8667,8659,8668 ,0,0,0}, {21635,21638,21663 ,8665,8667,8669 ,0,0,0}, + {21658,21627,21659 ,8658,8660,8661 ,0,0,0}, {21662,21637,21658 ,8668,8659,8658 ,0,0,0}, + {21660,21630,21632 ,8663,8662,8654 ,0,0,0}, {21659,21627,21630 ,8661,8660,8662 ,0,0,0}, + {21657,21655,21622 ,8656,8653,8652 ,0,0,0}, {21655,21660,21632 ,8653,8663,8654 ,0,0,0}, + {21624,21656,21625 ,8646,8655,8657 ,0,0,0}, {21625,21657,21622 ,8657,8656,8652 ,0,0,0}, + {21615,21669,21653 ,8647,8678,8648 ,0,0,0}, {21624,21653,21656 ,8646,8648,8655 ,0,0,0}, + {21654,21669,21617 ,8651,8678,8649 ,0,0,0}, {21615,21617,21669 ,8647,8649,8678 ,0,0,0}, + {21652,21620,21613 ,8644,8650,8645 ,0,0,0}, {21654,21620,21652 ,8651,8650,8644 ,0,0,0}, + {21611,21610,21650 ,8643,8601,8641 ,0,0,0}, {21651,21613,21611 ,8642,8645,8643 ,0,0,0}, + {21670,21671,21651 ,8679,8680,8681 ,0,0,0}, {21654,21652,21672 ,8651,8644,8682 ,0,0,0}, + {21656,21653,21673 ,8683,8684,8685 ,0,0,0}, {21669,21674,21675 ,8678,8686,8687 ,0,0,0}, + {21655,21676,21660 ,8688,8689,8690 ,0,0,0}, {21677,21678,21657 ,8691,8692,8693 ,0,0,0}, + {21679,21662,21680 ,8694,8695,8696 ,0,0,0}, {21658,21659,21681 ,8697,8698,8699 ,0,0,0}, + {21664,21661,21682 ,8700,8701,8702 ,0,0,0}, {21663,21683,21661 ,8703,8704,8701 ,0,0,0}, + {21684,21665,21664 ,8705,8706,8700 ,0,0,0}, {21664,21682,21684 ,8700,8702,8705 ,0,0,0}, + {21665,21685,21666 ,8706,8707,8675 ,0,0,0}, {21685,21665,21684 ,8707,8706,8705 ,0,0,0}, + {21667,21666,21686 ,8708,8675,8709 ,0,0,0}, {21685,21686,21666 ,8707,8709,8675 ,0,0,0}, + {21686,21687,21668 ,8709,8710,8677 ,0,0,0}, {21668,21667,21686 ,8677,8708,8709 ,0,0,0}, + {21682,21661,21683 ,8702,8701,8704 ,0,0,0}, {21663,21662,21679 ,8703,8695,8694 ,0,0,0}, + {21663,21679,21683 ,8703,8694,8704 ,0,0,0}, {21680,21658,21681 ,8696,8697,8699 ,0,0,0}, + {21662,21658,21680 ,8695,8697,8696 ,0,0,0}, {21688,21659,21660 ,8711,8698,8690 ,0,0,0}, + {21681,21659,21688 ,8699,8698,8711 ,0,0,0}, {21678,21676,21655 ,8692,8689,8688 ,0,0,0}, + {21676,21688,21660 ,8689,8711,8690 ,0,0,0}, {21656,21677,21657 ,8683,8691,8693 ,0,0,0}, + {21657,21678,21655 ,8693,8692,8688 ,0,0,0}, {21653,21675,21673 ,8684,8687,8685 ,0,0,0}, + {21656,21673,21677 ,8683,8685,8691 ,0,0,0}, {21669,21654,21674 ,8678,8651,8686 ,0,0,0}, + {21653,21669,21675 ,8684,8678,8687 ,0,0,0}, {21672,21652,21671 ,8682,8644,8680 ,0,0,0}, + {21674,21654,21672 ,8686,8651,8682 ,0,0,0}, {21670,21651,21650 ,8679,8681,8641 ,0,0,0}, + {21671,21652,21651 ,8680,8644,8681 ,0,0,0}, {21689,21690,21671 ,8712,8713,8714 ,0,0,0}, + {21674,21672,21691 ,8715,8716,8717 ,0,0,0}, {21677,21673,21692 ,8718,8719,8720 ,0,0,0}, + {21675,21674,21693 ,8721,8715,8722 ,0,0,0}, {21676,21694,21688 ,8723,8724,8725 ,0,0,0}, + {21695,21696,21678 ,8726,8727,8728 ,0,0,0}, {21697,21679,21680 ,8729,8730,8731 ,0,0,0}, + {21698,21681,21699 ,8732,8733,8734 ,0,0,0}, {21700,21682,21701 ,8735,8736,8737 ,0,0,0}, + {21683,21702,21701 ,8738,8739,8737 ,0,0,0}, {21700,21703,21684 ,8735,8740,8741 ,0,0,0}, + {21684,21682,21700 ,8741,8736,8735 ,0,0,0}, {21685,21703,21704 ,8742,8740,8743 ,0,0,0}, + {21703,21685,21684 ,8740,8742,8741 ,0,0,0}, {21705,21686,21704 ,8744,8745,8743 ,0,0,0}, + {21685,21704,21686 ,8742,8743,8745 ,0,0,0}, {21705,21706,21687 ,8744,8746,8710 ,0,0,0}, + {21687,21686,21705 ,8710,8745,8744 ,0,0,0}, {21701,21682,21683 ,8737,8736,8738 ,0,0,0}, + {21702,21679,21697 ,8739,8730,8729 ,0,0,0}, {21683,21679,21702 ,8738,8730,8739 ,0,0,0}, + {21698,21680,21681 ,8732,8731,8733 ,0,0,0}, {21697,21680,21698 ,8729,8731,8732 ,0,0,0}, + {21694,21699,21688 ,8724,8734,8725 ,0,0,0}, {21699,21681,21688 ,8734,8733,8725 ,0,0,0}, + {21678,21696,21676 ,8728,8727,8723 ,0,0,0}, {21696,21694,21676 ,8727,8724,8723 ,0,0,0}, + {21677,21692,21695 ,8718,8720,8726 ,0,0,0}, {21677,21695,21678 ,8718,8726,8728 ,0,0,0}, + {21673,21675,21707 ,8719,8721,8747 ,0,0,0}, {21673,21707,21692 ,8719,8747,8720 ,0,0,0}, + {21693,21674,21691 ,8722,8715,8717 ,0,0,0}, {21707,21675,21693 ,8747,8721,8722 ,0,0,0}, + {21690,21672,21671 ,8713,8716,8714 ,0,0,0}, {21691,21672,21690 ,8717,8716,8713 ,0,0,0}, + {21689,21671,21670 ,8712,8714,8679 ,0,0,0}, {21704,21708,21709 ,8748,8749,8750 ,0,0,0}, + {21706,21705,21710 ,8746,8751,8752 ,0,0,0}, {21711,21701,21712 ,8753,8754,8755 ,0,0,0}, + {21700,21713,21703 ,8756,8757,8758 ,0,0,0}, {21699,21714,21698 ,8759,8760,8761 ,0,0,0}, + {21697,21715,21702 ,8762,8763,8764 ,0,0,0}, {21716,21696,21695 ,8765,8766,8767 ,0,0,0}, + {21717,21694,21718 ,8768,8769,8770 ,0,0,0}, {21719,21707,21720 ,8771,8772,8773 ,0,0,0}, + {21692,21719,21721 ,8774,8771,8775 ,0,0,0}, {21722,21720,21693 ,8776,8773,8777 ,0,0,0}, + {21707,21693,21720 ,8772,8777,8773 ,0,0,0}, {21691,21723,21722 ,8778,8779,8776 ,0,0,0}, + {21722,21693,21691 ,8776,8777,8778 ,0,0,0}, {21723,21690,21724 ,8779,8780,8781 ,0,0,0}, + {21690,21723,21691 ,8780,8779,8778 ,0,0,0}, {21721,21695,21692 ,8775,8767,8774 ,0,0,0}, + {21724,21690,21689 ,8781,8780,8782 ,0,0,0}, {21719,21692,21707 ,8771,8774,8772 ,0,0,0}, + {21716,21718,21696 ,8765,8770,8766 ,0,0,0}, {21721,21716,21695 ,8775,8765,8767 ,0,0,0}, + {21694,21717,21699 ,8769,8768,8759 ,0,0,0}, {21696,21718,21694 ,8766,8770,8769 ,0,0,0}, + {21698,21714,21725 ,8761,8760,8783 ,0,0,0}, {21699,21717,21714 ,8759,8768,8760 ,0,0,0}, + {21725,21715,21697 ,8783,8763,8762 ,0,0,0}, {21697,21698,21725 ,8762,8761,8783 ,0,0,0}, + {21712,21701,21702 ,8755,8754,8764 ,0,0,0}, {21712,21702,21715 ,8755,8764,8763 ,0,0,0}, + {21711,21713,21700 ,8753,8757,8756 ,0,0,0}, {21711,21700,21701 ,8753,8756,8754 ,0,0,0}, + {21703,21708,21704 ,8758,8749,8748 ,0,0,0}, {21713,21708,21703 ,8757,8749,8758 ,0,0,0}, + {21705,21709,21710 ,8751,8750,8752 ,0,0,0}, {21704,21709,21705 ,8748,8750,8751 ,0,0,0}, + {21706,21710,21726 ,8746,8752,8784 ,0,0,0}, {21727,21728,21729 ,8785,8786,8787 ,0,0,0}, + {21730,21731,21732 ,8788,8789,8790 ,0,0,0}, {21731,21733,21734 ,8789,8791,8792 ,0,0,0}, + {21734,21732,21731 ,8792,8790,8789 ,0,0,0}, {21731,21729,21735 ,8789,8787,8793 ,0,0,0}, + {21733,21736,21734 ,8791,8794,8792 ,0,0,0}, {21737,21738,21739 ,8795,8796,8797 ,0,0,0}, + {21689,21728,21724 ,8782,8786,8798 ,0,0,0}, {21740,21741,21742 ,8799,8800,8801 ,0,0,0}, + {21720,21722,21743 ,8802,8803,8804 ,0,0,0}, {21744,21745,21746 ,8805,8806,8807 ,0,0,0}, + {21721,21747,21716 ,8808,8809,8810 ,0,0,0}, {21748,21749,21715 ,8811,8812,8813 ,0,0,0}, + {21750,21751,21746 ,8814,8815,8807 ,0,0,0}, {21752,21753,21754 ,8816,8817,8818 ,0,0,0}, + {21755,21749,21756 ,8819,8812,8820 ,0,0,0}, {21709,21753,21710 ,8821,8817,8822 ,0,0,0}, + {21710,21757,21726 ,8822,8823,8824 ,0,0,0}, {21758,21759,21754 ,8825,8826,8818 ,0,0,0}, + {21710,21753,21757 ,8822,8817,8823 ,0,0,0}, {21760,21752,21761 ,8827,8816,8828 ,0,0,0}, + {21758,21754,21708 ,8825,8818,8829 ,0,0,0}, {21758,21762,21763 ,8825,8830,8831 ,0,0,0}, + {21713,21762,21758 ,8832,8830,8825 ,0,0,0}, {21712,21749,21755 ,8833,8812,8819 ,0,0,0}, + {21762,21755,21764 ,8830,8819,8834 ,0,0,0}, {21762,21711,21755 ,8830,8835,8819 ,0,0,0}, + {21765,21748,21751 ,8836,8811,8815 ,0,0,0}, {21766,21749,21748 ,8837,8812,8811 ,0,0,0}, + {21751,21714,21717 ,8815,8838,8839 ,0,0,0}, {21751,21748,21725 ,8815,8811,8840 ,0,0,0}, + {21716,21744,21718 ,8810,8805,8841 ,0,0,0}, {21718,21746,21717 ,8841,8807,8839 ,0,0,0}, + {21740,21767,21747 ,8799,8842,8809 ,0,0,0}, {21747,21768,21744 ,8809,8843,8805 ,0,0,0}, + {21719,21720,21741 ,8844,8802,8800 ,0,0,0}, {21721,21719,21740 ,8808,8844,8799 ,0,0,0}, + {21738,21769,21743 ,8796,8845,8804 ,0,0,0}, {21742,21741,21769 ,8801,8800,8845 ,0,0,0}, + {21770,21723,21724 ,8846,8847,8798 ,0,0,0}, {21739,21722,21723 ,8797,8803,8847 ,0,0,0}, + {21771,21735,21729 ,8848,8793,8787 ,0,0,0}, {21770,21727,21737 ,8846,8785,8795 ,0,0,0}, + {21729,21728,21771 ,8787,8786,8848 ,0,0,0}, {21733,21731,21735 ,8791,8789,8793 ,0,0,0}, + {21772,21730,21732 ,8849,8788,8790 ,0,0,0}, {21773,21730,21772 ,8850,8788,8849 ,0,0,0}, + {21728,21689,21771 ,8786,8782,8848 ,0,0,0}, {21729,21730,21727 ,8787,8788,8785 ,0,0,0}, + {21724,21728,21770 ,8798,8786,8846 ,0,0,0}, {21731,21730,21729 ,8789,8788,8787 ,0,0,0}, + {21774,21773,21772 ,8851,8850,8849 ,0,0,0}, {21775,21773,21774 ,8852,8850,8851 ,0,0,0}, + {21728,21727,21770 ,8786,8785,8846 ,0,0,0}, {21727,21773,21737 ,8785,8850,8795 ,0,0,0}, + {21723,21770,21739 ,8847,8846,8797 ,0,0,0}, {21730,21773,21727 ,8788,8850,8785 ,0,0,0}, + {21776,21775,21774 ,8853,8852,8851 ,0,0,0}, {21777,21775,21776 ,8854,8852,8853 ,0,0,0}, + {21770,21737,21739 ,8846,8795,8797 ,0,0,0}, {21737,21775,21738 ,8795,8852,8796 ,0,0,0}, + {21722,21739,21743 ,8803,8797,8804 ,0,0,0}, {21773,21775,21737 ,8850,8852,8795 ,0,0,0}, + {21778,21777,21776 ,8855,8854,8853 ,0,0,0}, {21779,21777,21778 ,8856,8854,8855 ,0,0,0}, + {21739,21738,21743 ,8797,8796,8804 ,0,0,0}, {21738,21777,21769 ,8796,8854,8845 ,0,0,0}, + {21720,21743,21741 ,8802,8804,8800 ,0,0,0}, {21775,21777,21738 ,8852,8854,8796 ,0,0,0}, + {21780,21779,21778 ,8857,8856,8855 ,0,0,0}, {21781,21779,21780 ,8858,8856,8857 ,0,0,0}, + {21743,21769,21741 ,8804,8845,8800 ,0,0,0}, {21769,21779,21742 ,8845,8856,8801 ,0,0,0}, + {21719,21741,21740 ,8844,8800,8799 ,0,0,0}, {21777,21779,21769 ,8854,8856,8845 ,0,0,0}, + {21782,21781,21780 ,8859,8858,8857 ,0,0,0}, {21783,21784,21761 ,8860,8861,8828 ,0,0,0}, + {21785,21781,21782 ,8862,8858,8859 ,0,0,0}, {21742,21781,21767 ,8801,8858,8842 ,0,0,0}, + {21721,21740,21747 ,8808,8799,8809 ,0,0,0}, {21779,21781,21742 ,8856,8858,8801 ,0,0,0}, + {21786,21785,21782 ,8863,8862,8859 ,0,0,0}, {21787,21788,21785 ,8864,8865,8862 ,0,0,0}, + {21742,21767,21740 ,8801,8842,8799 ,0,0,0}, {21767,21785,21768 ,8842,8862,8843 ,0,0,0}, + {21716,21747,21744 ,8810,8809,8805 ,0,0,0}, {21781,21785,21767 ,8858,8862,8842 ,0,0,0}, + {21786,21787,21785 ,8863,8864,8862 ,0,0,0}, {21789,21790,21788 ,8866,8867,8865 ,0,0,0}, + {21767,21768,21747 ,8842,8843,8809 ,0,0,0}, {21768,21788,21745 ,8843,8865,8806 ,0,0,0}, + {21718,21744,21746 ,8841,8805,8807 ,0,0,0}, {21785,21788,21768 ,8862,8865,8843 ,0,0,0}, + {21787,21789,21788 ,8864,8866,8865 ,0,0,0}, {21791,21792,21790 ,8868,8869,8867 ,0,0,0}, + {21768,21745,21744 ,8843,8806,8805 ,0,0,0}, {21790,21750,21745 ,8867,8814,8806 ,0,0,0}, + {21717,21746,21751 ,8839,8807,8815 ,0,0,0}, {21788,21790,21745 ,8865,8867,8806 ,0,0,0}, + {21789,21791,21790 ,8866,8868,8867 ,0,0,0}, {21792,21793,21794 ,8869,8870,8871 ,0,0,0}, + {21745,21750,21746 ,8806,8814,8807 ,0,0,0}, {21792,21765,21750 ,8869,8836,8814 ,0,0,0}, + {21725,21714,21751 ,8840,8838,8815 ,0,0,0}, {21790,21792,21750 ,8867,8869,8814 ,0,0,0}, + {21791,21793,21792 ,8868,8870,8869 ,0,0,0}, {21794,21795,21796 ,8871,8872,8873 ,0,0,0}, + {21750,21765,21751 ,8814,8836,8815 ,0,0,0}, {21794,21766,21765 ,8871,8837,8836 ,0,0,0}, + {21715,21725,21748 ,8813,8840,8811 ,0,0,0}, {21792,21794,21765 ,8869,8871,8836 ,0,0,0}, + {21793,21795,21794 ,8870,8872,8871 ,0,0,0}, {21796,21797,21798 ,8873,8874,8875 ,0,0,0}, + {21765,21766,21748 ,8836,8837,8811 ,0,0,0}, {21796,21756,21766 ,8873,8820,8837 ,0,0,0}, + {21712,21715,21749 ,8833,8813,8812 ,0,0,0}, {21794,21796,21766 ,8871,8873,8837 ,0,0,0}, + {21795,21797,21796 ,8872,8874,8873 ,0,0,0}, {21798,21799,21800 ,8875,8876,8877 ,0,0,0}, + {21766,21756,21749 ,8837,8820,8812 ,0,0,0}, {21798,21764,21756 ,8875,8834,8820 ,0,0,0}, + {21711,21712,21755 ,8835,8833,8819 ,0,0,0}, {21796,21798,21756 ,8873,8875,8820 ,0,0,0}, + {21797,21799,21798 ,8874,8876,8875 ,0,0,0}, {21800,21801,21802 ,8877,8878,8879 ,0,0,0}, + {21756,21764,21755 ,8820,8834,8819 ,0,0,0}, {21800,21763,21764 ,8877,8831,8834 ,0,0,0}, + {21713,21711,21762 ,8832,8835,8830 ,0,0,0}, {21798,21800,21764 ,8875,8877,8834 ,0,0,0}, + {21799,21801,21800 ,8876,8878,8877 ,0,0,0}, {21761,21802,21783 ,8828,8879,8860 ,0,0,0}, + {21764,21763,21762 ,8834,8831,8830 ,0,0,0}, {21763,21802,21759 ,8831,8879,8826 ,0,0,0}, + {21708,21713,21758 ,8829,8832,8825 ,0,0,0}, {21800,21802,21763 ,8877,8879,8831 ,0,0,0}, + {21801,21783,21802 ,8878,8860,8879 ,0,0,0}, {21709,21754,21753 ,8821,8818,8817 ,0,0,0}, + {21763,21759,21758 ,8831,8826,8825 ,0,0,0}, {21761,21752,21759 ,8828,8816,8826 ,0,0,0}, + {21709,21708,21754 ,8821,8829,8818 ,0,0,0}, {21761,21759,21802 ,8828,8826,8879 ,0,0,0}, + {21784,21760,21761 ,8861,8827,8828 ,0,0,0}, {21803,21752,21760 ,8880,8816,8827 ,0,0,0}, + {21759,21752,21754 ,8826,8816,8818 ,0,0,0}, {21752,21803,21753 ,8816,8880,8817 ,0,0,0}, + {21757,21753,21803 ,8823,8817,8880 ,0,0,0}, {21804,21805,21734 ,8881,8882,8883 ,0,0,0}, + {21772,21732,21806 ,8884,8885,8886 ,0,0,0}, {21778,21776,21807 ,8887,8888,8889 ,0,0,0}, + {21774,21808,21809 ,8890,8891,8892 ,0,0,0}, {21810,21811,21786 ,8893,8894,8895 ,0,0,0}, + {21812,21813,21780 ,8896,8897,8898 ,0,0,0}, {21814,21791,21815 ,8899,8900,8901 ,0,0,0}, + {21789,21787,21816 ,8902,8903,8904 ,0,0,0}, {21797,21795,21817 ,8905,8906,8907 ,0,0,0}, + {21793,21818,21795 ,8908,8909,8906 ,0,0,0}, {21819,21799,21797 ,8910,8911,8905 ,0,0,0}, + {21797,21817,21819 ,8905,8907,8910 ,0,0,0}, {21799,21820,21801 ,8911,8912,8913 ,0,0,0}, + {21820,21799,21819 ,8912,8911,8910 ,0,0,0}, {21783,21801,21821 ,8914,8913,8915 ,0,0,0}, + {21820,21821,21801 ,8912,8915,8913 ,0,0,0}, {21821,21822,21784 ,8915,8916,8861 ,0,0,0}, + {21784,21783,21821 ,8861,8914,8915 ,0,0,0}, {21817,21795,21818 ,8907,8906,8909 ,0,0,0}, + {21793,21791,21814 ,8908,8900,8899 ,0,0,0}, {21793,21814,21818 ,8908,8899,8909 ,0,0,0}, + {21815,21789,21816 ,8901,8902,8904 ,0,0,0}, {21791,21789,21815 ,8900,8902,8901 ,0,0,0}, + {21811,21787,21786 ,8894,8903,8895 ,0,0,0}, {21816,21787,21811 ,8904,8903,8894 ,0,0,0}, + {21813,21810,21782 ,8897,8893,8917 ,0,0,0}, {21810,21786,21782 ,8893,8895,8917 ,0,0,0}, + {21778,21812,21780 ,8887,8896,8898 ,0,0,0}, {21780,21813,21782 ,8898,8897,8917 ,0,0,0}, + {21776,21809,21807 ,8888,8892,8889 ,0,0,0}, {21778,21807,21812 ,8887,8889,8896 ,0,0,0}, + {21774,21772,21808 ,8890,8884,8891 ,0,0,0}, {21776,21774,21809 ,8888,8890,8892 ,0,0,0}, + {21806,21732,21805 ,8886,8885,8882 ,0,0,0}, {21808,21772,21806 ,8891,8884,8886 ,0,0,0}, + {21804,21734,21736 ,8881,8883,8918 ,0,0,0}, {21805,21732,21734 ,8882,8885,8883 ,0,0,0}, + {21823,21824,21805 ,8919,8920,8921 ,0,0,0}, {21806,21805,21825 ,8922,8921,8923 ,0,0,0}, + {21807,21809,21826 ,8924,8925,8926 ,0,0,0}, {21808,21827,21828 ,8927,8928,8929 ,0,0,0}, + {21813,21829,21810 ,8930,8931,8932 ,0,0,0}, {21830,21831,21812 ,8933,8934,8935 ,0,0,0}, + {21832,21815,21816 ,8936,8937,8938 ,0,0,0}, {21833,21811,21834 ,8939,8940,8941 ,0,0,0}, + {21817,21818,21835 ,8942,8943,8944 ,0,0,0}, {21814,21836,21837 ,8945,8946,8947 ,0,0,0}, + {21838,21819,21817 ,8948,8949,8942 ,0,0,0}, {21817,21835,21838 ,8942,8944,8948 ,0,0,0}, + {21819,21839,21820 ,8949,8950,8951 ,0,0,0}, {21839,21819,21838 ,8950,8949,8948 ,0,0,0}, + {21821,21820,21840 ,8952,8951,8953 ,0,0,0}, {21839,21840,21820 ,8950,8953,8951 ,0,0,0}, + {21841,21822,21821 ,8954,8916,8952 ,0,0,0}, {21821,21840,21841 ,8952,8953,8954 ,0,0,0}, + {21842,21822,21841 ,8955,8916,8954 ,0,0,0}, {21818,21837,21835 ,8943,8947,8944 ,0,0,0}, + {21814,21815,21836 ,8945,8937,8946 ,0,0,0}, {21818,21814,21837 ,8943,8945,8947 ,0,0,0}, + {21832,21816,21833 ,8936,8938,8939 ,0,0,0}, {21836,21815,21832 ,8946,8937,8936 ,0,0,0}, + {21834,21811,21810 ,8941,8940,8932 ,0,0,0}, {21833,21816,21811 ,8939,8938,8940 ,0,0,0}, + {21831,21829,21813 ,8934,8931,8930 ,0,0,0}, {21829,21834,21810 ,8931,8941,8932 ,0,0,0}, + {21807,21830,21812 ,8924,8933,8935 ,0,0,0}, {21812,21831,21813 ,8935,8934,8930 ,0,0,0}, + {21809,21828,21826 ,8925,8929,8926 ,0,0,0}, {21807,21826,21830 ,8924,8926,8933 ,0,0,0}, + {21808,21806,21827 ,8927,8922,8928 ,0,0,0}, {21809,21808,21828 ,8925,8927,8929 ,0,0,0}, + {21825,21805,21824 ,8923,8921,8920 ,0,0,0}, {21827,21806,21825 ,8928,8922,8923 ,0,0,0}, + {21823,21805,21804 ,8919,8921,8881 ,0,0,0}, {21843,21844,21824 ,8956,8957,8958 ,0,0,0}, + {21845,21825,21844 ,8959,8923,8957 ,0,0,0}, {21830,21826,21846 ,8960,8961,8962 ,0,0,0}, + {21828,21827,21847 ,8929,8928,8963 ,0,0,0}, {21829,21848,21834 ,8964,8965,8966 ,0,0,0}, + {21849,21850,21831 ,8967,8968,8969 ,0,0,0}, {21851,21836,21832 ,8970,8971,8972 ,0,0,0}, + {21852,21833,21853 ,8973,8974,8975 ,0,0,0}, {21838,21835,21854 ,8948,8944,8976 ,0,0,0}, + {21837,21855,21856 ,8977,8978,8979 ,0,0,0}, {21857,21839,21838 ,8980,8950,8948 ,0,0,0}, + {21838,21854,21857 ,8948,8976,8980 ,0,0,0}, {21839,21858,21840 ,8950,8981,8953 ,0,0,0}, + {21858,21839,21857 ,8981,8950,8980 ,0,0,0}, {21841,21840,21859 ,8982,8953,8983 ,0,0,0}, + {21858,21859,21840 ,8981,8983,8953 ,0,0,0}, {21860,21842,21841 ,8984,8955,8982 ,0,0,0}, + {21841,21859,21860 ,8982,8983,8984 ,0,0,0}, {21861,21842,21860 ,8985,8955,8984 ,0,0,0}, + {21835,21856,21854 ,8944,8979,8976 ,0,0,0}, {21837,21836,21855 ,8977,8971,8978 ,0,0,0}, + {21835,21837,21856 ,8944,8977,8979 ,0,0,0}, {21851,21832,21852 ,8970,8972,8973 ,0,0,0}, + {21855,21836,21851 ,8978,8971,8970 ,0,0,0}, {21853,21833,21834 ,8975,8974,8966 ,0,0,0}, + {21852,21832,21833 ,8973,8972,8974 ,0,0,0}, {21850,21848,21829 ,8968,8965,8964 ,0,0,0}, + {21848,21853,21834 ,8965,8975,8966 ,0,0,0}, {21830,21849,21831 ,8960,8967,8969 ,0,0,0}, + {21831,21850,21829 ,8969,8968,8964 ,0,0,0}, {21826,21862,21846 ,8961,8986,8962 ,0,0,0}, + {21830,21846,21849 ,8960,8962,8967 ,0,0,0}, {21847,21862,21828 ,8963,8986,8929 ,0,0,0}, + {21826,21828,21862 ,8961,8929,8986 ,0,0,0}, {21845,21827,21825 ,8959,8928,8923 ,0,0,0}, + {21847,21827,21845 ,8963,8928,8959 ,0,0,0}, {21824,21823,21843 ,8958,8919,8956 ,0,0,0}, + {21844,21825,21824 ,8957,8923,8958 ,0,0,0}, {21863,21864,21844 ,8987,8988,8989 ,0,0,0}, + {21865,21845,21864 ,8990,8991,8988 ,0,0,0}, {21849,21846,21866 ,8992,8993,8994 ,0,0,0}, + {21862,21847,21867 ,8995,8996,8997 ,0,0,0}, {21848,21868,21853 ,8998,8999,9000 ,0,0,0}, + {21869,21870,21850 ,9001,9002,9003 ,0,0,0}, {21871,21855,21851 ,9004,9005,9006 ,0,0,0}, + {21872,21852,21873 ,9007,9008,9009 ,0,0,0}, {21874,21854,21875 ,9010,9011,9012 ,0,0,0}, + {21856,21855,21876 ,9013,9005,9014 ,0,0,0}, {21877,21858,21857 ,9015,9016,9017 ,0,0,0}, + {21857,21874,21877 ,9017,9010,9015 ,0,0,0}, {21858,21878,21859 ,9016,9018,9019 ,0,0,0}, + {21878,21858,21877 ,9018,9016,9015 ,0,0,0}, {21860,21859,21879 ,9020,9019,9021 ,0,0,0}, + {21878,21879,21859 ,9018,9021,9019 ,0,0,0}, {21880,21861,21860 ,9022,8985,9020 ,0,0,0}, + {21860,21879,21880 ,9020,9021,9022 ,0,0,0}, {21881,21861,21880 ,9023,8985,9022 ,0,0,0}, + {21874,21857,21854 ,9010,9017,9011 ,0,0,0}, {21875,21856,21876 ,9012,9013,9014 ,0,0,0}, + {21854,21856,21875 ,9011,9013,9012 ,0,0,0}, {21851,21872,21871 ,9006,9007,9004 ,0,0,0}, + {21876,21855,21871 ,9014,9005,9004 ,0,0,0}, {21873,21852,21853 ,9009,9008,9000 ,0,0,0}, + {21872,21851,21852 ,9007,9006,9008 ,0,0,0}, {21870,21868,21848 ,9002,8999,8998 ,0,0,0}, + {21868,21873,21853 ,8999,9009,9000 ,0,0,0}, {21849,21869,21850 ,8992,9001,9003 ,0,0,0}, + {21850,21870,21848 ,9003,9002,8998 ,0,0,0}, {21846,21882,21866 ,8993,9024,8994 ,0,0,0}, + {21849,21866,21869 ,8992,8994,9001 ,0,0,0}, {21867,21882,21862 ,8997,9024,8995 ,0,0,0}, + {21846,21862,21882 ,8993,8995,9024 ,0,0,0}, {21865,21847,21845 ,8990,8996,8991 ,0,0,0}, + {21867,21847,21865 ,8997,8996,8990 ,0,0,0}, {21844,21843,21863 ,8989,8956,8987 ,0,0,0}, + {21864,21845,21844 ,8988,8991,8989 ,0,0,0}, {21883,21863,21884 ,9025,8987,9026 ,0,0,0}, + {21885,21867,21886 ,9027,9028,9029 ,0,0,0}, {21887,21865,21864 ,9030,9031,9032 ,0,0,0}, + {21869,21888,21870 ,9033,9034,9035 ,0,0,0}, {21882,21889,21866 ,9036,9037,9038 ,0,0,0}, + {21890,21872,21873 ,9039,9040,9041 ,0,0,0}, {21891,21868,21892 ,9042,9043,9044 ,0,0,0}, + {21893,21876,21894 ,9045,9046,9047 ,0,0,0}, {21871,21895,21894 ,9048,9049,9047 ,0,0,0}, + {21877,21874,21896 ,9050,9051,9052 ,0,0,0}, {21875,21897,21874 ,9053,9054,9051 ,0,0,0}, + {21898,21878,21877 ,9055,9056,9050 ,0,0,0}, {21877,21896,21898 ,9050,9052,9055 ,0,0,0}, + {21878,21899,21879 ,9056,9057,9058 ,0,0,0}, {21899,21878,21898 ,9057,9056,9055 ,0,0,0}, + {21880,21879,21900 ,9059,9058,9060 ,0,0,0}, {21899,21900,21879 ,9057,9060,9058 ,0,0,0}, + {21901,21881,21880 ,9061,9023,9059 ,0,0,0}, {21880,21900,21901 ,9059,9060,9061 ,0,0,0}, + {21893,21897,21875 ,9045,9054,9053 ,0,0,0}, {21874,21897,21896 ,9051,9054,9052 ,0,0,0}, + {21876,21871,21894 ,9046,9048,9047 ,0,0,0}, {21875,21876,21893 ,9053,9046,9045 ,0,0,0}, + {21895,21872,21890 ,9049,9040,9039 ,0,0,0}, {21871,21872,21895 ,9048,9040,9049 ,0,0,0}, + {21891,21873,21868 ,9042,9041,9043 ,0,0,0}, {21890,21873,21891 ,9039,9041,9042 ,0,0,0}, + {21888,21892,21870 ,9034,9044,9035 ,0,0,0}, {21892,21868,21870 ,9044,9043,9035 ,0,0,0}, + {21866,21902,21869 ,9038,9062,9033 ,0,0,0}, {21902,21888,21869 ,9062,9034,9033 ,0,0,0}, + {21882,21885,21889 ,9036,9027,9037 ,0,0,0}, {21866,21889,21902 ,9038,9037,9062 ,0,0,0}, + {21867,21865,21886 ,9028,9031,9029 ,0,0,0}, {21882,21867,21885 ,9036,9028,9027 ,0,0,0}, + {21887,21864,21883 ,9030,9032,9025 ,0,0,0}, {21886,21865,21887 ,9029,9031,9030 ,0,0,0}, + {21863,21883,21864 ,8987,9025,9032 ,0,0,0}, {21890,21891,21903 ,9063,9064,9065 ,0,0,0}, + {21904,21891,21892 ,9066,9064,9067 ,0,0,0}, {21891,21904,21903 ,9064,9066,9065 ,0,0,0}, + {21888,21905,21892 ,9068,9069,9067 ,0,0,0}, {21904,21892,21905 ,9066,9067,9069 ,0,0,0}, + {21888,21902,21906 ,9068,9070,9071 ,0,0,0}, {21906,21905,21888 ,9071,9069,9068 ,0,0,0}, + {21907,21902,21889 ,9072,9070,9073 ,0,0,0}, {21902,21907,21906 ,9070,9072,9071 ,0,0,0}, + {21885,21908,21889 ,9074,9075,9073 ,0,0,0}, {21907,21889,21908 ,9072,9073,9075 ,0,0,0}, + {21885,21886,21909 ,9074,9076,9077 ,0,0,0}, {21909,21908,21885 ,9077,9075,9074 ,0,0,0}, + {21910,21886,21887 ,9078,9076,9079 ,0,0,0}, {21886,21910,21909 ,9076,9078,9077 ,0,0,0}, + {21883,21911,21887 ,9080,9081,9079 ,0,0,0}, {21910,21887,21911 ,9078,9079,9081 ,0,0,0}, + {21884,21912,21911 ,9082,9083,9081 ,0,0,0}, {21911,21883,21884 ,9081,9080,9082 ,0,0,0}, + {21890,21903,21913 ,9063,9065,9084 ,0,0,0}, {21913,21914,21895 ,9084,9085,9086 ,0,0,0}, + {21895,21890,21913 ,9086,9063,9084 ,0,0,0}, {21894,21914,21915 ,9087,9085,9088 ,0,0,0}, + {21914,21894,21895 ,9085,9087,9086 ,0,0,0}, {21916,21893,21915 ,9089,9090,9088 ,0,0,0}, + {21894,21915,21893 ,9087,9088,9090 ,0,0,0}, {21916,21917,21897 ,9089,9091,9092 ,0,0,0}, + {21897,21893,21916 ,9092,9090,9089 ,0,0,0}, {21896,21917,21918 ,9093,9091,9094 ,0,0,0}, + {21917,21896,21897 ,9091,9093,9092 ,0,0,0}, {21919,21898,21918 ,9095,9096,9094 ,0,0,0}, + {21896,21918,21898 ,9093,9094,9096 ,0,0,0}, {21919,21920,21899 ,9095,9097,9098 ,0,0,0}, + {21899,21898,21919 ,9098,9096,9095 ,0,0,0}, {21900,21920,21921 ,9099,9097,9100 ,0,0,0}, + {21920,21900,21899 ,9097,9099,9098 ,0,0,0}, {21900,21921,21901 ,9099,9100,9101 ,0,0,0}, + {21922,21912,21923 ,9102,9103,9104 ,0,0,0}, {21924,21908,21925 ,9105,9106,9107 ,0,0,0}, + {21922,21926,21910 ,9102,9108,9109 ,0,0,0}, {21905,21927,21928 ,9110,9111,9112 ,0,0,0}, + {21907,21929,21906 ,9113,9114,9115 ,0,0,0}, {21930,21931,21913 ,9116,9117,9118 ,0,0,0}, + {21932,21903,21904 ,9119,9120,9121 ,0,0,0}, {21933,21916,21934 ,9122,9123,9124 ,0,0,0}, + {21915,21914,21935 ,9125,9126,9127 ,0,0,0}, {21936,21918,21917 ,9128,9129,9130 ,0,0,0}, + {21917,21933,21936 ,9130,9122,9128 ,0,0,0}, {21918,21937,21919 ,9129,9131,9132 ,0,0,0}, + {21937,21918,21936 ,9131,9129,9128 ,0,0,0}, {21920,21919,21938 ,9133,9132,9134 ,0,0,0}, + {21937,21938,21919 ,9131,9134,9132 ,0,0,0}, {21939,21921,21920 ,9135,9100,9133 ,0,0,0}, + {21920,21938,21939 ,9133,9134,9135 ,0,0,0}, {21916,21915,21934 ,9123,9125,9124 ,0,0,0}, + {21917,21916,21933 ,9130,9123,9122 ,0,0,0}, {21935,21914,21931 ,9127,9126,9117 ,0,0,0}, + {21934,21915,21935 ,9124,9125,9127 ,0,0,0}, {21930,21913,21903 ,9116,9118,9120 ,0,0,0}, + {21931,21914,21913 ,9117,9126,9118 ,0,0,0}, {21928,21932,21904 ,9112,9119,9121 ,0,0,0}, + {21932,21930,21903 ,9119,9116,9120 ,0,0,0}, {21906,21927,21905 ,9115,9111,9110 ,0,0,0}, + {21905,21928,21904 ,9110,9112,9121 ,0,0,0}, {21907,21924,21929 ,9113,9105,9114 ,0,0,0}, + {21906,21929,21927 ,9115,9114,9111 ,0,0,0}, {21908,21909,21925 ,9106,9136,9107 ,0,0,0}, + {21907,21908,21924 ,9113,9106,9105 ,0,0,0}, {21910,21926,21909 ,9109,9108,9136 ,0,0,0}, + {21925,21909,21926 ,9107,9136,9108 ,0,0,0}, {21922,21911,21912 ,9102,9137,9103 ,0,0,0}, + {21922,21910,21911 ,9102,9109,9137 ,0,0,0}, {21940,21923,21941 ,9138,9139,9140 ,0,0,0}, + {21942,21925,21943 ,9141,9142,9143 ,0,0,0}, {21944,21926,21922 ,9144,9145,9146 ,0,0,0}, + {21927,21945,21928 ,9147,9148,9149 ,0,0,0}, {21924,21946,21929 ,9150,9151,9152 ,0,0,0}, + {21947,21948,21930 ,9153,9154,9155 ,0,0,0}, {21947,21932,21949 ,9153,9156,9157 ,0,0,0}, + {21950,21934,21951 ,9158,9159,9160 ,0,0,0}, {21935,21931,21952 ,9161,9162,9163 ,0,0,0}, + {21953,21936,21933 ,9164,9165,9166 ,0,0,0}, {21933,21950,21953 ,9166,9158,9164 ,0,0,0}, + {21936,21954,21937 ,9165,9167,9168 ,0,0,0}, {21954,21936,21953 ,9167,9165,9164 ,0,0,0}, + {21938,21937,21955 ,9169,9168,9170 ,0,0,0}, {21954,21955,21937 ,9167,9170,9168 ,0,0,0}, + {21956,21939,21938 ,9171,9172,9169 ,0,0,0}, {21938,21955,21956 ,9169,9170,9171 ,0,0,0}, + {21934,21935,21951 ,9159,9161,9160 ,0,0,0}, {21933,21934,21950 ,9166,9159,9158 ,0,0,0}, + {21952,21931,21948 ,9163,9162,9154 ,0,0,0}, {21951,21935,21952 ,9160,9161,9163 ,0,0,0}, + {21947,21930,21932 ,9153,9155,9156 ,0,0,0}, {21948,21931,21930 ,9154,9162,9155 ,0,0,0}, + {21945,21949,21928 ,9148,9157,9149 ,0,0,0}, {21949,21932,21928 ,9157,9156,9149 ,0,0,0}, + {21929,21957,21927 ,9152,9173,9147 ,0,0,0}, {21957,21945,21927 ,9173,9148,9147 ,0,0,0}, + {21924,21942,21946 ,9150,9141,9151 ,0,0,0}, {21929,21946,21957 ,9152,9151,9173 ,0,0,0}, + {21925,21926,21943 ,9142,9145,9143 ,0,0,0}, {21924,21925,21942 ,9150,9142,9141 ,0,0,0}, + {21944,21922,21940 ,9144,9146,9138 ,0,0,0}, {21943,21926,21944 ,9143,9145,9144 ,0,0,0}, + {21923,21940,21922 ,9139,9138,9146 ,0,0,0}, {21958,21941,21959 ,9174,9175,9176 ,0,0,0}, + {21960,21943,21961 ,9177,9178,9179 ,0,0,0}, {21962,21944,21940 ,9180,9181,9182 ,0,0,0}, + {21957,21963,21964 ,9183,9184,9185 ,0,0,0}, {21942,21965,21946 ,9186,9187,9188 ,0,0,0}, + {21966,21967,21947 ,9189,9190,9191 ,0,0,0}, {21966,21949,21968 ,9189,9192,9193 ,0,0,0}, + {21969,21951,21970 ,9194,9195,9196 ,0,0,0}, {21952,21948,21971 ,9197,9198,9199 ,0,0,0}, + {21972,21953,21950 ,9200,9201,9202 ,0,0,0}, {21950,21969,21972 ,9202,9194,9200 ,0,0,0}, + {21953,21973,21954 ,9201,9203,9204 ,0,0,0}, {21973,21953,21972 ,9203,9201,9200 ,0,0,0}, + {21955,21954,21974 ,9205,9204,9206 ,0,0,0}, {21973,21974,21954 ,9203,9206,9204 ,0,0,0}, + {21975,21956,21955 ,9207,9208,9205 ,0,0,0}, {21955,21974,21975 ,9205,9206,9207 ,0,0,0}, + {21951,21952,21970 ,9195,9197,9196 ,0,0,0}, {21950,21951,21969 ,9202,9195,9194 ,0,0,0}, + {21971,21948,21967 ,9199,9198,9190 ,0,0,0}, {21970,21952,21971 ,9196,9197,9199 ,0,0,0}, + {21966,21947,21949 ,9189,9191,9192 ,0,0,0}, {21967,21948,21947 ,9190,9198,9191 ,0,0,0}, + {21964,21968,21945 ,9185,9193,9209 ,0,0,0}, {21968,21949,21945 ,9193,9192,9209 ,0,0,0}, + {21946,21963,21957 ,9188,9184,9183 ,0,0,0}, {21957,21964,21945 ,9183,9185,9209 ,0,0,0}, + {21942,21960,21965 ,9186,9177,9187 ,0,0,0}, {21946,21965,21963 ,9188,9187,9184 ,0,0,0}, + {21943,21944,21961 ,9178,9181,9179 ,0,0,0}, {21942,21943,21960 ,9186,9178,9177 ,0,0,0}, + {21962,21940,21958 ,9180,9182,9174 ,0,0,0}, {21961,21944,21962 ,9179,9181,9180 ,0,0,0}, + {21941,21958,21940 ,9175,9174,9182 ,0,0,0}, {21546,21959,21544 ,9210,9211,9212 ,0,0,0}, + {21547,21961,21548 ,9213,9214,9215 ,0,0,0}, {21558,21962,21958 ,9216,9217,9218 ,0,0,0}, + {21963,21571,21572 ,9219,9220,9221 ,0,0,0}, {21960,21559,21965 ,9222,9223,9224 ,0,0,0}, + {21574,21575,21966 ,9225,9226,9227 ,0,0,0}, {21573,21968,21964 ,9228,9229,9230 ,0,0,0}, + {21604,21970,21971 ,9231,9232,9233 ,0,0,0}, {21601,21967,21575 ,9234,9235,9226 ,0,0,0}, + {21605,21972,21969 ,9236,9237,9238 ,0,0,0}, {21969,21603,21605 ,9238,9239,9236 ,0,0,0}, + {21972,21606,21973 ,9237,9240,9241 ,0,0,0}, {21606,21972,21605 ,9240,9237,9236 ,0,0,0}, + {21973,21508,21505 ,9241,9242,9243 ,0,0,0}, {21606,21508,21973 ,9240,9242,9241 ,0,0,0}, + {21504,21974,21505 ,8461,9244,9243 ,0,0,0}, {21973,21505,21974 ,9241,9243,9244 ,0,0,0}, + {21975,21974,21504 ,9207,9244,8461 ,0,0,0}, {21603,21970,21604 ,9239,9232,9231 ,0,0,0}, + {21969,21970,21603 ,9238,9232,9239 ,0,0,0}, {21601,21971,21967 ,9234,9233,9235 ,0,0,0}, + {21604,21971,21601 ,9231,9233,9234 ,0,0,0}, {21966,21968,21574 ,9227,9229,9225 ,0,0,0}, + {21575,21967,21966 ,9226,9235,9227 ,0,0,0}, {21572,21573,21964 ,9221,9228,9230 ,0,0,0}, + {21573,21574,21968 ,9228,9225,9229 ,0,0,0}, {21965,21571,21963 ,9224,9220,9219 ,0,0,0}, + {21963,21572,21964 ,9219,9221,9230 ,0,0,0}, {21960,21547,21559 ,9222,9213,9223 ,0,0,0}, + {21965,21559,21571 ,9224,9223,9220 ,0,0,0}, {21961,21962,21548 ,9214,9217,9215 ,0,0,0}, + {21960,21961,21547 ,9222,9214,9213 ,0,0,0}, {21558,21958,21546 ,9216,9218,9210 ,0,0,0}, + {21548,21962,21558 ,9215,9217,9216 ,0,0,0}, {21959,21546,21958 ,9211,9210,9218 ,0,0,0}, + {21976,21484,21977 ,9245,8438,9246 ,0,0,0}, {21978,21594,21541 ,9247,9248,9249 ,0,0,0}, + {21979,21556,21482 ,9250,9251,9252 ,0,0,0}, {21599,21980,21981 ,9253,9254,9255 ,0,0,0}, + {21595,21982,21596 ,9256,9257,9258 ,0,0,0}, {21983,21984,21564 ,9259,9260,9261 ,0,0,0}, + {21985,21567,21568 ,9262,9263,9264 ,0,0,0}, {21986,21602,21987 ,9265,9266,9267 ,0,0,0}, + {21600,21565,21988 ,9268,9269,9270 ,0,0,0}, {21989,21579,21524 ,9271,9272,9273 ,0,0,0}, + {21524,21986,21989 ,9273,9265,9271 ,0,0,0}, {21579,21990,21607 ,9272,9274,9275 ,0,0,0}, + {21990,21579,21989 ,9274,9272,9271 ,0,0,0}, {21515,21607,21991 ,9276,9275,9277 ,0,0,0}, + {21990,21991,21607 ,9274,9277,9275 ,0,0,0}, {21992,21518,21515 ,9278,9279,9276 ,0,0,0}, + {21515,21991,21992 ,9276,9277,9278 ,0,0,0}, {21602,21600,21987 ,9266,9268,9267 ,0,0,0}, + {21524,21602,21986 ,9273,9266,9265 ,0,0,0}, {21988,21565,21984 ,9270,9269,9260 ,0,0,0}, + {21987,21600,21988 ,9267,9268,9270 ,0,0,0}, {21983,21564,21567 ,9259,9261,9263 ,0,0,0}, + {21984,21565,21564 ,9260,9269,9261 ,0,0,0}, {21981,21985,21568 ,9255,9262,9264 ,0,0,0}, + {21985,21983,21567 ,9262,9259,9263 ,0,0,0}, {21596,21980,21599 ,9258,9254,9253 ,0,0,0}, + {21599,21981,21568 ,9253,9255,9264 ,0,0,0}, {21595,21993,21982 ,9256,9280,9257 ,0,0,0}, + {21596,21982,21980 ,9258,9257,9254 ,0,0,0}, {21978,21993,21594 ,9247,9280,9248 ,0,0,0}, + {21595,21594,21993 ,9256,9248,9280 ,0,0,0}, {21979,21541,21556 ,9250,9249,9251 ,0,0,0}, + {21978,21541,21979 ,9247,9249,9250 ,0,0,0}, {21976,21482,21484 ,9245,9252,8438 ,0,0,0}, + {21979,21482,21976 ,9250,9252,9245 ,0,0,0}, {21994,21977,21995 ,9281,9246,9282 ,0,0,0}, + {21996,21978,21997 ,9283,9284,9285 ,0,0,0}, {21998,21979,21976 ,9286,9287,9288 ,0,0,0}, + {21980,21999,22000 ,9289,9290,9291 ,0,0,0}, {21993,22001,21982 ,9292,9293,9294 ,0,0,0}, + {22002,21984,21983 ,9295,9296,9297 ,0,0,0}, {22003,21985,22004 ,9298,9299,9300 ,0,0,0}, + {22005,21987,22006 ,9301,9302,9303 ,0,0,0}, {21988,21984,22007 ,9304,9296,9305 ,0,0,0}, + {22008,21989,21986 ,9306,9307,9308 ,0,0,0}, {21986,22005,22008 ,9308,9301,9306 ,0,0,0}, + {21989,22009,21990 ,9307,9309,9310 ,0,0,0}, {22009,21989,22008 ,9309,9307,9306 ,0,0,0}, + {21991,21990,22010 ,9311,9310,9312 ,0,0,0}, {22009,22010,21990 ,9309,9312,9310 ,0,0,0}, + {22011,21992,21991 ,9313,9314,9311 ,0,0,0}, {21991,22010,22011 ,9311,9312,9313 ,0,0,0}, + {21987,21988,22006 ,9302,9304,9303 ,0,0,0}, {21986,21987,22005 ,9308,9302,9301 ,0,0,0}, + {22007,21984,22002 ,9305,9296,9295 ,0,0,0}, {22006,21988,22007 ,9303,9304,9305 ,0,0,0}, + {22003,21983,21985 ,9298,9297,9299 ,0,0,0}, {22002,21983,22003 ,9295,9297,9298 ,0,0,0}, + {22000,22004,21981 ,9291,9300,9315 ,0,0,0}, {22004,21985,21981 ,9300,9299,9315 ,0,0,0}, + {21982,21999,21980 ,9294,9290,9289 ,0,0,0}, {21980,22000,21981 ,9289,9291,9315 ,0,0,0}, + {21993,21996,22001 ,9292,9283,9293 ,0,0,0}, {21982,22001,21999 ,9294,9293,9290 ,0,0,0}, + {21978,21979,21997 ,9284,9287,9285 ,0,0,0}, {21993,21978,21996 ,9292,9284,9283 ,0,0,0}, + {21998,21976,21994 ,9286,9288,9281 ,0,0,0}, {21997,21979,21998 ,9285,9287,9286 ,0,0,0}, + {21977,21994,21976 ,9246,9281,9288 ,0,0,0}, {22012,21995,22013 ,9316,9282,9317 ,0,0,0}, + {22014,21997,22015 ,9318,9319,9320 ,0,0,0}, {22016,21998,21994 ,9321,9322,9323 ,0,0,0}, + {21999,22017,22000 ,9324,9325,9326 ,0,0,0}, {21996,22018,22001 ,9327,9328,9329 ,0,0,0}, + {22019,22002,22003 ,9330,9331,9332 ,0,0,0}, {22020,22004,22021 ,9333,9334,9335 ,0,0,0}, + {22022,22006,22023 ,9336,9337,9338 ,0,0,0}, {22007,22002,22024 ,9339,9331,9340 ,0,0,0}, + {22025,22008,22005 ,9341,9342,9343 ,0,0,0}, {22005,22022,22025 ,9343,9336,9341 ,0,0,0}, + {22008,22026,22009 ,9342,9344,9345 ,0,0,0}, {22026,22008,22025 ,9344,9342,9341 ,0,0,0}, + {22010,22009,22027 ,9346,9345,9347 ,0,0,0}, {22026,22027,22009 ,9344,9347,9345 ,0,0,0}, + {22028,22011,22010 ,9348,9349,9346 ,0,0,0}, {22010,22027,22028 ,9346,9347,9348 ,0,0,0}, + {22006,22007,22023 ,9337,9339,9338 ,0,0,0}, {22005,22006,22022 ,9343,9337,9336 ,0,0,0}, + {22024,22002,22019 ,9340,9331,9330 ,0,0,0}, {22023,22007,22024 ,9338,9339,9340 ,0,0,0}, + {22020,22003,22004 ,9333,9332,9334 ,0,0,0}, {22019,22003,22020 ,9330,9332,9333 ,0,0,0}, + {22017,22021,22000 ,9325,9335,9326 ,0,0,0}, {22021,22004,22000 ,9335,9334,9326 ,0,0,0}, + {22001,22029,21999 ,9329,9350,9324 ,0,0,0}, {22029,22017,21999 ,9350,9325,9324 ,0,0,0}, + {21996,22014,22018 ,9327,9318,9328 ,0,0,0}, {22001,22018,22029 ,9329,9328,9350 ,0,0,0}, + {21997,21998,22015 ,9319,9322,9320 ,0,0,0}, {21996,21997,22014 ,9327,9319,9318 ,0,0,0}, + {22016,21994,22012 ,9321,9323,9316 ,0,0,0}, {22015,21998,22016 ,9320,9322,9321 ,0,0,0}, + {21995,22012,21994 ,9282,9316,9323 ,0,0,0}, {21612,22030,21649 ,9351,9352,8640 ,0,0,0}, + {21618,22031,21619 ,9353,9354,9355 ,0,0,0}, {21614,22032,22033 ,9356,9357,9358 ,0,0,0}, + {22034,21626,22035 ,9359,9360,9361 ,0,0,0}, {22036,21616,22037 ,9362,9363,9364 ,0,0,0}, + {21631,22038,22039 ,9365,9366,9367 ,0,0,0}, {21623,22040,21621 ,9368,9369,9370 ,0,0,0}, + {22041,22042,21636 ,9371,9372,9373 ,0,0,0}, {22043,21629,21628 ,9374,9375,9376 ,0,0,0}, + {22044,22045,21633 ,9377,9378,9379 ,0,0,0}, {21634,21633,22045 ,9380,9379,9378 ,0,0,0}, + {21640,22046,22044 ,9381,9382,9377 ,0,0,0}, {22044,21633,21640 ,9377,9379,9381 ,0,0,0}, + {22046,21642,22047 ,9382,9383,9384 ,0,0,0}, {21642,22046,21640 ,9383,9382,9381 ,0,0,0}, + {22048,22047,21643 ,9385,9384,9386 ,0,0,0}, {21642,21643,22047 ,9383,9386,9384 ,0,0,0}, + {21646,22049,22048 ,8637,9387,9385 ,0,0,0}, {22048,21643,21646 ,9385,9386,8637 ,0,0,0}, + {21636,21634,22041 ,9373,9380,9371 ,0,0,0}, {22041,21634,22045 ,9371,9380,9378 ,0,0,0}, + {22042,22043,21628 ,9372,9374,9376 ,0,0,0}, {22042,21628,21636 ,9372,9376,9373 ,0,0,0}, + {21629,22038,21631 ,9375,9366,9365 ,0,0,0}, {22043,22038,21629 ,9374,9366,9375 ,0,0,0}, + {21623,22039,22040 ,9368,9367,9369 ,0,0,0}, {21631,22039,21623 ,9365,9367,9368 ,0,0,0}, + {21626,21621,22035 ,9360,9370,9361 ,0,0,0}, {21621,22040,22035 ,9370,9369,9361 ,0,0,0}, + {22037,21648,22034 ,9364,9388,9359 ,0,0,0}, {21648,21626,22034 ,9388,9360,9359 ,0,0,0}, + {22036,21618,21616 ,9362,9353,9363 ,0,0,0}, {22037,21616,21648 ,9364,9363,9388 ,0,0,0}, + {22031,22032,21619 ,9354,9357,9355 ,0,0,0}, {22036,22031,21618 ,9362,9354,9353 ,0,0,0}, + {21614,22033,21612 ,9356,9358,9351 ,0,0,0}, {21619,22032,21614 ,9355,9357,9356 ,0,0,0}, + {22030,21612,22033 ,9352,9351,9358 ,0,0,0}, {22050,22013,22051 ,9389,9317,9390 ,0,0,0}, + {22052,22015,22053 ,9391,9392,9393 ,0,0,0}, {22054,22016,22012 ,9394,9395,9396 ,0,0,0}, + {22029,22055,22056 ,9397,9398,9399 ,0,0,0}, {22014,22057,22018 ,9400,9401,9402 ,0,0,0}, + {22058,22059,22020 ,9403,9404,9405 ,0,0,0}, {22060,22021,22017 ,9406,9407,9408 ,0,0,0}, + {22061,22023,22024 ,9409,9410,9411 ,0,0,0}, {22024,22019,22062 ,9411,9412,9413 ,0,0,0}, + {22063,22025,22022 ,9414,9415,9416 ,0,0,0}, {22022,22064,22063 ,9416,9417,9414 ,0,0,0}, + {22025,22065,22026 ,9415,9418,9419 ,0,0,0}, {22065,22025,22063 ,9418,9415,9414 ,0,0,0}, + {22027,22026,22066 ,9420,9419,9421 ,0,0,0}, {22065,22066,22026 ,9418,9421,9419 ,0,0,0}, + {22067,22027,22068 ,9422,9420,9423 ,0,0,0}, {22027,22066,22068 ,9420,9421,9423 ,0,0,0}, + {22028,22027,22067 ,9424,9420,9422 ,0,0,0}, {22064,22023,22061 ,9417,9410,9409 ,0,0,0}, + {22022,22023,22064 ,9416,9410,9417 ,0,0,0}, {22019,22059,22062 ,9412,9404,9413 ,0,0,0}, + {22061,22024,22062 ,9409,9411,9413 ,0,0,0}, {22058,22020,22021 ,9403,9405,9407 ,0,0,0}, + {22059,22019,22020 ,9404,9412,9405 ,0,0,0}, {22056,22060,22017 ,9399,9406,9408 ,0,0,0}, + {22060,22058,22021 ,9406,9403,9407 ,0,0,0}, {22018,22055,22029 ,9402,9398,9397 ,0,0,0}, + {22029,22056,22017 ,9397,9399,9408 ,0,0,0}, {22014,22052,22057 ,9400,9391,9401 ,0,0,0}, + {22018,22057,22055 ,9402,9401,9398 ,0,0,0}, {22015,22016,22053 ,9392,9395,9393 ,0,0,0}, + {22014,22015,22052 ,9400,9392,9391 ,0,0,0}, {22054,22012,22050 ,9394,9396,9389 ,0,0,0}, + {22053,22016,22054 ,9393,9395,9394 ,0,0,0}, {22013,22050,22012 ,9317,9389,9396 ,0,0,0}, + {22033,22051,22030 ,9425,9390,9426 ,0,0,0}, {22036,22053,22031 ,9427,9428,9429 ,0,0,0}, + {22032,22054,22050 ,9430,9431,9432 ,0,0,0}, {22055,22034,22035 ,9433,9434,9435 ,0,0,0}, + {22052,22037,22057 ,9436,9437,9438 ,0,0,0}, {22039,22038,22058 ,9439,9440,9441 ,0,0,0}, + {22040,22060,22056 ,9442,9443,9444 ,0,0,0}, {22041,22061,22042 ,9445,9446,9447 ,0,0,0}, + {22062,22059,22043 ,9448,9449,9450 ,0,0,0}, {22044,22063,22045 ,9451,9452,9453 ,0,0,0}, + {22064,22041,22045 ,9454,9445,9453 ,0,0,0}, {22044,22046,22065 ,9451,9455,9456 ,0,0,0}, + {22065,22063,22044 ,9456,9452,9451 ,0,0,0}, {22066,22046,22047 ,9457,9455,9458 ,0,0,0}, + {22046,22066,22065 ,9455,9457,9456 ,0,0,0}, {22048,22068,22047 ,9459,9460,9458 ,0,0,0}, + {22066,22047,22068 ,9457,9458,9460 ,0,0,0}, {22049,22067,22068 ,9461,9422,9460 ,0,0,0}, + {22068,22048,22049 ,9460,9459,9461 ,0,0,0}, {22061,22041,22064 ,9446,9445,9454 ,0,0,0}, + {22063,22064,22045 ,9452,9454,9453 ,0,0,0}, {22042,22062,22043 ,9447,9448,9450 ,0,0,0}, + {22061,22062,22042 ,9446,9448,9447 ,0,0,0}, {22038,22059,22058 ,9440,9449,9441 ,0,0,0}, + {22043,22059,22038 ,9450,9449,9440 ,0,0,0}, {22040,22039,22060 ,9442,9439,9443 ,0,0,0}, + {22039,22058,22060 ,9439,9441,9443 ,0,0,0}, {22055,22035,22056 ,9433,9435,9444 ,0,0,0}, + {22035,22040,22056 ,9435,9442,9444 ,0,0,0}, {22057,22037,22034 ,9438,9437,9434 ,0,0,0}, + {22057,22034,22055 ,9438,9434,9433 ,0,0,0}, {22052,22053,22036 ,9436,9428,9427 ,0,0,0}, + {22052,22036,22037 ,9436,9427,9437 ,0,0,0}, {22031,22054,22032 ,9429,9431,9430 ,0,0,0}, + {22053,22054,22031 ,9428,9431,9429 ,0,0,0}, {22033,22050,22051 ,9425,9432,9390 ,0,0,0}, + {22032,22050,22033 ,9430,9432,9425 ,0,0,0}, {21736,22069,22070 ,9462,9463,9464 ,0,0,0}, + {21735,22071,21733 ,9465,9466,9467 ,0,0,0}, {22069,21736,22072 ,9463,9462,9468 ,0,0,0}, + {22070,22073,21736 ,9464,9462,9462 ,0,0,0}, {22072,21736,21733 ,9468,9462,9467 ,0,0,0}, + {22074,22072,21733 ,9469,9468,9467 ,0,0,0}, {22074,21733,22071 ,9469,9467,9466 ,0,0,0}, + {21771,21689,22075 ,9470,9471,9472 ,0,0,0}, {21771,22076,22077 ,9470,9473,9474 ,0,0,0}, + {22075,22076,21771 ,9472,9473,9470 ,0,0,0}, {21735,22077,22078 ,9465,9474,9475 ,0,0,0}, + {21735,21771,22077 ,9465,9470,9474 ,0,0,0}, {21735,22079,22080 ,9465,9476,9477 ,0,0,0}, + {22078,22079,21735 ,9475,9476,9465 ,0,0,0}, {21735,22081,22082 ,9465,9478,9479 ,0,0,0}, + {22080,22081,21735 ,9477,9478,9465 ,0,0,0}, {22071,21735,22083 ,9466,9465,9480 ,0,0,0}, + {22082,22083,21735 ,9479,9480,9465 ,0,0,0}, {22084,21557,22085 ,9481,9482,9483 ,0,0,0}, + {21557,22086,22087 ,9482,9484,9485 ,0,0,0}, {22087,21555,21557 ,9485,9486,9482 ,0,0,0}, + {21557,22084,22086 ,9482,9481,9484 ,0,0,0}, {21555,22088,22089 ,9486,9487,9488 ,0,0,0}, + {21555,22087,22088 ,9486,9485,9487 ,0,0,0}, {21557,22090,22085 ,9482,9489,9483 ,0,0,0}, + {21555,22089,21484 ,9486,9488,9490 ,0,0,0}, {22091,21557,21542 ,9491,9482,9492 ,0,0,0}, + {21557,22091,22090 ,9482,9491,9489 ,0,0,0}, {21544,22092,22093 ,9493,9493,9494 ,0,0,0}, + {22094,22095,21545 ,9495,9496,9497 ,0,0,0}, {22096,22097,21544 ,9498,9499,9493 ,0,0,0}, + {22096,21544,22093 ,9498,9493,9494 ,0,0,0}, {21544,22098,21545 ,9493,9500,9497 ,0,0,0}, + {22098,21544,22097 ,9500,9493,9499 ,0,0,0}, {22099,21545,22095 ,9501,9497,9496 ,0,0,0}, + {22098,22094,21545 ,9500,9495,9497 ,0,0,0}, {22091,21542,22099 ,9491,9492,9501 ,0,0,0}, + {22099,21542,21545 ,9501,9492,9497 ,0,0,0}, {22092,21544,22100 ,9502,9503,9504 ,0,0,0}, + {21941,22100,21959 ,9505,9504,9506 ,0,0,0}, {21941,21923,22100 ,9505,9507,9504 ,0,0,0}, + {22100,21923,21912 ,9504,9507,9508 ,0,0,0}, {21912,21884,22100 ,9508,9509,9504 ,0,0,0}, + {22100,21544,21959 ,9504,9503,9506 ,0,0,0}, {22101,22099,22102 ,9510,9511,4303 ,0,0,0}, + {22101,22103,22091 ,9510,82,9512 ,0,0,0}, {22091,22099,22101 ,9512,9511,9510 ,0,0,0}, + {22104,22105,22106 ,9513,9514,9515 ,0,0,0}, {22105,22107,22106 ,9514,9516,9515 ,0,0,0}, + {22105,22104,22108 ,9514,9513,9517 ,0,0,0}, {22086,22109,22108 ,9518,9519,9517 ,0,0,0}, + {22104,22086,22108 ,9513,9518,9517 ,0,0,0}, {22084,22109,22086 ,9520,9519,9518 ,0,0,0}, + {22109,22084,22110 ,9519,9520,9521 ,0,0,0}, {22085,22111,22110 ,9522,9523,9521 ,0,0,0}, + {22110,22084,22085 ,9521,9520,9522 ,0,0,0}, {22111,22090,22112 ,9523,9524,9525 ,0,0,0}, + {22090,22111,22085 ,9524,9523,9522 ,0,0,0}, {22103,22112,22091 ,9526,9525,9527 ,0,0,0}, + {22090,22091,22112 ,9524,9527,9525 ,0,0,0}, {22097,22113,22114 ,9528,9529,9530 ,0,0,0}, + {22102,22099,22095 ,9531,9532,9533 ,0,0,0}, {22095,22094,22115 ,9533,9534,9535 ,0,0,0}, + {22116,22098,22114 ,9536,9537,9530 ,0,0,0}, {22115,22094,22116 ,9535,9534,9536 ,0,0,0}, + {22095,22115,22102 ,9533,9535,9531 ,0,0,0}, {22094,22098,22116 ,9534,9537,9536 ,0,0,0}, + {22098,22097,22114 ,9537,9528,9530 ,0,0,0}, {22113,22097,22096 ,9529,9528,9538 ,0,0,0}, + {22096,22093,22117 ,9538,9539,9540 ,0,0,0}, {22117,22113,22096 ,9540,9529,9538 ,0,0,0}, + {22118,22093,22092 ,9541,9539,9542 ,0,0,0}, {22093,22118,22117 ,9539,9541,9540 ,0,0,0}, + {22118,22092,22100 ,9541,9542,9542 ,0,0,0}, {22073,22119,22120 ,9543,9543,9544 ,0,0,0}, + {22073,22120,22121 ,9543,9544,9543 ,0,0,0}, {22122,22073,22121 ,9543,9543,9543 ,0,0,0}, + {22113,22117,22073 ,9543,9543,9543 ,0,0,0}, {22113,22073,22122 ,9543,9543,9543 ,0,0,0}, + {22073,22118,22100 ,9543,9543,9544 ,0,0,0}, {22117,22118,22073 ,9543,9543,9543 ,0,0,0}, + {22073,22100,21736 ,9543,9544,9543 ,0,0,0}, {22100,21863,21843 ,9544,9543,9543 ,0,0,0}, + {22100,21884,21863 ,9544,9544,9543 ,0,0,0}, {21843,21823,22100 ,9543,9544,9544 ,0,0,0}, + {21736,22100,21804 ,9543,9544,9543 ,0,0,0}, {22100,21823,21804 ,9544,9544,9543 ,0,0,0}, + {21649,22030,22123 ,9545,9546,9547 ,0,0,0}, {22075,22124,22076 ,9548,9549,9550 ,0,0,0}, + {22125,22124,21650 ,9551,9549,9552 ,0,0,0}, {22126,22107,22127 ,9553,9554,9555 ,0,0,0}, + {22128,22126,22127 ,9556,9553,9555 ,0,0,0}, {22129,22130,22131 ,9557,9558,9559 ,0,0,0}, + {22130,22128,22131 ,9558,9556,9559 ,0,0,0}, {22124,21670,21650 ,9549,9560,9552 ,0,0,0}, + {22125,21650,21610 ,9551,9552,9561 ,0,0,0}, {22129,22077,22076 ,9557,9562,9550 ,0,0,0}, + {21689,21670,22075 ,9563,9560,9548 ,0,0,0}, {21649,22125,21610 ,9545,9551,9561 ,0,0,0}, + {22123,22132,22125 ,9547,9564,9551 ,0,0,0}, {22125,21649,22123 ,9551,9545,9547 ,0,0,0}, + {22132,22126,22128 ,9564,9553,9556 ,0,0,0}, {22130,22129,22076 ,9558,9557,9550 ,0,0,0}, + {22128,22130,22125 ,9556,9558,9551 ,0,0,0}, {22075,21670,22124 ,9548,9560,9549 ,0,0,0}, + {22128,22125,22132 ,9556,9551,9564 ,0,0,0}, {22127,22131,22128 ,9555,9559,9556 ,0,0,0}, + {22076,22124,22130 ,9550,9549,9558 ,0,0,0}, {22125,22130,22124 ,9551,9558,9549 ,0,0,0}, + {22133,22134,22135 ,9565,9566,9567 ,0,0,0}, {22136,22137,22138 ,9568,9569,9570 ,0,0,0}, + {22139,22140,22141 ,9571,9572,9573 ,0,0,0}, {22107,22105,22142 ,9574,9575,9576 ,0,0,0}, + {22143,22144,22081 ,9577,9578,9579 ,0,0,0}, {22145,22146,22147 ,9580,9581,9582 ,0,0,0}, + {22148,22149,22134 ,9583,9584,9566 ,0,0,0}, {22071,22083,22149 ,9585,9586,9584 ,0,0,0}, + {22150,22112,22103 ,9587,9588,9589 ,0,0,0}, {22133,22135,22150 ,9565,9567,9587 ,0,0,0}, + {22071,22149,22148 ,9585,9584,9583 ,0,0,0}, {22138,22135,22134 ,9570,9567,9566 ,0,0,0}, + {22083,22151,22149 ,9586,9590,9584 ,0,0,0}, {22144,22151,22082 ,9578,9590,9591 ,0,0,0}, + {22152,22143,22147 ,9592,9577,9582 ,0,0,0}, {22153,22141,22137 ,9593,9573,9569 ,0,0,0}, + {22078,22129,22145 ,9594,9595,9580 ,0,0,0}, {22140,22152,22142 ,9572,9592,9576 ,0,0,0}, + {22077,22129,22078 ,9596,9595,9594 ,0,0,0}, {22145,22129,22131 ,9580,9595,9597 ,0,0,0}, + {22082,22151,22083 ,9591,9590,9586 ,0,0,0}, {22082,22081,22144 ,9591,9579,9578 ,0,0,0}, + {22150,22135,22112 ,9587,9567,9588 ,0,0,0}, {22148,22134,22133 ,9583,9566,9565 ,0,0,0}, + {22138,22134,22136 ,9570,9566,9568 ,0,0,0}, {22111,22112,22135 ,9598,9588,9567 ,0,0,0}, + {22136,22149,22151 ,9568,9584,9590 ,0,0,0}, {22127,22107,22142 ,9599,9574,9576 ,0,0,0}, + {22135,22138,22111 ,9567,9570,9598 ,0,0,0}, {22149,22136,22134 ,9584,9568,9566 ,0,0,0}, + {22137,22136,22153 ,9569,9568,9593 ,0,0,0}, {22110,22111,22138 ,9600,9598,9570 ,0,0,0}, + {22144,22153,22151 ,9578,9593,9590 ,0,0,0}, {22080,22143,22081 ,9601,9577,9579 ,0,0,0}, + {22138,22137,22110 ,9570,9569,9600 ,0,0,0}, {22151,22153,22136 ,9590,9593,9568 ,0,0,0}, + {22141,22153,22139 ,9573,9593,9571 ,0,0,0}, {22109,22110,22137 ,9602,9600,9569 ,0,0,0}, + {22143,22139,22144 ,9577,9571,9578 ,0,0,0}, {22079,22147,22080 ,9603,9582,9601 ,0,0,0}, + {22141,22108,22109 ,9573,9604,9602 ,0,0,0}, {22144,22139,22153 ,9578,9571,9593 ,0,0,0}, + {22139,22152,22140 ,9571,9592,9572 ,0,0,0}, {22109,22137,22141 ,9602,9569,9573 ,0,0,0}, + {22080,22147,22143 ,9601,9582,9577 ,0,0,0}, {22145,22079,22078 ,9580,9603,9594 ,0,0,0}, + {22140,22105,22108 ,9572,9575,9604 ,0,0,0}, {22143,22152,22139 ,9577,9592,9571 ,0,0,0}, + {22146,22142,22152 ,9581,9576,9592 ,0,0,0}, {22108,22141,22140 ,9604,9573,9572 ,0,0,0}, + {22079,22145,22147 ,9603,9580,9582 ,0,0,0}, {22147,22146,22152 ,9582,9581,9592 ,0,0,0}, + {22131,22127,22146 ,9597,9599,9581 ,0,0,0}, {22145,22131,22146 ,9580,9597,9581 ,0,0,0}, + {22127,22142,22146 ,9599,9576,9581 ,0,0,0}, {22105,22140,22142 ,9575,9572,9576 ,0,0,0}, + {22150,22101,22154 ,9605,9606,9607 ,0,0,0}, {22074,22155,22072 ,9608,9609,9468 ,0,0,0}, + {22154,22101,22156 ,9607,9606,9610 ,0,0,0}, {22101,22102,22156 ,9606,82,9610 ,0,0,0}, + {22154,22157,22155 ,9607,9611,9609 ,0,0,0}, {22150,22103,22101 ,9605,82,9606 ,0,0,0}, + {22155,22157,22072 ,9609,9611,9468 ,0,0,0}, {22148,22155,22074 ,9612,9609,9608 ,0,0,0}, + {22071,22148,22074 ,9613,9612,9608 ,0,0,0}, {22148,22133,22155 ,9612,9614,9609 ,0,0,0}, + {22133,22150,22154 ,9614,9605,9607 ,0,0,0}, {22133,22154,22155 ,9614,9607,9609 ,0,0,0}, + {22157,22154,22156 ,9611,9607,9610 ,0,0,0}, {22122,22121,22114 ,9615,9616,9617 ,0,0,0}, + {22156,22102,22115 ,9618,82,9619 ,0,0,0}, {22115,22116,22158 ,9619,9620,9621 ,0,0,0}, + {22115,22158,22156 ,9619,9621,9618 ,0,0,0}, {22113,22122,22114 ,9622,9615,9617 ,0,0,0}, + {22120,22119,22159 ,9623,9624,9625 ,0,0,0}, {22159,22160,22120 ,9625,9626,9623 ,0,0,0}, + {22157,22158,22161 ,9627,9621,9628 ,0,0,0}, {22161,22158,22160 ,9628,9621,9626 ,0,0,0}, + {22119,22073,22070 ,9624,9629,9630 ,0,0,0}, {22157,22161,22072 ,9627,9628,9631 ,0,0,0}, + {22070,22161,22159 ,9630,9628,9625 ,0,0,0}, {22156,22158,22157 ,9618,9621,9627 ,0,0,0}, + {22070,22069,22161 ,9630,9632,9628 ,0,0,0}, {22161,22069,22072 ,9628,9632,9631 ,0,0,0}, + {22158,22116,22160 ,9621,9620,9626 ,0,0,0}, {22114,22160,22116 ,9617,9626,9620 ,0,0,0}, + {22070,22159,22119 ,9630,9625,9624 ,0,0,0}, {22161,22160,22159 ,9628,9626,9625 ,0,0,0}, + {22121,22160,22114 ,9616,9626,9617 ,0,0,0}, {22121,22120,22160 ,9616,9623,9626 ,0,0,0}, + {21995,22162,22163 ,9633,9634,9635 ,0,0,0}, {22107,22126,22164 ,9636,9637,9638 ,0,0,0}, + {22165,22164,22126 ,9639,9638,9637 ,0,0,0}, {21995,22163,22013 ,9633,9635,9640 ,0,0,0}, + {22163,22162,22165 ,9635,9634,9639 ,0,0,0}, {22123,22030,22051 ,9641,9642,9643 ,0,0,0}, + {22013,22163,22051 ,9640,9635,9643 ,0,0,0}, {22089,22162,21977 ,9644,9634,9645 ,0,0,0}, + {22166,22089,22088 ,9646,9644,9647 ,0,0,0}, {22162,21995,21977 ,9634,9633,9645 ,0,0,0}, + {22164,22104,22106 ,9638,9648,9649 ,0,0,0}, {22164,22166,22167 ,9638,9646,9650 ,0,0,0}, + {21977,21484,22089 ,9645,9651,9644 ,0,0,0}, {22104,22167,22086 ,9648,9650,9652 ,0,0,0}, + {22167,22104,22164 ,9650,9648,9638 ,0,0,0}, {22163,22123,22051 ,9635,9641,9643 ,0,0,0}, + {22162,22166,22165 ,9634,9646,9639 ,0,0,0}, {22132,22123,22163 ,9653,9641,9635 ,0,0,0}, + {22089,22166,22162 ,9644,9646,9634 ,0,0,0}, {22167,22088,22087 ,9650,9647,9654 ,0,0,0}, + {22126,22132,22165 ,9637,9653,9639 ,0,0,0}, {22163,22165,22132 ,9635,9639,9653 ,0,0,0}, + {22088,22167,22166 ,9647,9650,9646 ,0,0,0}, {22086,22167,22087 ,9652,9650,9654 ,0,0,0}, + {22164,22106,22107 ,9638,9649,9636 ,0,0,0}, {22166,22164,22165 ,9646,9638,9639 ,0,0,0}, + {22168,21609,22169 ,9655,9656,9657 ,0,0,0}, {21609,22170,22171 ,9656,9658,9659 ,0,0,0}, + {22171,21608,21609 ,9659,9660,9656 ,0,0,0}, {21609,22168,22170 ,9656,9655,9658 ,0,0,0}, + {21608,22172,22173 ,9660,9661,9662 ,0,0,0}, {21608,22171,22172 ,9660,9659,9661 ,0,0,0}, + {21609,22174,22169 ,9656,9663,9657 ,0,0,0}, {21608,22173,21504 ,9660,9662,9664 ,0,0,0}, + {22175,21609,21517 ,9665,9656,9666 ,0,0,0}, {21609,22175,22174 ,9656,9665,9663 ,0,0,0}, + {21518,22176,22177 ,9667,9667,9668 ,0,0,0}, {22178,22179,21516 ,9669,9670,9671 ,0,0,0}, + {22180,22181,21518 ,9672,9673,9667 ,0,0,0}, {22180,21518,22177 ,9672,9667,9668 ,0,0,0}, + {21518,22182,21516 ,9667,9674,9671 ,0,0,0}, {22182,21518,22181 ,9674,9667,9673 ,0,0,0}, + {22183,21516,22179 ,9675,9671,9670 ,0,0,0}, {22182,22178,21516 ,9674,9669,9671 ,0,0,0}, + {22175,21517,22183 ,9665,9666,9675 ,0,0,0}, {22183,21517,21516 ,9675,9666,9671 ,0,0,0}, + {21726,22184,22185 ,9676,9677,9678 ,0,0,0}, {21803,22186,21757 ,9679,9680,9681 ,0,0,0}, + {22184,21726,22187 ,9677,9676,9682 ,0,0,0}, {22185,22188,21726 ,9678,9676,9676 ,0,0,0}, + {22187,21726,21757 ,9682,9676,9681 ,0,0,0}, {22189,22187,21757 ,9683,9682,9681 ,0,0,0}, + {22189,21757,22186 ,9683,9681,9680 ,0,0,0}, {21760,21784,22190 ,9684,9685,9686 ,0,0,0}, + {21760,22191,22192 ,9684,9687,9688 ,0,0,0}, {22190,22191,21760 ,9686,9687,9684 ,0,0,0}, + {21803,22192,22193 ,9679,9688,9689 ,0,0,0}, {21803,21760,22192 ,9679,9684,9688 ,0,0,0}, + {21803,22194,22195 ,9679,9690,9691 ,0,0,0}, {22193,22194,21803 ,9689,9690,9679 ,0,0,0}, + {21803,22196,22197 ,9679,9692,9693 ,0,0,0}, {22195,22196,21803 ,9691,9692,9679 ,0,0,0}, + {22186,21803,22198 ,9680,9679,9694 ,0,0,0}, {22197,22198,21803 ,9693,9694,9679 ,0,0,0}, + {22067,22176,22028 ,9695,9696,9695 ,0,0,0}, {21518,21992,22176 ,9695,9695,9696 ,0,0,0}, + {22049,22199,22176 ,9695,9696,9696 ,0,0,0}, {22176,22067,22049 ,9696,9695,9695 ,0,0,0}, + {22011,22028,22176 ,9695,9695,9696 ,0,0,0}, {22011,22176,21992 ,9695,9696,9695 ,0,0,0}, + {22200,22201,22175 ,126,126,126 ,0,0,0}, {22183,22202,22200 ,9697,126,126 ,0,0,0}, + {22200,22175,22183 ,126,126,9697 ,0,0,0}, {22203,22204,22205 ,9698,9699,9700 ,0,0,0}, + {22204,22206,22205 ,9699,9701,9700 ,0,0,0}, {22204,22203,22207 ,9699,9698,9702 ,0,0,0}, + {22170,22208,22207 ,9703,9704,9702 ,0,0,0}, {22203,22170,22207 ,9698,9703,9702 ,0,0,0}, + {22168,22208,22170 ,9705,9704,9703 ,0,0,0}, {22208,22168,22209 ,9704,9705,9706 ,0,0,0}, + {22169,22210,22209 ,9707,9708,9706 ,0,0,0}, {22209,22168,22169 ,9706,9705,9707 ,0,0,0}, + {22210,22174,22211 ,9708,9709,9710 ,0,0,0}, {22174,22210,22169 ,9709,9708,9707 ,0,0,0}, + {22201,22211,22175 ,9711,9710,9712 ,0,0,0}, {22174,22175,22211 ,9709,9712,9710 ,0,0,0}, + {22212,22213,22181 ,9713,9714,9715 ,0,0,0}, {22214,22182,22213 ,9716,9717,9714 ,0,0,0}, + {22183,22179,22202 ,126,9718,126 ,0,0,0}, {22178,22215,22179 ,9719,9720,9718 ,0,0,0}, + {22178,22214,22215 ,9719,9716,9720 ,0,0,0}, {22215,22202,22179 ,9720,126,9718 ,0,0,0}, + {22182,22214,22178 ,9717,9716,9719 ,0,0,0}, {22182,22181,22213 ,9717,9715,9714 ,0,0,0}, + {22212,22181,22180 ,9713,9715,9721 ,0,0,0}, {22180,22177,22216 ,9721,9722,9723 ,0,0,0}, + {22216,22212,22180 ,9723,9713,9721 ,0,0,0}, {22217,22177,22176 ,9724,9722,9725 ,0,0,0}, + {22177,22217,22216 ,9722,9724,9723 ,0,0,0}, {22217,22176,22199 ,9724,9725,9725 ,0,0,0}, + {21687,22199,21668 ,9726,9727,9728 ,0,0,0}, {22218,22188,22219 ,9729,9730,9731 ,0,0,0}, + {22188,22212,22216 ,9730,9732,9733 ,0,0,0}, {22216,22217,22188 ,9733,9734,9730 ,0,0,0}, + {22218,22220,22188 ,9729,9735,9730 ,0,0,0}, {22188,22221,22212 ,9730,9736,9732 ,0,0,0}, + {22220,22221,22188 ,9735,9736,9730 ,0,0,0}, {22199,21726,22188 ,9727,9737,9730 ,0,0,0}, + {22217,22199,22188 ,9734,9727,9730 ,0,0,0}, {22199,21706,21726 ,9727,9738,9737 ,0,0,0}, + {21706,22199,21687 ,9738,9727,9726 ,0,0,0}, {22199,21646,21647 ,9727,9739,9740 ,0,0,0}, + {22199,22049,21646 ,9727,9727,9739 ,0,0,0}, {21647,21668,22199 ,9740,9728,9727 ,0,0,0}, + {21881,21901,22222 ,9741,9742,9743 ,0,0,0}, {22190,22223,22191 ,9744,9745,9746 ,0,0,0}, + {22224,22223,21842 ,9747,9745,9748 ,0,0,0}, {22225,22206,22226 ,9749,9750,9751 ,0,0,0}, + {22227,22225,22226 ,9752,9749,9751 ,0,0,0}, {22228,22229,22230 ,9753,9754,9755 ,0,0,0}, + {22229,22227,22230 ,9754,9752,9755 ,0,0,0}, {22223,21822,21842 ,9745,9756,9748 ,0,0,0}, + {22224,21842,21861 ,9747,9748,9757 ,0,0,0}, {22228,22192,22191 ,9753,9758,9746 ,0,0,0}, + {21784,21822,22190 ,9759,9756,9744 ,0,0,0}, {21881,22224,21861 ,9741,9747,9757 ,0,0,0}, + {22222,22231,22224 ,9743,9760,9747 ,0,0,0}, {22224,21881,22222 ,9747,9741,9743 ,0,0,0}, + {22231,22225,22227 ,9760,9749,9752 ,0,0,0}, {22229,22228,22191 ,9754,9753,9746 ,0,0,0}, + {22227,22229,22224 ,9752,9754,9747 ,0,0,0}, {22190,21822,22223 ,9744,9756,9745 ,0,0,0}, + {22227,22224,22231 ,9752,9747,9760 ,0,0,0}, {22226,22230,22227 ,9751,9755,9752 ,0,0,0}, + {22191,22223,22229 ,9746,9745,9754 ,0,0,0}, {22224,22229,22223 ,9747,9754,9745 ,0,0,0}, + {22232,22233,22234 ,9761,9762,9763 ,0,0,0}, {22208,22235,22236 ,9764,9765,9766 ,0,0,0}, + {22208,22209,22235 ,9764,9767,9765 ,0,0,0}, {22226,22204,22237 ,9768,9769,9770 ,0,0,0}, + {22238,22196,22239 ,9771,9772,9773 ,0,0,0}, {22226,22206,22204 ,9768,9774,9769 ,0,0,0}, + {22240,22241,22242 ,9775,9776,9777 ,0,0,0}, {22210,22243,22244 ,9778,9779,9780 ,0,0,0}, + {22201,22241,22245 ,126,9776,9781 ,0,0,0}, {22240,22246,22245 ,9775,9782,9781 ,0,0,0}, + {22198,22197,22247 ,9783,9784,9785 ,0,0,0}, {22197,22238,22247 ,9784,9771,9785 ,0,0,0}, + {22248,22249,22232 ,9786,9787,9761 ,0,0,0}, {22238,22239,22246 ,9771,9773,9782 ,0,0,0}, + {22250,22186,22198 ,9788,9789,9783 ,0,0,0}, {22207,22236,22237 ,9790,9766,9770 ,0,0,0}, + {22210,22244,22209 ,9778,9780,9767 ,0,0,0}, {22237,22234,22230 ,9770,9763,9791 ,0,0,0}, + {22230,22234,22228 ,9791,9763,9792 ,0,0,0}, {22228,22233,22192 ,9792,9762,9793 ,0,0,0}, + {22226,22237,22230 ,9768,9770,9791 ,0,0,0}, {22204,22207,22237 ,9769,9790,9770 ,0,0,0}, + {22233,22228,22234 ,9762,9792,9763 ,0,0,0}, {22233,22249,22193 ,9762,9787,9794 ,0,0,0}, + {22234,22236,22232 ,9763,9766,9761 ,0,0,0}, {22192,22233,22193 ,9793,9762,9794 ,0,0,0}, + {22237,22236,22234 ,9770,9766,9763 ,0,0,0}, {22207,22208,22236 ,9790,9764,9766 ,0,0,0}, + {22249,22233,22232 ,9787,9762,9761 ,0,0,0}, {22249,22251,22194 ,9787,9795,9796 ,0,0,0}, + {22232,22235,22248 ,9761,9765,9786 ,0,0,0}, {22193,22249,22194 ,9794,9787,9796 ,0,0,0}, + {22236,22235,22232 ,9766,9765,9761 ,0,0,0}, {22244,22235,22209 ,9780,9765,9767 ,0,0,0}, + {22251,22249,22248 ,9795,9787,9786 ,0,0,0}, {22251,22239,22195 ,9795,9773,9797 ,0,0,0}, + {22244,22252,22248 ,9780,9798,9786 ,0,0,0}, {22194,22251,22195 ,9796,9795,9797 ,0,0,0}, + {22244,22248,22235 ,9780,9786,9765 ,0,0,0}, {22211,22243,22210 ,9799,9779,9778 ,0,0,0}, + {22239,22251,22252 ,9773,9795,9798 ,0,0,0}, {22248,22252,22251 ,9786,9798,9795 ,0,0,0}, + {22243,22246,22252 ,9779,9782,9798 ,0,0,0}, {22195,22239,22196 ,9797,9773,9772 ,0,0,0}, + {22244,22243,22252 ,9780,9779,9798 ,0,0,0}, {22201,22245,22211 ,126,9781,9799 ,0,0,0}, + {22247,22238,22240 ,9785,9771,9775 ,0,0,0}, {22252,22246,22239 ,9798,9782,9773 ,0,0,0}, + {22246,22240,22238 ,9782,9775,9771 ,0,0,0}, {22196,22238,22197 ,9772,9771,9784 ,0,0,0}, + {22243,22211,22245 ,9779,9799,9781 ,0,0,0}, {22246,22243,22245 ,9782,9779,9781 ,0,0,0}, + {22247,22242,22250 ,9785,9777,9788 ,0,0,0}, {22241,22240,22245 ,9776,9775,9781 ,0,0,0}, + {22250,22198,22247 ,9788,9783,9785 ,0,0,0}, {22242,22247,22240 ,9777,9785,9775 ,0,0,0}, + {22241,22200,22253 ,9800,9801,9802 ,0,0,0}, {22189,22254,22187 ,9803,9804,9682 ,0,0,0}, + {22253,22200,22255 ,9802,9801,9805 ,0,0,0}, {22200,22202,22255 ,9801,126,9805 ,0,0,0}, + {22253,22256,22254 ,9802,9806,9804 ,0,0,0}, {22241,22201,22200 ,9800,126,9801 ,0,0,0}, + {22254,22256,22187 ,9804,9806,9682 ,0,0,0}, {22250,22254,22189 ,9807,9804,9803 ,0,0,0}, + {22186,22250,22189 ,9808,9807,9803 ,0,0,0}, {22250,22242,22254 ,9807,9809,9804 ,0,0,0}, + {22242,22241,22253 ,9809,9800,9802 ,0,0,0}, {22242,22253,22254 ,9809,9802,9804 ,0,0,0}, + {22256,22253,22255 ,9806,9802,9805 ,0,0,0}, {22221,22220,22213 ,9810,9811,9812 ,0,0,0}, + {22255,22202,22215 ,9813,126,9814 ,0,0,0}, {22215,22214,22257 ,9814,9815,9816 ,0,0,0}, + {22215,22257,22255 ,9814,9816,9813 ,0,0,0}, {22212,22221,22213 ,9817,9810,9812 ,0,0,0}, + {22218,22219,22258 ,9818,9819,9820 ,0,0,0}, {22258,22259,22218 ,9820,9821,9818 ,0,0,0}, + {22256,22257,22260 ,9822,9816,9823 ,0,0,0}, {22260,22257,22259 ,9823,9816,9821 ,0,0,0}, + {22219,22188,22185 ,9819,9824,9825 ,0,0,0}, {22256,22260,22187 ,9822,9823,9826 ,0,0,0}, + {22185,22260,22258 ,9825,9823,9820 ,0,0,0}, {22255,22257,22256 ,9813,9816,9822 ,0,0,0}, + {22185,22184,22260 ,9825,9827,9823 ,0,0,0}, {22260,22184,22187 ,9823,9827,9826 ,0,0,0}, + {22257,22214,22259 ,9816,9815,9821 ,0,0,0}, {22213,22259,22214 ,9812,9821,9815 ,0,0,0}, + {22185,22258,22219 ,9825,9820,9819 ,0,0,0}, {22260,22259,22258 ,9823,9821,9820 ,0,0,0}, + {22220,22259,22213 ,9811,9821,9812 ,0,0,0}, {22220,22218,22259 ,9811,9818,9821 ,0,0,0}, + {22261,21956,22262 ,9828,9829,9830 ,0,0,0}, {21975,21504,22173 ,9831,9832,9833 ,0,0,0}, + {22203,22263,22170 ,9834,9835,9836 ,0,0,0}, {22264,22225,22265 ,9837,9838,9839 ,0,0,0}, + {22225,22264,22205 ,9838,9837,9840 ,0,0,0}, {22205,22206,22225 ,9840,9841,9838 ,0,0,0}, + {22231,22265,22225 ,9842,9839,9838 ,0,0,0}, {22261,21939,21956 ,9828,9843,9829 ,0,0,0}, + {22205,22264,22203 ,9840,9837,9834 ,0,0,0}, {22263,22265,22266 ,9835,9839,9844 ,0,0,0}, + {22222,21901,21921 ,9845,9846,9847 ,0,0,0}, {21939,22261,21921 ,9843,9828,9847 ,0,0,0}, + {22266,22172,22171 ,9844,9848,9849 ,0,0,0}, {22262,21975,22173 ,9830,9831,9833 ,0,0,0}, + {22264,22265,22263 ,9837,9839,9835 ,0,0,0}, {22266,22171,22263 ,9844,9849,9835 ,0,0,0}, + {22170,22263,22171 ,9836,9835,9849 ,0,0,0}, {22203,22264,22263 ,9834,9837,9835 ,0,0,0}, + {22261,22231,22222 ,9828,9842,9845 ,0,0,0}, {22266,22261,22262 ,9844,9828,9830 ,0,0,0}, + {22266,22265,22261 ,9844,9839,9828 ,0,0,0}, {22172,22266,22262 ,9848,9844,9830 ,0,0,0}, + {22231,22261,22265 ,9842,9828,9839 ,0,0,0}, {21921,22261,22222 ,9847,9828,9845 ,0,0,0}, + {21975,22262,21956 ,9831,9830,9829 ,0,0,0}, {22262,22173,22172 ,9830,9833,9848 ,0,0,0}, + {21598,21461,21460 ,9850,9851,8275 ,0,0,0}, {22267,22268,21487 ,9852,9853,9854 ,0,0,0}, + {21534,22269,22270 ,9855,9856,9857 ,0,0,0}, {21492,21491,22271 ,9858,9859,9860 ,0,0,0}, + {21531,21566,22272 ,9861,9862,9863 ,0,0,0}, {21495,21496,22273 ,9864,9865,9866 ,0,0,0}, + {21495,22274,21491 ,9864,9867,9859 ,0,0,0}, {22275,21586,22276 ,9868,9869,9870 ,0,0,0}, + {21586,22275,21496 ,9869,9868,9865 ,0,0,0}, {22277,22276,21585 ,9871,9870,9872 ,0,0,0}, + {21586,21585,22276 ,9869,9872,9870 ,0,0,0}, {21474,21475,22277 ,126,126,9871 ,0,0,0}, + {22277,21585,21474 ,9871,9872,126 ,0,0,0}, {22273,22274,21495 ,9866,9867,9864 ,0,0,0}, + {21496,22275,22273 ,9865,9868,9866 ,0,0,0}, {22271,22272,21492 ,9860,9863,9858 ,0,0,0}, + {21491,22274,22271 ,9859,9867,9860 ,0,0,0}, {22267,21531,22272 ,9852,9861,9863 ,0,0,0}, + {21566,21492,22272 ,9862,9858,9863 ,0,0,0}, {22268,21485,21487 ,9853,9873,9854 ,0,0,0}, + {22267,21487,21531 ,9852,9854,9861 ,0,0,0}, {21534,21485,22269 ,9855,9873,9856 ,0,0,0}, + {22268,22269,21485 ,9853,9856,9873 ,0,0,0}, {21598,22270,22278 ,9850,9857,9874 ,0,0,0}, + {21534,22270,21598 ,9855,9857,9850 ,0,0,0}, {21461,21598,22278 ,9851,9850,9874 ,0,0,0}, + {22269,21440,21443 ,730,730,730 ,0,0,0}, {21456,22279,21454 ,730,730,730 ,0,0,0}, + {21456,21459,22280 ,730,730,730 ,0,0,0}, {21452,21454,22281 ,730,730,730 ,0,0,0}, + {21459,21446,22280 ,730,730,730 ,0,0,0}, {22279,21456,22280 ,730,730,730 ,0,0,0}, + {21446,21459,21461 ,730,730,730 ,0,0,0}, {21452,22282,21449 ,730,730,730 ,0,0,0}, + {22278,21446,21461 ,730,730,730 ,0,0,0}, {21428,21440,22267 ,730,730,730 ,0,0,0}, + {21463,21451,22283 ,730,730,730 ,0,0,0}, {22284,21464,21463 ,730,730,730 ,0,0,0}, + {15792,21428,22272 ,730,730,730 ,0,0,0}, {21430,22271,22274 ,730,730,730 ,0,0,0}, + {22285,21467,21464 ,730,730,730 ,0,0,0}, {21467,22286,21468 ,730,730,730 ,0,0,0}, + {21470,21468,22287 ,730,730,730 ,0,0,0}, {22274,21431,21430 ,730,730,730 ,0,0,0}, + {21431,22273,22275 ,730,730,730 ,0,0,0}, {21438,22277,21475 ,730,730,730 ,0,0,0}, + {21475,21473,21438 ,730,730,730 ,0,0,0}, {21470,22288,21473 ,730,730,730 ,0,0,0}, + {22276,21437,22275 ,730,730,730 ,0,0,0}, {21451,21449,22283 ,730,730,730 ,0,0,0}, + {21443,21445,22270 ,730,730,730 ,0,0,0}, {22272,22271,15792 ,730,730,730 ,0,0,0}, + {22279,22281,21454 ,730,730,730 ,0,0,0}, {22281,22282,21452 ,730,730,730 ,0,0,0}, + {22282,22283,21449 ,730,730,730 ,0,0,0}, {22283,22284,21463 ,730,730,730 ,0,0,0}, + {22284,22285,21464 ,730,730,730 ,0,0,0}, {22285,22286,21467 ,730,730,730 ,0,0,0}, + {22286,22287,21468 ,730,730,730 ,0,0,0}, {22287,22288,21470 ,730,730,730 ,0,0,0}, + {22288,21438,21473 ,730,730,730 ,0,0,0}, {21438,21434,22277 ,730,730,730 ,0,0,0}, + {21434,21437,22276 ,730,730,730 ,0,0,0}, {21434,22276,22277 ,730,730,730 ,0,0,0}, + {21437,21431,22275 ,730,730,730 ,0,0,0}, {22273,21431,22274 ,730,730,730 ,0,0,0}, + {21430,15792,22271 ,730,730,730 ,0,0,0}, {21428,22267,22272 ,730,730,730 ,0,0,0}, + {21440,22268,22267 ,730,730,730 ,0,0,0}, {22269,21443,22270 ,730,730,730 ,0,0,0}, + {22268,21440,22269 ,730,730,730 ,0,0,0}, {22270,21445,22278 ,730,730,730 ,0,0,0}, + {21446,22278,21445 ,730,730,730 ,0,0,0}, {21444,22289,22290 ,730,730,9875 ,0,0,0}, + {22291,22290,22292 ,730,9875,730 ,0,0,0}, {22291,22292,22293 ,730,730,9875 ,0,0,0}, + {22294,22290,22291 ,730,9875,730 ,0,0,0}, {22294,21447,22290 ,730,730,9875 ,0,0,0}, + {22293,22292,22295 ,9875,730,9876 ,0,0,0}, {21444,22290,21447 ,730,9875,730 ,0,0,0}, + {22289,21442,22296 ,730,730,9876 ,0,0,0}, {22289,21444,21442 ,730,730,730 ,0,0,0}, + {22296,21442,22297 ,9876,730,730 ,0,0,0}, {22297,21442,21441 ,730,730,9876 ,0,0,0}, + {22297,21441,21439 ,730,9876,730 ,0,0,0}, {22298,21439,21427 ,9877,730,9876 ,0,0,0}, + {21439,22298,22297 ,730,9877,730 ,0,0,0}, {21435,22298,21432 ,730,9877,730 ,0,0,0}, + {21427,21432,22298 ,9876,730,9877 ,0,0,0}, {21436,21429,21433 ,9876,730,9878 ,0,0,0}, + {21432,21429,21436 ,730,730,9876 ,0,0,0}, {21436,21435,21432 ,9876,730,730 ,0,0,0}, + {21438,22288,22298 ,9879,9880,9881 ,0,0,0}, {22290,22289,22285 ,9882,9883,9884 ,0,0,0}, + {22296,22297,22287 ,9885,9886,9887 ,0,0,0}, {22295,22283,22282 ,9888,9889,9890 ,0,0,0}, + {22284,22283,22292 ,9891,9889,9892 ,0,0,0}, {22291,22281,22279 ,9893,9894,9895 ,0,0,0}, + {22281,22291,22293 ,9894,9893,9896 ,0,0,0}, {22280,22294,22279 ,9897,9898,9895 ,0,0,0}, + {22291,22279,22294 ,9893,9895,9898 ,0,0,0}, {22280,21446,21447 ,9897,96,96 ,0,0,0}, + {21447,22294,22280 ,96,9898,9897 ,0,0,0}, {22295,22282,22293 ,9888,9890,9896 ,0,0,0}, + {22282,22281,22293 ,9890,9894,9896 ,0,0,0}, {22285,22284,22290 ,9884,9891,9882 ,0,0,0}, + {22284,22292,22290 ,9891,9892,9882 ,0,0,0}, {22292,22283,22295 ,9892,9889,9888 ,0,0,0}, + {22297,22298,22288 ,9886,9881,9880 ,0,0,0}, {22286,22285,22289 ,9899,9884,9883 ,0,0,0}, + {22288,22287,22297 ,9880,9887,9886 ,0,0,0}, {22286,22296,22287 ,9899,9885,9887 ,0,0,0}, + {22289,22296,22286 ,9883,9885,9899 ,0,0,0}, {22298,21435,21438 ,9881,761,9879 ,0,0,0}, + {21500,21415,21414 ,9900,82,9901 ,0,0,0}, {22299,22300,21582 ,9902,9903,9904 ,0,0,0}, + {21583,22301,21502 ,9905,9906,9907 ,0,0,0}, {22302,21521,22303 ,9908,9909,9910 ,0,0,0}, + {21578,21523,22304 ,9911,9912,9913 ,0,0,0}, {22305,21520,21580 ,9914,9915,9916 ,0,0,0}, + {21520,22305,22303 ,9915,9914,9910 ,0,0,0}, {21512,22306,21580 ,9917,9918,9916 ,0,0,0}, + {22305,21580,22306 ,9914,9916,9918 ,0,0,0}, {21512,21426,21425 ,9917,2619,3135 ,0,0,0}, + {21425,22306,21512 ,3135,9918,9917 ,0,0,0}, {21521,22302,21523 ,9909,9908,9912 ,0,0,0}, + {21521,21520,22303 ,9909,9915,9910 ,0,0,0}, {22299,21578,22304 ,9902,9911,9913 ,0,0,0}, + {22304,21523,22302 ,9913,9912,9908 ,0,0,0}, {22300,21583,21582 ,9903,9905,9904 ,0,0,0}, + {22299,21582,21578 ,9902,9904,9911 ,0,0,0}, {22301,22307,21502 ,9906,9919,9907 ,0,0,0}, + {22300,22301,21583 ,9903,9906,9905 ,0,0,0}, {21415,21500,22307 ,82,9900,9919 ,0,0,0}, + {21502,22307,21500 ,9907,9919,9900 ,0,0,0}, {21422,22299,21423 ,730,730,730 ,0,0,0}, + {21419,22301,21420 ,730,730,730 ,0,0,0}, {21425,22304,22302 ,730,730,730 ,0,0,0}, + {22306,22302,22303 ,730,730,730 ,0,0,0}, {22305,22306,22303 ,730,730,730 ,0,0,0}, + {21423,22304,21425 ,730,730,730 ,0,0,0}, {21425,22302,22306 ,730,730,730 ,0,0,0}, + {21423,22299,22304 ,730,730,730 ,0,0,0}, {21422,22300,22299 ,730,730,730 ,0,0,0}, + {21422,21420,22301 ,730,730,730 ,0,0,0}, {22301,22300,21422 ,730,730,730 ,0,0,0}, + {22307,22301,21419 ,730,730,730 ,0,0,0}, {22307,21416,21415 ,730,730,730 ,0,0,0}, + {21416,22307,21419 ,730,730,730 ,0,0,0}, {21415,21416,21408 ,730,730,730 ,0,0,0}, + {21411,21405,21409 ,730,730,730 ,0,0,0}, {21408,21405,21411 ,730,730,730 ,0,0,0}, + {21411,21415,21408 ,730,730,730 ,0,0,0}, {21593,21393,21394 ,9920,9921,9922 ,0,0,0}, + {22308,22309,21539 ,9902,9903,9923 ,0,0,0}, {21540,22310,21592 ,9924,9906,9925 ,0,0,0}, + {22311,21537,21536 ,9908,9926,9927 ,0,0,0}, {21553,21537,22312 ,9928,9926,8336 ,0,0,0}, + {22313,21597,21489 ,9914,9929,9930 ,0,0,0}, {21536,21597,22314 ,9927,9929,9910 ,0,0,0}, + {21488,22315,21489 ,9931,9918,9930 ,0,0,0}, {22313,21489,22315 ,9914,9930,9918 ,0,0,0}, + {21488,21404,21403 ,9931,96,9932 ,0,0,0}, {21403,22315,21488 ,9932,9918,9931 ,0,0,0}, + {22311,21536,22314 ,9908,9927,9910 ,0,0,0}, {22314,21597,22313 ,9910,9929,9914 ,0,0,0}, + {21553,22312,22308 ,9928,8336,9902 ,0,0,0}, {22312,21537,22311 ,8336,9926,9908 ,0,0,0}, + {22309,21540,21539 ,9903,9924,9923 ,0,0,0}, {22308,21539,21553 ,9902,9923,9928 ,0,0,0}, + {22310,22316,21592 ,9906,9919,9925 ,0,0,0}, {22309,22310,21540 ,9903,9906,9924 ,0,0,0}, + {21393,21593,22316 ,9921,9920,9919 ,0,0,0}, {21592,22316,21593 ,9925,9919,9920 ,0,0,0}, + {21398,22308,21400 ,730,730,730 ,0,0,0}, {21395,22310,21397 ,730,730,730 ,0,0,0}, + {21403,22312,22311 ,730,730,730 ,0,0,0}, {22315,22311,22314 ,730,730,730 ,0,0,0}, + {22313,22315,22314 ,730,730,730 ,0,0,0}, {21400,22312,21403 ,730,730,730 ,0,0,0}, + {21403,22311,22315 ,730,730,730 ,0,0,0}, {21400,22308,22312 ,730,730,730 ,0,0,0}, + {21398,22309,22308 ,730,730,730 ,0,0,0}, {21398,21397,22310 ,730,730,730 ,0,0,0}, + {22310,22309,21398 ,730,730,730 ,0,0,0}, {22316,22310,21395 ,730,730,730 ,0,0,0}, + {22316,21383,21393 ,730,730,730 ,0,0,0}, {21383,22316,21395 ,730,730,730 ,0,0,0}, + {21393,21383,21386 ,730,730,730 ,0,0,0}, {21389,21387,21390 ,730,730,730 ,0,0,0}, + {21386,21387,21389 ,730,730,730 ,0,0,0}, {21389,21393,21386 ,730,730,730 ,0,0,0} +// X-Ufo 8ZollPropeller.prt + , {22317,22318,22319 ,9933,9934,9935 ,0,0,0}, {22317,22320,22321 ,9933,9936,9937 ,0,0,0}, + {22321,22318,22317 ,9937,9934,9933 ,0,0,0}, {22322,22320,22323 ,9938,9936,9939 ,0,0,0}, + {22320,22322,22321 ,9936,9938,9937 ,0,0,0}, {22324,22325,22326 ,9940,9941,9942 ,0,0,0}, + {22322,22323,22325 ,9938,9939,9941 ,0,0,0}, {22327,22328,22324 ,9943,2394,9940 ,0,0,0}, + {22327,22329,22328 ,9943,9944,2394 ,0,0,0}, {22327,22324,22326 ,9943,9940,9942 ,0,0,0}, + {22325,22323,22326 ,9941,9939,9942 ,0,0,0}, {22330,22319,22318 ,9945,9935,9934 ,0,0,0}, + {22331,22330,22332 ,9946,9945,9947 ,0,0,0}, {22330,22331,22319 ,9945,9946,9935 ,0,0,0}, + {22333,22334,22332 ,9948,9949,9947 ,0,0,0}, {22331,22332,22334 ,9946,9947,9949 ,0,0,0}, + {22333,22335,22336 ,9948,9950,9951 ,0,0,0}, {22336,22334,22333 ,9951,9949,9948 ,0,0,0}, + {22337,22335,22338 ,9952,9950,9953 ,0,0,0}, {22335,22337,22336 ,9950,9952,9951 ,0,0,0}, + {22337,22338,22339 ,9952,9953,9954 ,0,0,0}, {22340,22341,22342 ,9938,9955,9956 ,0,0,0}, + {22340,22343,22341 ,9938,9937,9955 ,0,0,0}, {22340,22342,22344 ,9938,9956,9941 ,0,0,0}, + {22344,22345,22346 ,9941,9957,9940 ,0,0,0}, {22345,22344,22342 ,9957,9941,9956 ,0,0,0}, + {22347,22346,22345 ,9958,9940,9957 ,0,0,0}, {22348,22341,22343 ,9959,9955,9937 ,0,0,0}, + {22347,22349,22350 ,9958,9960,9961 ,0,0,0}, {22350,22346,22347 ,9961,9940,9958 ,0,0,0}, + {22348,22343,22351 ,9959,9937,9962 ,0,0,0}, {22351,22352,22348 ,9962,9963,9959 ,0,0,0}, + {22353,22352,22354 ,9964,9963,9945 ,0,0,0}, {22351,22354,22352 ,9962,9945,9963 ,0,0,0}, + {22355,22356,22353 ,9947,9965,9964 ,0,0,0}, {22353,22354,22355 ,9964,9945,9947 ,0,0,0}, + {22357,22358,22356 ,9948,9950,9965 ,0,0,0}, {22357,22356,22355 ,9948,9965,9947 ,0,0,0}, + {22359,22358,22360 ,9966,9950,9967 ,0,0,0}, {22358,22359,22356 ,9950,9966,9965 ,0,0,0}, + {22359,22360,22361 ,9966,9967,9968 ,0,0,0}, {22362,22363,15837 ,9969,9970,9971 ,0,0,0}, + {22364,22365,22366 ,9972,9973,9974 ,0,0,0}, {22367,22362,15837 ,9975,9969,9971 ,0,0,0}, + {22364,22366,22368 ,9972,9974,9976 ,0,0,0}, {22365,22364,22367 ,9973,9972,9975 ,0,0,0}, + {22365,22367,15837 ,9973,9975,9971 ,0,0,0}, {22369,22370,22371 ,9977,9978,9979 ,0,0,0}, + {22371,22368,22372 ,9979,9976,9980 ,0,0,0}, {22369,22371,22372 ,9977,9979,9980 ,0,0,0}, + {22370,22369,22373 ,9978,9977,9981 ,0,0,0}, {22372,22368,22366 ,9980,9976,9974 ,0,0,0}, + {22362,22374,22363 ,9969,9945,9970 ,0,0,0}, {22375,22374,22376 ,9982,9945,9983 ,0,0,0}, + {22374,22375,22363 ,9945,9982,9970 ,0,0,0}, {22377,22378,22376 ,9984,9985,9983 ,0,0,0}, + {22375,22376,22378 ,9982,9983,9985 ,0,0,0}, {22377,22379,22380 ,9984,9986,9987 ,0,0,0}, + {22380,22378,22377 ,9987,9985,9984 ,0,0,0}, {22381,22379,22382 ,9988,9986,21 ,0,0,0}, + {22379,22381,22380 ,9986,9988,9987 ,0,0,0}, {22383,22384,22385 ,9989,9990,9991 ,0,0,0}, + {22385,22384,22386 ,9991,9990,9992 ,0,0,0}, {22387,22384,22383 ,9993,9990,9989 ,0,0,0}, + {22388,22385,22386 ,9994,9991,9992 ,0,0,0}, {22387,22383,22389 ,9993,9989,9995 ,0,0,0}, + {22389,22390,22391 ,9995,9996,9997 ,0,0,0}, {22390,22389,22383 ,9996,9995,9989 ,0,0,0}, + {22388,22386,22392 ,9994,9992,9998 ,0,0,0}, {22393,22394,22391 ,9999,10000,9997 ,0,0,0}, + {22391,22390,22393 ,9997,9996,9999 ,0,0,0}, {22394,22395,22396 ,10000,9961,10001 ,0,0,0}, + {22397,22394,22393 ,10002,10000,9999 ,0,0,0}, {22397,22395,22394 ,10002,9961,10000 ,0,0,0}, + {22386,22398,22392 ,9992,10003,9998 ,0,0,0}, {22398,22399,22400 ,10003,10004,10005 ,0,0,0}, + {22400,22392,22398 ,10005,9998,10003 ,0,0,0}, {22401,22399,22402 ,10006,10004,10007 ,0,0,0}, + {22399,22401,22400 ,10004,10006,10005 ,0,0,0}, {22403,22404,22402 ,10008,10009,10007 ,0,0,0}, + {22401,22402,22404 ,10006,10007,10009 ,0,0,0}, {22403,22405,22406 ,10008,10010,10011 ,0,0,0}, + {22406,22404,22403 ,10011,10009,10008 ,0,0,0}, {22407,22405,22408 ,10012,10010,10013 ,0,0,0}, + {22405,22407,22406 ,10010,10012,10011 ,0,0,0}, {22407,22408,22409 ,10012,10013,10014 ,0,0,0}, + {22409,22408,22410 ,10014,10013,10015 ,0,0,0}, {22411,22412,22413 ,10016,10017,10018 ,0,0,0}, + {22414,22415,22416 ,10019,10020,10021 ,0,0,0}, {22417,22418,22419 ,10022,10023,10024 ,0,0,0}, + {22420,22421,22422 ,10025,10026,10027 ,0,0,0}, {22423,22424,22425 ,10028,10029,10030 ,0,0,0}, + {22425,22339,22423 ,10030,10031,10028 ,0,0,0}, {22426,22427,22428 ,10032,10033,10034 ,0,0,0}, + {22404,22429,22401 ,10035,10036,10037 ,0,0,0}, {22430,22428,22431 ,10038,10034,10039 ,0,0,0}, + {22432,22433,22434 ,10040,10041,10042 ,0,0,0}, {22435,22436,22437 ,10043,10044,10045 ,0,0,0}, + {22438,22439,22440 ,10046,10047,10048 ,0,0,0}, {22441,22429,22434 ,10049,10036,10042 ,0,0,0}, + {22442,22353,22356 ,10050,10051,10052 ,0,0,0}, {22443,22444,22440 ,10053,10054,10048 ,0,0,0}, + {22445,22446,22447 ,10055,10056,10057 ,0,0,0}, {22448,22449,22445 ,10058,10059,10055 ,0,0,0}, + {22450,22451,22448 ,10060,10061,10058 ,0,0,0}, {22452,22448,22451 ,10062,10058,10061 ,0,0,0}, + {22453,22451,22450 ,10063,10061,10060 ,0,0,0}, {22454,22455,22456 ,10064,10065,10066 ,0,0,0}, + {22457,22442,22446 ,10067,10050,10056 ,0,0,0}, {22458,22459,22454 ,10068,10069,10064 ,0,0,0}, + {22407,22409,22434 ,10070,10071,10042 ,0,0,0}, {22436,22460,22437 ,10044,10072,10045 ,0,0,0}, + {22427,22461,22428 ,10033,10073,10034 ,0,0,0}, {22462,22463,22464 ,10074,10075,10076 ,0,0,0}, + {22385,22465,22383 ,10077,10078,10079 ,0,0,0}, {22422,22461,22466 ,10027,10073,10080 ,0,0,0}, + {22467,22336,22468 ,10081,10082,10083 ,0,0,0}, {22469,22470,22420 ,10084,10085,10025 ,0,0,0}, + {22415,22471,22472 ,10020,10086,10087 ,0,0,0}, {22473,22474,22475 ,10088,10089,10090 ,0,0,0}, + {22414,22416,22476 ,10019,10021,10091 ,0,0,0}, {22412,22411,22477 ,10017,10016,10092 ,0,0,0}, + {22478,22416,22473 ,10093,10021,10088 ,0,0,0}, {22479,22480,22481 ,10094,10095,10096 ,0,0,0}, + {22480,22477,22411 ,10095,10092,10016 ,0,0,0}, {22319,22482,22317 ,10097,10098,10099 ,0,0,0}, + {22483,22413,22484 ,10100,10018,10101 ,0,0,0}, {22414,22485,22486 ,10019,10102,10103 ,0,0,0}, + {22470,22395,22487 ,10085,10104,10105 ,0,0,0}, {22473,22416,22415 ,10088,10021,10020 ,0,0,0}, + {22473,22472,22488 ,10088,10087,10106 ,0,0,0}, {22415,22472,22473 ,10020,10087,10088 ,0,0,0}, + {22489,22490,22418 ,10107,10108,10023 ,0,0,0}, {22478,22417,22491 ,10093,10022,10109 ,0,0,0}, + {22413,22327,22326 ,10018,10110,10111 ,0,0,0}, {22492,22490,22489 ,10112,10108,10107 ,0,0,0}, + {22412,22492,22489 ,10017,10112,10107 ,0,0,0}, {22480,22411,22481 ,10095,10016,10096 ,0,0,0}, + {22477,22492,22412 ,10092,10112,10017 ,0,0,0}, {22484,22413,22326 ,10101,10018,10111 ,0,0,0}, + {22413,22483,22493 ,10018,10100,10113 ,0,0,0}, {22482,22484,22317 ,10098,10101,10099 ,0,0,0}, + {22484,22482,22483 ,10101,10098,10100 ,0,0,0}, {22331,22467,22319 ,10114,10081,10097 ,0,0,0}, + {22336,22467,22334 ,10082,10081,10115 ,0,0,0}, {22467,22482,22319 ,10081,10098,10097 ,0,0,0}, + {22468,22494,22467 ,10083,10116,10081 ,0,0,0}, {22337,22468,22336 ,10117,10083,10082 ,0,0,0}, + {22468,22339,22425 ,10083,10031,10030 ,0,0,0}, {22388,22495,22465 ,10118,10119,10078 ,0,0,0}, + {22496,22431,22428 ,10120,10039,10034 ,0,0,0}, {22436,22497,22498 ,10044,10121,10122 ,0,0,0}, + {22347,22497,22349 ,10123,10121,10124 ,0,0,0}, {22496,22499,22500 ,10120,10125,10126 ,0,0,0}, + {22430,22426,22428 ,10038,10032,10034 ,0,0,0}, {22385,22388,22465 ,10077,10118,10078 ,0,0,0}, + {22427,22501,22461 ,10033,10127,10073 ,0,0,0}, {22428,22461,22502 ,10034,10073,10128 ,0,0,0}, + {22461,22422,22421 ,10073,10027,10026 ,0,0,0}, {22470,22421,22420 ,10085,10026,10025 ,0,0,0}, + {22461,22421,22503 ,10073,10026,10129 ,0,0,0}, {22504,22487,22462 ,10130,10105,10074 ,0,0,0}, + {22470,22505,22421 ,10085,10131,10026 ,0,0,0}, {22415,22486,22425 ,10020,10103,10030 ,0,0,0}, + {22485,22505,22504 ,10102,10131,10130 ,0,0,0}, {22464,22468,22425 ,10076,10083,10030 ,0,0,0}, + {22425,22424,22415 ,10030,10029,10020 ,0,0,0}, {22464,22506,22468 ,10076,10132,10083 ,0,0,0}, + {22507,22464,22463 ,10133,10076,10075 ,0,0,0}, {22465,22508,22463 ,10078,10134,10075 ,0,0,0}, + {22465,22495,22509 ,10078,10119,10135 ,0,0,0}, {22388,22392,22495 ,10118,10136,10119 ,0,0,0}, + {22392,22400,22495 ,10136,10137,10119 ,0,0,0}, {22495,22429,22510 ,10119,10036,10138 ,0,0,0}, + {22404,22434,22429 ,10035,10042,10036 ,0,0,0}, {22406,22434,22404 ,10139,10042,10035 ,0,0,0}, + {22434,22406,22407 ,10042,10139,10070 ,0,0,0}, {22495,22401,22429 ,10119,10037,10036 ,0,0,0}, + {22409,22432,22434 ,10071,10040,10042 ,0,0,0}, {22511,22497,22512 ,10140,10121,10141 ,0,0,0}, + {22459,22458,22513 ,10069,10068,10142 ,0,0,0}, {22514,22445,22454 ,10143,10055,10064 ,0,0,0}, + {22454,22445,22515 ,10064,10055,10144 ,0,0,0}, {22515,22455,22454 ,10144,10065,10064 ,0,0,0}, + {22454,22459,22514 ,10064,10069,10143 ,0,0,0}, {22516,22441,22433 ,10145,10049,10041 ,0,0,0}, + {22460,22459,22513 ,10072,10069,10142 ,0,0,0}, {22460,22513,22517 ,10072,10142,10146 ,0,0,0}, + {22437,22460,22518 ,10045,10072,10147 ,0,0,0}, {22435,22349,22436 ,10043,10124,10044 ,0,0,0}, + {22519,22496,22498 ,10148,10120,10122 ,0,0,0}, {22497,22436,22349 ,10121,10044,10124 ,0,0,0}, + {22432,22409,22520 ,10040,10071,10149 ,0,0,0}, {22431,22432,22521 ,10039,10040,10150 ,0,0,0}, + {22511,22433,22519 ,10140,10041,10148 ,0,0,0}, {22511,22522,22516 ,10140,10151,10145 ,0,0,0}, + {22523,22352,22353 ,10152,10153,10051 ,0,0,0}, {22523,22348,22352 ,10152,10154,10153 ,0,0,0}, + {22524,22523,22444 ,10155,10152,10054 ,0,0,0}, {22522,22512,22524 ,10151,10141,10155 ,0,0,0}, + {22353,22442,22523 ,10051,10050,10152 ,0,0,0}, {22361,22447,22446 ,10156,10057,10056 ,0,0,0}, + {22489,22525,22412 ,10107,10157,10017 ,0,0,0}, {22419,22418,22490 ,10024,10023,10108 ,0,0,0}, + {22478,22526,22418 ,10093,10158,10023 ,0,0,0}, {22329,22327,22525 ,10159,10110,10157 ,0,0,0}, + {22526,22525,22489 ,10158,10157,10107 ,0,0,0}, {22525,22327,22413 ,10157,10110,10018 ,0,0,0}, + {22412,22525,22413 ,10017,10157,10018 ,0,0,0}, {22493,22481,22411 ,10113,10096,10016 ,0,0,0}, + {22417,22478,22418 ,10022,10093,10023 ,0,0,0}, {22491,22476,22416 ,10109,10091,10021 ,0,0,0}, + {22525,22527,22528 ,10157,10160,10161 ,0,0,0}, {22418,22526,22489 ,10023,10158,10107 ,0,0,0}, + {22475,22526,22473 ,10090,10158,10088 ,0,0,0}, {22329,22525,22528 ,10159,10157,10161 ,0,0,0}, + {22326,22323,22484 ,10111,10162,10101 ,0,0,0}, {22493,22411,22413 ,10113,10016,10018 ,0,0,0}, + {22491,22416,22478 ,10109,10021,10093 ,0,0,0}, {22476,22529,22414 ,10091,10163,10019 ,0,0,0}, + {22474,22473,22488 ,10089,10088,10106 ,0,0,0}, {22478,22473,22526 ,10093,10088,10158 ,0,0,0}, + {22527,22526,22475 ,10160,10158,10090 ,0,0,0}, {22526,22527,22525 ,10158,10160,10157 ,0,0,0}, + {22323,22320,22484 ,10162,10164,10101 ,0,0,0}, {22484,22320,22317 ,10101,10164,10099 ,0,0,0}, + {22530,22485,22529 ,10165,10102,10163 ,0,0,0}, {22530,22531,22505 ,10165,10166,10131 ,0,0,0}, + {22471,22415,22532 ,10086,10020,10167 ,0,0,0}, {22424,22532,22415 ,10029,10167,10020 ,0,0,0}, + {22482,22467,22494 ,10098,10081,10116 ,0,0,0}, {22331,22334,22467 ,10114,10115,10081 ,0,0,0}, + {22485,22414,22529 ,10102,10019,10163 ,0,0,0}, {22533,22395,22470 ,10168,10104,10085 ,0,0,0}, + {22425,22486,22462 ,10030,10103,10074 ,0,0,0}, {22414,22486,22415 ,10019,10103,10020 ,0,0,0}, + {22462,22486,22504 ,10074,10103,10130 ,0,0,0}, {22339,22468,22337 ,10031,10083,10117 ,0,0,0}, + {22425,22462,22464 ,10030,10074,10076 ,0,0,0}, {22468,22506,22494 ,10083,10132,10116 ,0,0,0}, + {22530,22505,22485 ,10165,10131,10102 ,0,0,0}, {22534,22505,22531 ,10169,10131,10166 ,0,0,0}, + {22395,22397,22487 ,10104,10170,10105 ,0,0,0}, {22485,22504,22486 ,10102,10130,10103 ,0,0,0}, + {22470,22487,22504 ,10085,10105,10130 ,0,0,0}, {22383,22465,22390 ,10079,10078,10171 ,0,0,0}, + {22463,22462,22487 ,10075,10074,10105 ,0,0,0}, {22506,22464,22507 ,10132,10076,10133 ,0,0,0}, + {22505,22534,22421 ,10131,10169,10026 ,0,0,0}, {22503,22421,22534 ,10129,10026,10169 ,0,0,0}, + {22533,22470,22469 ,10168,10085,10084 ,0,0,0}, {22505,22470,22504 ,10131,10085,10130 ,0,0,0}, + {22397,22393,22487 ,10170,10172,10105 ,0,0,0}, {22487,22393,22390 ,10105,10172,10171 ,0,0,0}, + {22390,22463,22487 ,10171,10075,10105 ,0,0,0}, {22507,22463,22508 ,10133,10075,10134 ,0,0,0}, + {22461,22503,22502 ,10073,10129,10128 ,0,0,0}, {22501,22466,22461 ,10127,10080,10073 ,0,0,0}, + {22508,22465,22509 ,10134,10078,10135 ,0,0,0}, {22390,22465,22463 ,10171,10078,10075 ,0,0,0}, + {22502,22499,22428 ,10128,10125,10034 ,0,0,0}, {22428,22499,22496 ,10034,10125,10120 ,0,0,0}, + {22401,22495,22400 ,10037,10119,10137 ,0,0,0}, {22495,22510,22509 ,10119,10138,10135 ,0,0,0}, + {22496,22432,22431 ,10120,10040,10039 ,0,0,0}, {22500,22535,22498 ,10126,10173,10122 ,0,0,0}, + {22345,22497,22347 ,10174,10121,10123 ,0,0,0}, {22521,22432,22520 ,10150,10040,10149 ,0,0,0}, + {22519,22432,22496 ,10148,10040,10120 ,0,0,0}, {22536,22429,22441 ,10175,10036,10049 ,0,0,0}, + {22434,22433,22441 ,10042,10041,10049 ,0,0,0}, {22510,22429,22536 ,10138,10036,10175 ,0,0,0}, + {22500,22498,22496 ,10126,10122,10120 ,0,0,0}, {22535,22537,22436 ,10173,10176,10044 ,0,0,0}, + {22341,22512,22342 ,10177,10141,10178 ,0,0,0}, {22432,22519,22433 ,10040,10148,10041 ,0,0,0}, + {22519,22498,22497 ,10148,10122,10121 ,0,0,0}, {22441,22538,22539 ,10049,10179,10180 ,0,0,0}, + {22433,22511,22516 ,10041,10140,10145 ,0,0,0}, {22536,22441,22539 ,10175,10049,10180 ,0,0,0}, + {22535,22436,22498 ,10173,10044,10122 ,0,0,0}, {22537,22460,22436 ,10176,10072,10044 ,0,0,0}, + {22512,22345,22342 ,10141,10174,10178 ,0,0,0}, {22519,22497,22511 ,10148,10121,10140 ,0,0,0}, + {22497,22345,22512 ,10121,10174,10141 ,0,0,0}, {22516,22540,22538 ,10145,10181,10179 ,0,0,0}, + {22511,22512,22522 ,10140,10141,10151 ,0,0,0}, {22538,22441,22516 ,10179,10049,10145 ,0,0,0}, + {22459,22460,22537 ,10069,10072,10176 ,0,0,0}, {22517,22518,22460 ,10146,10147,10072 ,0,0,0}, + {22523,22341,22348 ,10152,10177,10154 ,0,0,0}, {22522,22541,22540 ,10151,10182,10181 ,0,0,0}, + {22512,22523,22524 ,10141,10152,10155 ,0,0,0}, {22540,22516,22522 ,10181,10145,10151 ,0,0,0}, + {22454,22456,22458 ,10064,10066,10068 ,0,0,0}, {22514,22542,22445 ,10143,10183,10055 ,0,0,0}, + {22356,22359,22446 ,10052,10184,10056 ,0,0,0}, {22356,22446,22442 ,10052,10056,10050 ,0,0,0}, + {22524,22443,22541 ,10155,10053,10182 ,0,0,0}, {22523,22512,22341 ,10152,10141,10177 ,0,0,0}, + {22523,22442,22444 ,10152,10050,10054 ,0,0,0}, {22541,22522,22524 ,10182,10151,10155 ,0,0,0}, + {22445,22447,22515 ,10055,10057,10144 ,0,0,0}, {22542,22450,22448 ,10183,10060,10058 ,0,0,0}, + {22543,22439,22438 ,10185,10047,10046 ,0,0,0}, {22361,22446,22359 ,10156,10056,10184 ,0,0,0}, + {22446,22449,22457 ,10056,10059,10067 ,0,0,0}, {22438,22444,22442 ,10046,10054,10050 ,0,0,0}, + {22457,22438,22442 ,10067,10046,10050 ,0,0,0}, {22443,22524,22444 ,10053,10155,10054 ,0,0,0}, + {22542,22448,22445 ,10183,10058,10055 ,0,0,0}, {22445,22449,22446 ,10055,10059,10056 ,0,0,0}, + {22452,22544,22449 ,10062,10186,10059 ,0,0,0}, {22448,22452,22449 ,10058,10062,10059 ,0,0,0}, + {22544,22543,22457 ,10186,10185,10067 ,0,0,0}, {22449,22544,22457 ,10059,10186,10067 ,0,0,0}, + {22543,22438,22457 ,10185,10046,10067 ,0,0,0}, {22440,22444,22438 ,10048,10054,10046 ,0,0,0}, + {22545,22546,22547 ,10187,10188,10189 ,0,0,0}, {22548,22549,22546 ,10190,10191,10188 ,0,0,0}, + {22550,22551,22552 ,10192,10193,10194 ,0,0,0}, {22553,22554,22555 ,10195,10196,10197 ,0,0,0}, + {22556,22557,22558 ,10198,10199,10200 ,0,0,0}, {22559,22560,22561 ,10201,10202,10203 ,0,0,0}, + {22562,22563,22564 ,10204,10205,10206 ,0,0,0}, {22565,22566,22567 ,10207,10208,10209 ,0,0,0}, + {22568,22569,22570 ,10210,10211,10212 ,0,0,0}, {22571,22572,22573 ,10213,10214,10215 ,0,0,0}, + {22574,22575,22568 ,10216,10217,10210 ,0,0,0}, {22568,22570,22574 ,10210,10212,10216 ,0,0,0}, + {22575,22576,22577 ,10217,10218,10219 ,0,0,0}, {22576,22575,22574 ,10218,10217,10216 ,0,0,0}, + {22578,22577,22579 ,10220,10219,10221 ,0,0,0}, {22576,22579,22577 ,10218,10221,10219 ,0,0,0}, + {22580,22581,22578 ,10222,10223,10220 ,0,0,0}, {22578,22579,22580 ,10220,10221,10222 ,0,0,0}, + {22582,22581,22580 ,10224,10223,10222 ,0,0,0}, {22569,22573,22570 ,10211,10215,10212 ,0,0,0}, + {22571,22563,22572 ,10213,10205,10214 ,0,0,0}, {22569,22571,22573 ,10211,10213,10215 ,0,0,0}, + {22562,22564,22565 ,10204,10206,10207 ,0,0,0}, {22572,22563,22562 ,10214,10205,10204 ,0,0,0}, + {22567,22566,22558 ,10209,10208,10200 ,0,0,0}, {22565,22564,22566 ,10207,10206,10208 ,0,0,0}, + {22560,22557,22556 ,10202,10199,10198 ,0,0,0}, {22557,22567,22558 ,10199,10209,10200 ,0,0,0}, + {22583,22559,22561 ,10225,10201,10203 ,0,0,0}, {22561,22560,22556 ,10203,10202,10198 ,0,0,0}, + {22550,22583,22551 ,10192,10225,10193 ,0,0,0}, {22583,22550,22559 ,10225,10192,10201 ,0,0,0}, + {22552,22553,22555 ,10194,10195,10197 ,0,0,0}, {22551,22553,22552 ,10193,10195,10194 ,0,0,0}, + {22548,22554,22549 ,10190,10196,10191 ,0,0,0}, {22555,22554,22548 ,10197,10196,10190 ,0,0,0}, + {22547,22584,22545 ,10189,10226,10187 ,0,0,0}, {22546,22549,22547 ,10188,10191,10189 ,0,0,0}, + {22585,22586,22546 ,10227,10228,10229 ,0,0,0}, {22587,22548,22586 ,10230,10231,10228 ,0,0,0}, + {22559,22550,22588 ,10232,10233,10234 ,0,0,0}, {22552,22555,22589 ,10235,10236,10237 ,0,0,0}, + {22557,22590,22567 ,10238,10239,10240 ,0,0,0}, {22591,22592,22560 ,10241,10242,10243 ,0,0,0}, + {22593,22572,22562 ,10244,10245,10246 ,0,0,0}, {22594,22565,22595 ,10247,10248,10249 ,0,0,0}, + {22574,22570,22596 ,10250,10251,10252 ,0,0,0}, {22573,22597,22598 ,10253,10254,10255 ,0,0,0}, + {22599,22576,22574 ,10256,10257,10250 ,0,0,0}, {22574,22596,22599 ,10250,10252,10256 ,0,0,0}, + {22576,22600,22579 ,10257,10258,10259 ,0,0,0}, {22600,22576,22599 ,10258,10257,10256 ,0,0,0}, + {22580,22579,22601 ,10260,10259,10261 ,0,0,0}, {22600,22601,22579 ,10258,10261,10259 ,0,0,0}, + {22602,22582,22580 ,10262,10224,10260 ,0,0,0}, {22580,22601,22602 ,10260,10261,10262 ,0,0,0}, + {22603,22582,22602 ,10263,10224,10262 ,0,0,0}, {22570,22598,22596 ,10251,10255,10252 ,0,0,0}, + {22573,22572,22597 ,10253,10245,10254 ,0,0,0}, {22570,22573,22598 ,10251,10253,10255 ,0,0,0}, + {22593,22562,22594 ,10244,10246,10247 ,0,0,0}, {22597,22572,22593 ,10254,10245,10244 ,0,0,0}, + {22595,22565,22567 ,10249,10248,10240 ,0,0,0}, {22594,22562,22565 ,10247,10246,10248 ,0,0,0}, + {22592,22590,22557 ,10242,10239,10238 ,0,0,0}, {22590,22595,22567 ,10239,10249,10240 ,0,0,0}, + {22559,22591,22560 ,10232,10241,10243 ,0,0,0}, {22560,22592,22557 ,10243,10242,10238 ,0,0,0}, + {22550,22604,22588 ,10233,10264,10234 ,0,0,0}, {22559,22588,22591 ,10232,10234,10241 ,0,0,0}, + {22589,22604,22552 ,10237,10264,10235 ,0,0,0}, {22550,22552,22604 ,10233,10235,10264 ,0,0,0}, + {22587,22555,22548 ,10230,10236,10231 ,0,0,0}, {22589,22555,22587 ,10237,10236,10230 ,0,0,0}, + {22546,22545,22585 ,10229,10187,10227 ,0,0,0}, {22586,22548,22546 ,10228,10231,10229 ,0,0,0}, + {22605,22606,22586 ,10265,10266,10267 ,0,0,0}, {22589,22587,22607 ,10237,10230,10268 ,0,0,0}, + {22591,22588,22608 ,10269,10270,10271 ,0,0,0}, {22604,22609,22610 ,10264,10272,10273 ,0,0,0}, + {22590,22611,22595 ,10274,10275,10276 ,0,0,0}, {22612,22613,22592 ,10277,10278,10279 ,0,0,0}, + {22614,22597,22615 ,10280,10281,10282 ,0,0,0}, {22593,22594,22616 ,10283,10284,10285 ,0,0,0}, + {22599,22596,22617 ,10286,10287,10288 ,0,0,0}, {22598,22618,22596 ,10289,10290,10287 ,0,0,0}, + {22619,22600,22599 ,10291,10292,10286 ,0,0,0}, {22599,22617,22619 ,10286,10288,10291 ,0,0,0}, + {22600,22620,22601 ,10292,10293,10261 ,0,0,0}, {22620,22600,22619 ,10293,10292,10291 ,0,0,0}, + {22602,22601,22621 ,10294,10261,10295 ,0,0,0}, {22620,22621,22601 ,10293,10295,10261 ,0,0,0}, + {22621,22622,22603 ,10295,10296,10263 ,0,0,0}, {22603,22602,22621 ,10263,10294,10295 ,0,0,0}, + {22617,22596,22618 ,10288,10287,10290 ,0,0,0}, {22598,22597,22614 ,10289,10281,10280 ,0,0,0}, + {22598,22614,22618 ,10289,10280,10290 ,0,0,0}, {22615,22593,22616 ,10282,10283,10285 ,0,0,0}, + {22597,22593,22615 ,10281,10283,10282 ,0,0,0}, {22623,22594,22595 ,10297,10284,10276 ,0,0,0}, + {22616,22594,22623 ,10285,10284,10297 ,0,0,0}, {22613,22611,22590 ,10278,10275,10274 ,0,0,0}, + {22611,22623,22595 ,10275,10297,10276 ,0,0,0}, {22591,22612,22592 ,10269,10277,10279 ,0,0,0}, + {22592,22613,22590 ,10279,10278,10274 ,0,0,0}, {22588,22610,22608 ,10270,10273,10271 ,0,0,0}, + {22591,22608,22612 ,10269,10271,10277 ,0,0,0}, {22604,22589,22609 ,10264,10237,10272 ,0,0,0}, + {22588,22604,22610 ,10270,10264,10273 ,0,0,0}, {22607,22587,22606 ,10268,10230,10266 ,0,0,0}, + {22609,22589,22607 ,10272,10237,10268 ,0,0,0}, {22605,22586,22585 ,10265,10267,10227 ,0,0,0}, + {22606,22587,22586 ,10266,10230,10267 ,0,0,0}, {22624,22625,22606 ,10298,10299,10300 ,0,0,0}, + {22609,22607,22626 ,10301,10302,10303 ,0,0,0}, {22612,22608,22627 ,10304,10305,10306 ,0,0,0}, + {22610,22609,22628 ,10307,10301,10308 ,0,0,0}, {22611,22629,22623 ,10309,10310,10311 ,0,0,0}, + {22630,22631,22613 ,10312,10313,10314 ,0,0,0}, {22632,22614,22615 ,10315,10316,10317 ,0,0,0}, + {22633,22616,22634 ,10318,10319,10320 ,0,0,0}, {22635,22617,22636 ,10321,10322,10323 ,0,0,0}, + {22618,22637,22636 ,10324,10325,10323 ,0,0,0}, {22635,22638,22619 ,10321,10326,10327 ,0,0,0}, + {22619,22617,22635 ,10327,10322,10321 ,0,0,0}, {22620,22638,22639 ,10328,10326,10329 ,0,0,0}, + {22638,22620,22619 ,10326,10328,10327 ,0,0,0}, {22640,22621,22639 ,10330,10331,10329 ,0,0,0}, + {22620,22639,22621 ,10328,10329,10331 ,0,0,0}, {22640,22641,22622 ,10330,10332,10296 ,0,0,0}, + {22622,22621,22640 ,10296,10331,10330 ,0,0,0}, {22636,22617,22618 ,10323,10322,10324 ,0,0,0}, + {22637,22614,22632 ,10325,10316,10315 ,0,0,0}, {22618,22614,22637 ,10324,10316,10325 ,0,0,0}, + {22633,22615,22616 ,10318,10317,10319 ,0,0,0}, {22632,22615,22633 ,10315,10317,10318 ,0,0,0}, + {22629,22634,22623 ,10310,10320,10311 ,0,0,0}, {22634,22616,22623 ,10320,10319,10311 ,0,0,0}, + {22613,22631,22611 ,10314,10313,10309 ,0,0,0}, {22631,22629,22611 ,10313,10310,10309 ,0,0,0}, + {22612,22627,22630 ,10304,10306,10312 ,0,0,0}, {22612,22630,22613 ,10304,10312,10314 ,0,0,0}, + {22608,22610,22642 ,10305,10307,10333 ,0,0,0}, {22608,22642,22627 ,10305,10333,10306 ,0,0,0}, + {22628,22609,22626 ,10308,10301,10303 ,0,0,0}, {22642,22610,22628 ,10333,10307,10308 ,0,0,0}, + {22625,22607,22606 ,10299,10302,10300 ,0,0,0}, {22626,22607,22625 ,10303,10302,10299 ,0,0,0}, + {22624,22606,22605 ,10298,10300,10265 ,0,0,0}, {22639,22643,22644 ,10334,10335,10336 ,0,0,0}, + {22641,22640,22645 ,10332,10337,10338 ,0,0,0}, {22646,22636,22647 ,10339,10340,10341 ,0,0,0}, + {22635,22648,22638 ,10342,10343,10344 ,0,0,0}, {22634,22649,22633 ,10345,10346,10347 ,0,0,0}, + {22632,22650,22637 ,10348,10349,10350 ,0,0,0}, {22651,22631,22630 ,10351,10352,10353 ,0,0,0}, + {22652,22629,22653 ,10354,10355,10356 ,0,0,0}, {22654,22642,22655 ,10357,10358,10359 ,0,0,0}, + {22627,22654,22656 ,10360,10357,10361 ,0,0,0}, {22657,22655,22628 ,10362,10359,10363 ,0,0,0}, + {22642,22628,22655 ,10358,10363,10359 ,0,0,0}, {22626,22658,22657 ,10364,10365,10362 ,0,0,0}, + {22657,22628,22626 ,10362,10363,10364 ,0,0,0}, {22658,22625,22659 ,10365,10366,10367 ,0,0,0}, + {22625,22658,22626 ,10366,10365,10364 ,0,0,0}, {22656,22630,22627 ,10361,10353,10360 ,0,0,0}, + {22659,22625,22624 ,10367,10366,10368 ,0,0,0}, {22654,22627,22642 ,10357,10360,10358 ,0,0,0}, + {22651,22653,22631 ,10351,10356,10352 ,0,0,0}, {22656,22651,22630 ,10361,10351,10353 ,0,0,0}, + {22629,22652,22634 ,10355,10354,10345 ,0,0,0}, {22631,22653,22629 ,10352,10356,10355 ,0,0,0}, + {22633,22649,22660 ,10347,10346,10369 ,0,0,0}, {22634,22652,22649 ,10345,10354,10346 ,0,0,0}, + {22660,22650,22632 ,10369,10349,10348 ,0,0,0}, {22632,22633,22660 ,10348,10347,10369 ,0,0,0}, + {22647,22636,22637 ,10341,10340,10350 ,0,0,0}, {22647,22637,22650 ,10341,10350,10349 ,0,0,0}, + {22646,22648,22635 ,10339,10343,10342 ,0,0,0}, {22646,22635,22636 ,10339,10342,10340 ,0,0,0}, + {22638,22643,22639 ,10344,10335,10334 ,0,0,0}, {22648,22643,22638 ,10343,10335,10344 ,0,0,0}, + {22640,22644,22645 ,10337,10336,10338 ,0,0,0}, {22639,22644,22640 ,10334,10336,10337 ,0,0,0}, + {22641,22645,22661 ,10332,10338,10370 ,0,0,0}, {22662,22663,22664 ,10371,10372,10373 ,0,0,0}, + {22665,22666,22667 ,10374,10375,10376 ,0,0,0}, {22666,22668,22669 ,10375,10377,10378 ,0,0,0}, + {22669,22667,22666 ,10378,10376,10375 ,0,0,0}, {22666,22664,22670 ,10375,10373,10379 ,0,0,0}, + {22668,22671,22669 ,10377,10380,10378 ,0,0,0}, {22672,22673,22674 ,10381,10382,10383 ,0,0,0}, + {22624,22663,22659 ,10368,10372,10384 ,0,0,0}, {22675,22676,22677 ,10385,10386,10387 ,0,0,0}, + {22655,22657,22678 ,10388,10389,10390 ,0,0,0}, {22679,22680,22681 ,10391,10392,10393 ,0,0,0}, + {22656,22682,22651 ,10394,10395,10396 ,0,0,0}, {22683,22684,22650 ,10397,10398,10399 ,0,0,0}, + {22685,22686,22681 ,10400,10401,10393 ,0,0,0}, {22687,22688,22689 ,10402,10403,10404 ,0,0,0}, + {22690,22684,22691 ,10405,10398,10406 ,0,0,0}, {22644,22688,22645 ,10407,10403,10408 ,0,0,0}, + {22645,22692,22661 ,10408,10409,10410 ,0,0,0}, {22693,22694,22689 ,10411,10412,10404 ,0,0,0}, + {22645,22688,22692 ,10408,10403,10409 ,0,0,0}, {22695,22687,22696 ,10413,10402,10414 ,0,0,0}, + {22693,22689,22643 ,10411,10404,10415 ,0,0,0}, {22693,22697,22698 ,10411,10416,10417 ,0,0,0}, + {22648,22697,22693 ,10418,10416,10411 ,0,0,0}, {22647,22684,22690 ,10419,10398,10405 ,0,0,0}, + {22697,22690,22699 ,10416,10405,10420 ,0,0,0}, {22697,22646,22690 ,10416,10421,10405 ,0,0,0}, + {22700,22683,22686 ,10422,10397,10401 ,0,0,0}, {22701,22684,22683 ,10423,10398,10397 ,0,0,0}, + {22686,22649,22652 ,10401,10424,10425 ,0,0,0}, {22686,22683,22660 ,10401,10397,10426 ,0,0,0}, + {22651,22679,22653 ,10396,10391,10427 ,0,0,0}, {22653,22681,22652 ,10427,10393,10425 ,0,0,0}, + {22675,22702,22682 ,10385,10428,10395 ,0,0,0}, {22682,22703,22679 ,10395,10429,10391 ,0,0,0}, + {22654,22655,22676 ,10430,10388,10386 ,0,0,0}, {22656,22654,22675 ,10394,10430,10385 ,0,0,0}, + {22673,22704,22678 ,10382,10431,10390 ,0,0,0}, {22677,22676,22704 ,10387,10386,10431 ,0,0,0}, + {22705,22658,22659 ,10432,10433,10384 ,0,0,0}, {22674,22657,22658 ,10383,10389,10433 ,0,0,0}, + {22706,22670,22664 ,10434,10379,10373 ,0,0,0}, {22705,22662,22672 ,10432,10371,10381 ,0,0,0}, + {22664,22663,22706 ,10373,10372,10434 ,0,0,0}, {22668,22666,22670 ,10377,10375,10379 ,0,0,0}, + {22707,22665,22667 ,10435,10374,10376 ,0,0,0}, {22708,22665,22707 ,10436,10374,10435 ,0,0,0}, + {22663,22624,22706 ,10372,10368,10434 ,0,0,0}, {22664,22665,22662 ,10373,10374,10371 ,0,0,0}, + {22659,22663,22705 ,10384,10372,10432 ,0,0,0}, {22666,22665,22664 ,10375,10374,10373 ,0,0,0}, + {22709,22708,22707 ,10437,10436,10435 ,0,0,0}, {22710,22708,22709 ,10438,10436,10437 ,0,0,0}, + {22663,22662,22705 ,10372,10371,10432 ,0,0,0}, {22662,22708,22672 ,10371,10436,10381 ,0,0,0}, + {22658,22705,22674 ,10433,10432,10383 ,0,0,0}, {22665,22708,22662 ,10374,10436,10371 ,0,0,0}, + {22711,22710,22709 ,10439,10438,10437 ,0,0,0}, {22712,22710,22711 ,10440,10438,10439 ,0,0,0}, + {22705,22672,22674 ,10432,10381,10383 ,0,0,0}, {22672,22710,22673 ,10381,10438,10382 ,0,0,0}, + {22657,22674,22678 ,10389,10383,10390 ,0,0,0}, {22708,22710,22672 ,10436,10438,10381 ,0,0,0}, + {22713,22712,22711 ,10441,10440,10439 ,0,0,0}, {22714,22712,22713 ,10442,10440,10441 ,0,0,0}, + {22674,22673,22678 ,10383,10382,10390 ,0,0,0}, {22673,22712,22704 ,10382,10440,10431 ,0,0,0}, + {22655,22678,22676 ,10388,10390,10386 ,0,0,0}, {22710,22712,22673 ,10438,10440,10382 ,0,0,0}, + {22715,22714,22713 ,10443,10442,10441 ,0,0,0}, {22716,22714,22715 ,10444,10442,10443 ,0,0,0}, + {22678,22704,22676 ,10390,10431,10386 ,0,0,0}, {22704,22714,22677 ,10431,10442,10387 ,0,0,0}, + {22654,22676,22675 ,10430,10386,10385 ,0,0,0}, {22712,22714,22704 ,10440,10442,10431 ,0,0,0}, + {22717,22716,22715 ,10445,10444,10443 ,0,0,0}, {22718,22719,22696 ,10446,10447,10414 ,0,0,0}, + {22720,22716,22717 ,10448,10444,10445 ,0,0,0}, {22677,22716,22702 ,10387,10444,10428 ,0,0,0}, + {22656,22675,22682 ,10394,10385,10395 ,0,0,0}, {22714,22716,22677 ,10442,10444,10387 ,0,0,0}, + {22721,22720,22717 ,10449,10448,10445 ,0,0,0}, {22722,22723,22720 ,10450,10451,10448 ,0,0,0}, + {22677,22702,22675 ,10387,10428,10385 ,0,0,0}, {22702,22720,22703 ,10428,10448,10429 ,0,0,0}, + {22651,22682,22679 ,10396,10395,10391 ,0,0,0}, {22716,22720,22702 ,10444,10448,10428 ,0,0,0}, + {22721,22722,22720 ,10449,10450,10448 ,0,0,0}, {22724,22725,22723 ,10452,10453,10451 ,0,0,0}, + {22702,22703,22682 ,10428,10429,10395 ,0,0,0}, {22703,22723,22680 ,10429,10451,10392 ,0,0,0}, + {22653,22679,22681 ,10427,10391,10393 ,0,0,0}, {22720,22723,22703 ,10448,10451,10429 ,0,0,0}, + {22722,22724,22723 ,10450,10452,10451 ,0,0,0}, {22726,22727,22725 ,10454,10455,10453 ,0,0,0}, + {22703,22680,22679 ,10429,10392,10391 ,0,0,0}, {22725,22685,22680 ,10453,10400,10392 ,0,0,0}, + {22652,22681,22686 ,10425,10393,10401 ,0,0,0}, {22723,22725,22680 ,10451,10453,10392 ,0,0,0}, + {22724,22726,22725 ,10452,10454,10453 ,0,0,0}, {22727,22728,22729 ,10455,10456,10457 ,0,0,0}, + {22680,22685,22681 ,10392,10400,10393 ,0,0,0}, {22727,22700,22685 ,10455,10422,10400 ,0,0,0}, + {22660,22649,22686 ,10426,10424,10401 ,0,0,0}, {22725,22727,22685 ,10453,10455,10400 ,0,0,0}, + {22726,22728,22727 ,10454,10456,10455 ,0,0,0}, {22729,22730,22731 ,10457,10458,10459 ,0,0,0}, + {22685,22700,22686 ,10400,10422,10401 ,0,0,0}, {22729,22701,22700 ,10457,10423,10422 ,0,0,0}, + {22650,22660,22683 ,10399,10426,10397 ,0,0,0}, {22727,22729,22700 ,10455,10457,10422 ,0,0,0}, + {22728,22730,22729 ,10456,10458,10457 ,0,0,0}, {22731,22732,22733 ,10459,10460,10461 ,0,0,0}, + {22700,22701,22683 ,10422,10423,10397 ,0,0,0}, {22731,22691,22701 ,10459,10406,10423 ,0,0,0}, + {22647,22650,22684 ,10419,10399,10398 ,0,0,0}, {22729,22731,22701 ,10457,10459,10423 ,0,0,0}, + {22730,22732,22731 ,10458,10460,10459 ,0,0,0}, {22733,22734,22735 ,10461,10462,10463 ,0,0,0}, + {22701,22691,22684 ,10423,10406,10398 ,0,0,0}, {22733,22699,22691 ,10461,10420,10406 ,0,0,0}, + {22646,22647,22690 ,10421,10419,10405 ,0,0,0}, {22731,22733,22691 ,10459,10461,10406 ,0,0,0}, + {22732,22734,22733 ,10460,10462,10461 ,0,0,0}, {22735,22736,22737 ,10463,10464,10465 ,0,0,0}, + {22691,22699,22690 ,10406,10420,10405 ,0,0,0}, {22735,22698,22699 ,10463,10417,10420 ,0,0,0}, + {22648,22646,22697 ,10418,10421,10416 ,0,0,0}, {22733,22735,22699 ,10461,10463,10420 ,0,0,0}, + {22734,22736,22735 ,10462,10464,10463 ,0,0,0}, {22696,22737,22718 ,10414,10465,10446 ,0,0,0}, + {22699,22698,22697 ,10420,10417,10416 ,0,0,0}, {22698,22737,22694 ,10417,10465,10412 ,0,0,0}, + {22643,22648,22693 ,10415,10418,10411 ,0,0,0}, {22735,22737,22698 ,10463,10465,10417 ,0,0,0}, + {22736,22718,22737 ,10464,10446,10465 ,0,0,0}, {22644,22689,22688 ,10407,10404,10403 ,0,0,0}, + {22698,22694,22693 ,10417,10412,10411 ,0,0,0}, {22696,22687,22694 ,10414,10402,10412 ,0,0,0}, + {22644,22643,22689 ,10407,10415,10404 ,0,0,0}, {22696,22694,22737 ,10414,10412,10465 ,0,0,0}, + {22719,22695,22696 ,10447,10413,10414 ,0,0,0}, {22738,22687,22695 ,10466,10402,10413 ,0,0,0}, + {22694,22687,22689 ,10412,10402,10404 ,0,0,0}, {22687,22738,22688 ,10402,10466,10403 ,0,0,0}, + {22692,22688,22738 ,10409,10403,10466 ,0,0,0}, {22739,22740,22669 ,10467,10468,10469 ,0,0,0}, + {22707,22667,22741 ,10470,10471,10472 ,0,0,0}, {22713,22711,22742 ,10473,10474,10475 ,0,0,0}, + {22709,22743,22744 ,10476,10477,10478 ,0,0,0}, {22745,22746,22721 ,10479,10480,10481 ,0,0,0}, + {22747,22748,22715 ,10482,10483,10484 ,0,0,0}, {22749,22726,22750 ,10485,10486,10487 ,0,0,0}, + {22724,22722,22751 ,10488,10489,10490 ,0,0,0}, {22732,22730,22752 ,10491,10492,10493 ,0,0,0}, + {22728,22753,22730 ,10494,10495,10492 ,0,0,0}, {22754,22734,22732 ,10496,10497,10491 ,0,0,0}, + {22732,22752,22754 ,10491,10493,10496 ,0,0,0}, {22734,22755,22736 ,10497,10498,10499 ,0,0,0}, + {22755,22734,22754 ,10498,10497,10496 ,0,0,0}, {22718,22736,22756 ,10500,10499,10501 ,0,0,0}, + {22755,22756,22736 ,10498,10501,10499 ,0,0,0}, {22756,22757,22719 ,10501,10502,10447 ,0,0,0}, + {22719,22718,22756 ,10447,10500,10501 ,0,0,0}, {22752,22730,22753 ,10493,10492,10495 ,0,0,0}, + {22728,22726,22749 ,10494,10486,10485 ,0,0,0}, {22728,22749,22753 ,10494,10485,10495 ,0,0,0}, + {22750,22724,22751 ,10487,10488,10490 ,0,0,0}, {22726,22724,22750 ,10486,10488,10487 ,0,0,0}, + {22746,22722,22721 ,10480,10489,10481 ,0,0,0}, {22751,22722,22746 ,10490,10489,10480 ,0,0,0}, + {22748,22745,22717 ,10483,10479,10503 ,0,0,0}, {22745,22721,22717 ,10479,10481,10503 ,0,0,0}, + {22713,22747,22715 ,10473,10482,10484 ,0,0,0}, {22715,22748,22717 ,10484,10483,10503 ,0,0,0}, + {22711,22744,22742 ,10474,10478,10475 ,0,0,0}, {22713,22742,22747 ,10473,10475,10482 ,0,0,0}, + {22709,22707,22743 ,10476,10470,10477 ,0,0,0}, {22711,22709,22744 ,10474,10476,10478 ,0,0,0}, + {22741,22667,22740 ,10472,10471,10468 ,0,0,0}, {22743,22707,22741 ,10477,10470,10472 ,0,0,0}, + {22739,22669,22671 ,10467,10469,10504 ,0,0,0}, {22740,22667,22669 ,10468,10471,10469 ,0,0,0}, + {22758,22759,22740 ,10505,10506,10507 ,0,0,0}, {22741,22740,22760 ,10508,10507,10509 ,0,0,0}, + {22742,22744,22761 ,10510,10511,10512 ,0,0,0}, {22743,22762,22763 ,10513,10514,10515 ,0,0,0}, + {22748,22764,22745 ,10516,10517,10518 ,0,0,0}, {22765,22766,22747 ,10519,10520,10521 ,0,0,0}, + {22767,22750,22751 ,10522,10523,10524 ,0,0,0}, {22768,22746,22769 ,10525,10526,10527 ,0,0,0}, + {22752,22753,22770 ,10528,10529,10530 ,0,0,0}, {22749,22771,22772 ,10531,10532,10533 ,0,0,0}, + {22773,22754,22752 ,10534,10535,10528 ,0,0,0}, {22752,22770,22773 ,10528,10530,10534 ,0,0,0}, + {22754,22774,22755 ,10535,10536,10537 ,0,0,0}, {22774,22754,22773 ,10536,10535,10534 ,0,0,0}, + {22756,22755,22775 ,10538,10537,10539 ,0,0,0}, {22774,22775,22755 ,10536,10539,10537 ,0,0,0}, + {22776,22757,22756 ,10540,10502,10538 ,0,0,0}, {22756,22775,22776 ,10538,10539,10540 ,0,0,0}, + {22777,22757,22776 ,10541,10502,10540 ,0,0,0}, {22753,22772,22770 ,10529,10533,10530 ,0,0,0}, + {22749,22750,22771 ,10531,10523,10532 ,0,0,0}, {22753,22749,22772 ,10529,10531,10533 ,0,0,0}, + {22767,22751,22768 ,10522,10524,10525 ,0,0,0}, {22771,22750,22767 ,10532,10523,10522 ,0,0,0}, + {22769,22746,22745 ,10527,10526,10518 ,0,0,0}, {22768,22751,22746 ,10525,10524,10526 ,0,0,0}, + {22766,22764,22748 ,10520,10517,10516 ,0,0,0}, {22764,22769,22745 ,10517,10527,10518 ,0,0,0}, + {22742,22765,22747 ,10510,10519,10521 ,0,0,0}, {22747,22766,22748 ,10521,10520,10516 ,0,0,0}, + {22744,22763,22761 ,10511,10515,10512 ,0,0,0}, {22742,22761,22765 ,10510,10512,10519 ,0,0,0}, + {22743,22741,22762 ,10513,10508,10514 ,0,0,0}, {22744,22743,22763 ,10511,10513,10515 ,0,0,0}, + {22760,22740,22759 ,10509,10507,10506 ,0,0,0}, {22762,22741,22760 ,10514,10508,10509 ,0,0,0}, + {22758,22740,22739 ,10505,10507,10467 ,0,0,0}, {22778,22779,22759 ,10542,10543,10544 ,0,0,0}, + {22780,22760,22779 ,10545,10509,10543 ,0,0,0}, {22765,22761,22781 ,10546,10547,10548 ,0,0,0}, + {22763,22762,22782 ,10515,10514,10549 ,0,0,0}, {22764,22783,22769 ,10550,10551,10552 ,0,0,0}, + {22784,22785,22766 ,10553,10554,10555 ,0,0,0}, {22786,22771,22767 ,10556,10557,10558 ,0,0,0}, + {22787,22768,22788 ,10559,10560,10561 ,0,0,0}, {22773,22770,22789 ,10534,10530,10562 ,0,0,0}, + {22772,22790,22791 ,10563,10564,10565 ,0,0,0}, {22792,22774,22773 ,10566,10536,10534 ,0,0,0}, + {22773,22789,22792 ,10534,10562,10566 ,0,0,0}, {22774,22793,22775 ,10536,10567,10539 ,0,0,0}, + {22793,22774,22792 ,10567,10536,10566 ,0,0,0}, {22776,22775,22794 ,10568,10539,10569 ,0,0,0}, + {22793,22794,22775 ,10567,10569,10539 ,0,0,0}, {22795,22777,22776 ,10570,10541,10568 ,0,0,0}, + {22776,22794,22795 ,10568,10569,10570 ,0,0,0}, {22796,22777,22795 ,10571,10541,10570 ,0,0,0}, + {22770,22791,22789 ,10530,10565,10562 ,0,0,0}, {22772,22771,22790 ,10563,10557,10564 ,0,0,0}, + {22770,22772,22791 ,10530,10563,10565 ,0,0,0}, {22786,22767,22787 ,10556,10558,10559 ,0,0,0}, + {22790,22771,22786 ,10564,10557,10556 ,0,0,0}, {22788,22768,22769 ,10561,10560,10552 ,0,0,0}, + {22787,22767,22768 ,10559,10558,10560 ,0,0,0}, {22785,22783,22764 ,10554,10551,10550 ,0,0,0}, + {22783,22788,22769 ,10551,10561,10552 ,0,0,0}, {22765,22784,22766 ,10546,10553,10555 ,0,0,0}, + {22766,22785,22764 ,10555,10554,10550 ,0,0,0}, {22761,22797,22781 ,10547,10572,10548 ,0,0,0}, + {22765,22781,22784 ,10546,10548,10553 ,0,0,0}, {22782,22797,22763 ,10549,10572,10515 ,0,0,0}, + {22761,22763,22797 ,10547,10515,10572 ,0,0,0}, {22780,22762,22760 ,10545,10514,10509 ,0,0,0}, + {22782,22762,22780 ,10549,10514,10545 ,0,0,0}, {22759,22758,22778 ,10544,10505,10542 ,0,0,0}, + {22779,22760,22759 ,10543,10509,10544 ,0,0,0}, {22798,22799,22779 ,10573,10574,10575 ,0,0,0}, + {22800,22780,22799 ,10576,10577,10574 ,0,0,0}, {22784,22781,22801 ,10578,10579,10580 ,0,0,0}, + {22797,22782,22802 ,10581,10582,10583 ,0,0,0}, {22783,22803,22788 ,10584,10585,10586 ,0,0,0}, + {22804,22805,22785 ,10587,10588,10589 ,0,0,0}, {22806,22790,22786 ,10590,10591,10592 ,0,0,0}, + {22807,22787,22808 ,10593,10594,10595 ,0,0,0}, {22809,22789,22810 ,10596,10597,10598 ,0,0,0}, + {22791,22790,22811 ,10599,10591,10600 ,0,0,0}, {22812,22793,22792 ,10601,10602,10603 ,0,0,0}, + {22792,22809,22812 ,10603,10596,10601 ,0,0,0}, {22793,22813,22794 ,10602,10604,10605 ,0,0,0}, + {22813,22793,22812 ,10604,10602,10601 ,0,0,0}, {22795,22794,22814 ,10606,10605,10607 ,0,0,0}, + {22813,22814,22794 ,10604,10607,10605 ,0,0,0}, {22815,22796,22795 ,10608,10571,10606 ,0,0,0}, + {22795,22814,22815 ,10606,10607,10608 ,0,0,0}, {22816,22796,22815 ,10609,10571,10608 ,0,0,0}, + {22809,22792,22789 ,10596,10603,10597 ,0,0,0}, {22810,22791,22811 ,10598,10599,10600 ,0,0,0}, + {22789,22791,22810 ,10597,10599,10598 ,0,0,0}, {22786,22807,22806 ,10592,10593,10590 ,0,0,0}, + {22811,22790,22806 ,10600,10591,10590 ,0,0,0}, {22808,22787,22788 ,10595,10594,10586 ,0,0,0}, + {22807,22786,22787 ,10593,10592,10594 ,0,0,0}, {22805,22803,22783 ,10588,10585,10584 ,0,0,0}, + {22803,22808,22788 ,10585,10595,10586 ,0,0,0}, {22784,22804,22785 ,10578,10587,10589 ,0,0,0}, + {22785,22805,22783 ,10589,10588,10584 ,0,0,0}, {22781,22817,22801 ,10579,10610,10580 ,0,0,0}, + {22784,22801,22804 ,10578,10580,10587 ,0,0,0}, {22802,22817,22797 ,10583,10610,10581 ,0,0,0}, + {22781,22797,22817 ,10579,10581,10610 ,0,0,0}, {22800,22782,22780 ,10576,10582,10577 ,0,0,0}, + {22802,22782,22800 ,10583,10582,10576 ,0,0,0}, {22779,22778,22798 ,10575,10542,10573 ,0,0,0}, + {22799,22780,22779 ,10574,10577,10575 ,0,0,0}, {22818,22798,22819 ,10611,10573,10612 ,0,0,0}, + {22820,22802,22821 ,10613,10614,10615 ,0,0,0}, {22822,22800,22799 ,10616,10617,10618 ,0,0,0}, + {22804,22823,22805 ,10619,10620,10621 ,0,0,0}, {22817,22824,22801 ,10622,10623,10624 ,0,0,0}, + {22825,22807,22808 ,10625,10626,10627 ,0,0,0}, {22826,22803,22827 ,10628,10629,10630 ,0,0,0}, + {22828,22811,22829 ,10631,10632,10633 ,0,0,0}, {22806,22830,22829 ,10634,10635,10633 ,0,0,0}, + {22812,22809,22831 ,10636,10637,10638 ,0,0,0}, {22810,22832,22809 ,10639,10640,10637 ,0,0,0}, + {22833,22813,22812 ,10641,10642,10636 ,0,0,0}, {22812,22831,22833 ,10636,10638,10641 ,0,0,0}, + {22813,22834,22814 ,10642,10643,10644 ,0,0,0}, {22834,22813,22833 ,10643,10642,10641 ,0,0,0}, + {22815,22814,22835 ,10645,10644,10646 ,0,0,0}, {22834,22835,22814 ,10643,10646,10644 ,0,0,0}, + {22836,22816,22815 ,10647,10609,10645 ,0,0,0}, {22815,22835,22836 ,10645,10646,10647 ,0,0,0}, + {22828,22832,22810 ,10631,10640,10639 ,0,0,0}, {22809,22832,22831 ,10637,10640,10638 ,0,0,0}, + {22811,22806,22829 ,10632,10634,10633 ,0,0,0}, {22810,22811,22828 ,10639,10632,10631 ,0,0,0}, + {22830,22807,22825 ,10635,10626,10625 ,0,0,0}, {22806,22807,22830 ,10634,10626,10635 ,0,0,0}, + {22826,22808,22803 ,10628,10627,10629 ,0,0,0}, {22825,22808,22826 ,10625,10627,10628 ,0,0,0}, + {22823,22827,22805 ,10620,10630,10621 ,0,0,0}, {22827,22803,22805 ,10630,10629,10621 ,0,0,0}, + {22801,22837,22804 ,10624,10648,10619 ,0,0,0}, {22837,22823,22804 ,10648,10620,10619 ,0,0,0}, + {22817,22820,22824 ,10622,10613,10623 ,0,0,0}, {22801,22824,22837 ,10624,10623,10648 ,0,0,0}, + {22802,22800,22821 ,10614,10617,10615 ,0,0,0}, {22817,22802,22820 ,10622,10614,10613 ,0,0,0}, + {22822,22799,22818 ,10616,10618,10611 ,0,0,0}, {22821,22800,22822 ,10615,10617,10616 ,0,0,0}, + {22798,22818,22799 ,10573,10611,10618 ,0,0,0}, {22825,22826,22838 ,10649,10650,10651 ,0,0,0}, + {22839,22826,22827 ,10652,10650,10653 ,0,0,0}, {22826,22839,22838 ,10650,10652,10651 ,0,0,0}, + {22823,22840,22827 ,10654,10655,10653 ,0,0,0}, {22839,22827,22840 ,10652,10653,10655 ,0,0,0}, + {22823,22837,22841 ,10654,10656,10657 ,0,0,0}, {22841,22840,22823 ,10657,10655,10654 ,0,0,0}, + {22842,22837,22824 ,10658,10656,10659 ,0,0,0}, {22837,22842,22841 ,10656,10658,10657 ,0,0,0}, + {22820,22843,22824 ,10660,10661,10659 ,0,0,0}, {22842,22824,22843 ,10658,10659,10661 ,0,0,0}, + {22820,22821,22844 ,10660,10662,10663 ,0,0,0}, {22844,22843,22820 ,10663,10661,10660 ,0,0,0}, + {22845,22821,22822 ,10664,10662,10665 ,0,0,0}, {22821,22845,22844 ,10662,10664,10663 ,0,0,0}, + {22818,22846,22822 ,10666,10667,10665 ,0,0,0}, {22845,22822,22846 ,10664,10665,10667 ,0,0,0}, + {22819,22847,22846 ,10668,10669,10667 ,0,0,0}, {22846,22818,22819 ,10667,10666,10668 ,0,0,0}, + {22825,22838,22848 ,10649,10651,10670 ,0,0,0}, {22848,22849,22830 ,10670,10671,10672 ,0,0,0}, + {22830,22825,22848 ,10672,10649,10670 ,0,0,0}, {22829,22849,22850 ,10673,10671,10674 ,0,0,0}, + {22849,22829,22830 ,10671,10673,10672 ,0,0,0}, {22851,22828,22850 ,10675,10676,10674 ,0,0,0}, + {22829,22850,22828 ,10673,10674,10676 ,0,0,0}, {22851,22852,22832 ,10675,10677,10678 ,0,0,0}, + {22832,22828,22851 ,10678,10676,10675 ,0,0,0}, {22831,22852,22853 ,10679,10677,10680 ,0,0,0}, + {22852,22831,22832 ,10677,10679,10678 ,0,0,0}, {22854,22833,22853 ,10681,10682,10680 ,0,0,0}, + {22831,22853,22833 ,10679,10680,10682 ,0,0,0}, {22854,22855,22834 ,10681,10683,10684 ,0,0,0}, + {22834,22833,22854 ,10684,10682,10681 ,0,0,0}, {22835,22855,22856 ,10685,10683,10686 ,0,0,0}, + {22855,22835,22834 ,10683,10685,10684 ,0,0,0}, {22835,22856,22836 ,10685,10686,10687 ,0,0,0}, + {22857,22847,22858 ,10688,10689,10690 ,0,0,0}, {22859,22843,22860 ,10691,10692,10693 ,0,0,0}, + {22857,22861,22845 ,10688,10694,10695 ,0,0,0}, {22840,22862,22863 ,10696,10697,10698 ,0,0,0}, + {22842,22864,22841 ,10699,10700,10701 ,0,0,0}, {22865,22866,22848 ,10702,10703,10704 ,0,0,0}, + {22867,22838,22839 ,10705,10706,10707 ,0,0,0}, {22868,22851,22869 ,10708,10709,10710 ,0,0,0}, + {22850,22849,22870 ,10711,10712,10713 ,0,0,0}, {22871,22853,22852 ,10714,10715,10716 ,0,0,0}, + {22852,22868,22871 ,10716,10708,10714 ,0,0,0}, {22853,22872,22854 ,10715,10717,10718 ,0,0,0}, + {22872,22853,22871 ,10717,10715,10714 ,0,0,0}, {22855,22854,22873 ,10719,10718,10720 ,0,0,0}, + {22872,22873,22854 ,10717,10720,10718 ,0,0,0}, {22874,22856,22855 ,10721,10686,10719 ,0,0,0}, + {22855,22873,22874 ,10719,10720,10721 ,0,0,0}, {22851,22850,22869 ,10709,10711,10710 ,0,0,0}, + {22852,22851,22868 ,10716,10709,10708 ,0,0,0}, {22870,22849,22866 ,10713,10712,10703 ,0,0,0}, + {22869,22850,22870 ,10710,10711,10713 ,0,0,0}, {22865,22848,22838 ,10702,10704,10706 ,0,0,0}, + {22866,22849,22848 ,10703,10712,10704 ,0,0,0}, {22863,22867,22839 ,10698,10705,10707 ,0,0,0}, + {22867,22865,22838 ,10705,10702,10706 ,0,0,0}, {22841,22862,22840 ,10701,10697,10696 ,0,0,0}, + {22840,22863,22839 ,10696,10698,10707 ,0,0,0}, {22842,22859,22864 ,10699,10691,10700 ,0,0,0}, + {22841,22864,22862 ,10701,10700,10697 ,0,0,0}, {22843,22844,22860 ,10692,10722,10693 ,0,0,0}, + {22842,22843,22859 ,10699,10692,10691 ,0,0,0}, {22845,22861,22844 ,10695,10694,10722 ,0,0,0}, + {22860,22844,22861 ,10693,10722,10694 ,0,0,0}, {22857,22846,22847 ,10688,10723,10689 ,0,0,0}, + {22857,22845,22846 ,10688,10695,10723 ,0,0,0}, {22875,22858,22876 ,10724,10725,10726 ,0,0,0}, + {22877,22860,22878 ,10727,10728,10729 ,0,0,0}, {22879,22861,22857 ,10730,10731,10732 ,0,0,0}, + {22862,22880,22863 ,10733,10734,10735 ,0,0,0}, {22859,22881,22864 ,10736,10737,10738 ,0,0,0}, + {22882,22883,22865 ,10739,10740,10741 ,0,0,0}, {22882,22867,22884 ,10739,10742,10743 ,0,0,0}, + {22885,22869,22886 ,10744,10745,10746 ,0,0,0}, {22870,22866,22887 ,10747,10748,10749 ,0,0,0}, + {22888,22871,22868 ,10750,10751,10752 ,0,0,0}, {22868,22885,22888 ,10752,10744,10750 ,0,0,0}, + {22871,22889,22872 ,10751,10753,10754 ,0,0,0}, {22889,22871,22888 ,10753,10751,10750 ,0,0,0}, + {22873,22872,22890 ,10755,10754,10756 ,0,0,0}, {22889,22890,22872 ,10753,10756,10754 ,0,0,0}, + {22891,22874,22873 ,10757,10758,10755 ,0,0,0}, {22873,22890,22891 ,10755,10756,10757 ,0,0,0}, + {22869,22870,22886 ,10745,10747,10746 ,0,0,0}, {22868,22869,22885 ,10752,10745,10744 ,0,0,0}, + {22887,22866,22883 ,10749,10748,10740 ,0,0,0}, {22886,22870,22887 ,10746,10747,10749 ,0,0,0}, + {22882,22865,22867 ,10739,10741,10742 ,0,0,0}, {22883,22866,22865 ,10740,10748,10741 ,0,0,0}, + {22880,22884,22863 ,10734,10743,10735 ,0,0,0}, {22884,22867,22863 ,10743,10742,10735 ,0,0,0}, + {22864,22892,22862 ,10738,10759,10733 ,0,0,0}, {22892,22880,22862 ,10759,10734,10733 ,0,0,0}, + {22859,22877,22881 ,10736,10727,10737 ,0,0,0}, {22864,22881,22892 ,10738,10737,10759 ,0,0,0}, + {22860,22861,22878 ,10728,10731,10729 ,0,0,0}, {22859,22860,22877 ,10736,10728,10727 ,0,0,0}, + {22879,22857,22875 ,10730,10732,10724 ,0,0,0}, {22878,22861,22879 ,10729,10731,10730 ,0,0,0}, + {22858,22875,22857 ,10725,10724,10732 ,0,0,0}, {22893,22876,22894 ,10760,10761,10762 ,0,0,0}, + {22895,22878,22896 ,10763,10764,10765 ,0,0,0}, {22897,22879,22875 ,10766,10767,10768 ,0,0,0}, + {22892,22898,22899 ,10769,10770,10771 ,0,0,0}, {22877,22900,22881 ,10772,10773,10774 ,0,0,0}, + {22901,22902,22882 ,10775,10776,10777 ,0,0,0}, {22901,22884,22903 ,10775,10778,10779 ,0,0,0}, + {22904,22886,22905 ,10780,10781,10782 ,0,0,0}, {22887,22883,22906 ,10783,10784,10785 ,0,0,0}, + {22907,22888,22885 ,10786,10787,10788 ,0,0,0}, {22885,22904,22907 ,10788,10780,10786 ,0,0,0}, + {22888,22908,22889 ,10787,10789,10790 ,0,0,0}, {22908,22888,22907 ,10789,10787,10786 ,0,0,0}, + {22890,22889,22909 ,10791,10790,10792 ,0,0,0}, {22908,22909,22889 ,10789,10792,10790 ,0,0,0}, + {22910,22891,22890 ,10793,10794,10791 ,0,0,0}, {22890,22909,22910 ,10791,10792,10793 ,0,0,0}, + {22886,22887,22905 ,10781,10783,10782 ,0,0,0}, {22885,22886,22904 ,10788,10781,10780 ,0,0,0}, + {22906,22883,22902 ,10785,10784,10776 ,0,0,0}, {22905,22887,22906 ,10782,10783,10785 ,0,0,0}, + {22901,22882,22884 ,10775,10777,10778 ,0,0,0}, {22902,22883,22882 ,10776,10784,10777 ,0,0,0}, + {22899,22903,22880 ,10771,10779,10795 ,0,0,0}, {22903,22884,22880 ,10779,10778,10795 ,0,0,0}, + {22881,22898,22892 ,10774,10770,10769 ,0,0,0}, {22892,22899,22880 ,10769,10771,10795 ,0,0,0}, + {22877,22895,22900 ,10772,10763,10773 ,0,0,0}, {22881,22900,22898 ,10774,10773,10770 ,0,0,0}, + {22878,22879,22896 ,10764,10767,10765 ,0,0,0}, {22877,22878,22895 ,10772,10764,10763 ,0,0,0}, + {22897,22875,22893 ,10766,10768,10760 ,0,0,0}, {22896,22879,22897 ,10765,10767,10766 ,0,0,0}, + {22876,22893,22875 ,10761,10760,10768 ,0,0,0}, {22481,22894,22479 ,10796,10797,10798 ,0,0,0}, + {22482,22896,22483 ,10799,10800,10801 ,0,0,0}, {22493,22897,22893 ,10802,10803,10804 ,0,0,0}, + {22898,22506,22507 ,10805,10806,10807 ,0,0,0}, {22895,22494,22900 ,10808,10809,10810 ,0,0,0}, + {22509,22510,22901 ,10811,10812,10813 ,0,0,0}, {22508,22903,22899 ,10814,10815,10816 ,0,0,0}, + {22539,22905,22906 ,10817,10818,10819 ,0,0,0}, {22536,22902,22510 ,10820,10821,10812 ,0,0,0}, + {22540,22907,22904 ,10822,10823,10824 ,0,0,0}, {22904,22538,22540 ,10824,10825,10822 ,0,0,0}, + {22907,22541,22908 ,10823,10826,10827 ,0,0,0}, {22541,22907,22540 ,10826,10823,10822 ,0,0,0}, + {22908,22443,22440 ,10827,10828,10829 ,0,0,0}, {22541,22443,22908 ,10826,10828,10827 ,0,0,0}, + {22439,22909,22440 ,10047,10830,10829 ,0,0,0}, {22908,22440,22909 ,10827,10829,10830 ,0,0,0}, + {22910,22909,22439 ,10793,10830,10047 ,0,0,0}, {22538,22905,22539 ,10825,10818,10817 ,0,0,0}, + {22904,22905,22538 ,10824,10818,10825 ,0,0,0}, {22536,22906,22902 ,10820,10819,10821 ,0,0,0}, + {22539,22906,22536 ,10817,10819,10820 ,0,0,0}, {22901,22903,22509 ,10813,10815,10811 ,0,0,0}, + {22510,22902,22901 ,10812,10821,10813 ,0,0,0}, {22507,22508,22899 ,10807,10814,10816 ,0,0,0}, + {22508,22509,22903 ,10814,10811,10815 ,0,0,0}, {22900,22506,22898 ,10810,10806,10805 ,0,0,0}, + {22898,22507,22899 ,10805,10807,10816 ,0,0,0}, {22895,22482,22494 ,10808,10799,10809 ,0,0,0}, + {22900,22494,22506 ,10810,10809,10806 ,0,0,0}, {22896,22897,22483 ,10800,10803,10801 ,0,0,0}, + {22895,22896,22482 ,10808,10800,10799 ,0,0,0}, {22493,22893,22481 ,10802,10804,10796 ,0,0,0}, + {22483,22897,22493 ,10801,10803,10802 ,0,0,0}, {22894,22481,22893 ,10797,10796,10804 ,0,0,0}, + {22911,22419,22912 ,10831,10024,10832 ,0,0,0}, {22913,22529,22476 ,10833,10834,10835 ,0,0,0}, + {22914,22491,22417 ,10836,10837,10838 ,0,0,0}, {22534,22915,22916 ,10839,10840,10841 ,0,0,0}, + {22530,22917,22531 ,10842,10843,10844 ,0,0,0}, {22918,22919,22499 ,10845,10846,10847 ,0,0,0}, + {22920,22502,22503 ,10848,10849,10850 ,0,0,0}, {22921,22537,22922 ,10851,10852,10853 ,0,0,0}, + {22535,22500,22923 ,10854,10855,10856 ,0,0,0}, {22924,22514,22459 ,10857,10858,10859 ,0,0,0}, + {22459,22921,22924 ,10859,10851,10857 ,0,0,0}, {22514,22925,22542 ,10858,10860,10861 ,0,0,0}, + {22925,22514,22924 ,10860,10858,10857 ,0,0,0}, {22450,22542,22926 ,10862,10861,10863 ,0,0,0}, + {22925,22926,22542 ,10860,10863,10861 ,0,0,0}, {22927,22453,22450 ,10864,10865,10862 ,0,0,0}, + {22450,22926,22927 ,10862,10863,10864 ,0,0,0}, {22537,22535,22922 ,10852,10854,10853 ,0,0,0}, + {22459,22537,22921 ,10859,10852,10851 ,0,0,0}, {22923,22500,22919 ,10856,10855,10846 ,0,0,0}, + {22922,22535,22923 ,10853,10854,10856 ,0,0,0}, {22918,22499,22502 ,10845,10847,10849 ,0,0,0}, + {22919,22500,22499 ,10846,10855,10847 ,0,0,0}, {22916,22920,22503 ,10841,10848,10850 ,0,0,0}, + {22920,22918,22502 ,10848,10845,10849 ,0,0,0}, {22531,22915,22534 ,10844,10840,10839 ,0,0,0}, + {22534,22916,22503 ,10839,10841,10850 ,0,0,0}, {22530,22928,22917 ,10842,10866,10843 ,0,0,0}, + {22531,22917,22915 ,10844,10843,10840 ,0,0,0}, {22913,22928,22529 ,10833,10866,10834 ,0,0,0}, + {22530,22529,22928 ,10842,10834,10866 ,0,0,0}, {22914,22476,22491 ,10836,10835,10837 ,0,0,0}, + {22913,22476,22914 ,10833,10835,10836 ,0,0,0}, {22911,22417,22419 ,10831,10838,10024 ,0,0,0}, + {22914,22417,22911 ,10836,10838,10831 ,0,0,0}, {22929,22912,22930 ,10867,10832,10868 ,0,0,0}, + {22931,22913,22932 ,10869,10870,10871 ,0,0,0}, {22933,22914,22911 ,10872,10873,10874 ,0,0,0}, + {22915,22934,22935 ,10875,10876,10877 ,0,0,0}, {22928,22936,22917 ,10878,10879,10880 ,0,0,0}, + {22937,22919,22918 ,10881,10882,10883 ,0,0,0}, {22938,22920,22939 ,10884,10885,10886 ,0,0,0}, + {22940,22922,22941 ,10887,10888,10889 ,0,0,0}, {22923,22919,22942 ,10890,10882,10891 ,0,0,0}, + {22943,22924,22921 ,10892,10893,10894 ,0,0,0}, {22921,22940,22943 ,10894,10887,10892 ,0,0,0}, + {22924,22944,22925 ,10893,10895,10896 ,0,0,0}, {22944,22924,22943 ,10895,10893,10892 ,0,0,0}, + {22926,22925,22945 ,10897,10896,10898 ,0,0,0}, {22944,22945,22925 ,10895,10898,10896 ,0,0,0}, + {22946,22927,22926 ,10899,10900,10897 ,0,0,0}, {22926,22945,22946 ,10897,10898,10899 ,0,0,0}, + {22922,22923,22941 ,10888,10890,10889 ,0,0,0}, {22921,22922,22940 ,10894,10888,10887 ,0,0,0}, + {22942,22919,22937 ,10891,10882,10881 ,0,0,0}, {22941,22923,22942 ,10889,10890,10891 ,0,0,0}, + {22938,22918,22920 ,10884,10883,10885 ,0,0,0}, {22937,22918,22938 ,10881,10883,10884 ,0,0,0}, + {22935,22939,22916 ,10877,10886,10901 ,0,0,0}, {22939,22920,22916 ,10886,10885,10901 ,0,0,0}, + {22917,22934,22915 ,10880,10876,10875 ,0,0,0}, {22915,22935,22916 ,10875,10877,10901 ,0,0,0}, + {22928,22931,22936 ,10878,10869,10879 ,0,0,0}, {22917,22936,22934 ,10880,10879,10876 ,0,0,0}, + {22913,22914,22932 ,10870,10873,10871 ,0,0,0}, {22928,22913,22931 ,10878,10870,10869 ,0,0,0}, + {22933,22911,22929 ,10872,10874,10867 ,0,0,0}, {22932,22914,22933 ,10871,10873,10872 ,0,0,0}, + {22912,22929,22911 ,10832,10867,10874 ,0,0,0}, {22947,22930,22948 ,10902,10868,10903 ,0,0,0}, + {22949,22932,22950 ,10904,10905,10906 ,0,0,0}, {22951,22933,22929 ,10907,10908,10909 ,0,0,0}, + {22934,22952,22935 ,10910,10911,10912 ,0,0,0}, {22931,22953,22936 ,10913,10914,10915 ,0,0,0}, + {22954,22937,22938 ,10916,10917,10918 ,0,0,0}, {22955,22939,22956 ,10919,10920,10921 ,0,0,0}, + {22957,22941,22958 ,10922,10923,10924 ,0,0,0}, {22942,22937,22959 ,10925,10917,10926 ,0,0,0}, + {22960,22943,22940 ,10927,10928,10929 ,0,0,0}, {22940,22957,22960 ,10929,10922,10927 ,0,0,0}, + {22943,22961,22944 ,10928,10930,10931 ,0,0,0}, {22961,22943,22960 ,10930,10928,10927 ,0,0,0}, + {22945,22944,22962 ,10932,10931,10933 ,0,0,0}, {22961,22962,22944 ,10930,10933,10931 ,0,0,0}, + {22963,22946,22945 ,10934,10935,10932 ,0,0,0}, {22945,22962,22963 ,10932,10933,10934 ,0,0,0}, + {22941,22942,22958 ,10923,10925,10924 ,0,0,0}, {22940,22941,22957 ,10929,10923,10922 ,0,0,0}, + {22959,22937,22954 ,10926,10917,10916 ,0,0,0}, {22958,22942,22959 ,10924,10925,10926 ,0,0,0}, + {22955,22938,22939 ,10919,10918,10920 ,0,0,0}, {22954,22938,22955 ,10916,10918,10919 ,0,0,0}, + {22952,22956,22935 ,10911,10921,10912 ,0,0,0}, {22956,22939,22935 ,10921,10920,10912 ,0,0,0}, + {22936,22964,22934 ,10915,10936,10910 ,0,0,0}, {22964,22952,22934 ,10936,10911,10910 ,0,0,0}, + {22931,22949,22953 ,10913,10904,10914 ,0,0,0}, {22936,22953,22964 ,10915,10914,10936 ,0,0,0}, + {22932,22933,22950 ,10905,10908,10906 ,0,0,0}, {22931,22932,22949 ,10913,10905,10904 ,0,0,0}, + {22951,22929,22947 ,10907,10909,10902 ,0,0,0}, {22950,22933,22951 ,10906,10908,10907 ,0,0,0}, + {22930,22947,22929 ,10868,10902,10909 ,0,0,0}, {22547,22965,22584 ,10937,10938,10226 ,0,0,0}, + {22553,22966,22554 ,10939,10940,10941 ,0,0,0}, {22549,22967,22968 ,10942,10943,10944 ,0,0,0}, + {22969,22561,22970 ,10945,10946,10947 ,0,0,0}, {22971,22551,22972 ,10948,10949,10950 ,0,0,0}, + {22566,22973,22974 ,10951,10952,10953 ,0,0,0}, {22558,22975,22556 ,10954,10955,10956 ,0,0,0}, + {22976,22977,22571 ,10957,10958,10959 ,0,0,0}, {22978,22564,22563 ,10960,10961,10962 ,0,0,0}, + {22979,22980,22568 ,10963,10964,10965 ,0,0,0}, {22569,22568,22980 ,10966,10965,10964 ,0,0,0}, + {22575,22981,22979 ,10967,10968,10963 ,0,0,0}, {22979,22568,22575 ,10963,10965,10967 ,0,0,0}, + {22981,22577,22982 ,10968,10969,10970 ,0,0,0}, {22577,22981,22575 ,10969,10968,10967 ,0,0,0}, + {22983,22982,22578 ,10971,10970,10972 ,0,0,0}, {22577,22578,22982 ,10969,10972,10970 ,0,0,0}, + {22581,22984,22983 ,10223,10973,10971 ,0,0,0}, {22983,22578,22581 ,10971,10972,10223 ,0,0,0}, + {22571,22569,22976 ,10959,10966,10957 ,0,0,0}, {22976,22569,22980 ,10957,10966,10964 ,0,0,0}, + {22977,22978,22563 ,10958,10960,10962 ,0,0,0}, {22977,22563,22571 ,10958,10962,10959 ,0,0,0}, + {22564,22973,22566 ,10961,10952,10951 ,0,0,0}, {22978,22973,22564 ,10960,10952,10961 ,0,0,0}, + {22558,22974,22975 ,10954,10953,10955 ,0,0,0}, {22566,22974,22558 ,10951,10953,10954 ,0,0,0}, + {22561,22556,22970 ,10946,10956,10947 ,0,0,0}, {22556,22975,22970 ,10956,10955,10947 ,0,0,0}, + {22972,22583,22969 ,10950,10974,10945 ,0,0,0}, {22583,22561,22969 ,10974,10946,10945 ,0,0,0}, + {22971,22553,22551 ,10948,10939,10949 ,0,0,0}, {22972,22551,22583 ,10950,10949,10974 ,0,0,0}, + {22966,22967,22554 ,10940,10943,10941 ,0,0,0}, {22971,22966,22553 ,10948,10940,10939 ,0,0,0}, + {22549,22968,22547 ,10942,10944,10937 ,0,0,0}, {22554,22967,22549 ,10941,10943,10942 ,0,0,0}, + {22965,22547,22968 ,10938,10937,10944 ,0,0,0}, {22985,22948,22986 ,10975,10903,10976 ,0,0,0}, + {22987,22950,22988 ,10977,10978,10979 ,0,0,0}, {22989,22951,22947 ,10980,10981,10982 ,0,0,0}, + {22964,22990,22991 ,10983,10984,10985 ,0,0,0}, {22949,22992,22953 ,10986,10987,10988 ,0,0,0}, + {22993,22994,22955 ,10989,10990,10991 ,0,0,0}, {22995,22956,22952 ,10992,10993,10994 ,0,0,0}, + {22996,22958,22959 ,10995,10996,10997 ,0,0,0}, {22959,22954,22997 ,10997,10998,10999 ,0,0,0}, + {22998,22960,22957 ,11000,11001,11002 ,0,0,0}, {22957,22999,22998 ,11002,11003,11000 ,0,0,0}, + {22960,23000,22961 ,11001,11004,11005 ,0,0,0}, {23000,22960,22998 ,11004,11001,11000 ,0,0,0}, + {22962,22961,23001 ,11006,11005,11007 ,0,0,0}, {23000,23001,22961 ,11004,11007,11005 ,0,0,0}, + {23002,22962,23003 ,11008,11006,11009 ,0,0,0}, {22962,23001,23003 ,11006,11007,11009 ,0,0,0}, + {22963,22962,23002 ,11010,11006,11008 ,0,0,0}, {22999,22958,22996 ,11003,10996,10995 ,0,0,0}, + {22957,22958,22999 ,11002,10996,11003 ,0,0,0}, {22954,22994,22997 ,10998,10990,10999 ,0,0,0}, + {22996,22959,22997 ,10995,10997,10999 ,0,0,0}, {22993,22955,22956 ,10989,10991,10993 ,0,0,0}, + {22994,22954,22955 ,10990,10998,10991 ,0,0,0}, {22991,22995,22952 ,10985,10992,10994 ,0,0,0}, + {22995,22993,22956 ,10992,10989,10993 ,0,0,0}, {22953,22990,22964 ,10988,10984,10983 ,0,0,0}, + {22964,22991,22952 ,10983,10985,10994 ,0,0,0}, {22949,22987,22992 ,10986,10977,10987 ,0,0,0}, + {22953,22992,22990 ,10988,10987,10984 ,0,0,0}, {22950,22951,22988 ,10978,10981,10979 ,0,0,0}, + {22949,22950,22987 ,10986,10978,10977 ,0,0,0}, {22989,22947,22985 ,10980,10982,10975 ,0,0,0}, + {22988,22951,22989 ,10979,10981,10980 ,0,0,0}, {22948,22985,22947 ,10903,10975,10982 ,0,0,0}, + {22968,22986,22965 ,11011,10976,11012 ,0,0,0}, {22971,22988,22966 ,11013,11014,11015 ,0,0,0}, + {22967,22989,22985 ,11016,11017,11018 ,0,0,0}, {22990,22969,22970 ,11019,11020,11021 ,0,0,0}, + {22987,22972,22992 ,11022,11023,11024 ,0,0,0}, {22974,22973,22993 ,11025,11026,11027 ,0,0,0}, + {22975,22995,22991 ,11028,11029,11030 ,0,0,0}, {22976,22996,22977 ,11031,11032,11033 ,0,0,0}, + {22997,22994,22978 ,11034,11035,11036 ,0,0,0}, {22979,22998,22980 ,11037,11038,11039 ,0,0,0}, + {22999,22976,22980 ,11040,11031,11039 ,0,0,0}, {22979,22981,23000 ,11037,11041,11042 ,0,0,0}, + {23000,22998,22979 ,11042,11038,11037 ,0,0,0}, {23001,22981,22982 ,11043,11041,11044 ,0,0,0}, + {22981,23001,23000 ,11041,11043,11042 ,0,0,0}, {22983,23003,22982 ,11045,11046,11044 ,0,0,0}, + {23001,22982,23003 ,11043,11044,11046 ,0,0,0}, {22984,23002,23003 ,11047,11008,11046 ,0,0,0}, + {23003,22983,22984 ,11046,11045,11047 ,0,0,0}, {22996,22976,22999 ,11032,11031,11040 ,0,0,0}, + {22998,22999,22980 ,11038,11040,11039 ,0,0,0}, {22977,22997,22978 ,11033,11034,11036 ,0,0,0}, + {22996,22997,22977 ,11032,11034,11033 ,0,0,0}, {22973,22994,22993 ,11026,11035,11027 ,0,0,0}, + {22978,22994,22973 ,11036,11035,11026 ,0,0,0}, {22975,22974,22995 ,11028,11025,11029 ,0,0,0}, + {22974,22993,22995 ,11025,11027,11029 ,0,0,0}, {22990,22970,22991 ,11019,11021,11030 ,0,0,0}, + {22970,22975,22991 ,11021,11028,11030 ,0,0,0}, {22992,22972,22969 ,11024,11023,11020 ,0,0,0}, + {22992,22969,22990 ,11024,11020,11019 ,0,0,0}, {22987,22988,22971 ,11022,11014,11013 ,0,0,0}, + {22987,22971,22972 ,11022,11013,11023 ,0,0,0}, {22966,22989,22967 ,11015,11017,11016 ,0,0,0}, + {22988,22989,22966 ,11014,11017,11015 ,0,0,0}, {22968,22985,22986 ,11011,11018,10976 ,0,0,0}, + {22967,22985,22968 ,11016,11018,11011 ,0,0,0}, {22671,23004,23005 ,11048,11049,11050 ,0,0,0}, + {22670,23006,22668 ,11051,11052,11053 ,0,0,0}, {23004,22671,23007 ,11049,11048,11054 ,0,0,0}, + {23005,23008,22671 ,11050,11048,11048 ,0,0,0}, {23007,22671,22668 ,11054,11048,11053 ,0,0,0}, + {23009,23007,22668 ,11055,11054,11053 ,0,0,0}, {23009,22668,23006 ,11055,11053,11052 ,0,0,0}, + {22706,22624,23010 ,11056,11057,11058 ,0,0,0}, {22706,23011,23012 ,11056,11059,11060 ,0,0,0}, + {23010,23011,22706 ,11058,11059,11056 ,0,0,0}, {22670,23012,23013 ,11051,11060,11061 ,0,0,0}, + {22670,22706,23012 ,11051,11056,11060 ,0,0,0}, {22670,23014,23015 ,11051,11062,11063 ,0,0,0}, + {23013,23014,22670 ,11061,11062,11051 ,0,0,0}, {22670,23016,23017 ,11051,11064,11065 ,0,0,0}, + {23015,23016,22670 ,11063,11064,11051 ,0,0,0}, {23006,22670,23018 ,11052,11051,11066 ,0,0,0}, + {23017,23018,22670 ,11065,11066,11051 ,0,0,0}, {23019,22492,23020 ,11067,11068,11069 ,0,0,0}, + {22492,23021,23022 ,11068,11070,11071 ,0,0,0}, {23022,22490,22492 ,11071,11072,11068 ,0,0,0}, + {22492,23019,23021 ,11068,11067,11070 ,0,0,0}, {22490,23023,23024 ,11072,11073,11074 ,0,0,0}, + {22490,23022,23023 ,11072,11071,11073 ,0,0,0}, {22492,23025,23020 ,11068,11075,11069 ,0,0,0}, + {22490,23024,22419 ,11072,11074,11076 ,0,0,0}, {23026,22492,22477 ,11077,11068,11078 ,0,0,0}, + {22492,23026,23025 ,11068,11077,11075 ,0,0,0}, {22479,23027,23028 ,11079,11079,11080 ,0,0,0}, + {23029,23030,22480 ,11081,11082,11083 ,0,0,0}, {23031,23032,22479 ,11084,11085,11079 ,0,0,0}, + {23031,22479,23028 ,11084,11079,11080 ,0,0,0}, {22479,23033,22480 ,11079,11086,11083 ,0,0,0}, + {23033,22479,23032 ,11086,11079,11085 ,0,0,0}, {23034,22480,23030 ,11087,11083,11082 ,0,0,0}, + {23033,23029,22480 ,11086,11081,11083 ,0,0,0}, {23026,22477,23034 ,11077,11078,11087 ,0,0,0}, + {23034,22477,22480 ,11087,11078,11083 ,0,0,0}, {23027,22479,23035 ,11088,11089,11090 ,0,0,0}, + {22876,23035,22894 ,11091,11090,11092 ,0,0,0}, {22876,22858,23035 ,11091,11093,11090 ,0,0,0}, + {23035,22858,22847 ,11090,11093,11094 ,0,0,0}, {22847,22819,23035 ,11094,11095,11090 ,0,0,0}, + {23035,22479,22894 ,11090,11089,11092 ,0,0,0}, {23036,23034,23037 ,11096,11097,11098 ,0,0,0}, + {23036,23038,23026 ,11096,324,11099 ,0,0,0}, {23026,23034,23036 ,11099,11097,11096 ,0,0,0}, + {23039,23040,23041 ,11100,11101,11102 ,0,0,0}, {23040,23042,23041 ,11101,11103,11102 ,0,0,0}, + {23040,23039,23043 ,11101,11100,11104 ,0,0,0}, {23021,23044,23043 ,11105,11106,11104 ,0,0,0}, + {23039,23021,23043 ,11100,11105,11104 ,0,0,0}, {23019,23044,23021 ,11107,11106,11105 ,0,0,0}, + {23044,23019,23045 ,11106,11107,11108 ,0,0,0}, {23020,23046,23045 ,11109,11110,11108 ,0,0,0}, + {23045,23019,23020 ,11108,11107,11109 ,0,0,0}, {23046,23025,23047 ,11110,11111,11112 ,0,0,0}, + {23025,23046,23020 ,11111,11110,11109 ,0,0,0}, {23038,23047,23026 ,11113,11112,11114 ,0,0,0}, + {23025,23026,23047 ,11111,11114,11112 ,0,0,0}, {23032,23048,23049 ,11115,11116,11117 ,0,0,0}, + {23037,23034,23030 ,11118,11119,11120 ,0,0,0}, {23030,23029,23050 ,11120,11121,11122 ,0,0,0}, + {23051,23033,23049 ,11123,11124,11117 ,0,0,0}, {23050,23029,23051 ,11122,11121,11123 ,0,0,0}, + {23030,23050,23037 ,11120,11122,11118 ,0,0,0}, {23029,23033,23051 ,11121,11124,11123 ,0,0,0}, + {23033,23032,23049 ,11124,11115,11117 ,0,0,0}, {23048,23032,23031 ,11116,11115,11125 ,0,0,0}, + {23031,23028,23052 ,11125,11126,11127 ,0,0,0}, {23052,23048,23031 ,11127,11116,11125 ,0,0,0}, + {23053,23028,23027 ,11128,11126,11129 ,0,0,0}, {23028,23053,23052 ,11126,11128,11127 ,0,0,0}, + {23053,23027,23035 ,11128,11129,11129 ,0,0,0}, {23008,23054,23055 ,11130,11130,11131 ,0,0,0}, + {23008,23055,23056 ,11130,11131,11130 ,0,0,0}, {23057,23008,23056 ,11130,11130,11130 ,0,0,0}, + {23048,23052,23008 ,11130,11130,11130 ,0,0,0}, {23048,23008,23057 ,11130,11130,11130 ,0,0,0}, + {23008,23053,23035 ,11130,11130,11131 ,0,0,0}, {23052,23053,23008 ,11130,11130,11130 ,0,0,0}, + {23008,23035,22671 ,11130,11131,11130 ,0,0,0}, {23035,22798,22778 ,11131,11130,11130 ,0,0,0}, + {23035,22819,22798 ,11131,11131,11130 ,0,0,0}, {22778,22758,23035 ,11130,11131,11131 ,0,0,0}, + {22671,23035,22739 ,11130,11131,11130 ,0,0,0}, {23035,22758,22739 ,11131,11131,11130 ,0,0,0}, + {22584,22965,23058 ,11132,11133,11134 ,0,0,0}, {23010,23059,23011 ,11135,11136,11137 ,0,0,0}, + {23060,23059,22585 ,11138,11136,11139 ,0,0,0}, {23061,23042,23062 ,11140,11141,11142 ,0,0,0}, + {23063,23061,23062 ,11143,11140,11142 ,0,0,0}, {23064,23065,23066 ,11144,11145,11146 ,0,0,0}, + {23065,23063,23066 ,11145,11143,11146 ,0,0,0}, {23059,22605,22585 ,11136,11147,11139 ,0,0,0}, + {23060,22585,22545 ,11138,11139,11148 ,0,0,0}, {23064,23012,23011 ,11144,11149,11137 ,0,0,0}, + {22624,22605,23010 ,11150,11147,11135 ,0,0,0}, {22584,23060,22545 ,11132,11138,11148 ,0,0,0}, + {23058,23067,23060 ,11134,11151,11138 ,0,0,0}, {23060,22584,23058 ,11138,11132,11134 ,0,0,0}, + {23067,23061,23063 ,11151,11140,11143 ,0,0,0}, {23065,23064,23011 ,11145,11144,11137 ,0,0,0}, + {23063,23065,23060 ,11143,11145,11138 ,0,0,0}, {23010,22605,23059 ,11135,11147,11136 ,0,0,0}, + {23063,23060,23067 ,11143,11138,11151 ,0,0,0}, {23062,23066,23063 ,11142,11146,11143 ,0,0,0}, + {23011,23059,23065 ,11137,11136,11145 ,0,0,0}, {23060,23065,23059 ,11138,11145,11136 ,0,0,0}, + {23068,23069,23070 ,11152,11153,11154 ,0,0,0}, {23071,23072,23073 ,11155,11156,11157 ,0,0,0}, + {23074,23075,23076 ,11158,11159,11160 ,0,0,0}, {23042,23040,23077 ,11161,11162,11163 ,0,0,0}, + {23078,23079,23016 ,11164,11165,11166 ,0,0,0}, {23080,23081,23082 ,11167,11168,11169 ,0,0,0}, + {23083,23084,23069 ,11170,11171,11153 ,0,0,0}, {23006,23018,23084 ,11172,11173,11171 ,0,0,0}, + {23085,23047,23038 ,11174,11175,11176 ,0,0,0}, {23068,23070,23085 ,11152,11154,11174 ,0,0,0}, + {23006,23084,23083 ,11172,11171,11170 ,0,0,0}, {23073,23070,23069 ,11157,11154,11153 ,0,0,0}, + {23018,23086,23084 ,11173,11177,11171 ,0,0,0}, {23079,23086,23017 ,11165,11177,11178 ,0,0,0}, + {23087,23078,23082 ,11179,11164,11169 ,0,0,0}, {23088,23076,23072 ,11180,11160,11156 ,0,0,0}, + {23013,23064,23080 ,11181,11182,11167 ,0,0,0}, {23075,23087,23077 ,11159,11179,11163 ,0,0,0}, + {23012,23064,23013 ,11183,11182,11181 ,0,0,0}, {23080,23064,23066 ,11167,11182,11184 ,0,0,0}, + {23017,23086,23018 ,11178,11177,11173 ,0,0,0}, {23017,23016,23079 ,11178,11166,11165 ,0,0,0}, + {23085,23070,23047 ,11174,11154,11175 ,0,0,0}, {23083,23069,23068 ,11170,11153,11152 ,0,0,0}, + {23073,23069,23071 ,11157,11153,11155 ,0,0,0}, {23046,23047,23070 ,11185,11175,11154 ,0,0,0}, + {23071,23084,23086 ,11155,11171,11177 ,0,0,0}, {23062,23042,23077 ,11186,11161,11163 ,0,0,0}, + {23070,23073,23046 ,11154,11157,11185 ,0,0,0}, {23084,23071,23069 ,11171,11155,11153 ,0,0,0}, + {23072,23071,23088 ,11156,11155,11180 ,0,0,0}, {23045,23046,23073 ,11187,11185,11157 ,0,0,0}, + {23079,23088,23086 ,11165,11180,11177 ,0,0,0}, {23015,23078,23016 ,11188,11164,11166 ,0,0,0}, + {23073,23072,23045 ,11157,11156,11187 ,0,0,0}, {23086,23088,23071 ,11177,11180,11155 ,0,0,0}, + {23076,23088,23074 ,11160,11180,11158 ,0,0,0}, {23044,23045,23072 ,11189,11187,11156 ,0,0,0}, + {23078,23074,23079 ,11164,11158,11165 ,0,0,0}, {23014,23082,23015 ,11190,11169,11188 ,0,0,0}, + {23076,23043,23044 ,11160,11191,11189 ,0,0,0}, {23079,23074,23088 ,11165,11158,11180 ,0,0,0}, + {23074,23087,23075 ,11158,11179,11159 ,0,0,0}, {23044,23072,23076 ,11189,11156,11160 ,0,0,0}, + {23015,23082,23078 ,11188,11169,11164 ,0,0,0}, {23080,23014,23013 ,11167,11190,11181 ,0,0,0}, + {23075,23040,23043 ,11159,11162,11191 ,0,0,0}, {23078,23087,23074 ,11164,11179,11158 ,0,0,0}, + {23081,23077,23087 ,11168,11163,11179 ,0,0,0}, {23043,23076,23075 ,11191,11160,11159 ,0,0,0}, + {23014,23080,23082 ,11190,11167,11169 ,0,0,0}, {23082,23081,23087 ,11169,11168,11179 ,0,0,0}, + {23066,23062,23081 ,11184,11186,11168 ,0,0,0}, {23080,23066,23081 ,11167,11184,11168 ,0,0,0}, + {23062,23077,23081 ,11186,11163,11168 ,0,0,0}, {23040,23075,23077 ,11162,11159,11163 ,0,0,0}, + {23085,23036,23089 ,11192,11193,11194 ,0,0,0}, {23009,23090,23007 ,11195,11196,11054 ,0,0,0}, + {23089,23036,23091 ,11194,11193,11197 ,0,0,0}, {23036,23037,23091 ,11193,324,11197 ,0,0,0}, + {23089,23092,23090 ,11194,11198,11196 ,0,0,0}, {23085,23038,23036 ,11192,324,11193 ,0,0,0}, + {23090,23092,23007 ,11196,11198,11054 ,0,0,0}, {23083,23090,23009 ,11199,11196,11195 ,0,0,0}, + {23006,23083,23009 ,11200,11199,11195 ,0,0,0}, {23083,23068,23090 ,11199,11201,11196 ,0,0,0}, + {23068,23085,23089 ,11201,11192,11194 ,0,0,0}, {23068,23089,23090 ,11201,11194,11196 ,0,0,0}, + {23092,23089,23091 ,11198,11194,11197 ,0,0,0}, {23057,23056,23049 ,11202,11203,11204 ,0,0,0}, + {23091,23037,23050 ,11205,324,11206 ,0,0,0}, {23050,23051,23093 ,11206,11207,11208 ,0,0,0}, + {23050,23093,23091 ,11206,11208,11205 ,0,0,0}, {23048,23057,23049 ,11209,11202,11204 ,0,0,0}, + {23055,23054,23094 ,11210,11211,11212 ,0,0,0}, {23094,23095,23055 ,11212,11213,11210 ,0,0,0}, + {23092,23093,23096 ,11214,11208,11215 ,0,0,0}, {23096,23093,23095 ,11215,11208,11213 ,0,0,0}, + {23054,23008,23005 ,11211,11216,11217 ,0,0,0}, {23092,23096,23007 ,11214,11215,11218 ,0,0,0}, + {23005,23096,23094 ,11217,11215,11212 ,0,0,0}, {23091,23093,23092 ,11205,11208,11214 ,0,0,0}, + {23005,23004,23096 ,11217,11219,11215 ,0,0,0}, {23096,23004,23007 ,11215,11219,11218 ,0,0,0}, + {23093,23051,23095 ,11208,11207,11213 ,0,0,0}, {23049,23095,23051 ,11204,11213,11207 ,0,0,0}, + {23005,23094,23054 ,11217,11212,11211 ,0,0,0}, {23096,23095,23094 ,11215,11213,11212 ,0,0,0}, + {23056,23095,23049 ,11203,11213,11204 ,0,0,0}, {23056,23055,23095 ,11203,11210,11213 ,0,0,0}, + {22930,23097,23098 ,11220,11221,11222 ,0,0,0}, {23042,23061,23099 ,11223,11224,11225 ,0,0,0}, + {23100,23099,23061 ,11226,11225,11224 ,0,0,0}, {22930,23098,22948 ,11220,11222,11227 ,0,0,0}, + {23098,23097,23100 ,11222,11221,11226 ,0,0,0}, {23058,22965,22986 ,11228,11229,11230 ,0,0,0}, + {22948,23098,22986 ,11227,11222,11230 ,0,0,0}, {23024,23097,22912 ,11231,11221,11232 ,0,0,0}, + {23101,23024,23023 ,11233,11231,11234 ,0,0,0}, {23097,22930,22912 ,11221,11220,11232 ,0,0,0}, + {23099,23039,23041 ,11225,11235,11236 ,0,0,0}, {23099,23101,23102 ,11225,11233,11237 ,0,0,0}, + {22912,22419,23024 ,11232,11238,11231 ,0,0,0}, {23039,23102,23021 ,11235,11237,11239 ,0,0,0}, + {23102,23039,23099 ,11237,11235,11225 ,0,0,0}, {23098,23058,22986 ,11222,11228,11230 ,0,0,0}, + {23097,23101,23100 ,11221,11233,11226 ,0,0,0}, {23067,23058,23098 ,11240,11228,11222 ,0,0,0}, + {23024,23101,23097 ,11231,11233,11221 ,0,0,0}, {23102,23023,23022 ,11237,11234,11241 ,0,0,0}, + {23061,23067,23100 ,11224,11240,11226 ,0,0,0}, {23098,23100,23067 ,11222,11226,11240 ,0,0,0}, + {23023,23102,23101 ,11234,11237,11233 ,0,0,0}, {23021,23102,23022 ,11239,11237,11241 ,0,0,0}, + {23099,23041,23042 ,11225,11236,11223 ,0,0,0}, {23101,23099,23100 ,11233,11225,11226 ,0,0,0}, + {23103,22544,23104 ,11242,11243,11244 ,0,0,0}, {22544,23105,23106 ,11243,11245,11246 ,0,0,0}, + {23106,22543,22544 ,11246,11247,11243 ,0,0,0}, {22544,23103,23105 ,11243,11242,11245 ,0,0,0}, + {22543,23107,23108 ,11247,11248,11249 ,0,0,0}, {22543,23106,23107 ,11247,11246,11248 ,0,0,0}, + {22544,23109,23104 ,11243,11250,11244 ,0,0,0}, {22543,23108,22439 ,11247,11249,11251 ,0,0,0}, + {23110,22544,22452 ,11252,11243,11253 ,0,0,0}, {22544,23110,23109 ,11243,11252,11250 ,0,0,0}, + {22453,23111,23112 ,11254,11254,11255 ,0,0,0}, {23113,23114,22451 ,11256,11257,11258 ,0,0,0}, + {23115,23116,22453 ,11259,11260,11254 ,0,0,0}, {23115,22453,23112 ,11259,11254,11255 ,0,0,0}, + {22453,23117,22451 ,11254,11261,11258 ,0,0,0}, {23117,22453,23116 ,11261,11254,11260 ,0,0,0}, + {23118,22451,23114 ,11262,11258,11257 ,0,0,0}, {23117,23113,22451 ,11261,11256,11258 ,0,0,0}, + {23110,22452,23118 ,11252,11253,11262 ,0,0,0}, {23118,22452,22451 ,11262,11253,11258 ,0,0,0}, + {22661,23119,23120 ,11263,11264,11265 ,0,0,0}, {22738,23121,22692 ,11266,11267,11268 ,0,0,0}, + {23119,22661,23122 ,11264,11263,11269 ,0,0,0}, {23120,23123,22661 ,11265,11263,11263 ,0,0,0}, + {23122,22661,22692 ,11269,11263,11268 ,0,0,0}, {23124,23122,22692 ,11270,11269,11268 ,0,0,0}, + {23124,22692,23121 ,11270,11268,11267 ,0,0,0}, {22695,22719,23125 ,11271,11272,11273 ,0,0,0}, + {22695,23126,23127 ,11271,11274,11275 ,0,0,0}, {23125,23126,22695 ,11273,11274,11271 ,0,0,0}, + {22738,23127,23128 ,11266,11275,11276 ,0,0,0}, {22738,22695,23127 ,11266,11271,11275 ,0,0,0}, + {22738,23129,23130 ,11266,11277,11278 ,0,0,0}, {23128,23129,22738 ,11276,11277,11266 ,0,0,0}, + {22738,23131,23132 ,11266,11279,11280 ,0,0,0}, {23130,23131,22738 ,11278,11279,11266 ,0,0,0}, + {23121,22738,23133 ,11267,11266,11281 ,0,0,0}, {23132,23133,22738 ,11280,11281,11266 ,0,0,0}, + {23002,23111,22963 ,11282,11283,11282 ,0,0,0}, {22453,22927,23111 ,11282,11282,11283 ,0,0,0}, + {22984,23134,23111 ,11282,11283,11283 ,0,0,0}, {23111,23002,22984 ,11283,11282,11282 ,0,0,0}, + {22946,22963,23111 ,11282,11282,11283 ,0,0,0}, {22946,23111,22927 ,11282,11283,11282 ,0,0,0}, + {23135,23136,23110 ,21,21,21 ,0,0,0}, {23118,23137,23135 ,11284,21,21 ,0,0,0}, + {23135,23110,23118 ,21,21,11284 ,0,0,0}, {23138,23139,23140 ,11285,11286,11287 ,0,0,0}, + {23139,23141,23140 ,11286,11288,11287 ,0,0,0}, {23139,23138,23142 ,11286,11285,11289 ,0,0,0}, + {23105,23143,23142 ,11290,11291,11289 ,0,0,0}, {23138,23105,23142 ,11285,11290,11289 ,0,0,0}, + {23103,23143,23105 ,11292,11291,11290 ,0,0,0}, {23143,23103,23144 ,11291,11292,11293 ,0,0,0}, + {23104,23145,23144 ,11294,11295,11293 ,0,0,0}, {23144,23103,23104 ,11293,11292,11294 ,0,0,0}, + {23145,23109,23146 ,11295,11296,11297 ,0,0,0}, {23109,23145,23104 ,11296,11295,11294 ,0,0,0}, + {23136,23146,23110 ,11298,11297,11299 ,0,0,0}, {23109,23110,23146 ,11296,11299,11297 ,0,0,0}, + {23147,23148,23116 ,11300,11301,11302 ,0,0,0}, {23149,23117,23148 ,11303,11304,11301 ,0,0,0}, + {23118,23114,23137 ,21,11305,21 ,0,0,0}, {23113,23150,23114 ,11306,11307,11305 ,0,0,0}, + {23113,23149,23150 ,11306,11303,11307 ,0,0,0}, {23150,23137,23114 ,11307,21,11305 ,0,0,0}, + {23117,23149,23113 ,11304,11303,11306 ,0,0,0}, {23117,23116,23148 ,11304,11302,11301 ,0,0,0}, + {23147,23116,23115 ,11300,11302,11308 ,0,0,0}, {23115,23112,23151 ,11308,11309,11310 ,0,0,0}, + {23151,23147,23115 ,11310,11300,11308 ,0,0,0}, {23152,23112,23111 ,11311,11309,11312 ,0,0,0}, + {23112,23152,23151 ,11309,11311,11310 ,0,0,0}, {23152,23111,23134 ,11311,11312,11312 ,0,0,0}, + {22622,23134,22603 ,11313,11314,11315 ,0,0,0}, {23153,23123,23154 ,11316,11317,11318 ,0,0,0}, + {23123,23147,23151 ,11317,11319,11320 ,0,0,0}, {23151,23152,23123 ,11320,11321,11317 ,0,0,0}, + {23153,23155,23123 ,11316,11322,11317 ,0,0,0}, {23123,23156,23147 ,11317,11323,11319 ,0,0,0}, + {23155,23156,23123 ,11322,11323,11317 ,0,0,0}, {23134,22661,23123 ,11314,11324,11317 ,0,0,0}, + {23152,23134,23123 ,11321,11314,11317 ,0,0,0}, {23134,22641,22661 ,11314,11325,11324 ,0,0,0}, + {22641,23134,22622 ,11325,11314,11313 ,0,0,0}, {23134,22581,22582 ,11314,11326,11327 ,0,0,0}, + {23134,22984,22581 ,11314,11314,11326 ,0,0,0}, {22582,22603,23134 ,11327,11315,11314 ,0,0,0}, + {22816,22836,23157 ,11328,11329,11330 ,0,0,0}, {23125,23158,23126 ,11331,11332,11333 ,0,0,0}, + {23159,23158,22777 ,11334,11332,11335 ,0,0,0}, {23160,23141,23161 ,11336,11337,11338 ,0,0,0}, + {23162,23160,23161 ,11339,11336,11338 ,0,0,0}, {23163,23164,23165 ,11340,11341,11342 ,0,0,0}, + {23164,23162,23165 ,11341,11339,11342 ,0,0,0}, {23158,22757,22777 ,11332,11343,11335 ,0,0,0}, + {23159,22777,22796 ,11334,11335,11344 ,0,0,0}, {23163,23127,23126 ,11340,11345,11333 ,0,0,0}, + {22719,22757,23125 ,11346,11343,11331 ,0,0,0}, {22816,23159,22796 ,11328,11334,11344 ,0,0,0}, + {23157,23166,23159 ,11330,11347,11334 ,0,0,0}, {23159,22816,23157 ,11334,11328,11330 ,0,0,0}, + {23166,23160,23162 ,11347,11336,11339 ,0,0,0}, {23164,23163,23126 ,11341,11340,11333 ,0,0,0}, + {23162,23164,23159 ,11339,11341,11334 ,0,0,0}, {23125,22757,23158 ,11331,11343,11332 ,0,0,0}, + {23162,23159,23166 ,11339,11334,11347 ,0,0,0}, {23161,23165,23162 ,11338,11342,11339 ,0,0,0}, + {23126,23158,23164 ,11333,11332,11341 ,0,0,0}, {23159,23164,23158 ,11334,11341,11332 ,0,0,0}, + {23167,23168,23169 ,11348,11349,11350 ,0,0,0}, {23143,23170,23171 ,11351,11352,11353 ,0,0,0}, + {23143,23144,23170 ,11351,11354,11352 ,0,0,0}, {23161,23139,23172 ,11355,11356,11357 ,0,0,0}, + {23173,23131,23174 ,11358,11359,11360 ,0,0,0}, {23161,23141,23139 ,11355,11361,11356 ,0,0,0}, + {23175,23176,23177 ,11362,11363,11364 ,0,0,0}, {23145,23178,23179 ,11365,11366,11367 ,0,0,0}, + {23136,23176,23180 ,21,11363,11368 ,0,0,0}, {23175,23181,23180 ,11362,11369,11368 ,0,0,0}, + {23133,23132,23182 ,11370,11371,11372 ,0,0,0}, {23132,23173,23182 ,11371,11358,11372 ,0,0,0}, + {23183,23184,23167 ,11373,11374,11348 ,0,0,0}, {23173,23174,23181 ,11358,11360,11369 ,0,0,0}, + {23185,23121,23133 ,11375,11376,11370 ,0,0,0}, {23142,23171,23172 ,11377,11353,11357 ,0,0,0}, + {23145,23179,23144 ,11365,11367,11354 ,0,0,0}, {23172,23169,23165 ,11357,11350,11378 ,0,0,0}, + {23165,23169,23163 ,11378,11350,11379 ,0,0,0}, {23163,23168,23127 ,11379,11349,11380 ,0,0,0}, + {23161,23172,23165 ,11355,11357,11378 ,0,0,0}, {23139,23142,23172 ,11356,11377,11357 ,0,0,0}, + {23168,23163,23169 ,11349,11379,11350 ,0,0,0}, {23168,23184,23128 ,11349,11374,11381 ,0,0,0}, + {23169,23171,23167 ,11350,11353,11348 ,0,0,0}, {23127,23168,23128 ,11380,11349,11381 ,0,0,0}, + {23172,23171,23169 ,11357,11353,11350 ,0,0,0}, {23142,23143,23171 ,11377,11351,11353 ,0,0,0}, + {23184,23168,23167 ,11374,11349,11348 ,0,0,0}, {23184,23186,23129 ,11374,11382,11383 ,0,0,0}, + {23167,23170,23183 ,11348,11352,11373 ,0,0,0}, {23128,23184,23129 ,11381,11374,11383 ,0,0,0}, + {23171,23170,23167 ,11353,11352,11348 ,0,0,0}, {23179,23170,23144 ,11367,11352,11354 ,0,0,0}, + {23186,23184,23183 ,11382,11374,11373 ,0,0,0}, {23186,23174,23130 ,11382,11360,11384 ,0,0,0}, + {23179,23187,23183 ,11367,11385,11373 ,0,0,0}, {23129,23186,23130 ,11383,11382,11384 ,0,0,0}, + {23179,23183,23170 ,11367,11373,11352 ,0,0,0}, {23146,23178,23145 ,11386,11366,11365 ,0,0,0}, + {23174,23186,23187 ,11360,11382,11385 ,0,0,0}, {23183,23187,23186 ,11373,11385,11382 ,0,0,0}, + {23178,23181,23187 ,11366,11369,11385 ,0,0,0}, {23130,23174,23131 ,11384,11360,11359 ,0,0,0}, + {23179,23178,23187 ,11367,11366,11385 ,0,0,0}, {23136,23180,23146 ,21,11368,11386 ,0,0,0}, + {23182,23173,23175 ,11372,11358,11362 ,0,0,0}, {23187,23181,23174 ,11385,11369,11360 ,0,0,0}, + {23181,23175,23173 ,11369,11362,11358 ,0,0,0}, {23131,23173,23132 ,11359,11358,11371 ,0,0,0}, + {23178,23146,23180 ,11366,11386,11368 ,0,0,0}, {23181,23178,23180 ,11369,11366,11368 ,0,0,0}, + {23182,23177,23185 ,11372,11364,11375 ,0,0,0}, {23176,23175,23180 ,11363,11362,11368 ,0,0,0}, + {23185,23133,23182 ,11375,11370,11372 ,0,0,0}, {23177,23182,23175 ,11364,11372,11362 ,0,0,0}, + {23176,23135,23188 ,11387,11388,11389 ,0,0,0}, {23124,23189,23122 ,11390,11391,11269 ,0,0,0}, + {23188,23135,23190 ,11389,11388,11392 ,0,0,0}, {23135,23137,23190 ,11388,21,11392 ,0,0,0}, + {23188,23191,23189 ,11389,11393,11391 ,0,0,0}, {23176,23136,23135 ,11387,21,11388 ,0,0,0}, + {23189,23191,23122 ,11391,11393,11269 ,0,0,0}, {23185,23189,23124 ,11394,11391,11390 ,0,0,0}, + {23121,23185,23124 ,11395,11394,11390 ,0,0,0}, {23185,23177,23189 ,11394,11396,11391 ,0,0,0}, + {23177,23176,23188 ,11396,11387,11389 ,0,0,0}, {23177,23188,23189 ,11396,11389,11391 ,0,0,0}, + {23191,23188,23190 ,11393,11389,11392 ,0,0,0}, {23156,23155,23148 ,11397,11398,11399 ,0,0,0}, + {23190,23137,23150 ,11400,21,11401 ,0,0,0}, {23150,23149,23192 ,11401,11402,11403 ,0,0,0}, + {23150,23192,23190 ,11401,11403,11400 ,0,0,0}, {23147,23156,23148 ,11404,11397,11399 ,0,0,0}, + {23153,23154,23193 ,11405,11406,11407 ,0,0,0}, {23193,23194,23153 ,11407,11408,11405 ,0,0,0}, + {23191,23192,23195 ,11409,11403,11410 ,0,0,0}, {23195,23192,23194 ,11410,11403,11408 ,0,0,0}, + {23154,23123,23120 ,11406,11411,11412 ,0,0,0}, {23191,23195,23122 ,11409,11410,11413 ,0,0,0}, + {23120,23195,23193 ,11412,11410,11407 ,0,0,0}, {23190,23192,23191 ,11400,11403,11409 ,0,0,0}, + {23120,23119,23195 ,11412,11414,11410 ,0,0,0}, {23195,23119,23122 ,11410,11414,11413 ,0,0,0}, + {23192,23149,23194 ,11403,11402,11408 ,0,0,0}, {23148,23194,23149 ,11399,11408,11402 ,0,0,0}, + {23120,23193,23154 ,11412,11407,11406 ,0,0,0}, {23195,23194,23193 ,11410,11408,11407 ,0,0,0}, + {23155,23194,23148 ,11398,11408,11399 ,0,0,0}, {23155,23153,23194 ,11398,11405,11408 ,0,0,0}, + {23196,22891,23197 ,11415,11416,11417 ,0,0,0}, {22910,22439,23108 ,11418,11419,11420 ,0,0,0}, + {23138,23198,23105 ,11421,11422,11423 ,0,0,0}, {23199,23160,23200 ,11424,11425,11426 ,0,0,0}, + {23160,23199,23140 ,11425,11424,11427 ,0,0,0}, {23140,23141,23160 ,11427,11428,11425 ,0,0,0}, + {23166,23200,23160 ,11429,11426,11425 ,0,0,0}, {23196,22874,22891 ,11415,11430,11416 ,0,0,0}, + {23140,23199,23138 ,11427,11424,11421 ,0,0,0}, {23198,23200,23201 ,11422,11426,11431 ,0,0,0}, + {23157,22836,22856 ,11432,11433,11434 ,0,0,0}, {22874,23196,22856 ,11430,11415,11434 ,0,0,0}, + {23201,23107,23106 ,11431,11435,11436 ,0,0,0}, {23197,22910,23108 ,11417,11418,11420 ,0,0,0}, + {23199,23200,23198 ,11424,11426,11422 ,0,0,0}, {23201,23106,23198 ,11431,11436,11422 ,0,0,0}, + {23105,23198,23106 ,11423,11422,11436 ,0,0,0}, {23138,23199,23198 ,11421,11424,11422 ,0,0,0}, + {23196,23166,23157 ,11415,11429,11432 ,0,0,0}, {23201,23196,23197 ,11431,11415,11417 ,0,0,0}, + {23201,23200,23196 ,11431,11426,11415 ,0,0,0}, {23107,23201,23197 ,11435,11431,11417 ,0,0,0}, + {23166,23196,23200 ,11429,11415,11426 ,0,0,0}, {22856,23196,23157 ,11434,11415,11432 ,0,0,0}, + {22910,23197,22891 ,11418,11417,11416 ,0,0,0}, {23197,23108,23107 ,11417,11420,11435 ,0,0,0}, + {22533,22396,22395 ,11437,11438,11439 ,0,0,0}, {23202,23203,22422 ,11440,11441,11442 ,0,0,0}, + {22469,23204,23205 ,11443,11444,11445 ,0,0,0}, {22427,22426,23206 ,11446,11447,11448 ,0,0,0}, + {22466,22501,23207 ,11449,11450,11451 ,0,0,0}, {22430,22431,23208 ,11452,11453,11454 ,0,0,0}, + {22430,23209,22426 ,11452,11455,11447 ,0,0,0}, {23210,22521,23211 ,11456,11457,11458 ,0,0,0}, + {22521,23210,22431 ,11457,11456,11453 ,0,0,0}, {23212,23211,22520 ,11459,11458,11460 ,0,0,0}, + {22521,22520,23211 ,11457,11460,11458 ,0,0,0}, {22409,22410,23212 ,21,21,11459 ,0,0,0}, + {23212,22520,22409 ,11459,11460,21 ,0,0,0}, {23208,23209,22430 ,11454,11455,11452 ,0,0,0}, + {22431,23210,23208 ,11453,11456,11454 ,0,0,0}, {23206,23207,22427 ,11448,11451,11446 ,0,0,0}, + {22426,23209,23206 ,11447,11455,11448 ,0,0,0}, {23202,22466,23207 ,11440,11449,11451 ,0,0,0}, + {22501,22427,23207 ,11450,11446,11451 ,0,0,0}, {23203,22420,22422 ,11441,11461,11442 ,0,0,0}, + {23202,22422,22466 ,11440,11442,11449 ,0,0,0}, {22469,22420,23204 ,11443,11461,11444 ,0,0,0}, + {23203,23204,22420 ,11441,11444,11461 ,0,0,0}, {22533,23205,23213 ,11437,11445,11462 ,0,0,0}, + {22469,23205,22533 ,11443,11445,11437 ,0,0,0}, {22396,22533,23213 ,11438,11437,11462 ,0,0,0}, + {23204,22375,22378 ,730,730,730 ,0,0,0}, {22391,23214,22389 ,730,730,730 ,0,0,0}, + {22391,22394,23215 ,730,730,730 ,0,0,0}, {22387,22389,23216 ,730,730,730 ,0,0,0}, + {22394,22381,23215 ,730,730,730 ,0,0,0}, {23214,22391,23215 ,730,730,730 ,0,0,0}, + {22381,22394,22396 ,730,730,730 ,0,0,0}, {22387,23217,22384 ,730,730,730 ,0,0,0}, + {23213,22381,22396 ,730,730,730 ,0,0,0}, {22363,22375,23202 ,730,730,730 ,0,0,0}, + {22398,22386,23218 ,730,730,730 ,0,0,0}, {23219,22399,22398 ,730,730,730 ,0,0,0}, + {15837,22363,23207 ,730,730,730 ,0,0,0}, {22365,23206,23209 ,730,730,730 ,0,0,0}, + {23220,22402,22399 ,730,730,730 ,0,0,0}, {22402,23221,22403 ,730,730,730 ,0,0,0}, + {22405,22403,23222 ,730,730,730 ,0,0,0}, {23209,22366,22365 ,730,730,730 ,0,0,0}, + {22366,23208,23210 ,730,730,730 ,0,0,0}, {22373,23212,22410 ,730,730,730 ,0,0,0}, + {22410,22408,22373 ,730,730,730 ,0,0,0}, {22405,23223,22408 ,730,730,730 ,0,0,0}, + {23211,22372,23210 ,730,730,730 ,0,0,0}, {22386,22384,23218 ,730,730,730 ,0,0,0}, + {22378,22380,23205 ,730,730,730 ,0,0,0}, {23207,23206,15837 ,730,730,730 ,0,0,0}, + {23214,23216,22389 ,730,730,730 ,0,0,0}, {23216,23217,22387 ,730,730,730 ,0,0,0}, + {23217,23218,22384 ,730,730,730 ,0,0,0}, {23218,23219,22398 ,730,730,730 ,0,0,0}, + {23219,23220,22399 ,730,730,730 ,0,0,0}, {23220,23221,22402 ,730,730,730 ,0,0,0}, + {23221,23222,22403 ,730,730,730 ,0,0,0}, {23222,23223,22405 ,730,730,730 ,0,0,0}, + {23223,22373,22408 ,730,730,730 ,0,0,0}, {22373,22369,23212 ,730,730,730 ,0,0,0}, + {22369,22372,23211 ,730,730,730 ,0,0,0}, {22369,23211,23212 ,730,730,730 ,0,0,0}, + {22372,22366,23210 ,730,730,730 ,0,0,0}, {23208,22366,23209 ,730,730,730 ,0,0,0}, + {22365,15837,23206 ,730,730,730 ,0,0,0}, {22363,23202,23207 ,730,730,730 ,0,0,0}, + {22375,23203,23202 ,730,730,730 ,0,0,0}, {23204,22378,23205 ,730,730,730 ,0,0,0}, + {23203,22375,23204 ,730,730,730 ,0,0,0}, {23205,22380,23213 ,730,730,730 ,0,0,0}, + {22381,23213,22380 ,730,730,730 ,0,0,0}, {22379,23224,23225 ,730,730,11463 ,0,0,0}, + {23226,23225,23227 ,730,11463,730 ,0,0,0}, {23226,23227,23228 ,730,730,11463 ,0,0,0}, + {23229,23225,23226 ,730,11463,730 ,0,0,0}, {23229,22382,23225 ,730,730,11463 ,0,0,0}, + {23228,23227,23230 ,11463,730,11464 ,0,0,0}, {22379,23225,22382 ,730,11463,730 ,0,0,0}, + {23224,22377,23231 ,730,730,11464 ,0,0,0}, {23224,22379,22377 ,730,730,730 ,0,0,0}, + {23231,22377,23232 ,11464,730,730 ,0,0,0}, {23232,22377,22376 ,730,730,11464 ,0,0,0}, + {23232,22376,22374 ,730,11464,730 ,0,0,0}, {23233,22374,22362 ,11465,730,11464 ,0,0,0}, + {22374,23233,23232 ,730,11465,730 ,0,0,0}, {22370,23233,22367 ,730,11465,730 ,0,0,0}, + {22362,22367,23233 ,11464,730,11465 ,0,0,0}, {22371,22364,22368 ,11464,730,11466 ,0,0,0}, + {22367,22364,22371 ,730,730,11464 ,0,0,0}, {22371,22370,22367 ,11464,730,730 ,0,0,0}, + {22373,23223,23233 ,11467,11468,11469 ,0,0,0}, {23225,23224,23220 ,11470,11471,11472 ,0,0,0}, + {23231,23232,23222 ,11473,11474,11475 ,0,0,0}, {23230,23218,23217 ,11476,11477,11478 ,0,0,0}, + {23219,23218,23227 ,11479,11477,11480 ,0,0,0}, {23226,23216,23214 ,11481,11482,11483 ,0,0,0}, + {23216,23226,23228 ,11482,11481,11484 ,0,0,0}, {23215,23229,23214 ,11485,11486,11483 ,0,0,0}, + {23226,23214,23229 ,11481,11483,11486 ,0,0,0}, {23215,22381,22382 ,11485,11487,11487 ,0,0,0}, + {22382,23229,23215 ,11487,11486,11485 ,0,0,0}, {23230,23217,23228 ,11476,11478,11484 ,0,0,0}, + {23217,23216,23228 ,11478,11482,11484 ,0,0,0}, {23220,23219,23225 ,11472,11479,11470 ,0,0,0}, + {23219,23227,23225 ,11479,11480,11470 ,0,0,0}, {23227,23218,23230 ,11480,11477,11476 ,0,0,0}, + {23232,23233,23223 ,11474,11469,11468 ,0,0,0}, {23221,23220,23224 ,11488,11472,11471 ,0,0,0}, + {23223,23222,23232 ,11468,11475,11474 ,0,0,0}, {23221,23231,23222 ,11488,11473,11475 ,0,0,0}, + {23224,23231,23221 ,11471,11473,11488 ,0,0,0}, {23233,22370,22373 ,11469,11489,11467 ,0,0,0}, + {22435,22350,22349 ,11490,324,11491 ,0,0,0}, {23234,23235,22517 ,11492,11493,11494 ,0,0,0}, + {22518,23236,22437 ,11495,11496,11497 ,0,0,0}, {23237,22456,23238 ,11498,11499,11500 ,0,0,0}, + {22513,22458,23239 ,11501,11502,11503 ,0,0,0}, {23240,22455,22515 ,11504,11505,11506 ,0,0,0}, + {22455,23240,23238 ,11505,11504,11500 ,0,0,0}, {22447,23241,22515 ,11507,11508,11506 ,0,0,0}, + {23240,22515,23241 ,11504,11506,11508 ,0,0,0}, {22447,22361,22360 ,11507,1095,1631 ,0,0,0}, + {22360,23241,22447 ,1631,11508,11507 ,0,0,0}, {22456,23237,22458 ,11499,11498,11502 ,0,0,0}, + {22456,22455,23238 ,11499,11505,11500 ,0,0,0}, {23234,22513,23239 ,11492,11501,11503 ,0,0,0}, + {23239,22458,23237 ,11503,11502,11498 ,0,0,0}, {23235,22518,22517 ,11493,11495,11494 ,0,0,0}, + {23234,22517,22513 ,11492,11494,11501 ,0,0,0}, {23236,23242,22437 ,11496,11509,11497 ,0,0,0}, + {23235,23236,22518 ,11493,11496,11495 ,0,0,0}, {22350,22435,23242 ,324,11490,11509 ,0,0,0}, + {22437,23242,22435 ,11497,11509,11490 ,0,0,0}, {22357,23234,22358 ,730,730,730 ,0,0,0}, + {22354,23236,22355 ,730,730,730 ,0,0,0}, {22360,23239,23237 ,730,730,730 ,0,0,0}, + {23241,23237,23238 ,730,730,730 ,0,0,0}, {23240,23241,23238 ,730,730,730 ,0,0,0}, + {22358,23239,22360 ,730,730,730 ,0,0,0}, {22360,23237,23241 ,730,730,730 ,0,0,0}, + {22358,23234,23239 ,730,730,730 ,0,0,0}, {22357,23235,23234 ,730,730,730 ,0,0,0}, + {22357,22355,23236 ,730,730,730 ,0,0,0}, {23236,23235,22357 ,730,730,730 ,0,0,0}, + {23242,23236,22354 ,730,730,730 ,0,0,0}, {23242,22351,22350 ,730,730,730 ,0,0,0}, + {22351,23242,22354 ,730,730,730 ,0,0,0}, {22350,22351,22343 ,730,730,730 ,0,0,0}, + {22346,22340,22344 ,730,730,730 ,0,0,0}, {22343,22340,22346 ,730,730,730 ,0,0,0}, + {22346,22350,22343 ,730,730,730 ,0,0,0}, {22528,22328,22329 ,11510,11511,11512 ,0,0,0}, + {23243,23244,22474 ,11492,11493,11513 ,0,0,0}, {22475,23245,22527 ,11514,11496,11515 ,0,0,0}, + {23246,22472,22471 ,11498,11516,11517 ,0,0,0}, {22488,22472,23247 ,11518,11516,11519 ,0,0,0}, + {23248,22532,22424 ,11504,11520,11521 ,0,0,0}, {22471,22532,23249 ,11517,11520,11500 ,0,0,0}, + {22423,23250,22424 ,11522,11508,11521 ,0,0,0}, {23248,22424,23250 ,11504,11521,11508 ,0,0,0}, + {22423,22339,22338 ,11522,11487,11523 ,0,0,0}, {22338,23250,22423 ,11523,11508,11522 ,0,0,0}, + {23246,22471,23249 ,11498,11517,11500 ,0,0,0}, {23249,22532,23248 ,11500,11520,11504 ,0,0,0}, + {22488,23247,23243 ,11518,11519,11492 ,0,0,0}, {23247,22472,23246 ,11519,11516,11498 ,0,0,0}, + {23244,22475,22474 ,11493,11514,11513 ,0,0,0}, {23243,22474,22488 ,11492,11513,11518 ,0,0,0}, + {23245,23251,22527 ,11496,11509,11515 ,0,0,0}, {23244,23245,22475 ,11493,11496,11514 ,0,0,0}, + {22328,22528,23251 ,11511,11510,11509 ,0,0,0}, {22527,23251,22528 ,11515,11509,11510 ,0,0,0}, + {22333,23243,22335 ,730,730,730 ,0,0,0}, {22330,23245,22332 ,730,730,730 ,0,0,0}, + {22338,23247,23246 ,730,730,730 ,0,0,0}, {23250,23246,23249 ,730,730,730 ,0,0,0}, + {23248,23250,23249 ,730,730,730 ,0,0,0}, {22335,23247,22338 ,730,730,730 ,0,0,0}, + {22338,23246,23250 ,730,730,730 ,0,0,0}, {22335,23243,23247 ,730,730,730 ,0,0,0}, + {22333,23244,23243 ,730,730,730 ,0,0,0}, {22333,22332,23245 ,730,730,730 ,0,0,0}, + {23245,23244,22333 ,730,730,730 ,0,0,0}, {23251,23245,22330 ,730,730,730 ,0,0,0}, + {23251,22318,22328 ,730,730,730 ,0,0,0}, {22318,23251,22330 ,730,730,730 ,0,0,0}, + {22328,22318,22321 ,730,730,730 ,0,0,0}, {22324,22322,22325 ,730,730,730 ,0,0,0}, + {22321,22322,22324 ,730,730,730 ,0,0,0}, {22324,22328,22321 ,730,730,730 ,0,0,0} +// Landegestell.prt + , {23252,23253,23254 ,11524,11525,11526 ,0,0,0}, {23255,23256,23257 ,11527,11528,11529 ,0,0,0}, + {23258,23259,23260 ,11530,11531,11532 ,0,0,0}, {23261,23253,23262 ,11533,11525,11534 ,0,0,0}, + {23263,23260,23264 ,11535,11532,11536 ,0,0,0}, {23265,23266,23267 ,11537,11538,11539 ,0,0,0}, + {23268,23269,23270 ,11540,11541,11542 ,0,0,0}, {23271,23264,23259 ,11543,11536,11531 ,0,0,0}, + {23272,23273,23274 ,11544,11545,11546 ,0,0,0}, {23268,23275,23274 ,11540,11547,11546 ,0,0,0}, + {23276,23277,23278 ,11548,11549,11550 ,0,0,0}, {23278,23277,23273 ,11550,11549,11545 ,0,0,0}, + {23279,23278,23280 ,11551,11550,11552 ,0,0,0}, {23262,23253,23252 ,11534,11525,11524 ,0,0,0}, + {23280,23281,23279 ,11552,11553,11551 ,0,0,0}, {23282,23283,23284 ,11554,11555,11556 ,0,0,0}, + {23254,23285,23252 ,11526,11557,11524 ,0,0,0}, {23286,23287,23284 ,11558,11559,11556 ,0,0,0}, + {23288,23289,23286 ,11560,11561,11558 ,0,0,0}, {23289,23290,23286 ,11561,11562,11558 ,0,0,0}, + {23284,23287,23282 ,11556,11559,11554 ,0,0,0}, {23291,23292,23256 ,11563,11564,11528 ,0,0,0}, + {23293,23294,23295 ,11565,11566,11567 ,0,0,0}, {23291,23296,23292 ,11563,11568,11564 ,0,0,0}, + {23297,23298,23299 ,11569,11570,11571 ,0,0,0}, {23294,23300,23295 ,11566,11572,11567 ,0,0,0}, + {23301,23302,23303 ,11573,11574,11575 ,0,0,0}, {23297,23299,23304 ,11569,11571,11576 ,0,0,0}, + {23305,23306,23307 ,11577,11578,11579 ,0,0,0}, {23306,23305,23308 ,11578,11577,11580 ,0,0,0}, + {23309,23310,23311 ,11581,11582,11583 ,0,0,0}, {23312,23313,23310 ,11584,11585,11582 ,0,0,0}, + {23314,23315,23316 ,11586,11587,11588 ,0,0,0}, {23309,23311,23317 ,11581,11583,11589 ,0,0,0}, + {23318,23319,23320 ,11590,11591,11592 ,0,0,0}, {23314,23316,23321 ,11586,11588,11593 ,0,0,0}, + {23322,23323,23324 ,11594,11595,11596 ,0,0,0}, {23325,23319,23318 ,11597,11591,11590 ,0,0,0}, + {23326,23327,23328 ,11598,11599,11600 ,0,0,0}, {23328,23324,23326 ,11600,11596,11598 ,0,0,0}, + {23329,23330,23331 ,11601,11602,11603 ,0,0,0}, {23332,23327,23333 ,11604,11599,11605 ,0,0,0}, + {23334,23335,23336 ,11606,11607,11608 ,0,0,0}, {23337,23334,23338 ,11609,11606,11610 ,0,0,0}, + {23339,23340,23341 ,11611,11612,11613 ,0,0,0}, {23342,23339,23336 ,11614,11611,11608 ,0,0,0}, + {23343,23344,23345 ,11615,11616,11617 ,0,0,0}, {23346,23341,23347 ,11618,11613,11619 ,0,0,0}, + {23348,23349,23350 ,11620,11621,11622 ,0,0,0}, {23345,23351,23343 ,11617,11623,11615 ,0,0,0}, + {23352,23348,23353 ,11624,11620,11625 ,0,0,0}, {23343,23351,23354 ,11615,11623,11626 ,0,0,0}, + {23355,23352,23346 ,11627,11624,11618 ,0,0,0}, {23348,23352,23355 ,11620,11624,11627 ,0,0,0}, + {23356,23357,23358 ,11628,11629,11630 ,0,0,0}, {23359,23342,23360 ,11631,11614,11632 ,0,0,0}, + {23361,23362,23363 ,11633,11634,11635 ,0,0,0}, {23359,23360,23364 ,11631,11632,11636 ,0,0,0}, + {23365,23366,23367 ,11637,11638,11639 ,0,0,0}, {23363,23368,23369 ,11635,11640,11641 ,0,0,0}, + {23370,23371,23367 ,11642,11643,11639 ,0,0,0}, {23372,23373,23374 ,11644,11645,11646 ,0,0,0}, + {23375,23376,23377 ,11647,11648,11649 ,0,0,0}, {23377,23374,23375 ,11649,11646,11647 ,0,0,0}, + {23376,23375,23378 ,11648,11647,11650 ,0,0,0}, {23347,23341,23340 ,11619,11613,11612 ,0,0,0}, + {23348,23354,23353 ,11620,11626,11625 ,0,0,0}, {23342,23336,23335 ,11614,11608,11607 ,0,0,0}, + {23342,23340,23339 ,11614,11612,11611 ,0,0,0}, {23337,23338,23329 ,11609,11610,11601 ,0,0,0}, + {23334,23337,23335 ,11606,11609,11607 ,0,0,0}, {23331,23330,23332 ,11603,11602,11604 ,0,0,0}, + {23338,23330,23329 ,11610,11602,11601 ,0,0,0}, {23331,23332,23333 ,11603,11604,11605 ,0,0,0}, + {23379,23337,23329 ,11651,11609,11601 ,0,0,0}, {23328,23322,23324 ,11600,11594,11596 ,0,0,0}, + {23327,23326,23333 ,11599,11598,11605 ,0,0,0}, {23318,23320,23380 ,11590,11592,11652 ,0,0,0}, + {23381,23325,23382 ,11653,11597,11654 ,0,0,0}, {23324,23323,23382 ,11596,11595,11654 ,0,0,0}, + {23319,23325,23381 ,11591,11597,11653 ,0,0,0}, {23323,23381,23382 ,11595,11653,11654 ,0,0,0}, + {23380,23320,23321 ,11652,11592,11593 ,0,0,0}, {23383,23318,23380 ,11655,11590,11652 ,0,0,0}, + {23321,23316,23380 ,11593,11588,11652 ,0,0,0}, {23317,23315,23384 ,11589,11587,11656 ,0,0,0}, + {23314,23384,23315 ,11586,11656,11587 ,0,0,0}, {23385,23317,23384 ,11657,11589,11656 ,0,0,0}, + {23313,23311,23310 ,11585,11583,11582 ,0,0,0}, {23309,23317,23385 ,11581,11589,11657 ,0,0,0}, + {23312,23386,23313 ,11584,11658,11585 ,0,0,0}, {23307,23306,23386 ,11579,11578,11658 ,0,0,0}, + {23386,23312,23307 ,11658,11584,11579 ,0,0,0}, {23308,23387,23303 ,11580,11659,11575 ,0,0,0}, + {23388,23389,23390 ,11660,11661,11662 ,0,0,0}, {23303,23387,23391 ,11575,11659,11663 ,0,0,0}, + {23387,23308,23305 ,11659,11580,11577 ,0,0,0}, {23392,23304,23302 ,11664,11576,11574 ,0,0,0}, + {23301,23303,23391 ,11573,11575,11663 ,0,0,0}, {23304,23392,23297 ,11576,11664,11569 ,0,0,0}, + {23392,23302,23301 ,11664,11574,11573 ,0,0,0}, {23296,23393,23394 ,11568,11665,11666 ,0,0,0}, + {23298,23300,23395 ,11570,11572,11667 ,0,0,0}, {23299,23298,23395 ,11571,11570,11667 ,0,0,0}, + {23395,23300,23294 ,11667,11572,11566 ,0,0,0}, {23396,23397,23398 ,11668,11669,11670 ,0,0,0}, + {23393,23293,23295 ,11665,11565,11567 ,0,0,0}, {23285,23254,23283 ,11557,11526,11555 ,0,0,0}, + {23296,23293,23393 ,11568,11565,11665 ,0,0,0}, {23296,23394,23292 ,11568,11666,11564 ,0,0,0}, + {23256,23255,23291 ,11528,11527,11563 ,0,0,0}, {23290,23289,23257 ,11562,11561,11529 ,0,0,0}, + {23257,23289,23255 ,11529,11561,11527 ,0,0,0}, {23282,23285,23283 ,11554,11557,11555 ,0,0,0}, + {23290,23287,23286 ,11562,11559,11558 ,0,0,0}, {23267,23399,23400 ,11539,11671,11672 ,0,0,0}, + {23261,23262,23399 ,11533,11534,11671 ,0,0,0}, {23400,23265,23267 ,11672,11537,11539 ,0,0,0}, + {23261,23399,23267 ,11533,11671,11539 ,0,0,0}, {23400,23401,23265 ,11672,11673,11537 ,0,0,0}, + {23402,23403,23269 ,11674,11675,11541 ,0,0,0}, {23265,23401,23404 ,11537,11673,11676 ,0,0,0}, + {23404,23401,23405 ,11676,11673,11677 ,0,0,0}, {23406,23404,23407 ,11678,11676,11679 ,0,0,0}, + {23405,23407,23404 ,11677,11679,11676 ,0,0,0}, {23270,23408,23268 ,11542,11680,11540 ,0,0,0}, + {23409,23406,23407 ,11681,11678,11679 ,0,0,0}, {23410,23409,23407 ,11682,11681,11679 ,0,0,0}, + {23406,23409,23411 ,11678,11681,11683 ,0,0,0}, {23412,23413,23411 ,11684,11685,11683 ,0,0,0}, + {23403,23402,23414 ,11675,11674,11686 ,0,0,0}, {23411,23413,23406 ,11683,11685,11678 ,0,0,0}, + {23412,23402,23413 ,11684,11674,11685 ,0,0,0}, {23406,23415,23404 ,11678,11687,11676 ,0,0,0}, + {23416,23261,23267 ,11688,11533,11539 ,0,0,0}, {23404,23258,23265 ,11676,11530,11537 ,0,0,0}, + {23417,23253,23261 ,11689,11525,11533 ,0,0,0}, {23266,23265,23258 ,11538,11537,11530 ,0,0,0}, + {23418,23254,23253 ,11690,11526,11525 ,0,0,0}, {23416,23267,23266 ,11688,11539,11538 ,0,0,0}, + {23419,23283,23254 ,11691,11555,11526 ,0,0,0}, {23417,23261,23416 ,11689,11533,11688 ,0,0,0}, + {23420,23284,23283 ,11692,11556,11555 ,0,0,0}, {23418,23253,23417 ,11690,11525,11689 ,0,0,0}, + {23421,23286,23284 ,11693,11558,11556 ,0,0,0}, {23254,23418,23419 ,11526,11690,11691 ,0,0,0}, + {23422,23423,23424 ,11694,11695,11696 ,0,0,0}, {23283,23419,23420 ,11555,11691,11692 ,0,0,0}, + {23424,23255,23289 ,11696,11527,11561 ,0,0,0}, {23284,23420,23421 ,11556,11692,11693 ,0,0,0}, + {23425,23291,23255 ,11697,11563,11527 ,0,0,0}, {23286,23421,23288 ,11558,11693,11560 ,0,0,0}, + {23426,23296,23291 ,11698,11568,11563 ,0,0,0}, {23289,23288,23424 ,11561,11560,11696 ,0,0,0}, + {23427,23293,23296 ,11699,11565,11568 ,0,0,0}, {23255,23424,23425 ,11527,11696,11697 ,0,0,0}, + {23428,23294,23293 ,11700,11566,11565 ,0,0,0}, {23426,23291,23425 ,11698,11563,11697 ,0,0,0}, + {23429,23395,23294 ,11701,11667,11566 ,0,0,0}, {23427,23296,23426 ,11699,11568,11698 ,0,0,0}, + {23430,23299,23395 ,11702,11571,11667 ,0,0,0}, {23293,23427,23428 ,11565,11699,11700 ,0,0,0}, + {23397,23304,23299 ,11669,11576,11571 ,0,0,0}, {23294,23428,23429 ,11566,11700,11701 ,0,0,0}, + {23431,23302,23304 ,11703,11574,11576 ,0,0,0}, {23395,23429,23430 ,11667,11701,11702 ,0,0,0}, + {23432,23303,23302 ,11704,11575,11574 ,0,0,0}, {23299,23430,23397 ,11571,11702,11669 ,0,0,0}, + {23433,23308,23303 ,11705,11580,11575 ,0,0,0}, {23431,23304,23397 ,11703,11576,11669 ,0,0,0}, + {23434,23306,23308 ,11706,11578,11580 ,0,0,0}, {23432,23302,23431 ,11704,11574,11703 ,0,0,0}, + {23435,23386,23306 ,11707,11658,11578 ,0,0,0}, {23303,23432,23433 ,11575,11704,11705 ,0,0,0}, + {23313,23386,23388 ,11585,11658,11660 ,0,0,0}, {23308,23433,23434 ,11580,11705,11706 ,0,0,0}, + {23436,23311,23313 ,11708,11583,11585 ,0,0,0}, {23306,23434,23435 ,11578,11706,11707 ,0,0,0}, + {23437,23317,23311 ,11709,11589,11583 ,0,0,0}, {23386,23435,23388 ,11658,11707,11660 ,0,0,0}, + {23438,23315,23317 ,11710,11587,11589 ,0,0,0}, {23436,23313,23388 ,11708,11585,11660 ,0,0,0}, + {23439,23316,23315 ,11711,11588,11587 ,0,0,0}, {23437,23311,23436 ,11709,11583,11708 ,0,0,0}, + {23440,23380,23316 ,11712,11652,11588 ,0,0,0}, {23317,23437,23438 ,11589,11709,11710 ,0,0,0}, + {23441,23442,23443 ,11713,11714,11715 ,0,0,0}, {23315,23438,23439 ,11587,11710,11711 ,0,0,0}, + {23444,23325,23318 ,11716,11597,11590 ,0,0,0}, {23316,23439,23440 ,11588,11711,11712 ,0,0,0}, + {23445,23382,23325 ,11717,11654,11597 ,0,0,0}, {23380,23440,23383 ,11652,11712,11655 ,0,0,0}, + {23446,23324,23382 ,11718,11596,11654 ,0,0,0}, {23318,23383,23444 ,11590,11655,11716 ,0,0,0}, + {23447,23326,23324 ,11719,11598,11596 ,0,0,0}, {23445,23325,23444 ,11717,11597,11716 ,0,0,0}, + {23448,23333,23326 ,11720,11605,11598 ,0,0,0}, {23446,23382,23445 ,11718,11654,11717 ,0,0,0}, + {23449,23331,23333 ,11721,11603,11605 ,0,0,0}, {23447,23324,23446 ,11719,11596,11718 ,0,0,0}, + {23450,23329,23331 ,11722,11601,11603 ,0,0,0}, {23326,23447,23448 ,11598,11719,11720 ,0,0,0}, + {23337,23451,23335 ,11609,11723,11607 ,0,0,0}, {23333,23448,23449 ,11605,11720,11721 ,0,0,0}, + {23360,23452,23364 ,11632,11724,11636 ,0,0,0}, {23331,23449,23450 ,11603,11721,11722 ,0,0,0}, + {23360,23342,23335 ,11632,11614,11607 ,0,0,0}, {23329,23450,23379 ,11601,11722,11651 ,0,0,0}, + {23359,23340,23342 ,11631,11612,11614 ,0,0,0}, {23337,23379,23451 ,11609,11651,11723 ,0,0,0}, + {23347,23340,23453 ,11619,11612,11725 ,0,0,0}, {23451,23360,23335 ,11723,11632,11607 ,0,0,0}, + {23362,23349,23355 ,11634,11621,11627 ,0,0,0}, {23349,23362,23361 ,11621,11634,11633 ,0,0,0}, + {23347,23355,23346 ,11619,11627,11618 ,0,0,0}, {23340,23359,23453 ,11612,11631,11725 ,0,0,0}, + {23343,23354,23454 ,11615,11626,11726 ,0,0,0}, {23347,23362,23355 ,11619,11634,11627 ,0,0,0}, + {23348,23355,23349 ,11620,11627,11621 ,0,0,0}, {23455,23456,23343 ,11727,11728,11615 ,0,0,0}, + {23353,23354,23351 ,11625,11626,11623 ,0,0,0}, {23350,23454,23354 ,11622,11726,11626 ,0,0,0}, + {23344,23343,23456 ,11616,11615,11728 ,0,0,0}, {23413,23415,23406 ,11685,11687,11678 ,0,0,0}, + {23414,23402,23412 ,11686,11674,11684 ,0,0,0}, {23275,23457,23274 ,11547,11729,11546 ,0,0,0}, + {23415,23258,23404 ,11687,11530,11676 ,0,0,0}, {23413,23458,23415 ,11685,11730,11687 ,0,0,0}, + {23266,23260,23459 ,11538,11532,11731 ,0,0,0}, {23259,23258,23415 ,11531,11530,11687 ,0,0,0}, + {23416,23459,23460 ,11688,11731,11732 ,0,0,0}, {23260,23266,23258 ,11532,11538,11530 ,0,0,0}, + {23417,23460,23461 ,11689,11732,11733 ,0,0,0}, {23459,23416,23266 ,11731,11688,11538 ,0,0,0}, + {23418,23461,23462 ,11690,11733,11734 ,0,0,0}, {23460,23417,23416 ,11732,11689,11688 ,0,0,0}, + {23419,23462,23463 ,11691,11734,11735 ,0,0,0}, {23461,23418,23417 ,11733,11690,11689 ,0,0,0}, + {23420,23463,23464 ,11692,11735,11736 ,0,0,0}, {23462,23419,23418 ,11734,11691,11690 ,0,0,0}, + {23421,23464,23465 ,11693,11736,11737 ,0,0,0}, {23463,23420,23419 ,11735,11692,11691 ,0,0,0}, + {23288,23465,23422 ,11560,11737,11694 ,0,0,0}, {23421,23420,23464 ,11693,11692,11736 ,0,0,0}, + {23466,23467,23468 ,11738,11739,11740 ,0,0,0}, {23288,23421,23465 ,11560,11693,11737 ,0,0,0}, + {23425,23423,23466 ,11697,11695,11738 ,0,0,0}, {23424,23288,23422 ,11696,11560,11694 ,0,0,0}, + {23426,23466,23469 ,11698,11738,11741 ,0,0,0}, {23425,23424,23423 ,11697,11696,11695 ,0,0,0}, + {23427,23469,23470 ,11699,11741,11742 ,0,0,0}, {23466,23426,23425 ,11738,11698,11697 ,0,0,0}, + {23428,23470,23471 ,11700,11742,11743 ,0,0,0}, {23469,23427,23426 ,11741,11699,11698 ,0,0,0}, + {23429,23471,23472 ,11701,11743,11744 ,0,0,0}, {23470,23428,23427 ,11742,11700,11699 ,0,0,0}, + {23430,23472,23398 ,11702,11744,11670 ,0,0,0}, {23429,23428,23471 ,11701,11700,11743 ,0,0,0}, + {23473,23474,23475 ,11745,11746,11747 ,0,0,0}, {23430,23429,23472 ,11702,11701,11744 ,0,0,0}, + {23431,23396,23476 ,11703,11668,11748 ,0,0,0}, {23397,23430,23398 ,11669,11702,11670 ,0,0,0}, + {23432,23476,23477 ,11704,11748,11749 ,0,0,0}, {23396,23431,23397 ,11668,11703,11669 ,0,0,0}, + {23433,23477,23478 ,11705,11749,11750 ,0,0,0}, {23476,23432,23431 ,11748,11704,11703 ,0,0,0}, + {23434,23478,23479 ,11706,11750,11751 ,0,0,0}, {23477,23433,23432 ,11749,11705,11704 ,0,0,0}, + {23435,23479,23389 ,11707,11751,11661 ,0,0,0}, {23434,23433,23478 ,11706,11705,11750 ,0,0,0}, + {23480,23481,23482 ,11752,11753,11754 ,0,0,0}, {23435,23434,23479 ,11707,11706,11751 ,0,0,0}, + {23436,23390,23483 ,11708,11662,11755 ,0,0,0}, {23388,23435,23389 ,11660,11707,11661 ,0,0,0}, + {23437,23483,23484 ,11709,11755,11756 ,0,0,0}, {23436,23388,23390 ,11708,11660,11662 ,0,0,0}, + {23438,23484,23485 ,11710,11756,11757 ,0,0,0}, {23483,23437,23436 ,11755,11709,11708 ,0,0,0}, + {23439,23485,23486 ,11711,11757,11758 ,0,0,0}, {23484,23438,23437 ,11756,11710,11709 ,0,0,0}, + {23440,23486,23487 ,11712,11758,11759 ,0,0,0}, {23485,23439,23438 ,11757,11711,11710 ,0,0,0}, + {23383,23487,23488 ,11655,11759,11760 ,0,0,0}, {23440,23439,23486 ,11712,11711,11758 ,0,0,0}, + {23444,23488,23442 ,11716,11760,11714 ,0,0,0}, {23383,23440,23487 ,11655,11712,11759 ,0,0,0}, + {23445,23442,23489 ,11717,11714,11761 ,0,0,0}, {23444,23383,23488 ,11716,11655,11760 ,0,0,0}, + {23446,23489,23490 ,11718,11761,11762 ,0,0,0}, {23442,23445,23444 ,11714,11717,11716 ,0,0,0}, + {23447,23490,23491 ,11719,11762,11763 ,0,0,0}, {23489,23446,23445 ,11761,11718,11717 ,0,0,0}, + {23448,23491,23492 ,11720,11763,11764 ,0,0,0}, {23490,23447,23446 ,11762,11719,11718 ,0,0,0}, + {23449,23492,23493 ,11721,11764,11765 ,0,0,0}, {23491,23448,23447 ,11763,11720,11719 ,0,0,0}, + {23450,23493,23494 ,11722,11765,11766 ,0,0,0}, {23492,23449,23448 ,11764,11721,11720 ,0,0,0}, + {23379,23494,23495 ,11651,11766,11767 ,0,0,0}, {23493,23450,23449 ,11765,11722,11721 ,0,0,0}, + {23451,23495,23452 ,11723,11767,11724 ,0,0,0}, {23379,23450,23494 ,11651,11722,11766 ,0,0,0}, + {23496,23359,23364 ,11768,11631,11636 ,0,0,0}, {23451,23379,23495 ,11723,11651,11767 ,0,0,0}, + {23369,23365,23497 ,11641,11637,11769 ,0,0,0}, {23360,23451,23452 ,11632,11723,11724 ,0,0,0}, + {23496,23363,23453 ,11768,11635,11725 ,0,0,0}, {23356,23349,23361 ,11628,11621,11633 ,0,0,0}, + {23453,23362,23347 ,11725,11634,11619 ,0,0,0}, {23496,23453,23359 ,11768,11725,11631 ,0,0,0}, + {23369,23361,23363 ,11641,11633,11635 ,0,0,0}, {23453,23363,23362 ,11725,11635,11634 ,0,0,0}, + {23498,23454,23358 ,11770,11726,11630 ,0,0,0}, {23454,23455,23343 ,11726,11727,11615 ,0,0,0}, + {23348,23350,23354 ,11620,11622,11626 ,0,0,0}, {23350,23356,23358 ,11622,11628,11630 ,0,0,0}, + {23498,23455,23454 ,11770,11727,11726 ,0,0,0}, {23402,23458,23413 ,11674,11730,11685 ,0,0,0}, + {23270,23269,23403 ,11542,11541,11675 ,0,0,0}, {23273,23277,23499 ,11545,11549,11771 ,0,0,0}, + {23458,23259,23415 ,11730,11531,11687 ,0,0,0}, {23402,23500,23458 ,11674,11772,11730 ,0,0,0}, + {23501,23502,23503 ,11773,11774,11775 ,0,0,0}, {23271,23259,23458 ,11543,11531,11730 ,0,0,0}, + {23263,23501,23459 ,11535,11773,11731 ,0,0,0}, {23264,23260,23259 ,11536,11532,11531 ,0,0,0}, + {23501,23504,23460 ,11773,11776,11732 ,0,0,0}, {23263,23459,23260 ,11535,11731,11532 ,0,0,0}, + {23504,23505,23461 ,11776,11777,11733 ,0,0,0}, {23501,23460,23459 ,11773,11732,11731 ,0,0,0}, + {23505,23506,23462 ,11777,11778,11734 ,0,0,0}, {23504,23461,23460 ,11776,11733,11732 ,0,0,0}, + {23506,23507,23463 ,11778,11779,11735 ,0,0,0}, {23505,23462,23461 ,11777,11734,11733 ,0,0,0}, + {23507,23508,23464 ,11779,11780,11736 ,0,0,0}, {23506,23463,23462 ,11778,11735,11734 ,0,0,0}, + {23508,23509,23465 ,11780,11781,11737 ,0,0,0}, {23507,23464,23463 ,11779,11736,11735 ,0,0,0}, + {23509,23510,23422 ,11781,11782,11694 ,0,0,0}, {23508,23465,23464 ,11780,11737,11736 ,0,0,0}, + {23510,23467,23423 ,11782,11739,11695 ,0,0,0}, {23422,23465,23509 ,11694,11737,11781 ,0,0,0}, + {23511,23512,23513 ,11783,11784,11785 ,0,0,0}, {23423,23422,23510 ,11695,11694,11782 ,0,0,0}, + {23468,23511,23469 ,11740,11783,11741 ,0,0,0}, {23467,23466,23423 ,11739,11738,11695 ,0,0,0}, + {23511,23514,23470 ,11783,11786,11742 ,0,0,0}, {23468,23469,23466 ,11740,11741,11738 ,0,0,0}, + {23514,23515,23471 ,11786,11787,11743 ,0,0,0}, {23511,23470,23469 ,11783,11742,11741 ,0,0,0}, + {23515,23516,23472 ,11787,11788,11744 ,0,0,0}, {23514,23471,23470 ,11786,11743,11742 ,0,0,0}, + {23516,23517,23398 ,11788,11789,11670 ,0,0,0}, {23515,23472,23471 ,11787,11744,11743 ,0,0,0}, + {23396,23517,23518 ,11668,11789,11790 ,0,0,0}, {23398,23472,23516 ,11670,11744,11788 ,0,0,0}, + {23518,23473,23476 ,11790,11745,11748 ,0,0,0}, {23517,23396,23398 ,11789,11668,11670 ,0,0,0}, + {23473,23519,23477 ,11745,11791,11749 ,0,0,0}, {23518,23476,23396 ,11790,11748,11668 ,0,0,0}, + {23519,23520,23478 ,11791,11792,11750 ,0,0,0}, {23473,23477,23476 ,11745,11749,11748 ,0,0,0}, + {23520,23521,23479 ,11792,11793,11751 ,0,0,0}, {23519,23478,23477 ,11791,11750,11749 ,0,0,0}, + {23521,23522,23389 ,11793,11794,11661 ,0,0,0}, {23520,23479,23478 ,11792,11751,11750 ,0,0,0}, + {23522,23523,23390 ,11794,11795,11662 ,0,0,0}, {23389,23479,23521 ,11661,11751,11793 ,0,0,0}, + {23523,23480,23483 ,11795,11752,11755 ,0,0,0}, {23390,23389,23522 ,11662,11661,11794 ,0,0,0}, + {23480,23524,23484 ,11752,11796,11756 ,0,0,0}, {23523,23483,23390 ,11795,11755,11662 ,0,0,0}, + {23524,23525,23485 ,11796,11797,11757 ,0,0,0}, {23480,23484,23483 ,11752,11756,11755 ,0,0,0}, + {23525,23526,23486 ,11797,11798,11758 ,0,0,0}, {23524,23485,23484 ,11796,11757,11756 ,0,0,0}, + {23526,23527,23487 ,11798,11799,11759 ,0,0,0}, {23525,23486,23485 ,11797,11758,11757 ,0,0,0}, + {23527,23443,23488 ,11799,11715,11760 ,0,0,0}, {23487,23486,23526 ,11759,11758,11798 ,0,0,0}, + {23528,23529,23530 ,11800,11801,11802 ,0,0,0}, {23488,23487,23527 ,11760,11759,11799 ,0,0,0}, + {23441,23528,23489 ,11713,11800,11761 ,0,0,0}, {23443,23442,23488 ,11715,11714,11760 ,0,0,0}, + {23528,23531,23490 ,11800,11803,11762 ,0,0,0}, {23441,23489,23442 ,11713,11761,11714 ,0,0,0}, + {23531,23532,23491 ,11803,11804,11763 ,0,0,0}, {23528,23490,23489 ,11800,11762,11761 ,0,0,0}, + {23532,23533,23492 ,11804,11805,11764 ,0,0,0}, {23531,23491,23490 ,11803,11763,11762 ,0,0,0}, + {23533,23534,23493 ,11805,11806,11765 ,0,0,0}, {23532,23492,23491 ,11804,11764,11763 ,0,0,0}, + {23534,23535,23494 ,11806,11807,11766 ,0,0,0}, {23533,23493,23492 ,11805,11765,11764 ,0,0,0}, + {23535,23536,23495 ,11807,11808,11767 ,0,0,0}, {23534,23494,23493 ,11806,11766,11765 ,0,0,0}, + {23536,23537,23452 ,11808,11809,11724 ,0,0,0}, {23535,23495,23494 ,11807,11767,11766 ,0,0,0}, + {23537,23538,23364 ,11809,11810,11636 ,0,0,0}, {23536,23452,23495 ,11808,11724,11767 ,0,0,0}, + {23538,23368,23496 ,11810,11640,11768 ,0,0,0}, {23364,23452,23537 ,11636,11724,11809 ,0,0,0}, + {23539,23361,23369 ,11811,11633,11641 ,0,0,0}, {23364,23538,23496 ,11636,11810,11768 ,0,0,0}, + {23368,23365,23369 ,11640,11637,11641 ,0,0,0}, {23496,23368,23363 ,11768,11640,11635 ,0,0,0}, + {23540,23358,23357 ,11812,11630,11629 ,0,0,0}, {23350,23358,23454 ,11622,11630,11726 ,0,0,0}, + {23349,23356,23350 ,11621,11628,11622 ,0,0,0}, {23539,23357,23356 ,11811,11629,11628 ,0,0,0}, + {23498,23358,23540 ,11770,11630,11812 ,0,0,0}, {23500,23402,23269 ,11772,11674,11541 ,0,0,0}, + {23275,23268,23408 ,11547,11540,11680 ,0,0,0}, {23271,23541,23542 ,11543,11813,11814 ,0,0,0}, + {23500,23271,23458 ,11772,11543,11730 ,0,0,0}, {23543,23500,23269 ,11815,11772,11541 ,0,0,0}, + {23264,23542,23544 ,11536,11814,11816 ,0,0,0}, {23500,23541,23271 ,11772,11813,11543 ,0,0,0}, + {23263,23544,23502 ,11535,11816,11774 ,0,0,0}, {23542,23264,23271 ,11814,11536,11543 ,0,0,0}, + {23545,23504,23503 ,11817,11776,11775 ,0,0,0}, {23544,23263,23264 ,11816,11535,11536 ,0,0,0}, + {23546,23505,23545 ,11818,11777,11817 ,0,0,0}, {23502,23501,23263 ,11774,11773,11535 ,0,0,0}, + {23547,23548,23549 ,11819,11820,11821 ,0,0,0}, {23503,23504,23501 ,11775,11776,11773 ,0,0,0}, + {23546,23547,23506 ,11818,11819,11778 ,0,0,0}, {23545,23505,23504 ,11817,11777,11776 ,0,0,0}, + {23547,23550,23507 ,11819,11822,11779 ,0,0,0}, {23546,23506,23505 ,11818,11778,11777 ,0,0,0}, + {23550,23551,23508 ,11822,11823,11780 ,0,0,0}, {23547,23507,23506 ,11819,11779,11778 ,0,0,0}, + {23551,23552,23509 ,11823,11824,11781 ,0,0,0}, {23550,23508,23507 ,11822,11780,11779 ,0,0,0}, + {23552,23553,23510 ,11824,11825,11782 ,0,0,0}, {23551,23509,23508 ,11823,11781,11780 ,0,0,0}, + {23467,23553,23554 ,11739,11825,11826 ,0,0,0}, {23552,23510,23509 ,11824,11782,11781 ,0,0,0}, + {23468,23554,23512 ,11740,11826,11784 ,0,0,0}, {23553,23467,23510 ,11825,11739,11782 ,0,0,0}, + {23555,23556,23557 ,11827,11828,11829 ,0,0,0}, {23554,23468,23467 ,11826,11740,11739 ,0,0,0}, + {23513,23555,23514 ,11785,11827,11786 ,0,0,0}, {23512,23511,23468 ,11784,11783,11740 ,0,0,0}, + {23555,23558,23515 ,11827,11830,11787 ,0,0,0}, {23513,23514,23511 ,11785,11786,11783 ,0,0,0}, + {23558,23559,23516 ,11830,11831,11788 ,0,0,0}, {23555,23515,23514 ,11827,11787,11786 ,0,0,0}, + {23517,23559,23560 ,11789,11831,11832 ,0,0,0}, {23558,23516,23515 ,11830,11788,11787 ,0,0,0}, + {23518,23560,23474 ,11790,11832,11746 ,0,0,0}, {23517,23516,23559 ,11789,11788,11831 ,0,0,0}, + {23561,23562,23563 ,11833,11834,11835 ,0,0,0}, {23560,23518,23517 ,11832,11790,11789 ,0,0,0}, + {23475,23561,23519 ,11747,11833,11791 ,0,0,0}, {23474,23473,23518 ,11746,11745,11790 ,0,0,0}, + {23561,23564,23520 ,11833,11836,11792 ,0,0,0}, {23475,23519,23473 ,11747,11791,11745 ,0,0,0}, + {23564,23565,23521 ,11836,11837,11793 ,0,0,0}, {23561,23520,23519 ,11833,11792,11791 ,0,0,0}, + {23565,23566,23522 ,11837,11838,11794 ,0,0,0}, {23564,23521,23520 ,11836,11793,11792 ,0,0,0}, + {23523,23566,23481 ,11795,11838,11753 ,0,0,0}, {23522,23521,23565 ,11794,11793,11837 ,0,0,0}, + {23567,23568,23569 ,11839,11840,11841 ,0,0,0}, {23566,23523,23522 ,11838,11795,11794 ,0,0,0}, + {23482,23567,23524 ,11754,11839,11796 ,0,0,0}, {23481,23480,23523 ,11753,11752,11795 ,0,0,0}, + {23567,23570,23525 ,11839,11842,11797 ,0,0,0}, {23482,23524,23480 ,11754,11796,11752 ,0,0,0}, + {23570,23571,23526 ,11842,11843,11798 ,0,0,0}, {23567,23525,23524 ,11839,11797,11796 ,0,0,0}, + {23571,23572,23527 ,11843,11844,11799 ,0,0,0}, {23570,23526,23525 ,11842,11798,11797 ,0,0,0}, + {23443,23572,23573 ,11715,11844,11845 ,0,0,0}, {23571,23527,23526 ,11843,11799,11798 ,0,0,0}, + {23441,23573,23529 ,11713,11845,11801 ,0,0,0}, {23572,23443,23527 ,11844,11715,11799 ,0,0,0}, + {23574,23531,23530 ,11846,11803,11802 ,0,0,0}, {23573,23441,23443 ,11845,11713,11715 ,0,0,0}, + {23575,23576,23577 ,11847,11848,11849 ,0,0,0}, {23529,23528,23441 ,11801,11800,11713 ,0,0,0}, + {23574,23575,23532 ,11846,11847,11804 ,0,0,0}, {23530,23531,23528 ,11802,11803,11800 ,0,0,0}, + {23575,23578,23533 ,11847,11850,11805 ,0,0,0}, {23574,23532,23531 ,11846,11804,11803 ,0,0,0}, + {23578,23579,23534 ,11850,11851,11806 ,0,0,0}, {23575,23533,23532 ,11847,11805,11804 ,0,0,0}, + {23579,23580,23535 ,11851,11852,11807 ,0,0,0}, {23578,23534,23533 ,11850,11806,11805 ,0,0,0}, + {23580,23581,23536 ,11852,11853,11808 ,0,0,0}, {23579,23535,23534 ,11851,11807,11806 ,0,0,0}, + {23581,23582,23537 ,11853,11854,11809 ,0,0,0}, {23580,23536,23535 ,11852,11808,11807 ,0,0,0}, + {23582,23366,23538 ,11854,11638,11810 ,0,0,0}, {23581,23537,23536 ,11853,11809,11808 ,0,0,0}, + {23368,23366,23365 ,11640,11638,11637 ,0,0,0}, {23537,23582,23538 ,11809,11854,11810 ,0,0,0}, + {23583,23357,23539 ,11855,11629,11811 ,0,0,0}, {23368,23538,23366 ,11640,11810,11638 ,0,0,0}, + {23584,23357,23583 ,11856,11629,11855 ,0,0,0}, {23585,23540,23357 ,11857,11812,11629 ,0,0,0}, + {23361,23539,23356 ,11633,11811,11628 ,0,0,0}, {23497,23583,23539 ,11769,11855,11811 ,0,0,0}, + {23584,23585,23357 ,11856,11857,11629 ,0,0,0}, {23543,23269,23268 ,11815,11541,11540 ,0,0,0}, + {23272,23274,23457 ,11544,11546,11729 ,0,0,0}, {23541,23586,23587 ,11813,11858,11859 ,0,0,0}, + {23543,23541,23500 ,11815,11813,11772 ,0,0,0}, {23268,23588,23543 ,11540,11860,11815 ,0,0,0}, + {23542,23587,23589 ,11814,11859,11861 ,0,0,0}, {23543,23586,23541 ,11815,11858,11813 ,0,0,0}, + {23544,23589,23590 ,11816,11861,11862 ,0,0,0}, {23541,23587,23542 ,11813,11859,11814 ,0,0,0}, + {23502,23590,23591 ,11774,11862,11863 ,0,0,0}, {23542,23589,23544 ,11814,11861,11816 ,0,0,0}, + {23503,23591,23592 ,11775,11863,11864 ,0,0,0}, {23544,23590,23502 ,11816,11862,11774 ,0,0,0}, + {23545,23592,23593 ,11817,11864,11865 ,0,0,0}, {23502,23591,23503 ,11774,11863,11775 ,0,0,0}, + {23546,23593,23548 ,11818,11865,11820 ,0,0,0}, {23592,23545,23503 ,11864,11817,11775 ,0,0,0}, + {23594,23550,23549 ,11866,11822,11821 ,0,0,0}, {23593,23546,23545 ,11865,11818,11817 ,0,0,0}, + {23595,23596,23594 ,11867,11868,11866 ,0,0,0}, {23548,23547,23546 ,11820,11819,11818 ,0,0,0}, + {23594,23596,23551 ,11866,11868,11823 ,0,0,0}, {23549,23550,23547 ,11821,11822,11819 ,0,0,0}, + {23596,23597,23552 ,11868,11869,11824 ,0,0,0}, {23594,23551,23550 ,11866,11823,11822 ,0,0,0}, + {23553,23597,23598 ,11825,11869,11870 ,0,0,0}, {23596,23552,23551 ,11868,11824,11823 ,0,0,0}, + {23554,23598,23599 ,11826,11870,11871 ,0,0,0}, {23552,23597,23553 ,11824,11869,11825 ,0,0,0}, + {23512,23599,23600 ,11784,11871,11872 ,0,0,0}, {23553,23598,23554 ,11825,11870,11826 ,0,0,0}, + {23513,23600,23556 ,11785,11872,11828 ,0,0,0}, {23599,23512,23554 ,11871,11784,11826 ,0,0,0}, + {23601,23602,23557 ,11873,11874,11829 ,0,0,0}, {23600,23513,23512 ,11872,11785,11784 ,0,0,0}, + {23557,23602,23558 ,11829,11874,11830 ,0,0,0}, {23556,23555,23513 ,11828,11827,11785 ,0,0,0}, + {23602,23603,23559 ,11874,11875,11831 ,0,0,0}, {23557,23558,23555 ,11829,11830,11827 ,0,0,0}, + {23560,23603,23604 ,11832,11875,11876 ,0,0,0}, {23602,23559,23558 ,11874,11831,11830 ,0,0,0}, + {23474,23604,23605 ,11746,11876,11877 ,0,0,0}, {23559,23603,23560 ,11831,11875,11832 ,0,0,0}, + {23475,23605,23562 ,11747,11877,11834 ,0,0,0}, {23604,23474,23560 ,11876,11746,11832 ,0,0,0}, + {23606,23607,23563 ,11878,11879,11835 ,0,0,0}, {23605,23475,23474 ,11877,11747,11746 ,0,0,0}, + {23563,23607,23564 ,11835,11879,11836 ,0,0,0}, {23562,23561,23475 ,11834,11833,11747 ,0,0,0}, + {23607,23608,23565 ,11879,11880,11837 ,0,0,0}, {23563,23564,23561 ,11835,11836,11833 ,0,0,0}, + {23566,23608,23609 ,11838,11880,11881 ,0,0,0}, {23607,23565,23564 ,11879,11837,11836 ,0,0,0}, + {23481,23609,23610 ,11753,11881,11882 ,0,0,0}, {23565,23608,23566 ,11837,11880,11838 ,0,0,0}, + {23482,23610,23568 ,11754,11882,11840 ,0,0,0}, {23609,23481,23566 ,11881,11753,11838 ,0,0,0}, + {23611,23612,23569 ,11883,11884,11841 ,0,0,0}, {23610,23482,23481 ,11882,11754,11753 ,0,0,0}, + {23569,23612,23570 ,11841,11884,11842 ,0,0,0}, {23568,23567,23482 ,11840,11839,11754 ,0,0,0}, + {23612,23613,23571 ,11884,11885,11843 ,0,0,0}, {23569,23570,23567 ,11841,11842,11839 ,0,0,0}, + {23572,23613,23614 ,11844,11885,11886 ,0,0,0}, {23612,23571,23570 ,11884,11843,11842 ,0,0,0}, + {23573,23614,23615 ,11845,11886,11887 ,0,0,0}, {23571,23613,23572 ,11843,11885,11844 ,0,0,0}, + {23529,23615,23616 ,11801,11887,11888 ,0,0,0}, {23572,23614,23573 ,11844,11886,11845 ,0,0,0}, + {23530,23616,23617 ,11802,11888,11889 ,0,0,0}, {23573,23615,23529 ,11845,11887,11801 ,0,0,0}, + {23574,23617,23576 ,11846,11889,11848 ,0,0,0}, {23616,23530,23529 ,11888,11802,11801 ,0,0,0}, + {23618,23578,23577 ,11890,11850,11849 ,0,0,0}, {23617,23574,23530 ,11889,11846,11802 ,0,0,0}, + {23619,23620,23618 ,11891,11892,11890 ,0,0,0}, {23576,23575,23574 ,11848,11847,11846 ,0,0,0}, + {23618,23620,23579 ,11890,11892,11851 ,0,0,0}, {23577,23578,23575 ,11849,11850,11847 ,0,0,0}, + {23620,23621,23580 ,11892,11893,11852 ,0,0,0}, {23618,23579,23578 ,11890,11851,11850 ,0,0,0}, + {23621,23622,23581 ,11893,11894,11853 ,0,0,0}, {23620,23580,23579 ,11892,11852,11851 ,0,0,0}, + {23622,23623,23582 ,11894,11895,11854 ,0,0,0}, {23621,23581,23580 ,11893,11853,11852 ,0,0,0}, + {23366,23623,23367 ,11638,11895,11639 ,0,0,0}, {23622,23582,23581 ,11894,11854,11853 ,0,0,0}, + {23367,23624,23365 ,11639,11896,11637 ,0,0,0}, {23366,23582,23623 ,11638,11854,11895 ,0,0,0}, + {23625,23583,23373 ,11897,11855,11645 ,0,0,0}, {23625,23626,23583 ,11897,11898,11855 ,0,0,0}, + {23369,23497,23539 ,11641,11769,11811 ,0,0,0}, {23624,23373,23497 ,11896,11645,11769 ,0,0,0}, + {23584,23583,23626 ,11856,11855,11898 ,0,0,0}, {23274,23588,23268 ,11546,11860,11540 ,0,0,0}, + {23627,23273,23272 ,11899,11545,11544 ,0,0,0}, {23628,23586,23588 ,11900,11858,11860 ,0,0,0}, + {23588,23586,23543 ,11860,11858,11815 ,0,0,0}, {23588,23499,23628 ,11860,11771,11900 ,0,0,0}, + {23629,23587,23586 ,11901,11859,11858 ,0,0,0}, {23586,23628,23629 ,11858,11900,11901 ,0,0,0}, + {23630,23589,23587 ,11902,11861,11859 ,0,0,0}, {23587,23629,23630 ,11859,11901,11902 ,0,0,0}, + {23631,23590,23589 ,11903,11862,11861 ,0,0,0}, {23589,23630,23631 ,11861,11902,11903 ,0,0,0}, + {23632,23591,23590 ,11904,11863,11862 ,0,0,0}, {23590,23631,23632 ,11862,11903,11904 ,0,0,0}, + {23633,23592,23591 ,11905,11864,11863 ,0,0,0}, {23591,23632,23633 ,11863,11904,11905 ,0,0,0}, + {23634,23593,23592 ,11906,11865,11864 ,0,0,0}, {23592,23633,23634 ,11864,11905,11906 ,0,0,0}, + {23635,23548,23593 ,11907,11820,11865 ,0,0,0}, {23593,23634,23635 ,11865,11906,11907 ,0,0,0}, + {23636,23549,23548 ,11908,11821,11820 ,0,0,0}, {23548,23635,23636 ,11820,11907,11908 ,0,0,0}, + {23637,23594,23549 ,11909,11866,11821 ,0,0,0}, {23636,23637,23549 ,11908,11909,11821 ,0,0,0}, + {23638,23639,23640 ,11910,11911,11912 ,0,0,0}, {23637,23595,23594 ,11909,11867,11866 ,0,0,0}, + {23641,23597,23596 ,11913,11869,11868 ,0,0,0}, {23595,23641,23596 ,11867,11913,11868 ,0,0,0}, + {23642,23598,23597 ,11914,11870,11869 ,0,0,0}, {23597,23641,23642 ,11869,11913,11914 ,0,0,0}, + {23643,23599,23598 ,11915,11871,11870 ,0,0,0}, {23598,23642,23643 ,11870,11914,11915 ,0,0,0}, + {23644,23600,23599 ,11916,11872,11871 ,0,0,0}, {23599,23643,23644 ,11871,11915,11916 ,0,0,0}, + {23645,23556,23600 ,11917,11828,11872 ,0,0,0}, {23600,23644,23645 ,11872,11916,11917 ,0,0,0}, + {23646,23557,23556 ,11918,11829,11828 ,0,0,0}, {23645,23646,23556 ,11917,11918,11828 ,0,0,0}, + {23647,23601,23648 ,11919,11873,11920 ,0,0,0}, {23646,23601,23557 ,11918,11873,11829 ,0,0,0}, + {23647,23603,23602 ,11919,11875,11874 ,0,0,0}, {23601,23647,23602 ,11873,11919,11874 ,0,0,0}, + {23649,23604,23603 ,11921,11876,11875 ,0,0,0}, {23603,23647,23649 ,11875,11919,11921 ,0,0,0}, + {23650,23605,23604 ,11922,11877,11876 ,0,0,0}, {23604,23649,23650 ,11876,11921,11922 ,0,0,0}, + {23651,23562,23605 ,11923,11834,11877 ,0,0,0}, {23605,23650,23651 ,11877,11922,11923 ,0,0,0}, + {23652,23563,23562 ,11924,11835,11834 ,0,0,0}, {23651,23652,23562 ,11923,11924,11834 ,0,0,0}, + {23653,23654,23655 ,11925,11926,11927 ,0,0,0}, {23652,23606,23563 ,11924,11878,11835 ,0,0,0}, + {23656,23608,23607 ,11928,11880,11879 ,0,0,0}, {23606,23656,23607 ,11878,11928,11879 ,0,0,0}, + {23657,23609,23608 ,11929,11881,11880 ,0,0,0}, {23608,23656,23657 ,11880,11928,11929 ,0,0,0}, + {23658,23610,23609 ,11930,11882,11881 ,0,0,0}, {23609,23657,23658 ,11881,11929,11930 ,0,0,0}, + {23659,23568,23610 ,11931,11840,11882 ,0,0,0}, {23610,23658,23659 ,11882,11930,11931 ,0,0,0}, + {23660,23569,23568 ,11932,11841,11840 ,0,0,0}, {23659,23660,23568 ,11931,11932,11840 ,0,0,0}, + {23612,23661,23613 ,11884,11933,11885 ,0,0,0}, {23660,23611,23569 ,11932,11883,11841 ,0,0,0}, + {23662,23663,23661 ,11934,11935,11933 ,0,0,0}, {23611,23661,23612 ,11883,11933,11884 ,0,0,0}, + {23663,23614,23613 ,11935,11886,11885 ,0,0,0}, {23613,23661,23663 ,11885,11933,11935 ,0,0,0}, + {23664,23615,23614 ,11936,11887,11886 ,0,0,0}, {23614,23663,23664 ,11886,11935,11936 ,0,0,0}, + {23665,23616,23615 ,11937,11888,11887 ,0,0,0}, {23615,23664,23665 ,11887,11936,11937 ,0,0,0}, + {23666,23617,23616 ,11938,11889,11888 ,0,0,0}, {23616,23665,23666 ,11888,11937,11938 ,0,0,0}, + {23667,23576,23617 ,11939,11848,11889 ,0,0,0}, {23617,23666,23667 ,11889,11938,11939 ,0,0,0}, + {23668,23577,23576 ,11940,11849,11848 ,0,0,0}, {23576,23667,23668 ,11848,11939,11940 ,0,0,0}, + {23669,23618,23577 ,11941,11890,11849 ,0,0,0}, {23668,23669,23577 ,11940,11941,11849 ,0,0,0}, + {23620,23670,23621 ,11892,11942,11893 ,0,0,0}, {23669,23619,23618 ,11941,11891,11890 ,0,0,0}, + {23621,23671,23622 ,11893,11943,11894 ,0,0,0}, {23619,23670,23620 ,11891,11942,11892 ,0,0,0}, + {23622,23672,23623 ,11894,11944,11895 ,0,0,0}, {23670,23671,23621 ,11942,11943,11893 ,0,0,0}, + {23623,23370,23367 ,11895,11642,11639 ,0,0,0}, {23671,23672,23622 ,11943,11944,11894 ,0,0,0}, + {23375,23374,23371 ,11647,11646,11643 ,0,0,0}, {23672,23370,23623 ,11944,11642,11895 ,0,0,0}, + {23371,23624,23367 ,11643,11896,11639 ,0,0,0}, {23497,23373,23583 ,11769,11645,11855 ,0,0,0}, + {23365,23624,23497 ,11637,11896,11769 ,0,0,0}, {23624,23371,23374 ,11896,11643,11646 ,0,0,0}, + {23625,23373,23372 ,11897,11645,11644 ,0,0,0}, {23273,23499,23274 ,11545,11771,11546 ,0,0,0}, + {23627,23280,23278 ,11899,11552,11550 ,0,0,0}, {23628,23499,23673 ,11900,11771,11945 ,0,0,0}, + {23274,23499,23588 ,11546,11771,11860 ,0,0,0}, {23499,23277,23673 ,11771,11549,11945 ,0,0,0}, + {23629,23628,23674 ,11901,11900,11946 ,0,0,0}, {23628,23673,23674 ,11900,11945,11946 ,0,0,0}, + {23630,23629,23675 ,11902,11901,11947 ,0,0,0}, {23629,23674,23675 ,11901,11946,11947 ,0,0,0}, + {23631,23630,23676 ,11903,11902,11948 ,0,0,0}, {23630,23675,23676 ,11902,11947,11948 ,0,0,0}, + {23632,23631,23677 ,11904,11903,11949 ,0,0,0}, {23631,23676,23677 ,11903,11948,11949 ,0,0,0}, + {23633,23632,23678 ,11905,11904,11950 ,0,0,0}, {23632,23677,23678 ,11904,11949,11950 ,0,0,0}, + {23634,23633,23679 ,11906,11905,11951 ,0,0,0}, {23633,23678,23679 ,11905,11950,11951 ,0,0,0}, + {23635,23634,23680 ,11907,11906,11952 ,0,0,0}, {23634,23679,23680 ,11906,11951,11952 ,0,0,0}, + {23636,23635,23681 ,11908,11907,11953 ,0,0,0}, {23635,23680,23681 ,11907,11952,11953 ,0,0,0}, + {23637,23636,23682 ,11909,11908,11954 ,0,0,0}, {23636,23681,23682 ,11908,11953,11954 ,0,0,0}, + {23595,23637,23683 ,11867,11909,11955 ,0,0,0}, {23637,23682,23683 ,11909,11954,11955 ,0,0,0}, + {23641,23595,23638 ,11913,11867,11910 ,0,0,0}, {23683,23638,23595 ,11955,11910,11867 ,0,0,0}, + {23642,23641,23640 ,11914,11913,11912 ,0,0,0}, {23641,23638,23640 ,11913,11910,11912 ,0,0,0}, + {23643,23642,23684 ,11915,11914,11956 ,0,0,0}, {23642,23640,23684 ,11914,11912,11956 ,0,0,0}, + {23644,23643,23685 ,11916,11915,11957 ,0,0,0}, {23643,23684,23685 ,11915,11956,11957 ,0,0,0}, + {23645,23644,23686 ,11917,11916,11958 ,0,0,0}, {23644,23685,23686 ,11916,11957,11958 ,0,0,0}, + {23646,23645,23687 ,11918,11917,11959 ,0,0,0}, {23645,23686,23687 ,11917,11958,11959 ,0,0,0}, + {23601,23646,23688 ,11873,11918,11960 ,0,0,0}, {23646,23687,23688 ,11918,11959,11960 ,0,0,0}, + {23688,23689,23648 ,11960,11961,11920 ,0,0,0}, {23688,23648,23601 ,11960,11920,11873 ,0,0,0}, + {23649,23647,23690 ,11921,11919,11962 ,0,0,0}, {23647,23648,23690 ,11919,11920,11962 ,0,0,0}, + {23650,23649,23691 ,11922,11921,11963 ,0,0,0}, {23649,23690,23691 ,11921,11962,11963 ,0,0,0}, + {23651,23650,23692 ,11923,11922,11964 ,0,0,0}, {23650,23691,23692 ,11922,11963,11964 ,0,0,0}, + {23652,23651,23693 ,11924,11923,11965 ,0,0,0}, {23651,23692,23693 ,11923,11964,11965 ,0,0,0}, + {23606,23652,23694 ,11878,11924,11966 ,0,0,0}, {23652,23693,23694 ,11924,11965,11966 ,0,0,0}, + {23656,23606,23653 ,11928,11878,11925 ,0,0,0}, {23694,23653,23606 ,11966,11925,11878 ,0,0,0}, + {23657,23656,23655 ,11929,11928,11927 ,0,0,0}, {23656,23653,23655 ,11928,11925,11927 ,0,0,0}, + {23658,23657,23695 ,11930,11929,11967 ,0,0,0}, {23657,23655,23695 ,11929,11927,11967 ,0,0,0}, + {23659,23658,23696 ,11931,11930,11968 ,0,0,0}, {23658,23695,23696 ,11930,11967,11968 ,0,0,0}, + {23660,23659,23697 ,11932,11931,11969 ,0,0,0}, {23659,23696,23697 ,11931,11968,11969 ,0,0,0}, + {23611,23660,23698 ,11883,11932,11970 ,0,0,0}, {23660,23697,23698 ,11932,11969,11970 ,0,0,0}, + {23661,23611,23699 ,11933,11883,11971 ,0,0,0}, {23611,23698,23699 ,11883,11970,11971 ,0,0,0}, + {23662,23699,23700 ,11934,11971,11972 ,0,0,0}, {23699,23662,23661 ,11971,11934,11933 ,0,0,0}, + {23664,23663,23701 ,11936,11935,11973 ,0,0,0}, {23663,23662,23701 ,11935,11934,11973 ,0,0,0}, + {23665,23664,23702 ,11937,11936,11974 ,0,0,0}, {23664,23701,23702 ,11936,11973,11974 ,0,0,0}, + {23666,23665,23703 ,11938,11937,11975 ,0,0,0}, {23665,23702,23703 ,11937,11974,11975 ,0,0,0}, + {23667,23666,23704 ,11939,11938,11976 ,0,0,0}, {23666,23703,23704 ,11938,11975,11976 ,0,0,0}, + {23668,23667,23705 ,11940,11939,11977 ,0,0,0}, {23667,23704,23705 ,11939,11976,11977 ,0,0,0}, + {23669,23668,23706 ,11941,11940,11978 ,0,0,0}, {23668,23705,23706 ,11940,11977,11978 ,0,0,0}, + {23619,23669,23707 ,11891,11941,11979 ,0,0,0}, {23669,23706,23707 ,11941,11978,11979 ,0,0,0}, + {23670,23619,23708 ,11942,11891,11980 ,0,0,0}, {23619,23707,23708 ,11891,11979,11980 ,0,0,0}, + {23671,23670,23709 ,11943,11942,11981 ,0,0,0}, {23670,23708,23709 ,11942,11980,11981 ,0,0,0}, + {23672,23671,23710 ,11944,11943,11982 ,0,0,0}, {23671,23709,23710 ,11943,11981,11982 ,0,0,0}, + {23370,23672,23711 ,11642,11944,11983 ,0,0,0}, {23672,23710,23711 ,11944,11982,11983 ,0,0,0}, + {23712,23371,23370 ,11984,11643,11642 ,0,0,0}, {23712,23370,23711 ,11984,11642,11983 ,0,0,0}, + {23624,23374,23373 ,11896,11646,11645 ,0,0,0}, {23712,23375,23371 ,11984,11647,11643 ,0,0,0}, + {23372,23374,23377 ,11644,11646,11649 ,0,0,0}, {23278,23273,23627 ,11550,11545,11899 ,0,0,0}, + {23279,23276,23278 ,11551,11548,11550 ,0,0,0}, {23276,23713,23277 ,11548,11985,11549 ,0,0,0}, + {23277,23713,23673 ,11549,11985,11945 ,0,0,0}, {23713,23714,23673 ,11985,11986,11945 ,0,0,0}, + {23673,23714,23674 ,11945,11986,11946 ,0,0,0}, {23714,23715,23674 ,11986,11987,11946 ,0,0,0}, + {23674,23715,23675 ,11946,11987,11947 ,0,0,0}, {23715,23716,23675 ,11987,11988,11947 ,0,0,0}, + {23675,23716,23676 ,11947,11988,11948 ,0,0,0}, {23716,23717,23676 ,11988,11989,11948 ,0,0,0}, + {23676,23717,23677 ,11948,11989,11949 ,0,0,0}, {23717,23718,23677 ,11989,11990,11949 ,0,0,0}, + {23677,23718,23678 ,11949,11990,11950 ,0,0,0}, {23718,23719,23678 ,11990,11991,11950 ,0,0,0}, + {23678,23719,23679 ,11950,11991,11951 ,0,0,0}, {23719,23720,23679 ,11991,11992,11951 ,0,0,0}, + {23720,23721,23680 ,11992,11993,11952 ,0,0,0}, {23720,23680,23679 ,11992,11952,11951 ,0,0,0}, + {23721,23722,23681 ,11993,11994,11953 ,0,0,0}, {23721,23681,23680 ,11993,11953,11952 ,0,0,0}, + {23722,23723,23682 ,11994,11995,11954 ,0,0,0}, {23722,23682,23681 ,11994,11954,11953 ,0,0,0}, + {23723,23724,23683 ,11995,11996,11955 ,0,0,0}, {23723,23683,23682 ,11995,11955,11954 ,0,0,0}, + {23724,23725,23638 ,11996,11997,11910 ,0,0,0}, {23724,23638,23683 ,11996,11910,11955 ,0,0,0}, + {23639,23638,23725 ,11911,11910,11997 ,0,0,0}, {23639,23726,23640 ,11911,11998,11912 ,0,0,0}, + {23640,23726,23684 ,11912,11998,11956 ,0,0,0}, {23726,23727,23684 ,11998,11999,11956 ,0,0,0}, + {23684,23727,23685 ,11956,11999,11957 ,0,0,0}, {23727,23728,23685 ,11999,12000,11957 ,0,0,0}, + {23728,23729,23686 ,12000,12001,11958 ,0,0,0}, {23728,23686,23685 ,12000,11958,11957 ,0,0,0}, + {23729,23730,23687 ,12001,12002,11959 ,0,0,0}, {23729,23687,23686 ,12001,11959,11958 ,0,0,0}, + {23730,23689,23688 ,12002,11961,11960 ,0,0,0}, {23730,23688,23687 ,12002,11960,11959 ,0,0,0}, + {23689,23731,23648 ,11961,12003,11920 ,0,0,0}, {23731,23732,23648 ,12003,12004,11920 ,0,0,0}, + {23648,23732,23690 ,11920,12004,11962 ,0,0,0}, {23732,23733,23690 ,12004,12005,11962 ,0,0,0}, + {23690,23733,23691 ,11962,12005,11963 ,0,0,0}, {23733,23734,23691 ,12005,12006,11963 ,0,0,0}, + {23734,23735,23692 ,12006,12007,11964 ,0,0,0}, {23734,23692,23691 ,12006,11964,11963 ,0,0,0}, + {23735,23736,23693 ,12007,12008,11965 ,0,0,0}, {23735,23693,23692 ,12007,11965,11964 ,0,0,0}, + {23736,23737,23694 ,12008,12009,11966 ,0,0,0}, {23736,23694,23693 ,12008,11966,11965 ,0,0,0}, + {23737,23738,23653 ,12009,12010,11925 ,0,0,0}, {23737,23653,23694 ,12009,11925,11966 ,0,0,0}, + {23654,23653,23738 ,11926,11925,12010 ,0,0,0}, {23654,23739,23655 ,11926,12011,11927 ,0,0,0}, + {23655,23739,23695 ,11927,12011,11967 ,0,0,0}, {23739,23740,23695 ,12011,12012,11967 ,0,0,0}, + {23740,23741,23696 ,12012,12013,11968 ,0,0,0}, {23740,23696,23695 ,12012,11968,11967 ,0,0,0}, + {23741,23742,23697 ,12013,12014,11969 ,0,0,0}, {23741,23697,23696 ,12013,11969,11968 ,0,0,0}, + {23742,23743,23698 ,12014,12015,11970 ,0,0,0}, {23742,23698,23697 ,12014,11970,11969 ,0,0,0}, + {23743,23700,23699 ,12015,11972,11971 ,0,0,0}, {23743,23699,23698 ,12015,11971,11970 ,0,0,0}, + {23700,23744,23662 ,11972,12016,11934 ,0,0,0}, {23744,23745,23662 ,12016,12017,11934 ,0,0,0}, + {23662,23745,23701 ,11934,12017,11973 ,0,0,0}, {23745,23746,23701 ,12017,12018,11973 ,0,0,0}, + {23701,23746,23702 ,11973,12018,11974 ,0,0,0}, {23746,23747,23702 ,12018,12019,11974 ,0,0,0}, + {23702,23747,23703 ,11974,12019,11975 ,0,0,0}, {23747,23748,23703 ,12019,12020,11975 ,0,0,0}, + {23748,23749,23704 ,12020,12021,11976 ,0,0,0}, {23748,23704,23703 ,12020,11976,11975 ,0,0,0}, + {23749,23750,23705 ,12021,12022,11977 ,0,0,0}, {23749,23705,23704 ,12021,11977,11976 ,0,0,0}, + {23750,23751,23706 ,12022,12023,11978 ,0,0,0}, {23750,23706,23705 ,12022,11978,11977 ,0,0,0}, + {23751,23752,23707 ,12023,12024,11979 ,0,0,0}, {23751,23707,23706 ,12023,11979,11978 ,0,0,0}, + {23752,23753,23708 ,12024,12025,11980 ,0,0,0}, {23752,23708,23707 ,12024,11980,11979 ,0,0,0}, + {23753,23754,23709 ,12025,12026,11981 ,0,0,0}, {23753,23709,23708 ,12025,11981,11980 ,0,0,0}, + {23754,23755,23710 ,12026,12027,11982 ,0,0,0}, {23754,23710,23709 ,12026,11982,11981 ,0,0,0}, + {23755,23756,23711 ,12027,12028,11983 ,0,0,0}, {23755,23711,23710 ,12027,11983,11982 ,0,0,0}, + {23756,23757,23712 ,12028,12029,11984 ,0,0,0}, {23756,23712,23711 ,12028,11984,11983 ,0,0,0}, + {23758,23712,23757 ,12030,11984,12029 ,0,0,0}, {23712,23758,23375 ,11984,12030,11647 ,0,0,0}, + {23375,23758,23378 ,11647,12030,11650 ,0,0,0}, {23759,23760,23761 ,12031,12032,12033 ,0,0,0}, + {23762,23763,23764 ,12034,12035,12036 ,0,0,0}, {23765,23766,23767 ,12037,12038,12039 ,0,0,0}, + {23768,23769,23765 ,12040,12041,12037 ,0,0,0}, {23770,23771,23772 ,12042,12043,12044 ,0,0,0}, + {23773,23774,23775 ,12045,12046,12047 ,0,0,0}, {23776,23777,23778 ,12048,12049,12050 ,0,0,0}, + {23779,23780,23773 ,12051,12052,12045 ,0,0,0}, {23781,23782,23783 ,12053,12054,12055 ,0,0,0}, + {23783,23778,23784 ,12055,12050,12056 ,0,0,0}, {23785,23781,23786 ,12057,12053,12058 ,0,0,0}, + {23782,23781,23787 ,12054,12053,12059 ,0,0,0}, {23768,23788,23789 ,12040,12060,12061 ,0,0,0}, + {23785,23790,23781 ,12057,12062,12053 ,0,0,0}, {23791,23792,23793 ,12063,12064,12065 ,0,0,0}, + {23792,23794,23761 ,12064,12066,12033 ,0,0,0}, {23795,23796,23793 ,12067,12068,12065 ,0,0,0}, + {23794,23792,23791 ,12066,12064,12063 ,0,0,0}, {23797,23798,23795 ,12069,12070,12067 ,0,0,0}, + {23793,23796,23791 ,12065,12068,12063 ,0,0,0}, {23799,23800,23763 ,12071,12072,12035 ,0,0,0}, + {23801,23802,23803 ,12073,12074,12075 ,0,0,0}, {23799,23804,23800 ,12071,12076,12072 ,0,0,0}, + {23805,23806,23807 ,12077,12078,12079 ,0,0,0}, {23802,23808,23803 ,12074,12080,12075 ,0,0,0}, + {23809,23810,23811 ,12081,12082,12083 ,0,0,0}, {23805,23807,23812 ,12077,12079,12084 ,0,0,0}, + {23813,23814,23815 ,12085,12086,12087 ,0,0,0}, {23814,23813,23816 ,12086,12085,12088 ,0,0,0}, + {23817,23818,23819 ,12089,12090,12091 ,0,0,0}, {23820,23821,23818 ,12092,12093,12090 ,0,0,0}, + {23822,23823,23824 ,12094,12095,12096 ,0,0,0}, {23817,23819,23825 ,12089,12091,12097 ,0,0,0}, + {23826,23827,23828 ,12098,12099,12100 ,0,0,0}, {23822,23824,23829 ,12094,12096,12101 ,0,0,0}, + {23830,23831,23832 ,12102,12103,12104 ,0,0,0}, {23833,23827,23826 ,12105,12099,12098 ,0,0,0}, + {23834,23835,23836 ,12106,12107,12108 ,0,0,0}, {23836,23832,23834 ,12108,12104,12106 ,0,0,0}, + {23837,23838,23839 ,12109,12110,12111 ,0,0,0}, {23840,23835,23841 ,12112,12107,12113 ,0,0,0}, + {23842,23843,23844 ,12114,12115,12116 ,0,0,0}, {23843,23842,23845 ,12115,12114,12117 ,0,0,0}, + {23846,23847,23848 ,12118,12119,12120 ,0,0,0}, {23844,23847,23849 ,12116,12119,12121 ,0,0,0}, + {23850,23851,23852 ,12122,12123,12124 ,0,0,0}, {23853,23854,23855 ,12125,12126,12127 ,0,0,0}, + {23856,23857,23858 ,12128,12129,12130 ,0,0,0}, {23857,23856,23859 ,12129,12128,12131 ,0,0,0}, + {23860,23861,23862 ,12132,12133,12134 ,0,0,0}, {23863,23864,23860 ,12135,12136,12132 ,0,0,0}, + {23861,23860,23864 ,12133,12132,12136 ,0,0,0}, {23861,23864,23850 ,12133,12136,12122 ,0,0,0}, + {23865,23866,23867 ,12137,12138,12139 ,0,0,0}, {23848,23852,23851 ,12120,12124,12123 ,0,0,0}, + {23868,23853,23855 ,12140,12125,12127 ,0,0,0}, {23854,23869,23855 ,12126,12141,12127 ,0,0,0}, + {23870,23871,23853 ,12142,12143,12125 ,0,0,0}, {23853,23872,23854 ,12125,12144,12126 ,0,0,0}, + {23873,23874,23875 ,12145,12146,12147 ,0,0,0}, {23272,23876,23877 ,12148,12149,12150 ,0,0,0}, + {23877,23878,23627 ,12150,12151,12152 ,0,0,0}, {23878,23280,23627 ,12151,12153,12152 ,0,0,0}, + {23281,23280,23879 ,730,12153,12154 ,0,0,0}, {23867,23847,23865 ,12139,12119,12137 ,0,0,0}, + {23858,23863,23860 ,12130,12135,12132 ,0,0,0}, {23848,23851,23846 ,12120,12123,12118 ,0,0,0}, + {23410,23859,23409 ,12155,12131,12156 ,0,0,0}, {23842,23844,23849 ,12114,12116,12121 ,0,0,0}, + {23847,23846,23849 ,12119,12118,12121 ,0,0,0}, {23837,23845,23838 ,12109,12117,12110 ,0,0,0}, + {23843,23845,23837 ,12115,12117,12109 ,0,0,0}, {23837,23880,23843 ,12109,12157,12115 ,0,0,0}, + {23838,23840,23839 ,12110,12112,12111 ,0,0,0}, {23841,23835,23834 ,12113,12107,12106 ,0,0,0}, + {23840,23841,23839 ,12112,12113,12111 ,0,0,0}, {23830,23832,23836 ,12102,12104,12108 ,0,0,0}, + {23826,23828,23881 ,12098,12100,12158 ,0,0,0}, {23882,23833,23883 ,12159,12105,12160 ,0,0,0}, + {23832,23831,23883 ,12104,12103,12160 ,0,0,0}, {23827,23833,23882 ,12099,12105,12159 ,0,0,0}, + {23831,23882,23883 ,12103,12159,12160 ,0,0,0}, {23881,23828,23829 ,12158,12100,12101 ,0,0,0}, + {23884,23826,23881 ,12161,12098,12158 ,0,0,0}, {23829,23824,23881 ,12101,12096,12158 ,0,0,0}, + {23825,23823,23885 ,12097,12095,12162 ,0,0,0}, {23822,23885,23823 ,12094,12162,12095 ,0,0,0}, + {23886,23825,23885 ,12163,12097,12162 ,0,0,0}, {23821,23819,23818 ,12093,12091,12090 ,0,0,0}, + {23817,23825,23886 ,12089,12097,12163 ,0,0,0}, {23820,23887,23821 ,12092,12164,12093 ,0,0,0}, + {23815,23814,23887 ,12087,12086,12164 ,0,0,0}, {23887,23820,23815 ,12164,12092,12087 ,0,0,0}, + {23816,23888,23811 ,12088,12165,12083 ,0,0,0}, {23889,23890,23891 ,12166,12167,12168 ,0,0,0}, + {23811,23888,23892 ,12083,12165,12169 ,0,0,0}, {23888,23816,23813 ,12165,12088,12085 ,0,0,0}, + {23893,23812,23810 ,12170,12084,12082 ,0,0,0}, {23809,23811,23892 ,12081,12083,12169 ,0,0,0}, + {23812,23893,23805 ,12084,12170,12077 ,0,0,0}, {23893,23810,23809 ,12170,12082,12081 ,0,0,0}, + {23804,23894,23895 ,12076,12171,12172 ,0,0,0}, {23806,23808,23896 ,12078,12080,12173 ,0,0,0}, + {23807,23806,23896 ,12079,12078,12173 ,0,0,0}, {23896,23808,23802 ,12173,12080,12074 ,0,0,0}, + {23897,23898,23899 ,12174,12175,12176 ,0,0,0}, {23894,23801,23803 ,12171,12073,12075 ,0,0,0}, + {23761,23794,23759 ,12033,12066,12031 ,0,0,0}, {23804,23801,23894 ,12076,12073,12171 ,0,0,0}, + {23804,23895,23800 ,12076,12172,12072 ,0,0,0}, {23763,23762,23799 ,12035,12034,12071 ,0,0,0}, + {23798,23797,23764 ,12070,12069,12036 ,0,0,0}, {23764,23797,23762 ,12036,12069,12034 ,0,0,0}, + {23900,23797,23795 ,12177,12069,12067 ,0,0,0}, {23798,23796,23795 ,12070,12068,12067 ,0,0,0}, + {23760,23789,23788 ,12032,12061,12060 ,0,0,0}, {23759,23789,23760 ,12031,12061,12032 ,0,0,0}, + {23769,23766,23765 ,12041,12038,12037 ,0,0,0}, {23768,23765,23788 ,12040,12037,12060 ,0,0,0}, + {23769,23901,23766 ,12041,12178,12038 ,0,0,0}, {23772,23902,23776 ,12044,12179,12048 ,0,0,0}, + {23903,23904,23901 ,12180,12181,12178 ,0,0,0}, {23770,23905,23906 ,12042,12182,12183 ,0,0,0}, + {23904,23907,23908 ,12181,12184,12185 ,0,0,0}, {23903,23907,23904 ,12180,12184,12181 ,0,0,0}, + {23904,23766,23901 ,12181,12038,12178 ,0,0,0}, {23908,23909,23910 ,12185,12186,12187 ,0,0,0}, + {23909,23908,23911 ,12186,12185,12188 ,0,0,0}, {23907,23911,23908 ,12184,12188,12185 ,0,0,0}, + {23906,23905,23910 ,12183,12182,12187 ,0,0,0}, {23912,23772,23771 ,12189,12044,12043 ,0,0,0}, + {23908,23910,23905 ,12185,12187,12182 ,0,0,0}, {23777,23776,23913 ,12049,12048,12190 ,0,0,0}, + {23908,23914,23904 ,12185,12191,12181 ,0,0,0}, {23915,23788,23765 ,12192,12060,12037 ,0,0,0}, + {23904,23775,23766 ,12181,12047,12038 ,0,0,0}, {23916,23760,23788 ,12193,12032,12060 ,0,0,0}, + {23767,23766,23775 ,12039,12038,12047 ,0,0,0}, {23917,23761,23760 ,12194,12033,12032 ,0,0,0}, + {23915,23765,23767 ,12192,12037,12039 ,0,0,0}, {23918,23792,23761 ,12195,12064,12033 ,0,0,0}, + {23916,23788,23915 ,12193,12060,12192 ,0,0,0}, {23919,23793,23792 ,12196,12065,12064 ,0,0,0}, + {23917,23760,23916 ,12194,12032,12193 ,0,0,0}, {23920,23795,23793 ,12197,12067,12065 ,0,0,0}, + {23761,23917,23918 ,12033,12194,12195 ,0,0,0}, {23921,23922,23923 ,12198,12199,12200 ,0,0,0}, + {23792,23918,23919 ,12064,12195,12196 ,0,0,0}, {23923,23762,23797 ,12200,12034,12069 ,0,0,0}, + {23793,23919,23920 ,12065,12196,12197 ,0,0,0}, {23924,23799,23762 ,12201,12071,12034 ,0,0,0}, + {23795,23920,23900 ,12067,12197,12177 ,0,0,0}, {23925,23804,23799 ,12202,12076,12071 ,0,0,0}, + {23797,23900,23923 ,12069,12177,12200 ,0,0,0}, {23926,23801,23804 ,12203,12073,12076 ,0,0,0}, + {23762,23923,23924 ,12034,12200,12201 ,0,0,0}, {23927,23802,23801 ,12204,12074,12073 ,0,0,0}, + {23925,23799,23924 ,12202,12071,12201 ,0,0,0}, {23928,23896,23802 ,12205,12173,12074 ,0,0,0}, + {23926,23804,23925 ,12203,12076,12202 ,0,0,0}, {23929,23807,23896 ,12206,12079,12173 ,0,0,0}, + {23801,23926,23927 ,12073,12203,12204 ,0,0,0}, {23898,23812,23807 ,12175,12084,12079 ,0,0,0}, + {23802,23927,23928 ,12074,12204,12205 ,0,0,0}, {23930,23810,23812 ,12207,12082,12084 ,0,0,0}, + {23896,23928,23929 ,12173,12205,12206 ,0,0,0}, {23931,23811,23810 ,12208,12083,12082 ,0,0,0}, + {23807,23929,23898 ,12079,12206,12175 ,0,0,0}, {23932,23816,23811 ,12209,12088,12083 ,0,0,0}, + {23930,23812,23898 ,12207,12084,12175 ,0,0,0}, {23933,23814,23816 ,12210,12086,12088 ,0,0,0}, + {23931,23810,23930 ,12208,12082,12207 ,0,0,0}, {23934,23887,23814 ,12211,12164,12086 ,0,0,0}, + {23811,23931,23932 ,12083,12208,12209 ,0,0,0}, {23821,23887,23889 ,12093,12164,12166 ,0,0,0}, + {23816,23932,23933 ,12088,12209,12210 ,0,0,0}, {23935,23819,23821 ,12212,12091,12093 ,0,0,0}, + {23814,23933,23934 ,12086,12210,12211 ,0,0,0}, {23936,23825,23819 ,12213,12097,12091 ,0,0,0}, + {23887,23934,23889 ,12164,12211,12166 ,0,0,0}, {23937,23823,23825 ,12214,12095,12097 ,0,0,0}, + {23935,23821,23889 ,12212,12093,12166 ,0,0,0}, {23938,23824,23823 ,12215,12096,12095 ,0,0,0}, + {23936,23819,23935 ,12213,12091,12212 ,0,0,0}, {23939,23881,23824 ,12216,12158,12096 ,0,0,0}, + {23825,23936,23937 ,12097,12213,12214 ,0,0,0}, {23940,23941,23942 ,12217,12218,12219 ,0,0,0}, + {23823,23937,23938 ,12095,12214,12215 ,0,0,0}, {23943,23833,23826 ,12220,12105,12098 ,0,0,0}, + {23824,23938,23939 ,12096,12215,12216 ,0,0,0}, {23944,23883,23833 ,12221,12160,12105 ,0,0,0}, + {23881,23939,23884 ,12158,12216,12161 ,0,0,0}, {23945,23832,23883 ,12222,12104,12160 ,0,0,0}, + {23826,23884,23943 ,12098,12161,12220 ,0,0,0}, {23946,23834,23832 ,12223,12106,12104 ,0,0,0}, + {23944,23833,23943 ,12221,12105,12220 ,0,0,0}, {23947,23841,23834 ,12224,12113,12106 ,0,0,0}, + {23945,23883,23944 ,12222,12160,12221 ,0,0,0}, {23948,23839,23841 ,12225,12111,12113 ,0,0,0}, + {23946,23832,23945 ,12223,12104,12222 ,0,0,0}, {23949,23837,23839 ,12226,12109,12111 ,0,0,0}, + {23834,23946,23947 ,12106,12223,12224 ,0,0,0}, {23843,23950,23844 ,12115,12227,12116 ,0,0,0}, + {23841,23947,23948 ,12113,12224,12225 ,0,0,0}, {23865,23951,23866 ,12137,12228,12138 ,0,0,0}, + {23839,23948,23949 ,12111,12225,12226 ,0,0,0}, {23865,23847,23844 ,12137,12119,12116 ,0,0,0}, + {23837,23949,23880 ,12109,12226,12157 ,0,0,0}, {23867,23848,23847 ,12139,12120,12119 ,0,0,0}, + {23843,23880,23950 ,12115,12157,12227 ,0,0,0}, {23852,23848,23952 ,12124,12120,12229 ,0,0,0}, + {23865,23844,23950 ,12137,12116,12227 ,0,0,0}, {23869,23862,23861 ,12141,12134,12133 ,0,0,0}, + {23953,23860,23862 ,12230,12132,12134 ,0,0,0}, {23852,23861,23850 ,12124,12133,12122 ,0,0,0}, + {23952,23848,23867 ,12229,12120,12139 ,0,0,0}, {23869,23854,23862 ,12141,12126,12134 ,0,0,0}, + {23861,23852,23869 ,12133,12124,12141 ,0,0,0}, {23858,23954,23856 ,12130,12231,12128 ,0,0,0}, + {23856,23409,23859 ,12128,12156,12131 ,0,0,0}, {23863,23858,23857 ,12135,12130,12129 ,0,0,0}, + {23858,23953,23954 ,12130,12230,12231 ,0,0,0}, {23411,23409,23856 ,12232,12156,12128 ,0,0,0}, + {23905,23914,23908 ,12182,12191,12185 ,0,0,0}, {23771,23770,23906 ,12043,12042,12183 ,0,0,0}, + {23955,23783,23782 ,12233,12055,12054 ,0,0,0}, {23914,23775,23904 ,12191,12047,12181 ,0,0,0}, + {23914,23905,23956 ,12191,12182,12234 ,0,0,0}, {23767,23774,23957 ,12039,12046,12235 ,0,0,0}, + {23773,23775,23914 ,12045,12047,12191 ,0,0,0}, {23915,23957,23958 ,12192,12235,12236 ,0,0,0}, + {23774,23767,23775 ,12046,12039,12047 ,0,0,0}, {23916,23958,23959 ,12193,12236,12237 ,0,0,0}, + {23957,23915,23767 ,12235,12192,12039 ,0,0,0}, {23917,23959,23960 ,12194,12237,12238 ,0,0,0}, + {23958,23916,23915 ,12236,12193,12192 ,0,0,0}, {23918,23960,23961 ,12195,12238,12239 ,0,0,0}, + {23959,23917,23916 ,12237,12194,12193 ,0,0,0}, {23919,23961,23962 ,12196,12239,12240 ,0,0,0}, + {23960,23918,23917 ,12238,12195,12194 ,0,0,0}, {23920,23962,23963 ,12197,12240,12241 ,0,0,0}, + {23961,23919,23918 ,12239,12196,12195 ,0,0,0}, {23900,23963,23921 ,12177,12241,12198 ,0,0,0}, + {23920,23919,23962 ,12197,12196,12240 ,0,0,0}, {23964,23965,23966 ,12242,12243,12244 ,0,0,0}, + {23900,23920,23963 ,12177,12197,12241 ,0,0,0}, {23924,23922,23964 ,12201,12199,12242 ,0,0,0}, + {23923,23900,23921 ,12200,12177,12198 ,0,0,0}, {23925,23964,23967 ,12202,12242,12245 ,0,0,0}, + {23924,23923,23922 ,12201,12200,12199 ,0,0,0}, {23926,23967,23968 ,12203,12245,12246 ,0,0,0}, + {23964,23925,23924 ,12242,12202,12201 ,0,0,0}, {23927,23968,23969 ,12204,12246,12247 ,0,0,0}, + {23967,23926,23925 ,12245,12203,12202 ,0,0,0}, {23928,23969,23970 ,12205,12247,12248 ,0,0,0}, + {23968,23927,23926 ,12246,12204,12203 ,0,0,0}, {23929,23970,23899 ,12206,12248,12176 ,0,0,0}, + {23928,23927,23969 ,12205,12204,12247 ,0,0,0}, {23971,23972,23973 ,12249,12250,12251 ,0,0,0}, + {23929,23928,23970 ,12206,12205,12248 ,0,0,0}, {23930,23897,23974 ,12207,12174,12252 ,0,0,0}, + {23898,23929,23899 ,12175,12206,12176 ,0,0,0}, {23931,23974,23975 ,12208,12252,12253 ,0,0,0}, + {23897,23930,23898 ,12174,12207,12175 ,0,0,0}, {23932,23975,23976 ,12209,12253,12254 ,0,0,0}, + {23974,23931,23930 ,12252,12208,12207 ,0,0,0}, {23933,23976,23977 ,12210,12254,12255 ,0,0,0}, + {23975,23932,23931 ,12253,12209,12208 ,0,0,0}, {23934,23977,23890 ,12211,12255,12167 ,0,0,0}, + {23933,23932,23976 ,12210,12209,12254 ,0,0,0}, {23978,23979,23980 ,12256,12257,12258 ,0,0,0}, + {23934,23933,23977 ,12211,12210,12255 ,0,0,0}, {23935,23891,23981 ,12212,12168,12259 ,0,0,0}, + {23889,23934,23890 ,12166,12211,12167 ,0,0,0}, {23936,23981,23982 ,12213,12259,12260 ,0,0,0}, + {23935,23889,23891 ,12212,12166,12168 ,0,0,0}, {23937,23982,23983 ,12214,12260,12261 ,0,0,0}, + {23981,23936,23935 ,12259,12213,12212 ,0,0,0}, {23938,23983,23984 ,12215,12261,12262 ,0,0,0}, + {23982,23937,23936 ,12260,12214,12213 ,0,0,0}, {23939,23984,23985 ,12216,12262,12263 ,0,0,0}, + {23983,23938,23937 ,12261,12215,12214 ,0,0,0}, {23884,23985,23986 ,12161,12263,12264 ,0,0,0}, + {23939,23938,23984 ,12216,12215,12262 ,0,0,0}, {23943,23986,23941 ,12220,12264,12218 ,0,0,0}, + {23884,23939,23985 ,12161,12216,12263 ,0,0,0}, {23944,23941,23987 ,12221,12218,12265 ,0,0,0}, + {23943,23884,23986 ,12220,12161,12264 ,0,0,0}, {23945,23987,23988 ,12222,12265,12266 ,0,0,0}, + {23941,23944,23943 ,12218,12221,12220 ,0,0,0}, {23946,23988,23989 ,12223,12266,12267 ,0,0,0}, + {23987,23945,23944 ,12265,12222,12221 ,0,0,0}, {23947,23989,23990 ,12224,12267,12268 ,0,0,0}, + {23988,23946,23945 ,12266,12223,12222 ,0,0,0}, {23948,23990,23991 ,12225,12268,12269 ,0,0,0}, + {23989,23947,23946 ,12267,12224,12223 ,0,0,0}, {23949,23991,23992 ,12226,12269,12270 ,0,0,0}, + {23990,23948,23947 ,12268,12225,12224 ,0,0,0}, {23880,23992,23993 ,12157,12270,12271 ,0,0,0}, + {23991,23949,23948 ,12269,12226,12225 ,0,0,0}, {23950,23993,23951 ,12227,12271,12228 ,0,0,0}, + {23880,23949,23992 ,12157,12226,12270 ,0,0,0}, {23994,23867,23866 ,12272,12139,12138 ,0,0,0}, + {23950,23880,23993 ,12227,12157,12271 ,0,0,0}, {23876,23995,23871 ,12149,12273,12143 ,0,0,0}, + {23865,23950,23951 ,12137,12227,12228 ,0,0,0}, {23994,23855,23952 ,12272,12127,12229 ,0,0,0}, + {23854,23996,23862 ,12126,12274,12134 ,0,0,0}, {23952,23869,23852 ,12229,12141,12124 ,0,0,0}, + {23994,23952,23867 ,12272,12229,12139 ,0,0,0}, {23997,23954,23953 ,12275,12231,12230 ,0,0,0}, + {23952,23855,23869 ,12229,12127,12141 ,0,0,0}, {23412,23954,23997 ,12276,12231,12275 ,0,0,0}, + {23954,23411,23856 ,12231,12232,12128 ,0,0,0}, {23860,23953,23858 ,12132,12230,12130 ,0,0,0}, + {23996,23997,23953 ,12274,12275,12230 ,0,0,0}, {23412,23411,23954 ,12276,12232,12231 ,0,0,0}, + {23956,23905,23770 ,12234,12182,12042 ,0,0,0}, {23902,23772,23912 ,12179,12044,12189 ,0,0,0}, + {23998,23774,23780 ,12277,12046,12052 ,0,0,0}, {23956,23773,23914 ,12234,12045,12191 ,0,0,0}, + {23956,23770,23999 ,12234,12042,12278 ,0,0,0}, {24000,24001,24002 ,12279,12280,12281 ,0,0,0}, + {23779,23773,23956 ,12051,12045,12234 ,0,0,0}, {23998,24000,23957 ,12277,12279,12235 ,0,0,0}, + {23780,23774,23773 ,12052,12046,12045 ,0,0,0}, {24000,24003,23958 ,12279,12282,12236 ,0,0,0}, + {23998,23957,23774 ,12277,12235,12046 ,0,0,0}, {24003,24004,23959 ,12282,12283,12237 ,0,0,0}, + {24000,23958,23957 ,12279,12236,12235 ,0,0,0}, {24004,24005,23960 ,12283,12284,12238 ,0,0,0}, + {24003,23959,23958 ,12282,12237,12236 ,0,0,0}, {24005,24006,23961 ,12284,12285,12239 ,0,0,0}, + {24004,23960,23959 ,12283,12238,12237 ,0,0,0}, {24006,24007,23962 ,12285,12286,12240 ,0,0,0}, + {24005,23961,23960 ,12284,12239,12238 ,0,0,0}, {24007,24008,23963 ,12286,12287,12241 ,0,0,0}, + {24006,23962,23961 ,12285,12240,12239 ,0,0,0}, {24008,24009,23921 ,12287,12288,12198 ,0,0,0}, + {24007,23963,23962 ,12286,12241,12240 ,0,0,0}, {24009,23965,23922 ,12288,12243,12199 ,0,0,0}, + {23921,23963,24008 ,12198,12241,12287 ,0,0,0}, {24010,24011,24012 ,12289,12290,12291 ,0,0,0}, + {23922,23921,24009 ,12199,12198,12288 ,0,0,0}, {23966,24010,23967 ,12244,12289,12245 ,0,0,0}, + {23965,23964,23922 ,12243,12242,12199 ,0,0,0}, {24010,24013,23968 ,12289,12292,12246 ,0,0,0}, + {23966,23967,23964 ,12244,12245,12242 ,0,0,0}, {24013,24014,23969 ,12292,12293,12247 ,0,0,0}, + {24010,23968,23967 ,12289,12246,12245 ,0,0,0}, {24014,24015,23970 ,12293,12294,12248 ,0,0,0}, + {24013,23969,23968 ,12292,12247,12246 ,0,0,0}, {24015,24016,23899 ,12294,12295,12176 ,0,0,0}, + {24014,23970,23969 ,12293,12248,12247 ,0,0,0}, {23897,24016,24017 ,12174,12295,12296 ,0,0,0}, + {23899,23970,24015 ,12176,12248,12294 ,0,0,0}, {24017,23971,23974 ,12296,12249,12252 ,0,0,0}, + {24016,23897,23899 ,12295,12174,12176 ,0,0,0}, {23971,24018,23975 ,12249,12297,12253 ,0,0,0}, + {24017,23974,23897 ,12296,12252,12174 ,0,0,0}, {24018,24019,23976 ,12297,12298,12254 ,0,0,0}, + {23971,23975,23974 ,12249,12253,12252 ,0,0,0}, {24019,24020,23977 ,12298,12299,12255 ,0,0,0}, + {24018,23976,23975 ,12297,12254,12253 ,0,0,0}, {24020,24021,23890 ,12299,12300,12167 ,0,0,0}, + {24019,23977,23976 ,12298,12255,12254 ,0,0,0}, {24021,24022,23891 ,12300,12301,12168 ,0,0,0}, + {23890,23977,24020 ,12167,12255,12299 ,0,0,0}, {24022,23978,23981 ,12301,12256,12259 ,0,0,0}, + {23891,23890,24021 ,12168,12167,12300 ,0,0,0}, {23978,24023,23982 ,12256,12302,12260 ,0,0,0}, + {24022,23981,23891 ,12301,12259,12168 ,0,0,0}, {24023,24024,23983 ,12302,12303,12261 ,0,0,0}, + {23978,23982,23981 ,12256,12260,12259 ,0,0,0}, {24024,24025,23984 ,12303,12304,12262 ,0,0,0}, + {24023,23983,23982 ,12302,12261,12260 ,0,0,0}, {24025,24026,23985 ,12304,12305,12263 ,0,0,0}, + {24024,23984,23983 ,12303,12262,12261 ,0,0,0}, {24026,23942,23986 ,12305,12219,12264 ,0,0,0}, + {23985,23984,24025 ,12263,12262,12304 ,0,0,0}, {24027,24028,24029 ,12306,12307,12308 ,0,0,0}, + {23986,23985,24026 ,12264,12263,12305 ,0,0,0}, {23940,24027,23987 ,12217,12306,12265 ,0,0,0}, + {23942,23941,23986 ,12219,12218,12264 ,0,0,0}, {24027,24030,23988 ,12306,12309,12266 ,0,0,0}, + {23940,23987,23941 ,12217,12265,12218 ,0,0,0}, {24030,24031,23989 ,12309,12310,12267 ,0,0,0}, + {24027,23988,23987 ,12306,12266,12265 ,0,0,0}, {24031,24032,23990 ,12310,12311,12268 ,0,0,0}, + {24030,23989,23988 ,12309,12267,12266 ,0,0,0}, {24032,24033,23991 ,12311,12312,12269 ,0,0,0}, + {24031,23990,23989 ,12310,12268,12267 ,0,0,0}, {24033,24034,23992 ,12312,12313,12270 ,0,0,0}, + {24032,23991,23990 ,12311,12269,12268 ,0,0,0}, {24034,24035,23993 ,12313,12314,12271 ,0,0,0}, + {24033,23992,23991 ,12312,12270,12269 ,0,0,0}, {24035,24036,23951 ,12314,12315,12228 ,0,0,0}, + {24034,23993,23992 ,12313,12271,12270 ,0,0,0}, {24036,24037,23866 ,12315,12316,12138 ,0,0,0}, + {24035,23951,23993 ,12314,12228,12271 ,0,0,0}, {24037,23868,23994 ,12316,12140,12272 ,0,0,0}, + {23866,23951,24036 ,12138,12228,12315 ,0,0,0}, {24038,23408,23270 ,12317,12318,12319 ,0,0,0}, + {24037,23994,23866 ,12316,12272,12138 ,0,0,0}, {23870,23853,23868 ,12142,12125,12140 ,0,0,0}, + {23994,23868,23855 ,12272,12140,12127 ,0,0,0}, {23403,23997,24038 ,12320,12275,12317 ,0,0,0}, + {23403,23414,23997 ,12320,12321,12275 ,0,0,0}, {23862,23996,23953 ,12134,12274,12230 ,0,0,0}, + {23872,24038,23996 ,12144,12317,12274 ,0,0,0}, {23412,23997,23414 ,12276,12275,12321 ,0,0,0}, + {23772,23999,23770 ,12044,12278,12042 ,0,0,0}, {23913,23776,23902 ,12190,12048,12179 ,0,0,0}, + {23779,24039,24040 ,12051,12322,12323 ,0,0,0}, {23999,23779,23956 ,12278,12051,12234 ,0,0,0}, + {24041,23999,23772 ,12324,12278,12044 ,0,0,0}, {23780,24040,24042 ,12052,12323,12325 ,0,0,0}, + {23999,24039,23779 ,12278,12322,12051 ,0,0,0}, {23998,24042,24001 ,12277,12325,12280 ,0,0,0}, + {24040,23780,23779 ,12323,12052,12051 ,0,0,0}, {24043,24003,24002 ,12326,12282,12281 ,0,0,0}, + {24042,23998,23780 ,12325,12277,12052 ,0,0,0}, {24044,24004,24043 ,12327,12283,12326 ,0,0,0}, + {24001,24000,23998 ,12280,12279,12277 ,0,0,0}, {24045,24046,24047 ,12328,12329,12330 ,0,0,0}, + {24002,24003,24000 ,12281,12282,12279 ,0,0,0}, {24044,24045,24005 ,12327,12328,12284 ,0,0,0}, + {24043,24004,24003 ,12326,12283,12282 ,0,0,0}, {24045,24048,24006 ,12328,12331,12285 ,0,0,0}, + {24044,24005,24004 ,12327,12284,12283 ,0,0,0}, {24048,24049,24007 ,12331,12332,12286 ,0,0,0}, + {24045,24006,24005 ,12328,12285,12284 ,0,0,0}, {24049,24050,24008 ,12332,12333,12287 ,0,0,0}, + {24048,24007,24006 ,12331,12286,12285 ,0,0,0}, {24050,24051,24009 ,12333,12334,12288 ,0,0,0}, + {24049,24008,24007 ,12332,12287,12286 ,0,0,0}, {23965,24051,24052 ,12243,12334,12335 ,0,0,0}, + {24050,24009,24008 ,12333,12288,12287 ,0,0,0}, {23966,24052,24011 ,12244,12335,12290 ,0,0,0}, + {24051,23965,24009 ,12334,12243,12288 ,0,0,0}, {24053,24054,24055 ,12336,12337,12338 ,0,0,0}, + {24052,23966,23965 ,12335,12244,12243 ,0,0,0}, {24012,24053,24013 ,12291,12336,12292 ,0,0,0}, + {24011,24010,23966 ,12290,12289,12244 ,0,0,0}, {24053,24056,24014 ,12336,12339,12293 ,0,0,0}, + {24012,24013,24010 ,12291,12292,12289 ,0,0,0}, {24056,24057,24015 ,12339,12340,12294 ,0,0,0}, + {24053,24014,24013 ,12336,12293,12292 ,0,0,0}, {24016,24057,24058 ,12295,12340,12341 ,0,0,0}, + {24056,24015,24014 ,12339,12294,12293 ,0,0,0}, {24017,24058,23972 ,12296,12341,12250 ,0,0,0}, + {24016,24015,24057 ,12295,12294,12340 ,0,0,0}, {24059,24060,24061 ,12342,12343,12344 ,0,0,0}, + {24058,24017,24016 ,12341,12296,12295 ,0,0,0}, {23973,24059,24018 ,12251,12342,12297 ,0,0,0}, + {23972,23971,24017 ,12250,12249,12296 ,0,0,0}, {24059,24062,24019 ,12342,12345,12298 ,0,0,0}, + {23973,24018,23971 ,12251,12297,12249 ,0,0,0}, {24062,24063,24020 ,12345,12346,12299 ,0,0,0}, + {24059,24019,24018 ,12342,12298,12297 ,0,0,0}, {24063,24064,24021 ,12346,12347,12300 ,0,0,0}, + {24062,24020,24019 ,12345,12299,12298 ,0,0,0}, {24022,24064,23979 ,12301,12347,12257 ,0,0,0}, + {24021,24020,24063 ,12300,12299,12346 ,0,0,0}, {24065,24066,24067 ,12348,12349,12350 ,0,0,0}, + {24064,24022,24021 ,12347,12301,12300 ,0,0,0}, {23980,24065,24023 ,12258,12348,12302 ,0,0,0}, + {23979,23978,24022 ,12257,12256,12301 ,0,0,0}, {24065,24068,24024 ,12348,12351,12303 ,0,0,0}, + {23980,24023,23978 ,12258,12302,12256 ,0,0,0}, {24068,24069,24025 ,12351,12352,12304 ,0,0,0}, + {24065,24024,24023 ,12348,12303,12302 ,0,0,0}, {24069,24070,24026 ,12352,12353,12305 ,0,0,0}, + {24068,24025,24024 ,12351,12304,12303 ,0,0,0}, {23942,24070,24071 ,12219,12353,12354 ,0,0,0}, + {24069,24026,24025 ,12352,12305,12304 ,0,0,0}, {23940,24071,24028 ,12217,12354,12307 ,0,0,0}, + {24070,23942,24026 ,12353,12219,12305 ,0,0,0}, {24072,24030,24029 ,12355,12309,12308 ,0,0,0}, + {24071,23940,23942 ,12354,12217,12219 ,0,0,0}, {24073,24074,24075 ,12356,12357,12358 ,0,0,0}, + {24028,24027,23940 ,12307,12306,12217 ,0,0,0}, {24072,24073,24031 ,12355,12356,12310 ,0,0,0}, + {24029,24030,24027 ,12308,12309,12306 ,0,0,0}, {24073,24076,24032 ,12356,12359,12311 ,0,0,0}, + {24072,24031,24030 ,12355,12310,12309 ,0,0,0}, {24076,24077,24033 ,12359,12360,12312 ,0,0,0}, + {24073,24032,24031 ,12356,12311,12310 ,0,0,0}, {24077,24078,24034 ,12360,12361,12313 ,0,0,0}, + {24076,24033,24032 ,12359,12312,12311 ,0,0,0}, {24078,24079,24035 ,12361,12362,12314 ,0,0,0}, + {24077,24034,24033 ,12360,12313,12312 ,0,0,0}, {24079,24080,24036 ,12362,12363,12315 ,0,0,0}, + {24078,24035,24034 ,12361,12314,12313 ,0,0,0}, {24080,24081,24037 ,12363,12364,12316 ,0,0,0}, + {24079,24036,24035 ,12362,12315,12314 ,0,0,0}, {23868,24081,23870 ,12140,12364,12142 ,0,0,0}, + {24037,24036,24080 ,12316,12315,12363 ,0,0,0}, {23875,23870,24081 ,12147,12142,12364 ,0,0,0}, + {23868,24037,24081 ,12140,12316,12364 ,0,0,0}, {23872,23995,24038 ,12144,12273,12317 ,0,0,0}, + {23996,24038,23997 ,12274,12317,12275 ,0,0,0}, {23854,23872,23996 ,12126,12144,12274 ,0,0,0}, + {23871,23995,23872 ,12143,12273,12144 ,0,0,0}, {23403,24038,23270 ,12320,12317,12319 ,0,0,0}, + {23776,24041,23772 ,12048,12324,12044 ,0,0,0}, {23784,23778,23777 ,12056,12050,12049 ,0,0,0}, + {24039,24082,24083 ,12322,12365,12366 ,0,0,0}, {24041,24039,23999 ,12324,12322,12278 ,0,0,0}, + {23776,24084,24041 ,12048,12367,12324 ,0,0,0}, {24040,24083,24085 ,12323,12366,12368 ,0,0,0}, + {24041,24082,24039 ,12324,12365,12322 ,0,0,0}, {24042,24085,24086 ,12325,12368,12369 ,0,0,0}, + {24039,24083,24040 ,12322,12366,12323 ,0,0,0}, {24001,24086,24087 ,12280,12369,12370 ,0,0,0}, + {24040,24085,24042 ,12323,12368,12325 ,0,0,0}, {24002,24087,24088 ,12281,12370,12371 ,0,0,0}, + {24042,24086,24001 ,12325,12369,12280 ,0,0,0}, {24043,24088,24089 ,12326,12371,12372 ,0,0,0}, + {24001,24087,24002 ,12280,12370,12281 ,0,0,0}, {24044,24089,24046 ,12327,12372,12329 ,0,0,0}, + {24088,24043,24002 ,12371,12326,12281 ,0,0,0}, {24090,24048,24047 ,12373,12331,12330 ,0,0,0}, + {24089,24044,24043 ,12372,12327,12326 ,0,0,0}, {24091,24092,24090 ,12374,12375,12373 ,0,0,0}, + {24046,24045,24044 ,12329,12328,12327 ,0,0,0}, {24090,24092,24049 ,12373,12375,12332 ,0,0,0}, + {24047,24048,24045 ,12330,12331,12328 ,0,0,0}, {24092,24093,24050 ,12375,12376,12333 ,0,0,0}, + {24090,24049,24048 ,12373,12332,12331 ,0,0,0}, {24051,24093,24094 ,12334,12376,12377 ,0,0,0}, + {24092,24050,24049 ,12375,12333,12332 ,0,0,0}, {24052,24094,24095 ,12335,12377,12378 ,0,0,0}, + {24050,24093,24051 ,12333,12376,12334 ,0,0,0}, {24011,24095,24096 ,12290,12378,12379 ,0,0,0}, + {24051,24094,24052 ,12334,12377,12335 ,0,0,0}, {24012,24096,24054 ,12291,12379,12337 ,0,0,0}, + {24095,24011,24052 ,12378,12290,12335 ,0,0,0}, {24097,24098,24055 ,12380,12381,12338 ,0,0,0}, + {24096,24012,24011 ,12379,12291,12290 ,0,0,0}, {24055,24098,24056 ,12338,12381,12339 ,0,0,0}, + {24054,24053,24012 ,12337,12336,12291 ,0,0,0}, {24098,24099,24057 ,12381,12382,12340 ,0,0,0}, + {24055,24056,24053 ,12338,12339,12336 ,0,0,0}, {24058,24099,24100 ,12341,12382,12383 ,0,0,0}, + {24098,24057,24056 ,12381,12340,12339 ,0,0,0}, {23972,24100,24101 ,12250,12383,12384 ,0,0,0}, + {24057,24099,24058 ,12340,12382,12341 ,0,0,0}, {23973,24101,24060 ,12251,12384,12343 ,0,0,0}, + {24100,23972,24058 ,12383,12250,12341 ,0,0,0}, {24102,24103,24061 ,12385,12386,12344 ,0,0,0}, + {24101,23973,23972 ,12384,12251,12250 ,0,0,0}, {24061,24103,24062 ,12344,12386,12345 ,0,0,0}, + {24060,24059,23973 ,12343,12342,12251 ,0,0,0}, {24103,24104,24063 ,12386,12387,12346 ,0,0,0}, + {24061,24062,24059 ,12344,12345,12342 ,0,0,0}, {24064,24104,24105 ,12347,12387,12388 ,0,0,0}, + {24103,24063,24062 ,12386,12346,12345 ,0,0,0}, {23979,24105,24106 ,12257,12388,12389 ,0,0,0}, + {24063,24104,24064 ,12346,12387,12347 ,0,0,0}, {23980,24106,24066 ,12258,12389,12349 ,0,0,0}, + {24105,23979,24064 ,12388,12257,12347 ,0,0,0}, {24107,24108,24067 ,12390,12391,12350 ,0,0,0}, + {24106,23980,23979 ,12389,12258,12257 ,0,0,0}, {24067,24108,24068 ,12350,12391,12351 ,0,0,0}, + {24066,24065,23980 ,12349,12348,12258 ,0,0,0}, {24108,24109,24069 ,12391,12392,12352 ,0,0,0}, + {24067,24068,24065 ,12350,12351,12348 ,0,0,0}, {24070,24109,24110 ,12353,12392,12393 ,0,0,0}, + {24108,24069,24068 ,12391,12352,12351 ,0,0,0}, {24071,24110,24111 ,12354,12393,12394 ,0,0,0}, + {24069,24109,24070 ,12352,12392,12353 ,0,0,0}, {24028,24111,24112 ,12307,12394,12395 ,0,0,0}, + {24070,24110,24071 ,12353,12393,12354 ,0,0,0}, {24029,24112,24113 ,12308,12395,12396 ,0,0,0}, + {24071,24111,24028 ,12354,12394,12307 ,0,0,0}, {24072,24113,24074 ,12355,12396,12357 ,0,0,0}, + {24112,24029,24028 ,12395,12308,12307 ,0,0,0}, {24114,24076,24075 ,12397,12359,12358 ,0,0,0}, + {24113,24072,24029 ,12396,12355,12308 ,0,0,0}, {24115,24116,24114 ,12398,12399,12397 ,0,0,0}, + {24074,24073,24072 ,12357,12356,12355 ,0,0,0}, {24114,24116,24077 ,12397,12399,12360 ,0,0,0}, + {24075,24076,24073 ,12358,12359,12356 ,0,0,0}, {24116,24117,24078 ,12399,12400,12361 ,0,0,0}, + {24114,24077,24076 ,12397,12360,12359 ,0,0,0}, {24117,24118,24079 ,12400,12401,12362 ,0,0,0}, + {24116,24078,24077 ,12399,12361,12360 ,0,0,0}, {24118,24119,24080 ,12401,12402,12363 ,0,0,0}, + {24117,24079,24078 ,12400,12362,12361 ,0,0,0}, {24081,24119,23875 ,12364,12402,12147 ,0,0,0}, + {24118,24080,24079 ,12401,12363,12362 ,0,0,0}, {23875,24120,23870 ,12147,12403,12142 ,0,0,0}, + {24080,24119,24081 ,12363,12402,12364 ,0,0,0}, {23275,23995,23876 ,12404,12273,12149 ,0,0,0}, + {23995,23408,24038 ,12273,12318,12317 ,0,0,0}, {23853,23871,23872 ,12125,12143,12144 ,0,0,0}, + {24120,23876,23871 ,12403,12149,12143 ,0,0,0}, {23275,23408,23995 ,12404,12318,12273 ,0,0,0}, + {23778,24084,23776 ,12050,12367,12048 ,0,0,0}, {24121,23783,23784 ,12405,12055,12056 ,0,0,0}, + {24122,24082,24084 ,12406,12365,12367 ,0,0,0}, {24084,24082,24041 ,12367,12365,12324 ,0,0,0}, + {24084,23955,24122 ,12367,12233,12406 ,0,0,0}, {24123,24083,24082 ,12407,12366,12365 ,0,0,0}, + {24082,24122,24123 ,12365,12406,12407 ,0,0,0}, {24124,24085,24083 ,12408,12368,12366 ,0,0,0}, + {24083,24123,24124 ,12366,12407,12408 ,0,0,0}, {24125,24086,24085 ,12409,12369,12368 ,0,0,0}, + {24085,24124,24125 ,12368,12408,12409 ,0,0,0}, {24126,24087,24086 ,12410,12370,12369 ,0,0,0}, + {24086,24125,24126 ,12369,12409,12410 ,0,0,0}, {24127,24088,24087 ,12411,12371,12370 ,0,0,0}, + {24087,24126,24127 ,12370,12410,12411 ,0,0,0}, {24128,24089,24088 ,12412,12372,12371 ,0,0,0}, + {24088,24127,24128 ,12371,12411,12412 ,0,0,0}, {24129,24046,24089 ,12413,12329,12372 ,0,0,0}, + {24089,24128,24129 ,12372,12412,12413 ,0,0,0}, {24130,24047,24046 ,12414,12330,12329 ,0,0,0}, + {24046,24129,24130 ,12329,12413,12414 ,0,0,0}, {24131,24090,24047 ,12415,12373,12330 ,0,0,0}, + {24130,24131,24047 ,12414,12415,12330 ,0,0,0}, {24132,24133,24134 ,12416,12417,12418 ,0,0,0}, + {24131,24091,24090 ,12415,12374,12373 ,0,0,0}, {24135,24093,24092 ,12419,12376,12375 ,0,0,0}, + {24091,24135,24092 ,12374,12419,12375 ,0,0,0}, {24136,24094,24093 ,12420,12377,12376 ,0,0,0}, + {24093,24135,24136 ,12376,12419,12420 ,0,0,0}, {24137,24095,24094 ,12421,12378,12377 ,0,0,0}, + {24094,24136,24137 ,12377,12420,12421 ,0,0,0}, {24138,24096,24095 ,12422,12379,12378 ,0,0,0}, + {24095,24137,24138 ,12378,12421,12422 ,0,0,0}, {24139,24054,24096 ,12423,12337,12379 ,0,0,0}, + {24096,24138,24139 ,12379,12422,12423 ,0,0,0}, {24140,24055,24054 ,12424,12338,12337 ,0,0,0}, + {24139,24140,24054 ,12423,12424,12337 ,0,0,0}, {24141,24097,24142 ,12425,12380,12426 ,0,0,0}, + {24140,24097,24055 ,12424,12380,12338 ,0,0,0}, {24141,24099,24098 ,12425,12382,12381 ,0,0,0}, + {24097,24141,24098 ,12380,12425,12381 ,0,0,0}, {24143,24100,24099 ,12427,12383,12382 ,0,0,0}, + {24099,24141,24143 ,12382,12425,12427 ,0,0,0}, {24144,24101,24100 ,12428,12384,12383 ,0,0,0}, + {24100,24143,24144 ,12383,12427,12428 ,0,0,0}, {24145,24060,24101 ,12429,12343,12384 ,0,0,0}, + {24101,24144,24145 ,12384,12428,12429 ,0,0,0}, {24146,24061,24060 ,12430,12344,12343 ,0,0,0}, + {24145,24146,24060 ,12429,12430,12343 ,0,0,0}, {24147,24148,24149 ,12431,12432,12433 ,0,0,0}, + {24146,24102,24061 ,12430,12385,12344 ,0,0,0}, {24150,24104,24103 ,12434,12387,12386 ,0,0,0}, + {24102,24150,24103 ,12385,12434,12386 ,0,0,0}, {24151,24105,24104 ,12435,12388,12387 ,0,0,0}, + {24104,24150,24151 ,12387,12434,12435 ,0,0,0}, {24152,24106,24105 ,12436,12389,12388 ,0,0,0}, + {24105,24151,24152 ,12388,12435,12436 ,0,0,0}, {24153,24066,24106 ,12437,12349,12389 ,0,0,0}, + {24106,24152,24153 ,12389,12436,12437 ,0,0,0}, {24154,24067,24066 ,12438,12350,12349 ,0,0,0}, + {24153,24154,24066 ,12437,12438,12349 ,0,0,0}, {24108,24155,24109 ,12391,12439,12392 ,0,0,0}, + {24154,24107,24067 ,12438,12390,12350 ,0,0,0}, {24156,24157,24155 ,12440,12441,12439 ,0,0,0}, + {24107,24155,24108 ,12390,12439,12391 ,0,0,0}, {24157,24110,24109 ,12441,12393,12392 ,0,0,0}, + {24109,24155,24157 ,12392,12439,12441 ,0,0,0}, {24158,24111,24110 ,12442,12394,12393 ,0,0,0}, + {24110,24157,24158 ,12393,12441,12442 ,0,0,0}, {24159,24112,24111 ,12443,12395,12394 ,0,0,0}, + {24111,24158,24159 ,12394,12442,12443 ,0,0,0}, {24160,24113,24112 ,12444,12396,12395 ,0,0,0}, + {24112,24159,24160 ,12395,12443,12444 ,0,0,0}, {24161,24074,24113 ,12445,12357,12396 ,0,0,0}, + {24113,24160,24161 ,12396,12444,12445 ,0,0,0}, {24162,24075,24074 ,12446,12358,12357 ,0,0,0}, + {24074,24161,24162 ,12357,12445,12446 ,0,0,0}, {24163,24114,24075 ,12447,12397,12358 ,0,0,0}, + {24162,24163,24075 ,12446,12447,12358 ,0,0,0}, {24116,24164,24117 ,12399,12448,12400 ,0,0,0}, + {24163,24115,24114 ,12447,12398,12397 ,0,0,0}, {24117,24165,24118 ,12400,12449,12401 ,0,0,0}, + {24115,24164,24116 ,12398,12448,12399 ,0,0,0}, {24118,24166,24119 ,12401,12450,12402 ,0,0,0}, + {24164,24165,24117 ,12448,12449,12400 ,0,0,0}, {24119,23873,23875 ,12402,12145,12147 ,0,0,0}, + {24165,24166,24118 ,12449,12450,12401 ,0,0,0}, {23874,23878,23877 ,12146,12151,12150 ,0,0,0}, + {24166,23873,24119 ,12450,12145,12402 ,0,0,0}, {23874,24120,23875 ,12146,12403,12147 ,0,0,0}, + {23457,23275,23876 ,12451,12404,12149 ,0,0,0}, {23870,24120,23871 ,12142,12403,12143 ,0,0,0}, + {24120,23874,23877 ,12403,12146,12150 ,0,0,0}, {23272,23457,23876 ,12148,12451,12149 ,0,0,0}, + {23783,23955,23778 ,12055,12233,12050 ,0,0,0}, {24121,23786,23781 ,12405,12058,12053 ,0,0,0}, + {24122,23955,24167 ,12406,12233,12452 ,0,0,0}, {23778,23955,24084 ,12050,12233,12367 ,0,0,0}, + {23955,23782,24167 ,12233,12054,12452 ,0,0,0}, {24123,24122,24168 ,12407,12406,12453 ,0,0,0}, + {24122,24167,24168 ,12406,12452,12453 ,0,0,0}, {24124,24123,24169 ,12408,12407,12454 ,0,0,0}, + {24123,24168,24169 ,12407,12453,12454 ,0,0,0}, {24125,24124,24170 ,12409,12408,12455 ,0,0,0}, + {24124,24169,24170 ,12408,12454,12455 ,0,0,0}, {24126,24125,24171 ,12410,12409,12456 ,0,0,0}, + {24125,24170,24171 ,12409,12455,12456 ,0,0,0}, {24127,24126,24172 ,12411,12410,12457 ,0,0,0}, + {24126,24171,24172 ,12410,12456,12457 ,0,0,0}, {24128,24127,24173 ,12412,12411,12458 ,0,0,0}, + {24127,24172,24173 ,12411,12457,12458 ,0,0,0}, {24129,24128,24174 ,12413,12412,12459 ,0,0,0}, + {24128,24173,24174 ,12412,12458,12459 ,0,0,0}, {24130,24129,24175 ,12414,12413,12460 ,0,0,0}, + {24129,24174,24175 ,12413,12459,12460 ,0,0,0}, {24131,24130,24176 ,12415,12414,12461 ,0,0,0}, + {24130,24175,24176 ,12414,12460,12461 ,0,0,0}, {24091,24131,24177 ,12374,12415,12462 ,0,0,0}, + {24131,24176,24177 ,12415,12461,12462 ,0,0,0}, {24135,24091,24132 ,12419,12374,12416 ,0,0,0}, + {24177,24132,24091 ,12462,12416,12374 ,0,0,0}, {24136,24135,24134 ,12420,12419,12418 ,0,0,0}, + {24135,24132,24134 ,12419,12416,12418 ,0,0,0}, {24137,24136,24178 ,12421,12420,12463 ,0,0,0}, + {24136,24134,24178 ,12420,12418,12463 ,0,0,0}, {24138,24137,24179 ,12422,12421,12464 ,0,0,0}, + {24137,24178,24179 ,12421,12463,12464 ,0,0,0}, {24139,24138,24180 ,12423,12422,12465 ,0,0,0}, + {24138,24179,24180 ,12422,12464,12465 ,0,0,0}, {24140,24139,24181 ,12424,12423,12466 ,0,0,0}, + {24139,24180,24181 ,12423,12465,12466 ,0,0,0}, {24097,24140,24182 ,12380,12424,12467 ,0,0,0}, + {24140,24181,24182 ,12424,12466,12467 ,0,0,0}, {24182,24183,24142 ,12467,12468,12426 ,0,0,0}, + {24182,24142,24097 ,12467,12426,12380 ,0,0,0}, {24143,24141,24184 ,12427,12425,12469 ,0,0,0}, + {24141,24142,24184 ,12425,12426,12469 ,0,0,0}, {24144,24143,24185 ,12428,12427,12470 ,0,0,0}, + {24143,24184,24185 ,12427,12469,12470 ,0,0,0}, {24145,24144,24186 ,12429,12428,12471 ,0,0,0}, + {24144,24185,24186 ,12428,12470,12471 ,0,0,0}, {24146,24145,24187 ,12430,12429,12472 ,0,0,0}, + {24145,24186,24187 ,12429,12471,12472 ,0,0,0}, {24102,24146,24188 ,12385,12430,12473 ,0,0,0}, + {24146,24187,24188 ,12430,12472,12473 ,0,0,0}, {24150,24102,24147 ,12434,12385,12431 ,0,0,0}, + {24188,24147,24102 ,12473,12431,12385 ,0,0,0}, {24151,24150,24149 ,12435,12434,12433 ,0,0,0}, + {24150,24147,24149 ,12434,12431,12433 ,0,0,0}, {24152,24151,24189 ,12436,12435,12474 ,0,0,0}, + {24151,24149,24189 ,12435,12433,12474 ,0,0,0}, {24153,24152,24190 ,12437,12436,12475 ,0,0,0}, + {24152,24189,24190 ,12436,12474,12475 ,0,0,0}, {24154,24153,24191 ,12438,12437,12476 ,0,0,0}, + {24153,24190,24191 ,12437,12475,12476 ,0,0,0}, {24107,24154,24192 ,12390,12438,12477 ,0,0,0}, + {24154,24191,24192 ,12438,12476,12477 ,0,0,0}, {24155,24107,24193 ,12439,12390,12478 ,0,0,0}, + {24107,24192,24193 ,12390,12477,12478 ,0,0,0}, {24156,24193,24194 ,12440,12478,12479 ,0,0,0}, + {24193,24156,24155 ,12478,12440,12439 ,0,0,0}, {24158,24157,24195 ,12442,12441,12480 ,0,0,0}, + {24157,24156,24195 ,12441,12440,12480 ,0,0,0}, {24159,24158,24196 ,12443,12442,12481 ,0,0,0}, + {24158,24195,24196 ,12442,12480,12481 ,0,0,0}, {24160,24159,24197 ,12444,12443,12482 ,0,0,0}, + {24159,24196,24197 ,12443,12481,12482 ,0,0,0}, {24161,24160,24198 ,12445,12444,12483 ,0,0,0}, + {24160,24197,24198 ,12444,12482,12483 ,0,0,0}, {24162,24161,24199 ,12446,12445,12484 ,0,0,0}, + {24161,24198,24199 ,12445,12483,12484 ,0,0,0}, {24163,24162,24200 ,12447,12446,12485 ,0,0,0}, + {24162,24199,24200 ,12446,12484,12485 ,0,0,0}, {24115,24163,24201 ,12398,12447,12486 ,0,0,0}, + {24163,24200,24201 ,12447,12485,12486 ,0,0,0}, {24164,24115,24202 ,12448,12398,12487 ,0,0,0}, + {24115,24201,24202 ,12398,12486,12487 ,0,0,0}, {24165,24164,24203 ,12449,12448,12488 ,0,0,0}, + {24164,24202,24203 ,12448,12487,12488 ,0,0,0}, {24166,24165,24204 ,12450,12449,12489 ,0,0,0}, + {24165,24203,24204 ,12449,12488,12489 ,0,0,0}, {23873,24166,24205 ,12145,12450,12490 ,0,0,0}, + {24166,24204,24205 ,12450,12489,12490 ,0,0,0}, {24206,23874,23873 ,12491,12146,12145 ,0,0,0}, + {24205,24206,23873 ,12490,12491,12145 ,0,0,0}, {24120,23877,23876 ,12403,12150,12149 ,0,0,0}, + {24206,23878,23874 ,12491,12151,12146 ,0,0,0}, {23272,23877,23627 ,12148,12150,12152 ,0,0,0}, + {23781,23783,24121 ,12053,12055,12405 ,0,0,0}, {23790,23787,23781 ,12062,12059,12053 ,0,0,0}, + {23787,24207,23782 ,12059,12492,12054 ,0,0,0}, {23782,24207,24167 ,12054,12492,12452 ,0,0,0}, + {24207,24208,24167 ,12492,12493,12452 ,0,0,0}, {24167,24208,24168 ,12452,12493,12453 ,0,0,0}, + {24208,24209,24168 ,12493,12494,12453 ,0,0,0}, {24168,24209,24169 ,12453,12494,12454 ,0,0,0}, + {24209,24210,24169 ,12494,12495,12454 ,0,0,0}, {24169,24210,24170 ,12454,12495,12455 ,0,0,0}, + {24210,24211,24170 ,12495,12496,12455 ,0,0,0}, {24170,24211,24171 ,12455,12496,12456 ,0,0,0}, + {24211,24212,24171 ,12496,12497,12456 ,0,0,0}, {24171,24212,24172 ,12456,12497,12457 ,0,0,0}, + {24212,24213,24172 ,12497,12498,12457 ,0,0,0}, {24172,24213,24173 ,12457,12498,12458 ,0,0,0}, + {24213,24214,24173 ,12498,12499,12458 ,0,0,0}, {24214,24215,24174 ,12499,12500,12459 ,0,0,0}, + {24214,24174,24173 ,12499,12459,12458 ,0,0,0}, {24215,24216,24175 ,12500,12501,12460 ,0,0,0}, + {24215,24175,24174 ,12500,12460,12459 ,0,0,0}, {24216,24217,24176 ,12501,12502,12461 ,0,0,0}, + {24216,24176,24175 ,12501,12461,12460 ,0,0,0}, {24217,24218,24177 ,12502,12503,12462 ,0,0,0}, + {24217,24177,24176 ,12502,12462,12461 ,0,0,0}, {24218,24219,24132 ,12503,12504,12416 ,0,0,0}, + {24218,24132,24177 ,12503,12416,12462 ,0,0,0}, {24133,24132,24219 ,12417,12416,12504 ,0,0,0}, + {24133,24220,24134 ,12417,12505,12418 ,0,0,0}, {24134,24220,24178 ,12418,12505,12463 ,0,0,0}, + {24220,24221,24178 ,12505,12506,12463 ,0,0,0}, {24178,24221,24179 ,12463,12506,12464 ,0,0,0}, + {24221,24222,24179 ,12506,12507,12464 ,0,0,0}, {24222,24223,24180 ,12507,12508,12465 ,0,0,0}, + {24222,24180,24179 ,12507,12465,12464 ,0,0,0}, {24223,24224,24181 ,12508,12509,12466 ,0,0,0}, + {24223,24181,24180 ,12508,12466,12465 ,0,0,0}, {24224,24183,24182 ,12509,12468,12467 ,0,0,0}, + {24224,24182,24181 ,12509,12467,12466 ,0,0,0}, {24183,24225,24142 ,12468,12510,12426 ,0,0,0}, + {24225,24226,24142 ,12510,12511,12426 ,0,0,0}, {24142,24226,24184 ,12426,12511,12469 ,0,0,0}, + {24226,24227,24184 ,12511,12512,12469 ,0,0,0}, {24184,24227,24185 ,12469,12512,12470 ,0,0,0}, + {24227,24228,24185 ,12512,12513,12470 ,0,0,0}, {24228,24229,24186 ,12513,12514,12471 ,0,0,0}, + {24228,24186,24185 ,12513,12471,12470 ,0,0,0}, {24229,24230,24187 ,12514,12515,12472 ,0,0,0}, + {24229,24187,24186 ,12514,12472,12471 ,0,0,0}, {24230,24231,24188 ,12515,12516,12473 ,0,0,0}, + {24230,24188,24187 ,12515,12473,12472 ,0,0,0}, {24231,24232,24147 ,12516,12517,12431 ,0,0,0}, + {24231,24147,24188 ,12516,12431,12473 ,0,0,0}, {24148,24147,24232 ,12432,12431,12517 ,0,0,0}, + {24148,24233,24149 ,12432,12518,12433 ,0,0,0}, {24149,24233,24189 ,12433,12518,12474 ,0,0,0}, + {24233,24234,24189 ,12518,12519,12474 ,0,0,0}, {24234,24235,24190 ,12519,12520,12475 ,0,0,0}, + {24234,24190,24189 ,12519,12475,12474 ,0,0,0}, {24235,24236,24191 ,12520,12521,12476 ,0,0,0}, + {24235,24191,24190 ,12520,12476,12475 ,0,0,0}, {24236,24237,24192 ,12521,12522,12477 ,0,0,0}, + {24236,24192,24191 ,12521,12477,12476 ,0,0,0}, {24237,24194,24193 ,12522,12479,12478 ,0,0,0}, + {24237,24193,24192 ,12522,12478,12477 ,0,0,0}, {24194,24238,24156 ,12479,12523,12440 ,0,0,0}, + {24238,24239,24156 ,12523,12524,12440 ,0,0,0}, {24156,24239,24195 ,12440,12524,12480 ,0,0,0}, + {24239,24240,24195 ,12524,12525,12480 ,0,0,0}, {24195,24240,24196 ,12480,12525,12481 ,0,0,0}, + {24240,24241,24196 ,12525,12526,12481 ,0,0,0}, {24196,24241,24197 ,12481,12526,12482 ,0,0,0}, + {24241,24242,24197 ,12526,12527,12482 ,0,0,0}, {24242,24243,24198 ,12527,12528,12483 ,0,0,0}, + {24242,24198,24197 ,12527,12483,12482 ,0,0,0}, {24243,24244,24199 ,12528,12529,12484 ,0,0,0}, + {24243,24199,24198 ,12528,12484,12483 ,0,0,0}, {24244,24245,24200 ,12529,12530,12485 ,0,0,0}, + {24244,24200,24199 ,12529,12485,12484 ,0,0,0}, {24245,24246,24201 ,12530,12531,12486 ,0,0,0}, + {24245,24201,24200 ,12530,12486,12485 ,0,0,0}, {24246,24247,24202 ,12531,12532,12487 ,0,0,0}, + {24246,24202,24201 ,12531,12487,12486 ,0,0,0}, {24247,24248,24203 ,12532,12533,12488 ,0,0,0}, + {24247,24203,24202 ,12532,12488,12487 ,0,0,0}, {24248,24249,24204 ,12533,12534,12489 ,0,0,0}, + {24248,24204,24203 ,12533,12489,12488 ,0,0,0}, {24249,24250,24205 ,12534,12535,12490 ,0,0,0}, + {24249,24205,24204 ,12534,12490,12489 ,0,0,0}, {24250,24251,24206 ,12535,12536,12491 ,0,0,0}, + {24250,24206,24205 ,12535,12491,12490 ,0,0,0}, {23879,24206,24251 ,12154,12491,12536 ,0,0,0}, + {24206,23879,23878 ,12491,12154,12151 ,0,0,0}, {23280,23878,23879 ,12153,12151,12154 ,0,0,0}, + {24252,24253,24223 ,12537,12538,12539 ,0,0,0}, {24223,24222,24252 ,12539,12540,12537 ,0,0,0}, + {24254,24255,24256 ,12541,12542,12543 ,0,0,0}, {24257,24221,24220 ,12544,12545,12546 ,0,0,0}, + {24222,24221,24258 ,12540,12545,12547 ,0,0,0}, {24257,24258,24221 ,12544,12547,12545 ,0,0,0}, + {24133,24219,24259 ,12548,12549,12550 ,0,0,0}, {24260,24133,24259 ,12551,12548,12550 ,0,0,0}, + {24220,24133,24260 ,12546,12548,12551 ,0,0,0}, {24259,24218,24261 ,12550,12552,12553 ,0,0,0}, + {24220,24260,24257 ,12546,12551,12544 ,0,0,0}, {24259,24219,24218 ,12550,12549,12552 ,0,0,0}, + {24258,24252,24222 ,12547,12537,12540 ,0,0,0}, {24262,24217,24216 ,12554,12555,12556 ,0,0,0}, + {24262,24261,24217 ,12554,12553,12555 ,0,0,0}, {24263,24262,24216 ,12557,12554,12556 ,0,0,0}, + {24264,24265,24266 ,12558,12559,12560 ,0,0,0}, {24267,24263,24215 ,12561,12557,12562 ,0,0,0}, + {24214,24267,24215 ,12563,12561,12562 ,0,0,0}, {24268,24214,24213 ,12564,12563,12565 ,0,0,0}, + {24267,24214,24268 ,12561,12563,12564 ,0,0,0}, {24269,24268,24213 ,12566,12564,12565 ,0,0,0}, + {24215,24263,24216 ,12562,12557,12556 ,0,0,0}, {24261,24218,24217 ,12553,12552,12555 ,0,0,0}, + {24270,24211,24271 ,12567,12568,12569 ,0,0,0}, {24212,24270,24269 ,12570,12567,12566 ,0,0,0}, + {24210,24272,24271 ,12571,12572,12569 ,0,0,0}, {24212,24211,24270 ,12570,12568,12567 ,0,0,0}, + {24272,24209,24273 ,12572,12573,12574 ,0,0,0}, {24209,24272,24210 ,12573,12572,12571 ,0,0,0}, + {24273,24208,24274 ,12574,12575,12576 ,0,0,0}, {24211,24210,24271 ,12568,12571,12569 ,0,0,0}, + {24209,24208,24273 ,12573,12575,12574 ,0,0,0}, {24273,24275,24276 ,12574,12577,12578 ,0,0,0}, + {23907,24277,23911 ,12579,12580,12188 ,0,0,0}, {24278,24279,24280 ,12581,12582,12583 ,0,0,0}, + {24277,24281,23911 ,12580,12584,12188 ,0,0,0}, {24282,24283,24284 ,12585,12586,12587 ,0,0,0}, + {24277,23907,24282 ,12580,12579,12585 ,0,0,0}, {24274,24208,24207 ,12576,12575,12588 ,0,0,0}, + {24276,24285,24286 ,12578,12589,12590 ,0,0,0}, {24287,24288,24286 ,12591,12592,12590 ,0,0,0}, + {24286,24285,24289 ,12590,12589,12593 ,0,0,0}, {24207,23787,24290 ,12588,12594,12595 ,0,0,0}, + {24291,24292,24293 ,12596,12597,12598 ,0,0,0}, {24292,24294,24295 ,12597,12599,12600 ,0,0,0}, + {24294,24296,24295 ,12599,12601,12600 ,0,0,0}, {24297,24293,24298 ,12602,12598,12603 ,0,0,0}, + {24299,24298,23785 ,12604,12603,12057 ,0,0,0}, {23787,24298,24290 ,12594,12603,12595 ,0,0,0}, + {24298,23790,23785 ,12603,12605,12057 ,0,0,0}, {24299,24297,24298 ,12604,12602,12603 ,0,0,0}, + {24279,24300,24301 ,12582,12606,12607 ,0,0,0}, {24212,24269,24213 ,12570,12566,12565 ,0,0,0}, + {24253,24224,24223 ,12538,12608,12539 ,0,0,0}, {24183,24224,24302 ,12609,12608,12610 ,0,0,0}, + {24253,24302,24224 ,12538,12610,12608 ,0,0,0}, {24303,24225,24183 ,12611,12612,12609 ,0,0,0}, + {24183,24302,24303 ,12609,12610,12611 ,0,0,0}, {24226,24303,24304 ,12613,12611,12614 ,0,0,0}, + {24303,24226,24225 ,12611,12613,12612 ,0,0,0}, {24305,24227,24304 ,12615,12616,12614 ,0,0,0}, + {24226,24304,24227 ,12613,12614,12616 ,0,0,0}, {24228,24227,24305 ,12617,12616,12615 ,0,0,0}, + {24305,24306,24228 ,12615,12618,12617 ,0,0,0}, {24228,24306,24229 ,12617,12618,12619 ,0,0,0}, + {24229,24306,24307 ,12619,12618,12620 ,0,0,0}, {24308,24309,24310 ,12621,12622,12623 ,0,0,0}, + {24311,24230,24307 ,12624,12625,12620 ,0,0,0}, {24229,24307,24230 ,12619,12620,12625 ,0,0,0}, + {24311,24312,24231 ,12624,12626,12627 ,0,0,0}, {24231,24230,24311 ,12627,12625,12624 ,0,0,0}, + {24148,24232,24312 ,12628,12629,12626 ,0,0,0}, {24312,24232,24231 ,12626,12629,12627 ,0,0,0}, + {24313,24233,24148 ,12630,12631,12628 ,0,0,0}, {24148,24312,24313 ,12628,12626,12630 ,0,0,0}, + {24233,24314,24234 ,12631,12632,12633 ,0,0,0}, {24314,24233,24313 ,12632,12631,12630 ,0,0,0}, + {24235,24234,24315 ,12634,12633,12635 ,0,0,0}, {24314,24315,24234 ,12632,12635,12633 ,0,0,0}, + {24316,24235,24315 ,12636,12634,12635 ,0,0,0}, {24316,24236,24235 ,12636,12637,12634 ,0,0,0}, + {24316,24317,24236 ,12636,12638,12637 ,0,0,0}, {24318,24319,24320 ,12639,12640,12641 ,0,0,0}, + {24237,24317,24321 ,12642,12638,12643 ,0,0,0}, {24317,24237,24236 ,12638,12642,12637 ,0,0,0}, + {24322,24194,24321 ,12644,12645,12643 ,0,0,0}, {24237,24321,24194 ,12642,12643,12645 ,0,0,0}, + {24238,24322,24239 ,12646,12644,12647 ,0,0,0}, {24238,24194,24322 ,12646,12645,12644 ,0,0,0}, + {24240,24239,24323 ,12648,12647,12649 ,0,0,0}, {24322,24323,24239 ,12644,12649,12647 ,0,0,0}, + {24324,24241,24240 ,12650,12651,12648 ,0,0,0}, {24240,24323,24324 ,12648,12649,12650 ,0,0,0}, + {24241,24325,24242 ,12651,12652,12653 ,0,0,0}, {24325,24241,24324 ,12652,12651,12650 ,0,0,0}, + {24243,24242,24326 ,12654,12653,12655 ,0,0,0}, {24325,24326,24242 ,12652,12655,12653 ,0,0,0}, + {24327,24243,24326 ,12656,12654,12655 ,0,0,0}, {24327,24244,24243 ,12656,12657,12654 ,0,0,0}, + {24327,24328,24244 ,12656,12658,12657 ,0,0,0}, {24329,24330,24331 ,12659,12660,12661 ,0,0,0}, + {24245,24328,24330 ,12662,12658,12660 ,0,0,0}, {24328,24245,24244 ,12658,12662,12657 ,0,0,0}, + {24332,24246,24330 ,12663,12664,12660 ,0,0,0}, {24245,24330,24246 ,12662,12660,12664 ,0,0,0}, + {24333,24334,24335 ,12665,12666,12667 ,0,0,0}, {24247,24246,24332 ,12668,12664,12663 ,0,0,0}, + {24336,24337,24338 ,12669,12670,12671 ,0,0,0}, {24339,24340,24341 ,12672,12673,12674 ,0,0,0}, + {24342,24343,24344 ,12675,12676,12677 ,0,0,0}, {24345,24346,24347 ,12678,12679,12680 ,0,0,0}, + {24348,24349,24336 ,12681,12682,12669 ,0,0,0}, {24350,24351,24352 ,12683,12684,12685 ,0,0,0}, + {24353,24354,24349 ,12686,12687,12682 ,0,0,0}, {24350,24345,24351 ,12683,12678,12684 ,0,0,0}, + {24349,24355,24356 ,12682,12688,12689 ,0,0,0}, {23859,23410,24352 ,12690,726,12685 ,0,0,0}, + {24357,24247,24332 ,12691,12668,12663 ,0,0,0}, {24247,24357,24248 ,12668,12691,12692 ,0,0,0}, + {24248,24333,24249 ,12692,12665,12693 ,0,0,0}, {24329,24332,24330 ,12659,12663,12660 ,0,0,0}, + {24358,24359,24250 ,12694,12695,12696 ,0,0,0}, {24333,24358,24249 ,12665,12694,12693 ,0,0,0}, + {24356,24358,24335 ,12689,12694,12667 ,0,0,0}, {24249,24358,24250 ,12693,12694,12696 ,0,0,0}, + {24359,24360,23879 ,12695,12697,12698 ,0,0,0}, {24359,23879,24251 ,12695,12698,12699 ,0,0,0}, + {23281,23879,24361 ,730,12698,12700 ,0,0,0}, {24298,23787,23790 ,12603,12594,12605 ,0,0,0}, + {24291,24293,24297 ,12596,12598,12602 ,0,0,0}, {24301,24300,24362 ,12607,12606,12701 ,0,0,0}, + {24290,24274,24207 ,12595,12576,12588 ,0,0,0}, {24290,24293,24363 ,12595,12598,12702 ,0,0,0}, + {24364,24272,24276 ,12703,12572,12578 ,0,0,0}, {24274,24363,24275 ,12576,12702,12577 ,0,0,0}, + {24365,24271,24364 ,12704,12569,12703 ,0,0,0}, {24275,24273,24274 ,12577,12574,12576 ,0,0,0}, + {24366,24270,24365 ,12705,12567,12704 ,0,0,0}, {24276,24272,24273 ,12578,12572,12574 ,0,0,0}, + {24367,24269,24366 ,12706,12566,12705 ,0,0,0}, {24364,24271,24272 ,12703,12569,12572 ,0,0,0}, + {24368,24268,24367 ,12707,12564,12706 ,0,0,0}, {24365,24270,24271 ,12704,12567,12569 ,0,0,0}, + {24369,24267,24368 ,12708,12561,12707 ,0,0,0}, {24366,24269,24270 ,12705,12566,12567 ,0,0,0}, + {24370,24263,24369 ,12709,12557,12708 ,0,0,0}, {24367,24268,24269 ,12706,12564,12566 ,0,0,0}, + {24370,24371,24262 ,12709,12710,12554 ,0,0,0}, {24267,24268,24368 ,12561,12564,12707 ,0,0,0}, + {24372,24261,24371 ,12711,12553,12710 ,0,0,0}, {24263,24267,24369 ,12557,12561,12708 ,0,0,0}, + {24265,24259,24372 ,12559,12550,12711 ,0,0,0}, {24262,24263,24370 ,12554,12557,12709 ,0,0,0}, + {24373,24260,24265 ,12712,12551,12559 ,0,0,0}, {24261,24262,24371 ,12553,12554,12710 ,0,0,0}, + {24374,24257,24373 ,12713,12544,12712 ,0,0,0}, {24259,24261,24372 ,12550,12553,12711 ,0,0,0}, + {24375,24258,24374 ,12714,12547,12713 ,0,0,0}, {24265,24260,24259 ,12559,12551,12550 ,0,0,0}, + {24376,24252,24375 ,12715,12537,12714 ,0,0,0}, {24373,24257,24260 ,12712,12544,12551 ,0,0,0}, + {24376,24377,24253 ,12715,12716,12538 ,0,0,0}, {24258,24257,24374 ,12547,12544,12713 ,0,0,0}, + {24378,24302,24377 ,12717,12610,12716 ,0,0,0}, {24252,24258,24375 ,12537,12547,12714 ,0,0,0}, + {24379,24303,24378 ,12718,12611,12717 ,0,0,0}, {24253,24252,24376 ,12538,12537,12715 ,0,0,0}, + {24380,24304,24379 ,12719,12614,12718 ,0,0,0}, {24302,24253,24377 ,12610,12538,12716 ,0,0,0}, + {24381,24305,24380 ,12720,12615,12719 ,0,0,0}, {24303,24302,24378 ,12611,12610,12717 ,0,0,0}, + {24382,24306,24381 ,12721,12618,12720 ,0,0,0}, {24379,24304,24303 ,12718,12614,12611 ,0,0,0}, + {24382,24383,24307 ,12721,12722,12620 ,0,0,0}, {24305,24304,24380 ,12615,12614,12719 ,0,0,0}, + {24384,24311,24383 ,12723,12624,12722 ,0,0,0}, {24306,24305,24381 ,12618,12615,12720 ,0,0,0}, + {24308,24312,24384 ,12621,12626,12723 ,0,0,0}, {24307,24306,24382 ,12620,12618,12721 ,0,0,0}, + {24385,24313,24308 ,12724,12630,12621 ,0,0,0}, {24311,24307,24383 ,12624,12620,12722 ,0,0,0}, + {24386,24314,24385 ,12725,12632,12724 ,0,0,0}, {24312,24311,24384 ,12626,12624,12723 ,0,0,0}, + {24387,24315,24386 ,12726,12635,12725 ,0,0,0}, {24308,24313,24312 ,12621,12630,12626 ,0,0,0}, + {24388,24316,24387 ,12727,12636,12726 ,0,0,0}, {24385,24314,24313 ,12724,12632,12630 ,0,0,0}, + {24388,24389,24317 ,12727,12728,12638 ,0,0,0}, {24315,24314,24386 ,12635,12632,12725 ,0,0,0}, + {24390,24321,24389 ,12729,12643,12728 ,0,0,0}, {24316,24315,24387 ,12636,12635,12726 ,0,0,0}, + {24391,24322,24390 ,12730,12644,12729 ,0,0,0}, {24317,24316,24388 ,12638,12636,12727 ,0,0,0}, + {24392,24323,24391 ,12731,12649,12730 ,0,0,0}, {24321,24317,24389 ,12643,12638,12728 ,0,0,0}, + {24393,24324,24392 ,12732,12650,12731 ,0,0,0}, {24390,24322,24321 ,12729,12644,12643 ,0,0,0}, + {24394,24325,24393 ,12733,12652,12732 ,0,0,0}, {24391,24323,24322 ,12730,12649,12644 ,0,0,0}, + {24395,24326,24394 ,12734,12655,12733 ,0,0,0}, {24392,24324,24323 ,12731,12650,12649 ,0,0,0}, + {24396,24327,24395 ,12735,12656,12734 ,0,0,0}, {24393,24325,24324 ,12732,12652,12650 ,0,0,0}, + {24396,24331,24328 ,12735,12661,12658 ,0,0,0}, {24326,24325,24394 ,12655,12652,12733 ,0,0,0}, + {24332,24329,24397 ,12663,12659,12736 ,0,0,0}, {24327,24326,24395 ,12656,12655,12734 ,0,0,0}, + {24353,24335,24341 ,12686,12667,12674 ,0,0,0}, {24328,24327,24396 ,12658,12656,12735 ,0,0,0}, + {24357,24397,24334 ,12691,12736,12666 ,0,0,0}, {24328,24331,24330 ,12658,12661,12660 ,0,0,0}, + {24397,24398,24334 ,12736,12737,12666 ,0,0,0}, {24356,24359,24358 ,12689,12695,12694 ,0,0,0}, + {24357,24333,24248 ,12691,12665,12692 ,0,0,0}, {24397,24357,24332 ,12736,12691,12663 ,0,0,0}, + {24356,24353,24349 ,12689,12686,12682 ,0,0,0}, {24333,24357,24334 ,12665,12691,12666 ,0,0,0}, + {24360,24355,24399 ,12697,12688,12738 ,0,0,0}, {24360,24361,23879 ,12697,12700,12698 ,0,0,0}, + {24250,24359,24251 ,12696,12695,12699 ,0,0,0}, {24360,24359,24355 ,12697,12695,12688 ,0,0,0}, + {24400,24361,24360 ,12739,12700,12697 ,0,0,0}, {24298,24293,24290 ,12603,12598,12595 ,0,0,0}, + {24294,24292,24291 ,12599,12597,12596 ,0,0,0}, {24282,23907,23903 ,12585,12579,12740 ,0,0,0}, + {24290,24363,24274 ,12595,12702,12576 ,0,0,0}, {24401,24363,24292 ,12741,12702,12597 ,0,0,0}, + {24286,24288,24364 ,12590,12592,12703 ,0,0,0}, {24285,24275,24401 ,12589,12577,12741 ,0,0,0}, + {24288,24402,24365 ,12592,12742,12704 ,0,0,0}, {24285,24276,24275 ,12589,12578,12577 ,0,0,0}, + {24402,24403,24366 ,12742,12743,12705 ,0,0,0}, {24286,24364,24276 ,12590,12703,12578 ,0,0,0}, + {24403,24404,24367 ,12743,12744,12706 ,0,0,0}, {24288,24365,24364 ,12592,12704,12703 ,0,0,0}, + {24404,24405,24368 ,12744,12745,12707 ,0,0,0}, {24402,24366,24365 ,12742,12705,12704 ,0,0,0}, + {24405,24406,24369 ,12745,12746,12708 ,0,0,0}, {24403,24367,24366 ,12743,12706,12705 ,0,0,0}, + {24406,24407,24370 ,12746,12747,12709 ,0,0,0}, {24404,24368,24367 ,12744,12707,12706 ,0,0,0}, + {24407,24408,24371 ,12747,12748,12710 ,0,0,0}, {24405,24369,24368 ,12745,12708,12707 ,0,0,0}, + {24408,24266,24372 ,12748,12560,12711 ,0,0,0}, {24370,24369,24406 ,12709,12708,12746 ,0,0,0}, + {24409,24410,24411 ,12749,12750,12751 ,0,0,0}, {24371,24370,24407 ,12710,12709,12747 ,0,0,0}, + {24264,24410,24373 ,12558,12750,12712 ,0,0,0}, {24372,24371,24408 ,12711,12710,12748 ,0,0,0}, + {24410,24409,24374 ,12750,12749,12713 ,0,0,0}, {24265,24372,24266 ,12559,12711,12560 ,0,0,0}, + {24409,24412,24375 ,12749,12752,12714 ,0,0,0}, {24264,24373,24265 ,12558,12712,12559 ,0,0,0}, + {24412,24413,24376 ,12752,12753,12715 ,0,0,0}, {24410,24374,24373 ,12750,12713,12712 ,0,0,0}, + {24413,24414,24377 ,12753,12754,12716 ,0,0,0}, {24409,24375,24374 ,12749,12714,12713 ,0,0,0}, + {24414,24415,24378 ,12754,12755,12717 ,0,0,0}, {24376,24375,24412 ,12715,12714,12752 ,0,0,0}, + {24256,24379,24415 ,12543,12718,12755 ,0,0,0}, {24377,24376,24413 ,12716,12715,12753 ,0,0,0}, + {24256,24255,24380 ,12543,12542,12719 ,0,0,0}, {24378,24377,24414 ,12717,12716,12754 ,0,0,0}, + {24255,24416,24381 ,12542,12756,12720 ,0,0,0}, {24415,24379,24378 ,12755,12718,12717 ,0,0,0}, + {24416,24417,24382 ,12756,12757,12721 ,0,0,0}, {24256,24380,24379 ,12543,12719,12718 ,0,0,0}, + {24417,24418,24383 ,12757,12758,12722 ,0,0,0}, {24255,24381,24380 ,12542,12720,12719 ,0,0,0}, + {24418,24309,24384 ,12758,12622,12723 ,0,0,0}, {24382,24381,24416 ,12721,12720,12756 ,0,0,0}, + {24419,24420,24421 ,12759,12760,12761 ,0,0,0}, {24383,24382,24417 ,12722,12721,12757 ,0,0,0}, + {24310,24422,24385 ,12623,12762,12724 ,0,0,0}, {24384,24383,24418 ,12723,12722,12758 ,0,0,0}, + {24422,24423,24386 ,12762,12763,12725 ,0,0,0}, {24308,24384,24309 ,12621,12723,12622 ,0,0,0}, + {24423,24424,24387 ,12763,12764,12726 ,0,0,0}, {24310,24385,24308 ,12623,12724,12621 ,0,0,0}, + {24424,24425,24388 ,12764,12765,12727 ,0,0,0}, {24422,24386,24385 ,12762,12725,12724 ,0,0,0}, + {24425,24426,24389 ,12765,12766,12728 ,0,0,0}, {24423,24387,24386 ,12763,12726,12725 ,0,0,0}, + {24426,24427,24390 ,12766,12767,12729 ,0,0,0}, {24388,24387,24424 ,12727,12726,12764 ,0,0,0}, + {24427,24318,24391 ,12767,12639,12730 ,0,0,0}, {24389,24388,24425 ,12728,12727,12765 ,0,0,0}, + {24318,24320,24392 ,12639,12641,12731 ,0,0,0}, {24390,24389,24426 ,12729,12728,12766 ,0,0,0}, + {24320,24428,24393 ,12641,12768,12732 ,0,0,0}, {24427,24391,24390 ,12767,12730,12729 ,0,0,0}, + {24428,24429,24394 ,12768,12769,12733 ,0,0,0}, {24318,24392,24391 ,12639,12731,12730 ,0,0,0}, + {24429,24430,24395 ,12769,12770,12734 ,0,0,0}, {24320,24393,24392 ,12641,12732,12731 ,0,0,0}, + {24430,24431,24396 ,12770,12771,12735 ,0,0,0}, {24428,24394,24393 ,12768,12733,12732 ,0,0,0}, + {24431,24432,24331 ,12771,12772,12661 ,0,0,0}, {24429,24395,24394 ,12769,12734,12733 ,0,0,0}, + {24432,24433,24329 ,12772,12773,12659 ,0,0,0}, {24430,24396,24395 ,12770,12735,12734 ,0,0,0}, + {24433,24398,24397 ,12773,12737,12736 ,0,0,0}, {24431,24331,24396 ,12771,12661,12735 ,0,0,0}, + {24398,24341,24334 ,12737,12674,12666 ,0,0,0}, {24329,24331,24432 ,12659,12661,12772 ,0,0,0}, + {24434,24435,24436 ,12774,12775,12776 ,0,0,0}, {24433,24397,24329 ,12773,12736,12659 ,0,0,0}, + {24354,24336,24349 ,12687,12669,12682 ,0,0,0}, {24348,24437,24399 ,12681,12777,12738 ,0,0,0}, + {24333,24335,24358 ,12665,12667,12694 ,0,0,0}, {24341,24335,24334 ,12674,12667,12666 ,0,0,0}, + {24438,24399,24437 ,12778,12738,12777 ,0,0,0}, {24399,24400,24360 ,12738,12739,12697 ,0,0,0}, + {24359,24356,24355 ,12695,12689,12688 ,0,0,0}, {24355,24348,24399 ,12688,12681,12738 ,0,0,0}, + {24438,24400,24399 ,12778,12739,12738 ,0,0,0}, {24292,24363,24293 ,12597,12702,12598 ,0,0,0}, + {24439,24295,24296 ,12779,12600,12601 ,0,0,0}, {24439,24300,24295 ,12779,12606,12600 ,0,0,0}, + {24363,24401,24275 ,12702,12741,12577 ,0,0,0}, {24440,24401,24295 ,12780,12741,12600 ,0,0,0}, + {24288,24441,24402 ,12592,12781,12742 ,0,0,0}, {24289,24285,24440 ,12593,12589,12780 ,0,0,0}, + {24402,24442,24403 ,12742,12782,12743 ,0,0,0}, {24289,24287,24286 ,12593,12591,12590 ,0,0,0}, + {24443,24444,24445 ,12783,12784,12785 ,0,0,0}, {24287,24441,24288 ,12591,12781,12592 ,0,0,0}, + {24404,24403,24446 ,12744,12743,12786 ,0,0,0}, {24441,24442,24402 ,12781,12782,12742 ,0,0,0}, + {24405,24404,24445 ,12745,12744,12785 ,0,0,0}, {24442,24446,24403 ,12782,12786,12743 ,0,0,0}, + {24406,24405,24444 ,12746,12745,12784 ,0,0,0}, {24446,24445,24404 ,12786,12785,12744 ,0,0,0}, + {24407,24406,24447 ,12747,12746,12787 ,0,0,0}, {24445,24444,24405 ,12785,12784,12745 ,0,0,0}, + {24408,24407,24448 ,12748,12747,12788 ,0,0,0}, {24444,24447,24406 ,12784,12787,12746 ,0,0,0}, + {24266,24408,24449 ,12560,12748,12789 ,0,0,0}, {24447,24448,24407 ,12787,12788,12747 ,0,0,0}, + {24264,24266,24450 ,12558,12560,12790 ,0,0,0}, {24448,24449,24408 ,12788,12789,12748 ,0,0,0}, + {24410,24264,24451 ,12750,12558,12791 ,0,0,0}, {24450,24266,24449 ,12790,12560,12789 ,0,0,0}, + {24452,24453,24454 ,12792,12793,12794 ,0,0,0}, {24451,24264,24450 ,12791,12558,12790 ,0,0,0}, + {24412,24409,24455 ,12752,12749,12795 ,0,0,0}, {24451,24411,24410 ,12791,12751,12750 ,0,0,0}, + {24413,24412,24454 ,12753,12752,12794 ,0,0,0}, {24411,24455,24409 ,12751,12795,12749 ,0,0,0}, + {24414,24413,24453 ,12754,12753,12793 ,0,0,0}, {24455,24454,24412 ,12795,12794,12752 ,0,0,0}, + {24415,24414,24456 ,12755,12754,12796 ,0,0,0}, {24454,24453,24413 ,12794,12793,12753 ,0,0,0}, + {24256,24415,24457 ,12543,12755,12797 ,0,0,0}, {24456,24414,24453 ,12796,12754,12793 ,0,0,0}, + {24458,24459,24460 ,12798,12799,12800 ,0,0,0}, {24457,24415,24456 ,12797,12755,12796 ,0,0,0}, + {24416,24255,24461 ,12756,12542,12801 ,0,0,0}, {24457,24254,24256 ,12797,12541,12543 ,0,0,0}, + {24417,24416,24460 ,12757,12756,12800 ,0,0,0}, {24254,24461,24255 ,12541,12801,12542 ,0,0,0}, + {24418,24417,24459 ,12758,12757,12799 ,0,0,0}, {24461,24460,24416 ,12801,12800,12756 ,0,0,0}, + {24309,24418,24462 ,12622,12758,12802 ,0,0,0}, {24460,24459,24417 ,12800,12799,12757 ,0,0,0}, + {24310,24309,24463 ,12623,12622,12803 ,0,0,0}, {24459,24462,24418 ,12799,12802,12758 ,0,0,0}, + {24422,24310,24464 ,12762,12623,12804 ,0,0,0}, {24463,24309,24462 ,12803,12622,12802 ,0,0,0}, + {24423,24422,24465 ,12763,12762,12805 ,0,0,0}, {24464,24310,24463 ,12804,12623,12803 ,0,0,0}, + {24424,24423,24419 ,12764,12763,12759 ,0,0,0}, {24464,24465,24422 ,12804,12805,12762 ,0,0,0}, + {24425,24424,24421 ,12765,12764,12761 ,0,0,0}, {24465,24419,24423 ,12805,12759,12763 ,0,0,0}, + {24426,24425,24466 ,12766,12765,12806 ,0,0,0}, {24419,24421,24424 ,12759,12761,12764 ,0,0,0}, + {24427,24426,24467 ,12767,12766,12807 ,0,0,0}, {24421,24466,24425 ,12761,12806,12765 ,0,0,0}, + {24318,24427,24468 ,12639,12767,12808 ,0,0,0}, {24467,24426,24466 ,12807,12766,12806 ,0,0,0}, + {24469,24470,24471 ,12809,12810,12811 ,0,0,0}, {24468,24427,24467 ,12808,12767,12807 ,0,0,0}, + {24428,24320,24472 ,12768,12641,12812 ,0,0,0}, {24468,24319,24318 ,12808,12640,12639 ,0,0,0}, + {24429,24428,24471 ,12769,12768,12811 ,0,0,0}, {24319,24472,24320 ,12640,12812,12641 ,0,0,0}, + {24430,24429,24470 ,12770,12769,12810 ,0,0,0}, {24472,24471,24428 ,12812,12811,12768 ,0,0,0}, + {24431,24430,24473 ,12771,12770,12813 ,0,0,0}, {24471,24470,24429 ,12811,12810,12769 ,0,0,0}, + {24432,24431,24474 ,12772,12771,12814 ,0,0,0}, {24470,24473,24430 ,12810,12813,12770 ,0,0,0}, + {24433,24432,24475 ,12773,12772,12815 ,0,0,0}, {24473,24474,24431 ,12813,12814,12771 ,0,0,0}, + {24398,24433,24476 ,12737,12773,12816 ,0,0,0}, {24474,24475,24432 ,12814,12815,12772 ,0,0,0}, + {24341,24398,24339 ,12674,12737,12672 ,0,0,0}, {24475,24476,24433 ,12815,12816,12773 ,0,0,0}, + {24353,24341,24340 ,12686,12674,12673 ,0,0,0}, {24476,24339,24398 ,12816,12672,12737 ,0,0,0}, + {24477,24347,24436 ,12817,12680,12776 ,0,0,0}, {24478,24337,24336 ,12818,12670,12669 ,0,0,0}, + {24335,24353,24356 ,12667,12686,12689 ,0,0,0}, {24340,24354,24353 ,12673,12687,12686 ,0,0,0}, + {24479,24437,24435 ,12819,12777,12775 ,0,0,0}, {24479,24480,24437 ,12819,12820,12777 ,0,0,0}, + {24355,24349,24348 ,12688,12682,12681 ,0,0,0}, {24348,24338,24437 ,12681,12671,12777 ,0,0,0}, + {24438,24437,24480 ,12778,12777,12820 ,0,0,0}, {24292,24295,24401 ,12597,12600,12741 ,0,0,0}, + {24362,24300,24439 ,12701,12606,12779 ,0,0,0}, {24289,24481,24287 ,12593,12821,12591 ,0,0,0}, + {24401,24440,24285 ,12741,12780,12589 ,0,0,0}, {24300,24482,24440 ,12606,12822,12780 ,0,0,0}, + {24441,24287,24483 ,12781,12591,12823 ,0,0,0}, {24482,24481,24289 ,12822,12821,12593 ,0,0,0}, + {24442,24441,24484 ,12782,12781,12824 ,0,0,0}, {24287,24481,24483 ,12591,12821,12823 ,0,0,0}, + {24446,24442,24485 ,12786,12782,12825 ,0,0,0}, {24441,24483,24484 ,12781,12823,12824 ,0,0,0}, + {24445,24446,24486 ,12785,12786,12826 ,0,0,0}, {24484,24485,24442 ,12824,12825,12782 ,0,0,0}, + {24487,24447,24444 ,12827,12787,12784 ,0,0,0}, {24485,24486,24446 ,12825,12826,12786 ,0,0,0}, + {24488,24489,24490 ,12828,12829,12830 ,0,0,0}, {24486,24443,24445 ,12826,12783,12785 ,0,0,0}, + {24447,24491,24448 ,12787,12831,12788 ,0,0,0}, {24443,24487,24444 ,12783,12827,12784 ,0,0,0}, + {24448,24489,24449 ,12788,12829,12789 ,0,0,0}, {24487,24491,24447 ,12827,12831,12787 ,0,0,0}, + {24449,24488,24450 ,12789,12828,12790 ,0,0,0}, {24491,24489,24448 ,12831,12829,12788 ,0,0,0}, + {24450,24492,24451 ,12790,12832,12791 ,0,0,0}, {24489,24488,24449 ,12829,12828,12789 ,0,0,0}, + {24451,24493,24411 ,12791,12833,12751 ,0,0,0}, {24488,24492,24450 ,12828,12832,12790 ,0,0,0}, + {24455,24411,24494 ,12795,12751,12834 ,0,0,0}, {24492,24493,24451 ,12832,12833,12791 ,0,0,0}, + {24454,24455,24495 ,12794,12795,12835 ,0,0,0}, {24493,24494,24411 ,12833,12834,12751 ,0,0,0}, + {24496,24497,24498 ,12836,12837,12838 ,0,0,0}, {24494,24495,24455 ,12834,12835,12795 ,0,0,0}, + {24453,24499,24456 ,12793,12839,12796 ,0,0,0}, {24495,24452,24454 ,12835,12792,12794 ,0,0,0}, + {24456,24500,24457 ,12796,12840,12797 ,0,0,0}, {24452,24499,24453 ,12792,12839,12793 ,0,0,0}, + {24457,24501,24254 ,12797,12841,12541 ,0,0,0}, {24499,24500,24456 ,12839,12840,12796 ,0,0,0}, + {24461,24254,24502 ,12801,12541,12842 ,0,0,0}, {24500,24501,24457 ,12840,12841,12797 ,0,0,0}, + {24460,24461,24503 ,12800,12801,12843 ,0,0,0}, {24501,24502,24254 ,12841,12842,12541 ,0,0,0}, + {24504,24505,24506 ,12844,12845,12846 ,0,0,0}, {24502,24503,24461 ,12842,12843,12801 ,0,0,0}, + {24459,24507,24462 ,12799,12847,12802 ,0,0,0}, {24503,24458,24460 ,12843,12798,12800 ,0,0,0}, + {24462,24508,24463 ,12802,12848,12803 ,0,0,0}, {24458,24507,24459 ,12798,12847,12799 ,0,0,0}, + {24463,24509,24464 ,12803,12849,12804 ,0,0,0}, {24507,24508,24462 ,12847,12848,12802 ,0,0,0}, + {24464,24510,24465 ,12804,12850,12805 ,0,0,0}, {24508,24509,24463 ,12848,12849,12803 ,0,0,0}, + {24419,24465,24511 ,12759,12805,12851 ,0,0,0}, {24509,24510,24464 ,12849,12850,12804 ,0,0,0}, + {24512,24513,24514 ,12852,12853,12854 ,0,0,0}, {24510,24511,24465 ,12850,12851,12805 ,0,0,0}, + {24421,24515,24466 ,12761,12855,12806 ,0,0,0}, {24511,24420,24419 ,12851,12760,12759 ,0,0,0}, + {24466,24513,24467 ,12806,12853,12807 ,0,0,0}, {24420,24515,24421 ,12760,12855,12761 ,0,0,0}, + {24467,24512,24468 ,12807,12852,12808 ,0,0,0}, {24515,24513,24466 ,12855,12853,12806 ,0,0,0}, + {24468,24516,24319 ,12808,12856,12640 ,0,0,0}, {24513,24512,24467 ,12853,12852,12807 ,0,0,0}, + {24472,24319,24517 ,12812,12640,12857 ,0,0,0}, {24512,24516,24468 ,12852,12856,12808 ,0,0,0}, + {24471,24472,24518 ,12811,12812,12858 ,0,0,0}, {24516,24517,24319 ,12856,12857,12640 ,0,0,0}, + {24519,24473,24470 ,12859,12813,12810 ,0,0,0}, {24517,24518,24472 ,12857,12858,12812 ,0,0,0}, + {24520,24521,24522 ,12860,12861,12862 ,0,0,0}, {24518,24469,24471 ,12858,12809,12811 ,0,0,0}, + {24473,24523,24474 ,12813,12863,12814 ,0,0,0}, {24469,24519,24470 ,12809,12859,12810 ,0,0,0}, + {24474,24521,24475 ,12814,12861,12815 ,0,0,0}, {24519,24523,24473 ,12859,12863,12813 ,0,0,0}, + {24475,24520,24476 ,12815,12860,12816 ,0,0,0}, {24523,24521,24474 ,12863,12861,12814 ,0,0,0}, + {24476,24524,24339 ,12816,12864,12672 ,0,0,0}, {24521,24520,24475 ,12861,12860,12815 ,0,0,0}, + {24339,24525,24340 ,12672,12865,12673 ,0,0,0}, {24520,24524,24476 ,12860,12864,12816 ,0,0,0}, + {24340,24526,24354 ,12673,12866,12687 ,0,0,0}, {24524,24525,24339 ,12864,12865,12672 ,0,0,0}, + {24354,24478,24336 ,12687,12818,12669 ,0,0,0}, {24526,24340,24525 ,12866,12673,12865 ,0,0,0}, + {24343,24337,24527 ,12676,12670,12867 ,0,0,0}, {24354,24526,24478 ,12687,12866,12818 ,0,0,0}, + {24435,24528,24436 ,12775,12868,12776 ,0,0,0}, {24437,24338,24435 ,12777,12671,12775 ,0,0,0}, + {24348,24336,24338 ,12681,12669,12671 ,0,0,0}, {24338,24528,24435 ,12671,12868,12775 ,0,0,0}, + {24479,24435,24434 ,12819,12775,12774 ,0,0,0}, {24295,24300,24440 ,12600,12606,12780 ,0,0,0}, + {24280,24279,24301 ,12583,12582,12607 ,0,0,0}, {24481,24529,24483 ,12821,12869,12823 ,0,0,0}, + {24440,24482,24289 ,12780,12822,12593 ,0,0,0}, {24279,24530,24482 ,12582,12870,12822 ,0,0,0}, + {24484,24483,24531 ,12824,12823,12871 ,0,0,0}, {24481,24530,24529 ,12821,12870,12869 ,0,0,0}, + {24485,24484,24532 ,12825,12824,12872 ,0,0,0}, {24483,24529,24531 ,12823,12869,12871 ,0,0,0}, + {24486,24485,24533 ,12826,12825,12873 ,0,0,0}, {24484,24531,24532 ,12824,12871,12872 ,0,0,0}, + {24443,24486,24534 ,12783,12826,12874 ,0,0,0}, {24485,24532,24533 ,12825,12872,12873 ,0,0,0}, + {24487,24443,24535 ,12827,12783,12875 ,0,0,0}, {24486,24533,24534 ,12826,12873,12874 ,0,0,0}, + {24491,24487,24536 ,12831,12827,12876 ,0,0,0}, {24443,24534,24535 ,12783,12874,12875 ,0,0,0}, + {24489,24491,24537 ,12829,12831,12877 ,0,0,0}, {24535,24536,24487 ,12875,12876,12827 ,0,0,0}, + {24538,24539,24540 ,12878,12879,12880 ,0,0,0}, {24536,24537,24491 ,12876,12877,12831 ,0,0,0}, + {24488,24541,24492 ,12828,12881,12832 ,0,0,0}, {24537,24490,24489 ,12877,12830,12829 ,0,0,0}, + {24492,24540,24493 ,12832,12880,12833 ,0,0,0}, {24490,24541,24488 ,12830,12881,12828 ,0,0,0}, + {24493,24542,24494 ,12833,12882,12834 ,0,0,0}, {24541,24540,24492 ,12881,12880,12832 ,0,0,0}, + {24495,24494,24543 ,12835,12834,12883 ,0,0,0}, {24540,24542,24493 ,12880,12882,12833 ,0,0,0}, + {24452,24495,24544 ,12792,12835,12884 ,0,0,0}, {24494,24542,24543 ,12834,12882,12883 ,0,0,0}, + {24499,24452,24545 ,12839,12792,12885 ,0,0,0}, {24495,24543,24544 ,12835,12883,12884 ,0,0,0}, + {24500,24499,24546 ,12840,12839,12886 ,0,0,0}, {24544,24545,24452 ,12884,12885,12792 ,0,0,0}, + {24500,24547,24501 ,12840,12887,12841 ,0,0,0}, {24545,24546,24499 ,12885,12886,12839 ,0,0,0}, + {24501,24497,24502 ,12841,12837,12842 ,0,0,0}, {24546,24547,24500 ,12886,12887,12840 ,0,0,0}, + {24503,24502,24548 ,12843,12842,12888 ,0,0,0}, {24547,24497,24501 ,12887,12837,12841 ,0,0,0}, + {24458,24503,24549 ,12798,12843,12889 ,0,0,0}, {24502,24497,24548 ,12842,12837,12888 ,0,0,0}, + {24507,24458,24550 ,12847,12798,12890 ,0,0,0}, {24503,24548,24549 ,12843,12888,12889 ,0,0,0}, + {24508,24507,24551 ,12848,12847,12891 ,0,0,0}, {24549,24550,24458 ,12889,12890,12798 ,0,0,0}, + {24508,24552,24509 ,12848,12892,12849 ,0,0,0}, {24550,24551,24507 ,12890,12891,12847 ,0,0,0}, + {24509,24505,24510 ,12849,12845,12850 ,0,0,0}, {24551,24552,24508 ,12891,12892,12848 ,0,0,0}, + {24511,24510,24553 ,12851,12850,12893 ,0,0,0}, {24552,24505,24509 ,12892,12845,12849 ,0,0,0}, + {24420,24511,24554 ,12760,12851,12894 ,0,0,0}, {24510,24505,24553 ,12850,12845,12893 ,0,0,0}, + {24515,24420,24555 ,12855,12760,12895 ,0,0,0}, {24511,24553,24554 ,12851,12893,12894 ,0,0,0}, + {24513,24515,24556 ,12853,12855,12896 ,0,0,0}, {24554,24555,24420 ,12894,12895,12760 ,0,0,0}, + {24557,24558,24559 ,12897,12898,12899 ,0,0,0}, {24555,24556,24515 ,12895,12896,12855 ,0,0,0}, + {24512,24560,24516 ,12852,12900,12856 ,0,0,0}, {24556,24514,24513 ,12896,12854,12853 ,0,0,0}, + {24516,24559,24517 ,12856,12899,12857 ,0,0,0}, {24514,24560,24512 ,12854,12900,12852 ,0,0,0}, + {24518,24517,24561 ,12858,12857,12901 ,0,0,0}, {24560,24559,24516 ,12900,12899,12856 ,0,0,0}, + {24469,24518,24562 ,12809,12858,12902 ,0,0,0}, {24517,24559,24561 ,12857,12899,12901 ,0,0,0}, + {24519,24469,24563 ,12859,12809,12903 ,0,0,0}, {24518,24561,24562 ,12858,12901,12902 ,0,0,0}, + {24523,24519,24564 ,12863,12859,12904 ,0,0,0}, {24469,24562,24563 ,12809,12902,12903 ,0,0,0}, + {24521,24523,24565 ,12861,12863,12905 ,0,0,0}, {24563,24564,24519 ,12903,12904,12859 ,0,0,0}, + {24566,24524,24520 ,12906,12864,12860 ,0,0,0}, {24564,24565,24523 ,12904,12905,12863 ,0,0,0}, + {24567,24568,24569 ,12907,12908,12909 ,0,0,0}, {24565,24522,24521 ,12905,12862,12861 ,0,0,0}, + {24524,24570,24525 ,12864,12910,12865 ,0,0,0}, {24522,24566,24520 ,12862,12906,12860 ,0,0,0}, + {24525,24569,24526 ,12865,12909,12866 ,0,0,0}, {24566,24570,24524 ,12906,12910,12864 ,0,0,0}, + {24526,24571,24478 ,12866,12911,12818 ,0,0,0}, {24570,24569,24525 ,12910,12909,12865 ,0,0,0}, + {24478,24527,24337 ,12818,12867,12670 ,0,0,0}, {24569,24571,24526 ,12909,12911,12866 ,0,0,0}, + {24337,24343,24528 ,12670,12676,12868 ,0,0,0}, {24478,24571,24527 ,12818,12911,12867 ,0,0,0}, + {24572,24436,24347 ,12912,12776,12680 ,0,0,0}, {24573,24434,24436 ,12913,12774,12776 ,0,0,0}, + {24338,24337,24528 ,12671,12670,12868 ,0,0,0}, {24528,24477,24436 ,12868,12817,12776 ,0,0,0}, + {24572,24573,24436 ,12912,12913,12776 ,0,0,0}, {24300,24279,24482 ,12606,12582,12822 ,0,0,0}, + {24574,24278,24280 ,12914,12581,12583 ,0,0,0}, {24531,24529,24284 ,12871,12869,12587 ,0,0,0}, + {24482,24530,24481 ,12822,12870,12821 ,0,0,0}, {24278,24575,24530 ,12581,12915,12870 ,0,0,0}, + {24532,24531,24576 ,12872,12871,12916 ,0,0,0}, {24529,24575,24284 ,12869,12915,12587 ,0,0,0}, + {24577,24576,24578 ,12917,12916,12918 ,0,0,0}, {24531,24284,24576 ,12871,12587,12916 ,0,0,0}, + {24577,24579,24533 ,12917,12919,12873 ,0,0,0}, {24533,24532,24577 ,12873,12872,12917 ,0,0,0}, + {24579,24580,24534 ,12919,12920,12874 ,0,0,0}, {24534,24533,24579 ,12874,12873,12919 ,0,0,0}, + {24580,24581,24535 ,12920,12921,12875 ,0,0,0}, {24535,24534,24580 ,12875,12874,12920 ,0,0,0}, + {24581,24582,24536 ,12921,12922,12876 ,0,0,0}, {24536,24535,24581 ,12876,12875,12921 ,0,0,0}, + {24582,24583,24537 ,12922,12923,12877 ,0,0,0}, {24537,24536,24582 ,12877,12876,12922 ,0,0,0}, + {24583,24584,24490 ,12923,12924,12830 ,0,0,0}, {24490,24537,24583 ,12830,12877,12923 ,0,0,0}, + {24584,24538,24541 ,12924,12878,12881 ,0,0,0}, {24490,24584,24541 ,12830,12924,12881 ,0,0,0}, + {23894,24585,24586 ,12925,12926,12927 ,0,0,0}, {24541,24538,24540 ,12881,12878,12880 ,0,0,0}, + {24542,24587,24543 ,12882,12928,12883 ,0,0,0}, {24540,24539,24542 ,12880,12879,12882 ,0,0,0}, + {24588,24587,24586 ,12929,12928,12927 ,0,0,0}, {24539,24587,24542 ,12879,12928,12882 ,0,0,0}, + {24588,24589,24544 ,12929,12930,12884 ,0,0,0}, {24544,24543,24588 ,12884,12883,12929 ,0,0,0}, + {24589,24590,24545 ,12930,12931,12885 ,0,0,0}, {24545,24544,24589 ,12885,12884,12930 ,0,0,0}, + {24590,24591,24546 ,12931,12932,12886 ,0,0,0}, {24546,24545,24590 ,12886,12885,12931 ,0,0,0}, + {24591,24498,24547 ,12932,12838,12887 ,0,0,0}, {24546,24591,24547 ,12886,12932,12887 ,0,0,0}, + {24592,24593,24594 ,12933,12934,12935 ,0,0,0}, {24547,24498,24497 ,12887,12838,12837 ,0,0,0}, + {24496,24593,24548 ,12836,12934,12888 ,0,0,0}, {24497,24496,24548 ,12837,12836,12888 ,0,0,0}, + {24593,24595,24549 ,12934,12936,12889 ,0,0,0}, {24549,24548,24593 ,12889,12888,12934 ,0,0,0}, + {24595,24596,24550 ,12936,12937,12890 ,0,0,0}, {24550,24549,24595 ,12890,12889,12936 ,0,0,0}, + {24596,24597,24551 ,12937,12938,12891 ,0,0,0}, {24551,24550,24596 ,12891,12890,12937 ,0,0,0}, + {24597,24506,24552 ,12938,12846,12892 ,0,0,0}, {24551,24597,24552 ,12891,12938,12892 ,0,0,0}, + {24598,23885,24599 ,12939,12940,12941 ,0,0,0}, {24552,24506,24505 ,12892,12846,12845 ,0,0,0}, + {24554,24553,24600 ,12894,12893,12942 ,0,0,0}, {24505,24504,24553 ,12845,12844,12893 ,0,0,0}, + {24601,24600,24598 ,12943,12942,12939 ,0,0,0}, {24553,24504,24600 ,12893,12844,12942 ,0,0,0}, + {24601,24602,24555 ,12943,12944,12895 ,0,0,0}, {24555,24554,24601 ,12895,12894,12943 ,0,0,0}, + {24602,24603,24556 ,12944,12945,12896 ,0,0,0}, {24556,24555,24602 ,12896,12895,12944 ,0,0,0}, + {24603,24604,24514 ,12945,12946,12854 ,0,0,0}, {24514,24556,24603 ,12854,12896,12945 ,0,0,0}, + {24604,24557,24560 ,12946,12897,12900 ,0,0,0}, {24514,24604,24560 ,12854,12946,12900 ,0,0,0}, + {24605,24606,24607 ,12947,12948,12949 ,0,0,0}, {24560,24557,24559 ,12900,12897,12899 ,0,0,0}, + {24558,24606,24561 ,12898,12948,12901 ,0,0,0}, {24559,24558,24561 ,12899,12898,12901 ,0,0,0}, + {24606,24608,24562 ,12948,12950,12902 ,0,0,0}, {24562,24561,24606 ,12902,12901,12948 ,0,0,0}, + {24608,24609,24563 ,12950,12951,12903 ,0,0,0}, {24563,24562,24608 ,12903,12902,12950 ,0,0,0}, + {24609,24610,24564 ,12951,12952,12904 ,0,0,0}, {24564,24563,24609 ,12904,12903,12951 ,0,0,0}, + {24610,24611,24565 ,12952,12953,12905 ,0,0,0}, {24565,24564,24610 ,12905,12904,12952 ,0,0,0}, + {24611,24612,24522 ,12953,12954,12862 ,0,0,0}, {24522,24565,24611 ,12862,12905,12953 ,0,0,0}, + {24612,24613,24566 ,12954,12955,12906 ,0,0,0}, {24566,24522,24612 ,12906,12862,12954 ,0,0,0}, + {24613,24567,24570 ,12955,12907,12910 ,0,0,0}, {24566,24613,24570 ,12906,12955,12910 ,0,0,0}, + {24571,24568,24614 ,12911,12908,12956 ,0,0,0}, {24570,24567,24569 ,12910,12907,12909 ,0,0,0}, + {24344,24343,24527 ,12677,12676,12867 ,0,0,0}, {24569,24568,24571 ,12909,12908,12911 ,0,0,0}, + {24342,24477,24343 ,12675,12817,12676 ,0,0,0}, {24571,24614,24527 ,12911,12956,12867 ,0,0,0}, + {24615,24351,24345 ,12957,12684,12678 ,0,0,0}, {24614,24344,24527 ,12956,12677,12867 ,0,0,0}, + {24342,24616,24617 ,12675,12958,12959 ,0,0,0}, {24618,24572,24347 ,12960,12912,12680 ,0,0,0}, + {24528,24343,24477 ,12868,12676,12817 ,0,0,0}, {24347,24477,24617 ,12680,12817,12959 ,0,0,0}, + {24346,24618,24347 ,12679,12960,12680 ,0,0,0}, {24279,24278,24530 ,12582,12581,12870 ,0,0,0}, + {24574,24281,24277 ,12914,12584,12580 ,0,0,0}, {24575,24277,24282 ,12915,12580,12585 ,0,0,0}, + {24530,24575,24529 ,12870,12915,12869 ,0,0,0}, {24284,24575,24282 ,12587,12915,12585 ,0,0,0}, + {24283,24578,24576 ,12586,12918,12916 ,0,0,0}, {24576,24284,24283 ,12916,12587,12586 ,0,0,0}, + {24578,24619,24577 ,12918,12961,12917 ,0,0,0}, {24620,24579,24619 ,12962,12919,12961 ,0,0,0}, + {24532,24576,24577 ,12872,12916,12917 ,0,0,0}, {24579,24577,24619 ,12919,12917,12961 ,0,0,0}, + {24621,24580,24620 ,12963,12920,12962 ,0,0,0}, {24580,24579,24620 ,12920,12919,12962 ,0,0,0}, + {24622,24581,24621 ,12964,12921,12963 ,0,0,0}, {24581,24580,24621 ,12921,12920,12963 ,0,0,0}, + {24623,24582,24622 ,12965,12922,12964 ,0,0,0}, {24582,24581,24622 ,12922,12921,12964 ,0,0,0}, + {24624,24583,24623 ,12966,12923,12965 ,0,0,0}, {24583,24582,24623 ,12923,12922,12965 ,0,0,0}, + {24625,24584,24624 ,12967,12924,12966 ,0,0,0}, {24584,24583,24624 ,12924,12923,12966 ,0,0,0}, + {24626,24538,24625 ,12968,12878,12967 ,0,0,0}, {24538,24584,24625 ,12878,12924,12967 ,0,0,0}, + {24627,24539,24626 ,12969,12879,12968 ,0,0,0}, {24539,24538,24626 ,12879,12878,12968 ,0,0,0}, + {24586,24587,24627 ,12927,12928,12969 ,0,0,0}, {24539,24627,24587 ,12879,12969,12928 ,0,0,0}, + {24586,24585,24588 ,12927,12926,12929 ,0,0,0}, {24628,24589,24585 ,12970,12930,12926 ,0,0,0}, + {24543,24587,24588 ,12883,12928,12929 ,0,0,0}, {24589,24588,24585 ,12930,12929,12926 ,0,0,0}, + {24629,24590,24628 ,12971,12931,12970 ,0,0,0}, {24590,24589,24628 ,12931,12930,12970 ,0,0,0}, + {24630,24591,24629 ,12972,12932,12971 ,0,0,0}, {24591,24590,24629 ,12932,12931,12971 ,0,0,0}, + {24631,24498,24630 ,12973,12838,12972 ,0,0,0}, {24498,24591,24630 ,12838,12932,12972 ,0,0,0}, + {24594,24496,24631 ,12935,12836,12973 ,0,0,0}, {24496,24498,24631 ,12836,12838,12973 ,0,0,0}, + {24594,23809,24592 ,12935,12974,12933 ,0,0,0}, {24496,24594,24593 ,12836,12935,12934 ,0,0,0}, + {24632,24595,24592 ,12975,12936,12933 ,0,0,0}, {24595,24593,24592 ,12936,12934,12933 ,0,0,0}, + {24633,24596,24632 ,12976,12937,12975 ,0,0,0}, {24596,24595,24632 ,12937,12936,12975 ,0,0,0}, + {24634,24597,24633 ,12977,12938,12976 ,0,0,0}, {24597,24596,24633 ,12938,12937,12976 ,0,0,0}, + {24635,24506,24634 ,12978,12846,12977 ,0,0,0}, {24506,24597,24634 ,12846,12938,12977 ,0,0,0}, + {24636,24504,24635 ,12979,12844,12978 ,0,0,0}, {24504,24506,24635 ,12844,12846,12978 ,0,0,0}, + {24598,24600,24636 ,12939,12942,12979 ,0,0,0}, {24504,24636,24600 ,12844,12979,12942 ,0,0,0}, + {24598,24599,24601 ,12939,12941,12943 ,0,0,0}, {24637,24602,24599 ,12980,12944,12941 ,0,0,0}, + {24554,24600,24601 ,12894,12942,12943 ,0,0,0}, {24602,24601,24599 ,12944,12943,12941 ,0,0,0}, + {24638,24603,24637 ,12981,12945,12980 ,0,0,0}, {24603,24602,24637 ,12945,12944,12980 ,0,0,0}, + {24639,24604,24638 ,12982,12946,12981 ,0,0,0}, {24604,24603,24638 ,12946,12945,12981 ,0,0,0}, + {24640,24557,24639 ,12983,12897,12982 ,0,0,0}, {24557,24604,24639 ,12897,12946,12982 ,0,0,0}, + {24607,24558,24640 ,12949,12898,12983 ,0,0,0}, {24558,24557,24640 ,12898,12897,12983 ,0,0,0}, + {24607,23831,24605 ,12949,12984,12947 ,0,0,0}, {24558,24607,24606 ,12898,12949,12948 ,0,0,0}, + {24641,24608,24605 ,12985,12950,12947 ,0,0,0}, {24608,24606,24605 ,12950,12948,12947 ,0,0,0}, + {24642,24609,24641 ,12986,12951,12985 ,0,0,0}, {24609,24608,24641 ,12951,12950,12985 ,0,0,0}, + {24643,24610,24642 ,12987,12952,12986 ,0,0,0}, {24610,24609,24642 ,12952,12951,12986 ,0,0,0}, + {24644,24611,24643 ,12988,12953,12987 ,0,0,0}, {24611,24610,24643 ,12953,12952,12987 ,0,0,0}, + {24645,24612,24644 ,12989,12954,12988 ,0,0,0}, {24612,24611,24644 ,12954,12953,12988 ,0,0,0}, + {24646,24613,24645 ,12990,12955,12989 ,0,0,0}, {24613,24612,24645 ,12955,12954,12989 ,0,0,0}, + {24647,24567,24646 ,12991,12907,12990 ,0,0,0}, {24567,24613,24646 ,12907,12955,12990 ,0,0,0}, + {24648,24568,24647 ,12992,12908,12991 ,0,0,0}, {24568,24567,24647 ,12908,12907,12991 ,0,0,0}, + {24649,24614,24648 ,12993,12956,12992 ,0,0,0}, {24614,24568,24648 ,12956,12908,12992 ,0,0,0}, + {24650,24344,24649 ,12994,12677,12993 ,0,0,0}, {24344,24614,24649 ,12677,12956,12993 ,0,0,0}, + {24650,24616,24342 ,12994,12958,12675 ,0,0,0}, {24342,24344,24650 ,12675,12677,12994 ,0,0,0}, + {24616,24615,24617 ,12958,12957,12959 ,0,0,0}, {24347,24617,24345 ,12680,12959,12678 ,0,0,0}, + {24477,24342,24617 ,12817,12675,12959 ,0,0,0}, {24615,24345,24617 ,12957,12678,12959 ,0,0,0}, + {24346,24345,24350 ,12679,12678,12683 ,0,0,0}, {24575,24278,24277 ,12915,12581,12580 ,0,0,0}, + {24277,24278,24574 ,12580,12581,12914 ,0,0,0}, {23903,23901,24282 ,12740,12995,12585 ,0,0,0}, + {24282,23901,24283 ,12585,12995,12586 ,0,0,0}, {23901,23769,24283 ,12995,12996,12586 ,0,0,0}, + {24283,23769,24578 ,12586,12996,12918 ,0,0,0}, {23769,23768,24578 ,12996,12997,12918 ,0,0,0}, + {24578,23768,24619 ,12918,12997,12961 ,0,0,0}, {23768,23789,24619 ,12997,12998,12961 ,0,0,0}, + {24619,23789,24620 ,12961,12998,12962 ,0,0,0}, {23789,23759,24620 ,12998,12999,12962 ,0,0,0}, + {24620,23759,24621 ,12962,12999,12963 ,0,0,0}, {23759,23794,24621 ,12999,13000,12963 ,0,0,0}, + {24621,23794,24622 ,12963,13000,12964 ,0,0,0}, {23794,23791,24622 ,13000,13001,12964 ,0,0,0}, + {24622,23791,24623 ,12964,13001,12965 ,0,0,0}, {23791,23796,24623 ,13001,13002,12965 ,0,0,0}, + {23796,23798,24624 ,13002,13003,12966 ,0,0,0}, {23796,24624,24623 ,13002,12966,12965 ,0,0,0}, + {23798,23764,24625 ,13003,13004,12967 ,0,0,0}, {23798,24625,24624 ,13003,12967,12966 ,0,0,0}, + {23764,23763,24626 ,13004,13005,12968 ,0,0,0}, {23764,24626,24625 ,13004,12968,12967 ,0,0,0}, + {23763,23800,24627 ,13005,13006,12969 ,0,0,0}, {23763,24627,24626 ,13005,12969,12968 ,0,0,0}, + {23800,23895,24586 ,13006,13007,12927 ,0,0,0}, {23800,24586,24627 ,13006,12927,12969 ,0,0,0}, + {23894,24586,23895 ,12925,12927,13007 ,0,0,0}, {23894,23803,24585 ,12925,13008,12926 ,0,0,0}, + {24585,23803,24628 ,12926,13008,12970 ,0,0,0}, {23803,23808,24628 ,13008,13009,12970 ,0,0,0}, + {24628,23808,24629 ,12970,13009,12971 ,0,0,0}, {23808,23806,24629 ,13009,13010,12971 ,0,0,0}, + {23806,23805,24630 ,13010,13011,12972 ,0,0,0}, {23806,24630,24629 ,13010,12972,12971 ,0,0,0}, + {23805,23893,24631 ,13011,13012,12973 ,0,0,0}, {23805,24631,24630 ,13011,12973,12972 ,0,0,0}, + {23893,23809,24594 ,13012,12974,12935 ,0,0,0}, {23893,24594,24631 ,13012,12935,12973 ,0,0,0}, + {23809,23892,24592 ,12974,13013,12933 ,0,0,0}, {23892,23888,24592 ,13013,13014,12933 ,0,0,0}, + {24592,23888,24632 ,12933,13014,12975 ,0,0,0}, {23888,23813,24632 ,13014,13015,12975 ,0,0,0}, + {24632,23813,24633 ,12975,13015,12976 ,0,0,0}, {23813,23815,24633 ,13015,13016,12976 ,0,0,0}, + {23815,23820,24634 ,13016,13017,12977 ,0,0,0}, {23815,24634,24633 ,13016,12977,12976 ,0,0,0}, + {23820,23818,24635 ,13017,13018,12978 ,0,0,0}, {23820,24635,24634 ,13017,12978,12977 ,0,0,0}, + {23818,23817,24636 ,13018,13019,12979 ,0,0,0}, {23818,24636,24635 ,13018,12979,12978 ,0,0,0}, + {23817,23886,24598 ,13019,13020,12939 ,0,0,0}, {23817,24598,24636 ,13019,12939,12979 ,0,0,0}, + {23885,24598,23886 ,12940,12939,13020 ,0,0,0}, {23885,23822,24599 ,12940,13021,12941 ,0,0,0}, + {24599,23822,24637 ,12941,13021,12980 ,0,0,0}, {23822,23829,24637 ,13021,13022,12980 ,0,0,0}, + {23829,23828,24638 ,13022,13023,12981 ,0,0,0}, {23829,24638,24637 ,13022,12981,12980 ,0,0,0}, + {23828,23827,24639 ,13023,13024,12982 ,0,0,0}, {23828,24639,24638 ,13023,12982,12981 ,0,0,0}, + {23827,23882,24640 ,13024,13025,12983 ,0,0,0}, {23827,24640,24639 ,13024,12983,12982 ,0,0,0}, + {23882,23831,24607 ,13025,12984,12949 ,0,0,0}, {23882,24607,24640 ,13025,12949,12983 ,0,0,0}, + {23831,23830,24605 ,12984,13026,12947 ,0,0,0}, {23830,23836,24605 ,13026,13027,12947 ,0,0,0}, + {24605,23836,24641 ,12947,13027,12985 ,0,0,0}, {23836,23835,24641 ,13027,13028,12985 ,0,0,0}, + {24641,23835,24642 ,12985,13028,12986 ,0,0,0}, {23835,23840,24642 ,13028,13029,12986 ,0,0,0}, + {24642,23840,24643 ,12986,13029,12987 ,0,0,0}, {23840,23838,24643 ,13029,13030,12987 ,0,0,0}, + {23838,23845,24644 ,13030,13031,12988 ,0,0,0}, {23838,24644,24643 ,13030,12988,12987 ,0,0,0}, + {23845,23842,24645 ,13031,13032,12989 ,0,0,0}, {23845,24645,24644 ,13031,12989,12988 ,0,0,0}, + {23842,23849,24646 ,13032,13033,12990 ,0,0,0}, {23842,24646,24645 ,13032,12990,12989 ,0,0,0}, + {23849,23846,24647 ,13033,13034,12991 ,0,0,0}, {23849,24647,24646 ,13033,12991,12990 ,0,0,0}, + {23846,23851,24648 ,13034,13035,12992 ,0,0,0}, {23846,24648,24647 ,13034,12992,12991 ,0,0,0}, + {23851,23850,24649 ,13035,13036,12993 ,0,0,0}, {23851,24649,24648 ,13035,12993,12992 ,0,0,0}, + {23850,23864,24650 ,13036,13037,12994 ,0,0,0}, {23850,24650,24649 ,13036,12994,12993 ,0,0,0}, + {23864,23863,24616 ,13037,13038,12958 ,0,0,0}, {23864,24616,24650 ,13037,12958,12994 ,0,0,0}, + {23863,23857,24615 ,13038,13039,12957 ,0,0,0}, {23863,24615,24616 ,13038,12957,12958 ,0,0,0}, + {23857,23859,24351 ,13039,12690,12684 ,0,0,0}, {23857,24351,24615 ,13039,12684,12957 ,0,0,0}, + {24352,24351,23859 ,12685,12684,12690 ,0,0,0}, {24651,24652,24653 ,13040,13041,13042 ,0,0,0}, + {24654,23728,23727 ,13043,13044,13045 ,0,0,0}, {24654,24655,23728 ,13043,13046,13044 ,0,0,0}, + {24656,23726,24657 ,13047,13048,13049 ,0,0,0}, {23727,24656,24654 ,13045,13047,13043 ,0,0,0}, + {24656,23727,23726 ,13047,13045,13048 ,0,0,0}, {23724,24658,23725 ,13050,13051,13052 ,0,0,0}, + {23639,23725,24658 ,13053,13052,13051 ,0,0,0}, {23639,24658,24657 ,13053,13051,13049 ,0,0,0}, + {23724,23723,24659 ,13050,13054,13055 ,0,0,0}, {23639,24657,23726 ,13053,13049,13048 ,0,0,0}, + {24658,23724,24659 ,13051,13050,13055 ,0,0,0}, {23729,23728,24655 ,13056,13044,13046 ,0,0,0}, + {24660,23722,24661 ,13057,13058,13059 ,0,0,0}, {24660,23723,23722 ,13057,13054,13058 ,0,0,0}, + {24662,24663,24664 ,13060,13061,13062 ,0,0,0}, {24665,24661,23721 ,13063,13059,13064 ,0,0,0}, + {23722,23721,24661 ,13058,13064,13059 ,0,0,0}, {24666,24665,23720 ,13065,13063,13066 ,0,0,0}, + {24666,23719,24667 ,13065,13067,13068 ,0,0,0}, {23720,23719,24666 ,13066,13067,13065 ,0,0,0}, + {24667,23719,23718 ,13068,13067,13069 ,0,0,0}, {23721,23720,24665 ,13064,13066,13063 ,0,0,0}, + {24659,23723,24660 ,13055,13054,13057 ,0,0,0}, {23717,23716,24668 ,13070,13071,13072 ,0,0,0}, + {23717,24669,23718 ,13070,13073,13069 ,0,0,0}, {23715,24670,23716 ,13074,13075,13071 ,0,0,0}, + {23717,24668,24669 ,13070,13072,13073 ,0,0,0}, {23715,23714,24671 ,13074,13076,13077 ,0,0,0}, + {24671,24670,23715 ,13077,13075,13074 ,0,0,0}, {24352,23410,23407 ,13078,11682,13079 ,0,0,0}, + {23716,24670,24668 ,13071,13075,13072 ,0,0,0}, {24671,23714,24672 ,13077,13076,13080 ,0,0,0}, + {24673,24352,23407 ,13081,13078,13079 ,0,0,0}, {24674,24675,24671 ,13082,13083,13077 ,0,0,0}, + {24676,24677,24678 ,13084,13085,13086 ,0,0,0}, {24679,24680,24681 ,13087,13088,13089 ,0,0,0}, + {24682,24683,24572 ,13090,13091,13092 ,0,0,0}, {24682,24346,24684 ,13090,13093,13094 ,0,0,0}, + {24672,23714,23713 ,13080,13076,13095 ,0,0,0}, {24673,23407,24678 ,13081,13079,13086 ,0,0,0}, + {24675,24685,24681 ,13083,13096,13089 ,0,0,0}, {24573,24683,24686 ,13097,13091,13098 ,0,0,0}, + {24687,24400,24688 ,13099,13100,13101 ,0,0,0}, {23276,24689,23713 ,13102,13103,13095 ,0,0,0}, + {24690,24479,24686 ,13104,13105,13098 ,0,0,0}, {24480,24479,24690 ,13106,13105,13104 ,0,0,0}, + {24573,24686,24434 ,13097,13098,13107 ,0,0,0}, {23281,24361,23279 ,11553,13108,13109 ,0,0,0}, + {23276,24687,24689 ,13102,13099,13103 ,0,0,0}, {24400,24687,24361 ,13100,13099,13108 ,0,0,0}, + {24687,23279,24361 ,13099,13109,13108 ,0,0,0}, {24685,24691,24681 ,13096,13110,13089 ,0,0,0}, + {24669,24667,23718 ,13073,13068,13069 ,0,0,0}, {24692,23729,24655 ,13111,13056,13046 ,0,0,0}, + {23730,24692,24693 ,13112,13111,13113 ,0,0,0}, {24692,23730,23729 ,13111,13112,13056 ,0,0,0}, + {24694,23689,24693 ,13114,13115,13113 ,0,0,0}, {23730,24693,23689 ,13112,13113,13115 ,0,0,0}, + {23731,24694,23732 ,13116,13114,13117 ,0,0,0}, {23731,23689,24694 ,13116,13115,13114 ,0,0,0}, + {23733,23732,24695 ,13118,13117,13119 ,0,0,0}, {24694,24695,23732 ,13114,13119,13117 ,0,0,0}, + {24696,23734,23733 ,13120,13121,13118 ,0,0,0}, {23733,24695,24696 ,13118,13119,13120 ,0,0,0}, + {24696,24697,23734 ,13120,13122,13121 ,0,0,0}, {23734,24697,23735 ,13121,13122,13123 ,0,0,0}, + {23735,24697,24698 ,13123,13122,13124 ,0,0,0}, {24699,24700,24701 ,13125,13126,13127 ,0,0,0}, + {24702,23736,24698 ,13128,13129,13124 ,0,0,0}, {23735,24698,23736 ,13123,13124,13129 ,0,0,0}, + {24702,24703,23737 ,13128,13130,13131 ,0,0,0}, {23737,23736,24702 ,13131,13129,13128 ,0,0,0}, + {23654,23738,24703 ,13132,13133,13130 ,0,0,0}, {24703,23738,23737 ,13130,13133,13131 ,0,0,0}, + {24704,23739,23654 ,13134,13135,13132 ,0,0,0}, {23654,24703,24704 ,13132,13130,13134 ,0,0,0}, + {23739,24705,23740 ,13135,13136,13137 ,0,0,0}, {24705,23739,24704 ,13136,13135,13134 ,0,0,0}, + {23741,23740,24706 ,13138,13137,13139 ,0,0,0}, {24705,24706,23740 ,13136,13139,13137 ,0,0,0}, + {24707,23741,24706 ,13140,13138,13139 ,0,0,0}, {24707,23742,23741 ,13140,13141,13138 ,0,0,0}, + {24707,24708,23742 ,13140,13142,13141 ,0,0,0}, {24709,24710,24711 ,13143,13144,13145 ,0,0,0}, + {23743,24708,24712 ,13146,13142,13147 ,0,0,0}, {24708,23743,23742 ,13142,13146,13141 ,0,0,0}, + {24713,23700,24712 ,13148,13149,13147 ,0,0,0}, {23743,24712,23700 ,13146,13147,13149 ,0,0,0}, + {23744,24713,23745 ,13150,13148,13151 ,0,0,0}, {23744,23700,24713 ,13150,13149,13148 ,0,0,0}, + {23746,23745,24714 ,13152,13151,13153 ,0,0,0}, {24713,24714,23745 ,13148,13153,13151 ,0,0,0}, + {24715,23747,23746 ,13154,13155,13152 ,0,0,0}, {23746,24714,24715 ,13152,13153,13154 ,0,0,0}, + {23747,24716,23748 ,13155,13156,13157 ,0,0,0}, {24716,23747,24715 ,13156,13155,13154 ,0,0,0}, + {23749,23748,24717 ,13158,13157,13159 ,0,0,0}, {24716,24717,23748 ,13156,13159,13157 ,0,0,0}, + {24718,23749,24717 ,13160,13158,13159 ,0,0,0}, {24718,23750,23749 ,13160,13161,13158 ,0,0,0}, + {24718,24719,23750 ,13160,13162,13161 ,0,0,0}, {24720,24721,24722 ,13163,13164,13165 ,0,0,0}, + {23751,24719,24721 ,13166,13162,13164 ,0,0,0}, {24719,23751,23750 ,13162,13166,13161 ,0,0,0}, + {24723,23752,24721 ,13167,13168,13164 ,0,0,0}, {23751,24721,23752 ,13166,13164,13168 ,0,0,0}, + {24724,24725,24726 ,13169,13170,13171 ,0,0,0}, {23753,23752,24723 ,13172,13168,13167 ,0,0,0}, + {24727,24728,24729 ,13173,13174,13175 ,0,0,0}, {24730,24731,24732 ,13176,13177,13178 ,0,0,0}, + {24733,24727,24734 ,13179,13173,13180 ,0,0,0}, {24735,24736,24737 ,13181,13182,13183 ,0,0,0}, + {24738,24739,24740 ,13184,13185,13186 ,0,0,0}, {24735,24741,24742 ,13181,13187,13188 ,0,0,0}, + {24743,24744,24745 ,13189,13190,13191 ,0,0,0}, {24742,24741,24746 ,13188,13187,13192 ,0,0,0}, + {23754,23753,24747 ,13193,13172,13194 ,0,0,0}, {23344,24746,24741 ,11616,13192,13187 ,0,0,0}, + {24748,24749,24750 ,13195,13196,13197 ,0,0,0}, {23753,24723,24747 ,13172,13167,13194 ,0,0,0}, + {23754,24732,23755 ,13193,13178,13198 ,0,0,0}, {24720,24723,24721 ,13163,13167,13164 ,0,0,0}, + {23756,23755,24749 ,13199,13198,13196 ,0,0,0}, {24732,24749,23755 ,13178,13196,13198 ,0,0,0}, + {23757,24748,23758 ,13200,13195,13201 ,0,0,0}, {23756,24749,24748 ,13199,13196,13195 ,0,0,0}, + {23758,24751,23378 ,13201,13202,11650 ,0,0,0}, {24748,24751,23758 ,13195,13202,13201 ,0,0,0}, + {23279,24687,23276 ,13109,13099,13102 ,0,0,0}, {24438,24688,24400 ,13203,13101,13100 ,0,0,0}, + {24438,24690,24688 ,13203,13104,13101 ,0,0,0}, {24689,24672,23713 ,13103,13080,13095 ,0,0,0}, + {24689,24688,24752 ,13103,13101,13204 ,0,0,0}, {24753,24670,24675 ,13205,13075,13083 ,0,0,0}, + {24672,24752,24674 ,13080,13204,13082 ,0,0,0}, {24754,24668,24753 ,13206,13072,13205 ,0,0,0}, + {24674,24671,24672 ,13082,13077,13080 ,0,0,0}, {24755,24669,24754 ,13207,13073,13206 ,0,0,0}, + {24675,24670,24671 ,13083,13075,13077 ,0,0,0}, {24756,24667,24755 ,13208,13068,13207 ,0,0,0}, + {24753,24668,24670 ,13205,13072,13075 ,0,0,0}, {24757,24666,24756 ,13209,13065,13208 ,0,0,0}, + {24754,24669,24668 ,13206,13073,13072 ,0,0,0}, {24758,24665,24757 ,13210,13063,13209 ,0,0,0}, + {24755,24667,24669 ,13207,13068,13073 ,0,0,0}, {24759,24661,24758 ,13211,13059,13210 ,0,0,0}, + {24756,24666,24667 ,13208,13065,13068 ,0,0,0}, {24759,24760,24660 ,13211,13212,13057 ,0,0,0}, + {24665,24666,24757 ,13063,13065,13209 ,0,0,0}, {24761,24659,24760 ,13213,13055,13212 ,0,0,0}, + {24661,24665,24758 ,13059,13063,13210 ,0,0,0}, {24662,24658,24761 ,13060,13051,13213 ,0,0,0}, + {24660,24661,24759 ,13057,13059,13211 ,0,0,0}, {24762,24657,24662 ,13214,13049,13060 ,0,0,0}, + {24659,24660,24760 ,13055,13057,13212 ,0,0,0}, {24763,24656,24762 ,13215,13047,13214 ,0,0,0}, + {24658,24659,24761 ,13051,13055,13213 ,0,0,0}, {24764,24654,24763 ,13216,13043,13215 ,0,0,0}, + {24662,24657,24658 ,13060,13049,13051 ,0,0,0}, {24765,24655,24764 ,13217,13046,13216 ,0,0,0}, + {24762,24656,24657 ,13214,13047,13049 ,0,0,0}, {24765,24766,24692 ,13217,13218,13111 ,0,0,0}, + {24654,24656,24763 ,13043,13047,13215 ,0,0,0}, {24767,24693,24766 ,13219,13113,13218 ,0,0,0}, + {24655,24654,24764 ,13046,13043,13216 ,0,0,0}, {24768,24694,24767 ,13220,13114,13219 ,0,0,0}, + {24692,24655,24765 ,13111,13046,13217 ,0,0,0}, {24769,24695,24768 ,13221,13119,13220 ,0,0,0}, + {24693,24692,24766 ,13113,13111,13218 ,0,0,0}, {24770,24696,24769 ,13222,13120,13221 ,0,0,0}, + {24694,24693,24767 ,13114,13113,13219 ,0,0,0}, {24771,24697,24770 ,13223,13122,13222 ,0,0,0}, + {24768,24695,24694 ,13220,13119,13114 ,0,0,0}, {24771,24772,24698 ,13223,13224,13124 ,0,0,0}, + {24696,24695,24769 ,13120,13119,13221 ,0,0,0}, {24773,24702,24772 ,13225,13128,13224 ,0,0,0}, + {24697,24696,24770 ,13122,13120,13222 ,0,0,0}, {24699,24703,24773 ,13125,13130,13225 ,0,0,0}, + {24698,24697,24771 ,13124,13122,13223 ,0,0,0}, {24774,24704,24699 ,13226,13134,13125 ,0,0,0}, + {24702,24698,24772 ,13128,13124,13224 ,0,0,0}, {24775,24705,24774 ,13227,13136,13226 ,0,0,0}, + {24703,24702,24773 ,13130,13128,13225 ,0,0,0}, {24776,24706,24775 ,13228,13139,13227 ,0,0,0}, + {24699,24704,24703 ,13125,13134,13130 ,0,0,0}, {24777,24707,24776 ,13229,13140,13228 ,0,0,0}, + {24774,24705,24704 ,13226,13136,13134 ,0,0,0}, {24777,24778,24708 ,13229,13230,13142 ,0,0,0}, + {24706,24705,24775 ,13139,13136,13227 ,0,0,0}, {24779,24712,24778 ,13231,13147,13230 ,0,0,0}, + {24707,24706,24776 ,13140,13139,13228 ,0,0,0}, {24780,24713,24779 ,13232,13148,13231 ,0,0,0}, + {24708,24707,24777 ,13142,13140,13229 ,0,0,0}, {24781,24714,24780 ,13233,13153,13232 ,0,0,0}, + {24712,24708,24778 ,13147,13142,13230 ,0,0,0}, {24782,24715,24781 ,13234,13154,13233 ,0,0,0}, + {24779,24713,24712 ,13231,13148,13147 ,0,0,0}, {24783,24716,24782 ,13235,13156,13234 ,0,0,0}, + {24780,24714,24713 ,13232,13153,13148 ,0,0,0}, {24784,24717,24783 ,13236,13159,13235 ,0,0,0}, + {24781,24715,24714 ,13233,13154,13153 ,0,0,0}, {24785,24718,24784 ,13237,13160,13236 ,0,0,0}, + {24782,24716,24715 ,13234,13156,13154 ,0,0,0}, {24785,24722,24719 ,13237,13165,13162 ,0,0,0}, + {24717,24716,24783 ,13159,13156,13235 ,0,0,0}, {24723,24720,24786 ,13167,13163,13238 ,0,0,0}, + {24718,24717,24784 ,13160,13159,13236 ,0,0,0}, {24740,24731,24744 ,13186,13177,13190 ,0,0,0}, + {24719,24718,24785 ,13162,13160,13237 ,0,0,0}, {24730,24747,24786 ,13176,13194,13238 ,0,0,0}, + {24721,24719,24722 ,13164,13162,13165 ,0,0,0}, {24730,24786,24787 ,13176,13238,13239 ,0,0,0}, + {24739,24750,24740 ,13185,13197,13186 ,0,0,0}, {24747,24732,23754 ,13194,13178,13193 ,0,0,0}, + {24747,24723,24786 ,13194,13167,13238 ,0,0,0}, {24788,24751,24789 ,13240,13202,13241 ,0,0,0}, + {24747,24730,24732 ,13194,13176,13178 ,0,0,0}, {24750,24749,24731 ,13197,13196,13177 ,0,0,0}, + {24790,24791,24751 ,13242,13243,13202 ,0,0,0}, {23756,24748,23757 ,13199,13195,13200 ,0,0,0}, + {24748,24789,24751 ,13195,13241,13202 ,0,0,0}, {23378,24751,24791 ,11650,13202,13243 ,0,0,0}, + {24687,24688,24689 ,13099,13101,13103 ,0,0,0}, {24480,24690,24438 ,13106,13104,13203 ,0,0,0}, + {24572,24618,24682 ,13092,13244,13090 ,0,0,0}, {24689,24752,24672 ,13103,13204,13080 ,0,0,0}, + {24752,24690,24792 ,13204,13104,13245 ,0,0,0}, {24681,24680,24753 ,13089,13088,13205 ,0,0,0}, + {24685,24674,24792 ,13096,13082,13245 ,0,0,0}, {24680,24793,24754 ,13088,13246,13206 ,0,0,0}, + {24685,24675,24674 ,13096,13083,13082 ,0,0,0}, {24793,24794,24755 ,13246,13247,13207 ,0,0,0}, + {24681,24753,24675 ,13089,13205,13083 ,0,0,0}, {24794,24795,24756 ,13247,13248,13208 ,0,0,0}, + {24680,24754,24753 ,13088,13206,13205 ,0,0,0}, {24795,24796,24757 ,13248,13249,13209 ,0,0,0}, + {24793,24755,24754 ,13246,13207,13206 ,0,0,0}, {24796,24797,24758 ,13249,13250,13210 ,0,0,0}, + {24794,24756,24755 ,13247,13208,13207 ,0,0,0}, {24797,24798,24759 ,13250,13251,13211 ,0,0,0}, + {24795,24757,24756 ,13248,13209,13208 ,0,0,0}, {24798,24799,24760 ,13251,13252,13212 ,0,0,0}, + {24796,24758,24757 ,13249,13210,13209 ,0,0,0}, {24799,24663,24761 ,13252,13061,13213 ,0,0,0}, + {24759,24758,24797 ,13211,13210,13250 ,0,0,0}, {24800,24801,24802 ,13253,13254,13255 ,0,0,0}, + {24760,24759,24798 ,13212,13211,13251 ,0,0,0}, {24664,24801,24762 ,13062,13254,13214 ,0,0,0}, + {24761,24760,24799 ,13213,13212,13252 ,0,0,0}, {24801,24800,24763 ,13254,13253,13215 ,0,0,0}, + {24662,24761,24663 ,13060,13213,13061 ,0,0,0}, {24800,24803,24764 ,13253,13256,13216 ,0,0,0}, + {24664,24762,24662 ,13062,13214,13060 ,0,0,0}, {24803,24804,24765 ,13256,13257,13217 ,0,0,0}, + {24801,24763,24762 ,13254,13215,13214 ,0,0,0}, {24804,24805,24766 ,13257,13258,13218 ,0,0,0}, + {24800,24764,24763 ,13253,13216,13215 ,0,0,0}, {24805,24806,24767 ,13258,13259,13219 ,0,0,0}, + {24765,24764,24803 ,13217,13216,13256 ,0,0,0}, {24652,24768,24806 ,13041,13220,13259 ,0,0,0}, + {24766,24765,24804 ,13218,13217,13257 ,0,0,0}, {24652,24651,24769 ,13041,13040,13221 ,0,0,0}, + {24767,24766,24805 ,13219,13218,13258 ,0,0,0}, {24651,24807,24770 ,13040,13260,13222 ,0,0,0}, + {24806,24768,24767 ,13259,13220,13219 ,0,0,0}, {24807,24808,24771 ,13260,13261,13223 ,0,0,0}, + {24652,24769,24768 ,13041,13221,13220 ,0,0,0}, {24808,24809,24772 ,13261,13262,13224 ,0,0,0}, + {24651,24770,24769 ,13040,13222,13221 ,0,0,0}, {24809,24700,24773 ,13262,13126,13225 ,0,0,0}, + {24771,24770,24807 ,13223,13222,13260 ,0,0,0}, {24810,24811,24812 ,13263,13264,13265 ,0,0,0}, + {24772,24771,24808 ,13224,13223,13261 ,0,0,0}, {24701,24813,24774 ,13127,13266,13226 ,0,0,0}, + {24773,24772,24809 ,13225,13224,13262 ,0,0,0}, {24813,24814,24775 ,13266,13267,13227 ,0,0,0}, + {24699,24773,24700 ,13125,13225,13126 ,0,0,0}, {24814,24815,24776 ,13267,13268,13228 ,0,0,0}, + {24701,24774,24699 ,13127,13226,13125 ,0,0,0}, {24815,24816,24777 ,13268,13269,13229 ,0,0,0}, + {24813,24775,24774 ,13266,13227,13226 ,0,0,0}, {24816,24817,24778 ,13269,13270,13230 ,0,0,0}, + {24814,24776,24775 ,13267,13228,13227 ,0,0,0}, {24817,24818,24779 ,13270,13271,13231 ,0,0,0}, + {24777,24776,24815 ,13229,13228,13268 ,0,0,0}, {24818,24709,24780 ,13271,13143,13232 ,0,0,0}, + {24778,24777,24816 ,13230,13229,13269 ,0,0,0}, {24709,24711,24781 ,13143,13145,13233 ,0,0,0}, + {24779,24778,24817 ,13231,13230,13270 ,0,0,0}, {24711,24819,24782 ,13145,13272,13234 ,0,0,0}, + {24818,24780,24779 ,13271,13232,13231 ,0,0,0}, {24819,24820,24783 ,13272,13273,13235 ,0,0,0}, + {24709,24781,24780 ,13143,13233,13232 ,0,0,0}, {24820,24821,24784 ,13273,13274,13236 ,0,0,0}, + {24711,24782,24781 ,13145,13234,13233 ,0,0,0}, {24821,24822,24785 ,13274,13275,13237 ,0,0,0}, + {24819,24783,24782 ,13272,13235,13234 ,0,0,0}, {24822,24823,24722 ,13275,13276,13165 ,0,0,0}, + {24820,24784,24783 ,13273,13236,13235 ,0,0,0}, {24823,24824,24720 ,13276,13277,13163 ,0,0,0}, + {24821,24785,24784 ,13274,13237,13236 ,0,0,0}, {24824,24787,24786 ,13277,13239,13238 ,0,0,0}, + {24822,24722,24785 ,13275,13165,13237 ,0,0,0}, {24787,24744,24730 ,13239,13190,13176 ,0,0,0}, + {24720,24722,24823 ,13163,13165,13276 ,0,0,0}, {24825,24739,24826 ,13278,13185,13279 ,0,0,0}, + {24720,24824,24786 ,13163,13277,13238 ,0,0,0}, {24750,24739,24789 ,13197,13185,13241 ,0,0,0}, + {24738,24826,24739 ,13184,13279,13185 ,0,0,0}, {24732,24731,24749 ,13178,13177,13196 ,0,0,0}, + {24744,24731,24730 ,13190,13177,13176 ,0,0,0}, {24827,24788,24724 ,13280,13240,13169 ,0,0,0}, + {24788,24790,24751 ,13240,13242,13202 ,0,0,0}, {24748,24750,24789 ,13195,13197,13241 ,0,0,0}, + {24788,24789,24825 ,13240,13241,13278 ,0,0,0}, {24827,24790,24788 ,13280,13242,13240 ,0,0,0}, + {24688,24690,24752 ,13101,13104,13204 ,0,0,0}, {24434,24686,24479 ,13107,13098,13105 ,0,0,0}, + {23405,24678,23407 ,13281,13086,13079 ,0,0,0}, {24752,24792,24674 ,13204,13245,13082 ,0,0,0}, + {24792,24686,24828 ,13245,13098,13282 ,0,0,0}, {24680,24829,24793 ,13088,13283,13246 ,0,0,0}, + {24691,24685,24828 ,13110,13096,13282 ,0,0,0}, {24793,24830,24794 ,13246,13284,13247 ,0,0,0}, + {24691,24679,24681 ,13110,13087,13089 ,0,0,0}, {24831,24832,24833 ,13285,13286,13287 ,0,0,0}, + {24679,24829,24680 ,13087,13283,13088 ,0,0,0}, {24795,24794,24834 ,13248,13247,13288 ,0,0,0}, + {24829,24830,24793 ,13283,13284,13246 ,0,0,0}, {24796,24795,24833 ,13249,13248,13287 ,0,0,0}, + {24830,24834,24794 ,13284,13288,13247 ,0,0,0}, {24797,24796,24832 ,13250,13249,13286 ,0,0,0}, + {24834,24833,24795 ,13288,13287,13248 ,0,0,0}, {24798,24797,24835 ,13251,13250,13289 ,0,0,0}, + {24833,24832,24796 ,13287,13286,13249 ,0,0,0}, {24799,24798,24836 ,13252,13251,13290 ,0,0,0}, + {24832,24835,24797 ,13286,13289,13250 ,0,0,0}, {24663,24799,24837 ,13061,13252,13291 ,0,0,0}, + {24835,24836,24798 ,13289,13290,13251 ,0,0,0}, {24664,24663,24838 ,13062,13061,13292 ,0,0,0}, + {24836,24837,24799 ,13290,13291,13252 ,0,0,0}, {24801,24664,24839 ,13254,13062,13293 ,0,0,0}, + {24838,24663,24837 ,13292,13061,13291 ,0,0,0}, {24840,24841,24842 ,13294,13295,13296 ,0,0,0}, + {24839,24664,24838 ,13293,13062,13292 ,0,0,0}, {24803,24800,24843 ,13256,13253,13297 ,0,0,0}, + {24839,24802,24801 ,13293,13255,13254 ,0,0,0}, {24804,24803,24842 ,13257,13256,13296 ,0,0,0}, + {24802,24843,24800 ,13255,13297,13253 ,0,0,0}, {24805,24804,24841 ,13258,13257,13295 ,0,0,0}, + {24843,24842,24803 ,13297,13296,13256 ,0,0,0}, {24806,24805,24844 ,13259,13258,13298 ,0,0,0}, + {24842,24841,24804 ,13296,13295,13257 ,0,0,0}, {24652,24806,24845 ,13041,13259,13299 ,0,0,0}, + {24844,24805,24841 ,13298,13258,13295 ,0,0,0}, {24846,24847,24848 ,13300,13301,13302 ,0,0,0}, + {24845,24806,24844 ,13299,13259,13298 ,0,0,0}, {24807,24651,24849 ,13260,13040,13303 ,0,0,0}, + {24845,24653,24652 ,13299,13042,13041 ,0,0,0}, {24808,24807,24848 ,13261,13260,13302 ,0,0,0}, + {24653,24849,24651 ,13042,13303,13040 ,0,0,0}, {24809,24808,24847 ,13262,13261,13301 ,0,0,0}, + {24849,24848,24807 ,13303,13302,13260 ,0,0,0}, {24700,24809,24850 ,13126,13262,13304 ,0,0,0}, + {24848,24847,24808 ,13302,13301,13261 ,0,0,0}, {24701,24700,24851 ,13127,13126,13305 ,0,0,0}, + {24847,24850,24809 ,13301,13304,13262 ,0,0,0}, {24813,24701,24852 ,13266,13127,13306 ,0,0,0}, + {24851,24700,24850 ,13305,13126,13304 ,0,0,0}, {24814,24813,24853 ,13267,13266,13307 ,0,0,0}, + {24852,24701,24851 ,13306,13127,13305 ,0,0,0}, {24815,24814,24810 ,13268,13267,13263 ,0,0,0}, + {24852,24853,24813 ,13306,13307,13266 ,0,0,0}, {24816,24815,24812 ,13269,13268,13265 ,0,0,0}, + {24853,24810,24814 ,13307,13263,13267 ,0,0,0}, {24817,24816,24854 ,13270,13269,13308 ,0,0,0}, + {24810,24812,24815 ,13263,13265,13268 ,0,0,0}, {24818,24817,24855 ,13271,13270,13309 ,0,0,0}, + {24812,24854,24816 ,13265,13308,13269 ,0,0,0}, {24709,24818,24856 ,13143,13271,13310 ,0,0,0}, + {24855,24817,24854 ,13309,13270,13308 ,0,0,0}, {24857,24858,24859 ,13311,13312,13313 ,0,0,0}, + {24856,24818,24855 ,13310,13271,13309 ,0,0,0}, {24819,24711,24860 ,13272,13145,13314 ,0,0,0}, + {24856,24710,24709 ,13310,13144,13143 ,0,0,0}, {24820,24819,24859 ,13273,13272,13313 ,0,0,0}, + {24710,24860,24711 ,13144,13314,13145 ,0,0,0}, {24821,24820,24858 ,13274,13273,13312 ,0,0,0}, + {24860,24859,24819 ,13314,13313,13272 ,0,0,0}, {24822,24821,24861 ,13275,13274,13315 ,0,0,0}, + {24859,24858,24820 ,13313,13312,13273 ,0,0,0}, {24823,24822,24862 ,13276,13275,13316 ,0,0,0}, + {24858,24861,24821 ,13312,13315,13274 ,0,0,0}, {24824,24823,24863 ,13277,13276,13317 ,0,0,0}, + {24861,24862,24822 ,13315,13316,13275 ,0,0,0}, {24787,24824,24864 ,13239,13277,13318 ,0,0,0}, + {24862,24863,24823 ,13316,13317,13276 ,0,0,0}, {24744,24787,24745 ,13190,13239,13191 ,0,0,0}, + {24863,24864,24824 ,13317,13318,13277 ,0,0,0}, {24740,24744,24743 ,13186,13190,13189 ,0,0,0}, + {24864,24745,24787 ,13318,13191,13239 ,0,0,0}, {24725,24826,24728 ,13170,13279,13174 ,0,0,0}, + {24826,24865,24728 ,13279,13319,13174 ,0,0,0}, {24731,24740,24750 ,13177,13186,13197 ,0,0,0}, + {24743,24738,24740 ,13189,13184,13186 ,0,0,0}, {24866,24724,24726 ,13320,13169,13171 ,0,0,0}, + {24788,24825,24724 ,13240,13278,13169 ,0,0,0}, {24789,24739,24825 ,13241,13185,13278 ,0,0,0}, + {24825,24725,24724 ,13278,13170,13169 ,0,0,0}, {24827,24724,24866 ,13280,13169,13320 ,0,0,0}, + {24686,24792,24690 ,13098,13245,13104 ,0,0,0}, {24572,24683,24573 ,13092,13091,13097 ,0,0,0}, + {24691,24867,24679 ,13110,13321,13087 ,0,0,0}, {24792,24828,24685 ,13245,13282,13096 ,0,0,0}, + {24683,24868,24828 ,13091,13322,13282 ,0,0,0}, {24829,24679,24869 ,13283,13087,13323 ,0,0,0}, + {24868,24867,24691 ,13322,13321,13110 ,0,0,0}, {24830,24829,24870 ,13284,13283,13324 ,0,0,0}, + {24679,24867,24869 ,13087,13321,13323 ,0,0,0}, {24834,24830,24871 ,13288,13284,13325 ,0,0,0}, + {24829,24869,24870 ,13283,13323,13324 ,0,0,0}, {24833,24834,24872 ,13287,13288,13326 ,0,0,0}, + {24870,24871,24830 ,13324,13325,13284 ,0,0,0}, {24873,24835,24832 ,13327,13289,13286 ,0,0,0}, + {24871,24872,24834 ,13325,13326,13288 ,0,0,0}, {24874,24875,24876 ,13328,13329,13330 ,0,0,0}, + {24872,24831,24833 ,13326,13285,13287 ,0,0,0}, {24835,24877,24836 ,13289,13331,13290 ,0,0,0}, + {24831,24873,24832 ,13285,13327,13286 ,0,0,0}, {24836,24875,24837 ,13290,13329,13291 ,0,0,0}, + {24873,24877,24835 ,13327,13331,13289 ,0,0,0}, {24837,24874,24838 ,13291,13328,13292 ,0,0,0}, + {24877,24875,24836 ,13331,13329,13290 ,0,0,0}, {24838,24878,24839 ,13292,13332,13293 ,0,0,0}, + {24875,24874,24837 ,13329,13328,13291 ,0,0,0}, {24839,24879,24802 ,13293,13333,13255 ,0,0,0}, + {24874,24878,24838 ,13328,13332,13292 ,0,0,0}, {24843,24802,24880 ,13297,13255,13334 ,0,0,0}, + {24878,24879,24839 ,13332,13333,13293 ,0,0,0}, {24842,24843,24881 ,13296,13297,13335 ,0,0,0}, + {24879,24880,24802 ,13333,13334,13255 ,0,0,0}, {24882,24883,24884 ,13336,13337,13338 ,0,0,0}, + {24880,24881,24843 ,13334,13335,13297 ,0,0,0}, {24841,24885,24844 ,13295,13339,13298 ,0,0,0}, + {24881,24840,24842 ,13335,13294,13296 ,0,0,0}, {24844,24886,24845 ,13298,13340,13299 ,0,0,0}, + {24840,24885,24841 ,13294,13339,13295 ,0,0,0}, {24845,24887,24653 ,13299,13341,13042 ,0,0,0}, + {24885,24886,24844 ,13339,13340,13298 ,0,0,0}, {24849,24653,24888 ,13303,13042,13342 ,0,0,0}, + {24886,24887,24845 ,13340,13341,13299 ,0,0,0}, {24848,24849,24889 ,13302,13303,13343 ,0,0,0}, + {24887,24888,24653 ,13341,13342,13042 ,0,0,0}, {24890,24891,24892 ,13344,13345,13346 ,0,0,0}, + {24888,24889,24849 ,13342,13343,13303 ,0,0,0}, {24847,24893,24850 ,13301,13347,13304 ,0,0,0}, + {24889,24846,24848 ,13343,13300,13302 ,0,0,0}, {24850,24894,24851 ,13304,13348,13305 ,0,0,0}, + {24846,24893,24847 ,13300,13347,13301 ,0,0,0}, {24851,24895,24852 ,13305,13349,13306 ,0,0,0}, + {24893,24894,24850 ,13347,13348,13304 ,0,0,0}, {24852,24896,24853 ,13306,13350,13307 ,0,0,0}, + {24894,24895,24851 ,13348,13349,13305 ,0,0,0}, {24810,24853,24897 ,13263,13307,13351 ,0,0,0}, + {24895,24896,24852 ,13349,13350,13306 ,0,0,0}, {24898,24899,24900 ,13352,13353,13354 ,0,0,0}, + {24896,24897,24853 ,13350,13351,13307 ,0,0,0}, {24812,24901,24854 ,13265,13355,13308 ,0,0,0}, + {24897,24811,24810 ,13351,13264,13263 ,0,0,0}, {24854,24899,24855 ,13308,13353,13309 ,0,0,0}, + {24811,24901,24812 ,13264,13355,13265 ,0,0,0}, {24855,24898,24856 ,13309,13352,13310 ,0,0,0}, + {24901,24899,24854 ,13355,13353,13308 ,0,0,0}, {24856,24902,24710 ,13310,13356,13144 ,0,0,0}, + {24899,24898,24855 ,13353,13352,13309 ,0,0,0}, {24860,24710,24903 ,13314,13144,13357 ,0,0,0}, + {24898,24902,24856 ,13352,13356,13310 ,0,0,0}, {24859,24860,24904 ,13313,13314,13358 ,0,0,0}, + {24902,24903,24710 ,13356,13357,13144 ,0,0,0}, {24905,24861,24858 ,13359,13315,13312 ,0,0,0}, + {24903,24904,24860 ,13357,13358,13314 ,0,0,0}, {24906,24907,24908 ,13360,13361,13362 ,0,0,0}, + {24904,24857,24859 ,13358,13311,13313 ,0,0,0}, {24861,24909,24862 ,13315,13363,13316 ,0,0,0}, + {24857,24905,24858 ,13311,13359,13312 ,0,0,0}, {24862,24907,24863 ,13316,13361,13317 ,0,0,0}, + {24905,24909,24861 ,13359,13363,13315 ,0,0,0}, {24863,24906,24864 ,13317,13360,13318 ,0,0,0}, + {24909,24907,24862 ,13363,13361,13316 ,0,0,0}, {24864,24910,24745 ,13318,13364,13191 ,0,0,0}, + {24907,24906,24863 ,13361,13360,13317 ,0,0,0}, {24745,24911,24743 ,13191,13365,13189 ,0,0,0}, + {24906,24910,24864 ,13360,13364,13318 ,0,0,0}, {24743,24912,24738 ,13189,13366,13184 ,0,0,0}, + {24910,24911,24745 ,13364,13365,13191 ,0,0,0}, {24738,24865,24826 ,13184,13319,13279 ,0,0,0}, + {24912,24743,24911 ,13366,13189,13365 ,0,0,0}, {24913,24914,24726 ,13367,13368,13171 ,0,0,0}, + {24738,24912,24865 ,13184,13366,13319 ,0,0,0}, {24915,24726,24914 ,13369,13171,13368 ,0,0,0}, + {24916,24866,24726 ,13370,13320,13171 ,0,0,0}, {24825,24826,24725 ,13278,13279,13170 ,0,0,0}, + {24725,24913,24726 ,13170,13367,13171 ,0,0,0}, {24915,24916,24726 ,13369,13370,13171 ,0,0,0}, + {24683,24828,24686 ,13091,13282,13098 ,0,0,0}, {24346,24682,24618 ,13093,13090,13244 ,0,0,0}, + {24867,24917,24869 ,13321,13371,13323 ,0,0,0}, {24828,24868,24691 ,13282,13322,13110 ,0,0,0}, + {24682,24918,24868 ,13090,13372,13322 ,0,0,0}, {24870,24869,24919 ,13324,13323,13373 ,0,0,0}, + {24867,24918,24917 ,13321,13372,13371 ,0,0,0}, {24871,24870,24920 ,13325,13324,13374 ,0,0,0}, + {24869,24917,24919 ,13323,13371,13373 ,0,0,0}, {24872,24871,24921 ,13326,13325,13375 ,0,0,0}, + {24870,24919,24920 ,13324,13373,13374 ,0,0,0}, {24831,24872,24922 ,13285,13326,13376 ,0,0,0}, + {24871,24920,24921 ,13325,13374,13375 ,0,0,0}, {24873,24831,24923 ,13327,13285,13377 ,0,0,0}, + {24872,24921,24922 ,13326,13375,13376 ,0,0,0}, {24877,24873,24924 ,13331,13327,13378 ,0,0,0}, + {24831,24922,24923 ,13285,13376,13377 ,0,0,0}, {24875,24877,24925 ,13329,13331,13379 ,0,0,0}, + {24923,24924,24873 ,13377,13378,13327 ,0,0,0}, {24926,24927,24928 ,13380,13381,13382 ,0,0,0}, + {24924,24925,24877 ,13378,13379,13331 ,0,0,0}, {24874,24929,24878 ,13328,13383,13332 ,0,0,0}, + {24925,24876,24875 ,13379,13330,13329 ,0,0,0}, {24878,24928,24879 ,13332,13382,13333 ,0,0,0}, + {24876,24929,24874 ,13330,13383,13328 ,0,0,0}, {24879,24930,24880 ,13333,13384,13334 ,0,0,0}, + {24929,24928,24878 ,13383,13382,13332 ,0,0,0}, {24881,24880,24931 ,13335,13334,13385 ,0,0,0}, + {24928,24930,24879 ,13382,13384,13333 ,0,0,0}, {24840,24881,24932 ,13294,13335,13386 ,0,0,0}, + {24880,24930,24931 ,13334,13384,13385 ,0,0,0}, {24885,24840,24933 ,13339,13294,13387 ,0,0,0}, + {24881,24931,24932 ,13335,13385,13386 ,0,0,0}, {24886,24885,24934 ,13340,13339,13388 ,0,0,0}, + {24932,24933,24840 ,13386,13387,13294 ,0,0,0}, {24886,24935,24887 ,13340,13389,13341 ,0,0,0}, + {24933,24934,24885 ,13387,13388,13339 ,0,0,0}, {24887,24883,24888 ,13341,13337,13342 ,0,0,0}, + {24934,24935,24886 ,13388,13389,13340 ,0,0,0}, {24889,24888,24936 ,13343,13342,13390 ,0,0,0}, + {24935,24883,24887 ,13389,13337,13341 ,0,0,0}, {24846,24889,24937 ,13300,13343,13391 ,0,0,0}, + {24888,24883,24936 ,13342,13337,13390 ,0,0,0}, {24893,24846,24938 ,13347,13300,13392 ,0,0,0}, + {24889,24936,24937 ,13343,13390,13391 ,0,0,0}, {24894,24893,24939 ,13348,13347,13393 ,0,0,0}, + {24937,24938,24846 ,13391,13392,13300 ,0,0,0}, {24894,24940,24895 ,13348,13394,13349 ,0,0,0}, + {24938,24939,24893 ,13392,13393,13347 ,0,0,0}, {24895,24891,24896 ,13349,13345,13350 ,0,0,0}, + {24939,24940,24894 ,13393,13394,13348 ,0,0,0}, {24897,24896,24941 ,13351,13350,13395 ,0,0,0}, + {24940,24891,24895 ,13394,13345,13349 ,0,0,0}, {24811,24897,24942 ,13264,13351,13396 ,0,0,0}, + {24896,24891,24941 ,13350,13345,13395 ,0,0,0}, {24901,24811,24943 ,13355,13264,13397 ,0,0,0}, + {24897,24941,24942 ,13351,13395,13396 ,0,0,0}, {24899,24901,24944 ,13353,13355,13398 ,0,0,0}, + {24942,24943,24811 ,13396,13397,13264 ,0,0,0}, {24945,24946,24947 ,13399,13400,13401 ,0,0,0}, + {24943,24944,24901 ,13397,13398,13355 ,0,0,0}, {24898,24948,24902 ,13352,13402,13356 ,0,0,0}, + {24944,24900,24899 ,13398,13354,13353 ,0,0,0}, {24902,24947,24903 ,13356,13401,13357 ,0,0,0}, + {24900,24948,24898 ,13354,13402,13352 ,0,0,0}, {24904,24903,24949 ,13358,13357,13403 ,0,0,0}, + {24948,24947,24902 ,13402,13401,13356 ,0,0,0}, {24857,24904,24950 ,13311,13358,13404 ,0,0,0}, + {24903,24947,24949 ,13357,13401,13403 ,0,0,0}, {24905,24857,24951 ,13359,13311,13405 ,0,0,0}, + {24904,24949,24950 ,13358,13403,13404 ,0,0,0}, {24909,24905,24952 ,13363,13359,13406 ,0,0,0}, + {24857,24950,24951 ,13311,13404,13405 ,0,0,0}, {24907,24909,24953 ,13361,13363,13407 ,0,0,0}, + {24951,24952,24905 ,13405,13406,13359 ,0,0,0}, {24954,24910,24906 ,13408,13364,13360 ,0,0,0}, + {24952,24953,24909 ,13406,13407,13363 ,0,0,0}, {24955,24956,24957 ,13409,13410,13411 ,0,0,0}, + {24953,24908,24907 ,13407,13362,13361 ,0,0,0}, {24910,24958,24911 ,13364,13412,13365 ,0,0,0}, + {24908,24954,24906 ,13362,13408,13360 ,0,0,0}, {24911,24957,24912 ,13365,13411,13366 ,0,0,0}, + {24954,24958,24910 ,13408,13412,13364 ,0,0,0}, {24912,24959,24865 ,13366,13413,13319 ,0,0,0}, + {24958,24957,24911 ,13412,13411,13365 ,0,0,0}, {24865,24729,24728 ,13319,13175,13174 ,0,0,0}, + {24957,24959,24912 ,13411,13413,13366 ,0,0,0}, {24728,24727,24913 ,13174,13173,13367 ,0,0,0}, + {24729,24865,24959 ,13175,13319,13413 ,0,0,0}, {24914,24960,24737 ,13368,13414,13183 ,0,0,0}, + {24961,24962,24914 ,13415,13416,13368 ,0,0,0}, {24725,24728,24913 ,13170,13174,13367 ,0,0,0}, + {24913,24960,24914 ,13367,13414,13368 ,0,0,0}, {24915,24914,24962 ,13369,13368,13416 ,0,0,0}, + {24683,24682,24868 ,13091,13090,13322 ,0,0,0}, {24350,24684,24346 ,13417,13094,13093 ,0,0,0}, + {24919,24917,24677 ,13373,13371,13085 ,0,0,0}, {24868,24918,24867 ,13322,13372,13321 ,0,0,0}, + {24684,24963,24918 ,13094,13418,13372 ,0,0,0}, {24920,24919,24964 ,13374,13373,13419 ,0,0,0}, + {24917,24963,24677 ,13371,13418,13085 ,0,0,0}, {24965,24964,24966 ,13420,13419,13421 ,0,0,0}, + {24919,24677,24964 ,13373,13085,13419 ,0,0,0}, {24965,24967,24921 ,13420,13422,13375 ,0,0,0}, + {24921,24920,24965 ,13375,13374,13420 ,0,0,0}, {24967,24968,24922 ,13422,13423,13376 ,0,0,0}, + {24922,24921,24967 ,13376,13375,13422 ,0,0,0}, {24968,24969,24923 ,13423,13424,13377 ,0,0,0}, + {24923,24922,24968 ,13377,13376,13423 ,0,0,0}, {24969,24970,24924 ,13424,13425,13378 ,0,0,0}, + {24924,24923,24969 ,13378,13377,13424 ,0,0,0}, {24970,24971,24925 ,13425,13426,13379 ,0,0,0}, + {24925,24924,24970 ,13379,13378,13425 ,0,0,0}, {24971,24972,24876 ,13426,13427,13330 ,0,0,0}, + {24876,24925,24971 ,13330,13379,13426 ,0,0,0}, {24972,24926,24929 ,13427,13380,13383 ,0,0,0}, + {24876,24972,24929 ,13330,13427,13383 ,0,0,0}, {23393,24973,24974 ,13428,13429,13430 ,0,0,0}, + {24929,24926,24928 ,13383,13380,13382 ,0,0,0}, {24930,24975,24931 ,13384,13431,13385 ,0,0,0}, + {24928,24927,24930 ,13382,13381,13384 ,0,0,0}, {24976,24975,24974 ,13432,13431,13430 ,0,0,0}, + {24927,24975,24930 ,13381,13431,13384 ,0,0,0}, {24976,24977,24932 ,13432,13433,13386 ,0,0,0}, + {24932,24931,24976 ,13386,13385,13432 ,0,0,0}, {24977,24978,24933 ,13433,13434,13387 ,0,0,0}, + {24933,24932,24977 ,13387,13386,13433 ,0,0,0}, {24978,24979,24934 ,13434,13435,13388 ,0,0,0}, + {24934,24933,24978 ,13388,13387,13434 ,0,0,0}, {24979,24884,24935 ,13435,13338,13389 ,0,0,0}, + {24934,24979,24935 ,13388,13435,13389 ,0,0,0}, {24980,24981,24982 ,13436,13437,13438 ,0,0,0}, + {24935,24884,24883 ,13389,13338,13337 ,0,0,0}, {24882,24981,24936 ,13336,13437,13390 ,0,0,0}, + {24883,24882,24936 ,13337,13336,13390 ,0,0,0}, {24981,24983,24937 ,13437,13439,13391 ,0,0,0}, + {24937,24936,24981 ,13391,13390,13437 ,0,0,0}, {24983,24984,24938 ,13439,13440,13392 ,0,0,0}, + {24938,24937,24983 ,13392,13391,13439 ,0,0,0}, {24984,24985,24939 ,13440,13441,13393 ,0,0,0}, + {24939,24938,24984 ,13393,13392,13440 ,0,0,0}, {24985,24892,24940 ,13441,13346,13394 ,0,0,0}, + {24939,24985,24940 ,13393,13441,13394 ,0,0,0}, {24986,23384,24987 ,13442,13443,13444 ,0,0,0}, + {24940,24892,24891 ,13394,13346,13345 ,0,0,0}, {24942,24941,24988 ,13396,13395,13445 ,0,0,0}, + {24891,24890,24941 ,13345,13344,13395 ,0,0,0}, {24989,24988,24986 ,13446,13445,13442 ,0,0,0}, + {24941,24890,24988 ,13395,13344,13445 ,0,0,0}, {24989,24990,24943 ,13446,13447,13397 ,0,0,0}, + {24943,24942,24989 ,13397,13396,13446 ,0,0,0}, {24990,24991,24944 ,13447,13448,13398 ,0,0,0}, + {24944,24943,24990 ,13398,13397,13447 ,0,0,0}, {24991,24992,24900 ,13448,13449,13354 ,0,0,0}, + {24900,24944,24991 ,13354,13398,13448 ,0,0,0}, {24992,24945,24948 ,13449,13399,13402 ,0,0,0}, + {24900,24992,24948 ,13354,13449,13402 ,0,0,0}, {24993,24994,24995 ,13450,13451,13452 ,0,0,0}, + {24948,24945,24947 ,13402,13399,13401 ,0,0,0}, {24946,24994,24949 ,13400,13451,13403 ,0,0,0}, + {24947,24946,24949 ,13401,13400,13403 ,0,0,0}, {24994,24996,24950 ,13451,13453,13404 ,0,0,0}, + {24950,24949,24994 ,13404,13403,13451 ,0,0,0}, {24996,24997,24951 ,13453,13454,13405 ,0,0,0}, + {24951,24950,24996 ,13405,13404,13453 ,0,0,0}, {24997,24998,24952 ,13454,13455,13406 ,0,0,0}, + {24952,24951,24997 ,13406,13405,13454 ,0,0,0}, {24998,24999,24953 ,13455,13456,13407 ,0,0,0}, + {24953,24952,24998 ,13407,13406,13455 ,0,0,0}, {24999,25000,24908 ,13456,13457,13362 ,0,0,0}, + {24908,24953,24999 ,13362,13407,13456 ,0,0,0}, {25000,25001,24954 ,13457,13458,13408 ,0,0,0}, + {24954,24908,25000 ,13408,13362,13457 ,0,0,0}, {25001,24955,24958 ,13458,13409,13412 ,0,0,0}, + {24954,25001,24958 ,13408,13458,13412 ,0,0,0}, {24959,24956,25002 ,13413,13410,13459 ,0,0,0}, + {24958,24955,24957 ,13412,13409,13411 ,0,0,0}, {24734,24727,24729 ,13180,13173,13175 ,0,0,0}, + {24957,24956,24959 ,13411,13410,13413 ,0,0,0}, {24733,24960,24727 ,13179,13414,13173 ,0,0,0}, + {24959,25002,24729 ,13413,13459,13175 ,0,0,0}, {24741,24735,25003 ,13187,13181,13460 ,0,0,0}, + {25002,24734,24729 ,13459,13180,13175 ,0,0,0}, {24733,25004,25005 ,13179,13461,13462 ,0,0,0}, + {24737,24961,24914 ,13183,13415,13368 ,0,0,0}, {24913,24727,24960 ,13367,13173,13414 ,0,0,0}, + {24737,24960,25005 ,13183,13414,13462 ,0,0,0}, {24736,24961,24737 ,13182,13415,13183 ,0,0,0}, + {24682,24684,24918 ,13090,13094,13372 ,0,0,0}, {24350,24352,24673 ,13417,13078,13081 ,0,0,0}, + {24963,24673,24678 ,13418,13081,13086 ,0,0,0}, {24918,24963,24917 ,13372,13418,13371 ,0,0,0}, + {24677,24963,24678 ,13085,13418,13086 ,0,0,0}, {24676,24966,24964 ,13084,13421,13419 ,0,0,0}, + {24964,24677,24676 ,13419,13085,13084 ,0,0,0}, {24966,25006,24965 ,13421,13463,13420 ,0,0,0}, + {25007,24967,25006 ,13464,13422,13463 ,0,0,0}, {24920,24964,24965 ,13374,13419,13420 ,0,0,0}, + {24967,24965,25006 ,13422,13420,13463 ,0,0,0}, {25008,24968,25007 ,13465,13423,13464 ,0,0,0}, + {24968,24967,25007 ,13423,13422,13464 ,0,0,0}, {25009,24969,25008 ,13466,13424,13465 ,0,0,0}, + {24969,24968,25008 ,13424,13423,13465 ,0,0,0}, {25010,24970,25009 ,13467,13425,13466 ,0,0,0}, + {24970,24969,25009 ,13425,13424,13466 ,0,0,0}, {25011,24971,25010 ,13468,13426,13467 ,0,0,0}, + {24971,24970,25010 ,13426,13425,13467 ,0,0,0}, {25012,24972,25011 ,13469,13427,13468 ,0,0,0}, + {24972,24971,25011 ,13427,13426,13468 ,0,0,0}, {25013,24926,25012 ,13470,13380,13469 ,0,0,0}, + {24926,24972,25012 ,13380,13427,13469 ,0,0,0}, {25014,24927,25013 ,13471,13381,13470 ,0,0,0}, + {24927,24926,25013 ,13381,13380,13470 ,0,0,0}, {24974,24975,25014 ,13430,13431,13471 ,0,0,0}, + {24927,25014,24975 ,13381,13471,13431 ,0,0,0}, {24974,24973,24976 ,13430,13429,13432 ,0,0,0}, + {25015,24977,24973 ,13472,13433,13429 ,0,0,0}, {24931,24975,24976 ,13385,13431,13432 ,0,0,0}, + {24977,24976,24973 ,13433,13432,13429 ,0,0,0}, {25016,24978,25015 ,13473,13434,13472 ,0,0,0}, + {24978,24977,25015 ,13434,13433,13472 ,0,0,0}, {25017,24979,25016 ,13474,13435,13473 ,0,0,0}, + {24979,24978,25016 ,13435,13434,13473 ,0,0,0}, {25018,24884,25017 ,13475,13338,13474 ,0,0,0}, + {24884,24979,25017 ,13338,13435,13474 ,0,0,0}, {24982,24882,25018 ,13438,13336,13475 ,0,0,0}, + {24882,24884,25018 ,13336,13338,13475 ,0,0,0}, {24982,23301,24980 ,13438,13476,13436 ,0,0,0}, + {24882,24982,24981 ,13336,13438,13437 ,0,0,0}, {25019,24983,24980 ,13477,13439,13436 ,0,0,0}, + {24983,24981,24980 ,13439,13437,13436 ,0,0,0}, {25020,24984,25019 ,13478,13440,13477 ,0,0,0}, + {24984,24983,25019 ,13440,13439,13477 ,0,0,0}, {25021,24985,25020 ,13479,13441,13478 ,0,0,0}, + {24985,24984,25020 ,13441,13440,13478 ,0,0,0}, {25022,24892,25021 ,13480,13346,13479 ,0,0,0}, + {24892,24985,25021 ,13346,13441,13479 ,0,0,0}, {25023,24890,25022 ,13481,13344,13480 ,0,0,0}, + {24890,24892,25022 ,13344,13346,13480 ,0,0,0}, {24986,24988,25023 ,13442,13445,13481 ,0,0,0}, + {24890,25023,24988 ,13344,13481,13445 ,0,0,0}, {24986,24987,24989 ,13442,13444,13446 ,0,0,0}, + {25024,24990,24987 ,13482,13447,13444 ,0,0,0}, {24942,24988,24989 ,13396,13445,13446 ,0,0,0}, + {24990,24989,24987 ,13447,13446,13444 ,0,0,0}, {25025,24991,25024 ,13483,13448,13482 ,0,0,0}, + {24991,24990,25024 ,13448,13447,13482 ,0,0,0}, {25026,24992,25025 ,13484,13449,13483 ,0,0,0}, + {24992,24991,25025 ,13449,13448,13483 ,0,0,0}, {25027,24945,25026 ,13485,13399,13484 ,0,0,0}, + {24945,24992,25026 ,13399,13449,13484 ,0,0,0}, {24995,24946,25027 ,13452,13400,13485 ,0,0,0}, + {24946,24945,25027 ,13400,13399,13485 ,0,0,0}, {24995,23323,24993 ,13452,13486,13450 ,0,0,0}, + {24946,24995,24994 ,13400,13452,13451 ,0,0,0}, {25028,24996,24993 ,13487,13453,13450 ,0,0,0}, + {24996,24994,24993 ,13453,13451,13450 ,0,0,0}, {25029,24997,25028 ,13488,13454,13487 ,0,0,0}, + {24997,24996,25028 ,13454,13453,13487 ,0,0,0}, {25030,24998,25029 ,13489,13455,13488 ,0,0,0}, + {24998,24997,25029 ,13455,13454,13488 ,0,0,0}, {25031,24999,25030 ,13490,13456,13489 ,0,0,0}, + {24999,24998,25030 ,13456,13455,13489 ,0,0,0}, {25032,25000,25031 ,13491,13457,13490 ,0,0,0}, + {25000,24999,25031 ,13457,13456,13490 ,0,0,0}, {25033,25001,25032 ,13492,13458,13491 ,0,0,0}, + {25001,25000,25032 ,13458,13457,13491 ,0,0,0}, {25034,24955,25033 ,13493,13409,13492 ,0,0,0}, + {24955,25001,25033 ,13409,13458,13492 ,0,0,0}, {25035,24956,25034 ,13494,13410,13493 ,0,0,0}, + {24956,24955,25034 ,13410,13409,13493 ,0,0,0}, {25036,25002,25035 ,13495,13459,13494 ,0,0,0}, + {25002,24956,25035 ,13459,13410,13494 ,0,0,0}, {25037,24734,25036 ,13496,13180,13495 ,0,0,0}, + {24734,25002,25036 ,13180,13459,13495 ,0,0,0}, {25037,25004,24733 ,13496,13461,13179 ,0,0,0}, + {24733,24734,25037 ,13179,13180,13496 ,0,0,0}, {25004,25003,25005 ,13461,13460,13462 ,0,0,0}, + {24737,25005,24735 ,13183,13462,13181 ,0,0,0}, {24960,24733,25005 ,13414,13179,13462 ,0,0,0}, + {25003,24735,25005 ,13460,13181,13462 ,0,0,0}, {24736,24735,24742 ,13182,13181,13188 ,0,0,0}, + {24963,24684,24673 ,13418,13094,13081 ,0,0,0}, {24673,24684,24350 ,13081,13094,13417 ,0,0,0}, + {23405,23401,24678 ,13281,13497,13086 ,0,0,0}, {24678,23401,24676 ,13086,13497,13084 ,0,0,0}, + {23401,23400,24676 ,13497,13498,13084 ,0,0,0}, {24676,23400,24966 ,13084,13498,13421 ,0,0,0}, + {23400,23399,24966 ,13498,13499,13421 ,0,0,0}, {24966,23399,25006 ,13421,13499,13463 ,0,0,0}, + {23399,23262,25006 ,13499,13500,13463 ,0,0,0}, {25006,23262,25007 ,13463,13500,13464 ,0,0,0}, + {23262,23252,25007 ,13500,13501,13464 ,0,0,0}, {25007,23252,25008 ,13464,13501,13465 ,0,0,0}, + {23252,23285,25008 ,13501,13502,13465 ,0,0,0}, {25008,23285,25009 ,13465,13502,13466 ,0,0,0}, + {23285,23282,25009 ,13502,13503,13466 ,0,0,0}, {25009,23282,25010 ,13466,13503,13467 ,0,0,0}, + {23282,23287,25010 ,13503,13504,13467 ,0,0,0}, {23287,23290,25011 ,13504,13505,13468 ,0,0,0}, + {23287,25011,25010 ,13504,13468,13467 ,0,0,0}, {23290,23257,25012 ,13505,13506,13469 ,0,0,0}, + {23290,25012,25011 ,13505,13469,13468 ,0,0,0}, {23257,23256,25013 ,13506,13507,13470 ,0,0,0}, + {23257,25013,25012 ,13506,13470,13469 ,0,0,0}, {23256,23292,25014 ,13507,13508,13471 ,0,0,0}, + {23256,25014,25013 ,13507,13471,13470 ,0,0,0}, {23292,23394,24974 ,13508,13509,13430 ,0,0,0}, + {23292,24974,25014 ,13508,13430,13471 ,0,0,0}, {23393,24974,23394 ,13428,13430,13509 ,0,0,0}, + {23393,23295,24973 ,13428,13510,13429 ,0,0,0}, {24973,23295,25015 ,13429,13510,13472 ,0,0,0}, + {23295,23300,25015 ,13510,13511,13472 ,0,0,0}, {25015,23300,25016 ,13472,13511,13473 ,0,0,0}, + {23300,23298,25016 ,13511,13512,13473 ,0,0,0}, {23298,23297,25017 ,13512,13513,13474 ,0,0,0}, + {23298,25017,25016 ,13512,13474,13473 ,0,0,0}, {23297,23392,25018 ,13513,13514,13475 ,0,0,0}, + {23297,25018,25017 ,13513,13475,13474 ,0,0,0}, {23392,23301,24982 ,13514,13476,13438 ,0,0,0}, + {23392,24982,25018 ,13514,13438,13475 ,0,0,0}, {23301,23391,24980 ,13476,13515,13436 ,0,0,0}, + {23391,23387,24980 ,13515,13516,13436 ,0,0,0}, {24980,23387,25019 ,13436,13516,13477 ,0,0,0}, + {23387,23305,25019 ,13516,13517,13477 ,0,0,0}, {25019,23305,25020 ,13477,13517,13478 ,0,0,0}, + {23305,23307,25020 ,13517,13518,13478 ,0,0,0}, {23307,23312,25021 ,13518,13519,13479 ,0,0,0}, + {23307,25021,25020 ,13518,13479,13478 ,0,0,0}, {23312,23310,25022 ,13519,13520,13480 ,0,0,0}, + {23312,25022,25021 ,13519,13480,13479 ,0,0,0}, {23310,23309,25023 ,13520,13521,13481 ,0,0,0}, + {23310,25023,25022 ,13520,13481,13480 ,0,0,0}, {23309,23385,24986 ,13521,13522,13442 ,0,0,0}, + {23309,24986,25023 ,13521,13442,13481 ,0,0,0}, {23384,24986,23385 ,13443,13442,13522 ,0,0,0}, + {23384,23314,24987 ,13443,13523,13444 ,0,0,0}, {24987,23314,25024 ,13444,13523,13482 ,0,0,0}, + {23314,23321,25024 ,13523,13524,13482 ,0,0,0}, {23321,23320,25025 ,13524,13525,13483 ,0,0,0}, + {23321,25025,25024 ,13524,13483,13482 ,0,0,0}, {23320,23319,25026 ,13525,13526,13484 ,0,0,0}, + {23320,25026,25025 ,13525,13484,13483 ,0,0,0}, {23319,23381,25027 ,13526,13527,13485 ,0,0,0}, + {23319,25027,25026 ,13526,13485,13484 ,0,0,0}, {23381,23323,24995 ,13527,13486,13452 ,0,0,0}, + {23381,24995,25027 ,13527,13452,13485 ,0,0,0}, {23323,23322,24993 ,13486,13528,13450 ,0,0,0}, + {23322,23328,24993 ,13528,13529,13450 ,0,0,0}, {24993,23328,25028 ,13450,13529,13487 ,0,0,0}, + {23328,23327,25028 ,13529,13530,13487 ,0,0,0}, {25028,23327,25029 ,13487,13530,13488 ,0,0,0}, + {23327,23332,25029 ,13530,13531,13488 ,0,0,0}, {25029,23332,25030 ,13488,13531,13489 ,0,0,0}, + {23332,23330,25030 ,13531,13532,13489 ,0,0,0}, {23330,23338,25031 ,13532,13533,13490 ,0,0,0}, + {23330,25031,25030 ,13532,13490,13489 ,0,0,0}, {23338,23334,25032 ,13533,13534,13491 ,0,0,0}, + {23338,25032,25031 ,13533,13491,13490 ,0,0,0}, {23334,23336,25033 ,13534,13535,13492 ,0,0,0}, + {23334,25033,25032 ,13534,13492,13491 ,0,0,0}, {23336,23339,25034 ,13535,13536,13493 ,0,0,0}, + {23336,25034,25033 ,13535,13493,13492 ,0,0,0}, {23339,23341,25035 ,13536,13537,13494 ,0,0,0}, + {23339,25035,25034 ,13536,13494,13493 ,0,0,0}, {23341,23346,25036 ,13537,13538,13495 ,0,0,0}, + {23341,25036,25035 ,13537,13495,13494 ,0,0,0}, {23346,23352,25037 ,13538,13539,13496 ,0,0,0}, + {23346,25037,25036 ,13538,13496,13495 ,0,0,0}, {23352,23353,25004 ,13539,13540,13461 ,0,0,0}, + {23352,25004,25037 ,13539,13461,13496 ,0,0,0}, {23353,23351,25003 ,13540,13541,13460 ,0,0,0}, + {23353,25003,25004 ,13540,13460,13461 ,0,0,0}, {23351,23345,24741 ,13541,13542,13187 ,0,0,0}, + {23351,24741,25003 ,13541,13187,13460 ,0,0,0}, {24741,23345,23344 ,13187,13542,11616 ,0,0,0}, + {24574,24280,24301 ,13543,13543,13543 ,0,0,0}, {23910,24297,23906 ,13543,13543,13543 ,0,0,0}, + {24296,24301,24362 ,13543,13543,13543 ,0,0,0}, {24574,24301,24281 ,13543,13543,13543 ,0,0,0}, + {24296,24362,24439 ,13543,13543,13543 ,0,0,0}, {24281,24296,23911 ,13543,13543,13543 ,0,0,0}, + {24301,24296,24281 ,13543,13543,13543 ,0,0,0}, {23771,23906,24297 ,13543,13543,13543 ,0,0,0}, + {23910,24294,24291 ,13543,13543,13543 ,0,0,0}, {23777,23786,24121 ,13543,13543,13543 ,0,0,0}, + {23912,23771,24297 ,13543,13543,13543 ,0,0,0}, {23913,23912,23777 ,13543,13543,13543 ,0,0,0}, + {23912,23913,23902 ,13543,13543,13543 ,0,0,0}, {23784,23777,24121 ,13543,13543,13543 ,0,0,0}, + {23785,23786,23912 ,13543,13543,13543 ,0,0,0}, {23786,23777,23912 ,13543,13543,13543 ,0,0,0}, + {24299,23912,24297 ,13543,13543,13543 ,0,0,0}, {24299,23785,23912 ,13543,13543,13543 ,0,0,0}, + {24297,23910,24291 ,13543,13543,13543 ,0,0,0}, {24294,23910,24296 ,13543,13543,13543 ,0,0,0}, + {23911,24296,23909 ,13543,13543,13543 ,0,0,0}, {23910,23909,24296 ,13543,13543,13543 ,0,0,0}, + {24961,24736,24742 ,13544,13544,13544 ,0,0,0}, {24790,24827,23540 ,13544,13544,13544 ,0,0,0}, + {24746,24962,24742 ,13544,13544,13544 ,0,0,0}, {24866,24916,23456 ,13544,13544,13544 ,0,0,0}, + {24915,24962,24916 ,13544,13544,13544 ,0,0,0}, {24962,24746,23344 ,13544,13544,13544 ,0,0,0}, + {24961,24742,24962 ,13544,13544,13544 ,0,0,0}, {23456,24916,24962 ,13544,13544,13544 ,0,0,0}, + {24962,23344,23456 ,13544,13544,13544 ,0,0,0}, {23455,24866,23456 ,13544,13544,13544 ,0,0,0}, + {23455,23498,24866 ,13544,13544,13544 ,0,0,0}, {24827,24866,23540 ,13544,13544,13544 ,0,0,0}, + {23498,23540,24866 ,13544,13544,13544 ,0,0,0}, {24791,24790,23540 ,13544,13544,13544 ,0,0,0}, + {23584,23626,23585 ,13544,13544,13544 ,0,0,0}, {23585,24791,23540 ,13544,13544,13544 ,0,0,0}, + {24791,23585,23626 ,13544,13544,13544 ,0,0,0}, {23377,23625,23372 ,13544,13544,13544 ,0,0,0}, + {24791,23626,23378 ,13544,13544,13544 ,0,0,0}, {23626,23377,23376 ,13544,13544,13544 ,0,0,0}, + {23377,23626,23625 ,13544,13544,13544 ,0,0,0}, {23626,23376,23378 ,13544,13544,13544 ,0,0,0} +// Landegestell.prt + , {25038,25039,25040 ,13545,13546,13547 ,0,0,0}, {25041,25042,25043 ,13548,13549,13550 ,0,0,0}, + {25044,25045,25046 ,13551,13552,13553 ,0,0,0}, {25047,25039,25048 ,13554,13546,13555 ,0,0,0}, + {25049,25046,25050 ,13556,13553,13557 ,0,0,0}, {25051,25052,25053 ,13558,13559,13560 ,0,0,0}, + {25054,25055,25056 ,13561,13562,13563 ,0,0,0}, {25057,25050,25045 ,13564,13557,13552 ,0,0,0}, + {25058,25059,25060 ,13565,13566,13567 ,0,0,0}, {25054,25061,25060 ,13561,13568,13567 ,0,0,0}, + {25062,25063,25064 ,13569,13570,13571 ,0,0,0}, {25064,25063,25059 ,13571,13570,13566 ,0,0,0}, + {25065,25064,25066 ,13572,13571,13573 ,0,0,0}, {25048,25039,25038 ,13555,13546,13545 ,0,0,0}, + {25066,25067,25065 ,13573,13574,13572 ,0,0,0}, {25068,25069,25070 ,13575,13576,13577 ,0,0,0}, + {25040,25071,25038 ,13547,13578,13545 ,0,0,0}, {25072,25073,25070 ,13579,13580,13577 ,0,0,0}, + {25074,25075,25072 ,13581,13582,13579 ,0,0,0}, {25075,25076,25072 ,13582,13583,13579 ,0,0,0}, + {25070,25073,25068 ,13577,13580,13575 ,0,0,0}, {25077,25078,25042 ,13584,13585,13549 ,0,0,0}, + {25079,25080,25081 ,13586,13587,13588 ,0,0,0}, {25077,25082,25078 ,13584,13589,13585 ,0,0,0}, + {25083,25084,25085 ,13590,13591,13592 ,0,0,0}, {25080,25086,25081 ,13587,13593,13588 ,0,0,0}, + {25087,25088,25089 ,13594,13595,13596 ,0,0,0}, {25083,25085,25090 ,13590,13592,13597 ,0,0,0}, + {25091,25092,25093 ,13598,13599,13600 ,0,0,0}, {25092,25091,25094 ,13599,13598,13601 ,0,0,0}, + {25095,25096,25097 ,13602,13603,13604 ,0,0,0}, {25098,25099,25096 ,13605,13606,13603 ,0,0,0}, + {25100,25101,25102 ,13607,13608,13609 ,0,0,0}, {25095,25097,25103 ,13602,13604,13610 ,0,0,0}, + {25104,25105,25106 ,13611,13612,13613 ,0,0,0}, {25100,25102,25107 ,13607,13609,13614 ,0,0,0}, + {25108,25109,25110 ,13615,13616,13617 ,0,0,0}, {25111,25105,25104 ,13618,13612,13611 ,0,0,0}, + {25112,25113,25114 ,13619,13620,13621 ,0,0,0}, {25114,25110,25112 ,13621,13617,13619 ,0,0,0}, + {25115,25116,25117 ,13622,13623,13624 ,0,0,0}, {25118,25113,25119 ,13625,13620,13626 ,0,0,0}, + {25120,25121,25122 ,13627,13628,13629 ,0,0,0}, {25123,25120,25124 ,13630,13627,13631 ,0,0,0}, + {25125,25126,25127 ,13632,13633,13634 ,0,0,0}, {25128,25125,25122 ,13635,13632,13629 ,0,0,0}, + {25129,25130,25131 ,13636,13637,13638 ,0,0,0}, {25132,25127,25133 ,13639,13634,13640 ,0,0,0}, + {25134,25135,25136 ,13641,13642,13643 ,0,0,0}, {25131,25137,25129 ,13638,13644,13636 ,0,0,0}, + {25138,25134,25139 ,13645,13641,13646 ,0,0,0}, {25129,25137,25140 ,13636,13644,13647 ,0,0,0}, + {25141,25138,25132 ,13648,13645,13639 ,0,0,0}, {25134,25138,25141 ,13641,13645,13648 ,0,0,0}, + {25142,25143,25144 ,13649,13650,13651 ,0,0,0}, {25145,25128,25146 ,13652,13635,13653 ,0,0,0}, + {25147,25148,25149 ,13654,13655,13656 ,0,0,0}, {25145,25146,25150 ,13652,13653,13657 ,0,0,0}, + {25151,25152,25153 ,13658,13659,13660 ,0,0,0}, {25149,25154,25155 ,13656,13661,13662 ,0,0,0}, + {25156,25157,25153 ,13663,13664,13660 ,0,0,0}, {25158,25159,25160 ,13665,13666,13667 ,0,0,0}, + {25161,25162,25163 ,13668,13669,13670 ,0,0,0}, {25163,25160,25161 ,13670,13667,13668 ,0,0,0}, + {25162,25161,25164 ,13669,13668,13671 ,0,0,0}, {25133,25127,25126 ,13640,13634,13633 ,0,0,0}, + {25134,25140,25139 ,13641,13647,13646 ,0,0,0}, {25128,25122,25121 ,13635,13629,13628 ,0,0,0}, + {25128,25126,25125 ,13635,13633,13632 ,0,0,0}, {25123,25124,25115 ,13630,13631,13622 ,0,0,0}, + {25120,25123,25121 ,13627,13630,13628 ,0,0,0}, {25117,25116,25118 ,13624,13623,13625 ,0,0,0}, + {25124,25116,25115 ,13631,13623,13622 ,0,0,0}, {25117,25118,25119 ,13624,13625,13626 ,0,0,0}, + {25165,25123,25115 ,13672,13630,13622 ,0,0,0}, {25114,25108,25110 ,13621,13615,13617 ,0,0,0}, + {25113,25112,25119 ,13620,13619,13626 ,0,0,0}, {25104,25106,25166 ,13611,13613,13673 ,0,0,0}, + {25167,25111,25168 ,13674,13618,13675 ,0,0,0}, {25110,25109,25168 ,13617,13616,13675 ,0,0,0}, + {25105,25111,25167 ,13612,13618,13674 ,0,0,0}, {25109,25167,25168 ,13616,13674,13675 ,0,0,0}, + {25166,25106,25107 ,13673,13613,13614 ,0,0,0}, {25169,25104,25166 ,13676,13611,13673 ,0,0,0}, + {25107,25102,25166 ,13614,13609,13673 ,0,0,0}, {25103,25101,25170 ,13610,13608,13677 ,0,0,0}, + {25100,25170,25101 ,13607,13677,13608 ,0,0,0}, {25171,25103,25170 ,13678,13610,13677 ,0,0,0}, + {25099,25097,25096 ,13606,13604,13603 ,0,0,0}, {25095,25103,25171 ,13602,13610,13678 ,0,0,0}, + {25098,25172,25099 ,13605,13679,13606 ,0,0,0}, {25093,25092,25172 ,13600,13599,13679 ,0,0,0}, + {25172,25098,25093 ,13679,13605,13600 ,0,0,0}, {25094,25173,25089 ,13601,13680,13596 ,0,0,0}, + {25174,25175,25176 ,13681,13682,13683 ,0,0,0}, {25089,25173,25177 ,13596,13680,13684 ,0,0,0}, + {25173,25094,25091 ,13680,13601,13598 ,0,0,0}, {25178,25090,25088 ,13685,13597,13595 ,0,0,0}, + {25087,25089,25177 ,13594,13596,13684 ,0,0,0}, {25090,25178,25083 ,13597,13685,13590 ,0,0,0}, + {25178,25088,25087 ,13685,13595,13594 ,0,0,0}, {25082,25179,25180 ,13589,13686,13687 ,0,0,0}, + {25084,25086,25181 ,13591,13593,13688 ,0,0,0}, {25085,25084,25181 ,13592,13591,13688 ,0,0,0}, + {25181,25086,25080 ,13688,13593,13587 ,0,0,0}, {25182,25183,25184 ,13689,13690,13691 ,0,0,0}, + {25179,25079,25081 ,13686,13586,13588 ,0,0,0}, {25071,25040,25069 ,13578,13547,13576 ,0,0,0}, + {25082,25079,25179 ,13589,13586,13686 ,0,0,0}, {25082,25180,25078 ,13589,13687,13585 ,0,0,0}, + {25042,25041,25077 ,13549,13548,13584 ,0,0,0}, {25076,25075,25043 ,13583,13582,13550 ,0,0,0}, + {25043,25075,25041 ,13550,13582,13548 ,0,0,0}, {25068,25071,25069 ,13575,13578,13576 ,0,0,0}, + {25076,25073,25072 ,13583,13580,13579 ,0,0,0}, {25053,25185,25186 ,13560,13692,13693 ,0,0,0}, + {25047,25048,25185 ,13554,13555,13692 ,0,0,0}, {25186,25051,25053 ,13693,13558,13560 ,0,0,0}, + {25047,25185,25053 ,13554,13692,13560 ,0,0,0}, {25186,25187,25051 ,13693,13694,13558 ,0,0,0}, + {25188,25189,25055 ,13695,13696,13562 ,0,0,0}, {25051,25187,25190 ,13558,13694,13697 ,0,0,0}, + {25190,25187,25191 ,13697,13694,13698 ,0,0,0}, {25192,25190,25193 ,13699,13697,13700 ,0,0,0}, + {25191,25193,25190 ,13698,13700,13697 ,0,0,0}, {25056,25194,25054 ,13563,13701,13561 ,0,0,0}, + {25195,25192,25193 ,13702,13699,13700 ,0,0,0}, {25196,25195,25193 ,13703,13702,13700 ,0,0,0}, + {25192,25195,25197 ,13699,13702,13704 ,0,0,0}, {25198,25199,25197 ,13705,13706,13704 ,0,0,0}, + {25189,25188,25200 ,13696,13695,13707 ,0,0,0}, {25197,25199,25192 ,13704,13706,13699 ,0,0,0}, + {25198,25188,25199 ,13705,13695,13706 ,0,0,0}, {25192,25201,25190 ,13699,13708,13697 ,0,0,0}, + {25202,25047,25053 ,13709,13554,13560 ,0,0,0}, {25190,25044,25051 ,13697,13551,13558 ,0,0,0}, + {25203,25039,25047 ,13710,13546,13554 ,0,0,0}, {25052,25051,25044 ,13559,13558,13551 ,0,0,0}, + {25204,25040,25039 ,13711,13547,13546 ,0,0,0}, {25202,25053,25052 ,13709,13560,13559 ,0,0,0}, + {25205,25069,25040 ,13712,13576,13547 ,0,0,0}, {25203,25047,25202 ,13710,13554,13709 ,0,0,0}, + {25206,25070,25069 ,13713,13577,13576 ,0,0,0}, {25204,25039,25203 ,13711,13546,13710 ,0,0,0}, + {25207,25072,25070 ,13714,13579,13577 ,0,0,0}, {25040,25204,25205 ,13547,13711,13712 ,0,0,0}, + {25208,25209,25210 ,13715,13716,13717 ,0,0,0}, {25069,25205,25206 ,13576,13712,13713 ,0,0,0}, + {25210,25041,25075 ,13717,13548,13582 ,0,0,0}, {25070,25206,25207 ,13577,13713,13714 ,0,0,0}, + {25211,25077,25041 ,13718,13584,13548 ,0,0,0}, {25072,25207,25074 ,13579,13714,13581 ,0,0,0}, + {25212,25082,25077 ,13719,13589,13584 ,0,0,0}, {25075,25074,25210 ,13582,13581,13717 ,0,0,0}, + {25213,25079,25082 ,13720,13586,13589 ,0,0,0}, {25041,25210,25211 ,13548,13717,13718 ,0,0,0}, + {25214,25080,25079 ,13721,13587,13586 ,0,0,0}, {25212,25077,25211 ,13719,13584,13718 ,0,0,0}, + {25215,25181,25080 ,13722,13688,13587 ,0,0,0}, {25213,25082,25212 ,13720,13589,13719 ,0,0,0}, + {25216,25085,25181 ,13723,13592,13688 ,0,0,0}, {25079,25213,25214 ,13586,13720,13721 ,0,0,0}, + {25183,25090,25085 ,13690,13597,13592 ,0,0,0}, {25080,25214,25215 ,13587,13721,13722 ,0,0,0}, + {25217,25088,25090 ,13724,13595,13597 ,0,0,0}, {25181,25215,25216 ,13688,13722,13723 ,0,0,0}, + {25218,25089,25088 ,13725,13596,13595 ,0,0,0}, {25085,25216,25183 ,13592,13723,13690 ,0,0,0}, + {25219,25094,25089 ,13726,13601,13596 ,0,0,0}, {25217,25090,25183 ,13724,13597,13690 ,0,0,0}, + {25220,25092,25094 ,13727,13599,13601 ,0,0,0}, {25218,25088,25217 ,13725,13595,13724 ,0,0,0}, + {25221,25172,25092 ,13728,13679,13599 ,0,0,0}, {25089,25218,25219 ,13596,13725,13726 ,0,0,0}, + {25099,25172,25174 ,13606,13679,13681 ,0,0,0}, {25094,25219,25220 ,13601,13726,13727 ,0,0,0}, + {25222,25097,25099 ,13729,13604,13606 ,0,0,0}, {25092,25220,25221 ,13599,13727,13728 ,0,0,0}, + {25223,25103,25097 ,13730,13610,13604 ,0,0,0}, {25172,25221,25174 ,13679,13728,13681 ,0,0,0}, + {25224,25101,25103 ,13731,13608,13610 ,0,0,0}, {25222,25099,25174 ,13729,13606,13681 ,0,0,0}, + {25225,25102,25101 ,13732,13609,13608 ,0,0,0}, {25223,25097,25222 ,13730,13604,13729 ,0,0,0}, + {25226,25166,25102 ,13733,13673,13609 ,0,0,0}, {25103,25223,25224 ,13610,13730,13731 ,0,0,0}, + {25227,25228,25229 ,13734,13735,13736 ,0,0,0}, {25101,25224,25225 ,13608,13731,13732 ,0,0,0}, + {25230,25111,25104 ,13737,13618,13611 ,0,0,0}, {25102,25225,25226 ,13609,13732,13733 ,0,0,0}, + {25231,25168,25111 ,13738,13675,13618 ,0,0,0}, {25166,25226,25169 ,13673,13733,13676 ,0,0,0}, + {25232,25110,25168 ,13739,13617,13675 ,0,0,0}, {25104,25169,25230 ,13611,13676,13737 ,0,0,0}, + {25233,25112,25110 ,13740,13619,13617 ,0,0,0}, {25231,25111,25230 ,13738,13618,13737 ,0,0,0}, + {25234,25119,25112 ,13741,13626,13619 ,0,0,0}, {25232,25168,25231 ,13739,13675,13738 ,0,0,0}, + {25235,25117,25119 ,13742,13624,13626 ,0,0,0}, {25233,25110,25232 ,13740,13617,13739 ,0,0,0}, + {25236,25115,25117 ,13743,13622,13624 ,0,0,0}, {25112,25233,25234 ,13619,13740,13741 ,0,0,0}, + {25123,25237,25121 ,13630,13744,13628 ,0,0,0}, {25119,25234,25235 ,13626,13741,13742 ,0,0,0}, + {25146,25238,25150 ,13653,13745,13657 ,0,0,0}, {25117,25235,25236 ,13624,13742,13743 ,0,0,0}, + {25146,25128,25121 ,13653,13635,13628 ,0,0,0}, {25115,25236,25165 ,13622,13743,13672 ,0,0,0}, + {25145,25126,25128 ,13652,13633,13635 ,0,0,0}, {25123,25165,25237 ,13630,13672,13744 ,0,0,0}, + {25133,25126,25239 ,13640,13633,13746 ,0,0,0}, {25237,25146,25121 ,13744,13653,13628 ,0,0,0}, + {25148,25135,25141 ,13655,13642,13648 ,0,0,0}, {25135,25148,25147 ,13642,13655,13654 ,0,0,0}, + {25133,25141,25132 ,13640,13648,13639 ,0,0,0}, {25126,25145,25239 ,13633,13652,13746 ,0,0,0}, + {25129,25140,25240 ,13636,13647,13747 ,0,0,0}, {25133,25148,25141 ,13640,13655,13648 ,0,0,0}, + {25134,25141,25135 ,13641,13648,13642 ,0,0,0}, {25241,25242,25129 ,13748,13749,13636 ,0,0,0}, + {25139,25140,25137 ,13646,13647,13644 ,0,0,0}, {25136,25240,25140 ,13643,13747,13647 ,0,0,0}, + {25130,25129,25242 ,13637,13636,13749 ,0,0,0}, {25199,25201,25192 ,13706,13708,13699 ,0,0,0}, + {25200,25188,25198 ,13707,13695,13705 ,0,0,0}, {25061,25243,25060 ,13568,13750,13567 ,0,0,0}, + {25201,25044,25190 ,13708,13551,13697 ,0,0,0}, {25199,25244,25201 ,13706,13751,13708 ,0,0,0}, + {25052,25046,25245 ,13559,13553,13752 ,0,0,0}, {25045,25044,25201 ,13552,13551,13708 ,0,0,0}, + {25202,25245,25246 ,13709,13752,13753 ,0,0,0}, {25046,25052,25044 ,13553,13559,13551 ,0,0,0}, + {25203,25246,25247 ,13710,13753,13754 ,0,0,0}, {25245,25202,25052 ,13752,13709,13559 ,0,0,0}, + {25204,25247,25248 ,13711,13754,13755 ,0,0,0}, {25246,25203,25202 ,13753,13710,13709 ,0,0,0}, + {25205,25248,25249 ,13712,13755,13756 ,0,0,0}, {25247,25204,25203 ,13754,13711,13710 ,0,0,0}, + {25206,25249,25250 ,13713,13756,13757 ,0,0,0}, {25248,25205,25204 ,13755,13712,13711 ,0,0,0}, + {25207,25250,25251 ,13714,13757,13758 ,0,0,0}, {25249,25206,25205 ,13756,13713,13712 ,0,0,0}, + {25074,25251,25208 ,13581,13758,13715 ,0,0,0}, {25207,25206,25250 ,13714,13713,13757 ,0,0,0}, + {25252,25253,25254 ,13759,13760,13761 ,0,0,0}, {25074,25207,25251 ,13581,13714,13758 ,0,0,0}, + {25211,25209,25252 ,13718,13716,13759 ,0,0,0}, {25210,25074,25208 ,13717,13581,13715 ,0,0,0}, + {25212,25252,25255 ,13719,13759,13762 ,0,0,0}, {25211,25210,25209 ,13718,13717,13716 ,0,0,0}, + {25213,25255,25256 ,13720,13762,13763 ,0,0,0}, {25252,25212,25211 ,13759,13719,13718 ,0,0,0}, + {25214,25256,25257 ,13721,13763,13764 ,0,0,0}, {25255,25213,25212 ,13762,13720,13719 ,0,0,0}, + {25215,25257,25258 ,13722,13764,13765 ,0,0,0}, {25256,25214,25213 ,13763,13721,13720 ,0,0,0}, + {25216,25258,25184 ,13723,13765,13691 ,0,0,0}, {25215,25214,25257 ,13722,13721,13764 ,0,0,0}, + {25259,25260,25261 ,13766,13767,13768 ,0,0,0}, {25216,25215,25258 ,13723,13722,13765 ,0,0,0}, + {25217,25182,25262 ,13724,13689,13769 ,0,0,0}, {25183,25216,25184 ,13690,13723,13691 ,0,0,0}, + {25218,25262,25263 ,13725,13769,13770 ,0,0,0}, {25182,25217,25183 ,13689,13724,13690 ,0,0,0}, + {25219,25263,25264 ,13726,13770,13771 ,0,0,0}, {25262,25218,25217 ,13769,13725,13724 ,0,0,0}, + {25220,25264,25265 ,13727,13771,13772 ,0,0,0}, {25263,25219,25218 ,13770,13726,13725 ,0,0,0}, + {25221,25265,25175 ,13728,13772,13682 ,0,0,0}, {25220,25219,25264 ,13727,13726,13771 ,0,0,0}, + {25266,25267,25268 ,13773,13774,13775 ,0,0,0}, {25221,25220,25265 ,13728,13727,13772 ,0,0,0}, + {25222,25176,25269 ,13729,13683,13776 ,0,0,0}, {25174,25221,25175 ,13681,13728,13682 ,0,0,0}, + {25223,25269,25270 ,13730,13776,13777 ,0,0,0}, {25222,25174,25176 ,13729,13681,13683 ,0,0,0}, + {25224,25270,25271 ,13731,13777,13778 ,0,0,0}, {25269,25223,25222 ,13776,13730,13729 ,0,0,0}, + {25225,25271,25272 ,13732,13778,13779 ,0,0,0}, {25270,25224,25223 ,13777,13731,13730 ,0,0,0}, + {25226,25272,25273 ,13733,13779,13780 ,0,0,0}, {25271,25225,25224 ,13778,13732,13731 ,0,0,0}, + {25169,25273,25274 ,13676,13780,13781 ,0,0,0}, {25226,25225,25272 ,13733,13732,13779 ,0,0,0}, + {25230,25274,25228 ,13737,13781,13735 ,0,0,0}, {25169,25226,25273 ,13676,13733,13780 ,0,0,0}, + {25231,25228,25275 ,13738,13735,13782 ,0,0,0}, {25230,25169,25274 ,13737,13676,13781 ,0,0,0}, + {25232,25275,25276 ,13739,13782,13783 ,0,0,0}, {25228,25231,25230 ,13735,13738,13737 ,0,0,0}, + {25233,25276,25277 ,13740,13783,13784 ,0,0,0}, {25275,25232,25231 ,13782,13739,13738 ,0,0,0}, + {25234,25277,25278 ,13741,13784,13785 ,0,0,0}, {25276,25233,25232 ,13783,13740,13739 ,0,0,0}, + {25235,25278,25279 ,13742,13785,13786 ,0,0,0}, {25277,25234,25233 ,13784,13741,13740 ,0,0,0}, + {25236,25279,25280 ,13743,13786,13787 ,0,0,0}, {25278,25235,25234 ,13785,13742,13741 ,0,0,0}, + {25165,25280,25281 ,13672,13787,13788 ,0,0,0}, {25279,25236,25235 ,13786,13743,13742 ,0,0,0}, + {25237,25281,25238 ,13744,13788,13745 ,0,0,0}, {25165,25236,25280 ,13672,13743,13787 ,0,0,0}, + {25282,25145,25150 ,13789,13652,13657 ,0,0,0}, {25237,25165,25281 ,13744,13672,13788 ,0,0,0}, + {25155,25151,25283 ,13662,13658,13790 ,0,0,0}, {25146,25237,25238 ,13653,13744,13745 ,0,0,0}, + {25282,25149,25239 ,13789,13656,13746 ,0,0,0}, {25142,25135,25147 ,13649,13642,13654 ,0,0,0}, + {25239,25148,25133 ,13746,13655,13640 ,0,0,0}, {25282,25239,25145 ,13789,13746,13652 ,0,0,0}, + {25155,25147,25149 ,13662,13654,13656 ,0,0,0}, {25239,25149,25148 ,13746,13656,13655 ,0,0,0}, + {25284,25240,25144 ,13791,13747,13651 ,0,0,0}, {25240,25241,25129 ,13747,13748,13636 ,0,0,0}, + {25134,25136,25140 ,13641,13643,13647 ,0,0,0}, {25136,25142,25144 ,13643,13649,13651 ,0,0,0}, + {25284,25241,25240 ,13791,13748,13747 ,0,0,0}, {25188,25244,25199 ,13695,13751,13706 ,0,0,0}, + {25056,25055,25189 ,13563,13562,13696 ,0,0,0}, {25059,25063,25285 ,13566,13570,13792 ,0,0,0}, + {25244,25045,25201 ,13751,13552,13708 ,0,0,0}, {25188,25286,25244 ,13695,13793,13751 ,0,0,0}, + {25287,25288,25289 ,13794,13795,13796 ,0,0,0}, {25057,25045,25244 ,13564,13552,13751 ,0,0,0}, + {25049,25287,25245 ,13556,13794,13752 ,0,0,0}, {25050,25046,25045 ,13557,13553,13552 ,0,0,0}, + {25287,25290,25246 ,13794,13797,13753 ,0,0,0}, {25049,25245,25046 ,13556,13752,13553 ,0,0,0}, + {25290,25291,25247 ,13797,13798,13754 ,0,0,0}, {25287,25246,25245 ,13794,13753,13752 ,0,0,0}, + {25291,25292,25248 ,13798,13799,13755 ,0,0,0}, {25290,25247,25246 ,13797,13754,13753 ,0,0,0}, + {25292,25293,25249 ,13799,13800,13756 ,0,0,0}, {25291,25248,25247 ,13798,13755,13754 ,0,0,0}, + {25293,25294,25250 ,13800,13801,13757 ,0,0,0}, {25292,25249,25248 ,13799,13756,13755 ,0,0,0}, + {25294,25295,25251 ,13801,13802,13758 ,0,0,0}, {25293,25250,25249 ,13800,13757,13756 ,0,0,0}, + {25295,25296,25208 ,13802,13803,13715 ,0,0,0}, {25294,25251,25250 ,13801,13758,13757 ,0,0,0}, + {25296,25253,25209 ,13803,13760,13716 ,0,0,0}, {25208,25251,25295 ,13715,13758,13802 ,0,0,0}, + {25297,25298,25299 ,13804,13805,13806 ,0,0,0}, {25209,25208,25296 ,13716,13715,13803 ,0,0,0}, + {25254,25297,25255 ,13761,13804,13762 ,0,0,0}, {25253,25252,25209 ,13760,13759,13716 ,0,0,0}, + {25297,25300,25256 ,13804,13807,13763 ,0,0,0}, {25254,25255,25252 ,13761,13762,13759 ,0,0,0}, + {25300,25301,25257 ,13807,13808,13764 ,0,0,0}, {25297,25256,25255 ,13804,13763,13762 ,0,0,0}, + {25301,25302,25258 ,13808,13809,13765 ,0,0,0}, {25300,25257,25256 ,13807,13764,13763 ,0,0,0}, + {25302,25303,25184 ,13809,13810,13691 ,0,0,0}, {25301,25258,25257 ,13808,13765,13764 ,0,0,0}, + {25182,25303,25304 ,13689,13810,13811 ,0,0,0}, {25184,25258,25302 ,13691,13765,13809 ,0,0,0}, + {25304,25259,25262 ,13811,13766,13769 ,0,0,0}, {25303,25182,25184 ,13810,13689,13691 ,0,0,0}, + {25259,25305,25263 ,13766,13812,13770 ,0,0,0}, {25304,25262,25182 ,13811,13769,13689 ,0,0,0}, + {25305,25306,25264 ,13812,13813,13771 ,0,0,0}, {25259,25263,25262 ,13766,13770,13769 ,0,0,0}, + {25306,25307,25265 ,13813,13814,13772 ,0,0,0}, {25305,25264,25263 ,13812,13771,13770 ,0,0,0}, + {25307,25308,25175 ,13814,13815,13682 ,0,0,0}, {25306,25265,25264 ,13813,13772,13771 ,0,0,0}, + {25308,25309,25176 ,13815,13816,13683 ,0,0,0}, {25175,25265,25307 ,13682,13772,13814 ,0,0,0}, + {25309,25266,25269 ,13816,13773,13776 ,0,0,0}, {25176,25175,25308 ,13683,13682,13815 ,0,0,0}, + {25266,25310,25270 ,13773,13817,13777 ,0,0,0}, {25309,25269,25176 ,13816,13776,13683 ,0,0,0}, + {25310,25311,25271 ,13817,13818,13778 ,0,0,0}, {25266,25270,25269 ,13773,13777,13776 ,0,0,0}, + {25311,25312,25272 ,13818,13819,13779 ,0,0,0}, {25310,25271,25270 ,13817,13778,13777 ,0,0,0}, + {25312,25313,25273 ,13819,13820,13780 ,0,0,0}, {25311,25272,25271 ,13818,13779,13778 ,0,0,0}, + {25313,25229,25274 ,13820,13736,13781 ,0,0,0}, {25273,25272,25312 ,13780,13779,13819 ,0,0,0}, + {25314,25315,25316 ,13821,13822,13823 ,0,0,0}, {25274,25273,25313 ,13781,13780,13820 ,0,0,0}, + {25227,25314,25275 ,13734,13821,13782 ,0,0,0}, {25229,25228,25274 ,13736,13735,13781 ,0,0,0}, + {25314,25317,25276 ,13821,13824,13783 ,0,0,0}, {25227,25275,25228 ,13734,13782,13735 ,0,0,0}, + {25317,25318,25277 ,13824,13825,13784 ,0,0,0}, {25314,25276,25275 ,13821,13783,13782 ,0,0,0}, + {25318,25319,25278 ,13825,13826,13785 ,0,0,0}, {25317,25277,25276 ,13824,13784,13783 ,0,0,0}, + {25319,25320,25279 ,13826,13827,13786 ,0,0,0}, {25318,25278,25277 ,13825,13785,13784 ,0,0,0}, + {25320,25321,25280 ,13827,13828,13787 ,0,0,0}, {25319,25279,25278 ,13826,13786,13785 ,0,0,0}, + {25321,25322,25281 ,13828,13829,13788 ,0,0,0}, {25320,25280,25279 ,13827,13787,13786 ,0,0,0}, + {25322,25323,25238 ,13829,13830,13745 ,0,0,0}, {25321,25281,25280 ,13828,13788,13787 ,0,0,0}, + {25323,25324,25150 ,13830,13831,13657 ,0,0,0}, {25322,25238,25281 ,13829,13745,13788 ,0,0,0}, + {25324,25154,25282 ,13831,13661,13789 ,0,0,0}, {25150,25238,25323 ,13657,13745,13830 ,0,0,0}, + {25325,25147,25155 ,13832,13654,13662 ,0,0,0}, {25150,25324,25282 ,13657,13831,13789 ,0,0,0}, + {25154,25151,25155 ,13661,13658,13662 ,0,0,0}, {25282,25154,25149 ,13789,13661,13656 ,0,0,0}, + {25326,25144,25143 ,13833,13651,13650 ,0,0,0}, {25136,25144,25240 ,13643,13651,13747 ,0,0,0}, + {25135,25142,25136 ,13642,13649,13643 ,0,0,0}, {25325,25143,25142 ,13832,13650,13649 ,0,0,0}, + {25284,25144,25326 ,13791,13651,13833 ,0,0,0}, {25286,25188,25055 ,13793,13695,13562 ,0,0,0}, + {25061,25054,25194 ,13568,13561,13701 ,0,0,0}, {25057,25327,25328 ,13564,13834,13835 ,0,0,0}, + {25286,25057,25244 ,13793,13564,13751 ,0,0,0}, {25329,25286,25055 ,13836,13793,13562 ,0,0,0}, + {25050,25328,25330 ,13557,13835,13837 ,0,0,0}, {25286,25327,25057 ,13793,13834,13564 ,0,0,0}, + {25049,25330,25288 ,13556,13837,13795 ,0,0,0}, {25328,25050,25057 ,13835,13557,13564 ,0,0,0}, + {25331,25290,25289 ,13838,13797,13796 ,0,0,0}, {25330,25049,25050 ,13837,13556,13557 ,0,0,0}, + {25332,25291,25331 ,13839,13798,13838 ,0,0,0}, {25288,25287,25049 ,13795,13794,13556 ,0,0,0}, + {25333,25334,25335 ,13840,13841,13842 ,0,0,0}, {25289,25290,25287 ,13796,13797,13794 ,0,0,0}, + {25332,25333,25292 ,13839,13840,13799 ,0,0,0}, {25331,25291,25290 ,13838,13798,13797 ,0,0,0}, + {25333,25336,25293 ,13840,13843,13800 ,0,0,0}, {25332,25292,25291 ,13839,13799,13798 ,0,0,0}, + {25336,25337,25294 ,13843,13844,13801 ,0,0,0}, {25333,25293,25292 ,13840,13800,13799 ,0,0,0}, + {25337,25338,25295 ,13844,13845,13802 ,0,0,0}, {25336,25294,25293 ,13843,13801,13800 ,0,0,0}, + {25338,25339,25296 ,13845,13846,13803 ,0,0,0}, {25337,25295,25294 ,13844,13802,13801 ,0,0,0}, + {25253,25339,25340 ,13760,13846,13847 ,0,0,0}, {25338,25296,25295 ,13845,13803,13802 ,0,0,0}, + {25254,25340,25298 ,13761,13847,13805 ,0,0,0}, {25339,25253,25296 ,13846,13760,13803 ,0,0,0}, + {25341,25342,25343 ,13848,13849,13850 ,0,0,0}, {25340,25254,25253 ,13847,13761,13760 ,0,0,0}, + {25299,25341,25300 ,13806,13848,13807 ,0,0,0}, {25298,25297,25254 ,13805,13804,13761 ,0,0,0}, + {25341,25344,25301 ,13848,13851,13808 ,0,0,0}, {25299,25300,25297 ,13806,13807,13804 ,0,0,0}, + {25344,25345,25302 ,13851,13852,13809 ,0,0,0}, {25341,25301,25300 ,13848,13808,13807 ,0,0,0}, + {25303,25345,25346 ,13810,13852,13853 ,0,0,0}, {25344,25302,25301 ,13851,13809,13808 ,0,0,0}, + {25304,25346,25260 ,13811,13853,13767 ,0,0,0}, {25303,25302,25345 ,13810,13809,13852 ,0,0,0}, + {25347,25348,25349 ,13854,13855,13856 ,0,0,0}, {25346,25304,25303 ,13853,13811,13810 ,0,0,0}, + {25261,25347,25305 ,13768,13854,13812 ,0,0,0}, {25260,25259,25304 ,13767,13766,13811 ,0,0,0}, + {25347,25350,25306 ,13854,13857,13813 ,0,0,0}, {25261,25305,25259 ,13768,13812,13766 ,0,0,0}, + {25350,25351,25307 ,13857,13858,13814 ,0,0,0}, {25347,25306,25305 ,13854,13813,13812 ,0,0,0}, + {25351,25352,25308 ,13858,13859,13815 ,0,0,0}, {25350,25307,25306 ,13857,13814,13813 ,0,0,0}, + {25309,25352,25267 ,13816,13859,13774 ,0,0,0}, {25308,25307,25351 ,13815,13814,13858 ,0,0,0}, + {25353,25354,25355 ,13860,13861,13862 ,0,0,0}, {25352,25309,25308 ,13859,13816,13815 ,0,0,0}, + {25268,25353,25310 ,13775,13860,13817 ,0,0,0}, {25267,25266,25309 ,13774,13773,13816 ,0,0,0}, + {25353,25356,25311 ,13860,13863,13818 ,0,0,0}, {25268,25310,25266 ,13775,13817,13773 ,0,0,0}, + {25356,25357,25312 ,13863,13864,13819 ,0,0,0}, {25353,25311,25310 ,13860,13818,13817 ,0,0,0}, + {25357,25358,25313 ,13864,13865,13820 ,0,0,0}, {25356,25312,25311 ,13863,13819,13818 ,0,0,0}, + {25229,25358,25359 ,13736,13865,13866 ,0,0,0}, {25357,25313,25312 ,13864,13820,13819 ,0,0,0}, + {25227,25359,25315 ,13734,13866,13822 ,0,0,0}, {25358,25229,25313 ,13865,13736,13820 ,0,0,0}, + {25360,25317,25316 ,13867,13824,13823 ,0,0,0}, {25359,25227,25229 ,13866,13734,13736 ,0,0,0}, + {25361,25362,25363 ,13868,13869,13870 ,0,0,0}, {25315,25314,25227 ,13822,13821,13734 ,0,0,0}, + {25360,25361,25318 ,13867,13868,13825 ,0,0,0}, {25316,25317,25314 ,13823,13824,13821 ,0,0,0}, + {25361,25364,25319 ,13868,13871,13826 ,0,0,0}, {25360,25318,25317 ,13867,13825,13824 ,0,0,0}, + {25364,25365,25320 ,13871,13872,13827 ,0,0,0}, {25361,25319,25318 ,13868,13826,13825 ,0,0,0}, + {25365,25366,25321 ,13872,13873,13828 ,0,0,0}, {25364,25320,25319 ,13871,13827,13826 ,0,0,0}, + {25366,25367,25322 ,13873,13874,13829 ,0,0,0}, {25365,25321,25320 ,13872,13828,13827 ,0,0,0}, + {25367,25368,25323 ,13874,13875,13830 ,0,0,0}, {25366,25322,25321 ,13873,13829,13828 ,0,0,0}, + {25368,25152,25324 ,13875,13659,13831 ,0,0,0}, {25367,25323,25322 ,13874,13830,13829 ,0,0,0}, + {25154,25152,25151 ,13661,13659,13658 ,0,0,0}, {25323,25368,25324 ,13830,13875,13831 ,0,0,0}, + {25369,25143,25325 ,13876,13650,13832 ,0,0,0}, {25154,25324,25152 ,13661,13831,13659 ,0,0,0}, + {25370,25143,25369 ,13877,13650,13876 ,0,0,0}, {25371,25326,25143 ,13878,13833,13650 ,0,0,0}, + {25147,25325,25142 ,13654,13832,13649 ,0,0,0}, {25283,25369,25325 ,13790,13876,13832 ,0,0,0}, + {25370,25371,25143 ,13877,13878,13650 ,0,0,0}, {25329,25055,25054 ,13836,13562,13561 ,0,0,0}, + {25058,25060,25243 ,13565,13567,13750 ,0,0,0}, {25327,25372,25373 ,13834,13879,13880 ,0,0,0}, + {25329,25327,25286 ,13836,13834,13793 ,0,0,0}, {25054,25374,25329 ,13561,13881,13836 ,0,0,0}, + {25328,25373,25375 ,13835,13880,13882 ,0,0,0}, {25329,25372,25327 ,13836,13879,13834 ,0,0,0}, + {25330,25375,25376 ,13837,13882,13883 ,0,0,0}, {25327,25373,25328 ,13834,13880,13835 ,0,0,0}, + {25288,25376,25377 ,13795,13883,13884 ,0,0,0}, {25328,25375,25330 ,13835,13882,13837 ,0,0,0}, + {25289,25377,25378 ,13796,13884,13885 ,0,0,0}, {25330,25376,25288 ,13837,13883,13795 ,0,0,0}, + {25331,25378,25379 ,13838,13885,13886 ,0,0,0}, {25288,25377,25289 ,13795,13884,13796 ,0,0,0}, + {25332,25379,25334 ,13839,13886,13841 ,0,0,0}, {25378,25331,25289 ,13885,13838,13796 ,0,0,0}, + {25380,25336,25335 ,13887,13843,13842 ,0,0,0}, {25379,25332,25331 ,13886,13839,13838 ,0,0,0}, + {25381,25382,25380 ,13888,13889,13887 ,0,0,0}, {25334,25333,25332 ,13841,13840,13839 ,0,0,0}, + {25380,25382,25337 ,13887,13889,13844 ,0,0,0}, {25335,25336,25333 ,13842,13843,13840 ,0,0,0}, + {25382,25383,25338 ,13889,13890,13845 ,0,0,0}, {25380,25337,25336 ,13887,13844,13843 ,0,0,0}, + {25339,25383,25384 ,13846,13890,13891 ,0,0,0}, {25382,25338,25337 ,13889,13845,13844 ,0,0,0}, + {25340,25384,25385 ,13847,13891,13892 ,0,0,0}, {25338,25383,25339 ,13845,13890,13846 ,0,0,0}, + {25298,25385,25386 ,13805,13892,13893 ,0,0,0}, {25339,25384,25340 ,13846,13891,13847 ,0,0,0}, + {25299,25386,25342 ,13806,13893,13849 ,0,0,0}, {25385,25298,25340 ,13892,13805,13847 ,0,0,0}, + {25387,25388,25343 ,13894,13895,13850 ,0,0,0}, {25386,25299,25298 ,13893,13806,13805 ,0,0,0}, + {25343,25388,25344 ,13850,13895,13851 ,0,0,0}, {25342,25341,25299 ,13849,13848,13806 ,0,0,0}, + {25388,25389,25345 ,13895,13896,13852 ,0,0,0}, {25343,25344,25341 ,13850,13851,13848 ,0,0,0}, + {25346,25389,25390 ,13853,13896,13897 ,0,0,0}, {25388,25345,25344 ,13895,13852,13851 ,0,0,0}, + {25260,25390,25391 ,13767,13897,13898 ,0,0,0}, {25345,25389,25346 ,13852,13896,13853 ,0,0,0}, + {25261,25391,25348 ,13768,13898,13855 ,0,0,0}, {25390,25260,25346 ,13897,13767,13853 ,0,0,0}, + {25392,25393,25349 ,13899,13900,13856 ,0,0,0}, {25391,25261,25260 ,13898,13768,13767 ,0,0,0}, + {25349,25393,25350 ,13856,13900,13857 ,0,0,0}, {25348,25347,25261 ,13855,13854,13768 ,0,0,0}, + {25393,25394,25351 ,13900,13901,13858 ,0,0,0}, {25349,25350,25347 ,13856,13857,13854 ,0,0,0}, + {25352,25394,25395 ,13859,13901,13902 ,0,0,0}, {25393,25351,25350 ,13900,13858,13857 ,0,0,0}, + {25267,25395,25396 ,13774,13902,13903 ,0,0,0}, {25351,25394,25352 ,13858,13901,13859 ,0,0,0}, + {25268,25396,25354 ,13775,13903,13861 ,0,0,0}, {25395,25267,25352 ,13902,13774,13859 ,0,0,0}, + {25397,25398,25355 ,13904,13905,13862 ,0,0,0}, {25396,25268,25267 ,13903,13775,13774 ,0,0,0}, + {25355,25398,25356 ,13862,13905,13863 ,0,0,0}, {25354,25353,25268 ,13861,13860,13775 ,0,0,0}, + {25398,25399,25357 ,13905,13906,13864 ,0,0,0}, {25355,25356,25353 ,13862,13863,13860 ,0,0,0}, + {25358,25399,25400 ,13865,13906,13907 ,0,0,0}, {25398,25357,25356 ,13905,13864,13863 ,0,0,0}, + {25359,25400,25401 ,13866,13907,13908 ,0,0,0}, {25357,25399,25358 ,13864,13906,13865 ,0,0,0}, + {25315,25401,25402 ,13822,13908,13909 ,0,0,0}, {25358,25400,25359 ,13865,13907,13866 ,0,0,0}, + {25316,25402,25403 ,13823,13909,13910 ,0,0,0}, {25359,25401,25315 ,13866,13908,13822 ,0,0,0}, + {25360,25403,25362 ,13867,13910,13869 ,0,0,0}, {25402,25316,25315 ,13909,13823,13822 ,0,0,0}, + {25404,25364,25363 ,13911,13871,13870 ,0,0,0}, {25403,25360,25316 ,13910,13867,13823 ,0,0,0}, + {25405,25406,25404 ,13912,13913,13911 ,0,0,0}, {25362,25361,25360 ,13869,13868,13867 ,0,0,0}, + {25404,25406,25365 ,13911,13913,13872 ,0,0,0}, {25363,25364,25361 ,13870,13871,13868 ,0,0,0}, + {25406,25407,25366 ,13913,13914,13873 ,0,0,0}, {25404,25365,25364 ,13911,13872,13871 ,0,0,0}, + {25407,25408,25367 ,13914,13915,13874 ,0,0,0}, {25406,25366,25365 ,13913,13873,13872 ,0,0,0}, + {25408,25409,25368 ,13915,13916,13875 ,0,0,0}, {25407,25367,25366 ,13914,13874,13873 ,0,0,0}, + {25152,25409,25153 ,13659,13916,13660 ,0,0,0}, {25408,25368,25367 ,13915,13875,13874 ,0,0,0}, + {25153,25410,25151 ,13660,13917,13658 ,0,0,0}, {25152,25368,25409 ,13659,13875,13916 ,0,0,0}, + {25411,25369,25159 ,13918,13876,13666 ,0,0,0}, {25411,25412,25369 ,13918,13919,13876 ,0,0,0}, + {25155,25283,25325 ,13662,13790,13832 ,0,0,0}, {25410,25159,25283 ,13917,13666,13790 ,0,0,0}, + {25370,25369,25412 ,13877,13876,13919 ,0,0,0}, {25060,25374,25054 ,13567,13881,13561 ,0,0,0}, + {25413,25059,25058 ,13920,13566,13565 ,0,0,0}, {25414,25372,25374 ,13921,13879,13881 ,0,0,0}, + {25374,25372,25329 ,13881,13879,13836 ,0,0,0}, {25374,25285,25414 ,13881,13792,13921 ,0,0,0}, + {25415,25373,25372 ,13922,13880,13879 ,0,0,0}, {25372,25414,25415 ,13879,13921,13922 ,0,0,0}, + {25416,25375,25373 ,13923,13882,13880 ,0,0,0}, {25373,25415,25416 ,13880,13922,13923 ,0,0,0}, + {25417,25376,25375 ,13924,13883,13882 ,0,0,0}, {25375,25416,25417 ,13882,13923,13924 ,0,0,0}, + {25418,25377,25376 ,13925,13884,13883 ,0,0,0}, {25376,25417,25418 ,13883,13924,13925 ,0,0,0}, + {25419,25378,25377 ,13926,13885,13884 ,0,0,0}, {25377,25418,25419 ,13884,13925,13926 ,0,0,0}, + {25420,25379,25378 ,13927,13886,13885 ,0,0,0}, {25378,25419,25420 ,13885,13926,13927 ,0,0,0}, + {25421,25334,25379 ,13928,13841,13886 ,0,0,0}, {25379,25420,25421 ,13886,13927,13928 ,0,0,0}, + {25422,25335,25334 ,13929,13842,13841 ,0,0,0}, {25334,25421,25422 ,13841,13928,13929 ,0,0,0}, + {25423,25380,25335 ,13930,13887,13842 ,0,0,0}, {25422,25423,25335 ,13929,13930,13842 ,0,0,0}, + {25424,25425,25426 ,13931,13932,13933 ,0,0,0}, {25423,25381,25380 ,13930,13888,13887 ,0,0,0}, + {25427,25383,25382 ,13934,13890,13889 ,0,0,0}, {25381,25427,25382 ,13888,13934,13889 ,0,0,0}, + {25428,25384,25383 ,13935,13891,13890 ,0,0,0}, {25383,25427,25428 ,13890,13934,13935 ,0,0,0}, + {25429,25385,25384 ,13936,13892,13891 ,0,0,0}, {25384,25428,25429 ,13891,13935,13936 ,0,0,0}, + {25430,25386,25385 ,13937,13893,13892 ,0,0,0}, {25385,25429,25430 ,13892,13936,13937 ,0,0,0}, + {25431,25342,25386 ,13938,13849,13893 ,0,0,0}, {25386,25430,25431 ,13893,13937,13938 ,0,0,0}, + {25432,25343,25342 ,13939,13850,13849 ,0,0,0}, {25431,25432,25342 ,13938,13939,13849 ,0,0,0}, + {25433,25387,25434 ,13940,13894,13941 ,0,0,0}, {25432,25387,25343 ,13939,13894,13850 ,0,0,0}, + {25433,25389,25388 ,13940,13896,13895 ,0,0,0}, {25387,25433,25388 ,13894,13940,13895 ,0,0,0}, + {25435,25390,25389 ,13942,13897,13896 ,0,0,0}, {25389,25433,25435 ,13896,13940,13942 ,0,0,0}, + {25436,25391,25390 ,13943,13898,13897 ,0,0,0}, {25390,25435,25436 ,13897,13942,13943 ,0,0,0}, + {25437,25348,25391 ,13944,13855,13898 ,0,0,0}, {25391,25436,25437 ,13898,13943,13944 ,0,0,0}, + {25438,25349,25348 ,13945,13856,13855 ,0,0,0}, {25437,25438,25348 ,13944,13945,13855 ,0,0,0}, + {25439,25440,25441 ,13946,13947,13948 ,0,0,0}, {25438,25392,25349 ,13945,13899,13856 ,0,0,0}, + {25442,25394,25393 ,13949,13901,13900 ,0,0,0}, {25392,25442,25393 ,13899,13949,13900 ,0,0,0}, + {25443,25395,25394 ,13950,13902,13901 ,0,0,0}, {25394,25442,25443 ,13901,13949,13950 ,0,0,0}, + {25444,25396,25395 ,13951,13903,13902 ,0,0,0}, {25395,25443,25444 ,13902,13950,13951 ,0,0,0}, + {25445,25354,25396 ,13952,13861,13903 ,0,0,0}, {25396,25444,25445 ,13903,13951,13952 ,0,0,0}, + {25446,25355,25354 ,13953,13862,13861 ,0,0,0}, {25445,25446,25354 ,13952,13953,13861 ,0,0,0}, + {25398,25447,25399 ,13905,13954,13906 ,0,0,0}, {25446,25397,25355 ,13953,13904,13862 ,0,0,0}, + {25448,25449,25447 ,13955,13956,13954 ,0,0,0}, {25397,25447,25398 ,13904,13954,13905 ,0,0,0}, + {25449,25400,25399 ,13956,13907,13906 ,0,0,0}, {25399,25447,25449 ,13906,13954,13956 ,0,0,0}, + {25450,25401,25400 ,13957,13908,13907 ,0,0,0}, {25400,25449,25450 ,13907,13956,13957 ,0,0,0}, + {25451,25402,25401 ,13958,13909,13908 ,0,0,0}, {25401,25450,25451 ,13908,13957,13958 ,0,0,0}, + {25452,25403,25402 ,13959,13910,13909 ,0,0,0}, {25402,25451,25452 ,13909,13958,13959 ,0,0,0}, + {25453,25362,25403 ,13960,13869,13910 ,0,0,0}, {25403,25452,25453 ,13910,13959,13960 ,0,0,0}, + {25454,25363,25362 ,13961,13870,13869 ,0,0,0}, {25362,25453,25454 ,13869,13960,13961 ,0,0,0}, + {25455,25404,25363 ,13962,13911,13870 ,0,0,0}, {25454,25455,25363 ,13961,13962,13870 ,0,0,0}, + {25406,25456,25407 ,13913,13963,13914 ,0,0,0}, {25455,25405,25404 ,13962,13912,13911 ,0,0,0}, + {25407,25457,25408 ,13914,13964,13915 ,0,0,0}, {25405,25456,25406 ,13912,13963,13913 ,0,0,0}, + {25408,25458,25409 ,13915,13965,13916 ,0,0,0}, {25456,25457,25407 ,13963,13964,13914 ,0,0,0}, + {25409,25156,25153 ,13916,13663,13660 ,0,0,0}, {25457,25458,25408 ,13964,13965,13915 ,0,0,0}, + {25161,25160,25157 ,13668,13667,13664 ,0,0,0}, {25458,25156,25409 ,13965,13663,13916 ,0,0,0}, + {25157,25410,25153 ,13664,13917,13660 ,0,0,0}, {25283,25159,25369 ,13790,13666,13876 ,0,0,0}, + {25151,25410,25283 ,13658,13917,13790 ,0,0,0}, {25410,25157,25160 ,13917,13664,13667 ,0,0,0}, + {25411,25159,25158 ,13918,13666,13665 ,0,0,0}, {25059,25285,25060 ,13566,13792,13567 ,0,0,0}, + {25413,25066,25064 ,13920,13573,13571 ,0,0,0}, {25414,25285,25459 ,13921,13792,13966 ,0,0,0}, + {25060,25285,25374 ,13567,13792,13881 ,0,0,0}, {25285,25063,25459 ,13792,13570,13966 ,0,0,0}, + {25415,25414,25460 ,13922,13921,13967 ,0,0,0}, {25414,25459,25460 ,13921,13966,13967 ,0,0,0}, + {25416,25415,25461 ,13923,13922,13968 ,0,0,0}, {25415,25460,25461 ,13922,13967,13968 ,0,0,0}, + {25417,25416,25462 ,13924,13923,13969 ,0,0,0}, {25416,25461,25462 ,13923,13968,13969 ,0,0,0}, + {25418,25417,25463 ,13925,13924,13970 ,0,0,0}, {25417,25462,25463 ,13924,13969,13970 ,0,0,0}, + {25419,25418,25464 ,13926,13925,13971 ,0,0,0}, {25418,25463,25464 ,13925,13970,13971 ,0,0,0}, + {25420,25419,25465 ,13927,13926,13972 ,0,0,0}, {25419,25464,25465 ,13926,13971,13972 ,0,0,0}, + {25421,25420,25466 ,13928,13927,13973 ,0,0,0}, {25420,25465,25466 ,13927,13972,13973 ,0,0,0}, + {25422,25421,25467 ,13929,13928,13974 ,0,0,0}, {25421,25466,25467 ,13928,13973,13974 ,0,0,0}, + {25423,25422,25468 ,13930,13929,13975 ,0,0,0}, {25422,25467,25468 ,13929,13974,13975 ,0,0,0}, + {25381,25423,25469 ,13888,13930,13976 ,0,0,0}, {25423,25468,25469 ,13930,13975,13976 ,0,0,0}, + {25427,25381,25424 ,13934,13888,13931 ,0,0,0}, {25469,25424,25381 ,13976,13931,13888 ,0,0,0}, + {25428,25427,25426 ,13935,13934,13933 ,0,0,0}, {25427,25424,25426 ,13934,13931,13933 ,0,0,0}, + {25429,25428,25470 ,13936,13935,13977 ,0,0,0}, {25428,25426,25470 ,13935,13933,13977 ,0,0,0}, + {25430,25429,25471 ,13937,13936,13978 ,0,0,0}, {25429,25470,25471 ,13936,13977,13978 ,0,0,0}, + {25431,25430,25472 ,13938,13937,13979 ,0,0,0}, {25430,25471,25472 ,13937,13978,13979 ,0,0,0}, + {25432,25431,25473 ,13939,13938,13980 ,0,0,0}, {25431,25472,25473 ,13938,13979,13980 ,0,0,0}, + {25387,25432,25474 ,13894,13939,13981 ,0,0,0}, {25432,25473,25474 ,13939,13980,13981 ,0,0,0}, + {25474,25475,25434 ,13981,13982,13941 ,0,0,0}, {25474,25434,25387 ,13981,13941,13894 ,0,0,0}, + {25435,25433,25476 ,13942,13940,13983 ,0,0,0}, {25433,25434,25476 ,13940,13941,13983 ,0,0,0}, + {25436,25435,25477 ,13943,13942,13984 ,0,0,0}, {25435,25476,25477 ,13942,13983,13984 ,0,0,0}, + {25437,25436,25478 ,13944,13943,13985 ,0,0,0}, {25436,25477,25478 ,13943,13984,13985 ,0,0,0}, + {25438,25437,25479 ,13945,13944,13986 ,0,0,0}, {25437,25478,25479 ,13944,13985,13986 ,0,0,0}, + {25392,25438,25480 ,13899,13945,13987 ,0,0,0}, {25438,25479,25480 ,13945,13986,13987 ,0,0,0}, + {25442,25392,25439 ,13949,13899,13946 ,0,0,0}, {25480,25439,25392 ,13987,13946,13899 ,0,0,0}, + {25443,25442,25441 ,13950,13949,13948 ,0,0,0}, {25442,25439,25441 ,13949,13946,13948 ,0,0,0}, + {25444,25443,25481 ,13951,13950,13988 ,0,0,0}, {25443,25441,25481 ,13950,13948,13988 ,0,0,0}, + {25445,25444,25482 ,13952,13951,13989 ,0,0,0}, {25444,25481,25482 ,13951,13988,13989 ,0,0,0}, + {25446,25445,25483 ,13953,13952,13990 ,0,0,0}, {25445,25482,25483 ,13952,13989,13990 ,0,0,0}, + {25397,25446,25484 ,13904,13953,13991 ,0,0,0}, {25446,25483,25484 ,13953,13990,13991 ,0,0,0}, + {25447,25397,25485 ,13954,13904,13992 ,0,0,0}, {25397,25484,25485 ,13904,13991,13992 ,0,0,0}, + {25448,25485,25486 ,13955,13992,13993 ,0,0,0}, {25485,25448,25447 ,13992,13955,13954 ,0,0,0}, + {25450,25449,25487 ,13957,13956,13994 ,0,0,0}, {25449,25448,25487 ,13956,13955,13994 ,0,0,0}, + {25451,25450,25488 ,13958,13957,13995 ,0,0,0}, {25450,25487,25488 ,13957,13994,13995 ,0,0,0}, + {25452,25451,25489 ,13959,13958,13996 ,0,0,0}, {25451,25488,25489 ,13958,13995,13996 ,0,0,0}, + {25453,25452,25490 ,13960,13959,13997 ,0,0,0}, {25452,25489,25490 ,13959,13996,13997 ,0,0,0}, + {25454,25453,25491 ,13961,13960,13998 ,0,0,0}, {25453,25490,25491 ,13960,13997,13998 ,0,0,0}, + {25455,25454,25492 ,13962,13961,13999 ,0,0,0}, {25454,25491,25492 ,13961,13998,13999 ,0,0,0}, + {25405,25455,25493 ,13912,13962,14000 ,0,0,0}, {25455,25492,25493 ,13962,13999,14000 ,0,0,0}, + {25456,25405,25494 ,13963,13912,14001 ,0,0,0}, {25405,25493,25494 ,13912,14000,14001 ,0,0,0}, + {25457,25456,25495 ,13964,13963,14002 ,0,0,0}, {25456,25494,25495 ,13963,14001,14002 ,0,0,0}, + {25458,25457,25496 ,13965,13964,14003 ,0,0,0}, {25457,25495,25496 ,13964,14002,14003 ,0,0,0}, + {25156,25458,25497 ,13663,13965,14004 ,0,0,0}, {25458,25496,25497 ,13965,14003,14004 ,0,0,0}, + {25498,25157,25156 ,14005,13664,13663 ,0,0,0}, {25498,25156,25497 ,14005,13663,14004 ,0,0,0}, + {25410,25160,25159 ,13917,13667,13666 ,0,0,0}, {25498,25161,25157 ,14005,13668,13664 ,0,0,0}, + {25158,25160,25163 ,13665,13667,13670 ,0,0,0}, {25064,25059,25413 ,13571,13566,13920 ,0,0,0}, + {25065,25062,25064 ,13572,13569,13571 ,0,0,0}, {25062,25499,25063 ,13569,14006,13570 ,0,0,0}, + {25063,25499,25459 ,13570,14006,13966 ,0,0,0}, {25499,25500,25459 ,14006,14007,13966 ,0,0,0}, + {25459,25500,25460 ,13966,14007,13967 ,0,0,0}, {25500,25501,25460 ,14007,14008,13967 ,0,0,0}, + {25460,25501,25461 ,13967,14008,13968 ,0,0,0}, {25501,25502,25461 ,14008,14009,13968 ,0,0,0}, + {25461,25502,25462 ,13968,14009,13969 ,0,0,0}, {25502,25503,25462 ,14009,14010,13969 ,0,0,0}, + {25462,25503,25463 ,13969,14010,13970 ,0,0,0}, {25503,25504,25463 ,14010,14011,13970 ,0,0,0}, + {25463,25504,25464 ,13970,14011,13971 ,0,0,0}, {25504,25505,25464 ,14011,14012,13971 ,0,0,0}, + {25464,25505,25465 ,13971,14012,13972 ,0,0,0}, {25505,25506,25465 ,14012,14013,13972 ,0,0,0}, + {25506,25507,25466 ,14013,14014,13973 ,0,0,0}, {25506,25466,25465 ,14013,13973,13972 ,0,0,0}, + {25507,25508,25467 ,14014,14015,13974 ,0,0,0}, {25507,25467,25466 ,14014,13974,13973 ,0,0,0}, + {25508,25509,25468 ,14015,14016,13975 ,0,0,0}, {25508,25468,25467 ,14015,13975,13974 ,0,0,0}, + {25509,25510,25469 ,14016,14017,13976 ,0,0,0}, {25509,25469,25468 ,14016,13976,13975 ,0,0,0}, + {25510,25511,25424 ,14017,14018,13931 ,0,0,0}, {25510,25424,25469 ,14017,13931,13976 ,0,0,0}, + {25425,25424,25511 ,13932,13931,14018 ,0,0,0}, {25425,25512,25426 ,13932,14019,13933 ,0,0,0}, + {25426,25512,25470 ,13933,14019,13977 ,0,0,0}, {25512,25513,25470 ,14019,14020,13977 ,0,0,0}, + {25470,25513,25471 ,13977,14020,13978 ,0,0,0}, {25513,25514,25471 ,14020,14021,13978 ,0,0,0}, + {25514,25515,25472 ,14021,14022,13979 ,0,0,0}, {25514,25472,25471 ,14021,13979,13978 ,0,0,0}, + {25515,25516,25473 ,14022,14023,13980 ,0,0,0}, {25515,25473,25472 ,14022,13980,13979 ,0,0,0}, + {25516,25475,25474 ,14023,13982,13981 ,0,0,0}, {25516,25474,25473 ,14023,13981,13980 ,0,0,0}, + {25475,25517,25434 ,13982,14024,13941 ,0,0,0}, {25517,25518,25434 ,14024,14025,13941 ,0,0,0}, + {25434,25518,25476 ,13941,14025,13983 ,0,0,0}, {25518,25519,25476 ,14025,14026,13983 ,0,0,0}, + {25476,25519,25477 ,13983,14026,13984 ,0,0,0}, {25519,25520,25477 ,14026,14027,13984 ,0,0,0}, + {25520,25521,25478 ,14027,14028,13985 ,0,0,0}, {25520,25478,25477 ,14027,13985,13984 ,0,0,0}, + {25521,25522,25479 ,14028,14029,13986 ,0,0,0}, {25521,25479,25478 ,14028,13986,13985 ,0,0,0}, + {25522,25523,25480 ,14029,14030,13987 ,0,0,0}, {25522,25480,25479 ,14029,13987,13986 ,0,0,0}, + {25523,25524,25439 ,14030,14031,13946 ,0,0,0}, {25523,25439,25480 ,14030,13946,13987 ,0,0,0}, + {25440,25439,25524 ,13947,13946,14031 ,0,0,0}, {25440,25525,25441 ,13947,14032,13948 ,0,0,0}, + {25441,25525,25481 ,13948,14032,13988 ,0,0,0}, {25525,25526,25481 ,14032,14033,13988 ,0,0,0}, + {25526,25527,25482 ,14033,14034,13989 ,0,0,0}, {25526,25482,25481 ,14033,13989,13988 ,0,0,0}, + {25527,25528,25483 ,14034,14035,13990 ,0,0,0}, {25527,25483,25482 ,14034,13990,13989 ,0,0,0}, + {25528,25529,25484 ,14035,14036,13991 ,0,0,0}, {25528,25484,25483 ,14035,13991,13990 ,0,0,0}, + {25529,25486,25485 ,14036,13993,13992 ,0,0,0}, {25529,25485,25484 ,14036,13992,13991 ,0,0,0}, + {25486,25530,25448 ,13993,14037,13955 ,0,0,0}, {25530,25531,25448 ,14037,14038,13955 ,0,0,0}, + {25448,25531,25487 ,13955,14038,13994 ,0,0,0}, {25531,25532,25487 ,14038,14039,13994 ,0,0,0}, + {25487,25532,25488 ,13994,14039,13995 ,0,0,0}, {25532,25533,25488 ,14039,14040,13995 ,0,0,0}, + {25488,25533,25489 ,13995,14040,13996 ,0,0,0}, {25533,25534,25489 ,14040,14041,13996 ,0,0,0}, + {25534,25535,25490 ,14041,14042,13997 ,0,0,0}, {25534,25490,25489 ,14041,13997,13996 ,0,0,0}, + {25535,25536,25491 ,14042,14043,13998 ,0,0,0}, {25535,25491,25490 ,14042,13998,13997 ,0,0,0}, + {25536,25537,25492 ,14043,14044,13999 ,0,0,0}, {25536,25492,25491 ,14043,13999,13998 ,0,0,0}, + {25537,25538,25493 ,14044,14045,14000 ,0,0,0}, {25537,25493,25492 ,14044,14000,13999 ,0,0,0}, + {25538,25539,25494 ,14045,14046,14001 ,0,0,0}, {25538,25494,25493 ,14045,14001,14000 ,0,0,0}, + {25539,25540,25495 ,14046,14047,14002 ,0,0,0}, {25539,25495,25494 ,14046,14002,14001 ,0,0,0}, + {25540,25541,25496 ,14047,14048,14003 ,0,0,0}, {25540,25496,25495 ,14047,14003,14002 ,0,0,0}, + {25541,25542,25497 ,14048,14049,14004 ,0,0,0}, {25541,25497,25496 ,14048,14004,14003 ,0,0,0}, + {25542,25543,25498 ,14049,14050,14005 ,0,0,0}, {25542,25498,25497 ,14049,14005,14004 ,0,0,0}, + {25544,25498,25543 ,14051,14005,14050 ,0,0,0}, {25498,25544,25161 ,14005,14051,13668 ,0,0,0}, + {25161,25544,25164 ,13668,14051,13671 ,0,0,0}, {25545,25546,25547 ,14052,14053,14054 ,0,0,0}, + {25548,25549,25550 ,14055,14056,14057 ,0,0,0}, {25551,25552,25553 ,14058,14059,14060 ,0,0,0}, + {25554,25555,25551 ,14061,14062,14058 ,0,0,0}, {25556,25557,25558 ,14063,14064,14065 ,0,0,0}, + {25559,25560,25561 ,14066,14067,14068 ,0,0,0}, {25562,25563,25564 ,14069,14070,14071 ,0,0,0}, + {25565,25566,25559 ,14072,14073,14066 ,0,0,0}, {25567,25568,25569 ,14074,14075,14076 ,0,0,0}, + {25569,25564,25570 ,14076,14071,14077 ,0,0,0}, {25571,25567,25572 ,14078,14074,14079 ,0,0,0}, + {25568,25567,25573 ,14075,14074,14080 ,0,0,0}, {25554,25574,25575 ,14061,14081,14082 ,0,0,0}, + {25571,25576,25567 ,14078,14083,14074 ,0,0,0}, {25577,25578,25579 ,14084,14085,14086 ,0,0,0}, + {25578,25580,25547 ,14085,14087,14054 ,0,0,0}, {25581,25582,25579 ,14088,14089,14086 ,0,0,0}, + {25580,25578,25577 ,14087,14085,14084 ,0,0,0}, {25583,25584,25581 ,14090,14091,14088 ,0,0,0}, + {25579,25582,25577 ,14086,14089,14084 ,0,0,0}, {25585,25586,25549 ,14092,14093,14056 ,0,0,0}, + {25587,25588,25589 ,14094,14095,14096 ,0,0,0}, {25585,25590,25586 ,14092,14097,14093 ,0,0,0}, + {25591,25592,25593 ,14098,14099,14100 ,0,0,0}, {25588,25594,25589 ,14095,14101,14096 ,0,0,0}, + {25595,25596,25597 ,14102,14103,14104 ,0,0,0}, {25591,25593,25598 ,14098,14100,14105 ,0,0,0}, + {25599,25600,25601 ,14106,14107,14108 ,0,0,0}, {25600,25599,25602 ,14107,14106,14109 ,0,0,0}, + {25603,25604,25605 ,14110,14111,14112 ,0,0,0}, {25606,25607,25604 ,14113,14114,14111 ,0,0,0}, + {25608,25609,25610 ,14115,14116,14117 ,0,0,0}, {25603,25605,25611 ,14110,14112,14118 ,0,0,0}, + {25612,25613,25614 ,14119,14120,14121 ,0,0,0}, {25608,25610,25615 ,14115,14117,14122 ,0,0,0}, + {25616,25617,25618 ,14123,14124,14125 ,0,0,0}, {25619,25613,25612 ,14126,14120,14119 ,0,0,0}, + {25620,25621,25622 ,14127,14128,14129 ,0,0,0}, {25622,25618,25620 ,14129,14125,14127 ,0,0,0}, + {25623,25624,25625 ,14130,14131,14132 ,0,0,0}, {25626,25621,25627 ,14133,14128,14134 ,0,0,0}, + {25628,25629,25630 ,14135,14136,14137 ,0,0,0}, {25629,25628,25631 ,14136,14135,14138 ,0,0,0}, + {25632,25633,25634 ,14139,14140,14141 ,0,0,0}, {25630,25633,25635 ,14137,14140,14142 ,0,0,0}, + {25636,25637,25638 ,14143,14144,14145 ,0,0,0}, {25639,25640,25641 ,14146,14147,14148 ,0,0,0}, + {25642,25643,25644 ,14149,14150,14151 ,0,0,0}, {25643,25642,25645 ,14150,14149,14152 ,0,0,0}, + {25646,25647,25648 ,14153,14154,14155 ,0,0,0}, {25649,25650,25646 ,14156,14157,14153 ,0,0,0}, + {25647,25646,25650 ,14154,14153,14157 ,0,0,0}, {25647,25650,25636 ,14154,14157,14143 ,0,0,0}, + {25651,25652,25653 ,14158,14159,14160 ,0,0,0}, {25634,25638,25637 ,14141,14145,14144 ,0,0,0}, + {25654,25639,25641 ,14161,14146,14148 ,0,0,0}, {25640,25655,25641 ,14147,14162,14148 ,0,0,0}, + {25656,25657,25639 ,14163,14164,14146 ,0,0,0}, {25639,25658,25640 ,14146,14165,14147 ,0,0,0}, + {25659,25660,25661 ,14166,14167,14168 ,0,0,0}, {25058,25662,25663 ,14169,14170,14171 ,0,0,0}, + {25663,25664,25413 ,14171,14172,14173 ,0,0,0}, {25664,25066,25413 ,14172,14174,14173 ,0,0,0}, + {25067,25066,25665 ,730,14174,14175 ,0,0,0}, {25653,25633,25651 ,14160,14140,14158 ,0,0,0}, + {25644,25649,25646 ,14151,14156,14153 ,0,0,0}, {25634,25637,25632 ,14141,14144,14139 ,0,0,0}, + {25196,25645,25195 ,14176,14152,14177 ,0,0,0}, {25628,25630,25635 ,14135,14137,14142 ,0,0,0}, + {25633,25632,25635 ,14140,14139,14142 ,0,0,0}, {25623,25631,25624 ,14130,14138,14131 ,0,0,0}, + {25629,25631,25623 ,14136,14138,14130 ,0,0,0}, {25623,25666,25629 ,14130,14178,14136 ,0,0,0}, + {25624,25626,25625 ,14131,14133,14132 ,0,0,0}, {25627,25621,25620 ,14134,14128,14127 ,0,0,0}, + {25626,25627,25625 ,14133,14134,14132 ,0,0,0}, {25616,25618,25622 ,14123,14125,14129 ,0,0,0}, + {25612,25614,25667 ,14119,14121,14179 ,0,0,0}, {25668,25619,25669 ,14180,14126,14181 ,0,0,0}, + {25618,25617,25669 ,14125,14124,14181 ,0,0,0}, {25613,25619,25668 ,14120,14126,14180 ,0,0,0}, + {25617,25668,25669 ,14124,14180,14181 ,0,0,0}, {25667,25614,25615 ,14179,14121,14122 ,0,0,0}, + {25670,25612,25667 ,14182,14119,14179 ,0,0,0}, {25615,25610,25667 ,14122,14117,14179 ,0,0,0}, + {25611,25609,25671 ,14118,14116,14183 ,0,0,0}, {25608,25671,25609 ,14115,14183,14116 ,0,0,0}, + {25672,25611,25671 ,14184,14118,14183 ,0,0,0}, {25607,25605,25604 ,14114,14112,14111 ,0,0,0}, + {25603,25611,25672 ,14110,14118,14184 ,0,0,0}, {25606,25673,25607 ,14113,14185,14114 ,0,0,0}, + {25601,25600,25673 ,14108,14107,14185 ,0,0,0}, {25673,25606,25601 ,14185,14113,14108 ,0,0,0}, + {25602,25674,25597 ,14109,14186,14104 ,0,0,0}, {25675,25676,25677 ,14187,14188,14189 ,0,0,0}, + {25597,25674,25678 ,14104,14186,14190 ,0,0,0}, {25674,25602,25599 ,14186,14109,14106 ,0,0,0}, + {25679,25598,25596 ,14191,14105,14103 ,0,0,0}, {25595,25597,25678 ,14102,14104,14190 ,0,0,0}, + {25598,25679,25591 ,14105,14191,14098 ,0,0,0}, {25679,25596,25595 ,14191,14103,14102 ,0,0,0}, + {25590,25680,25681 ,14097,14192,14193 ,0,0,0}, {25592,25594,25682 ,14099,14101,14194 ,0,0,0}, + {25593,25592,25682 ,14100,14099,14194 ,0,0,0}, {25682,25594,25588 ,14194,14101,14095 ,0,0,0}, + {25683,25684,25685 ,14195,14196,14197 ,0,0,0}, {25680,25587,25589 ,14192,14094,14096 ,0,0,0}, + {25547,25580,25545 ,14054,14087,14052 ,0,0,0}, {25590,25587,25680 ,14097,14094,14192 ,0,0,0}, + {25590,25681,25586 ,14097,14193,14093 ,0,0,0}, {25549,25548,25585 ,14056,14055,14092 ,0,0,0}, + {25584,25583,25550 ,14091,14090,14057 ,0,0,0}, {25550,25583,25548 ,14057,14090,14055 ,0,0,0}, + {25686,25583,25581 ,14198,14090,14088 ,0,0,0}, {25584,25582,25581 ,14091,14089,14088 ,0,0,0}, + {25546,25575,25574 ,14053,14082,14081 ,0,0,0}, {25545,25575,25546 ,14052,14082,14053 ,0,0,0}, + {25555,25552,25551 ,14062,14059,14058 ,0,0,0}, {25554,25551,25574 ,14061,14058,14081 ,0,0,0}, + {25555,25687,25552 ,14062,14199,14059 ,0,0,0}, {25558,25688,25562 ,14065,14200,14069 ,0,0,0}, + {25689,25690,25687 ,14201,14202,14199 ,0,0,0}, {25556,25691,25692 ,14063,14203,14204 ,0,0,0}, + {25690,25693,25694 ,14202,14205,14206 ,0,0,0}, {25689,25693,25690 ,14201,14205,14202 ,0,0,0}, + {25690,25552,25687 ,14202,14059,14199 ,0,0,0}, {25694,25695,25696 ,14206,14207,14208 ,0,0,0}, + {25695,25694,25697 ,14207,14206,14209 ,0,0,0}, {25693,25697,25694 ,14205,14209,14206 ,0,0,0}, + {25692,25691,25696 ,14204,14203,14208 ,0,0,0}, {25698,25558,25557 ,14210,14065,14064 ,0,0,0}, + {25694,25696,25691 ,14206,14208,14203 ,0,0,0}, {25563,25562,25699 ,14070,14069,14211 ,0,0,0}, + {25694,25700,25690 ,14206,14212,14202 ,0,0,0}, {25701,25574,25551 ,14213,14081,14058 ,0,0,0}, + {25690,25561,25552 ,14202,14068,14059 ,0,0,0}, {25702,25546,25574 ,14214,14053,14081 ,0,0,0}, + {25553,25552,25561 ,14060,14059,14068 ,0,0,0}, {25703,25547,25546 ,14215,14054,14053 ,0,0,0}, + {25701,25551,25553 ,14213,14058,14060 ,0,0,0}, {25704,25578,25547 ,14216,14085,14054 ,0,0,0}, + {25702,25574,25701 ,14214,14081,14213 ,0,0,0}, {25705,25579,25578 ,14217,14086,14085 ,0,0,0}, + {25703,25546,25702 ,14215,14053,14214 ,0,0,0}, {25706,25581,25579 ,14218,14088,14086 ,0,0,0}, + {25547,25703,25704 ,14054,14215,14216 ,0,0,0}, {25707,25708,25709 ,14219,14220,14221 ,0,0,0}, + {25578,25704,25705 ,14085,14216,14217 ,0,0,0}, {25709,25548,25583 ,14221,14055,14090 ,0,0,0}, + {25579,25705,25706 ,14086,14217,14218 ,0,0,0}, {25710,25585,25548 ,14222,14092,14055 ,0,0,0}, + {25581,25706,25686 ,14088,14218,14198 ,0,0,0}, {25711,25590,25585 ,14223,14097,14092 ,0,0,0}, + {25583,25686,25709 ,14090,14198,14221 ,0,0,0}, {25712,25587,25590 ,14224,14094,14097 ,0,0,0}, + {25548,25709,25710 ,14055,14221,14222 ,0,0,0}, {25713,25588,25587 ,14225,14095,14094 ,0,0,0}, + {25711,25585,25710 ,14223,14092,14222 ,0,0,0}, {25714,25682,25588 ,14226,14194,14095 ,0,0,0}, + {25712,25590,25711 ,14224,14097,14223 ,0,0,0}, {25715,25593,25682 ,14227,14100,14194 ,0,0,0}, + {25587,25712,25713 ,14094,14224,14225 ,0,0,0}, {25684,25598,25593 ,14196,14105,14100 ,0,0,0}, + {25588,25713,25714 ,14095,14225,14226 ,0,0,0}, {25716,25596,25598 ,14228,14103,14105 ,0,0,0}, + {25682,25714,25715 ,14194,14226,14227 ,0,0,0}, {25717,25597,25596 ,14229,14104,14103 ,0,0,0}, + {25593,25715,25684 ,14100,14227,14196 ,0,0,0}, {25718,25602,25597 ,14230,14109,14104 ,0,0,0}, + {25716,25598,25684 ,14228,14105,14196 ,0,0,0}, {25719,25600,25602 ,14231,14107,14109 ,0,0,0}, + {25717,25596,25716 ,14229,14103,14228 ,0,0,0}, {25720,25673,25600 ,14232,14185,14107 ,0,0,0}, + {25597,25717,25718 ,14104,14229,14230 ,0,0,0}, {25607,25673,25675 ,14114,14185,14187 ,0,0,0}, + {25602,25718,25719 ,14109,14230,14231 ,0,0,0}, {25721,25605,25607 ,14233,14112,14114 ,0,0,0}, + {25600,25719,25720 ,14107,14231,14232 ,0,0,0}, {25722,25611,25605 ,14234,14118,14112 ,0,0,0}, + {25673,25720,25675 ,14185,14232,14187 ,0,0,0}, {25723,25609,25611 ,14235,14116,14118 ,0,0,0}, + {25721,25607,25675 ,14233,14114,14187 ,0,0,0}, {25724,25610,25609 ,14236,14117,14116 ,0,0,0}, + {25722,25605,25721 ,14234,14112,14233 ,0,0,0}, {25725,25667,25610 ,14237,14179,14117 ,0,0,0}, + {25611,25722,25723 ,14118,14234,14235 ,0,0,0}, {25726,25727,25728 ,14238,14239,14240 ,0,0,0}, + {25609,25723,25724 ,14116,14235,14236 ,0,0,0}, {25729,25619,25612 ,14241,14126,14119 ,0,0,0}, + {25610,25724,25725 ,14117,14236,14237 ,0,0,0}, {25730,25669,25619 ,14242,14181,14126 ,0,0,0}, + {25667,25725,25670 ,14179,14237,14182 ,0,0,0}, {25731,25618,25669 ,14243,14125,14181 ,0,0,0}, + {25612,25670,25729 ,14119,14182,14241 ,0,0,0}, {25732,25620,25618 ,14244,14127,14125 ,0,0,0}, + {25730,25619,25729 ,14242,14126,14241 ,0,0,0}, {25733,25627,25620 ,14245,14134,14127 ,0,0,0}, + {25731,25669,25730 ,14243,14181,14242 ,0,0,0}, {25734,25625,25627 ,14246,14132,14134 ,0,0,0}, + {25732,25618,25731 ,14244,14125,14243 ,0,0,0}, {25735,25623,25625 ,14247,14130,14132 ,0,0,0}, + {25620,25732,25733 ,14127,14244,14245 ,0,0,0}, {25629,25736,25630 ,14136,14248,14137 ,0,0,0}, + {25627,25733,25734 ,14134,14245,14246 ,0,0,0}, {25651,25737,25652 ,14158,14249,14159 ,0,0,0}, + {25625,25734,25735 ,14132,14246,14247 ,0,0,0}, {25651,25633,25630 ,14158,14140,14137 ,0,0,0}, + {25623,25735,25666 ,14130,14247,14178 ,0,0,0}, {25653,25634,25633 ,14160,14141,14140 ,0,0,0}, + {25629,25666,25736 ,14136,14178,14248 ,0,0,0}, {25638,25634,25738 ,14145,14141,14250 ,0,0,0}, + {25651,25630,25736 ,14158,14137,14248 ,0,0,0}, {25655,25648,25647 ,14162,14155,14154 ,0,0,0}, + {25739,25646,25648 ,14251,14153,14155 ,0,0,0}, {25638,25647,25636 ,14145,14154,14143 ,0,0,0}, + {25738,25634,25653 ,14250,14141,14160 ,0,0,0}, {25655,25640,25648 ,14162,14147,14155 ,0,0,0}, + {25647,25638,25655 ,14154,14145,14162 ,0,0,0}, {25644,25740,25642 ,14151,14252,14149 ,0,0,0}, + {25642,25195,25645 ,14149,14177,14152 ,0,0,0}, {25649,25644,25643 ,14156,14151,14150 ,0,0,0}, + {25644,25739,25740 ,14151,14251,14252 ,0,0,0}, {25197,25195,25642 ,14253,14177,14149 ,0,0,0}, + {25691,25700,25694 ,14203,14212,14206 ,0,0,0}, {25557,25556,25692 ,14064,14063,14204 ,0,0,0}, + {25741,25569,25568 ,14254,14076,14075 ,0,0,0}, {25700,25561,25690 ,14212,14068,14202 ,0,0,0}, + {25700,25691,25742 ,14212,14203,14255 ,0,0,0}, {25553,25560,25743 ,14060,14067,14256 ,0,0,0}, + {25559,25561,25700 ,14066,14068,14212 ,0,0,0}, {25701,25743,25744 ,14213,14256,14257 ,0,0,0}, + {25560,25553,25561 ,14067,14060,14068 ,0,0,0}, {25702,25744,25745 ,14214,14257,14258 ,0,0,0}, + {25743,25701,25553 ,14256,14213,14060 ,0,0,0}, {25703,25745,25746 ,14215,14258,14259 ,0,0,0}, + {25744,25702,25701 ,14257,14214,14213 ,0,0,0}, {25704,25746,25747 ,14216,14259,14260 ,0,0,0}, + {25745,25703,25702 ,14258,14215,14214 ,0,0,0}, {25705,25747,25748 ,14217,14260,14261 ,0,0,0}, + {25746,25704,25703 ,14259,14216,14215 ,0,0,0}, {25706,25748,25749 ,14218,14261,14262 ,0,0,0}, + {25747,25705,25704 ,14260,14217,14216 ,0,0,0}, {25686,25749,25707 ,14198,14262,14219 ,0,0,0}, + {25706,25705,25748 ,14218,14217,14261 ,0,0,0}, {25750,25751,25752 ,14263,14264,14265 ,0,0,0}, + {25686,25706,25749 ,14198,14218,14262 ,0,0,0}, {25710,25708,25750 ,14222,14220,14263 ,0,0,0}, + {25709,25686,25707 ,14221,14198,14219 ,0,0,0}, {25711,25750,25753 ,14223,14263,14266 ,0,0,0}, + {25710,25709,25708 ,14222,14221,14220 ,0,0,0}, {25712,25753,25754 ,14224,14266,14267 ,0,0,0}, + {25750,25711,25710 ,14263,14223,14222 ,0,0,0}, {25713,25754,25755 ,14225,14267,14268 ,0,0,0}, + {25753,25712,25711 ,14266,14224,14223 ,0,0,0}, {25714,25755,25756 ,14226,14268,14269 ,0,0,0}, + {25754,25713,25712 ,14267,14225,14224 ,0,0,0}, {25715,25756,25685 ,14227,14269,14197 ,0,0,0}, + {25714,25713,25755 ,14226,14225,14268 ,0,0,0}, {25757,25758,25759 ,14270,14271,14272 ,0,0,0}, + {25715,25714,25756 ,14227,14226,14269 ,0,0,0}, {25716,25683,25760 ,14228,14195,14273 ,0,0,0}, + {25684,25715,25685 ,14196,14227,14197 ,0,0,0}, {25717,25760,25761 ,14229,14273,14274 ,0,0,0}, + {25683,25716,25684 ,14195,14228,14196 ,0,0,0}, {25718,25761,25762 ,14230,14274,14275 ,0,0,0}, + {25760,25717,25716 ,14273,14229,14228 ,0,0,0}, {25719,25762,25763 ,14231,14275,14276 ,0,0,0}, + {25761,25718,25717 ,14274,14230,14229 ,0,0,0}, {25720,25763,25676 ,14232,14276,14188 ,0,0,0}, + {25719,25718,25762 ,14231,14230,14275 ,0,0,0}, {25764,25765,25766 ,14277,14278,14279 ,0,0,0}, + {25720,25719,25763 ,14232,14231,14276 ,0,0,0}, {25721,25677,25767 ,14233,14189,14280 ,0,0,0}, + {25675,25720,25676 ,14187,14232,14188 ,0,0,0}, {25722,25767,25768 ,14234,14280,14281 ,0,0,0}, + {25721,25675,25677 ,14233,14187,14189 ,0,0,0}, {25723,25768,25769 ,14235,14281,14282 ,0,0,0}, + {25767,25722,25721 ,14280,14234,14233 ,0,0,0}, {25724,25769,25770 ,14236,14282,14283 ,0,0,0}, + {25768,25723,25722 ,14281,14235,14234 ,0,0,0}, {25725,25770,25771 ,14237,14283,14284 ,0,0,0}, + {25769,25724,25723 ,14282,14236,14235 ,0,0,0}, {25670,25771,25772 ,14182,14284,14285 ,0,0,0}, + {25725,25724,25770 ,14237,14236,14283 ,0,0,0}, {25729,25772,25727 ,14241,14285,14239 ,0,0,0}, + {25670,25725,25771 ,14182,14237,14284 ,0,0,0}, {25730,25727,25773 ,14242,14239,14286 ,0,0,0}, + {25729,25670,25772 ,14241,14182,14285 ,0,0,0}, {25731,25773,25774 ,14243,14286,14287 ,0,0,0}, + {25727,25730,25729 ,14239,14242,14241 ,0,0,0}, {25732,25774,25775 ,14244,14287,14288 ,0,0,0}, + {25773,25731,25730 ,14286,14243,14242 ,0,0,0}, {25733,25775,25776 ,14245,14288,14289 ,0,0,0}, + {25774,25732,25731 ,14287,14244,14243 ,0,0,0}, {25734,25776,25777 ,14246,14289,14290 ,0,0,0}, + {25775,25733,25732 ,14288,14245,14244 ,0,0,0}, {25735,25777,25778 ,14247,14290,14291 ,0,0,0}, + {25776,25734,25733 ,14289,14246,14245 ,0,0,0}, {25666,25778,25779 ,14178,14291,14292 ,0,0,0}, + {25777,25735,25734 ,14290,14247,14246 ,0,0,0}, {25736,25779,25737 ,14248,14292,14249 ,0,0,0}, + {25666,25735,25778 ,14178,14247,14291 ,0,0,0}, {25780,25653,25652 ,14293,14160,14159 ,0,0,0}, + {25736,25666,25779 ,14248,14178,14292 ,0,0,0}, {25662,25781,25657 ,14170,14294,14164 ,0,0,0}, + {25651,25736,25737 ,14158,14248,14249 ,0,0,0}, {25780,25641,25738 ,14293,14148,14250 ,0,0,0}, + {25640,25782,25648 ,14147,14295,14155 ,0,0,0}, {25738,25655,25638 ,14250,14162,14145 ,0,0,0}, + {25780,25738,25653 ,14293,14250,14160 ,0,0,0}, {25783,25740,25739 ,14296,14252,14251 ,0,0,0}, + {25738,25641,25655 ,14250,14148,14162 ,0,0,0}, {25198,25740,25783 ,14297,14252,14296 ,0,0,0}, + {25740,25197,25642 ,14252,14253,14149 ,0,0,0}, {25646,25739,25644 ,14153,14251,14151 ,0,0,0}, + {25782,25783,25739 ,14295,14296,14251 ,0,0,0}, {25198,25197,25740 ,14297,14253,14252 ,0,0,0}, + {25742,25691,25556 ,14255,14203,14063 ,0,0,0}, {25688,25558,25698 ,14200,14065,14210 ,0,0,0}, + {25784,25560,25566 ,14298,14067,14073 ,0,0,0}, {25742,25559,25700 ,14255,14066,14212 ,0,0,0}, + {25742,25556,25785 ,14255,14063,14299 ,0,0,0}, {25786,25787,25788 ,14300,14301,14302 ,0,0,0}, + {25565,25559,25742 ,14072,14066,14255 ,0,0,0}, {25784,25786,25743 ,14298,14300,14256 ,0,0,0}, + {25566,25560,25559 ,14073,14067,14066 ,0,0,0}, {25786,25789,25744 ,14300,14303,14257 ,0,0,0}, + {25784,25743,25560 ,14298,14256,14067 ,0,0,0}, {25789,25790,25745 ,14303,14304,14258 ,0,0,0}, + {25786,25744,25743 ,14300,14257,14256 ,0,0,0}, {25790,25791,25746 ,14304,14305,14259 ,0,0,0}, + {25789,25745,25744 ,14303,14258,14257 ,0,0,0}, {25791,25792,25747 ,14305,14306,14260 ,0,0,0}, + {25790,25746,25745 ,14304,14259,14258 ,0,0,0}, {25792,25793,25748 ,14306,14307,14261 ,0,0,0}, + {25791,25747,25746 ,14305,14260,14259 ,0,0,0}, {25793,25794,25749 ,14307,14308,14262 ,0,0,0}, + {25792,25748,25747 ,14306,14261,14260 ,0,0,0}, {25794,25795,25707 ,14308,14309,14219 ,0,0,0}, + {25793,25749,25748 ,14307,14262,14261 ,0,0,0}, {25795,25751,25708 ,14309,14264,14220 ,0,0,0}, + {25707,25749,25794 ,14219,14262,14308 ,0,0,0}, {25796,25797,25798 ,14310,14311,14312 ,0,0,0}, + {25708,25707,25795 ,14220,14219,14309 ,0,0,0}, {25752,25796,25753 ,14265,14310,14266 ,0,0,0}, + {25751,25750,25708 ,14264,14263,14220 ,0,0,0}, {25796,25799,25754 ,14310,14313,14267 ,0,0,0}, + {25752,25753,25750 ,14265,14266,14263 ,0,0,0}, {25799,25800,25755 ,14313,14314,14268 ,0,0,0}, + {25796,25754,25753 ,14310,14267,14266 ,0,0,0}, {25800,25801,25756 ,14314,14315,14269 ,0,0,0}, + {25799,25755,25754 ,14313,14268,14267 ,0,0,0}, {25801,25802,25685 ,14315,14316,14197 ,0,0,0}, + {25800,25756,25755 ,14314,14269,14268 ,0,0,0}, {25683,25802,25803 ,14195,14316,14317 ,0,0,0}, + {25685,25756,25801 ,14197,14269,14315 ,0,0,0}, {25803,25757,25760 ,14317,14270,14273 ,0,0,0}, + {25802,25683,25685 ,14316,14195,14197 ,0,0,0}, {25757,25804,25761 ,14270,14318,14274 ,0,0,0}, + {25803,25760,25683 ,14317,14273,14195 ,0,0,0}, {25804,25805,25762 ,14318,14319,14275 ,0,0,0}, + {25757,25761,25760 ,14270,14274,14273 ,0,0,0}, {25805,25806,25763 ,14319,14320,14276 ,0,0,0}, + {25804,25762,25761 ,14318,14275,14274 ,0,0,0}, {25806,25807,25676 ,14320,14321,14188 ,0,0,0}, + {25805,25763,25762 ,14319,14276,14275 ,0,0,0}, {25807,25808,25677 ,14321,14322,14189 ,0,0,0}, + {25676,25763,25806 ,14188,14276,14320 ,0,0,0}, {25808,25764,25767 ,14322,14277,14280 ,0,0,0}, + {25677,25676,25807 ,14189,14188,14321 ,0,0,0}, {25764,25809,25768 ,14277,14323,14281 ,0,0,0}, + {25808,25767,25677 ,14322,14280,14189 ,0,0,0}, {25809,25810,25769 ,14323,14324,14282 ,0,0,0}, + {25764,25768,25767 ,14277,14281,14280 ,0,0,0}, {25810,25811,25770 ,14324,14325,14283 ,0,0,0}, + {25809,25769,25768 ,14323,14282,14281 ,0,0,0}, {25811,25812,25771 ,14325,14326,14284 ,0,0,0}, + {25810,25770,25769 ,14324,14283,14282 ,0,0,0}, {25812,25728,25772 ,14326,14240,14285 ,0,0,0}, + {25771,25770,25811 ,14284,14283,14325 ,0,0,0}, {25813,25814,25815 ,14327,14328,14329 ,0,0,0}, + {25772,25771,25812 ,14285,14284,14326 ,0,0,0}, {25726,25813,25773 ,14238,14327,14286 ,0,0,0}, + {25728,25727,25772 ,14240,14239,14285 ,0,0,0}, {25813,25816,25774 ,14327,14330,14287 ,0,0,0}, + {25726,25773,25727 ,14238,14286,14239 ,0,0,0}, {25816,25817,25775 ,14330,14331,14288 ,0,0,0}, + {25813,25774,25773 ,14327,14287,14286 ,0,0,0}, {25817,25818,25776 ,14331,14332,14289 ,0,0,0}, + {25816,25775,25774 ,14330,14288,14287 ,0,0,0}, {25818,25819,25777 ,14332,14333,14290 ,0,0,0}, + {25817,25776,25775 ,14331,14289,14288 ,0,0,0}, {25819,25820,25778 ,14333,14334,14291 ,0,0,0}, + {25818,25777,25776 ,14332,14290,14289 ,0,0,0}, {25820,25821,25779 ,14334,14335,14292 ,0,0,0}, + {25819,25778,25777 ,14333,14291,14290 ,0,0,0}, {25821,25822,25737 ,14335,14336,14249 ,0,0,0}, + {25820,25779,25778 ,14334,14292,14291 ,0,0,0}, {25822,25823,25652 ,14336,14337,14159 ,0,0,0}, + {25821,25737,25779 ,14335,14249,14292 ,0,0,0}, {25823,25654,25780 ,14337,14161,14293 ,0,0,0}, + {25652,25737,25822 ,14159,14249,14336 ,0,0,0}, {25824,25194,25056 ,14338,14339,14340 ,0,0,0}, + {25823,25780,25652 ,14337,14293,14159 ,0,0,0}, {25656,25639,25654 ,14163,14146,14161 ,0,0,0}, + {25780,25654,25641 ,14293,14161,14148 ,0,0,0}, {25189,25783,25824 ,14341,14296,14338 ,0,0,0}, + {25189,25200,25783 ,14341,14342,14296 ,0,0,0}, {25648,25782,25739 ,14155,14295,14251 ,0,0,0}, + {25658,25824,25782 ,14165,14338,14295 ,0,0,0}, {25198,25783,25200 ,14297,14296,14342 ,0,0,0}, + {25558,25785,25556 ,14065,14299,14063 ,0,0,0}, {25699,25562,25688 ,14211,14069,14200 ,0,0,0}, + {25565,25825,25826 ,14072,14343,14344 ,0,0,0}, {25785,25565,25742 ,14299,14072,14255 ,0,0,0}, + {25827,25785,25558 ,14345,14299,14065 ,0,0,0}, {25566,25826,25828 ,14073,14344,14346 ,0,0,0}, + {25785,25825,25565 ,14299,14343,14072 ,0,0,0}, {25784,25828,25787 ,14298,14346,14301 ,0,0,0}, + {25826,25566,25565 ,14344,14073,14072 ,0,0,0}, {25829,25789,25788 ,14347,14303,14302 ,0,0,0}, + {25828,25784,25566 ,14346,14298,14073 ,0,0,0}, {25830,25790,25829 ,14348,14304,14347 ,0,0,0}, + {25787,25786,25784 ,14301,14300,14298 ,0,0,0}, {25831,25832,25833 ,14349,14350,14351 ,0,0,0}, + {25788,25789,25786 ,14302,14303,14300 ,0,0,0}, {25830,25831,25791 ,14348,14349,14305 ,0,0,0}, + {25829,25790,25789 ,14347,14304,14303 ,0,0,0}, {25831,25834,25792 ,14349,14352,14306 ,0,0,0}, + {25830,25791,25790 ,14348,14305,14304 ,0,0,0}, {25834,25835,25793 ,14352,14353,14307 ,0,0,0}, + {25831,25792,25791 ,14349,14306,14305 ,0,0,0}, {25835,25836,25794 ,14353,14354,14308 ,0,0,0}, + {25834,25793,25792 ,14352,14307,14306 ,0,0,0}, {25836,25837,25795 ,14354,14355,14309 ,0,0,0}, + {25835,25794,25793 ,14353,14308,14307 ,0,0,0}, {25751,25837,25838 ,14264,14355,14356 ,0,0,0}, + {25836,25795,25794 ,14354,14309,14308 ,0,0,0}, {25752,25838,25797 ,14265,14356,14311 ,0,0,0}, + {25837,25751,25795 ,14355,14264,14309 ,0,0,0}, {25839,25840,25841 ,14357,14358,14359 ,0,0,0}, + {25838,25752,25751 ,14356,14265,14264 ,0,0,0}, {25798,25839,25799 ,14312,14357,14313 ,0,0,0}, + {25797,25796,25752 ,14311,14310,14265 ,0,0,0}, {25839,25842,25800 ,14357,14360,14314 ,0,0,0}, + {25798,25799,25796 ,14312,14313,14310 ,0,0,0}, {25842,25843,25801 ,14360,14361,14315 ,0,0,0}, + {25839,25800,25799 ,14357,14314,14313 ,0,0,0}, {25802,25843,25844 ,14316,14361,14362 ,0,0,0}, + {25842,25801,25800 ,14360,14315,14314 ,0,0,0}, {25803,25844,25758 ,14317,14362,14271 ,0,0,0}, + {25802,25801,25843 ,14316,14315,14361 ,0,0,0}, {25845,25846,25847 ,14363,14364,14365 ,0,0,0}, + {25844,25803,25802 ,14362,14317,14316 ,0,0,0}, {25759,25845,25804 ,14272,14363,14318 ,0,0,0}, + {25758,25757,25803 ,14271,14270,14317 ,0,0,0}, {25845,25848,25805 ,14363,14366,14319 ,0,0,0}, + {25759,25804,25757 ,14272,14318,14270 ,0,0,0}, {25848,25849,25806 ,14366,14367,14320 ,0,0,0}, + {25845,25805,25804 ,14363,14319,14318 ,0,0,0}, {25849,25850,25807 ,14367,14368,14321 ,0,0,0}, + {25848,25806,25805 ,14366,14320,14319 ,0,0,0}, {25808,25850,25765 ,14322,14368,14278 ,0,0,0}, + {25807,25806,25849 ,14321,14320,14367 ,0,0,0}, {25851,25852,25853 ,14369,14370,14371 ,0,0,0}, + {25850,25808,25807 ,14368,14322,14321 ,0,0,0}, {25766,25851,25809 ,14279,14369,14323 ,0,0,0}, + {25765,25764,25808 ,14278,14277,14322 ,0,0,0}, {25851,25854,25810 ,14369,14372,14324 ,0,0,0}, + {25766,25809,25764 ,14279,14323,14277 ,0,0,0}, {25854,25855,25811 ,14372,14373,14325 ,0,0,0}, + {25851,25810,25809 ,14369,14324,14323 ,0,0,0}, {25855,25856,25812 ,14373,14374,14326 ,0,0,0}, + {25854,25811,25810 ,14372,14325,14324 ,0,0,0}, {25728,25856,25857 ,14240,14374,14375 ,0,0,0}, + {25855,25812,25811 ,14373,14326,14325 ,0,0,0}, {25726,25857,25814 ,14238,14375,14328 ,0,0,0}, + {25856,25728,25812 ,14374,14240,14326 ,0,0,0}, {25858,25816,25815 ,14376,14330,14329 ,0,0,0}, + {25857,25726,25728 ,14375,14238,14240 ,0,0,0}, {25859,25860,25861 ,14377,14378,14379 ,0,0,0}, + {25814,25813,25726 ,14328,14327,14238 ,0,0,0}, {25858,25859,25817 ,14376,14377,14331 ,0,0,0}, + {25815,25816,25813 ,14329,14330,14327 ,0,0,0}, {25859,25862,25818 ,14377,14380,14332 ,0,0,0}, + {25858,25817,25816 ,14376,14331,14330 ,0,0,0}, {25862,25863,25819 ,14380,14381,14333 ,0,0,0}, + {25859,25818,25817 ,14377,14332,14331 ,0,0,0}, {25863,25864,25820 ,14381,14382,14334 ,0,0,0}, + {25862,25819,25818 ,14380,14333,14332 ,0,0,0}, {25864,25865,25821 ,14382,14383,14335 ,0,0,0}, + {25863,25820,25819 ,14381,14334,14333 ,0,0,0}, {25865,25866,25822 ,14383,14384,14336 ,0,0,0}, + {25864,25821,25820 ,14382,14335,14334 ,0,0,0}, {25866,25867,25823 ,14384,14385,14337 ,0,0,0}, + {25865,25822,25821 ,14383,14336,14335 ,0,0,0}, {25654,25867,25656 ,14161,14385,14163 ,0,0,0}, + {25823,25822,25866 ,14337,14336,14384 ,0,0,0}, {25661,25656,25867 ,14168,14163,14385 ,0,0,0}, + {25654,25823,25867 ,14161,14337,14385 ,0,0,0}, {25658,25781,25824 ,14165,14294,14338 ,0,0,0}, + {25782,25824,25783 ,14295,14338,14296 ,0,0,0}, {25640,25658,25782 ,14147,14165,14295 ,0,0,0}, + {25657,25781,25658 ,14164,14294,14165 ,0,0,0}, {25189,25824,25056 ,14341,14338,14340 ,0,0,0}, + {25562,25827,25558 ,14069,14345,14065 ,0,0,0}, {25570,25564,25563 ,14077,14071,14070 ,0,0,0}, + {25825,25868,25869 ,14343,14386,14387 ,0,0,0}, {25827,25825,25785 ,14345,14343,14299 ,0,0,0}, + {25562,25870,25827 ,14069,14388,14345 ,0,0,0}, {25826,25869,25871 ,14344,14387,14389 ,0,0,0}, + {25827,25868,25825 ,14345,14386,14343 ,0,0,0}, {25828,25871,25872 ,14346,14389,14390 ,0,0,0}, + {25825,25869,25826 ,14343,14387,14344 ,0,0,0}, {25787,25872,25873 ,14301,14390,14391 ,0,0,0}, + {25826,25871,25828 ,14344,14389,14346 ,0,0,0}, {25788,25873,25874 ,14302,14391,14392 ,0,0,0}, + {25828,25872,25787 ,14346,14390,14301 ,0,0,0}, {25829,25874,25875 ,14347,14392,14393 ,0,0,0}, + {25787,25873,25788 ,14301,14391,14302 ,0,0,0}, {25830,25875,25832 ,14348,14393,14350 ,0,0,0}, + {25874,25829,25788 ,14392,14347,14302 ,0,0,0}, {25876,25834,25833 ,14394,14352,14351 ,0,0,0}, + {25875,25830,25829 ,14393,14348,14347 ,0,0,0}, {25877,25878,25876 ,14395,14396,14394 ,0,0,0}, + {25832,25831,25830 ,14350,14349,14348 ,0,0,0}, {25876,25878,25835 ,14394,14396,14353 ,0,0,0}, + {25833,25834,25831 ,14351,14352,14349 ,0,0,0}, {25878,25879,25836 ,14396,14397,14354 ,0,0,0}, + {25876,25835,25834 ,14394,14353,14352 ,0,0,0}, {25837,25879,25880 ,14355,14397,14398 ,0,0,0}, + {25878,25836,25835 ,14396,14354,14353 ,0,0,0}, {25838,25880,25881 ,14356,14398,14399 ,0,0,0}, + {25836,25879,25837 ,14354,14397,14355 ,0,0,0}, {25797,25881,25882 ,14311,14399,14400 ,0,0,0}, + {25837,25880,25838 ,14355,14398,14356 ,0,0,0}, {25798,25882,25840 ,14312,14400,14358 ,0,0,0}, + {25881,25797,25838 ,14399,14311,14356 ,0,0,0}, {25883,25884,25841 ,14401,14402,14359 ,0,0,0}, + {25882,25798,25797 ,14400,14312,14311 ,0,0,0}, {25841,25884,25842 ,14359,14402,14360 ,0,0,0}, + {25840,25839,25798 ,14358,14357,14312 ,0,0,0}, {25884,25885,25843 ,14402,14403,14361 ,0,0,0}, + {25841,25842,25839 ,14359,14360,14357 ,0,0,0}, {25844,25885,25886 ,14362,14403,14404 ,0,0,0}, + {25884,25843,25842 ,14402,14361,14360 ,0,0,0}, {25758,25886,25887 ,14271,14404,14405 ,0,0,0}, + {25843,25885,25844 ,14361,14403,14362 ,0,0,0}, {25759,25887,25846 ,14272,14405,14364 ,0,0,0}, + {25886,25758,25844 ,14404,14271,14362 ,0,0,0}, {25888,25889,25847 ,14406,14407,14365 ,0,0,0}, + {25887,25759,25758 ,14405,14272,14271 ,0,0,0}, {25847,25889,25848 ,14365,14407,14366 ,0,0,0}, + {25846,25845,25759 ,14364,14363,14272 ,0,0,0}, {25889,25890,25849 ,14407,14408,14367 ,0,0,0}, + {25847,25848,25845 ,14365,14366,14363 ,0,0,0}, {25850,25890,25891 ,14368,14408,14409 ,0,0,0}, + {25889,25849,25848 ,14407,14367,14366 ,0,0,0}, {25765,25891,25892 ,14278,14409,14410 ,0,0,0}, + {25849,25890,25850 ,14367,14408,14368 ,0,0,0}, {25766,25892,25852 ,14279,14410,14370 ,0,0,0}, + {25891,25765,25850 ,14409,14278,14368 ,0,0,0}, {25893,25894,25853 ,14411,14412,14371 ,0,0,0}, + {25892,25766,25765 ,14410,14279,14278 ,0,0,0}, {25853,25894,25854 ,14371,14412,14372 ,0,0,0}, + {25852,25851,25766 ,14370,14369,14279 ,0,0,0}, {25894,25895,25855 ,14412,14413,14373 ,0,0,0}, + {25853,25854,25851 ,14371,14372,14369 ,0,0,0}, {25856,25895,25896 ,14374,14413,14414 ,0,0,0}, + {25894,25855,25854 ,14412,14373,14372 ,0,0,0}, {25857,25896,25897 ,14375,14414,14415 ,0,0,0}, + {25855,25895,25856 ,14373,14413,14374 ,0,0,0}, {25814,25897,25898 ,14328,14415,14416 ,0,0,0}, + {25856,25896,25857 ,14374,14414,14375 ,0,0,0}, {25815,25898,25899 ,14329,14416,14417 ,0,0,0}, + {25857,25897,25814 ,14375,14415,14328 ,0,0,0}, {25858,25899,25860 ,14376,14417,14378 ,0,0,0}, + {25898,25815,25814 ,14416,14329,14328 ,0,0,0}, {25900,25862,25861 ,14418,14380,14379 ,0,0,0}, + {25899,25858,25815 ,14417,14376,14329 ,0,0,0}, {25901,25902,25900 ,14419,14420,14418 ,0,0,0}, + {25860,25859,25858 ,14378,14377,14376 ,0,0,0}, {25900,25902,25863 ,14418,14420,14381 ,0,0,0}, + {25861,25862,25859 ,14379,14380,14377 ,0,0,0}, {25902,25903,25864 ,14420,14421,14382 ,0,0,0}, + {25900,25863,25862 ,14418,14381,14380 ,0,0,0}, {25903,25904,25865 ,14421,14422,14383 ,0,0,0}, + {25902,25864,25863 ,14420,14382,14381 ,0,0,0}, {25904,25905,25866 ,14422,14423,14384 ,0,0,0}, + {25903,25865,25864 ,14421,14383,14382 ,0,0,0}, {25867,25905,25661 ,14385,14423,14168 ,0,0,0}, + {25904,25866,25865 ,14422,14384,14383 ,0,0,0}, {25661,25906,25656 ,14168,14424,14163 ,0,0,0}, + {25866,25905,25867 ,14384,14423,14385 ,0,0,0}, {25061,25781,25662 ,14425,14294,14170 ,0,0,0}, + {25781,25194,25824 ,14294,14339,14338 ,0,0,0}, {25639,25657,25658 ,14146,14164,14165 ,0,0,0}, + {25906,25662,25657 ,14424,14170,14164 ,0,0,0}, {25061,25194,25781 ,14425,14339,14294 ,0,0,0}, + {25564,25870,25562 ,14071,14388,14069 ,0,0,0}, {25907,25569,25570 ,14426,14076,14077 ,0,0,0}, + {25908,25868,25870 ,14427,14386,14388 ,0,0,0}, {25870,25868,25827 ,14388,14386,14345 ,0,0,0}, + {25870,25741,25908 ,14388,14254,14427 ,0,0,0}, {25909,25869,25868 ,14428,14387,14386 ,0,0,0}, + {25868,25908,25909 ,14386,14427,14428 ,0,0,0}, {25910,25871,25869 ,14429,14389,14387 ,0,0,0}, + {25869,25909,25910 ,14387,14428,14429 ,0,0,0}, {25911,25872,25871 ,14430,14390,14389 ,0,0,0}, + {25871,25910,25911 ,14389,14429,14430 ,0,0,0}, {25912,25873,25872 ,14431,14391,14390 ,0,0,0}, + {25872,25911,25912 ,14390,14430,14431 ,0,0,0}, {25913,25874,25873 ,14432,14392,14391 ,0,0,0}, + {25873,25912,25913 ,14391,14431,14432 ,0,0,0}, {25914,25875,25874 ,14433,14393,14392 ,0,0,0}, + {25874,25913,25914 ,14392,14432,14433 ,0,0,0}, {25915,25832,25875 ,14434,14350,14393 ,0,0,0}, + {25875,25914,25915 ,14393,14433,14434 ,0,0,0}, {25916,25833,25832 ,14435,14351,14350 ,0,0,0}, + {25832,25915,25916 ,14350,14434,14435 ,0,0,0}, {25917,25876,25833 ,14436,14394,14351 ,0,0,0}, + {25916,25917,25833 ,14435,14436,14351 ,0,0,0}, {25918,25919,25920 ,14437,14438,14439 ,0,0,0}, + {25917,25877,25876 ,14436,14395,14394 ,0,0,0}, {25921,25879,25878 ,14440,14397,14396 ,0,0,0}, + {25877,25921,25878 ,14395,14440,14396 ,0,0,0}, {25922,25880,25879 ,14441,14398,14397 ,0,0,0}, + {25879,25921,25922 ,14397,14440,14441 ,0,0,0}, {25923,25881,25880 ,14442,14399,14398 ,0,0,0}, + {25880,25922,25923 ,14398,14441,14442 ,0,0,0}, {25924,25882,25881 ,14443,14400,14399 ,0,0,0}, + {25881,25923,25924 ,14399,14442,14443 ,0,0,0}, {25925,25840,25882 ,14444,14358,14400 ,0,0,0}, + {25882,25924,25925 ,14400,14443,14444 ,0,0,0}, {25926,25841,25840 ,14445,14359,14358 ,0,0,0}, + {25925,25926,25840 ,14444,14445,14358 ,0,0,0}, {25927,25883,25928 ,14446,14401,14447 ,0,0,0}, + {25926,25883,25841 ,14445,14401,14359 ,0,0,0}, {25927,25885,25884 ,14446,14403,14402 ,0,0,0}, + {25883,25927,25884 ,14401,14446,14402 ,0,0,0}, {25929,25886,25885 ,14448,14404,14403 ,0,0,0}, + {25885,25927,25929 ,14403,14446,14448 ,0,0,0}, {25930,25887,25886 ,14449,14405,14404 ,0,0,0}, + {25886,25929,25930 ,14404,14448,14449 ,0,0,0}, {25931,25846,25887 ,14450,14364,14405 ,0,0,0}, + {25887,25930,25931 ,14405,14449,14450 ,0,0,0}, {25932,25847,25846 ,14451,14365,14364 ,0,0,0}, + {25931,25932,25846 ,14450,14451,14364 ,0,0,0}, {25933,25934,25935 ,14452,14453,14454 ,0,0,0}, + {25932,25888,25847 ,14451,14406,14365 ,0,0,0}, {25936,25890,25889 ,14455,14408,14407 ,0,0,0}, + {25888,25936,25889 ,14406,14455,14407 ,0,0,0}, {25937,25891,25890 ,14456,14409,14408 ,0,0,0}, + {25890,25936,25937 ,14408,14455,14456 ,0,0,0}, {25938,25892,25891 ,14457,14410,14409 ,0,0,0}, + {25891,25937,25938 ,14409,14456,14457 ,0,0,0}, {25939,25852,25892 ,14458,14370,14410 ,0,0,0}, + {25892,25938,25939 ,14410,14457,14458 ,0,0,0}, {25940,25853,25852 ,14459,14371,14370 ,0,0,0}, + {25939,25940,25852 ,14458,14459,14370 ,0,0,0}, {25894,25941,25895 ,14412,14460,14413 ,0,0,0}, + {25940,25893,25853 ,14459,14411,14371 ,0,0,0}, {25942,25943,25941 ,14461,14462,14460 ,0,0,0}, + {25893,25941,25894 ,14411,14460,14412 ,0,0,0}, {25943,25896,25895 ,14462,14414,14413 ,0,0,0}, + {25895,25941,25943 ,14413,14460,14462 ,0,0,0}, {25944,25897,25896 ,14463,14415,14414 ,0,0,0}, + {25896,25943,25944 ,14414,14462,14463 ,0,0,0}, {25945,25898,25897 ,14464,14416,14415 ,0,0,0}, + {25897,25944,25945 ,14415,14463,14464 ,0,0,0}, {25946,25899,25898 ,14465,14417,14416 ,0,0,0}, + {25898,25945,25946 ,14416,14464,14465 ,0,0,0}, {25947,25860,25899 ,14466,14378,14417 ,0,0,0}, + {25899,25946,25947 ,14417,14465,14466 ,0,0,0}, {25948,25861,25860 ,14467,14379,14378 ,0,0,0}, + {25860,25947,25948 ,14378,14466,14467 ,0,0,0}, {25949,25900,25861 ,14468,14418,14379 ,0,0,0}, + {25948,25949,25861 ,14467,14468,14379 ,0,0,0}, {25902,25950,25903 ,14420,14469,14421 ,0,0,0}, + {25949,25901,25900 ,14468,14419,14418 ,0,0,0}, {25903,25951,25904 ,14421,14470,14422 ,0,0,0}, + {25901,25950,25902 ,14419,14469,14420 ,0,0,0}, {25904,25952,25905 ,14422,14471,14423 ,0,0,0}, + {25950,25951,25903 ,14469,14470,14421 ,0,0,0}, {25905,25659,25661 ,14423,14166,14168 ,0,0,0}, + {25951,25952,25904 ,14470,14471,14422 ,0,0,0}, {25660,25664,25663 ,14167,14172,14171 ,0,0,0}, + {25952,25659,25905 ,14471,14166,14423 ,0,0,0}, {25660,25906,25661 ,14167,14424,14168 ,0,0,0}, + {25243,25061,25662 ,14472,14425,14170 ,0,0,0}, {25656,25906,25657 ,14163,14424,14164 ,0,0,0}, + {25906,25660,25663 ,14424,14167,14171 ,0,0,0}, {25058,25243,25662 ,14169,14472,14170 ,0,0,0}, + {25569,25741,25564 ,14076,14254,14071 ,0,0,0}, {25907,25572,25567 ,14426,14079,14074 ,0,0,0}, + {25908,25741,25953 ,14427,14254,14473 ,0,0,0}, {25564,25741,25870 ,14071,14254,14388 ,0,0,0}, + {25741,25568,25953 ,14254,14075,14473 ,0,0,0}, {25909,25908,25954 ,14428,14427,14474 ,0,0,0}, + {25908,25953,25954 ,14427,14473,14474 ,0,0,0}, {25910,25909,25955 ,14429,14428,14475 ,0,0,0}, + {25909,25954,25955 ,14428,14474,14475 ,0,0,0}, {25911,25910,25956 ,14430,14429,14476 ,0,0,0}, + {25910,25955,25956 ,14429,14475,14476 ,0,0,0}, {25912,25911,25957 ,14431,14430,14477 ,0,0,0}, + {25911,25956,25957 ,14430,14476,14477 ,0,0,0}, {25913,25912,25958 ,14432,14431,14478 ,0,0,0}, + {25912,25957,25958 ,14431,14477,14478 ,0,0,0}, {25914,25913,25959 ,14433,14432,14479 ,0,0,0}, + {25913,25958,25959 ,14432,14478,14479 ,0,0,0}, {25915,25914,25960 ,14434,14433,14480 ,0,0,0}, + {25914,25959,25960 ,14433,14479,14480 ,0,0,0}, {25916,25915,25961 ,14435,14434,14481 ,0,0,0}, + {25915,25960,25961 ,14434,14480,14481 ,0,0,0}, {25917,25916,25962 ,14436,14435,14482 ,0,0,0}, + {25916,25961,25962 ,14435,14481,14482 ,0,0,0}, {25877,25917,25963 ,14395,14436,14483 ,0,0,0}, + {25917,25962,25963 ,14436,14482,14483 ,0,0,0}, {25921,25877,25918 ,14440,14395,14437 ,0,0,0}, + {25963,25918,25877 ,14483,14437,14395 ,0,0,0}, {25922,25921,25920 ,14441,14440,14439 ,0,0,0}, + {25921,25918,25920 ,14440,14437,14439 ,0,0,0}, {25923,25922,25964 ,14442,14441,14484 ,0,0,0}, + {25922,25920,25964 ,14441,14439,14484 ,0,0,0}, {25924,25923,25965 ,14443,14442,14485 ,0,0,0}, + {25923,25964,25965 ,14442,14484,14485 ,0,0,0}, {25925,25924,25966 ,14444,14443,14486 ,0,0,0}, + {25924,25965,25966 ,14443,14485,14486 ,0,0,0}, {25926,25925,25967 ,14445,14444,14487 ,0,0,0}, + {25925,25966,25967 ,14444,14486,14487 ,0,0,0}, {25883,25926,25968 ,14401,14445,14488 ,0,0,0}, + {25926,25967,25968 ,14445,14487,14488 ,0,0,0}, {25968,25969,25928 ,14488,14489,14447 ,0,0,0}, + {25968,25928,25883 ,14488,14447,14401 ,0,0,0}, {25929,25927,25970 ,14448,14446,14490 ,0,0,0}, + {25927,25928,25970 ,14446,14447,14490 ,0,0,0}, {25930,25929,25971 ,14449,14448,14491 ,0,0,0}, + {25929,25970,25971 ,14448,14490,14491 ,0,0,0}, {25931,25930,25972 ,14450,14449,14492 ,0,0,0}, + {25930,25971,25972 ,14449,14491,14492 ,0,0,0}, {25932,25931,25973 ,14451,14450,14493 ,0,0,0}, + {25931,25972,25973 ,14450,14492,14493 ,0,0,0}, {25888,25932,25974 ,14406,14451,14494 ,0,0,0}, + {25932,25973,25974 ,14451,14493,14494 ,0,0,0}, {25936,25888,25933 ,14455,14406,14452 ,0,0,0}, + {25974,25933,25888 ,14494,14452,14406 ,0,0,0}, {25937,25936,25935 ,14456,14455,14454 ,0,0,0}, + {25936,25933,25935 ,14455,14452,14454 ,0,0,0}, {25938,25937,25975 ,14457,14456,14495 ,0,0,0}, + {25937,25935,25975 ,14456,14454,14495 ,0,0,0}, {25939,25938,25976 ,14458,14457,14496 ,0,0,0}, + {25938,25975,25976 ,14457,14495,14496 ,0,0,0}, {25940,25939,25977 ,14459,14458,14497 ,0,0,0}, + {25939,25976,25977 ,14458,14496,14497 ,0,0,0}, {25893,25940,25978 ,14411,14459,14498 ,0,0,0}, + {25940,25977,25978 ,14459,14497,14498 ,0,0,0}, {25941,25893,25979 ,14460,14411,14499 ,0,0,0}, + {25893,25978,25979 ,14411,14498,14499 ,0,0,0}, {25942,25979,25980 ,14461,14499,14500 ,0,0,0}, + {25979,25942,25941 ,14499,14461,14460 ,0,0,0}, {25944,25943,25981 ,14463,14462,14501 ,0,0,0}, + {25943,25942,25981 ,14462,14461,14501 ,0,0,0}, {25945,25944,25982 ,14464,14463,14502 ,0,0,0}, + {25944,25981,25982 ,14463,14501,14502 ,0,0,0}, {25946,25945,25983 ,14465,14464,14503 ,0,0,0}, + {25945,25982,25983 ,14464,14502,14503 ,0,0,0}, {25947,25946,25984 ,14466,14465,14504 ,0,0,0}, + {25946,25983,25984 ,14465,14503,14504 ,0,0,0}, {25948,25947,25985 ,14467,14466,14505 ,0,0,0}, + {25947,25984,25985 ,14466,14504,14505 ,0,0,0}, {25949,25948,25986 ,14468,14467,14506 ,0,0,0}, + {25948,25985,25986 ,14467,14505,14506 ,0,0,0}, {25901,25949,25987 ,14419,14468,14507 ,0,0,0}, + {25949,25986,25987 ,14468,14506,14507 ,0,0,0}, {25950,25901,25988 ,14469,14419,14508 ,0,0,0}, + {25901,25987,25988 ,14419,14507,14508 ,0,0,0}, {25951,25950,25989 ,14470,14469,14509 ,0,0,0}, + {25950,25988,25989 ,14469,14508,14509 ,0,0,0}, {25952,25951,25990 ,14471,14470,14510 ,0,0,0}, + {25951,25989,25990 ,14470,14509,14510 ,0,0,0}, {25659,25952,25991 ,14166,14471,14511 ,0,0,0}, + {25952,25990,25991 ,14471,14510,14511 ,0,0,0}, {25992,25660,25659 ,14512,14167,14166 ,0,0,0}, + {25991,25992,25659 ,14511,14512,14166 ,0,0,0}, {25906,25663,25662 ,14424,14171,14170 ,0,0,0}, + {25992,25664,25660 ,14512,14172,14167 ,0,0,0}, {25058,25663,25413 ,14169,14171,14173 ,0,0,0}, + {25567,25569,25907 ,14074,14076,14426 ,0,0,0}, {25576,25573,25567 ,14083,14080,14074 ,0,0,0}, + {25573,25993,25568 ,14080,14513,14075 ,0,0,0}, {25568,25993,25953 ,14075,14513,14473 ,0,0,0}, + {25993,25994,25953 ,14513,14514,14473 ,0,0,0}, {25953,25994,25954 ,14473,14514,14474 ,0,0,0}, + {25994,25995,25954 ,14514,14515,14474 ,0,0,0}, {25954,25995,25955 ,14474,14515,14475 ,0,0,0}, + {25995,25996,25955 ,14515,14516,14475 ,0,0,0}, {25955,25996,25956 ,14475,14516,14476 ,0,0,0}, + {25996,25997,25956 ,14516,14517,14476 ,0,0,0}, {25956,25997,25957 ,14476,14517,14477 ,0,0,0}, + {25997,25998,25957 ,14517,14518,14477 ,0,0,0}, {25957,25998,25958 ,14477,14518,14478 ,0,0,0}, + {25998,25999,25958 ,14518,14519,14478 ,0,0,0}, {25958,25999,25959 ,14478,14519,14479 ,0,0,0}, + {25999,26000,25959 ,14519,14520,14479 ,0,0,0}, {26000,26001,25960 ,14520,14521,14480 ,0,0,0}, + {26000,25960,25959 ,14520,14480,14479 ,0,0,0}, {26001,26002,25961 ,14521,14522,14481 ,0,0,0}, + {26001,25961,25960 ,14521,14481,14480 ,0,0,0}, {26002,26003,25962 ,14522,14523,14482 ,0,0,0}, + {26002,25962,25961 ,14522,14482,14481 ,0,0,0}, {26003,26004,25963 ,14523,14524,14483 ,0,0,0}, + {26003,25963,25962 ,14523,14483,14482 ,0,0,0}, {26004,26005,25918 ,14524,14525,14437 ,0,0,0}, + {26004,25918,25963 ,14524,14437,14483 ,0,0,0}, {25919,25918,26005 ,14438,14437,14525 ,0,0,0}, + {25919,26006,25920 ,14438,14526,14439 ,0,0,0}, {25920,26006,25964 ,14439,14526,14484 ,0,0,0}, + {26006,26007,25964 ,14526,14527,14484 ,0,0,0}, {25964,26007,25965 ,14484,14527,14485 ,0,0,0}, + {26007,26008,25965 ,14527,14528,14485 ,0,0,0}, {26008,26009,25966 ,14528,14529,14486 ,0,0,0}, + {26008,25966,25965 ,14528,14486,14485 ,0,0,0}, {26009,26010,25967 ,14529,14530,14487 ,0,0,0}, + {26009,25967,25966 ,14529,14487,14486 ,0,0,0}, {26010,25969,25968 ,14530,14489,14488 ,0,0,0}, + {26010,25968,25967 ,14530,14488,14487 ,0,0,0}, {25969,26011,25928 ,14489,14531,14447 ,0,0,0}, + {26011,26012,25928 ,14531,14532,14447 ,0,0,0}, {25928,26012,25970 ,14447,14532,14490 ,0,0,0}, + {26012,26013,25970 ,14532,14533,14490 ,0,0,0}, {25970,26013,25971 ,14490,14533,14491 ,0,0,0}, + {26013,26014,25971 ,14533,14534,14491 ,0,0,0}, {26014,26015,25972 ,14534,14535,14492 ,0,0,0}, + {26014,25972,25971 ,14534,14492,14491 ,0,0,0}, {26015,26016,25973 ,14535,14536,14493 ,0,0,0}, + {26015,25973,25972 ,14535,14493,14492 ,0,0,0}, {26016,26017,25974 ,14536,14537,14494 ,0,0,0}, + {26016,25974,25973 ,14536,14494,14493 ,0,0,0}, {26017,26018,25933 ,14537,14538,14452 ,0,0,0}, + {26017,25933,25974 ,14537,14452,14494 ,0,0,0}, {25934,25933,26018 ,14453,14452,14538 ,0,0,0}, + {25934,26019,25935 ,14453,14539,14454 ,0,0,0}, {25935,26019,25975 ,14454,14539,14495 ,0,0,0}, + {26019,26020,25975 ,14539,14540,14495 ,0,0,0}, {26020,26021,25976 ,14540,14541,14496 ,0,0,0}, + {26020,25976,25975 ,14540,14496,14495 ,0,0,0}, {26021,26022,25977 ,14541,14542,14497 ,0,0,0}, + {26021,25977,25976 ,14541,14497,14496 ,0,0,0}, {26022,26023,25978 ,14542,14543,14498 ,0,0,0}, + {26022,25978,25977 ,14542,14498,14497 ,0,0,0}, {26023,25980,25979 ,14543,14500,14499 ,0,0,0}, + {26023,25979,25978 ,14543,14499,14498 ,0,0,0}, {25980,26024,25942 ,14500,14544,14461 ,0,0,0}, + {26024,26025,25942 ,14544,14545,14461 ,0,0,0}, {25942,26025,25981 ,14461,14545,14501 ,0,0,0}, + {26025,26026,25981 ,14545,14546,14501 ,0,0,0}, {25981,26026,25982 ,14501,14546,14502 ,0,0,0}, + {26026,26027,25982 ,14546,14547,14502 ,0,0,0}, {25982,26027,25983 ,14502,14547,14503 ,0,0,0}, + {26027,26028,25983 ,14547,14548,14503 ,0,0,0}, {26028,26029,25984 ,14548,14549,14504 ,0,0,0}, + {26028,25984,25983 ,14548,14504,14503 ,0,0,0}, {26029,26030,25985 ,14549,14550,14505 ,0,0,0}, + {26029,25985,25984 ,14549,14505,14504 ,0,0,0}, {26030,26031,25986 ,14550,14551,14506 ,0,0,0}, + {26030,25986,25985 ,14550,14506,14505 ,0,0,0}, {26031,26032,25987 ,14551,14552,14507 ,0,0,0}, + {26031,25987,25986 ,14551,14507,14506 ,0,0,0}, {26032,26033,25988 ,14552,14553,14508 ,0,0,0}, + {26032,25988,25987 ,14552,14508,14507 ,0,0,0}, {26033,26034,25989 ,14553,14554,14509 ,0,0,0}, + {26033,25989,25988 ,14553,14509,14508 ,0,0,0}, {26034,26035,25990 ,14554,14555,14510 ,0,0,0}, + {26034,25990,25989 ,14554,14510,14509 ,0,0,0}, {26035,26036,25991 ,14555,14556,14511 ,0,0,0}, + {26035,25991,25990 ,14555,14511,14510 ,0,0,0}, {26036,26037,25992 ,14556,14557,14512 ,0,0,0}, + {26036,25992,25991 ,14556,14512,14511 ,0,0,0}, {25665,25992,26037 ,14175,14512,14557 ,0,0,0}, + {25992,25665,25664 ,14512,14175,14172 ,0,0,0}, {25066,25664,25665 ,14174,14172,14175 ,0,0,0}, + {26038,26039,26009 ,14558,14559,14560 ,0,0,0}, {26009,26008,26038 ,14560,14561,14558 ,0,0,0}, + {26040,26041,26042 ,14562,14563,14564 ,0,0,0}, {26043,26007,26006 ,14565,14566,14567 ,0,0,0}, + {26008,26007,26044 ,14561,14566,14568 ,0,0,0}, {26043,26044,26007 ,14565,14568,14566 ,0,0,0}, + {25919,26005,26045 ,14569,14570,14571 ,0,0,0}, {26046,25919,26045 ,14572,14569,14571 ,0,0,0}, + {26006,25919,26046 ,14567,14569,14572 ,0,0,0}, {26045,26004,26047 ,14571,14573,14574 ,0,0,0}, + {26006,26046,26043 ,14567,14572,14565 ,0,0,0}, {26045,26005,26004 ,14571,14570,14573 ,0,0,0}, + {26044,26038,26008 ,14568,14558,14561 ,0,0,0}, {26048,26003,26002 ,14575,14576,14577 ,0,0,0}, + {26048,26047,26003 ,14575,14574,14576 ,0,0,0}, {26049,26048,26002 ,14578,14575,14577 ,0,0,0}, + {26050,26051,26052 ,14579,14580,14581 ,0,0,0}, {26053,26049,26001 ,14582,14578,14583 ,0,0,0}, + {26000,26053,26001 ,14584,14582,14583 ,0,0,0}, {26054,26000,25999 ,14585,14584,14586 ,0,0,0}, + {26053,26000,26054 ,14582,14584,14585 ,0,0,0}, {26055,26054,25999 ,14587,14585,14586 ,0,0,0}, + {26001,26049,26002 ,14583,14578,14577 ,0,0,0}, {26047,26004,26003 ,14574,14573,14576 ,0,0,0}, + {26056,25997,26057 ,14588,14589,14590 ,0,0,0}, {25998,26056,26055 ,14591,14588,14587 ,0,0,0}, + {25996,26058,26057 ,14592,14593,14590 ,0,0,0}, {25998,25997,26056 ,14591,14589,14588 ,0,0,0}, + {26058,25995,26059 ,14593,14594,14595 ,0,0,0}, {25995,26058,25996 ,14594,14593,14592 ,0,0,0}, + {26059,25994,26060 ,14595,14596,14597 ,0,0,0}, {25997,25996,26057 ,14589,14592,14590 ,0,0,0}, + {25995,25994,26059 ,14594,14596,14595 ,0,0,0}, {26059,26061,26062 ,14595,14598,14599 ,0,0,0}, + {25693,26063,25697 ,14600,14601,14209 ,0,0,0}, {26064,26065,26066 ,14602,14603,14604 ,0,0,0}, + {26063,26067,25697 ,14601,14605,14209 ,0,0,0}, {26068,26069,26070 ,14606,14607,14608 ,0,0,0}, + {26063,25693,26068 ,14601,14600,14606 ,0,0,0}, {26060,25994,25993 ,14597,14596,14609 ,0,0,0}, + {26062,26071,26072 ,14599,14610,14611 ,0,0,0}, {26073,26074,26072 ,14612,14613,14611 ,0,0,0}, + {26072,26071,26075 ,14611,14610,14614 ,0,0,0}, {25993,25573,26076 ,14609,14615,14616 ,0,0,0}, + {26077,26078,26079 ,14617,14618,14619 ,0,0,0}, {26078,26080,26081 ,14618,14620,14621 ,0,0,0}, + {26080,26082,26081 ,14620,14622,14621 ,0,0,0}, {26083,26079,26084 ,14623,14619,14624 ,0,0,0}, + {26085,26084,25571 ,14625,14624,14078 ,0,0,0}, {25573,26084,26076 ,14615,14624,14616 ,0,0,0}, + {26084,25576,25571 ,14624,14626,14078 ,0,0,0}, {26085,26083,26084 ,14625,14623,14624 ,0,0,0}, + {26065,26086,26087 ,14603,14627,14628 ,0,0,0}, {25998,26055,25999 ,14591,14587,14586 ,0,0,0}, + {26039,26010,26009 ,14559,14629,14560 ,0,0,0}, {25969,26010,26088 ,14630,14629,14631 ,0,0,0}, + {26039,26088,26010 ,14559,14631,14629 ,0,0,0}, {26089,26011,25969 ,14632,14633,14630 ,0,0,0}, + {25969,26088,26089 ,14630,14631,14632 ,0,0,0}, {26012,26089,26090 ,14634,14632,14635 ,0,0,0}, + {26089,26012,26011 ,14632,14634,14633 ,0,0,0}, {26091,26013,26090 ,14636,14637,14635 ,0,0,0}, + {26012,26090,26013 ,14634,14635,14637 ,0,0,0}, {26014,26013,26091 ,14638,14637,14636 ,0,0,0}, + {26091,26092,26014 ,14636,14639,14638 ,0,0,0}, {26014,26092,26015 ,14638,14639,14640 ,0,0,0}, + {26015,26092,26093 ,14640,14639,14641 ,0,0,0}, {26094,26095,26096 ,14642,14643,14644 ,0,0,0}, + {26097,26016,26093 ,14645,14646,14641 ,0,0,0}, {26015,26093,26016 ,14640,14641,14646 ,0,0,0}, + {26097,26098,26017 ,14645,14647,14648 ,0,0,0}, {26017,26016,26097 ,14648,14646,14645 ,0,0,0}, + {25934,26018,26098 ,14649,14650,14647 ,0,0,0}, {26098,26018,26017 ,14647,14650,14648 ,0,0,0}, + {26099,26019,25934 ,14651,14652,14649 ,0,0,0}, {25934,26098,26099 ,14649,14647,14651 ,0,0,0}, + {26019,26100,26020 ,14652,14653,14654 ,0,0,0}, {26100,26019,26099 ,14653,14652,14651 ,0,0,0}, + {26021,26020,26101 ,14655,14654,14656 ,0,0,0}, {26100,26101,26020 ,14653,14656,14654 ,0,0,0}, + {26102,26021,26101 ,14657,14655,14656 ,0,0,0}, {26102,26022,26021 ,14657,14658,14655 ,0,0,0}, + {26102,26103,26022 ,14657,14659,14658 ,0,0,0}, {26104,26105,26106 ,14660,14661,14662 ,0,0,0}, + {26023,26103,26107 ,14663,14659,14664 ,0,0,0}, {26103,26023,26022 ,14659,14663,14658 ,0,0,0}, + {26108,25980,26107 ,14665,14666,14664 ,0,0,0}, {26023,26107,25980 ,14663,14664,14666 ,0,0,0}, + {26024,26108,26025 ,14667,14665,14668 ,0,0,0}, {26024,25980,26108 ,14667,14666,14665 ,0,0,0}, + {26026,26025,26109 ,14669,14668,14670 ,0,0,0}, {26108,26109,26025 ,14665,14670,14668 ,0,0,0}, + {26110,26027,26026 ,14671,14672,14669 ,0,0,0}, {26026,26109,26110 ,14669,14670,14671 ,0,0,0}, + {26027,26111,26028 ,14672,14673,14674 ,0,0,0}, {26111,26027,26110 ,14673,14672,14671 ,0,0,0}, + {26029,26028,26112 ,14675,14674,14676 ,0,0,0}, {26111,26112,26028 ,14673,14676,14674 ,0,0,0}, + {26113,26029,26112 ,14677,14675,14676 ,0,0,0}, {26113,26030,26029 ,14677,14678,14675 ,0,0,0}, + {26113,26114,26030 ,14677,14679,14678 ,0,0,0}, {26115,26116,26117 ,14680,14681,14682 ,0,0,0}, + {26031,26114,26116 ,14683,14679,14681 ,0,0,0}, {26114,26031,26030 ,14679,14683,14678 ,0,0,0}, + {26118,26032,26116 ,14684,14685,14681 ,0,0,0}, {26031,26116,26032 ,14683,14681,14685 ,0,0,0}, + {26119,26120,26121 ,14686,14687,14688 ,0,0,0}, {26033,26032,26118 ,14689,14685,14684 ,0,0,0}, + {26122,26123,26124 ,14690,14691,14692 ,0,0,0}, {26125,26126,26127 ,14693,14694,14695 ,0,0,0}, + {26128,26129,26130 ,14696,14697,14698 ,0,0,0}, {26131,26132,26133 ,14699,14700,14701 ,0,0,0}, + {26134,26135,26122 ,14702,14703,14690 ,0,0,0}, {26136,26137,26138 ,14704,14705,14706 ,0,0,0}, + {26139,26140,26135 ,14707,14708,14703 ,0,0,0}, {26136,26131,26137 ,14704,14699,14705 ,0,0,0}, + {26135,26141,26142 ,14703,14709,14710 ,0,0,0}, {25645,25196,26138 ,14711,726,14706 ,0,0,0}, + {26143,26033,26118 ,14712,14689,14684 ,0,0,0}, {26033,26143,26034 ,14689,14712,14713 ,0,0,0}, + {26034,26119,26035 ,14713,14686,14714 ,0,0,0}, {26115,26118,26116 ,14680,14684,14681 ,0,0,0}, + {26144,26145,26036 ,14715,14716,14717 ,0,0,0}, {26119,26144,26035 ,14686,14715,14714 ,0,0,0}, + {26142,26144,26121 ,14710,14715,14688 ,0,0,0}, {26035,26144,26036 ,14714,14715,14717 ,0,0,0}, + {26145,26146,25665 ,14716,14718,14719 ,0,0,0}, {26145,25665,26037 ,14716,14719,14720 ,0,0,0}, + {25067,25665,26147 ,730,14719,14721 ,0,0,0}, {26084,25573,25576 ,14624,14615,14626 ,0,0,0}, + {26077,26079,26083 ,14617,14619,14623 ,0,0,0}, {26087,26086,26148 ,14628,14627,14722 ,0,0,0}, + {26076,26060,25993 ,14616,14597,14609 ,0,0,0}, {26076,26079,26149 ,14616,14619,14723 ,0,0,0}, + {26150,26058,26062 ,14724,14593,14599 ,0,0,0}, {26060,26149,26061 ,14597,14723,14598 ,0,0,0}, + {26151,26057,26150 ,14725,14590,14724 ,0,0,0}, {26061,26059,26060 ,14598,14595,14597 ,0,0,0}, + {26152,26056,26151 ,14726,14588,14725 ,0,0,0}, {26062,26058,26059 ,14599,14593,14595 ,0,0,0}, + {26153,26055,26152 ,14727,14587,14726 ,0,0,0}, {26150,26057,26058 ,14724,14590,14593 ,0,0,0}, + {26154,26054,26153 ,14728,14585,14727 ,0,0,0}, {26151,26056,26057 ,14725,14588,14590 ,0,0,0}, + {26155,26053,26154 ,14729,14582,14728 ,0,0,0}, {26152,26055,26056 ,14726,14587,14588 ,0,0,0}, + {26156,26049,26155 ,14730,14578,14729 ,0,0,0}, {26153,26054,26055 ,14727,14585,14587 ,0,0,0}, + {26156,26157,26048 ,14730,14731,14575 ,0,0,0}, {26053,26054,26154 ,14582,14585,14728 ,0,0,0}, + {26158,26047,26157 ,14732,14574,14731 ,0,0,0}, {26049,26053,26155 ,14578,14582,14729 ,0,0,0}, + {26051,26045,26158 ,14580,14571,14732 ,0,0,0}, {26048,26049,26156 ,14575,14578,14730 ,0,0,0}, + {26159,26046,26051 ,14733,14572,14580 ,0,0,0}, {26047,26048,26157 ,14574,14575,14731 ,0,0,0}, + {26160,26043,26159 ,14734,14565,14733 ,0,0,0}, {26045,26047,26158 ,14571,14574,14732 ,0,0,0}, + {26161,26044,26160 ,14735,14568,14734 ,0,0,0}, {26051,26046,26045 ,14580,14572,14571 ,0,0,0}, + {26162,26038,26161 ,14736,14558,14735 ,0,0,0}, {26159,26043,26046 ,14733,14565,14572 ,0,0,0}, + {26162,26163,26039 ,14736,14737,14559 ,0,0,0}, {26044,26043,26160 ,14568,14565,14734 ,0,0,0}, + {26164,26088,26163 ,14738,14631,14737 ,0,0,0}, {26038,26044,26161 ,14558,14568,14735 ,0,0,0}, + {26165,26089,26164 ,14739,14632,14738 ,0,0,0}, {26039,26038,26162 ,14559,14558,14736 ,0,0,0}, + {26166,26090,26165 ,14740,14635,14739 ,0,0,0}, {26088,26039,26163 ,14631,14559,14737 ,0,0,0}, + {26167,26091,26166 ,14741,14636,14740 ,0,0,0}, {26089,26088,26164 ,14632,14631,14738 ,0,0,0}, + {26168,26092,26167 ,14742,14639,14741 ,0,0,0}, {26165,26090,26089 ,14739,14635,14632 ,0,0,0}, + {26168,26169,26093 ,14742,14743,14641 ,0,0,0}, {26091,26090,26166 ,14636,14635,14740 ,0,0,0}, + {26170,26097,26169 ,14744,14645,14743 ,0,0,0}, {26092,26091,26167 ,14639,14636,14741 ,0,0,0}, + {26094,26098,26170 ,14642,14647,14744 ,0,0,0}, {26093,26092,26168 ,14641,14639,14742 ,0,0,0}, + {26171,26099,26094 ,14745,14651,14642 ,0,0,0}, {26097,26093,26169 ,14645,14641,14743 ,0,0,0}, + {26172,26100,26171 ,14746,14653,14745 ,0,0,0}, {26098,26097,26170 ,14647,14645,14744 ,0,0,0}, + {26173,26101,26172 ,14747,14656,14746 ,0,0,0}, {26094,26099,26098 ,14642,14651,14647 ,0,0,0}, + {26174,26102,26173 ,14748,14657,14747 ,0,0,0}, {26171,26100,26099 ,14745,14653,14651 ,0,0,0}, + {26174,26175,26103 ,14748,14749,14659 ,0,0,0}, {26101,26100,26172 ,14656,14653,14746 ,0,0,0}, + {26176,26107,26175 ,14750,14664,14749 ,0,0,0}, {26102,26101,26173 ,14657,14656,14747 ,0,0,0}, + {26177,26108,26176 ,14751,14665,14750 ,0,0,0}, {26103,26102,26174 ,14659,14657,14748 ,0,0,0}, + {26178,26109,26177 ,14752,14670,14751 ,0,0,0}, {26107,26103,26175 ,14664,14659,14749 ,0,0,0}, + {26179,26110,26178 ,14753,14671,14752 ,0,0,0}, {26176,26108,26107 ,14750,14665,14664 ,0,0,0}, + {26180,26111,26179 ,14754,14673,14753 ,0,0,0}, {26177,26109,26108 ,14751,14670,14665 ,0,0,0}, + {26181,26112,26180 ,14755,14676,14754 ,0,0,0}, {26178,26110,26109 ,14752,14671,14670 ,0,0,0}, + {26182,26113,26181 ,14756,14677,14755 ,0,0,0}, {26179,26111,26110 ,14753,14673,14671 ,0,0,0}, + {26182,26117,26114 ,14756,14682,14679 ,0,0,0}, {26112,26111,26180 ,14676,14673,14754 ,0,0,0}, + {26118,26115,26183 ,14684,14680,14757 ,0,0,0}, {26113,26112,26181 ,14677,14676,14755 ,0,0,0}, + {26139,26121,26127 ,14707,14688,14695 ,0,0,0}, {26114,26113,26182 ,14679,14677,14756 ,0,0,0}, + {26143,26183,26120 ,14712,14757,14687 ,0,0,0}, {26114,26117,26116 ,14679,14682,14681 ,0,0,0}, + {26183,26184,26120 ,14757,14758,14687 ,0,0,0}, {26142,26145,26144 ,14710,14716,14715 ,0,0,0}, + {26143,26119,26034 ,14712,14686,14713 ,0,0,0}, {26183,26143,26118 ,14757,14712,14684 ,0,0,0}, + {26142,26139,26135 ,14710,14707,14703 ,0,0,0}, {26119,26143,26120 ,14686,14712,14687 ,0,0,0}, + {26146,26141,26185 ,14718,14709,14759 ,0,0,0}, {26146,26147,25665 ,14718,14721,14719 ,0,0,0}, + {26036,26145,26037 ,14717,14716,14720 ,0,0,0}, {26146,26145,26141 ,14718,14716,14709 ,0,0,0}, + {26186,26147,26146 ,14760,14721,14718 ,0,0,0}, {26084,26079,26076 ,14624,14619,14616 ,0,0,0}, + {26080,26078,26077 ,14620,14618,14617 ,0,0,0}, {26068,25693,25689 ,14606,14600,14761 ,0,0,0}, + {26076,26149,26060 ,14616,14723,14597 ,0,0,0}, {26187,26149,26078 ,14762,14723,14618 ,0,0,0}, + {26072,26074,26150 ,14611,14613,14724 ,0,0,0}, {26071,26061,26187 ,14610,14598,14762 ,0,0,0}, + {26074,26188,26151 ,14613,14763,14725 ,0,0,0}, {26071,26062,26061 ,14610,14599,14598 ,0,0,0}, + {26188,26189,26152 ,14763,14764,14726 ,0,0,0}, {26072,26150,26062 ,14611,14724,14599 ,0,0,0}, + {26189,26190,26153 ,14764,14765,14727 ,0,0,0}, {26074,26151,26150 ,14613,14725,14724 ,0,0,0}, + {26190,26191,26154 ,14765,14766,14728 ,0,0,0}, {26188,26152,26151 ,14763,14726,14725 ,0,0,0}, + {26191,26192,26155 ,14766,14767,14729 ,0,0,0}, {26189,26153,26152 ,14764,14727,14726 ,0,0,0}, + {26192,26193,26156 ,14767,14768,14730 ,0,0,0}, {26190,26154,26153 ,14765,14728,14727 ,0,0,0}, + {26193,26194,26157 ,14768,14769,14731 ,0,0,0}, {26191,26155,26154 ,14766,14729,14728 ,0,0,0}, + {26194,26052,26158 ,14769,14581,14732 ,0,0,0}, {26156,26155,26192 ,14730,14729,14767 ,0,0,0}, + {26195,26196,26197 ,14770,14771,14772 ,0,0,0}, {26157,26156,26193 ,14731,14730,14768 ,0,0,0}, + {26050,26196,26159 ,14579,14771,14733 ,0,0,0}, {26158,26157,26194 ,14732,14731,14769 ,0,0,0}, + {26196,26195,26160 ,14771,14770,14734 ,0,0,0}, {26051,26158,26052 ,14580,14732,14581 ,0,0,0}, + {26195,26198,26161 ,14770,14773,14735 ,0,0,0}, {26050,26159,26051 ,14579,14733,14580 ,0,0,0}, + {26198,26199,26162 ,14773,14774,14736 ,0,0,0}, {26196,26160,26159 ,14771,14734,14733 ,0,0,0}, + {26199,26200,26163 ,14774,14775,14737 ,0,0,0}, {26195,26161,26160 ,14770,14735,14734 ,0,0,0}, + {26200,26201,26164 ,14775,14776,14738 ,0,0,0}, {26162,26161,26198 ,14736,14735,14773 ,0,0,0}, + {26042,26165,26201 ,14564,14739,14776 ,0,0,0}, {26163,26162,26199 ,14737,14736,14774 ,0,0,0}, + {26042,26041,26166 ,14564,14563,14740 ,0,0,0}, {26164,26163,26200 ,14738,14737,14775 ,0,0,0}, + {26041,26202,26167 ,14563,14777,14741 ,0,0,0}, {26201,26165,26164 ,14776,14739,14738 ,0,0,0}, + {26202,26203,26168 ,14777,14778,14742 ,0,0,0}, {26042,26166,26165 ,14564,14740,14739 ,0,0,0}, + {26203,26204,26169 ,14778,14779,14743 ,0,0,0}, {26041,26167,26166 ,14563,14741,14740 ,0,0,0}, + {26204,26095,26170 ,14779,14643,14744 ,0,0,0}, {26168,26167,26202 ,14742,14741,14777 ,0,0,0}, + {26205,26206,26207 ,14780,14781,14782 ,0,0,0}, {26169,26168,26203 ,14743,14742,14778 ,0,0,0}, + {26096,26208,26171 ,14644,14783,14745 ,0,0,0}, {26170,26169,26204 ,14744,14743,14779 ,0,0,0}, + {26208,26209,26172 ,14783,14784,14746 ,0,0,0}, {26094,26170,26095 ,14642,14744,14643 ,0,0,0}, + {26209,26210,26173 ,14784,14785,14747 ,0,0,0}, {26096,26171,26094 ,14644,14745,14642 ,0,0,0}, + {26210,26211,26174 ,14785,14786,14748 ,0,0,0}, {26208,26172,26171 ,14783,14746,14745 ,0,0,0}, + {26211,26212,26175 ,14786,14787,14749 ,0,0,0}, {26209,26173,26172 ,14784,14747,14746 ,0,0,0}, + {26212,26213,26176 ,14787,14788,14750 ,0,0,0}, {26174,26173,26210 ,14748,14747,14785 ,0,0,0}, + {26213,26104,26177 ,14788,14660,14751 ,0,0,0}, {26175,26174,26211 ,14749,14748,14786 ,0,0,0}, + {26104,26106,26178 ,14660,14662,14752 ,0,0,0}, {26176,26175,26212 ,14750,14749,14787 ,0,0,0}, + {26106,26214,26179 ,14662,14789,14753 ,0,0,0}, {26213,26177,26176 ,14788,14751,14750 ,0,0,0}, + {26214,26215,26180 ,14789,14790,14754 ,0,0,0}, {26104,26178,26177 ,14660,14752,14751 ,0,0,0}, + {26215,26216,26181 ,14790,14791,14755 ,0,0,0}, {26106,26179,26178 ,14662,14753,14752 ,0,0,0}, + {26216,26217,26182 ,14791,14792,14756 ,0,0,0}, {26214,26180,26179 ,14789,14754,14753 ,0,0,0}, + {26217,26218,26117 ,14792,14793,14682 ,0,0,0}, {26215,26181,26180 ,14790,14755,14754 ,0,0,0}, + {26218,26219,26115 ,14793,14794,14680 ,0,0,0}, {26216,26182,26181 ,14791,14756,14755 ,0,0,0}, + {26219,26184,26183 ,14794,14758,14757 ,0,0,0}, {26217,26117,26182 ,14792,14682,14756 ,0,0,0}, + {26184,26127,26120 ,14758,14695,14687 ,0,0,0}, {26115,26117,26218 ,14680,14682,14793 ,0,0,0}, + {26220,26221,26222 ,14795,14796,14797 ,0,0,0}, {26219,26183,26115 ,14794,14757,14680 ,0,0,0}, + {26140,26122,26135 ,14708,14690,14703 ,0,0,0}, {26134,26223,26185 ,14702,14798,14759 ,0,0,0}, + {26119,26121,26144 ,14686,14688,14715 ,0,0,0}, {26127,26121,26120 ,14695,14688,14687 ,0,0,0}, + {26224,26185,26223 ,14799,14759,14798 ,0,0,0}, {26185,26186,26146 ,14759,14760,14718 ,0,0,0}, + {26145,26142,26141 ,14716,14710,14709 ,0,0,0}, {26141,26134,26185 ,14709,14702,14759 ,0,0,0}, + {26224,26186,26185 ,14799,14760,14759 ,0,0,0}, {26078,26149,26079 ,14618,14723,14619 ,0,0,0}, + {26225,26081,26082 ,14800,14621,14622 ,0,0,0}, {26225,26086,26081 ,14800,14627,14621 ,0,0,0}, + {26149,26187,26061 ,14723,14762,14598 ,0,0,0}, {26226,26187,26081 ,14801,14762,14621 ,0,0,0}, + {26074,26227,26188 ,14613,14802,14763 ,0,0,0}, {26075,26071,26226 ,14614,14610,14801 ,0,0,0}, + {26188,26228,26189 ,14763,14803,14764 ,0,0,0}, {26075,26073,26072 ,14614,14612,14611 ,0,0,0}, + {26229,26230,26231 ,14804,14805,14806 ,0,0,0}, {26073,26227,26074 ,14612,14802,14613 ,0,0,0}, + {26190,26189,26232 ,14765,14764,14807 ,0,0,0}, {26227,26228,26188 ,14802,14803,14763 ,0,0,0}, + {26191,26190,26231 ,14766,14765,14806 ,0,0,0}, {26228,26232,26189 ,14803,14807,14764 ,0,0,0}, + {26192,26191,26230 ,14767,14766,14805 ,0,0,0}, {26232,26231,26190 ,14807,14806,14765 ,0,0,0}, + {26193,26192,26233 ,14768,14767,14808 ,0,0,0}, {26231,26230,26191 ,14806,14805,14766 ,0,0,0}, + {26194,26193,26234 ,14769,14768,14809 ,0,0,0}, {26230,26233,26192 ,14805,14808,14767 ,0,0,0}, + {26052,26194,26235 ,14581,14769,14810 ,0,0,0}, {26233,26234,26193 ,14808,14809,14768 ,0,0,0}, + {26050,26052,26236 ,14579,14581,14811 ,0,0,0}, {26234,26235,26194 ,14809,14810,14769 ,0,0,0}, + {26196,26050,26237 ,14771,14579,14812 ,0,0,0}, {26236,26052,26235 ,14811,14581,14810 ,0,0,0}, + {26238,26239,26240 ,14813,14814,14815 ,0,0,0}, {26237,26050,26236 ,14812,14579,14811 ,0,0,0}, + {26198,26195,26241 ,14773,14770,14816 ,0,0,0}, {26237,26197,26196 ,14812,14772,14771 ,0,0,0}, + {26199,26198,26240 ,14774,14773,14815 ,0,0,0}, {26197,26241,26195 ,14772,14816,14770 ,0,0,0}, + {26200,26199,26239 ,14775,14774,14814 ,0,0,0}, {26241,26240,26198 ,14816,14815,14773 ,0,0,0}, + {26201,26200,26242 ,14776,14775,14817 ,0,0,0}, {26240,26239,26199 ,14815,14814,14774 ,0,0,0}, + {26042,26201,26243 ,14564,14776,14818 ,0,0,0}, {26242,26200,26239 ,14817,14775,14814 ,0,0,0}, + {26244,26245,26246 ,14819,14820,14821 ,0,0,0}, {26243,26201,26242 ,14818,14776,14817 ,0,0,0}, + {26202,26041,26247 ,14777,14563,14822 ,0,0,0}, {26243,26040,26042 ,14818,14562,14564 ,0,0,0}, + {26203,26202,26246 ,14778,14777,14821 ,0,0,0}, {26040,26247,26041 ,14562,14822,14563 ,0,0,0}, + {26204,26203,26245 ,14779,14778,14820 ,0,0,0}, {26247,26246,26202 ,14822,14821,14777 ,0,0,0}, + {26095,26204,26248 ,14643,14779,14823 ,0,0,0}, {26246,26245,26203 ,14821,14820,14778 ,0,0,0}, + {26096,26095,26249 ,14644,14643,14824 ,0,0,0}, {26245,26248,26204 ,14820,14823,14779 ,0,0,0}, + {26208,26096,26250 ,14783,14644,14825 ,0,0,0}, {26249,26095,26248 ,14824,14643,14823 ,0,0,0}, + {26209,26208,26251 ,14784,14783,14826 ,0,0,0}, {26250,26096,26249 ,14825,14644,14824 ,0,0,0}, + {26210,26209,26205 ,14785,14784,14780 ,0,0,0}, {26250,26251,26208 ,14825,14826,14783 ,0,0,0}, + {26211,26210,26207 ,14786,14785,14782 ,0,0,0}, {26251,26205,26209 ,14826,14780,14784 ,0,0,0}, + {26212,26211,26252 ,14787,14786,14827 ,0,0,0}, {26205,26207,26210 ,14780,14782,14785 ,0,0,0}, + {26213,26212,26253 ,14788,14787,14828 ,0,0,0}, {26207,26252,26211 ,14782,14827,14786 ,0,0,0}, + {26104,26213,26254 ,14660,14788,14829 ,0,0,0}, {26253,26212,26252 ,14828,14787,14827 ,0,0,0}, + {26255,26256,26257 ,14830,14831,14832 ,0,0,0}, {26254,26213,26253 ,14829,14788,14828 ,0,0,0}, + {26214,26106,26258 ,14789,14662,14833 ,0,0,0}, {26254,26105,26104 ,14829,14661,14660 ,0,0,0}, + {26215,26214,26257 ,14790,14789,14832 ,0,0,0}, {26105,26258,26106 ,14661,14833,14662 ,0,0,0}, + {26216,26215,26256 ,14791,14790,14831 ,0,0,0}, {26258,26257,26214 ,14833,14832,14789 ,0,0,0}, + {26217,26216,26259 ,14792,14791,14834 ,0,0,0}, {26257,26256,26215 ,14832,14831,14790 ,0,0,0}, + {26218,26217,26260 ,14793,14792,14835 ,0,0,0}, {26256,26259,26216 ,14831,14834,14791 ,0,0,0}, + {26219,26218,26261 ,14794,14793,14836 ,0,0,0}, {26259,26260,26217 ,14834,14835,14792 ,0,0,0}, + {26184,26219,26262 ,14758,14794,14837 ,0,0,0}, {26260,26261,26218 ,14835,14836,14793 ,0,0,0}, + {26127,26184,26125 ,14695,14758,14693 ,0,0,0}, {26261,26262,26219 ,14836,14837,14794 ,0,0,0}, + {26139,26127,26126 ,14707,14695,14694 ,0,0,0}, {26262,26125,26184 ,14837,14693,14758 ,0,0,0}, + {26263,26133,26222 ,14838,14701,14797 ,0,0,0}, {26264,26123,26122 ,14839,14691,14690 ,0,0,0}, + {26121,26139,26142 ,14688,14707,14710 ,0,0,0}, {26126,26140,26139 ,14694,14708,14707 ,0,0,0}, + {26265,26223,26221 ,14840,14798,14796 ,0,0,0}, {26265,26266,26223 ,14840,14841,14798 ,0,0,0}, + {26141,26135,26134 ,14709,14703,14702 ,0,0,0}, {26134,26124,26223 ,14702,14692,14798 ,0,0,0}, + {26224,26223,26266 ,14799,14798,14841 ,0,0,0}, {26078,26081,26187 ,14618,14621,14762 ,0,0,0}, + {26148,26086,26225 ,14722,14627,14800 ,0,0,0}, {26075,26267,26073 ,14614,14842,14612 ,0,0,0}, + {26187,26226,26071 ,14762,14801,14610 ,0,0,0}, {26086,26268,26226 ,14627,14843,14801 ,0,0,0}, + {26227,26073,26269 ,14802,14612,14844 ,0,0,0}, {26268,26267,26075 ,14843,14842,14614 ,0,0,0}, + {26228,26227,26270 ,14803,14802,14845 ,0,0,0}, {26073,26267,26269 ,14612,14842,14844 ,0,0,0}, + {26232,26228,26271 ,14807,14803,14846 ,0,0,0}, {26227,26269,26270 ,14802,14844,14845 ,0,0,0}, + {26231,26232,26272 ,14806,14807,14847 ,0,0,0}, {26270,26271,26228 ,14845,14846,14803 ,0,0,0}, + {26273,26233,26230 ,14848,14808,14805 ,0,0,0}, {26271,26272,26232 ,14846,14847,14807 ,0,0,0}, + {26274,26275,26276 ,14849,14850,14851 ,0,0,0}, {26272,26229,26231 ,14847,14804,14806 ,0,0,0}, + {26233,26277,26234 ,14808,14852,14809 ,0,0,0}, {26229,26273,26230 ,14804,14848,14805 ,0,0,0}, + {26234,26275,26235 ,14809,14850,14810 ,0,0,0}, {26273,26277,26233 ,14848,14852,14808 ,0,0,0}, + {26235,26274,26236 ,14810,14849,14811 ,0,0,0}, {26277,26275,26234 ,14852,14850,14809 ,0,0,0}, + {26236,26278,26237 ,14811,14853,14812 ,0,0,0}, {26275,26274,26235 ,14850,14849,14810 ,0,0,0}, + {26237,26279,26197 ,14812,14854,14772 ,0,0,0}, {26274,26278,26236 ,14849,14853,14811 ,0,0,0}, + {26241,26197,26280 ,14816,14772,14855 ,0,0,0}, {26278,26279,26237 ,14853,14854,14812 ,0,0,0}, + {26240,26241,26281 ,14815,14816,14856 ,0,0,0}, {26279,26280,26197 ,14854,14855,14772 ,0,0,0}, + {26282,26283,26284 ,14857,14858,14859 ,0,0,0}, {26280,26281,26241 ,14855,14856,14816 ,0,0,0}, + {26239,26285,26242 ,14814,14860,14817 ,0,0,0}, {26281,26238,26240 ,14856,14813,14815 ,0,0,0}, + {26242,26286,26243 ,14817,14861,14818 ,0,0,0}, {26238,26285,26239 ,14813,14860,14814 ,0,0,0}, + {26243,26287,26040 ,14818,14862,14562 ,0,0,0}, {26285,26286,26242 ,14860,14861,14817 ,0,0,0}, + {26247,26040,26288 ,14822,14562,14863 ,0,0,0}, {26286,26287,26243 ,14861,14862,14818 ,0,0,0}, + {26246,26247,26289 ,14821,14822,14864 ,0,0,0}, {26287,26288,26040 ,14862,14863,14562 ,0,0,0}, + {26290,26291,26292 ,14865,14866,14867 ,0,0,0}, {26288,26289,26247 ,14863,14864,14822 ,0,0,0}, + {26245,26293,26248 ,14820,14868,14823 ,0,0,0}, {26289,26244,26246 ,14864,14819,14821 ,0,0,0}, + {26248,26294,26249 ,14823,14869,14824 ,0,0,0}, {26244,26293,26245 ,14819,14868,14820 ,0,0,0}, + {26249,26295,26250 ,14824,14870,14825 ,0,0,0}, {26293,26294,26248 ,14868,14869,14823 ,0,0,0}, + {26250,26296,26251 ,14825,14871,14826 ,0,0,0}, {26294,26295,26249 ,14869,14870,14824 ,0,0,0}, + {26205,26251,26297 ,14780,14826,14872 ,0,0,0}, {26295,26296,26250 ,14870,14871,14825 ,0,0,0}, + {26298,26299,26300 ,14873,14874,14875 ,0,0,0}, {26296,26297,26251 ,14871,14872,14826 ,0,0,0}, + {26207,26301,26252 ,14782,14876,14827 ,0,0,0}, {26297,26206,26205 ,14872,14781,14780 ,0,0,0}, + {26252,26299,26253 ,14827,14874,14828 ,0,0,0}, {26206,26301,26207 ,14781,14876,14782 ,0,0,0}, + {26253,26298,26254 ,14828,14873,14829 ,0,0,0}, {26301,26299,26252 ,14876,14874,14827 ,0,0,0}, + {26254,26302,26105 ,14829,14877,14661 ,0,0,0}, {26299,26298,26253 ,14874,14873,14828 ,0,0,0}, + {26258,26105,26303 ,14833,14661,14878 ,0,0,0}, {26298,26302,26254 ,14873,14877,14829 ,0,0,0}, + {26257,26258,26304 ,14832,14833,14879 ,0,0,0}, {26302,26303,26105 ,14877,14878,14661 ,0,0,0}, + {26305,26259,26256 ,14880,14834,14831 ,0,0,0}, {26303,26304,26258 ,14878,14879,14833 ,0,0,0}, + {26306,26307,26308 ,14881,14882,14883 ,0,0,0}, {26304,26255,26257 ,14879,14830,14832 ,0,0,0}, + {26259,26309,26260 ,14834,14884,14835 ,0,0,0}, {26255,26305,26256 ,14830,14880,14831 ,0,0,0}, + {26260,26307,26261 ,14835,14882,14836 ,0,0,0}, {26305,26309,26259 ,14880,14884,14834 ,0,0,0}, + {26261,26306,26262 ,14836,14881,14837 ,0,0,0}, {26309,26307,26260 ,14884,14882,14835 ,0,0,0}, + {26262,26310,26125 ,14837,14885,14693 ,0,0,0}, {26307,26306,26261 ,14882,14881,14836 ,0,0,0}, + {26125,26311,26126 ,14693,14886,14694 ,0,0,0}, {26306,26310,26262 ,14881,14885,14837 ,0,0,0}, + {26126,26312,26140 ,14694,14887,14708 ,0,0,0}, {26310,26311,26125 ,14885,14886,14693 ,0,0,0}, + {26140,26264,26122 ,14708,14839,14690 ,0,0,0}, {26312,26126,26311 ,14887,14694,14886 ,0,0,0}, + {26129,26123,26313 ,14697,14691,14888 ,0,0,0}, {26140,26312,26264 ,14708,14887,14839 ,0,0,0}, + {26221,26314,26222 ,14796,14889,14797 ,0,0,0}, {26223,26124,26221 ,14798,14692,14796 ,0,0,0}, + {26134,26122,26124 ,14702,14690,14692 ,0,0,0}, {26124,26314,26221 ,14692,14889,14796 ,0,0,0}, + {26265,26221,26220 ,14840,14796,14795 ,0,0,0}, {26081,26086,26226 ,14621,14627,14801 ,0,0,0}, + {26066,26065,26087 ,14604,14603,14628 ,0,0,0}, {26267,26315,26269 ,14842,14890,14844 ,0,0,0}, + {26226,26268,26075 ,14801,14843,14614 ,0,0,0}, {26065,26316,26268 ,14603,14891,14843 ,0,0,0}, + {26270,26269,26317 ,14845,14844,14892 ,0,0,0}, {26267,26316,26315 ,14842,14891,14890 ,0,0,0}, + {26271,26270,26318 ,14846,14845,14893 ,0,0,0}, {26269,26315,26317 ,14844,14890,14892 ,0,0,0}, + {26272,26271,26319 ,14847,14846,14894 ,0,0,0}, {26270,26317,26318 ,14845,14892,14893 ,0,0,0}, + {26229,26272,26320 ,14804,14847,14895 ,0,0,0}, {26271,26318,26319 ,14846,14893,14894 ,0,0,0}, + {26273,26229,26321 ,14848,14804,14896 ,0,0,0}, {26272,26319,26320 ,14847,14894,14895 ,0,0,0}, + {26277,26273,26322 ,14852,14848,14897 ,0,0,0}, {26229,26320,26321 ,14804,14895,14896 ,0,0,0}, + {26275,26277,26323 ,14850,14852,14898 ,0,0,0}, {26321,26322,26273 ,14896,14897,14848 ,0,0,0}, + {26324,26325,26326 ,14899,14900,14901 ,0,0,0}, {26322,26323,26277 ,14897,14898,14852 ,0,0,0}, + {26274,26327,26278 ,14849,14902,14853 ,0,0,0}, {26323,26276,26275 ,14898,14851,14850 ,0,0,0}, + {26278,26326,26279 ,14853,14901,14854 ,0,0,0}, {26276,26327,26274 ,14851,14902,14849 ,0,0,0}, + {26279,26328,26280 ,14854,14903,14855 ,0,0,0}, {26327,26326,26278 ,14902,14901,14853 ,0,0,0}, + {26281,26280,26329 ,14856,14855,14904 ,0,0,0}, {26326,26328,26279 ,14901,14903,14854 ,0,0,0}, + {26238,26281,26330 ,14813,14856,14905 ,0,0,0}, {26280,26328,26329 ,14855,14903,14904 ,0,0,0}, + {26285,26238,26331 ,14860,14813,14906 ,0,0,0}, {26281,26329,26330 ,14856,14904,14905 ,0,0,0}, + {26286,26285,26332 ,14861,14860,14907 ,0,0,0}, {26330,26331,26238 ,14905,14906,14813 ,0,0,0}, + {26286,26333,26287 ,14861,14908,14862 ,0,0,0}, {26331,26332,26285 ,14906,14907,14860 ,0,0,0}, + {26287,26283,26288 ,14862,14858,14863 ,0,0,0}, {26332,26333,26286 ,14907,14908,14861 ,0,0,0}, + {26289,26288,26334 ,14864,14863,14909 ,0,0,0}, {26333,26283,26287 ,14908,14858,14862 ,0,0,0}, + {26244,26289,26335 ,14819,14864,14910 ,0,0,0}, {26288,26283,26334 ,14863,14858,14909 ,0,0,0}, + {26293,26244,26336 ,14868,14819,14911 ,0,0,0}, {26289,26334,26335 ,14864,14909,14910 ,0,0,0}, + {26294,26293,26337 ,14869,14868,14912 ,0,0,0}, {26335,26336,26244 ,14910,14911,14819 ,0,0,0}, + {26294,26338,26295 ,14869,14913,14870 ,0,0,0}, {26336,26337,26293 ,14911,14912,14868 ,0,0,0}, + {26295,26291,26296 ,14870,14866,14871 ,0,0,0}, {26337,26338,26294 ,14912,14913,14869 ,0,0,0}, + {26297,26296,26339 ,14872,14871,14914 ,0,0,0}, {26338,26291,26295 ,14913,14866,14870 ,0,0,0}, + {26206,26297,26340 ,14781,14872,14915 ,0,0,0}, {26296,26291,26339 ,14871,14866,14914 ,0,0,0}, + {26301,26206,26341 ,14876,14781,14916 ,0,0,0}, {26297,26339,26340 ,14872,14914,14915 ,0,0,0}, + {26299,26301,26342 ,14874,14876,14917 ,0,0,0}, {26340,26341,26206 ,14915,14916,14781 ,0,0,0}, + {26343,26344,26345 ,14918,14919,14920 ,0,0,0}, {26341,26342,26301 ,14916,14917,14876 ,0,0,0}, + {26298,26346,26302 ,14873,14921,14877 ,0,0,0}, {26342,26300,26299 ,14917,14875,14874 ,0,0,0}, + {26302,26345,26303 ,14877,14920,14878 ,0,0,0}, {26300,26346,26298 ,14875,14921,14873 ,0,0,0}, + {26304,26303,26347 ,14879,14878,14922 ,0,0,0}, {26346,26345,26302 ,14921,14920,14877 ,0,0,0}, + {26255,26304,26348 ,14830,14879,14923 ,0,0,0}, {26303,26345,26347 ,14878,14920,14922 ,0,0,0}, + {26305,26255,26349 ,14880,14830,14924 ,0,0,0}, {26304,26347,26348 ,14879,14922,14923 ,0,0,0}, + {26309,26305,26350 ,14884,14880,14925 ,0,0,0}, {26255,26348,26349 ,14830,14923,14924 ,0,0,0}, + {26307,26309,26351 ,14882,14884,14926 ,0,0,0}, {26349,26350,26305 ,14924,14925,14880 ,0,0,0}, + {26352,26310,26306 ,14927,14885,14881 ,0,0,0}, {26350,26351,26309 ,14925,14926,14884 ,0,0,0}, + {26353,26354,26355 ,14928,14929,14930 ,0,0,0}, {26351,26308,26307 ,14926,14883,14882 ,0,0,0}, + {26310,26356,26311 ,14885,14931,14886 ,0,0,0}, {26308,26352,26306 ,14883,14927,14881 ,0,0,0}, + {26311,26355,26312 ,14886,14930,14887 ,0,0,0}, {26352,26356,26310 ,14927,14931,14885 ,0,0,0}, + {26312,26357,26264 ,14887,14932,14839 ,0,0,0}, {26356,26355,26311 ,14931,14930,14886 ,0,0,0}, + {26264,26313,26123 ,14839,14888,14691 ,0,0,0}, {26355,26357,26312 ,14930,14932,14887 ,0,0,0}, + {26123,26129,26314 ,14691,14697,14889 ,0,0,0}, {26264,26357,26313 ,14839,14932,14888 ,0,0,0}, + {26358,26222,26133 ,14933,14797,14701 ,0,0,0}, {26359,26220,26222 ,14934,14795,14797 ,0,0,0}, + {26124,26123,26314 ,14692,14691,14889 ,0,0,0}, {26314,26263,26222 ,14889,14838,14797 ,0,0,0}, + {26358,26359,26222 ,14933,14934,14797 ,0,0,0}, {26086,26065,26268 ,14627,14603,14843 ,0,0,0}, + {26360,26064,26066 ,14935,14602,14604 ,0,0,0}, {26317,26315,26070 ,14892,14890,14608 ,0,0,0}, + {26268,26316,26267 ,14843,14891,14842 ,0,0,0}, {26064,26361,26316 ,14602,14936,14891 ,0,0,0}, + {26318,26317,26362 ,14893,14892,14937 ,0,0,0}, {26315,26361,26070 ,14890,14936,14608 ,0,0,0}, + {26363,26362,26364 ,14938,14937,14939 ,0,0,0}, {26317,26070,26362 ,14892,14608,14937 ,0,0,0}, + {26363,26365,26319 ,14938,14940,14894 ,0,0,0}, {26319,26318,26363 ,14894,14893,14938 ,0,0,0}, + {26365,26366,26320 ,14940,14941,14895 ,0,0,0}, {26320,26319,26365 ,14895,14894,14940 ,0,0,0}, + {26366,26367,26321 ,14941,14942,14896 ,0,0,0}, {26321,26320,26366 ,14896,14895,14941 ,0,0,0}, + {26367,26368,26322 ,14942,14943,14897 ,0,0,0}, {26322,26321,26367 ,14897,14896,14942 ,0,0,0}, + {26368,26369,26323 ,14943,14944,14898 ,0,0,0}, {26323,26322,26368 ,14898,14897,14943 ,0,0,0}, + {26369,26370,26276 ,14944,14945,14851 ,0,0,0}, {26276,26323,26369 ,14851,14898,14944 ,0,0,0}, + {26370,26324,26327 ,14945,14899,14902 ,0,0,0}, {26276,26370,26327 ,14851,14945,14902 ,0,0,0}, + {25680,26371,26372 ,14946,14947,14948 ,0,0,0}, {26327,26324,26326 ,14902,14899,14901 ,0,0,0}, + {26328,26373,26329 ,14903,14949,14904 ,0,0,0}, {26326,26325,26328 ,14901,14900,14903 ,0,0,0}, + {26374,26373,26372 ,14950,14949,14948 ,0,0,0}, {26325,26373,26328 ,14900,14949,14903 ,0,0,0}, + {26374,26375,26330 ,14950,14951,14905 ,0,0,0}, {26330,26329,26374 ,14905,14904,14950 ,0,0,0}, + {26375,26376,26331 ,14951,14952,14906 ,0,0,0}, {26331,26330,26375 ,14906,14905,14951 ,0,0,0}, + {26376,26377,26332 ,14952,14953,14907 ,0,0,0}, {26332,26331,26376 ,14907,14906,14952 ,0,0,0}, + {26377,26284,26333 ,14953,14859,14908 ,0,0,0}, {26332,26377,26333 ,14907,14953,14908 ,0,0,0}, + {26378,26379,26380 ,14954,14955,14956 ,0,0,0}, {26333,26284,26283 ,14908,14859,14858 ,0,0,0}, + {26282,26379,26334 ,14857,14955,14909 ,0,0,0}, {26283,26282,26334 ,14858,14857,14909 ,0,0,0}, + {26379,26381,26335 ,14955,14957,14910 ,0,0,0}, {26335,26334,26379 ,14910,14909,14955 ,0,0,0}, + {26381,26382,26336 ,14957,14958,14911 ,0,0,0}, {26336,26335,26381 ,14911,14910,14957 ,0,0,0}, + {26382,26383,26337 ,14958,14959,14912 ,0,0,0}, {26337,26336,26382 ,14912,14911,14958 ,0,0,0}, + {26383,26292,26338 ,14959,14867,14913 ,0,0,0}, {26337,26383,26338 ,14912,14959,14913 ,0,0,0}, + {26384,25671,26385 ,14960,14961,14962 ,0,0,0}, {26338,26292,26291 ,14913,14867,14866 ,0,0,0}, + {26340,26339,26386 ,14915,14914,14963 ,0,0,0}, {26291,26290,26339 ,14866,14865,14914 ,0,0,0}, + {26387,26386,26384 ,14964,14963,14960 ,0,0,0}, {26339,26290,26386 ,14914,14865,14963 ,0,0,0}, + {26387,26388,26341 ,14964,14965,14916 ,0,0,0}, {26341,26340,26387 ,14916,14915,14964 ,0,0,0}, + {26388,26389,26342 ,14965,14966,14917 ,0,0,0}, {26342,26341,26388 ,14917,14916,14965 ,0,0,0}, + {26389,26390,26300 ,14966,14967,14875 ,0,0,0}, {26300,26342,26389 ,14875,14917,14966 ,0,0,0}, + {26390,26343,26346 ,14967,14918,14921 ,0,0,0}, {26300,26390,26346 ,14875,14967,14921 ,0,0,0}, + {26391,26392,26393 ,14968,14969,14970 ,0,0,0}, {26346,26343,26345 ,14921,14918,14920 ,0,0,0}, + {26344,26392,26347 ,14919,14969,14922 ,0,0,0}, {26345,26344,26347 ,14920,14919,14922 ,0,0,0}, + {26392,26394,26348 ,14969,14971,14923 ,0,0,0}, {26348,26347,26392 ,14923,14922,14969 ,0,0,0}, + {26394,26395,26349 ,14971,14972,14924 ,0,0,0}, {26349,26348,26394 ,14924,14923,14971 ,0,0,0}, + {26395,26396,26350 ,14972,14973,14925 ,0,0,0}, {26350,26349,26395 ,14925,14924,14972 ,0,0,0}, + {26396,26397,26351 ,14973,14974,14926 ,0,0,0}, {26351,26350,26396 ,14926,14925,14973 ,0,0,0}, + {26397,26398,26308 ,14974,14975,14883 ,0,0,0}, {26308,26351,26397 ,14883,14926,14974 ,0,0,0}, + {26398,26399,26352 ,14975,14976,14927 ,0,0,0}, {26352,26308,26398 ,14927,14883,14975 ,0,0,0}, + {26399,26353,26356 ,14976,14928,14931 ,0,0,0}, {26352,26399,26356 ,14927,14976,14931 ,0,0,0}, + {26357,26354,26400 ,14932,14929,14977 ,0,0,0}, {26356,26353,26355 ,14931,14928,14930 ,0,0,0}, + {26130,26129,26313 ,14698,14697,14888 ,0,0,0}, {26355,26354,26357 ,14930,14929,14932 ,0,0,0}, + {26128,26263,26129 ,14696,14838,14697 ,0,0,0}, {26357,26400,26313 ,14932,14977,14888 ,0,0,0}, + {26401,26137,26131 ,14978,14705,14699 ,0,0,0}, {26400,26130,26313 ,14977,14698,14888 ,0,0,0}, + {26128,26402,26403 ,14696,14979,14980 ,0,0,0}, {26404,26358,26133 ,14981,14933,14701 ,0,0,0}, + {26314,26129,26263 ,14889,14697,14838 ,0,0,0}, {26133,26263,26403 ,14701,14838,14980 ,0,0,0}, + {26132,26404,26133 ,14700,14981,14701 ,0,0,0}, {26065,26064,26316 ,14603,14602,14891 ,0,0,0}, + {26360,26067,26063 ,14935,14605,14601 ,0,0,0}, {26361,26063,26068 ,14936,14601,14606 ,0,0,0}, + {26316,26361,26315 ,14891,14936,14890 ,0,0,0}, {26070,26361,26068 ,14608,14936,14606 ,0,0,0}, + {26069,26364,26362 ,14607,14939,14937 ,0,0,0}, {26362,26070,26069 ,14937,14608,14607 ,0,0,0}, + {26364,26405,26363 ,14939,14982,14938 ,0,0,0}, {26406,26365,26405 ,14983,14940,14982 ,0,0,0}, + {26318,26362,26363 ,14893,14937,14938 ,0,0,0}, {26365,26363,26405 ,14940,14938,14982 ,0,0,0}, + {26407,26366,26406 ,14984,14941,14983 ,0,0,0}, {26366,26365,26406 ,14941,14940,14983 ,0,0,0}, + {26408,26367,26407 ,14985,14942,14984 ,0,0,0}, {26367,26366,26407 ,14942,14941,14984 ,0,0,0}, + {26409,26368,26408 ,14986,14943,14985 ,0,0,0}, {26368,26367,26408 ,14943,14942,14985 ,0,0,0}, + {26410,26369,26409 ,14987,14944,14986 ,0,0,0}, {26369,26368,26409 ,14944,14943,14986 ,0,0,0}, + {26411,26370,26410 ,14988,14945,14987 ,0,0,0}, {26370,26369,26410 ,14945,14944,14987 ,0,0,0}, + {26412,26324,26411 ,14989,14899,14988 ,0,0,0}, {26324,26370,26411 ,14899,14945,14988 ,0,0,0}, + {26413,26325,26412 ,14990,14900,14989 ,0,0,0}, {26325,26324,26412 ,14900,14899,14989 ,0,0,0}, + {26372,26373,26413 ,14948,14949,14990 ,0,0,0}, {26325,26413,26373 ,14900,14990,14949 ,0,0,0}, + {26372,26371,26374 ,14948,14947,14950 ,0,0,0}, {26414,26375,26371 ,14991,14951,14947 ,0,0,0}, + {26329,26373,26374 ,14904,14949,14950 ,0,0,0}, {26375,26374,26371 ,14951,14950,14947 ,0,0,0}, + {26415,26376,26414 ,14992,14952,14991 ,0,0,0}, {26376,26375,26414 ,14952,14951,14991 ,0,0,0}, + {26416,26377,26415 ,14993,14953,14992 ,0,0,0}, {26377,26376,26415 ,14953,14952,14992 ,0,0,0}, + {26417,26284,26416 ,14994,14859,14993 ,0,0,0}, {26284,26377,26416 ,14859,14953,14993 ,0,0,0}, + {26380,26282,26417 ,14956,14857,14994 ,0,0,0}, {26282,26284,26417 ,14857,14859,14994 ,0,0,0}, + {26380,25595,26378 ,14956,14995,14954 ,0,0,0}, {26282,26380,26379 ,14857,14956,14955 ,0,0,0}, + {26418,26381,26378 ,14996,14957,14954 ,0,0,0}, {26381,26379,26378 ,14957,14955,14954 ,0,0,0}, + {26419,26382,26418 ,14997,14958,14996 ,0,0,0}, {26382,26381,26418 ,14958,14957,14996 ,0,0,0}, + {26420,26383,26419 ,14998,14959,14997 ,0,0,0}, {26383,26382,26419 ,14959,14958,14997 ,0,0,0}, + {26421,26292,26420 ,14999,14867,14998 ,0,0,0}, {26292,26383,26420 ,14867,14959,14998 ,0,0,0}, + {26422,26290,26421 ,15000,14865,14999 ,0,0,0}, {26290,26292,26421 ,14865,14867,14999 ,0,0,0}, + {26384,26386,26422 ,14960,14963,15000 ,0,0,0}, {26290,26422,26386 ,14865,15000,14963 ,0,0,0}, + {26384,26385,26387 ,14960,14962,14964 ,0,0,0}, {26423,26388,26385 ,15001,14965,14962 ,0,0,0}, + {26340,26386,26387 ,14915,14963,14964 ,0,0,0}, {26388,26387,26385 ,14965,14964,14962 ,0,0,0}, + {26424,26389,26423 ,15002,14966,15001 ,0,0,0}, {26389,26388,26423 ,14966,14965,15001 ,0,0,0}, + {26425,26390,26424 ,15003,14967,15002 ,0,0,0}, {26390,26389,26424 ,14967,14966,15002 ,0,0,0}, + {26426,26343,26425 ,15004,14918,15003 ,0,0,0}, {26343,26390,26425 ,14918,14967,15003 ,0,0,0}, + {26393,26344,26426 ,14970,14919,15004 ,0,0,0}, {26344,26343,26426 ,14919,14918,15004 ,0,0,0}, + {26393,25617,26391 ,14970,15005,14968 ,0,0,0}, {26344,26393,26392 ,14919,14970,14969 ,0,0,0}, + {26427,26394,26391 ,15006,14971,14968 ,0,0,0}, {26394,26392,26391 ,14971,14969,14968 ,0,0,0}, + {26428,26395,26427 ,15007,14972,15006 ,0,0,0}, {26395,26394,26427 ,14972,14971,15006 ,0,0,0}, + {26429,26396,26428 ,15008,14973,15007 ,0,0,0}, {26396,26395,26428 ,14973,14972,15007 ,0,0,0}, + {26430,26397,26429 ,15009,14974,15008 ,0,0,0}, {26397,26396,26429 ,14974,14973,15008 ,0,0,0}, + {26431,26398,26430 ,15010,14975,15009 ,0,0,0}, {26398,26397,26430 ,14975,14974,15009 ,0,0,0}, + {26432,26399,26431 ,15011,14976,15010 ,0,0,0}, {26399,26398,26431 ,14976,14975,15010 ,0,0,0}, + {26433,26353,26432 ,15012,14928,15011 ,0,0,0}, {26353,26399,26432 ,14928,14976,15011 ,0,0,0}, + {26434,26354,26433 ,15013,14929,15012 ,0,0,0}, {26354,26353,26433 ,14929,14928,15012 ,0,0,0}, + {26435,26400,26434 ,15014,14977,15013 ,0,0,0}, {26400,26354,26434 ,14977,14929,15013 ,0,0,0}, + {26436,26130,26435 ,15015,14698,15014 ,0,0,0}, {26130,26400,26435 ,14698,14977,15014 ,0,0,0}, + {26436,26402,26128 ,15015,14979,14696 ,0,0,0}, {26128,26130,26436 ,14696,14698,15015 ,0,0,0}, + {26402,26401,26403 ,14979,14978,14980 ,0,0,0}, {26133,26403,26131 ,14701,14980,14699 ,0,0,0}, + {26263,26128,26403 ,14838,14696,14980 ,0,0,0}, {26401,26131,26403 ,14978,14699,14980 ,0,0,0}, + {26132,26131,26136 ,14700,14699,14704 ,0,0,0}, {26361,26064,26063 ,14936,14602,14601 ,0,0,0}, + {26063,26064,26360 ,14601,14602,14935 ,0,0,0}, {25689,25687,26068 ,14761,15016,14606 ,0,0,0}, + {26068,25687,26069 ,14606,15016,14607 ,0,0,0}, {25687,25555,26069 ,15016,15017,14607 ,0,0,0}, + {26069,25555,26364 ,14607,15017,14939 ,0,0,0}, {25555,25554,26364 ,15017,15018,14939 ,0,0,0}, + {26364,25554,26405 ,14939,15018,14982 ,0,0,0}, {25554,25575,26405 ,15018,15019,14982 ,0,0,0}, + {26405,25575,26406 ,14982,15019,14983 ,0,0,0}, {25575,25545,26406 ,15019,15020,14983 ,0,0,0}, + {26406,25545,26407 ,14983,15020,14984 ,0,0,0}, {25545,25580,26407 ,15020,15021,14984 ,0,0,0}, + {26407,25580,26408 ,14984,15021,14985 ,0,0,0}, {25580,25577,26408 ,15021,15022,14985 ,0,0,0}, + {26408,25577,26409 ,14985,15022,14986 ,0,0,0}, {25577,25582,26409 ,15022,15023,14986 ,0,0,0}, + {25582,25584,26410 ,15023,15024,14987 ,0,0,0}, {25582,26410,26409 ,15023,14987,14986 ,0,0,0}, + {25584,25550,26411 ,15024,15025,14988 ,0,0,0}, {25584,26411,26410 ,15024,14988,14987 ,0,0,0}, + {25550,25549,26412 ,15025,15026,14989 ,0,0,0}, {25550,26412,26411 ,15025,14989,14988 ,0,0,0}, + {25549,25586,26413 ,15026,15027,14990 ,0,0,0}, {25549,26413,26412 ,15026,14990,14989 ,0,0,0}, + {25586,25681,26372 ,15027,15028,14948 ,0,0,0}, {25586,26372,26413 ,15027,14948,14990 ,0,0,0}, + {25680,26372,25681 ,14946,14948,15028 ,0,0,0}, {25680,25589,26371 ,14946,15029,14947 ,0,0,0}, + {26371,25589,26414 ,14947,15029,14991 ,0,0,0}, {25589,25594,26414 ,15029,15030,14991 ,0,0,0}, + {26414,25594,26415 ,14991,15030,14992 ,0,0,0}, {25594,25592,26415 ,15030,15031,14992 ,0,0,0}, + {25592,25591,26416 ,15031,15032,14993 ,0,0,0}, {25592,26416,26415 ,15031,14993,14992 ,0,0,0}, + {25591,25679,26417 ,15032,15033,14994 ,0,0,0}, {25591,26417,26416 ,15032,14994,14993 ,0,0,0}, + {25679,25595,26380 ,15033,14995,14956 ,0,0,0}, {25679,26380,26417 ,15033,14956,14994 ,0,0,0}, + {25595,25678,26378 ,14995,15034,14954 ,0,0,0}, {25678,25674,26378 ,15034,15035,14954 ,0,0,0}, + {26378,25674,26418 ,14954,15035,14996 ,0,0,0}, {25674,25599,26418 ,15035,15036,14996 ,0,0,0}, + {26418,25599,26419 ,14996,15036,14997 ,0,0,0}, {25599,25601,26419 ,15036,15037,14997 ,0,0,0}, + {25601,25606,26420 ,15037,15038,14998 ,0,0,0}, {25601,26420,26419 ,15037,14998,14997 ,0,0,0}, + {25606,25604,26421 ,15038,15039,14999 ,0,0,0}, {25606,26421,26420 ,15038,14999,14998 ,0,0,0}, + {25604,25603,26422 ,15039,15040,15000 ,0,0,0}, {25604,26422,26421 ,15039,15000,14999 ,0,0,0}, + {25603,25672,26384 ,15040,15041,14960 ,0,0,0}, {25603,26384,26422 ,15040,14960,15000 ,0,0,0}, + {25671,26384,25672 ,14961,14960,15041 ,0,0,0}, {25671,25608,26385 ,14961,15042,14962 ,0,0,0}, + {26385,25608,26423 ,14962,15042,15001 ,0,0,0}, {25608,25615,26423 ,15042,15043,15001 ,0,0,0}, + {25615,25614,26424 ,15043,15044,15002 ,0,0,0}, {25615,26424,26423 ,15043,15002,15001 ,0,0,0}, + {25614,25613,26425 ,15044,15045,15003 ,0,0,0}, {25614,26425,26424 ,15044,15003,15002 ,0,0,0}, + {25613,25668,26426 ,15045,15046,15004 ,0,0,0}, {25613,26426,26425 ,15045,15004,15003 ,0,0,0}, + {25668,25617,26393 ,15046,15005,14970 ,0,0,0}, {25668,26393,26426 ,15046,14970,15004 ,0,0,0}, + {25617,25616,26391 ,15005,15047,14968 ,0,0,0}, {25616,25622,26391 ,15047,15048,14968 ,0,0,0}, + {26391,25622,26427 ,14968,15048,15006 ,0,0,0}, {25622,25621,26427 ,15048,15049,15006 ,0,0,0}, + {26427,25621,26428 ,15006,15049,15007 ,0,0,0}, {25621,25626,26428 ,15049,15050,15007 ,0,0,0}, + {26428,25626,26429 ,15007,15050,15008 ,0,0,0}, {25626,25624,26429 ,15050,15051,15008 ,0,0,0}, + {25624,25631,26430 ,15051,15052,15009 ,0,0,0}, {25624,26430,26429 ,15051,15009,15008 ,0,0,0}, + {25631,25628,26431 ,15052,15053,15010 ,0,0,0}, {25631,26431,26430 ,15052,15010,15009 ,0,0,0}, + {25628,25635,26432 ,15053,15054,15011 ,0,0,0}, {25628,26432,26431 ,15053,15011,15010 ,0,0,0}, + {25635,25632,26433 ,15054,15055,15012 ,0,0,0}, {25635,26433,26432 ,15054,15012,15011 ,0,0,0}, + {25632,25637,26434 ,15055,15056,15013 ,0,0,0}, {25632,26434,26433 ,15055,15013,15012 ,0,0,0}, + {25637,25636,26435 ,15056,15057,15014 ,0,0,0}, {25637,26435,26434 ,15056,15014,15013 ,0,0,0}, + {25636,25650,26436 ,15057,15058,15015 ,0,0,0}, {25636,26436,26435 ,15057,15015,15014 ,0,0,0}, + {25650,25649,26402 ,15058,15059,14979 ,0,0,0}, {25650,26402,26436 ,15058,14979,15015 ,0,0,0}, + {25649,25643,26401 ,15059,15060,14978 ,0,0,0}, {25649,26401,26402 ,15059,14978,14979 ,0,0,0}, + {25643,25645,26137 ,15060,14711,14705 ,0,0,0}, {25643,26137,26401 ,15060,14705,14978 ,0,0,0}, + {26138,26137,25645 ,14706,14705,14711 ,0,0,0}, {26437,26438,26439 ,15061,15062,15063 ,0,0,0}, + {26440,25514,25513 ,15064,15065,15066 ,0,0,0}, {26440,26441,25514 ,15064,15067,15065 ,0,0,0}, + {26442,25512,26443 ,15068,15069,15070 ,0,0,0}, {25513,26442,26440 ,15066,15068,15064 ,0,0,0}, + {26442,25513,25512 ,15068,15066,15069 ,0,0,0}, {25510,26444,25511 ,15071,15072,15073 ,0,0,0}, + {25425,25511,26444 ,15074,15073,15072 ,0,0,0}, {25425,26444,26443 ,15074,15072,15070 ,0,0,0}, + {25510,25509,26445 ,15071,15075,15076 ,0,0,0}, {25425,26443,25512 ,15074,15070,15069 ,0,0,0}, + {26444,25510,26445 ,15072,15071,15076 ,0,0,0}, {25515,25514,26441 ,15077,15065,15067 ,0,0,0}, + {26446,25508,26447 ,15078,15079,15080 ,0,0,0}, {26446,25509,25508 ,15078,15075,15079 ,0,0,0}, + {26448,26449,26450 ,15081,15082,15083 ,0,0,0}, {26451,26447,25507 ,15084,15080,15085 ,0,0,0}, + {25508,25507,26447 ,15079,15085,15080 ,0,0,0}, {26452,26451,25506 ,15086,15084,15087 ,0,0,0}, + {26452,25505,26453 ,15086,15088,15089 ,0,0,0}, {25506,25505,26452 ,15087,15088,15086 ,0,0,0}, + {26453,25505,25504 ,15089,15088,15090 ,0,0,0}, {25507,25506,26451 ,15085,15087,15084 ,0,0,0}, + {26445,25509,26446 ,15076,15075,15078 ,0,0,0}, {25503,25502,26454 ,15091,15092,15093 ,0,0,0}, + {25503,26455,25504 ,15091,15094,15090 ,0,0,0}, {25501,26456,25502 ,15095,15096,15092 ,0,0,0}, + {25503,26454,26455 ,15091,15093,15094 ,0,0,0}, {25501,25500,26457 ,15095,15097,15098 ,0,0,0}, + {26457,26456,25501 ,15098,15096,15095 ,0,0,0}, {26138,25196,25193 ,15099,13703,15100 ,0,0,0}, + {25502,26456,26454 ,15092,15096,15093 ,0,0,0}, {26457,25500,26458 ,15098,15097,15101 ,0,0,0}, + {26459,26138,25193 ,15102,15099,15100 ,0,0,0}, {26460,26461,26457 ,15103,15104,15098 ,0,0,0}, + {26462,26463,26464 ,15105,15106,15107 ,0,0,0}, {26465,26466,26467 ,15108,15109,15110 ,0,0,0}, + {26468,26469,26358 ,15111,15112,15113 ,0,0,0}, {26468,26132,26470 ,15111,15114,15115 ,0,0,0}, + {26458,25500,25499 ,15101,15097,15116 ,0,0,0}, {26459,25193,26464 ,15102,15100,15107 ,0,0,0}, + {26461,26471,26467 ,15104,15117,15110 ,0,0,0}, {26359,26469,26472 ,15118,15112,15119 ,0,0,0}, + {26473,26186,26474 ,15120,15121,15122 ,0,0,0}, {25062,26475,25499 ,15123,15124,15116 ,0,0,0}, + {26476,26265,26472 ,15125,15126,15119 ,0,0,0}, {26266,26265,26476 ,15127,15126,15125 ,0,0,0}, + {26359,26472,26220 ,15118,15119,15128 ,0,0,0}, {25067,26147,25065 ,13574,15129,15130 ,0,0,0}, + {25062,26473,26475 ,15123,15120,15124 ,0,0,0}, {26186,26473,26147 ,15121,15120,15129 ,0,0,0}, + {26473,25065,26147 ,15120,15130,15129 ,0,0,0}, {26471,26477,26467 ,15117,15131,15110 ,0,0,0}, + {26455,26453,25504 ,15094,15089,15090 ,0,0,0}, {26478,25515,26441 ,15132,15077,15067 ,0,0,0}, + {25516,26478,26479 ,15133,15132,15134 ,0,0,0}, {26478,25516,25515 ,15132,15133,15077 ,0,0,0}, + {26480,25475,26479 ,15135,15136,15134 ,0,0,0}, {25516,26479,25475 ,15133,15134,15136 ,0,0,0}, + {25517,26480,25518 ,15137,15135,15138 ,0,0,0}, {25517,25475,26480 ,15137,15136,15135 ,0,0,0}, + {25519,25518,26481 ,15139,15138,15140 ,0,0,0}, {26480,26481,25518 ,15135,15140,15138 ,0,0,0}, + {26482,25520,25519 ,15141,15142,15139 ,0,0,0}, {25519,26481,26482 ,15139,15140,15141 ,0,0,0}, + {26482,26483,25520 ,15141,15143,15142 ,0,0,0}, {25520,26483,25521 ,15142,15143,15144 ,0,0,0}, + {25521,26483,26484 ,15144,15143,15145 ,0,0,0}, {26485,26486,26487 ,15146,15147,15148 ,0,0,0}, + {26488,25522,26484 ,15149,15150,15145 ,0,0,0}, {25521,26484,25522 ,15144,15145,15150 ,0,0,0}, + {26488,26489,25523 ,15149,15151,15152 ,0,0,0}, {25523,25522,26488 ,15152,15150,15149 ,0,0,0}, + {25440,25524,26489 ,15153,15154,15151 ,0,0,0}, {26489,25524,25523 ,15151,15154,15152 ,0,0,0}, + {26490,25525,25440 ,15155,15156,15153 ,0,0,0}, {25440,26489,26490 ,15153,15151,15155 ,0,0,0}, + {25525,26491,25526 ,15156,15157,15158 ,0,0,0}, {26491,25525,26490 ,15157,15156,15155 ,0,0,0}, + {25527,25526,26492 ,15159,15158,15160 ,0,0,0}, {26491,26492,25526 ,15157,15160,15158 ,0,0,0}, + {26493,25527,26492 ,15161,15159,15160 ,0,0,0}, {26493,25528,25527 ,15161,15162,15159 ,0,0,0}, + {26493,26494,25528 ,15161,15163,15162 ,0,0,0}, {26495,26496,26497 ,15164,15165,15166 ,0,0,0}, + {25529,26494,26498 ,15167,15163,15168 ,0,0,0}, {26494,25529,25528 ,15163,15167,15162 ,0,0,0}, + {26499,25486,26498 ,15169,15170,15168 ,0,0,0}, {25529,26498,25486 ,15167,15168,15170 ,0,0,0}, + {25530,26499,25531 ,15171,15169,15172 ,0,0,0}, {25530,25486,26499 ,15171,15170,15169 ,0,0,0}, + {25532,25531,26500 ,15173,15172,15174 ,0,0,0}, {26499,26500,25531 ,15169,15174,15172 ,0,0,0}, + {26501,25533,25532 ,15175,15176,15173 ,0,0,0}, {25532,26500,26501 ,15173,15174,15175 ,0,0,0}, + {25533,26502,25534 ,15176,15177,15178 ,0,0,0}, {26502,25533,26501 ,15177,15176,15175 ,0,0,0}, + {25535,25534,26503 ,15179,15178,15180 ,0,0,0}, {26502,26503,25534 ,15177,15180,15178 ,0,0,0}, + {26504,25535,26503 ,15181,15179,15180 ,0,0,0}, {26504,25536,25535 ,15181,15182,15179 ,0,0,0}, + {26504,26505,25536 ,15181,15183,15182 ,0,0,0}, {26506,26507,26508 ,15184,15185,15186 ,0,0,0}, + {25537,26505,26507 ,15187,15183,15185 ,0,0,0}, {26505,25537,25536 ,15183,15187,15182 ,0,0,0}, + {26509,25538,26507 ,15188,15189,15185 ,0,0,0}, {25537,26507,25538 ,15187,15185,15189 ,0,0,0}, + {26510,26511,26512 ,15190,15191,15192 ,0,0,0}, {25539,25538,26509 ,15193,15189,15188 ,0,0,0}, + {26513,26514,26515 ,15194,15195,15196 ,0,0,0}, {26516,26517,26518 ,15197,15198,15199 ,0,0,0}, + {26519,26513,26520 ,15200,15194,15201 ,0,0,0}, {26521,26522,26523 ,15202,15203,15204 ,0,0,0}, + {26524,26525,26526 ,15205,15206,15207 ,0,0,0}, {26521,26527,26528 ,15202,15208,15209 ,0,0,0}, + {26529,26530,26531 ,15210,15211,15212 ,0,0,0}, {26528,26527,26532 ,15209,15208,15213 ,0,0,0}, + {25540,25539,26533 ,15214,15193,15215 ,0,0,0}, {25130,26532,26527 ,13637,15213,15208 ,0,0,0}, + {26534,26535,26536 ,15216,15217,15218 ,0,0,0}, {25539,26509,26533 ,15193,15188,15215 ,0,0,0}, + {25540,26518,25541 ,15214,15199,15219 ,0,0,0}, {26506,26509,26507 ,15184,15188,15185 ,0,0,0}, + {25542,25541,26535 ,15220,15219,15217 ,0,0,0}, {26518,26535,25541 ,15199,15217,15219 ,0,0,0}, + {25543,26534,25544 ,15221,15216,15222 ,0,0,0}, {25542,26535,26534 ,15220,15217,15216 ,0,0,0}, + {25544,26537,25164 ,15222,15223,13671 ,0,0,0}, {26534,26537,25544 ,15216,15223,15222 ,0,0,0}, + {25065,26473,25062 ,15130,15120,15123 ,0,0,0}, {26224,26474,26186 ,15224,15122,15121 ,0,0,0}, + {26224,26476,26474 ,15224,15125,15122 ,0,0,0}, {26475,26458,25499 ,15124,15101,15116 ,0,0,0}, + {26475,26474,26538 ,15124,15122,15225 ,0,0,0}, {26539,26456,26461 ,15226,15096,15104 ,0,0,0}, + {26458,26538,26460 ,15101,15225,15103 ,0,0,0}, {26540,26454,26539 ,15227,15093,15226 ,0,0,0}, + {26460,26457,26458 ,15103,15098,15101 ,0,0,0}, {26541,26455,26540 ,15228,15094,15227 ,0,0,0}, + {26461,26456,26457 ,15104,15096,15098 ,0,0,0}, {26542,26453,26541 ,15229,15089,15228 ,0,0,0}, + {26539,26454,26456 ,15226,15093,15096 ,0,0,0}, {26543,26452,26542 ,15230,15086,15229 ,0,0,0}, + {26540,26455,26454 ,15227,15094,15093 ,0,0,0}, {26544,26451,26543 ,15231,15084,15230 ,0,0,0}, + {26541,26453,26455 ,15228,15089,15094 ,0,0,0}, {26545,26447,26544 ,15232,15080,15231 ,0,0,0}, + {26542,26452,26453 ,15229,15086,15089 ,0,0,0}, {26545,26546,26446 ,15232,15233,15078 ,0,0,0}, + {26451,26452,26543 ,15084,15086,15230 ,0,0,0}, {26547,26445,26546 ,15234,15076,15233 ,0,0,0}, + {26447,26451,26544 ,15080,15084,15231 ,0,0,0}, {26448,26444,26547 ,15081,15072,15234 ,0,0,0}, + {26446,26447,26545 ,15078,15080,15232 ,0,0,0}, {26548,26443,26448 ,15235,15070,15081 ,0,0,0}, + {26445,26446,26546 ,15076,15078,15233 ,0,0,0}, {26549,26442,26548 ,15236,15068,15235 ,0,0,0}, + {26444,26445,26547 ,15072,15076,15234 ,0,0,0}, {26550,26440,26549 ,15237,15064,15236 ,0,0,0}, + {26448,26443,26444 ,15081,15070,15072 ,0,0,0}, {26551,26441,26550 ,15238,15067,15237 ,0,0,0}, + {26548,26442,26443 ,15235,15068,15070 ,0,0,0}, {26551,26552,26478 ,15238,15239,15132 ,0,0,0}, + {26440,26442,26549 ,15064,15068,15236 ,0,0,0}, {26553,26479,26552 ,15240,15134,15239 ,0,0,0}, + {26441,26440,26550 ,15067,15064,15237 ,0,0,0}, {26554,26480,26553 ,15241,15135,15240 ,0,0,0}, + {26478,26441,26551 ,15132,15067,15238 ,0,0,0}, {26555,26481,26554 ,15242,15140,15241 ,0,0,0}, + {26479,26478,26552 ,15134,15132,15239 ,0,0,0}, {26556,26482,26555 ,15243,15141,15242 ,0,0,0}, + {26480,26479,26553 ,15135,15134,15240 ,0,0,0}, {26557,26483,26556 ,15244,15143,15243 ,0,0,0}, + {26554,26481,26480 ,15241,15140,15135 ,0,0,0}, {26557,26558,26484 ,15244,15245,15145 ,0,0,0}, + {26482,26481,26555 ,15141,15140,15242 ,0,0,0}, {26559,26488,26558 ,15246,15149,15245 ,0,0,0}, + {26483,26482,26556 ,15143,15141,15243 ,0,0,0}, {26485,26489,26559 ,15146,15151,15246 ,0,0,0}, + {26484,26483,26557 ,15145,15143,15244 ,0,0,0}, {26560,26490,26485 ,15247,15155,15146 ,0,0,0}, + {26488,26484,26558 ,15149,15145,15245 ,0,0,0}, {26561,26491,26560 ,15248,15157,15247 ,0,0,0}, + {26489,26488,26559 ,15151,15149,15246 ,0,0,0}, {26562,26492,26561 ,15249,15160,15248 ,0,0,0}, + {26485,26490,26489 ,15146,15155,15151 ,0,0,0}, {26563,26493,26562 ,15250,15161,15249 ,0,0,0}, + {26560,26491,26490 ,15247,15157,15155 ,0,0,0}, {26563,26564,26494 ,15250,15251,15163 ,0,0,0}, + {26492,26491,26561 ,15160,15157,15248 ,0,0,0}, {26565,26498,26564 ,15252,15168,15251 ,0,0,0}, + {26493,26492,26562 ,15161,15160,15249 ,0,0,0}, {26566,26499,26565 ,15253,15169,15252 ,0,0,0}, + {26494,26493,26563 ,15163,15161,15250 ,0,0,0}, {26567,26500,26566 ,15254,15174,15253 ,0,0,0}, + {26498,26494,26564 ,15168,15163,15251 ,0,0,0}, {26568,26501,26567 ,15255,15175,15254 ,0,0,0}, + {26565,26499,26498 ,15252,15169,15168 ,0,0,0}, {26569,26502,26568 ,15256,15177,15255 ,0,0,0}, + {26566,26500,26499 ,15253,15174,15169 ,0,0,0}, {26570,26503,26569 ,15257,15180,15256 ,0,0,0}, + {26567,26501,26500 ,15254,15175,15174 ,0,0,0}, {26571,26504,26570 ,15258,15181,15257 ,0,0,0}, + {26568,26502,26501 ,15255,15177,15175 ,0,0,0}, {26571,26508,26505 ,15258,15186,15183 ,0,0,0}, + {26503,26502,26569 ,15180,15177,15256 ,0,0,0}, {26509,26506,26572 ,15188,15184,15259 ,0,0,0}, + {26504,26503,26570 ,15181,15180,15257 ,0,0,0}, {26526,26517,26530 ,15207,15198,15211 ,0,0,0}, + {26505,26504,26571 ,15183,15181,15258 ,0,0,0}, {26516,26533,26572 ,15197,15215,15259 ,0,0,0}, + {26507,26505,26508 ,15185,15183,15186 ,0,0,0}, {26516,26572,26573 ,15197,15259,15260 ,0,0,0}, + {26525,26536,26526 ,15206,15218,15207 ,0,0,0}, {26533,26518,25540 ,15215,15199,15214 ,0,0,0}, + {26533,26509,26572 ,15215,15188,15259 ,0,0,0}, {26574,26537,26575 ,15261,15223,15262 ,0,0,0}, + {26533,26516,26518 ,15215,15197,15199 ,0,0,0}, {26536,26535,26517 ,15218,15217,15198 ,0,0,0}, + {26576,26577,26537 ,15263,15264,15223 ,0,0,0}, {25542,26534,25543 ,15220,15216,15221 ,0,0,0}, + {26534,26575,26537 ,15216,15262,15223 ,0,0,0}, {25164,26537,26577 ,13671,15223,15264 ,0,0,0}, + {26473,26474,26475 ,15120,15122,15124 ,0,0,0}, {26266,26476,26224 ,15127,15125,15224 ,0,0,0}, + {26358,26404,26468 ,15113,15265,15111 ,0,0,0}, {26475,26538,26458 ,15124,15225,15101 ,0,0,0}, + {26538,26476,26578 ,15225,15125,15266 ,0,0,0}, {26467,26466,26539 ,15110,15109,15226 ,0,0,0}, + {26471,26460,26578 ,15117,15103,15266 ,0,0,0}, {26466,26579,26540 ,15109,15267,15227 ,0,0,0}, + {26471,26461,26460 ,15117,15104,15103 ,0,0,0}, {26579,26580,26541 ,15267,15268,15228 ,0,0,0}, + {26467,26539,26461 ,15110,15226,15104 ,0,0,0}, {26580,26581,26542 ,15268,15269,15229 ,0,0,0}, + {26466,26540,26539 ,15109,15227,15226 ,0,0,0}, {26581,26582,26543 ,15269,15270,15230 ,0,0,0}, + {26579,26541,26540 ,15267,15228,15227 ,0,0,0}, {26582,26583,26544 ,15270,15271,15231 ,0,0,0}, + {26580,26542,26541 ,15268,15229,15228 ,0,0,0}, {26583,26584,26545 ,15271,15272,15232 ,0,0,0}, + {26581,26543,26542 ,15269,15230,15229 ,0,0,0}, {26584,26585,26546 ,15272,15273,15233 ,0,0,0}, + {26582,26544,26543 ,15270,15231,15230 ,0,0,0}, {26585,26449,26547 ,15273,15082,15234 ,0,0,0}, + {26545,26544,26583 ,15232,15231,15271 ,0,0,0}, {26586,26587,26588 ,15274,15275,15276 ,0,0,0}, + {26546,26545,26584 ,15233,15232,15272 ,0,0,0}, {26450,26587,26548 ,15083,15275,15235 ,0,0,0}, + {26547,26546,26585 ,15234,15233,15273 ,0,0,0}, {26587,26586,26549 ,15275,15274,15236 ,0,0,0}, + {26448,26547,26449 ,15081,15234,15082 ,0,0,0}, {26586,26589,26550 ,15274,15277,15237 ,0,0,0}, + {26450,26548,26448 ,15083,15235,15081 ,0,0,0}, {26589,26590,26551 ,15277,15278,15238 ,0,0,0}, + {26587,26549,26548 ,15275,15236,15235 ,0,0,0}, {26590,26591,26552 ,15278,15279,15239 ,0,0,0}, + {26586,26550,26549 ,15274,15237,15236 ,0,0,0}, {26591,26592,26553 ,15279,15280,15240 ,0,0,0}, + {26551,26550,26589 ,15238,15237,15277 ,0,0,0}, {26438,26554,26592 ,15062,15241,15280 ,0,0,0}, + {26552,26551,26590 ,15239,15238,15278 ,0,0,0}, {26438,26437,26555 ,15062,15061,15242 ,0,0,0}, + {26553,26552,26591 ,15240,15239,15279 ,0,0,0}, {26437,26593,26556 ,15061,15281,15243 ,0,0,0}, + {26592,26554,26553 ,15280,15241,15240 ,0,0,0}, {26593,26594,26557 ,15281,15282,15244 ,0,0,0}, + {26438,26555,26554 ,15062,15242,15241 ,0,0,0}, {26594,26595,26558 ,15282,15283,15245 ,0,0,0}, + {26437,26556,26555 ,15061,15243,15242 ,0,0,0}, {26595,26486,26559 ,15283,15147,15246 ,0,0,0}, + {26557,26556,26593 ,15244,15243,15281 ,0,0,0}, {26596,26597,26598 ,15284,15285,15286 ,0,0,0}, + {26558,26557,26594 ,15245,15244,15282 ,0,0,0}, {26487,26599,26560 ,15148,15287,15247 ,0,0,0}, + {26559,26558,26595 ,15246,15245,15283 ,0,0,0}, {26599,26600,26561 ,15287,15288,15248 ,0,0,0}, + {26485,26559,26486 ,15146,15246,15147 ,0,0,0}, {26600,26601,26562 ,15288,15289,15249 ,0,0,0}, + {26487,26560,26485 ,15148,15247,15146 ,0,0,0}, {26601,26602,26563 ,15289,15290,15250 ,0,0,0}, + {26599,26561,26560 ,15287,15248,15247 ,0,0,0}, {26602,26603,26564 ,15290,15291,15251 ,0,0,0}, + {26600,26562,26561 ,15288,15249,15248 ,0,0,0}, {26603,26604,26565 ,15291,15292,15252 ,0,0,0}, + {26563,26562,26601 ,15250,15249,15289 ,0,0,0}, {26604,26495,26566 ,15292,15164,15253 ,0,0,0}, + {26564,26563,26602 ,15251,15250,15290 ,0,0,0}, {26495,26497,26567 ,15164,15166,15254 ,0,0,0}, + {26565,26564,26603 ,15252,15251,15291 ,0,0,0}, {26497,26605,26568 ,15166,15293,15255 ,0,0,0}, + {26604,26566,26565 ,15292,15253,15252 ,0,0,0}, {26605,26606,26569 ,15293,15294,15256 ,0,0,0}, + {26495,26567,26566 ,15164,15254,15253 ,0,0,0}, {26606,26607,26570 ,15294,15295,15257 ,0,0,0}, + {26497,26568,26567 ,15166,15255,15254 ,0,0,0}, {26607,26608,26571 ,15295,15296,15258 ,0,0,0}, + {26605,26569,26568 ,15293,15256,15255 ,0,0,0}, {26608,26609,26508 ,15296,15297,15186 ,0,0,0}, + {26606,26570,26569 ,15294,15257,15256 ,0,0,0}, {26609,26610,26506 ,15297,15298,15184 ,0,0,0}, + {26607,26571,26570 ,15295,15258,15257 ,0,0,0}, {26610,26573,26572 ,15298,15260,15259 ,0,0,0}, + {26608,26508,26571 ,15296,15186,15258 ,0,0,0}, {26573,26530,26516 ,15260,15211,15197 ,0,0,0}, + {26506,26508,26609 ,15184,15186,15297 ,0,0,0}, {26611,26525,26612 ,15299,15206,15300 ,0,0,0}, + {26506,26610,26572 ,15184,15298,15259 ,0,0,0}, {26536,26525,26575 ,15218,15206,15262 ,0,0,0}, + {26524,26612,26525 ,15205,15300,15206 ,0,0,0}, {26518,26517,26535 ,15199,15198,15217 ,0,0,0}, + {26530,26517,26516 ,15211,15198,15197 ,0,0,0}, {26613,26574,26510 ,15301,15261,15190 ,0,0,0}, + {26574,26576,26537 ,15261,15263,15223 ,0,0,0}, {26534,26536,26575 ,15216,15218,15262 ,0,0,0}, + {26574,26575,26611 ,15261,15262,15299 ,0,0,0}, {26613,26576,26574 ,15301,15263,15261 ,0,0,0}, + {26474,26476,26538 ,15122,15125,15225 ,0,0,0}, {26220,26472,26265 ,15128,15119,15126 ,0,0,0}, + {25191,26464,25193 ,15302,15107,15100 ,0,0,0}, {26538,26578,26460 ,15225,15266,15103 ,0,0,0}, + {26578,26472,26614 ,15266,15119,15303 ,0,0,0}, {26466,26615,26579 ,15109,15304,15267 ,0,0,0}, + {26477,26471,26614 ,15131,15117,15303 ,0,0,0}, {26579,26616,26580 ,15267,15305,15268 ,0,0,0}, + {26477,26465,26467 ,15131,15108,15110 ,0,0,0}, {26617,26618,26619 ,15306,15307,15308 ,0,0,0}, + {26465,26615,26466 ,15108,15304,15109 ,0,0,0}, {26581,26580,26620 ,15269,15268,15309 ,0,0,0}, + {26615,26616,26579 ,15304,15305,15267 ,0,0,0}, {26582,26581,26619 ,15270,15269,15308 ,0,0,0}, + {26616,26620,26580 ,15305,15309,15268 ,0,0,0}, {26583,26582,26618 ,15271,15270,15307 ,0,0,0}, + {26620,26619,26581 ,15309,15308,15269 ,0,0,0}, {26584,26583,26621 ,15272,15271,15310 ,0,0,0}, + {26619,26618,26582 ,15308,15307,15270 ,0,0,0}, {26585,26584,26622 ,15273,15272,15311 ,0,0,0}, + {26618,26621,26583 ,15307,15310,15271 ,0,0,0}, {26449,26585,26623 ,15082,15273,15312 ,0,0,0}, + {26621,26622,26584 ,15310,15311,15272 ,0,0,0}, {26450,26449,26624 ,15083,15082,15313 ,0,0,0}, + {26622,26623,26585 ,15311,15312,15273 ,0,0,0}, {26587,26450,26625 ,15275,15083,15314 ,0,0,0}, + {26624,26449,26623 ,15313,15082,15312 ,0,0,0}, {26626,26627,26628 ,15315,15316,15317 ,0,0,0}, + {26625,26450,26624 ,15314,15083,15313 ,0,0,0}, {26589,26586,26629 ,15277,15274,15318 ,0,0,0}, + {26625,26588,26587 ,15314,15276,15275 ,0,0,0}, {26590,26589,26628 ,15278,15277,15317 ,0,0,0}, + {26588,26629,26586 ,15276,15318,15274 ,0,0,0}, {26591,26590,26627 ,15279,15278,15316 ,0,0,0}, + {26629,26628,26589 ,15318,15317,15277 ,0,0,0}, {26592,26591,26630 ,15280,15279,15319 ,0,0,0}, + {26628,26627,26590 ,15317,15316,15278 ,0,0,0}, {26438,26592,26631 ,15062,15280,15320 ,0,0,0}, + {26630,26591,26627 ,15319,15279,15316 ,0,0,0}, {26632,26633,26634 ,15321,15322,15323 ,0,0,0}, + {26631,26592,26630 ,15320,15280,15319 ,0,0,0}, {26593,26437,26635 ,15281,15061,15324 ,0,0,0}, + {26631,26439,26438 ,15320,15063,15062 ,0,0,0}, {26594,26593,26634 ,15282,15281,15323 ,0,0,0}, + {26439,26635,26437 ,15063,15324,15061 ,0,0,0}, {26595,26594,26633 ,15283,15282,15322 ,0,0,0}, + {26635,26634,26593 ,15324,15323,15281 ,0,0,0}, {26486,26595,26636 ,15147,15283,15325 ,0,0,0}, + {26634,26633,26594 ,15323,15322,15282 ,0,0,0}, {26487,26486,26637 ,15148,15147,15326 ,0,0,0}, + {26633,26636,26595 ,15322,15325,15283 ,0,0,0}, {26599,26487,26638 ,15287,15148,15327 ,0,0,0}, + {26637,26486,26636 ,15326,15147,15325 ,0,0,0}, {26600,26599,26639 ,15288,15287,15328 ,0,0,0}, + {26638,26487,26637 ,15327,15148,15326 ,0,0,0}, {26601,26600,26596 ,15289,15288,15284 ,0,0,0}, + {26638,26639,26599 ,15327,15328,15287 ,0,0,0}, {26602,26601,26598 ,15290,15289,15286 ,0,0,0}, + {26639,26596,26600 ,15328,15284,15288 ,0,0,0}, {26603,26602,26640 ,15291,15290,15329 ,0,0,0}, + {26596,26598,26601 ,15284,15286,15289 ,0,0,0}, {26604,26603,26641 ,15292,15291,15330 ,0,0,0}, + {26598,26640,26602 ,15286,15329,15290 ,0,0,0}, {26495,26604,26642 ,15164,15292,15331 ,0,0,0}, + {26641,26603,26640 ,15330,15291,15329 ,0,0,0}, {26643,26644,26645 ,15332,15333,15334 ,0,0,0}, + {26642,26604,26641 ,15331,15292,15330 ,0,0,0}, {26605,26497,26646 ,15293,15166,15335 ,0,0,0}, + {26642,26496,26495 ,15331,15165,15164 ,0,0,0}, {26606,26605,26645 ,15294,15293,15334 ,0,0,0}, + {26496,26646,26497 ,15165,15335,15166 ,0,0,0}, {26607,26606,26644 ,15295,15294,15333 ,0,0,0}, + {26646,26645,26605 ,15335,15334,15293 ,0,0,0}, {26608,26607,26647 ,15296,15295,15336 ,0,0,0}, + {26645,26644,26606 ,15334,15333,15294 ,0,0,0}, {26609,26608,26648 ,15297,15296,15337 ,0,0,0}, + {26644,26647,26607 ,15333,15336,15295 ,0,0,0}, {26610,26609,26649 ,15298,15297,15338 ,0,0,0}, + {26647,26648,26608 ,15336,15337,15296 ,0,0,0}, {26573,26610,26650 ,15260,15298,15339 ,0,0,0}, + {26648,26649,26609 ,15337,15338,15297 ,0,0,0}, {26530,26573,26531 ,15211,15260,15212 ,0,0,0}, + {26649,26650,26610 ,15338,15339,15298 ,0,0,0}, {26526,26530,26529 ,15207,15211,15210 ,0,0,0}, + {26650,26531,26573 ,15339,15212,15260 ,0,0,0}, {26511,26612,26514 ,15191,15300,15195 ,0,0,0}, + {26612,26651,26514 ,15300,15340,15195 ,0,0,0}, {26517,26526,26536 ,15198,15207,15218 ,0,0,0}, + {26529,26524,26526 ,15210,15205,15207 ,0,0,0}, {26652,26510,26512 ,15341,15190,15192 ,0,0,0}, + {26574,26611,26510 ,15261,15299,15190 ,0,0,0}, {26575,26525,26611 ,15262,15206,15299 ,0,0,0}, + {26611,26511,26510 ,15299,15191,15190 ,0,0,0}, {26613,26510,26652 ,15301,15190,15341 ,0,0,0}, + {26472,26578,26476 ,15119,15266,15125 ,0,0,0}, {26358,26469,26359 ,15113,15112,15118 ,0,0,0}, + {26477,26653,26465 ,15131,15342,15108 ,0,0,0}, {26578,26614,26471 ,15266,15303,15117 ,0,0,0}, + {26469,26654,26614 ,15112,15343,15303 ,0,0,0}, {26615,26465,26655 ,15304,15108,15344 ,0,0,0}, + {26654,26653,26477 ,15343,15342,15131 ,0,0,0}, {26616,26615,26656 ,15305,15304,15345 ,0,0,0}, + {26465,26653,26655 ,15108,15342,15344 ,0,0,0}, {26620,26616,26657 ,15309,15305,15346 ,0,0,0}, + {26615,26655,26656 ,15304,15344,15345 ,0,0,0}, {26619,26620,26658 ,15308,15309,15347 ,0,0,0}, + {26656,26657,26616 ,15345,15346,15305 ,0,0,0}, {26659,26621,26618 ,15348,15310,15307 ,0,0,0}, + {26657,26658,26620 ,15346,15347,15309 ,0,0,0}, {26660,26661,26662 ,15349,15350,15351 ,0,0,0}, + {26658,26617,26619 ,15347,15306,15308 ,0,0,0}, {26621,26663,26622 ,15310,15352,15311 ,0,0,0}, + {26617,26659,26618 ,15306,15348,15307 ,0,0,0}, {26622,26661,26623 ,15311,15350,15312 ,0,0,0}, + {26659,26663,26621 ,15348,15352,15310 ,0,0,0}, {26623,26660,26624 ,15312,15349,15313 ,0,0,0}, + {26663,26661,26622 ,15352,15350,15311 ,0,0,0}, {26624,26664,26625 ,15313,15353,15314 ,0,0,0}, + {26661,26660,26623 ,15350,15349,15312 ,0,0,0}, {26625,26665,26588 ,15314,15354,15276 ,0,0,0}, + {26660,26664,26624 ,15349,15353,15313 ,0,0,0}, {26629,26588,26666 ,15318,15276,15355 ,0,0,0}, + {26664,26665,26625 ,15353,15354,15314 ,0,0,0}, {26628,26629,26667 ,15317,15318,15356 ,0,0,0}, + {26665,26666,26588 ,15354,15355,15276 ,0,0,0}, {26668,26669,26670 ,15357,15358,15359 ,0,0,0}, + {26666,26667,26629 ,15355,15356,15318 ,0,0,0}, {26627,26671,26630 ,15316,15360,15319 ,0,0,0}, + {26667,26626,26628 ,15356,15315,15317 ,0,0,0}, {26630,26672,26631 ,15319,15361,15320 ,0,0,0}, + {26626,26671,26627 ,15315,15360,15316 ,0,0,0}, {26631,26673,26439 ,15320,15362,15063 ,0,0,0}, + {26671,26672,26630 ,15360,15361,15319 ,0,0,0}, {26635,26439,26674 ,15324,15063,15363 ,0,0,0}, + {26672,26673,26631 ,15361,15362,15320 ,0,0,0}, {26634,26635,26675 ,15323,15324,15364 ,0,0,0}, + {26673,26674,26439 ,15362,15363,15063 ,0,0,0}, {26676,26677,26678 ,15365,15366,15367 ,0,0,0}, + {26674,26675,26635 ,15363,15364,15324 ,0,0,0}, {26633,26679,26636 ,15322,15368,15325 ,0,0,0}, + {26675,26632,26634 ,15364,15321,15323 ,0,0,0}, {26636,26680,26637 ,15325,15369,15326 ,0,0,0}, + {26632,26679,26633 ,15321,15368,15322 ,0,0,0}, {26637,26681,26638 ,15326,15370,15327 ,0,0,0}, + {26679,26680,26636 ,15368,15369,15325 ,0,0,0}, {26638,26682,26639 ,15327,15371,15328 ,0,0,0}, + {26680,26681,26637 ,15369,15370,15326 ,0,0,0}, {26596,26639,26683 ,15284,15328,15372 ,0,0,0}, + {26681,26682,26638 ,15370,15371,15327 ,0,0,0}, {26684,26685,26686 ,15373,15374,15375 ,0,0,0}, + {26682,26683,26639 ,15371,15372,15328 ,0,0,0}, {26598,26687,26640 ,15286,15376,15329 ,0,0,0}, + {26683,26597,26596 ,15372,15285,15284 ,0,0,0}, {26640,26685,26641 ,15329,15374,15330 ,0,0,0}, + {26597,26687,26598 ,15285,15376,15286 ,0,0,0}, {26641,26684,26642 ,15330,15373,15331 ,0,0,0}, + {26687,26685,26640 ,15376,15374,15329 ,0,0,0}, {26642,26688,26496 ,15331,15377,15165 ,0,0,0}, + {26685,26684,26641 ,15374,15373,15330 ,0,0,0}, {26646,26496,26689 ,15335,15165,15378 ,0,0,0}, + {26684,26688,26642 ,15373,15377,15331 ,0,0,0}, {26645,26646,26690 ,15334,15335,15379 ,0,0,0}, + {26688,26689,26496 ,15377,15378,15165 ,0,0,0}, {26691,26647,26644 ,15380,15336,15333 ,0,0,0}, + {26689,26690,26646 ,15378,15379,15335 ,0,0,0}, {26692,26693,26694 ,15381,15382,15383 ,0,0,0}, + {26690,26643,26645 ,15379,15332,15334 ,0,0,0}, {26647,26695,26648 ,15336,15384,15337 ,0,0,0}, + {26643,26691,26644 ,15332,15380,15333 ,0,0,0}, {26648,26693,26649 ,15337,15382,15338 ,0,0,0}, + {26691,26695,26647 ,15380,15384,15336 ,0,0,0}, {26649,26692,26650 ,15338,15381,15339 ,0,0,0}, + {26695,26693,26648 ,15384,15382,15337 ,0,0,0}, {26650,26696,26531 ,15339,15385,15212 ,0,0,0}, + {26693,26692,26649 ,15382,15381,15338 ,0,0,0}, {26531,26697,26529 ,15212,15386,15210 ,0,0,0}, + {26692,26696,26650 ,15381,15385,15339 ,0,0,0}, {26529,26698,26524 ,15210,15387,15205 ,0,0,0}, + {26696,26697,26531 ,15385,15386,15212 ,0,0,0}, {26524,26651,26612 ,15205,15340,15300 ,0,0,0}, + {26698,26529,26697 ,15387,15210,15386 ,0,0,0}, {26699,26700,26512 ,15388,15389,15192 ,0,0,0}, + {26524,26698,26651 ,15205,15387,15340 ,0,0,0}, {26701,26512,26700 ,15390,15192,15389 ,0,0,0}, + {26702,26652,26512 ,15391,15341,15192 ,0,0,0}, {26611,26612,26511 ,15299,15300,15191 ,0,0,0}, + {26511,26699,26512 ,15191,15388,15192 ,0,0,0}, {26701,26702,26512 ,15390,15391,15192 ,0,0,0}, + {26469,26614,26472 ,15112,15303,15119 ,0,0,0}, {26132,26468,26404 ,15114,15111,15265 ,0,0,0}, + {26653,26703,26655 ,15342,15392,15344 ,0,0,0}, {26614,26654,26477 ,15303,15343,15131 ,0,0,0}, + {26468,26704,26654 ,15111,15393,15343 ,0,0,0}, {26656,26655,26705 ,15345,15344,15394 ,0,0,0}, + {26653,26704,26703 ,15342,15393,15392 ,0,0,0}, {26657,26656,26706 ,15346,15345,15395 ,0,0,0}, + {26655,26703,26705 ,15344,15392,15394 ,0,0,0}, {26658,26657,26707 ,15347,15346,15396 ,0,0,0}, + {26656,26705,26706 ,15345,15394,15395 ,0,0,0}, {26617,26658,26708 ,15306,15347,15397 ,0,0,0}, + {26657,26706,26707 ,15346,15395,15396 ,0,0,0}, {26659,26617,26709 ,15348,15306,15398 ,0,0,0}, + {26658,26707,26708 ,15347,15396,15397 ,0,0,0}, {26663,26659,26710 ,15352,15348,15399 ,0,0,0}, + {26617,26708,26709 ,15306,15397,15398 ,0,0,0}, {26661,26663,26711 ,15350,15352,15400 ,0,0,0}, + {26709,26710,26659 ,15398,15399,15348 ,0,0,0}, {26712,26713,26714 ,15401,15402,15403 ,0,0,0}, + {26710,26711,26663 ,15399,15400,15352 ,0,0,0}, {26660,26715,26664 ,15349,15404,15353 ,0,0,0}, + {26711,26662,26661 ,15400,15351,15350 ,0,0,0}, {26664,26714,26665 ,15353,15403,15354 ,0,0,0}, + {26662,26715,26660 ,15351,15404,15349 ,0,0,0}, {26665,26716,26666 ,15354,15405,15355 ,0,0,0}, + {26715,26714,26664 ,15404,15403,15353 ,0,0,0}, {26667,26666,26717 ,15356,15355,15406 ,0,0,0}, + {26714,26716,26665 ,15403,15405,15354 ,0,0,0}, {26626,26667,26718 ,15315,15356,15407 ,0,0,0}, + {26666,26716,26717 ,15355,15405,15406 ,0,0,0}, {26671,26626,26719 ,15360,15315,15408 ,0,0,0}, + {26667,26717,26718 ,15356,15406,15407 ,0,0,0}, {26672,26671,26720 ,15361,15360,15409 ,0,0,0}, + {26718,26719,26626 ,15407,15408,15315 ,0,0,0}, {26672,26721,26673 ,15361,15410,15362 ,0,0,0}, + {26719,26720,26671 ,15408,15409,15360 ,0,0,0}, {26673,26669,26674 ,15362,15358,15363 ,0,0,0}, + {26720,26721,26672 ,15409,15410,15361 ,0,0,0}, {26675,26674,26722 ,15364,15363,15411 ,0,0,0}, + {26721,26669,26673 ,15410,15358,15362 ,0,0,0}, {26632,26675,26723 ,15321,15364,15412 ,0,0,0}, + {26674,26669,26722 ,15363,15358,15411 ,0,0,0}, {26679,26632,26724 ,15368,15321,15413 ,0,0,0}, + {26675,26722,26723 ,15364,15411,15412 ,0,0,0}, {26680,26679,26725 ,15369,15368,15414 ,0,0,0}, + {26723,26724,26632 ,15412,15413,15321 ,0,0,0}, {26680,26726,26681 ,15369,15415,15370 ,0,0,0}, + {26724,26725,26679 ,15413,15414,15368 ,0,0,0}, {26681,26677,26682 ,15370,15366,15371 ,0,0,0}, + {26725,26726,26680 ,15414,15415,15369 ,0,0,0}, {26683,26682,26727 ,15372,15371,15416 ,0,0,0}, + {26726,26677,26681 ,15415,15366,15370 ,0,0,0}, {26597,26683,26728 ,15285,15372,15417 ,0,0,0}, + {26682,26677,26727 ,15371,15366,15416 ,0,0,0}, {26687,26597,26729 ,15376,15285,15418 ,0,0,0}, + {26683,26727,26728 ,15372,15416,15417 ,0,0,0}, {26685,26687,26730 ,15374,15376,15419 ,0,0,0}, + {26728,26729,26597 ,15417,15418,15285 ,0,0,0}, {26731,26732,26733 ,15420,15421,15422 ,0,0,0}, + {26729,26730,26687 ,15418,15419,15376 ,0,0,0}, {26684,26734,26688 ,15373,15423,15377 ,0,0,0}, + {26730,26686,26685 ,15419,15375,15374 ,0,0,0}, {26688,26733,26689 ,15377,15422,15378 ,0,0,0}, + {26686,26734,26684 ,15375,15423,15373 ,0,0,0}, {26690,26689,26735 ,15379,15378,15424 ,0,0,0}, + {26734,26733,26688 ,15423,15422,15377 ,0,0,0}, {26643,26690,26736 ,15332,15379,15425 ,0,0,0}, + {26689,26733,26735 ,15378,15422,15424 ,0,0,0}, {26691,26643,26737 ,15380,15332,15426 ,0,0,0}, + {26690,26735,26736 ,15379,15424,15425 ,0,0,0}, {26695,26691,26738 ,15384,15380,15427 ,0,0,0}, + {26643,26736,26737 ,15332,15425,15426 ,0,0,0}, {26693,26695,26739 ,15382,15384,15428 ,0,0,0}, + {26737,26738,26691 ,15426,15427,15380 ,0,0,0}, {26740,26696,26692 ,15429,15385,15381 ,0,0,0}, + {26738,26739,26695 ,15427,15428,15384 ,0,0,0}, {26741,26742,26743 ,15430,15431,15432 ,0,0,0}, + {26739,26694,26693 ,15428,15383,15382 ,0,0,0}, {26696,26744,26697 ,15385,15433,15386 ,0,0,0}, + {26694,26740,26692 ,15383,15429,15381 ,0,0,0}, {26697,26743,26698 ,15386,15432,15387 ,0,0,0}, + {26740,26744,26696 ,15429,15433,15385 ,0,0,0}, {26698,26745,26651 ,15387,15434,15340 ,0,0,0}, + {26744,26743,26697 ,15433,15432,15386 ,0,0,0}, {26651,26515,26514 ,15340,15196,15195 ,0,0,0}, + {26743,26745,26698 ,15432,15434,15387 ,0,0,0}, {26514,26513,26699 ,15195,15194,15388 ,0,0,0}, + {26515,26651,26745 ,15196,15340,15434 ,0,0,0}, {26700,26746,26523 ,15389,15435,15204 ,0,0,0}, + {26747,26748,26700 ,15436,15437,15389 ,0,0,0}, {26511,26514,26699 ,15191,15195,15388 ,0,0,0}, + {26699,26746,26700 ,15388,15435,15389 ,0,0,0}, {26701,26700,26748 ,15390,15389,15437 ,0,0,0}, + {26469,26468,26654 ,15112,15111,15343 ,0,0,0}, {26136,26470,26132 ,15438,15115,15114 ,0,0,0}, + {26705,26703,26463 ,15394,15392,15106 ,0,0,0}, {26654,26704,26653 ,15343,15393,15342 ,0,0,0}, + {26470,26749,26704 ,15115,15439,15393 ,0,0,0}, {26706,26705,26750 ,15395,15394,15440 ,0,0,0}, + {26703,26749,26463 ,15392,15439,15106 ,0,0,0}, {26751,26750,26752 ,15441,15440,15442 ,0,0,0}, + {26705,26463,26750 ,15394,15106,15440 ,0,0,0}, {26751,26753,26707 ,15441,15443,15396 ,0,0,0}, + {26707,26706,26751 ,15396,15395,15441 ,0,0,0}, {26753,26754,26708 ,15443,15444,15397 ,0,0,0}, + {26708,26707,26753 ,15397,15396,15443 ,0,0,0}, {26754,26755,26709 ,15444,15445,15398 ,0,0,0}, + {26709,26708,26754 ,15398,15397,15444 ,0,0,0}, {26755,26756,26710 ,15445,15446,15399 ,0,0,0}, + {26710,26709,26755 ,15399,15398,15445 ,0,0,0}, {26756,26757,26711 ,15446,15447,15400 ,0,0,0}, + {26711,26710,26756 ,15400,15399,15446 ,0,0,0}, {26757,26758,26662 ,15447,15448,15351 ,0,0,0}, + {26662,26711,26757 ,15351,15400,15447 ,0,0,0}, {26758,26712,26715 ,15448,15401,15404 ,0,0,0}, + {26662,26758,26715 ,15351,15448,15404 ,0,0,0}, {25179,26759,26760 ,15449,15450,15451 ,0,0,0}, + {26715,26712,26714 ,15404,15401,15403 ,0,0,0}, {26716,26761,26717 ,15405,15452,15406 ,0,0,0}, + {26714,26713,26716 ,15403,15402,15405 ,0,0,0}, {26762,26761,26760 ,15453,15452,15451 ,0,0,0}, + {26713,26761,26716 ,15402,15452,15405 ,0,0,0}, {26762,26763,26718 ,15453,15454,15407 ,0,0,0}, + {26718,26717,26762 ,15407,15406,15453 ,0,0,0}, {26763,26764,26719 ,15454,15455,15408 ,0,0,0}, + {26719,26718,26763 ,15408,15407,15454 ,0,0,0}, {26764,26765,26720 ,15455,15456,15409 ,0,0,0}, + {26720,26719,26764 ,15409,15408,15455 ,0,0,0}, {26765,26670,26721 ,15456,15359,15410 ,0,0,0}, + {26720,26765,26721 ,15409,15456,15410 ,0,0,0}, {26766,26767,26768 ,15457,15458,15459 ,0,0,0}, + {26721,26670,26669 ,15410,15359,15358 ,0,0,0}, {26668,26767,26722 ,15357,15458,15411 ,0,0,0}, + {26669,26668,26722 ,15358,15357,15411 ,0,0,0}, {26767,26769,26723 ,15458,15460,15412 ,0,0,0}, + {26723,26722,26767 ,15412,15411,15458 ,0,0,0}, {26769,26770,26724 ,15460,15461,15413 ,0,0,0}, + {26724,26723,26769 ,15413,15412,15460 ,0,0,0}, {26770,26771,26725 ,15461,15462,15414 ,0,0,0}, + {26725,26724,26770 ,15414,15413,15461 ,0,0,0}, {26771,26678,26726 ,15462,15367,15415 ,0,0,0}, + {26725,26771,26726 ,15414,15462,15415 ,0,0,0}, {26772,25170,26773 ,15463,15464,15465 ,0,0,0}, + {26726,26678,26677 ,15415,15367,15366 ,0,0,0}, {26728,26727,26774 ,15417,15416,15466 ,0,0,0}, + {26677,26676,26727 ,15366,15365,15416 ,0,0,0}, {26775,26774,26772 ,15467,15466,15463 ,0,0,0}, + {26727,26676,26774 ,15416,15365,15466 ,0,0,0}, {26775,26776,26729 ,15467,15468,15418 ,0,0,0}, + {26729,26728,26775 ,15418,15417,15467 ,0,0,0}, {26776,26777,26730 ,15468,15469,15419 ,0,0,0}, + {26730,26729,26776 ,15419,15418,15468 ,0,0,0}, {26777,26778,26686 ,15469,15470,15375 ,0,0,0}, + {26686,26730,26777 ,15375,15419,15469 ,0,0,0}, {26778,26731,26734 ,15470,15420,15423 ,0,0,0}, + {26686,26778,26734 ,15375,15470,15423 ,0,0,0}, {26779,26780,26781 ,15471,15472,15473 ,0,0,0}, + {26734,26731,26733 ,15423,15420,15422 ,0,0,0}, {26732,26780,26735 ,15421,15472,15424 ,0,0,0}, + {26733,26732,26735 ,15422,15421,15424 ,0,0,0}, {26780,26782,26736 ,15472,15474,15425 ,0,0,0}, + {26736,26735,26780 ,15425,15424,15472 ,0,0,0}, {26782,26783,26737 ,15474,15475,15426 ,0,0,0}, + {26737,26736,26782 ,15426,15425,15474 ,0,0,0}, {26783,26784,26738 ,15475,15476,15427 ,0,0,0}, + {26738,26737,26783 ,15427,15426,15475 ,0,0,0}, {26784,26785,26739 ,15476,15477,15428 ,0,0,0}, + {26739,26738,26784 ,15428,15427,15476 ,0,0,0}, {26785,26786,26694 ,15477,15478,15383 ,0,0,0}, + {26694,26739,26785 ,15383,15428,15477 ,0,0,0}, {26786,26787,26740 ,15478,15479,15429 ,0,0,0}, + {26740,26694,26786 ,15429,15383,15478 ,0,0,0}, {26787,26741,26744 ,15479,15430,15433 ,0,0,0}, + {26740,26787,26744 ,15429,15479,15433 ,0,0,0}, {26745,26742,26788 ,15434,15431,15480 ,0,0,0}, + {26744,26741,26743 ,15433,15430,15432 ,0,0,0}, {26520,26513,26515 ,15201,15194,15196 ,0,0,0}, + {26743,26742,26745 ,15432,15431,15434 ,0,0,0}, {26519,26746,26513 ,15200,15435,15194 ,0,0,0}, + {26745,26788,26515 ,15434,15480,15196 ,0,0,0}, {26527,26521,26789 ,15208,15202,15481 ,0,0,0}, + {26788,26520,26515 ,15480,15201,15196 ,0,0,0}, {26519,26790,26791 ,15200,15482,15483 ,0,0,0}, + {26523,26747,26700 ,15204,15436,15389 ,0,0,0}, {26699,26513,26746 ,15388,15194,15435 ,0,0,0}, + {26523,26746,26791 ,15204,15435,15483 ,0,0,0}, {26522,26747,26523 ,15203,15436,15204 ,0,0,0}, + {26468,26470,26704 ,15111,15115,15393 ,0,0,0}, {26136,26138,26459 ,15438,15099,15102 ,0,0,0}, + {26749,26459,26464 ,15439,15102,15107 ,0,0,0}, {26704,26749,26703 ,15393,15439,15392 ,0,0,0}, + {26463,26749,26464 ,15106,15439,15107 ,0,0,0}, {26462,26752,26750 ,15105,15442,15440 ,0,0,0}, + {26750,26463,26462 ,15440,15106,15105 ,0,0,0}, {26752,26792,26751 ,15442,15484,15441 ,0,0,0}, + {26793,26753,26792 ,15485,15443,15484 ,0,0,0}, {26706,26750,26751 ,15395,15440,15441 ,0,0,0}, + {26753,26751,26792 ,15443,15441,15484 ,0,0,0}, {26794,26754,26793 ,15486,15444,15485 ,0,0,0}, + {26754,26753,26793 ,15444,15443,15485 ,0,0,0}, {26795,26755,26794 ,15487,15445,15486 ,0,0,0}, + {26755,26754,26794 ,15445,15444,15486 ,0,0,0}, {26796,26756,26795 ,15488,15446,15487 ,0,0,0}, + {26756,26755,26795 ,15446,15445,15487 ,0,0,0}, {26797,26757,26796 ,15489,15447,15488 ,0,0,0}, + {26757,26756,26796 ,15447,15446,15488 ,0,0,0}, {26798,26758,26797 ,15490,15448,15489 ,0,0,0}, + {26758,26757,26797 ,15448,15447,15489 ,0,0,0}, {26799,26712,26798 ,15491,15401,15490 ,0,0,0}, + {26712,26758,26798 ,15401,15448,15490 ,0,0,0}, {26800,26713,26799 ,15492,15402,15491 ,0,0,0}, + {26713,26712,26799 ,15402,15401,15491 ,0,0,0}, {26760,26761,26800 ,15451,15452,15492 ,0,0,0}, + {26713,26800,26761 ,15402,15492,15452 ,0,0,0}, {26760,26759,26762 ,15451,15450,15453 ,0,0,0}, + {26801,26763,26759 ,15493,15454,15450 ,0,0,0}, {26717,26761,26762 ,15406,15452,15453 ,0,0,0}, + {26763,26762,26759 ,15454,15453,15450 ,0,0,0}, {26802,26764,26801 ,15494,15455,15493 ,0,0,0}, + {26764,26763,26801 ,15455,15454,15493 ,0,0,0}, {26803,26765,26802 ,15495,15456,15494 ,0,0,0}, + {26765,26764,26802 ,15456,15455,15494 ,0,0,0}, {26804,26670,26803 ,15496,15359,15495 ,0,0,0}, + {26670,26765,26803 ,15359,15456,15495 ,0,0,0}, {26768,26668,26804 ,15459,15357,15496 ,0,0,0}, + {26668,26670,26804 ,15357,15359,15496 ,0,0,0}, {26768,25087,26766 ,15459,15497,15457 ,0,0,0}, + {26668,26768,26767 ,15357,15459,15458 ,0,0,0}, {26805,26769,26766 ,15498,15460,15457 ,0,0,0}, + {26769,26767,26766 ,15460,15458,15457 ,0,0,0}, {26806,26770,26805 ,15499,15461,15498 ,0,0,0}, + {26770,26769,26805 ,15461,15460,15498 ,0,0,0}, {26807,26771,26806 ,15500,15462,15499 ,0,0,0}, + {26771,26770,26806 ,15462,15461,15499 ,0,0,0}, {26808,26678,26807 ,15501,15367,15500 ,0,0,0}, + {26678,26771,26807 ,15367,15462,15500 ,0,0,0}, {26809,26676,26808 ,15502,15365,15501 ,0,0,0}, + {26676,26678,26808 ,15365,15367,15501 ,0,0,0}, {26772,26774,26809 ,15463,15466,15502 ,0,0,0}, + {26676,26809,26774 ,15365,15502,15466 ,0,0,0}, {26772,26773,26775 ,15463,15465,15467 ,0,0,0}, + {26810,26776,26773 ,15503,15468,15465 ,0,0,0}, {26728,26774,26775 ,15417,15466,15467 ,0,0,0}, + {26776,26775,26773 ,15468,15467,15465 ,0,0,0}, {26811,26777,26810 ,15504,15469,15503 ,0,0,0}, + {26777,26776,26810 ,15469,15468,15503 ,0,0,0}, {26812,26778,26811 ,15505,15470,15504 ,0,0,0}, + {26778,26777,26811 ,15470,15469,15504 ,0,0,0}, {26813,26731,26812 ,15506,15420,15505 ,0,0,0}, + {26731,26778,26812 ,15420,15470,15505 ,0,0,0}, {26781,26732,26813 ,15473,15421,15506 ,0,0,0}, + {26732,26731,26813 ,15421,15420,15506 ,0,0,0}, {26781,25109,26779 ,15473,15507,15471 ,0,0,0}, + {26732,26781,26780 ,15421,15473,15472 ,0,0,0}, {26814,26782,26779 ,15508,15474,15471 ,0,0,0}, + {26782,26780,26779 ,15474,15472,15471 ,0,0,0}, {26815,26783,26814 ,15509,15475,15508 ,0,0,0}, + {26783,26782,26814 ,15475,15474,15508 ,0,0,0}, {26816,26784,26815 ,15510,15476,15509 ,0,0,0}, + {26784,26783,26815 ,15476,15475,15509 ,0,0,0}, {26817,26785,26816 ,15511,15477,15510 ,0,0,0}, + {26785,26784,26816 ,15477,15476,15510 ,0,0,0}, {26818,26786,26817 ,15512,15478,15511 ,0,0,0}, + {26786,26785,26817 ,15478,15477,15511 ,0,0,0}, {26819,26787,26818 ,15513,15479,15512 ,0,0,0}, + {26787,26786,26818 ,15479,15478,15512 ,0,0,0}, {26820,26741,26819 ,15514,15430,15513 ,0,0,0}, + {26741,26787,26819 ,15430,15479,15513 ,0,0,0}, {26821,26742,26820 ,15515,15431,15514 ,0,0,0}, + {26742,26741,26820 ,15431,15430,15514 ,0,0,0}, {26822,26788,26821 ,15516,15480,15515 ,0,0,0}, + {26788,26742,26821 ,15480,15431,15515 ,0,0,0}, {26823,26520,26822 ,15517,15201,15516 ,0,0,0}, + {26520,26788,26822 ,15201,15480,15516 ,0,0,0}, {26823,26790,26519 ,15517,15482,15200 ,0,0,0}, + {26519,26520,26823 ,15200,15201,15517 ,0,0,0}, {26790,26789,26791 ,15482,15481,15483 ,0,0,0}, + {26523,26791,26521 ,15204,15483,15202 ,0,0,0}, {26746,26519,26791 ,15435,15200,15483 ,0,0,0}, + {26789,26521,26791 ,15481,15202,15483 ,0,0,0}, {26522,26521,26528 ,15203,15202,15209 ,0,0,0}, + {26749,26470,26459 ,15439,15115,15102 ,0,0,0}, {26459,26470,26136 ,15102,15115,15438 ,0,0,0}, + {25191,25187,26464 ,15302,15518,15107 ,0,0,0}, {26464,25187,26462 ,15107,15518,15105 ,0,0,0}, + {25187,25186,26462 ,15518,15519,15105 ,0,0,0}, {26462,25186,26752 ,15105,15519,15442 ,0,0,0}, + {25186,25185,26752 ,15519,15520,15442 ,0,0,0}, {26752,25185,26792 ,15442,15520,15484 ,0,0,0}, + {25185,25048,26792 ,15520,15521,15484 ,0,0,0}, {26792,25048,26793 ,15484,15521,15485 ,0,0,0}, + {25048,25038,26793 ,15521,15522,15485 ,0,0,0}, {26793,25038,26794 ,15485,15522,15486 ,0,0,0}, + {25038,25071,26794 ,15522,15523,15486 ,0,0,0}, {26794,25071,26795 ,15486,15523,15487 ,0,0,0}, + {25071,25068,26795 ,15523,15524,15487 ,0,0,0}, {26795,25068,26796 ,15487,15524,15488 ,0,0,0}, + {25068,25073,26796 ,15524,15525,15488 ,0,0,0}, {25073,25076,26797 ,15525,15526,15489 ,0,0,0}, + {25073,26797,26796 ,15525,15489,15488 ,0,0,0}, {25076,25043,26798 ,15526,15527,15490 ,0,0,0}, + {25076,26798,26797 ,15526,15490,15489 ,0,0,0}, {25043,25042,26799 ,15527,15528,15491 ,0,0,0}, + {25043,26799,26798 ,15527,15491,15490 ,0,0,0}, {25042,25078,26800 ,15528,15529,15492 ,0,0,0}, + {25042,26800,26799 ,15528,15492,15491 ,0,0,0}, {25078,25180,26760 ,15529,15530,15451 ,0,0,0}, + {25078,26760,26800 ,15529,15451,15492 ,0,0,0}, {25179,26760,25180 ,15449,15451,15530 ,0,0,0}, + {25179,25081,26759 ,15449,15531,15450 ,0,0,0}, {26759,25081,26801 ,15450,15531,15493 ,0,0,0}, + {25081,25086,26801 ,15531,15532,15493 ,0,0,0}, {26801,25086,26802 ,15493,15532,15494 ,0,0,0}, + {25086,25084,26802 ,15532,15533,15494 ,0,0,0}, {25084,25083,26803 ,15533,15534,15495 ,0,0,0}, + {25084,26803,26802 ,15533,15495,15494 ,0,0,0}, {25083,25178,26804 ,15534,15535,15496 ,0,0,0}, + {25083,26804,26803 ,15534,15496,15495 ,0,0,0}, {25178,25087,26768 ,15535,15497,15459 ,0,0,0}, + {25178,26768,26804 ,15535,15459,15496 ,0,0,0}, {25087,25177,26766 ,15497,15536,15457 ,0,0,0}, + {25177,25173,26766 ,15536,15537,15457 ,0,0,0}, {26766,25173,26805 ,15457,15537,15498 ,0,0,0}, + {25173,25091,26805 ,15537,15538,15498 ,0,0,0}, {26805,25091,26806 ,15498,15538,15499 ,0,0,0}, + {25091,25093,26806 ,15538,15539,15499 ,0,0,0}, {25093,25098,26807 ,15539,15540,15500 ,0,0,0}, + {25093,26807,26806 ,15539,15500,15499 ,0,0,0}, {25098,25096,26808 ,15540,15541,15501 ,0,0,0}, + {25098,26808,26807 ,15540,15501,15500 ,0,0,0}, {25096,25095,26809 ,15541,15542,15502 ,0,0,0}, + {25096,26809,26808 ,15541,15502,15501 ,0,0,0}, {25095,25171,26772 ,15542,15543,15463 ,0,0,0}, + {25095,26772,26809 ,15542,15463,15502 ,0,0,0}, {25170,26772,25171 ,15464,15463,15543 ,0,0,0}, + {25170,25100,26773 ,15464,15544,15465 ,0,0,0}, {26773,25100,26810 ,15465,15544,15503 ,0,0,0}, + {25100,25107,26810 ,15544,15545,15503 ,0,0,0}, {25107,25106,26811 ,15545,15546,15504 ,0,0,0}, + {25107,26811,26810 ,15545,15504,15503 ,0,0,0}, {25106,25105,26812 ,15546,15547,15505 ,0,0,0}, + {25106,26812,26811 ,15546,15505,15504 ,0,0,0}, {25105,25167,26813 ,15547,15548,15506 ,0,0,0}, + {25105,26813,26812 ,15547,15506,15505 ,0,0,0}, {25167,25109,26781 ,15548,15507,15473 ,0,0,0}, + {25167,26781,26813 ,15548,15473,15506 ,0,0,0}, {25109,25108,26779 ,15507,15549,15471 ,0,0,0}, + {25108,25114,26779 ,15549,15550,15471 ,0,0,0}, {26779,25114,26814 ,15471,15550,15508 ,0,0,0}, + {25114,25113,26814 ,15550,15551,15508 ,0,0,0}, {26814,25113,26815 ,15508,15551,15509 ,0,0,0}, + {25113,25118,26815 ,15551,15552,15509 ,0,0,0}, {26815,25118,26816 ,15509,15552,15510 ,0,0,0}, + {25118,25116,26816 ,15552,15553,15510 ,0,0,0}, {25116,25124,26817 ,15553,15554,15511 ,0,0,0}, + {25116,26817,26816 ,15553,15511,15510 ,0,0,0}, {25124,25120,26818 ,15554,15555,15512 ,0,0,0}, + {25124,26818,26817 ,15554,15512,15511 ,0,0,0}, {25120,25122,26819 ,15555,15556,15513 ,0,0,0}, + {25120,26819,26818 ,15555,15513,15512 ,0,0,0}, {25122,25125,26820 ,15556,15557,15514 ,0,0,0}, + {25122,26820,26819 ,15556,15514,15513 ,0,0,0}, {25125,25127,26821 ,15557,15558,15515 ,0,0,0}, + {25125,26821,26820 ,15557,15515,15514 ,0,0,0}, {25127,25132,26822 ,15558,15559,15516 ,0,0,0}, + {25127,26822,26821 ,15558,15516,15515 ,0,0,0}, {25132,25138,26823 ,15559,15560,15517 ,0,0,0}, + {25132,26823,26822 ,15559,15517,15516 ,0,0,0}, {25138,25139,26790 ,15560,15561,15482 ,0,0,0}, + {25138,26790,26823 ,15560,15482,15517 ,0,0,0}, {25139,25137,26789 ,15561,15562,15481 ,0,0,0}, + {25139,26789,26790 ,15561,15481,15482 ,0,0,0}, {25137,25131,26527 ,15562,15563,15208 ,0,0,0}, + {25137,26527,26789 ,15562,15208,15481 ,0,0,0}, {26527,25131,25130 ,15208,15563,13637 ,0,0,0}, + {26360,26066,26087 ,15564,15564,15564 ,0,0,0}, {25696,26083,25692 ,15564,15564,15564 ,0,0,0}, + {26082,26087,26148 ,15564,15564,15564 ,0,0,0}, {26360,26087,26067 ,15564,15564,15564 ,0,0,0}, + {26082,26148,26225 ,15564,15564,15564 ,0,0,0}, {26067,26082,25697 ,15564,15564,15564 ,0,0,0}, + {26087,26082,26067 ,15564,15564,15564 ,0,0,0}, {25557,25692,26083 ,15564,15564,15564 ,0,0,0}, + {25696,26080,26077 ,15564,15564,15564 ,0,0,0}, {25563,25572,25907 ,15564,15564,15564 ,0,0,0}, + {25698,25557,26083 ,15564,15564,15564 ,0,0,0}, {25699,25698,25563 ,15564,15564,15564 ,0,0,0}, + {25698,25699,25688 ,15564,15564,15564 ,0,0,0}, {25570,25563,25907 ,15564,15564,15564 ,0,0,0}, + {25571,25572,25698 ,15564,15564,15564 ,0,0,0}, {25572,25563,25698 ,15564,15564,15564 ,0,0,0}, + {26085,25698,26083 ,15564,15564,15564 ,0,0,0}, {26085,25571,25698 ,15564,15564,15564 ,0,0,0}, + {26083,25696,26077 ,15564,15564,15564 ,0,0,0}, {26080,25696,26082 ,15564,15564,15564 ,0,0,0}, + {25697,26082,25695 ,15564,15564,15564 ,0,0,0}, {25696,25695,26082 ,15564,15564,15564 ,0,0,0}, + {26747,26522,26528 ,15565,15565,15565 ,0,0,0}, {26576,26613,25326 ,15565,15565,15565 ,0,0,0}, + {26532,26748,26528 ,15565,15565,15565 ,0,0,0}, {26652,26702,25242 ,15565,15565,15565 ,0,0,0}, + {26701,26748,26702 ,15565,15565,15565 ,0,0,0}, {26748,26532,25130 ,15565,15565,15565 ,0,0,0}, + {26747,26528,26748 ,15565,15565,15565 ,0,0,0}, {25242,26702,26748 ,15565,15565,15565 ,0,0,0}, + {26748,25130,25242 ,15565,15565,15565 ,0,0,0}, {25241,26652,25242 ,15565,15565,15565 ,0,0,0}, + {25241,25284,26652 ,15565,15565,15565 ,0,0,0}, {26613,26652,25326 ,15565,15565,15565 ,0,0,0}, + {25284,25326,26652 ,15565,15565,15565 ,0,0,0}, {26577,26576,25326 ,15565,15565,15565 ,0,0,0}, + {25370,25412,25371 ,15565,15565,15565 ,0,0,0}, {25371,26577,25326 ,15565,15565,15565 ,0,0,0}, + {26577,25371,25412 ,15565,15565,15565 ,0,0,0}, {25163,25411,25158 ,15565,15565,15565 ,0,0,0}, + {26577,25412,25164 ,15565,15565,15565 ,0,0,0}, {25412,25163,25162 ,15565,15565,15565 ,0,0,0}, + {25163,25412,25411 ,15565,15565,15565 ,0,0,0}, {25412,25162,25164 ,15565,15565,15565 ,0,0,0} +// Landegestell.prt + , {26824,26825,26826 ,15055,15013,15566 ,0,0,0}, {26827,26828,26829 ,15567,15049,15050 ,0,0,0}, + {26830,26831,26832 ,15568,15569,15570 ,0,0,0}, {26833,26825,26834 ,15571,15013,15572 ,0,0,0}, + {26835,26832,26836 ,15573,15570,15574 ,0,0,0}, {26837,26838,26839 ,15575,15576,15015 ,0,0,0}, + {26840,26841,26842 ,15577,15578,14934 ,0,0,0}, {26843,26836,26831 ,15579,15574,15569 ,0,0,0}, + {26844,26845,26846 ,15580,15581,15582 ,0,0,0}, {26840,26847,26846 ,15577,15583,15582 ,0,0,0}, + {26848,26849,26850 ,15584,15585,15586 ,0,0,0}, {26850,26849,26845 ,15586,15585,15581 ,0,0,0}, + {26851,26850,26852 ,15587,15586,15588 ,0,0,0}, {26834,26825,26824 ,15572,15013,15055 ,0,0,0}, + {26852,26853,26851 ,15588,15589,15587 ,0,0,0}, {26854,26855,26856 ,15590,15591,15592 ,0,0,0}, + {26826,26857,26824 ,15566,15593,15055 ,0,0,0}, {26858,26859,26856 ,15594,15595,15592 ,0,0,0}, + {26860,26861,26858 ,15596,15597,15594 ,0,0,0}, {26861,26862,26858 ,15597,15598,15594 ,0,0,0}, + {26856,26859,26854 ,15592,15595,15590 ,0,0,0}, {26863,26864,26828 ,15599,15600,15049 ,0,0,0}, + {26865,26866,26867 ,15601,15602,15603 ,0,0,0}, {26863,26868,26864 ,15599,15604,15600 ,0,0,0}, + {26869,26870,26871 ,15043,15044,15605 ,0,0,0}, {26866,26872,26867 ,15602,15606,15603 ,0,0,0}, + {26873,26874,26875 ,15607,14962,14960 ,0,0,0}, {26869,26871,26876 ,15043,15605,15608 ,0,0,0}, + {26877,26878,26879 ,15039,15609,15610 ,0,0,0}, {26878,26877,26880 ,15609,15039,15611 ,0,0,0}, + {26881,26882,26883 ,15035,15612,15613 ,0,0,0}, {26884,26885,26882 ,15614,15615,15612 ,0,0,0}, + {26886,26887,26888 ,15033,14956,15616 ,0,0,0}, {26881,26883,26889 ,15035,15613,14954 ,0,0,0}, + {26890,26891,26892 ,15617,15030,15031 ,0,0,0}, {26886,26888,26893 ,15033,15616,15032 ,0,0,0}, + {26894,26895,26896 ,15618,15619,14948 ,0,0,0}, {26897,26891,26890 ,15620,15030,15617 ,0,0,0}, + {26898,26899,26900 ,15621,15622,15027 ,0,0,0}, {26900,26896,26898 ,15027,14948,15621 ,0,0,0}, + {26901,26902,26903 ,15623,15624,14988 ,0,0,0}, {26904,26899,26905 ,15025,15622,14989 ,0,0,0}, + {26906,26907,26908 ,15625,15626,15627 ,0,0,0}, {26909,26906,26910 ,15628,15625,15629 ,0,0,0}, + {26911,26912,26913 ,15630,15631,15019 ,0,0,0}, {26914,26911,26908 ,15632,15630,15627 ,0,0,0}, + {26915,26916,26917 ,15633,15634,15635 ,0,0,0}, {26918,26913,26919 ,15018,15019,15636 ,0,0,0}, + {26920,26921,26922 ,14607,15637,15638 ,0,0,0}, {26917,26923,26915 ,15635,15639,15633 ,0,0,0}, + {26924,26920,26925 ,15017,14607,15640 ,0,0,0}, {26915,26923,26926 ,15633,15639,15641 ,0,0,0}, + {26927,26924,26918 ,15642,15017,15018 ,0,0,0}, {26920,26924,26927 ,14607,15017,15642 ,0,0,0}, + {26928,26929,26930 ,15643,15644,15645 ,0,0,0}, {26931,26914,26932 ,15646,15632,15647 ,0,0,0}, + {26933,26934,26935 ,14890,15648,15649 ,0,0,0}, {26931,26932,26936 ,15646,15647,15650 ,0,0,0}, + {26937,26938,26939 ,15651,15652,15653 ,0,0,0}, {26935,26940,26941 ,15649,15654,15655 ,0,0,0}, + {26942,26943,26939 ,15656,15657,15653 ,0,0,0}, {26944,26945,26946 ,15658,15659,15660 ,0,0,0}, + {26947,26948,26949 ,15661,15662,15663 ,0,0,0}, {26949,26946,26947 ,15663,15660,15661 ,0,0,0}, + {26948,26947,26950 ,15662,15661,15664 ,0,0,0}, {26919,26913,26912 ,15636,15019,15631 ,0,0,0}, + {26920,26926,26925 ,14607,15641,15640 ,0,0,0}, {26914,26908,26907 ,15632,15627,15626 ,0,0,0}, + {26914,26912,26911 ,15632,15631,15630 ,0,0,0}, {26909,26910,26901 ,15628,15629,15623 ,0,0,0}, + {26906,26909,26907 ,15625,15628,15626 ,0,0,0}, {26903,26902,26904 ,14988,15624,15025 ,0,0,0}, + {26910,26902,26901 ,15629,15624,15623 ,0,0,0}, {26903,26904,26905 ,14988,15025,14989 ,0,0,0}, + {26951,26909,26901 ,15665,15628,15623 ,0,0,0}, {26900,26894,26896 ,15027,15618,14948 ,0,0,0}, + {26899,26898,26905 ,15622,15621,14989 ,0,0,0}, {26890,26892,26952 ,15617,15031,15666 ,0,0,0}, + {26953,26897,26954 ,15667,15620,15668 ,0,0,0}, {26896,26895,26954 ,14948,15619,15668 ,0,0,0}, + {26891,26897,26953 ,15030,15620,15667 ,0,0,0}, {26895,26953,26954 ,15619,15667,15668 ,0,0,0}, + {26952,26892,26893 ,15666,15031,15032 ,0,0,0}, {26955,26890,26952 ,15669,15617,15666 ,0,0,0}, + {26893,26888,26952 ,15032,15616,15666 ,0,0,0}, {26889,26887,26956 ,14954,14956,14995 ,0,0,0}, + {26886,26956,26887 ,15033,14995,14956 ,0,0,0}, {26957,26889,26956 ,15670,14954,14995 ,0,0,0}, + {26885,26883,26882 ,15615,15613,15612 ,0,0,0}, {26881,26889,26957 ,15035,14954,15670 ,0,0,0}, + {26884,26958,26885 ,15614,14998,15615 ,0,0,0}, {26879,26878,26958 ,15610,15609,14998 ,0,0,0}, + {26958,26884,26879 ,14998,15614,15610 ,0,0,0}, {26880,26959,26875 ,15611,15040,14960 ,0,0,0}, + {26960,26961,26962 ,15671,15672,15673 ,0,0,0}, {26875,26959,26963 ,14960,15040,15674 ,0,0,0}, + {26959,26880,26877 ,15040,15611,15039 ,0,0,0}, {26964,26876,26874 ,15675,15608,14962 ,0,0,0}, + {26873,26875,26963 ,15607,14960,15674 ,0,0,0}, {26876,26964,26869 ,15608,15675,15043 ,0,0,0}, + {26964,26874,26873 ,15675,14962,15607 ,0,0,0}, {26868,26965,26966 ,15604,15005,15676 ,0,0,0}, + {26870,26872,26967 ,15044,15606,15677 ,0,0,0}, {26871,26870,26967 ,15605,15044,15677 ,0,0,0}, + {26967,26872,26866 ,15677,15606,15602 ,0,0,0}, {26968,26969,26970 ,15678,15679,15680 ,0,0,0}, + {26965,26865,26867 ,15005,15601,15603 ,0,0,0}, {26857,26826,26855 ,15593,15566,15591 ,0,0,0}, + {26868,26865,26965 ,15604,15601,15005 ,0,0,0}, {26868,26966,26864 ,15604,15676,15600 ,0,0,0}, + {26828,26827,26863 ,15049,15567,15599 ,0,0,0}, {26862,26861,26829 ,15598,15597,15050 ,0,0,0}, + {26829,26861,26827 ,15050,15597,15567 ,0,0,0}, {26854,26857,26855 ,15590,15593,15591 ,0,0,0}, + {26862,26859,26858 ,15598,15595,15594 ,0,0,0}, {26839,26971,26972 ,15015,15681,15682 ,0,0,0}, + {26833,26834,26971 ,15571,15572,15681 ,0,0,0}, {26972,26837,26839 ,15682,15575,15015 ,0,0,0}, + {26833,26971,26839 ,15571,15681,15015 ,0,0,0}, {26972,26973,26837 ,15682,15683,15575 ,0,0,0}, + {26974,26975,26841 ,15684,15685,15578 ,0,0,0}, {26837,26973,26976 ,15575,15683,15686 ,0,0,0}, + {26976,26973,26977 ,15686,15683,15687 ,0,0,0}, {26978,26976,26979 ,15688,15686,15689 ,0,0,0}, + {26977,26979,26976 ,15687,15689,15686 ,0,0,0}, {26842,26980,26840 ,14934,14795,15577 ,0,0,0}, + {26981,26978,26979 ,15690,15688,15689 ,0,0,0}, {26982,26981,26979 ,15691,15690,15689 ,0,0,0}, + {26978,26981,26983 ,15688,15690,15692 ,0,0,0}, {26984,26985,26983 ,15693,15694,15692 ,0,0,0}, + {26975,26974,26986 ,15685,15684,15695 ,0,0,0}, {26983,26985,26978 ,15692,15694,15688 ,0,0,0}, + {26984,26974,26985 ,15693,15684,15694 ,0,0,0}, {26978,26987,26976 ,15688,15696,15686 ,0,0,0}, + {26988,26833,26839 ,15697,15571,15015 ,0,0,0}, {26976,26830,26837 ,15686,15568,15575 ,0,0,0}, + {26989,26825,26833 ,15698,15013,15571 ,0,0,0}, {26838,26837,26830 ,15576,15575,15568 ,0,0,0}, + {26990,26826,26825 ,15699,15566,15013 ,0,0,0}, {26988,26839,26838 ,15697,15015,15576 ,0,0,0}, + {26991,26855,26826 ,15700,15591,15566 ,0,0,0}, {26989,26833,26988 ,15698,15571,15697 ,0,0,0}, + {26992,26856,26855 ,15701,15592,15591 ,0,0,0}, {26990,26825,26989 ,15699,15013,15698 ,0,0,0}, + {26993,26858,26856 ,15702,15594,15592 ,0,0,0}, {26826,26990,26991 ,15566,15699,15700 ,0,0,0}, + {26994,26995,26996 ,15703,15704,14972 ,0,0,0}, {26855,26991,26992 ,15591,15700,15701 ,0,0,0}, + {26996,26827,26861 ,14972,15567,15597 ,0,0,0}, {26856,26992,26993 ,15592,15701,15702 ,0,0,0}, + {26997,26863,26827 ,15705,15599,15567 ,0,0,0}, {26858,26993,26860 ,15594,15702,15596 ,0,0,0}, + {26998,26868,26863 ,15706,15604,15599 ,0,0,0}, {26861,26860,26996 ,15597,15596,14972 ,0,0,0}, + {26999,26865,26868 ,15707,15601,15604 ,0,0,0}, {26827,26996,26997 ,15567,14972,15705 ,0,0,0}, + {27000,26866,26865 ,15708,15602,15601 ,0,0,0}, {26998,26863,26997 ,15706,15599,15705 ,0,0,0}, + {27001,26967,26866 ,15709,15677,15602 ,0,0,0}, {26999,26868,26998 ,15707,15604,15706 ,0,0,0}, + {27002,26871,26967 ,15710,15605,15677 ,0,0,0}, {26865,26999,27000 ,15601,15707,15708 ,0,0,0}, + {26969,26876,26871 ,15679,15608,15605 ,0,0,0}, {26866,27000,27001 ,15602,15708,15709 ,0,0,0}, + {27003,26874,26876 ,15711,14962,15608 ,0,0,0}, {26967,27001,27002 ,15677,15709,15710 ,0,0,0}, + {27004,26875,26874 ,15712,14960,14962 ,0,0,0}, {26871,27002,26969 ,15605,15710,15679 ,0,0,0}, + {27005,26880,26875 ,15713,15611,14960 ,0,0,0}, {27003,26876,26969 ,15711,15608,15679 ,0,0,0}, + {27006,26878,26880 ,15714,15609,15611 ,0,0,0}, {27004,26874,27003 ,15712,14962,15711 ,0,0,0}, + {27007,26958,26878 ,15715,14998,15609 ,0,0,0}, {26875,27004,27005 ,14960,15712,15713 ,0,0,0}, + {26885,26958,26960 ,15615,14998,15671 ,0,0,0}, {26880,27005,27006 ,15611,15713,15714 ,0,0,0}, + {27008,26883,26885 ,15716,15613,15615 ,0,0,0}, {26878,27006,27007 ,15609,15714,15715 ,0,0,0}, + {27009,26889,26883 ,14955,14954,15613 ,0,0,0}, {26958,27007,26960 ,14998,15715,15671 ,0,0,0}, + {27010,26887,26889 ,15717,14956,14954 ,0,0,0}, {27008,26885,26960 ,15716,15615,15671 ,0,0,0}, + {27011,26888,26887 ,15718,15616,14956 ,0,0,0}, {27009,26883,27008 ,14955,15613,15716 ,0,0,0}, + {27012,26952,26888 ,15719,15666,15616 ,0,0,0}, {26889,27009,27010 ,14954,14955,15717 ,0,0,0}, + {27013,27014,27015 ,14854,15720,15721 ,0,0,0}, {26887,27010,27011 ,14956,15717,15718 ,0,0,0}, + {27016,26897,26890 ,15722,15620,15617 ,0,0,0}, {26888,27011,27012 ,15616,15718,15719 ,0,0,0}, + {27017,26954,26897 ,15723,15668,15620 ,0,0,0}, {26952,27012,26955 ,15666,15719,15669 ,0,0,0}, + {27018,26896,26954 ,15724,14948,15668 ,0,0,0}, {26890,26955,27016 ,15617,15669,15722 ,0,0,0}, + {27019,26898,26896 ,15725,15621,14948 ,0,0,0}, {27017,26897,27016 ,15723,15620,15722 ,0,0,0}, + {27020,26905,26898 ,15726,14989,15621 ,0,0,0}, {27018,26954,27017 ,15724,15668,15723 ,0,0,0}, + {27021,26903,26905 ,15727,14988,14989 ,0,0,0}, {27019,26896,27018 ,15725,14948,15724 ,0,0,0}, + {27022,26901,26903 ,15728,15623,14988 ,0,0,0}, {26898,27019,27020 ,15621,15725,15726 ,0,0,0}, + {26909,27023,26907 ,15628,15729,15626 ,0,0,0}, {26905,27020,27021 ,14989,15726,15727 ,0,0,0}, + {26932,27024,26936 ,15647,15730,15650 ,0,0,0}, {26903,27021,27022 ,14988,15727,15728 ,0,0,0}, + {26932,26914,26907 ,15647,15632,15626 ,0,0,0}, {26901,27022,26951 ,15623,15728,15665 ,0,0,0}, + {26931,26912,26914 ,15646,15631,15632 ,0,0,0}, {26909,26951,27023 ,15628,15665,15729 ,0,0,0}, + {26919,26912,27025 ,15636,15631,15731 ,0,0,0}, {27023,26932,26907 ,15729,15647,15626 ,0,0,0}, + {26934,26921,26927 ,15648,15637,15642 ,0,0,0}, {26921,26934,26933 ,15637,15648,14890 ,0,0,0}, + {26919,26927,26918 ,15636,15642,15018 ,0,0,0}, {26912,26931,27025 ,15631,15646,15731 ,0,0,0}, + {26915,26926,27026 ,15633,15641,15732 ,0,0,0}, {26919,26934,26927 ,15636,15648,15642 ,0,0,0}, + {26920,26927,26921 ,14607,15642,15637 ,0,0,0}, {27027,27028,26915 ,15733,15734,15633 ,0,0,0}, + {26925,26926,26923 ,15640,15641,15639 ,0,0,0}, {26922,27026,26926 ,15638,15732,15641 ,0,0,0}, + {26916,26915,27028 ,15634,15633,15734 ,0,0,0}, {26985,26987,26978 ,15694,15696,15688 ,0,0,0}, + {26986,26974,26984 ,15695,15684,15693 ,0,0,0}, {26847,27029,26846 ,15583,15735,15582 ,0,0,0}, + {26987,26830,26976 ,15696,15568,15686 ,0,0,0}, {26985,27030,26987 ,15694,15736,15696 ,0,0,0}, + {26838,26832,27031 ,15576,15570,15737 ,0,0,0}, {26831,26830,26987 ,15569,15568,15696 ,0,0,0}, + {26988,27031,27032 ,15697,15737,15738 ,0,0,0}, {26832,26838,26830 ,15570,15576,15568 ,0,0,0}, + {26989,27032,27033 ,15698,15738,15739 ,0,0,0}, {27031,26988,26838 ,15737,15697,15576 ,0,0,0}, + {26990,27033,27034 ,15699,15739,14927 ,0,0,0}, {27032,26989,26988 ,15738,15698,15697 ,0,0,0}, + {26991,27034,27035 ,15700,14927,14883 ,0,0,0}, {27033,26990,26989 ,15739,15699,15698 ,0,0,0}, + {26992,27035,27036 ,15701,14883,15740 ,0,0,0}, {27034,26991,26990 ,14927,15700,15699 ,0,0,0}, + {26993,27036,27037 ,15702,15740,15741 ,0,0,0}, {27035,26992,26991 ,14883,15701,15700 ,0,0,0}, + {26860,27037,26994 ,15596,15741,15703 ,0,0,0}, {26993,26992,27036 ,15702,15701,15740 ,0,0,0}, + {27038,27039,27040 ,15742,14878,15743 ,0,0,0}, {26860,26993,27037 ,15596,15702,15741 ,0,0,0}, + {26997,26995,27038 ,15705,15704,15742 ,0,0,0}, {26996,26860,26994 ,14972,15596,15703 ,0,0,0}, + {26998,27038,27041 ,15706,15742,15744 ,0,0,0}, {26997,26996,26995 ,15705,14972,15704 ,0,0,0}, + {26999,27041,27042 ,15707,15744,15745 ,0,0,0}, {27038,26998,26997 ,15742,15706,15705 ,0,0,0}, + {27000,27042,27043 ,15708,15745,15746 ,0,0,0}, {27041,26999,26998 ,15744,15707,15706 ,0,0,0}, + {27001,27043,27044 ,15709,15746,15747 ,0,0,0}, {27042,27000,26999 ,15745,15708,15707 ,0,0,0}, + {27002,27044,26970 ,15710,15747,15680 ,0,0,0}, {27001,27000,27043 ,15709,15708,15746 ,0,0,0}, + {27045,27046,27047 ,15748,15749,15750 ,0,0,0}, {27002,27001,27044 ,15710,15709,15747 ,0,0,0}, + {27003,26968,27048 ,15711,15678,15751 ,0,0,0}, {26969,27002,26970 ,15679,15710,15680 ,0,0,0}, + {27004,27048,27049 ,15712,15751,15752 ,0,0,0}, {26968,27003,26969 ,15678,15711,15679 ,0,0,0}, + {27005,27049,27050 ,15713,15752,15753 ,0,0,0}, {27048,27004,27003 ,15751,15712,15711 ,0,0,0}, + {27006,27050,27051 ,15714,15753,15754 ,0,0,0}, {27049,27005,27004 ,15752,15713,15712 ,0,0,0}, + {27007,27051,26961 ,15715,15754,15672 ,0,0,0}, {27006,27005,27050 ,15714,15713,15753 ,0,0,0}, + {27052,27053,27054 ,15755,15756,15757 ,0,0,0}, {27007,27006,27051 ,15715,15714,15754 ,0,0,0}, + {27008,26962,27055 ,15716,15673,15758 ,0,0,0}, {26960,27007,26961 ,15671,15715,15672 ,0,0,0}, + {27009,27055,27056 ,14955,15758,15759 ,0,0,0}, {27008,26960,26962 ,15716,15671,15673 ,0,0,0}, + {27010,27056,27057 ,15717,15759,15760 ,0,0,0}, {27055,27009,27008 ,15758,14955,15716 ,0,0,0}, + {27011,27057,27058 ,15718,15760,15761 ,0,0,0}, {27056,27010,27009 ,15759,15717,14955 ,0,0,0}, + {27012,27058,27059 ,15719,15761,15762 ,0,0,0}, {27057,27011,27010 ,15760,15718,15717 ,0,0,0}, + {26955,27059,27060 ,15669,15762,15763 ,0,0,0}, {27012,27011,27058 ,15719,15718,15761 ,0,0,0}, + {27016,27060,27014 ,15722,15763,15720 ,0,0,0}, {26955,27012,27059 ,15669,15719,15762 ,0,0,0}, + {27017,27014,27061 ,15723,15720,15764 ,0,0,0}, {27016,26955,27060 ,15722,15669,15763 ,0,0,0}, + {27018,27061,27062 ,15724,15764,15765 ,0,0,0}, {27014,27017,27016 ,15720,15723,15722 ,0,0,0}, + {27019,27062,27063 ,15725,15765,15766 ,0,0,0}, {27061,27018,27017 ,15764,15724,15723 ,0,0,0}, + {27020,27063,27064 ,15726,15766,15767 ,0,0,0}, {27062,27019,27018 ,15765,15725,15724 ,0,0,0}, + {27021,27064,27065 ,15727,15767,15768 ,0,0,0}, {27063,27020,27019 ,15766,15726,15725 ,0,0,0}, + {27022,27065,27066 ,15728,15768,14897 ,0,0,0}, {27064,27021,27020 ,15767,15727,15726 ,0,0,0}, + {26951,27066,27067 ,15665,14897,15769 ,0,0,0}, {27065,27022,27021 ,15768,15728,15727 ,0,0,0}, + {27023,27067,27024 ,15729,15769,15730 ,0,0,0}, {26951,27022,27066 ,15665,15728,14897 ,0,0,0}, + {27068,26931,26936 ,15770,15646,15650 ,0,0,0}, {27023,26951,27067 ,15729,15665,15769 ,0,0,0}, + {26941,26937,27069 ,15655,15651,15771 ,0,0,0}, {26932,27023,27024 ,15647,15729,15730 ,0,0,0}, + {27068,26935,27025 ,15770,15649,15731 ,0,0,0}, {26928,26921,26933 ,15643,15637,14890 ,0,0,0}, + {27025,26934,26919 ,15731,15648,15636 ,0,0,0}, {27068,27025,26931 ,15770,15731,15646 ,0,0,0}, + {26941,26933,26935 ,15655,14890,15649 ,0,0,0}, {27025,26935,26934 ,15731,15649,15648 ,0,0,0}, + {27070,27026,26930 ,15772,15732,15645 ,0,0,0}, {27026,27027,26915 ,15732,15733,15633 ,0,0,0}, + {26920,26922,26926 ,14607,15638,15641 ,0,0,0}, {26922,26928,26930 ,15638,15643,15645 ,0,0,0}, + {27070,27027,27026 ,15772,15733,15732 ,0,0,0}, {26974,27030,26985 ,15684,15736,15694 ,0,0,0}, + {26842,26841,26975 ,14934,15578,15685 ,0,0,0}, {26845,26849,27071 ,15581,15585,15773 ,0,0,0}, + {27030,26831,26987 ,15736,15569,15696 ,0,0,0}, {26974,27072,27030 ,15684,14889,15736 ,0,0,0}, + {27073,27074,27075 ,15774,15775,15776 ,0,0,0}, {26843,26831,27030 ,15579,15569,15736 ,0,0,0}, + {26835,27073,27031 ,15573,15774,15737 ,0,0,0}, {26836,26832,26831 ,15574,15570,15569 ,0,0,0}, + {27073,27076,27032 ,15774,14885,15738 ,0,0,0}, {26835,27031,26832 ,15573,15737,15570 ,0,0,0}, + {27076,27077,27033 ,14885,15777,15739 ,0,0,0}, {27073,27032,27031 ,15774,15738,15737 ,0,0,0}, + {27077,27078,27034 ,15777,14882,14927 ,0,0,0}, {27076,27033,27032 ,14885,15739,15738 ,0,0,0}, + {27078,27079,27035 ,14882,15778,14883 ,0,0,0}, {27077,27034,27033 ,15777,14927,15739 ,0,0,0}, + {27079,27080,27036 ,15778,15779,15740 ,0,0,0}, {27078,27035,27034 ,14882,14883,14927 ,0,0,0}, + {27080,27081,27037 ,15779,15780,15741 ,0,0,0}, {27079,27036,27035 ,15778,15740,14883 ,0,0,0}, + {27081,27082,26994 ,15780,15781,15703 ,0,0,0}, {27080,27037,27036 ,15779,15741,15740 ,0,0,0}, + {27082,27039,26995 ,15781,14878,15704 ,0,0,0}, {26994,27037,27081 ,15703,15741,15780 ,0,0,0}, + {27083,27084,27085 ,15782,15783,15784 ,0,0,0}, {26995,26994,27082 ,15704,15703,15781 ,0,0,0}, + {27040,27083,27041 ,15743,15782,15744 ,0,0,0}, {27039,27038,26995 ,14878,15742,15704 ,0,0,0}, + {27083,27086,27042 ,15782,15785,15745 ,0,0,0}, {27040,27041,27038 ,15743,15744,15742 ,0,0,0}, + {27086,27087,27043 ,15785,15786,15746 ,0,0,0}, {27083,27042,27041 ,15782,15745,15744 ,0,0,0}, + {27087,27088,27044 ,15786,14781,15747 ,0,0,0}, {27086,27043,27042 ,15785,15746,15745 ,0,0,0}, + {27088,27089,26970 ,14781,15787,15680 ,0,0,0}, {27087,27044,27043 ,15786,15747,15746 ,0,0,0}, + {26968,27089,27090 ,15678,15787,15788 ,0,0,0}, {26970,27044,27088 ,15680,15747,14781 ,0,0,0}, + {27090,27045,27048 ,15788,15748,15751 ,0,0,0}, {27089,26968,26970 ,15787,15678,15680 ,0,0,0}, + {27045,27091,27049 ,15748,15789,15752 ,0,0,0}, {27090,27048,26968 ,15788,15751,15678 ,0,0,0}, + {27091,27092,27050 ,15789,14868,15753 ,0,0,0}, {27045,27049,27048 ,15748,15752,15751 ,0,0,0}, + {27092,27093,27051 ,14868,15790,15754 ,0,0,0}, {27091,27050,27049 ,15789,15753,15752 ,0,0,0}, + {27093,27094,26961 ,15790,15791,15672 ,0,0,0}, {27092,27051,27050 ,14868,15754,15753 ,0,0,0}, + {27094,27095,26962 ,15791,15792,15673 ,0,0,0}, {26961,27051,27093 ,15672,15754,15790 ,0,0,0}, + {27095,27052,27055 ,15792,15755,15758 ,0,0,0}, {26962,26961,27094 ,15673,15672,15791 ,0,0,0}, + {27052,27096,27056 ,15755,15793,15759 ,0,0,0}, {27095,27055,26962 ,15792,15758,15673 ,0,0,0}, + {27096,27097,27057 ,15793,15794,15760 ,0,0,0}, {27052,27056,27055 ,15755,15759,15758 ,0,0,0}, + {27097,27098,27058 ,15794,15795,15761 ,0,0,0}, {27096,27057,27056 ,15793,15760,15759 ,0,0,0}, + {27098,27099,27059 ,15795,15796,15762 ,0,0,0}, {27097,27058,27057 ,15794,15761,15760 ,0,0,0}, + {27099,27015,27060 ,15796,15721,15763 ,0,0,0}, {27059,27058,27098 ,15762,15761,15795 ,0,0,0}, + {27100,27101,27102 ,15797,15798,15799 ,0,0,0}, {27060,27059,27099 ,15763,15762,15796 ,0,0,0}, + {27013,27100,27061 ,14854,15797,15764 ,0,0,0}, {27015,27014,27060 ,15721,15720,15763 ,0,0,0}, + {27100,27103,27062 ,15797,15800,15765 ,0,0,0}, {27013,27061,27014 ,14854,15764,15720 ,0,0,0}, + {27103,27104,27063 ,15800,15801,15766 ,0,0,0}, {27100,27062,27061 ,15797,15765,15764 ,0,0,0}, + {27104,27105,27064 ,15801,15802,15767 ,0,0,0}, {27103,27063,27062 ,15800,15766,15765 ,0,0,0}, + {27105,27106,27065 ,15802,14848,15768 ,0,0,0}, {27104,27064,27063 ,15801,15767,15766 ,0,0,0}, + {27106,27107,27066 ,14848,15803,14897 ,0,0,0}, {27105,27065,27064 ,15802,15768,15767 ,0,0,0}, + {27107,27108,27067 ,15803,15804,15769 ,0,0,0}, {27106,27066,27065 ,14848,14897,15768 ,0,0,0}, + {27108,27109,27024 ,15804,15805,15730 ,0,0,0}, {27107,27067,27066 ,15803,15769,14897 ,0,0,0}, + {27109,27110,26936 ,15805,15806,15650 ,0,0,0}, {27108,27024,27067 ,15804,15730,15769 ,0,0,0}, + {27110,26940,27068 ,15806,15654,15770 ,0,0,0}, {26936,27024,27109 ,15650,15730,15805 ,0,0,0}, + {27111,26933,26941 ,15807,14890,15655 ,0,0,0}, {26936,27110,27068 ,15650,15806,15770 ,0,0,0}, + {26940,26937,26941 ,15654,15651,15655 ,0,0,0}, {27068,26940,26935 ,15770,15654,15649 ,0,0,0}, + {27112,26930,26929 ,15808,15645,15644 ,0,0,0}, {26922,26930,27026 ,15638,15645,15732 ,0,0,0}, + {26921,26928,26922 ,15637,15643,15638 ,0,0,0}, {27111,26929,26928 ,15807,15644,15643 ,0,0,0}, + {27070,26930,27112 ,15772,15645,15808 ,0,0,0}, {27072,26974,26841 ,14889,15684,15578 ,0,0,0}, + {26847,26840,26980 ,15583,15577,14795 ,0,0,0}, {26843,27113,27114 ,15579,15809,15810 ,0,0,0}, + {27072,26843,27030 ,14889,15579,15736 ,0,0,0}, {27115,27072,26841 ,15811,14889,15578 ,0,0,0}, + {26836,27114,27116 ,15574,15810,15812 ,0,0,0}, {27072,27113,26843 ,14889,15809,15579 ,0,0,0}, + {26835,27116,27074 ,15573,15812,15775 ,0,0,0}, {27114,26836,26843 ,15810,15574,15579 ,0,0,0}, + {27117,27076,27075 ,15813,14885,15776 ,0,0,0}, {27116,26835,26836 ,15812,15573,15574 ,0,0,0}, + {27118,27077,27117 ,15814,15777,15813 ,0,0,0}, {27074,27073,26835 ,15775,15774,15573 ,0,0,0}, + {27119,27120,27121 ,15815,15816,15817 ,0,0,0}, {27075,27076,27073 ,15776,14885,15774 ,0,0,0}, + {27118,27119,27078 ,15814,15815,14882 ,0,0,0}, {27117,27077,27076 ,15813,15777,14885 ,0,0,0}, + {27119,27122,27079 ,15815,15818,15778 ,0,0,0}, {27118,27078,27077 ,15814,14882,15777 ,0,0,0}, + {27122,27123,27080 ,15818,15819,15779 ,0,0,0}, {27119,27079,27078 ,15815,15778,14882 ,0,0,0}, + {27123,27124,27081 ,15819,15820,15780 ,0,0,0}, {27122,27080,27079 ,15818,15779,15778 ,0,0,0}, + {27124,27125,27082 ,15820,15821,15781 ,0,0,0}, {27123,27081,27080 ,15819,15780,15779 ,0,0,0}, + {27039,27125,27126 ,14878,15821,15822 ,0,0,0}, {27124,27082,27081 ,15820,15781,15780 ,0,0,0}, + {27040,27126,27084 ,15743,15822,15783 ,0,0,0}, {27125,27039,27082 ,15821,14878,15781 ,0,0,0}, + {27127,27128,27129 ,15823,15824,15825 ,0,0,0}, {27126,27040,27039 ,15822,15743,14878 ,0,0,0}, + {27085,27127,27086 ,15784,15823,15785 ,0,0,0}, {27084,27083,27040 ,15783,15782,15743 ,0,0,0}, + {27127,27130,27087 ,15823,15826,15786 ,0,0,0}, {27085,27086,27083 ,15784,15785,15782 ,0,0,0}, + {27130,27131,27088 ,15826,15827,14781 ,0,0,0}, {27127,27087,27086 ,15823,15786,15785 ,0,0,0}, + {27089,27131,27132 ,15787,15827,15828 ,0,0,0}, {27130,27088,27087 ,15826,14781,15786 ,0,0,0}, + {27090,27132,27046 ,15788,15828,15749 ,0,0,0}, {27089,27088,27131 ,15787,14781,15827 ,0,0,0}, + {27133,27134,27135 ,15829,14778,15830 ,0,0,0}, {27132,27090,27089 ,15828,15788,15787 ,0,0,0}, + {27047,27133,27091 ,15750,15829,15789 ,0,0,0}, {27046,27045,27090 ,15749,15748,15788 ,0,0,0}, + {27133,27136,27092 ,15829,15831,14868 ,0,0,0}, {27047,27091,27045 ,15750,15789,15748 ,0,0,0}, + {27136,27137,27093 ,15831,15832,15790 ,0,0,0}, {27133,27092,27091 ,15829,14868,15789 ,0,0,0}, + {27137,27138,27094 ,15832,15833,15791 ,0,0,0}, {27136,27093,27092 ,15831,15790,14868 ,0,0,0}, + {27095,27138,27053 ,15792,15833,15756 ,0,0,0}, {27094,27093,27137 ,15791,15790,15832 ,0,0,0}, + {27139,27140,27141 ,15834,15835,15836 ,0,0,0}, {27138,27095,27094 ,15833,15792,15791 ,0,0,0}, + {27054,27139,27096 ,15757,15834,15793 ,0,0,0}, {27053,27052,27095 ,15756,15755,15792 ,0,0,0}, + {27139,27142,27097 ,15834,15837,15794 ,0,0,0}, {27054,27096,27052 ,15757,15793,15755 ,0,0,0}, + {27142,27143,27098 ,15837,15838,15795 ,0,0,0}, {27139,27097,27096 ,15834,15794,15793 ,0,0,0}, + {27143,27144,27099 ,15838,15839,15796 ,0,0,0}, {27142,27098,27097 ,15837,15795,15794 ,0,0,0}, + {27015,27144,27145 ,15721,15839,15840 ,0,0,0}, {27143,27099,27098 ,15838,15796,15795 ,0,0,0}, + {27013,27145,27101 ,14854,15840,15798 ,0,0,0}, {27144,27015,27099 ,15839,15721,15796 ,0,0,0}, + {27146,27103,27102 ,15841,15800,15799 ,0,0,0}, {27145,27013,27015 ,15840,14854,15721 ,0,0,0}, + {27147,27148,27149 ,15842,15843,14766 ,0,0,0}, {27101,27100,27013 ,15798,15797,14854 ,0,0,0}, + {27146,27147,27104 ,15841,15842,15801 ,0,0,0}, {27102,27103,27100 ,15799,15800,15797 ,0,0,0}, + {27147,27150,27105 ,15842,15844,15802 ,0,0,0}, {27146,27104,27103 ,15841,15801,15800 ,0,0,0}, + {27150,27151,27106 ,15844,15845,14848 ,0,0,0}, {27147,27105,27104 ,15842,15802,15801 ,0,0,0}, + {27151,27152,27107 ,15845,15846,15803 ,0,0,0}, {27150,27106,27105 ,15844,14848,15802 ,0,0,0}, + {27152,27153,27108 ,15846,15847,15804 ,0,0,0}, {27151,27107,27106 ,15845,15803,14848 ,0,0,0}, + {27153,27154,27109 ,15847,15848,15805 ,0,0,0}, {27152,27108,27107 ,15846,15804,15803 ,0,0,0}, + {27154,26938,27110 ,15848,15652,15806 ,0,0,0}, {27153,27109,27108 ,15847,15805,15804 ,0,0,0}, + {26940,26938,26937 ,15654,15652,15651 ,0,0,0}, {27109,27154,27110 ,15805,15848,15806 ,0,0,0}, + {27155,26929,27111 ,15849,15644,15807 ,0,0,0}, {26940,27110,26938 ,15654,15806,15652 ,0,0,0}, + {27156,26929,27155 ,15850,15644,15849 ,0,0,0}, {27157,27112,26929 ,15851,15808,15644 ,0,0,0}, + {26933,27111,26928 ,14890,15807,15643 ,0,0,0}, {27069,27155,27111 ,15771,15849,15807 ,0,0,0}, + {27156,27157,26929 ,15850,15851,15644 ,0,0,0}, {27115,26841,26840 ,15811,15578,15577 ,0,0,0}, + {26844,26846,27029 ,15580,15582,15735 ,0,0,0}, {27113,27158,27159 ,15809,15852,15853 ,0,0,0}, + {27115,27113,27072 ,15811,15809,14889 ,0,0,0}, {26840,27160,27115 ,15577,15854,15811 ,0,0,0}, + {27114,27159,27161 ,15810,15853,15855 ,0,0,0}, {27115,27158,27113 ,15811,15852,15809 ,0,0,0}, + {27116,27161,27162 ,15812,15855,15856 ,0,0,0}, {27113,27159,27114 ,15809,15853,15810 ,0,0,0}, + {27074,27162,27163 ,15775,15856,14794 ,0,0,0}, {27114,27161,27116 ,15810,15855,15812 ,0,0,0}, + {27075,27163,27164 ,15776,14794,15857 ,0,0,0}, {27116,27162,27074 ,15812,15856,15775 ,0,0,0}, + {27117,27164,27165 ,15813,15857,14792 ,0,0,0}, {27074,27163,27075 ,15775,14794,15776 ,0,0,0}, + {27118,27165,27120 ,15814,14792,15816 ,0,0,0}, {27164,27117,27075 ,15857,15813,15776 ,0,0,0}, + {27166,27122,27121 ,14789,15818,15817 ,0,0,0}, {27165,27118,27117 ,14792,15814,15813 ,0,0,0}, + {27167,27168,27166 ,15858,15859,14789 ,0,0,0}, {27120,27119,27118 ,15816,15815,15814 ,0,0,0}, + {27166,27168,27123 ,14789,15859,15819 ,0,0,0}, {27121,27122,27119 ,15817,15818,15815 ,0,0,0}, + {27168,27169,27124 ,15859,14660,15820 ,0,0,0}, {27166,27123,27122 ,14789,15819,15818 ,0,0,0}, + {27125,27169,27170 ,15821,14660,15860 ,0,0,0}, {27168,27124,27123 ,15859,15820,15819 ,0,0,0}, + {27126,27170,27171 ,15822,15860,15861 ,0,0,0}, {27124,27169,27125 ,15820,14660,15821 ,0,0,0}, + {27084,27171,27172 ,15783,15861,15862 ,0,0,0}, {27125,27170,27126 ,15821,15860,15822 ,0,0,0}, + {27085,27172,27128 ,15784,15862,15824 ,0,0,0}, {27171,27084,27126 ,15861,15783,15822 ,0,0,0}, + {27173,27174,27129 ,15863,15864,15825 ,0,0,0}, {27172,27085,27084 ,15862,15784,15783 ,0,0,0}, + {27129,27174,27130 ,15825,15864,15826 ,0,0,0}, {27128,27127,27085 ,15824,15823,15784 ,0,0,0}, + {27174,27175,27131 ,15864,15865,15827 ,0,0,0}, {27129,27130,27127 ,15825,15826,15823 ,0,0,0}, + {27132,27175,27176 ,15828,15865,15866 ,0,0,0}, {27174,27131,27130 ,15864,15827,15826 ,0,0,0}, + {27046,27176,27177 ,15749,15866,15867 ,0,0,0}, {27131,27175,27132 ,15827,15865,15828 ,0,0,0}, + {27047,27177,27134 ,15750,15867,14778 ,0,0,0}, {27176,27046,27132 ,15866,15749,15828 ,0,0,0}, + {27178,27179,27135 ,15868,15869,15830 ,0,0,0}, {27177,27047,27046 ,15867,15750,15749 ,0,0,0}, + {27135,27179,27136 ,15830,15869,15831 ,0,0,0}, {27134,27133,27047 ,14778,15829,15750 ,0,0,0}, + {27179,27180,27137 ,15869,15870,15832 ,0,0,0}, {27135,27136,27133 ,15830,15831,15829 ,0,0,0}, + {27138,27180,27181 ,15833,15870,15871 ,0,0,0}, {27179,27137,27136 ,15869,15832,15831 ,0,0,0}, + {27053,27181,27182 ,15756,15871,15872 ,0,0,0}, {27137,27180,27138 ,15832,15870,15833 ,0,0,0}, + {27054,27182,27140 ,15757,15872,15835 ,0,0,0}, {27181,27053,27138 ,15871,15756,15833 ,0,0,0}, + {27183,27184,27141 ,15873,15874,15836 ,0,0,0}, {27182,27054,27053 ,15872,15757,15756 ,0,0,0}, + {27141,27184,27142 ,15836,15874,15837 ,0,0,0}, {27140,27139,27054 ,15835,15834,15757 ,0,0,0}, + {27184,27185,27143 ,15874,15875,15838 ,0,0,0}, {27141,27142,27139 ,15836,15837,15834 ,0,0,0}, + {27144,27185,27186 ,15839,15875,14579 ,0,0,0}, {27184,27143,27142 ,15874,15838,15837 ,0,0,0}, + {27145,27186,27187 ,15840,14579,15876 ,0,0,0}, {27143,27185,27144 ,15838,15875,15839 ,0,0,0}, + {27101,27187,27188 ,15798,15876,14769 ,0,0,0}, {27144,27186,27145 ,15839,14579,15840 ,0,0,0}, + {27102,27188,27189 ,15799,14769,15877 ,0,0,0}, {27145,27187,27101 ,15840,15876,15798 ,0,0,0}, + {27146,27189,27148 ,15841,15877,15843 ,0,0,0}, {27188,27102,27101 ,14769,15799,15798 ,0,0,0}, + {27190,27150,27149 ,15878,15844,14766 ,0,0,0}, {27189,27146,27102 ,15877,15841,15799 ,0,0,0}, + {27191,27192,27190 ,15879,15880,15878 ,0,0,0}, {27148,27147,27146 ,15843,15842,15841 ,0,0,0}, + {27190,27192,27151 ,15878,15880,15845 ,0,0,0}, {27149,27150,27147 ,14766,15844,15842 ,0,0,0}, + {27192,27193,27152 ,15880,15881,15846 ,0,0,0}, {27190,27151,27150 ,15878,15845,15844 ,0,0,0}, + {27193,27194,27153 ,15881,15882,15847 ,0,0,0}, {27192,27152,27151 ,15880,15846,15845 ,0,0,0}, + {27194,27195,27154 ,15882,15883,15848 ,0,0,0}, {27193,27153,27152 ,15881,15847,15846 ,0,0,0}, + {26938,27195,26939 ,15652,15883,15653 ,0,0,0}, {27194,27154,27153 ,15882,15848,15847 ,0,0,0}, + {26939,27196,26937 ,15653,15884,15651 ,0,0,0}, {26938,27154,27195 ,15652,15848,15883 ,0,0,0}, + {27197,27155,26945 ,15885,15849,15659 ,0,0,0}, {27197,27198,27155 ,15885,15886,15849 ,0,0,0}, + {26941,27069,27111 ,15655,15771,15807 ,0,0,0}, {27196,26945,27069 ,15884,15659,15771 ,0,0,0}, + {27156,27155,27198 ,15850,15849,15886 ,0,0,0}, {26846,27160,26840 ,15582,15854,15577 ,0,0,0}, + {27199,26845,26844 ,14760,15581,15580 ,0,0,0}, {27200,27158,27160 ,15887,15852,15854 ,0,0,0}, + {27160,27158,27115 ,15854,15852,15811 ,0,0,0}, {27160,27071,27200 ,15854,15773,15887 ,0,0,0}, + {27201,27159,27158 ,15888,15853,15852 ,0,0,0}, {27158,27200,27201 ,15852,15887,15888 ,0,0,0}, + {27202,27161,27159 ,15889,15855,15853 ,0,0,0}, {27159,27201,27202 ,15853,15888,15889 ,0,0,0}, + {27203,27162,27161 ,15890,15856,15855 ,0,0,0}, {27161,27202,27203 ,15855,15889,15890 ,0,0,0}, + {27204,27163,27162 ,15891,14794,15856 ,0,0,0}, {27162,27203,27204 ,15856,15890,15891 ,0,0,0}, + {27205,27164,27163 ,15892,15857,14794 ,0,0,0}, {27163,27204,27205 ,14794,15891,15892 ,0,0,0}, + {27206,27165,27164 ,15893,14792,15857 ,0,0,0}, {27164,27205,27206 ,15857,15892,15893 ,0,0,0}, + {27207,27120,27165 ,15894,15816,14792 ,0,0,0}, {27165,27206,27207 ,14792,15893,15894 ,0,0,0}, + {27208,27121,27120 ,15895,15817,15816 ,0,0,0}, {27120,27207,27208 ,15816,15894,15895 ,0,0,0}, + {27209,27166,27121 ,15896,14789,15817 ,0,0,0}, {27208,27209,27121 ,15895,15896,15817 ,0,0,0}, + {27210,27211,27212 ,15897,15898,14664 ,0,0,0}, {27209,27167,27166 ,15896,15858,14789 ,0,0,0}, + {27213,27169,27168 ,15899,14660,15859 ,0,0,0}, {27167,27213,27168 ,15858,15899,15859 ,0,0,0}, + {27214,27170,27169 ,15900,15860,14660 ,0,0,0}, {27169,27213,27214 ,14660,15899,15900 ,0,0,0}, + {27215,27171,27170 ,15901,15861,15860 ,0,0,0}, {27170,27214,27215 ,15860,15900,15901 ,0,0,0}, + {27216,27172,27171 ,15902,15862,15861 ,0,0,0}, {27171,27215,27216 ,15861,15901,15902 ,0,0,0}, + {27217,27128,27172 ,14747,15824,15862 ,0,0,0}, {27172,27216,27217 ,15862,15902,14747 ,0,0,0}, + {27218,27129,27128 ,15903,15825,15824 ,0,0,0}, {27217,27218,27128 ,14747,15903,15824 ,0,0,0}, + {27219,27173,27220 ,15904,15863,15905 ,0,0,0}, {27218,27173,27129 ,15903,15863,15825 ,0,0,0}, + {27219,27175,27174 ,15904,15865,15864 ,0,0,0}, {27173,27219,27174 ,15863,15904,15864 ,0,0,0}, + {27221,27176,27175 ,15906,15866,15865 ,0,0,0}, {27175,27219,27221 ,15865,15904,15906 ,0,0,0}, + {27222,27177,27176 ,15907,15867,15866 ,0,0,0}, {27176,27221,27222 ,15866,15906,15907 ,0,0,0}, + {27223,27134,27177 ,14742,14778,15867 ,0,0,0}, {27177,27222,27223 ,15867,15907,14742 ,0,0,0}, + {27224,27135,27134 ,15908,15830,14778 ,0,0,0}, {27223,27224,27134 ,14742,15908,14778 ,0,0,0}, + {27225,27226,27227 ,15909,14630,15910 ,0,0,0}, {27224,27178,27135 ,15908,15868,15830 ,0,0,0}, + {27228,27180,27179 ,15911,15870,15869 ,0,0,0}, {27178,27228,27179 ,15868,15911,15869 ,0,0,0}, + {27229,27181,27180 ,15912,15871,15870 ,0,0,0}, {27180,27228,27229 ,15870,15911,15912 ,0,0,0}, + {27230,27182,27181 ,15913,15872,15871 ,0,0,0}, {27181,27229,27230 ,15871,15912,15913 ,0,0,0}, + {27231,27140,27182 ,15914,15835,15872 ,0,0,0}, {27182,27230,27231 ,15872,15913,15914 ,0,0,0}, + {27232,27141,27140 ,15915,15836,15835 ,0,0,0}, {27231,27232,27140 ,15914,15915,15835 ,0,0,0}, + {27184,27233,27185 ,15874,15916,15875 ,0,0,0}, {27232,27183,27141 ,15915,15873,15836 ,0,0,0}, + {27234,27235,27233 ,15917,14580,15916 ,0,0,0}, {27183,27233,27184 ,15873,15916,15874 ,0,0,0}, + {27235,27186,27185 ,14580,14579,15875 ,0,0,0}, {27185,27233,27235 ,15875,15916,14580 ,0,0,0}, + {27236,27187,27186 ,15918,15876,14579 ,0,0,0}, {27186,27235,27236 ,14579,14580,15918 ,0,0,0}, + {27237,27188,27187 ,15919,14769,15876 ,0,0,0}, {27187,27236,27237 ,15876,15918,15919 ,0,0,0}, + {27238,27189,27188 ,15920,15877,14769 ,0,0,0}, {27188,27237,27238 ,14769,15919,15920 ,0,0,0}, + {27239,27148,27189 ,15921,15843,15877 ,0,0,0}, {27189,27238,27239 ,15877,15920,15921 ,0,0,0}, + {27240,27149,27148 ,14728,14766,15843 ,0,0,0}, {27148,27239,27240 ,15843,15921,14728 ,0,0,0}, + {27241,27190,27149 ,15922,15878,14766 ,0,0,0}, {27240,27241,27149 ,14728,15922,14766 ,0,0,0}, + {27192,27242,27193 ,15880,15923,15881 ,0,0,0}, {27241,27191,27190 ,15922,15879,15878 ,0,0,0}, + {27193,27243,27194 ,15881,15924,15882 ,0,0,0}, {27191,27242,27192 ,15879,15923,15880 ,0,0,0}, + {27194,27244,27195 ,15882,15925,15883 ,0,0,0}, {27242,27243,27193 ,15923,15924,15881 ,0,0,0}, + {27195,26942,26939 ,15883,15656,15653 ,0,0,0}, {27243,27244,27194 ,15924,15925,15882 ,0,0,0}, + {26947,26946,26943 ,15661,15660,15657 ,0,0,0}, {27244,26942,27195 ,15925,15656,15883 ,0,0,0}, + {26943,27196,26939 ,15657,15884,15653 ,0,0,0}, {27069,26945,27155 ,15771,15659,15849 ,0,0,0}, + {26937,27196,27069 ,15651,15884,15771 ,0,0,0}, {27196,26943,26946 ,15884,15657,15660 ,0,0,0}, + {27197,26945,26944 ,15885,15659,15658 ,0,0,0}, {26845,27071,26846 ,15581,15773,15582 ,0,0,0}, + {27199,26852,26850 ,14760,15588,15586 ,0,0,0}, {27200,27071,27245 ,15887,15773,15926 ,0,0,0}, + {26846,27071,27160 ,15582,15773,15854 ,0,0,0}, {27071,26849,27245 ,15773,15585,15926 ,0,0,0}, + {27201,27200,27246 ,15888,15887,15927 ,0,0,0}, {27200,27245,27246 ,15887,15926,15927 ,0,0,0}, + {27202,27201,27247 ,15889,15888,15928 ,0,0,0}, {27201,27246,27247 ,15888,15927,15928 ,0,0,0}, + {27203,27202,27248 ,15890,15889,15929 ,0,0,0}, {27202,27247,27248 ,15889,15928,15929 ,0,0,0}, + {27204,27203,27249 ,15891,15890,15930 ,0,0,0}, {27203,27248,27249 ,15890,15929,15930 ,0,0,0}, + {27205,27204,27250 ,15892,15891,15931 ,0,0,0}, {27204,27249,27250 ,15891,15930,15931 ,0,0,0}, + {27206,27205,27251 ,15893,15892,15932 ,0,0,0}, {27205,27250,27251 ,15892,15931,15932 ,0,0,0}, + {27207,27206,27252 ,15894,15893,15933 ,0,0,0}, {27206,27251,27252 ,15893,15932,15933 ,0,0,0}, + {27208,27207,27253 ,15895,15894,15934 ,0,0,0}, {27207,27252,27253 ,15894,15933,15934 ,0,0,0}, + {27209,27208,27254 ,15896,15895,15935 ,0,0,0}, {27208,27253,27254 ,15895,15934,15935 ,0,0,0}, + {27167,27209,27255 ,15858,15896,15936 ,0,0,0}, {27209,27254,27255 ,15896,15935,15936 ,0,0,0}, + {27213,27167,27210 ,15899,15858,15897 ,0,0,0}, {27255,27210,27167 ,15936,15897,15858 ,0,0,0}, + {27214,27213,27212 ,15900,15899,14664 ,0,0,0}, {27213,27210,27212 ,15899,15897,14664 ,0,0,0}, + {27215,27214,27256 ,15901,15900,15937 ,0,0,0}, {27214,27212,27256 ,15900,14664,15937 ,0,0,0}, + {27216,27215,27257 ,15902,15901,15938 ,0,0,0}, {27215,27256,27257 ,15901,15937,15938 ,0,0,0}, + {27217,27216,27258 ,14747,15902,15939 ,0,0,0}, {27216,27257,27258 ,15902,15938,15939 ,0,0,0}, + {27218,27217,27259 ,15903,14747,15940 ,0,0,0}, {27217,27258,27259 ,14747,15939,15940 ,0,0,0}, + {27173,27218,27260 ,15863,15903,14651 ,0,0,0}, {27218,27259,27260 ,15903,15940,14651 ,0,0,0}, + {27260,27261,27220 ,14651,14649,15905 ,0,0,0}, {27260,27220,27173 ,14651,15905,15863 ,0,0,0}, + {27221,27219,27262 ,15906,15904,15941 ,0,0,0}, {27219,27220,27262 ,15904,15905,15941 ,0,0,0}, + {27222,27221,27263 ,15907,15906,15942 ,0,0,0}, {27221,27262,27263 ,15906,15941,15942 ,0,0,0}, + {27223,27222,27264 ,14742,15907,15943 ,0,0,0}, {27222,27263,27264 ,15907,15942,15943 ,0,0,0}, + {27224,27223,27265 ,15908,14742,15944 ,0,0,0}, {27223,27264,27265 ,14742,15943,15944 ,0,0,0}, + {27178,27224,27266 ,15868,15908,14635 ,0,0,0}, {27224,27265,27266 ,15908,15944,14635 ,0,0,0}, + {27228,27178,27225 ,15911,15868,15909 ,0,0,0}, {27266,27225,27178 ,14635,15909,15868 ,0,0,0}, + {27229,27228,27227 ,15912,15911,15910 ,0,0,0}, {27228,27225,27227 ,15911,15909,15910 ,0,0,0}, + {27230,27229,27267 ,15913,15912,15945 ,0,0,0}, {27229,27227,27267 ,15912,15910,15945 ,0,0,0}, + {27231,27230,27268 ,15914,15913,15946 ,0,0,0}, {27230,27267,27268 ,15913,15945,15946 ,0,0,0}, + {27232,27231,27269 ,15915,15914,15947 ,0,0,0}, {27231,27268,27269 ,15914,15946,15947 ,0,0,0}, + {27183,27232,27270 ,15873,15915,15948 ,0,0,0}, {27232,27269,27270 ,15915,15947,15948 ,0,0,0}, + {27233,27183,27271 ,15916,15873,14572 ,0,0,0}, {27183,27270,27271 ,15873,15948,14572 ,0,0,0}, + {27234,27271,27272 ,15917,14572,14569 ,0,0,0}, {27271,27234,27233 ,14572,15917,15916 ,0,0,0}, + {27236,27235,27273 ,15918,14580,14574 ,0,0,0}, {27235,27234,27273 ,14580,15917,14574 ,0,0,0}, + {27237,27236,27274 ,15919,15918,14575 ,0,0,0}, {27236,27273,27274 ,15918,14574,14575 ,0,0,0}, + {27238,27237,27275 ,15920,15919,15949 ,0,0,0}, {27237,27274,27275 ,15919,14575,15949 ,0,0,0}, + {27239,27238,27276 ,15921,15920,15950 ,0,0,0}, {27238,27275,27276 ,15920,15949,15950 ,0,0,0}, + {27240,27239,27277 ,14728,15921,14585 ,0,0,0}, {27239,27276,27277 ,15921,15950,14585 ,0,0,0}, + {27241,27240,27278 ,15922,14728,15951 ,0,0,0}, {27240,27277,27278 ,14728,14585,15951 ,0,0,0}, + {27191,27241,27279 ,15879,15922,15952 ,0,0,0}, {27241,27278,27279 ,15922,15951,15952 ,0,0,0}, + {27242,27191,27280 ,15923,15879,14590 ,0,0,0}, {27191,27279,27280 ,15879,15952,14590 ,0,0,0}, + {27243,27242,27281 ,15924,15923,15953 ,0,0,0}, {27242,27280,27281 ,15923,14590,15953 ,0,0,0}, + {27244,27243,27282 ,15925,15924,15954 ,0,0,0}, {27243,27281,27282 ,15924,15953,15954 ,0,0,0}, + {26942,27244,27283 ,15656,15925,15955 ,0,0,0}, {27244,27282,27283 ,15925,15954,15955 ,0,0,0}, + {27284,26943,26942 ,15956,15657,15656 ,0,0,0}, {27284,26942,27283 ,15956,15656,15955 ,0,0,0}, + {27196,26946,26945 ,15884,15660,15659 ,0,0,0}, {27284,26947,26943 ,15956,15661,15657 ,0,0,0}, + {26944,26946,26949 ,15658,15660,15663 ,0,0,0}, {26850,26845,27199 ,15586,15581,14760 ,0,0,0}, + {26851,26848,26850 ,15587,15584,15586 ,0,0,0}, {26848,27285,26849 ,15584,15957,15585 ,0,0,0}, + {26849,27285,27245 ,15585,15957,15926 ,0,0,0}, {27285,27286,27245 ,15957,14714,15926 ,0,0,0}, + {27245,27286,27246 ,15926,14714,15927 ,0,0,0}, {27286,27287,27246 ,14714,14713,15927 ,0,0,0}, + {27246,27287,27247 ,15927,14713,15928 ,0,0,0}, {27287,27288,27247 ,14713,15958,15928 ,0,0,0}, + {27247,27288,27248 ,15928,15958,15929 ,0,0,0}, {27288,27289,27248 ,15958,15959,15929 ,0,0,0}, + {27248,27289,27249 ,15929,15959,15930 ,0,0,0}, {27289,27290,27249 ,15959,15960,15930 ,0,0,0}, + {27249,27290,27250 ,15930,15960,15931 ,0,0,0}, {27290,27291,27250 ,15960,15961,15931 ,0,0,0}, + {27250,27291,27251 ,15931,15961,15932 ,0,0,0}, {27291,27292,27251 ,15961,15962,15932 ,0,0,0}, + {27292,27293,27252 ,15962,15963,15933 ,0,0,0}, {27292,27252,27251 ,15962,15933,15932 ,0,0,0}, + {27293,27294,27253 ,15963,15964,15934 ,0,0,0}, {27293,27253,27252 ,15963,15934,15933 ,0,0,0}, + {27294,27295,27254 ,15964,15965,15935 ,0,0,0}, {27294,27254,27253 ,15964,15935,15934 ,0,0,0}, + {27295,27296,27255 ,15965,15966,15936 ,0,0,0}, {27295,27255,27254 ,15965,15936,15935 ,0,0,0}, + {27296,27297,27210 ,15966,15967,15897 ,0,0,0}, {27296,27210,27255 ,15966,15897,15936 ,0,0,0}, + {27211,27210,27297 ,15898,15897,15967 ,0,0,0}, {27211,27298,27212 ,15898,14663,14664 ,0,0,0}, + {27212,27298,27256 ,14664,14663,15937 ,0,0,0}, {27298,27299,27256 ,14663,14658,15937 ,0,0,0}, + {27256,27299,27257 ,15937,14658,15938 ,0,0,0}, {27299,27300,27257 ,14658,14655,15938 ,0,0,0}, + {27300,27301,27258 ,14655,15968,15939 ,0,0,0}, {27300,27258,27257 ,14655,15939,15938 ,0,0,0}, + {27301,27302,27259 ,15968,14652,15940 ,0,0,0}, {27301,27259,27258 ,15968,15940,15939 ,0,0,0}, + {27302,27261,27260 ,14652,14649,14651 ,0,0,0}, {27302,27260,27259 ,14652,14651,15940 ,0,0,0}, + {27261,27303,27220 ,14649,15969,15905 ,0,0,0}, {27303,27304,27220 ,15969,14648,15905 ,0,0,0}, + {27220,27304,27262 ,15905,14648,15941 ,0,0,0}, {27304,27305,27262 ,14648,14646,15941 ,0,0,0}, + {27262,27305,27263 ,15941,14646,15942 ,0,0,0}, {27305,27306,27263 ,14646,15970,15942 ,0,0,0}, + {27306,27307,27264 ,15970,14638,15943 ,0,0,0}, {27306,27264,27263 ,15970,15943,15942 ,0,0,0}, + {27307,27308,27265 ,14638,15971,15944 ,0,0,0}, {27307,27265,27264 ,14638,15944,15943 ,0,0,0}, + {27308,27309,27266 ,15971,14634,14635 ,0,0,0}, {27308,27266,27265 ,15971,14635,15944 ,0,0,0}, + {27309,27310,27225 ,14634,15972,15909 ,0,0,0}, {27309,27225,27266 ,14634,15909,14635 ,0,0,0}, + {27226,27225,27310 ,14630,15909,15972 ,0,0,0}, {27226,27311,27227 ,14630,15973,15910 ,0,0,0}, + {27227,27311,27267 ,15910,15973,15945 ,0,0,0}, {27311,27312,27267 ,15973,14560,15945 ,0,0,0}, + {27312,27313,27268 ,14560,14561,15946 ,0,0,0}, {27312,27268,27267 ,14560,15946,15945 ,0,0,0}, + {27313,27314,27269 ,14561,15974,15947 ,0,0,0}, {27313,27269,27268 ,14561,15947,15946 ,0,0,0}, + {27314,27315,27270 ,15974,14567,15948 ,0,0,0}, {27314,27270,27269 ,15974,15948,15947 ,0,0,0}, + {27315,27272,27271 ,14567,14569,14572 ,0,0,0}, {27315,27271,27270 ,14567,14572,15948 ,0,0,0}, + {27272,27316,27234 ,14569,15975,15917 ,0,0,0}, {27316,27317,27234 ,15975,15976,15917 ,0,0,0}, + {27234,27317,27273 ,15917,15976,14574 ,0,0,0}, {27317,27318,27273 ,15976,14576,14574 ,0,0,0}, + {27273,27318,27274 ,14574,14576,14575 ,0,0,0}, {27318,27319,27274 ,14576,14577,14575 ,0,0,0}, + {27274,27319,27275 ,14575,14577,15949 ,0,0,0}, {27319,27320,27275 ,14577,14583,15949 ,0,0,0}, + {27320,27321,27276 ,14583,15977,15950 ,0,0,0}, {27320,27276,27275 ,14583,15950,15949 ,0,0,0}, + {27321,27322,27277 ,15977,15978,14585 ,0,0,0}, {27321,27277,27276 ,15977,14585,15950 ,0,0,0}, + {27322,27323,27278 ,15978,15979,15951 ,0,0,0}, {27322,27278,27277 ,15978,15951,14585 ,0,0,0}, + {27323,27324,27279 ,15979,14589,15952 ,0,0,0}, {27323,27279,27278 ,15979,15952,15951 ,0,0,0}, + {27324,27325,27280 ,14589,15980,14590 ,0,0,0}, {27324,27280,27279 ,14589,14590,15952 ,0,0,0}, + {27325,27326,27281 ,15980,15981,15953 ,0,0,0}, {27325,27281,27280 ,15980,15953,14590 ,0,0,0}, + {27326,27327,27282 ,15981,15982,15954 ,0,0,0}, {27326,27282,27281 ,15981,15954,15953 ,0,0,0}, + {27327,27328,27283 ,15982,15983,15955 ,0,0,0}, {27327,27283,27282 ,15982,15955,15954 ,0,0,0}, + {27328,27329,27284 ,15983,15984,15956 ,0,0,0}, {27328,27284,27283 ,15983,15956,15955 ,0,0,0}, + {27330,27284,27329 ,15985,15956,15984 ,0,0,0}, {27284,27330,26947 ,15956,15985,15661 ,0,0,0}, + {26947,27330,26950 ,15661,15985,15664 ,0,0,0}, {27331,27332,27333 ,15557,15515,15986 ,0,0,0}, + {27334,27335,27336 ,15987,15551,15552 ,0,0,0}, {27337,27338,27339 ,15988,15989,15990 ,0,0,0}, + {27340,27341,27337 ,15991,15992,15988 ,0,0,0}, {27342,27343,27344 ,15993,15994,15995 ,0,0,0}, + {27345,27346,27347 ,15996,15997,15998 ,0,0,0}, {27348,27349,27350 ,15999,16000,16001 ,0,0,0}, + {27351,27352,27345 ,16002,16003,15996 ,0,0,0}, {27353,27354,27355 ,16004,16005,16006 ,0,0,0}, + {27355,27350,27356 ,16006,16001,16007 ,0,0,0}, {27357,27353,27358 ,16008,16004,16009 ,0,0,0}, + {27354,27353,27359 ,16005,16004,16010 ,0,0,0}, {27340,27360,27361 ,15991,16011,16012 ,0,0,0}, + {27357,27362,27353 ,16008,16013,16004 ,0,0,0}, {27363,27364,27365 ,16014,16015,16016 ,0,0,0}, + {27364,27366,27333 ,16015,16017,15986 ,0,0,0}, {27367,27368,27365 ,16018,16019,16016 ,0,0,0}, + {27366,27364,27363 ,16017,16015,16014 ,0,0,0}, {27369,27370,27367 ,16020,16021,16018 ,0,0,0}, + {27365,27368,27363 ,16016,16019,16014 ,0,0,0}, {27371,27372,27335 ,15508,16022,15551 ,0,0,0}, + {27373,27374,27375 ,16023,16024,15548 ,0,0,0}, {27371,27376,27372 ,15508,16025,16022 ,0,0,0}, + {27377,27378,27379 ,15545,15546,16026 ,0,0,0}, {27374,27380,27375 ,16024,16027,15548 ,0,0,0}, + {27381,27382,27383 ,16028,15465,16029 ,0,0,0}, {27377,27379,27384 ,15545,16026,16030 ,0,0,0}, + {27385,27386,27387 ,15541,16031,16032 ,0,0,0}, {27386,27385,27388 ,16031,15541,16033 ,0,0,0}, + {27389,27390,27391 ,15537,16034,16035 ,0,0,0}, {27392,27393,27390 ,16036,16037,16034 ,0,0,0}, + {27394,27395,27396 ,15535,15459,16038 ,0,0,0}, {27389,27391,27397 ,15537,16035,15457 ,0,0,0}, + {27398,27399,27400 ,16039,15532,15533 ,0,0,0}, {27394,27396,27401 ,15535,16038,15534 ,0,0,0}, + {27402,27403,27404 ,16040,16041,16042 ,0,0,0}, {27405,27399,27398 ,16043,15532,16039 ,0,0,0}, + {27406,27407,27408 ,16044,16045,16046 ,0,0,0}, {27408,27404,27406 ,16046,16042,16044 ,0,0,0}, + {27409,27410,27411 ,16047,16048,16049 ,0,0,0}, {27412,27407,27413 ,15527,16045,15491 ,0,0,0}, + {27414,27415,27416 ,16050,16051,16052 ,0,0,0}, {27415,27414,27417 ,16051,16050,16053 ,0,0,0}, + {27418,27419,27420 ,16054,16055,16056 ,0,0,0}, {27416,27419,27421 ,16052,16055,16057 ,0,0,0}, + {27422,27423,27424 ,15520,15521,16058 ,0,0,0}, {27425,27426,27427 ,16059,15392,16060 ,0,0,0}, + {27428,27429,27430 ,16061,16062,16063 ,0,0,0}, {27429,27428,27431 ,16062,16061,16064 ,0,0,0}, + {27432,27433,27434 ,16065,16066,16067 ,0,0,0}, {27435,27436,27432 ,16068,16069,16065 ,0,0,0}, + {27433,27432,27436 ,16066,16065,16069 ,0,0,0}, {27433,27436,27422 ,16066,16069,15520 ,0,0,0}, + {27437,27438,27439 ,16070,16071,16072 ,0,0,0}, {27420,27424,27423 ,16056,16058,15521 ,0,0,0}, + {27440,27425,27427 ,16073,16059,16060 ,0,0,0}, {27426,27441,27427 ,15392,16074,16060 ,0,0,0}, + {27442,27443,27425 ,16075,16076,16059 ,0,0,0}, {27425,27444,27426 ,16059,16077,15392 ,0,0,0}, + {27445,27446,27447 ,16078,16079,16080 ,0,0,0}, {26844,27448,27449 ,16081,16082,16083 ,0,0,0}, + {27449,27450,27199 ,16083,16084,16085 ,0,0,0}, {27450,26852,27199 ,16084,16086,16085 ,0,0,0}, + {26853,26852,27451 ,16087,16086,16088 ,0,0,0}, {27439,27419,27437 ,16072,16055,16070 ,0,0,0}, + {27430,27435,27432 ,16063,16068,16065 ,0,0,0}, {27420,27423,27418 ,16056,15521,16054 ,0,0,0}, + {26982,27431,26981 ,16089,16064,16090 ,0,0,0}, {27414,27416,27421 ,16050,16052,16057 ,0,0,0}, + {27419,27418,27421 ,16055,16054,16057 ,0,0,0}, {27409,27417,27410 ,16047,16053,16048 ,0,0,0}, + {27415,27417,27409 ,16051,16053,16047 ,0,0,0}, {27409,27452,27415 ,16047,16091,16051 ,0,0,0}, + {27410,27412,27411 ,16048,15527,16049 ,0,0,0}, {27413,27407,27406 ,15491,16045,16044 ,0,0,0}, + {27412,27413,27411 ,15527,15491,16049 ,0,0,0}, {27402,27404,27408 ,16040,16042,16046 ,0,0,0}, + {27398,27400,27453 ,16039,15533,16092 ,0,0,0}, {27454,27405,27455 ,15531,16043,16093 ,0,0,0}, + {27404,27403,27455 ,16042,16041,16093 ,0,0,0}, {27399,27405,27454 ,15532,16043,15531 ,0,0,0}, + {27403,27454,27455 ,16041,15531,16093 ,0,0,0}, {27453,27400,27401 ,16092,15533,15534 ,0,0,0}, + {27456,27398,27453 ,16094,16039,16092 ,0,0,0}, {27401,27396,27453 ,15534,16038,16092 ,0,0,0}, + {27397,27395,27457 ,15457,15459,15497 ,0,0,0}, {27394,27457,27395 ,15535,15497,15459 ,0,0,0}, + {27458,27397,27457 ,16095,15457,15497 ,0,0,0}, {27393,27391,27390 ,16037,16035,16034 ,0,0,0}, + {27389,27397,27458 ,15537,15457,16095 ,0,0,0}, {27392,27459,27393 ,16036,15500,16037 ,0,0,0}, + {27387,27386,27459 ,16032,16031,15500 ,0,0,0}, {27459,27392,27387 ,15500,16036,16032 ,0,0,0}, + {27388,27460,27383 ,16033,15542,16029 ,0,0,0}, {27461,27462,27463 ,16096,16097,16098 ,0,0,0}, + {27383,27460,27464 ,16029,15542,16099 ,0,0,0}, {27460,27388,27385 ,15542,16033,15541 ,0,0,0}, + {27465,27384,27382 ,16100,16030,15465 ,0,0,0}, {27381,27383,27464 ,16028,16029,16099 ,0,0,0}, + {27384,27465,27377 ,16030,16100,15545 ,0,0,0}, {27465,27382,27381 ,16100,15465,16028 ,0,0,0}, + {27376,27466,27467 ,16025,15507,16101 ,0,0,0}, {27378,27380,27468 ,15546,16027,16102 ,0,0,0}, + {27379,27378,27468 ,16026,15546,16102 ,0,0,0}, {27468,27380,27374 ,16102,16027,16024 ,0,0,0}, + {27469,27470,27471 ,16103,16104,16105 ,0,0,0}, {27466,27373,27375 ,15507,16023,15548 ,0,0,0}, + {27333,27366,27331 ,15986,16017,15557 ,0,0,0}, {27376,27373,27466 ,16025,16023,15507 ,0,0,0}, + {27376,27467,27372 ,16025,16101,16022 ,0,0,0}, {27335,27334,27371 ,15551,15987,15508 ,0,0,0}, + {27370,27369,27336 ,16021,16020,15552 ,0,0,0}, {27336,27369,27334 ,15552,16020,15987 ,0,0,0}, + {27472,27369,27367 ,16106,16020,16018 ,0,0,0}, {27370,27368,27367 ,16021,16019,16018 ,0,0,0}, + {27332,27361,27360 ,15515,16012,16011 ,0,0,0}, {27331,27361,27332 ,15557,16012,15515 ,0,0,0}, + {27341,27338,27337 ,15992,15989,15988 ,0,0,0}, {27340,27337,27360 ,15991,15988,16011 ,0,0,0}, + {27341,27473,27338 ,15992,16107,15989 ,0,0,0}, {27344,27474,27348 ,15995,14800,15999 ,0,0,0}, + {27475,27476,27473 ,16108,16109,16107 ,0,0,0}, {27342,27477,27478 ,15993,16110,16111 ,0,0,0}, + {27476,27479,27480 ,16109,16112,16113 ,0,0,0}, {27475,27479,27476 ,16108,16112,16109 ,0,0,0}, + {27476,27338,27473 ,16109,15989,16107 ,0,0,0}, {27480,27481,27482 ,16113,16114,16115 ,0,0,0}, + {27481,27480,27483 ,16114,16113,16116 ,0,0,0}, {27479,27483,27480 ,16112,16116,16113 ,0,0,0}, + {27478,27477,27482 ,16111,16110,16115 ,0,0,0}, {27484,27344,27343 ,16117,15995,15994 ,0,0,0}, + {27480,27482,27477 ,16113,16115,16110 ,0,0,0}, {27349,27348,27485 ,16000,15999,16118 ,0,0,0}, + {27480,27486,27476 ,16113,16119,16109 ,0,0,0}, {27487,27360,27337 ,16120,16011,15988 ,0,0,0}, + {27476,27347,27338 ,16109,15998,15989 ,0,0,0}, {27488,27332,27360 ,16121,15515,16011 ,0,0,0}, + {27339,27338,27347 ,15990,15989,15998 ,0,0,0}, {27489,27333,27332 ,16122,15986,15515 ,0,0,0}, + {27487,27337,27339 ,16120,15988,15990 ,0,0,0}, {27490,27364,27333 ,16123,16015,15986 ,0,0,0}, + {27488,27360,27487 ,16121,16011,16120 ,0,0,0}, {27491,27365,27364 ,16124,16016,16015 ,0,0,0}, + {27489,27332,27488 ,16122,15515,16121 ,0,0,0}, {27492,27367,27365 ,16125,16018,16016 ,0,0,0}, + {27333,27489,27490 ,15986,16122,16123 ,0,0,0}, {27493,27494,27495 ,16126,16127,15475 ,0,0,0}, + {27364,27490,27491 ,16015,16123,16124 ,0,0,0}, {27495,27334,27369 ,15475,15987,16020 ,0,0,0}, + {27365,27491,27492 ,16016,16124,16125 ,0,0,0}, {27496,27371,27334 ,16128,15508,15987 ,0,0,0}, + {27367,27492,27472 ,16018,16125,16106 ,0,0,0}, {27497,27376,27371 ,16129,16025,15508 ,0,0,0}, + {27369,27472,27495 ,16020,16106,15475 ,0,0,0}, {27498,27373,27376 ,16130,16023,16025 ,0,0,0}, + {27334,27495,27496 ,15987,15475,16128 ,0,0,0}, {27499,27374,27373 ,16131,16024,16023 ,0,0,0}, + {27497,27371,27496 ,16129,15508,16128 ,0,0,0}, {27500,27468,27374 ,16132,16102,16024 ,0,0,0}, + {27498,27376,27497 ,16130,16025,16129 ,0,0,0}, {27501,27379,27468 ,16133,16026,16102 ,0,0,0}, + {27373,27498,27499 ,16023,16130,16131 ,0,0,0}, {27470,27384,27379 ,16104,16030,16026 ,0,0,0}, + {27374,27499,27500 ,16024,16131,16132 ,0,0,0}, {27502,27382,27384 ,16134,15465,16030 ,0,0,0}, + {27468,27500,27501 ,16102,16132,16133 ,0,0,0}, {27503,27383,27382 ,16135,16029,15465 ,0,0,0}, + {27379,27501,27470 ,16026,16133,16104 ,0,0,0}, {27504,27388,27383 ,16136,16033,16029 ,0,0,0}, + {27502,27384,27470 ,16134,16030,16104 ,0,0,0}, {27505,27386,27388 ,16137,16031,16033 ,0,0,0}, + {27503,27382,27502 ,16135,15465,16134 ,0,0,0}, {27506,27459,27386 ,16138,15500,16031 ,0,0,0}, + {27383,27503,27504 ,16029,16135,16136 ,0,0,0}, {27393,27459,27461 ,16037,15500,16096 ,0,0,0}, + {27388,27504,27505 ,16033,16136,16137 ,0,0,0}, {27507,27391,27393 ,16139,16035,16037 ,0,0,0}, + {27386,27505,27506 ,16031,16137,16138 ,0,0,0}, {27508,27397,27391 ,15458,15457,16035 ,0,0,0}, + {27459,27506,27461 ,15500,16138,16096 ,0,0,0}, {27509,27395,27397 ,16140,15459,15457 ,0,0,0}, + {27507,27393,27461 ,16139,16037,16096 ,0,0,0}, {27510,27396,27395 ,16141,16038,15459 ,0,0,0}, + {27508,27391,27507 ,15458,16035,16139 ,0,0,0}, {27511,27453,27396 ,16142,16092,16038 ,0,0,0}, + {27397,27508,27509 ,15457,15458,16140 ,0,0,0}, {27512,27513,27514 ,15354,16143,16144 ,0,0,0}, + {27395,27509,27510 ,15459,16140,16141 ,0,0,0}, {27515,27405,27398 ,16145,16043,16039 ,0,0,0}, + {27396,27510,27511 ,16038,16141,16142 ,0,0,0}, {27516,27455,27405 ,16146,16093,16043 ,0,0,0}, + {27453,27511,27456 ,16092,16142,16094 ,0,0,0}, {27517,27404,27455 ,16147,16042,16093 ,0,0,0}, + {27398,27456,27515 ,16039,16094,16145 ,0,0,0}, {27518,27406,27404 ,16148,16044,16042 ,0,0,0}, + {27516,27405,27515 ,16146,16043,16145 ,0,0,0}, {27519,27413,27406 ,16149,15491,16044 ,0,0,0}, + {27517,27455,27516 ,16147,16093,16146 ,0,0,0}, {27520,27411,27413 ,16150,16049,15491 ,0,0,0}, + {27518,27404,27517 ,16148,16042,16147 ,0,0,0}, {27521,27409,27411 ,16151,16047,16049 ,0,0,0}, + {27406,27518,27519 ,16044,16148,16149 ,0,0,0}, {27415,27522,27416 ,16051,16152,16052 ,0,0,0}, + {27413,27519,27520 ,15491,16149,16150 ,0,0,0}, {27437,27523,27438 ,16070,16153,16071 ,0,0,0}, + {27411,27520,27521 ,16049,16150,16151 ,0,0,0}, {27437,27419,27416 ,16070,16055,16052 ,0,0,0}, + {27409,27521,27452 ,16047,16151,16091 ,0,0,0}, {27439,27420,27419 ,16072,16056,16055 ,0,0,0}, + {27415,27452,27522 ,16051,16091,16152 ,0,0,0}, {27424,27420,27524 ,16058,16056,16154 ,0,0,0}, + {27437,27416,27522 ,16070,16052,16152 ,0,0,0}, {27441,27434,27433 ,16074,16067,16066 ,0,0,0}, + {27525,27432,27434 ,16155,16065,16067 ,0,0,0}, {27424,27433,27422 ,16058,16066,15520 ,0,0,0}, + {27524,27420,27439 ,16154,16056,16072 ,0,0,0}, {27441,27426,27434 ,16074,15392,16067 ,0,0,0}, + {27433,27424,27441 ,16066,16058,16074 ,0,0,0}, {27430,27526,27428 ,16063,16156,16061 ,0,0,0}, + {27428,26981,27431 ,16061,16090,16064 ,0,0,0}, {27435,27430,27429 ,16068,16063,16062 ,0,0,0}, + {27430,27525,27526 ,16063,16155,16156 ,0,0,0}, {26983,26981,27428 ,16157,16090,16061 ,0,0,0}, + {27477,27486,27480 ,16110,16119,16113 ,0,0,0}, {27343,27342,27478 ,15994,15993,16111 ,0,0,0}, + {27527,27355,27354 ,16158,16006,16005 ,0,0,0}, {27486,27347,27476 ,16119,15998,16109 ,0,0,0}, + {27486,27477,27528 ,16119,16110,16159 ,0,0,0}, {27339,27346,27529 ,15990,15997,16160 ,0,0,0}, + {27345,27347,27486 ,15996,15998,16119 ,0,0,0}, {27487,27529,27530 ,16120,16160,16161 ,0,0,0}, + {27346,27339,27347 ,15997,15990,15998 ,0,0,0}, {27488,27530,27531 ,16121,16161,16162 ,0,0,0}, + {27529,27487,27339 ,16160,16120,15990 ,0,0,0}, {27489,27531,27532 ,16122,16162,16163 ,0,0,0}, + {27530,27488,27487 ,16161,16121,16120 ,0,0,0}, {27490,27532,27533 ,16123,16163,15383 ,0,0,0}, + {27531,27489,27488 ,16162,16122,16121 ,0,0,0}, {27491,27533,27534 ,16124,15383,16164 ,0,0,0}, + {27532,27490,27489 ,16163,16123,16122 ,0,0,0}, {27492,27534,27535 ,16125,16164,16165 ,0,0,0}, + {27533,27491,27490 ,15383,16124,16123 ,0,0,0}, {27472,27535,27493 ,16106,16165,16126 ,0,0,0}, + {27492,27491,27534 ,16125,16124,16164 ,0,0,0}, {27536,27537,27538 ,16166,15378,16167 ,0,0,0}, + {27472,27492,27535 ,16106,16125,16165 ,0,0,0}, {27496,27494,27536 ,16128,16127,16166 ,0,0,0}, + {27495,27472,27493 ,15475,16106,16126 ,0,0,0}, {27497,27536,27539 ,16129,16166,16168 ,0,0,0}, + {27496,27495,27494 ,16128,15475,16127 ,0,0,0}, {27498,27539,27540 ,16130,16168,16169 ,0,0,0}, + {27536,27497,27496 ,16166,16129,16128 ,0,0,0}, {27499,27540,27541 ,16131,16169,16170 ,0,0,0}, + {27539,27498,27497 ,16168,16130,16129 ,0,0,0}, {27500,27541,27542 ,16132,16170,16171 ,0,0,0}, + {27540,27499,27498 ,16169,16131,16130 ,0,0,0}, {27501,27542,27471 ,16133,16171,16105 ,0,0,0}, + {27500,27499,27541 ,16132,16131,16170 ,0,0,0}, {27543,27544,27545 ,16172,16173,16174 ,0,0,0}, + {27501,27500,27542 ,16133,16132,16171 ,0,0,0}, {27502,27469,27546 ,16134,16103,16175 ,0,0,0}, + {27470,27501,27471 ,16104,16133,16105 ,0,0,0}, {27503,27546,27547 ,16135,16175,16176 ,0,0,0}, + {27469,27502,27470 ,16103,16134,16104 ,0,0,0}, {27504,27547,27548 ,16136,16176,16177 ,0,0,0}, + {27546,27503,27502 ,16175,16135,16134 ,0,0,0}, {27505,27548,27549 ,16137,16177,16178 ,0,0,0}, + {27547,27504,27503 ,16176,16136,16135 ,0,0,0}, {27506,27549,27462 ,16138,16178,16097 ,0,0,0}, + {27505,27504,27548 ,16137,16136,16177 ,0,0,0}, {27550,27551,27552 ,16179,16180,16181 ,0,0,0}, + {27506,27505,27549 ,16138,16137,16178 ,0,0,0}, {27507,27463,27553 ,16139,16098,16182 ,0,0,0}, + {27461,27506,27462 ,16096,16138,16097 ,0,0,0}, {27508,27553,27554 ,15458,16182,16183 ,0,0,0}, + {27507,27461,27463 ,16139,16096,16098 ,0,0,0}, {27509,27554,27555 ,16140,16183,16184 ,0,0,0}, + {27553,27508,27507 ,16182,15458,16139 ,0,0,0}, {27510,27555,27556 ,16141,16184,16185 ,0,0,0}, + {27554,27509,27508 ,16183,16140,15458 ,0,0,0}, {27511,27556,27557 ,16142,16185,16186 ,0,0,0}, + {27555,27510,27509 ,16184,16141,16140 ,0,0,0}, {27456,27557,27558 ,16094,16186,16187 ,0,0,0}, + {27511,27510,27556 ,16142,16141,16185 ,0,0,0}, {27515,27558,27513 ,16145,16187,16143 ,0,0,0}, + {27456,27511,27557 ,16094,16142,16186 ,0,0,0}, {27516,27513,27559 ,16146,16143,16188 ,0,0,0}, + {27515,27456,27558 ,16145,16094,16187 ,0,0,0}, {27517,27559,27560 ,16147,16188,16189 ,0,0,0}, + {27513,27516,27515 ,16143,16146,16145 ,0,0,0}, {27518,27560,27561 ,16148,16189,16190 ,0,0,0}, + {27559,27517,27516 ,16188,16147,16146 ,0,0,0}, {27519,27561,27562 ,16149,16190,16191 ,0,0,0}, + {27560,27518,27517 ,16189,16148,16147 ,0,0,0}, {27520,27562,27563 ,16150,16191,16192 ,0,0,0}, + {27561,27519,27518 ,16190,16149,16148 ,0,0,0}, {27521,27563,27564 ,16151,16192,15399 ,0,0,0}, + {27562,27520,27519 ,16191,16150,16149 ,0,0,0}, {27452,27564,27565 ,16091,15399,16193 ,0,0,0}, + {27563,27521,27520 ,16192,16151,16150 ,0,0,0}, {27522,27565,27523 ,16152,16193,16153 ,0,0,0}, + {27452,27521,27564 ,16091,16151,15399 ,0,0,0}, {27566,27439,27438 ,16194,16072,16071 ,0,0,0}, + {27522,27452,27565 ,16152,16091,16193 ,0,0,0}, {27448,27567,27443 ,16082,16195,16076 ,0,0,0}, + {27437,27522,27523 ,16070,16152,16153 ,0,0,0}, {27566,27427,27524 ,16194,16060,16154 ,0,0,0}, + {27426,27568,27434 ,15392,16196,16067 ,0,0,0}, {27524,27441,27424 ,16154,16074,16058 ,0,0,0}, + {27566,27524,27439 ,16194,16154,16072 ,0,0,0}, {27569,27526,27525 ,16197,16156,16155 ,0,0,0}, + {27524,27427,27441 ,16154,16060,16074 ,0,0,0}, {26984,27526,27569 ,16198,16156,16197 ,0,0,0}, + {27526,26983,27428 ,16156,16157,16061 ,0,0,0}, {27432,27525,27430 ,16065,16155,16063 ,0,0,0}, + {27568,27569,27525 ,16196,16197,16155 ,0,0,0}, {26984,26983,27526 ,16198,16157,16156 ,0,0,0}, + {27528,27477,27342 ,16159,16110,15993 ,0,0,0}, {27474,27344,27484 ,14800,15995,16117 ,0,0,0}, + {27570,27346,27352 ,16199,15997,16003 ,0,0,0}, {27528,27345,27486 ,16159,15996,16119 ,0,0,0}, + {27528,27342,27571 ,16159,15993,16200 ,0,0,0}, {27572,27573,27574 ,16201,16202,16203 ,0,0,0}, + {27351,27345,27528 ,16002,15996,16159 ,0,0,0}, {27570,27572,27529 ,16199,16201,16160 ,0,0,0}, + {27352,27346,27345 ,16003,15997,15996 ,0,0,0}, {27572,27575,27530 ,16201,16204,16161 ,0,0,0}, + {27570,27529,27346 ,16199,16160,15997 ,0,0,0}, {27575,27576,27531 ,16204,16205,16162 ,0,0,0}, + {27572,27530,27529 ,16201,16161,16160 ,0,0,0}, {27576,27577,27532 ,16205,15382,16163 ,0,0,0}, + {27575,27531,27530 ,16204,16162,16161 ,0,0,0}, {27577,27578,27533 ,15382,16206,15383 ,0,0,0}, + {27576,27532,27531 ,16205,16163,16162 ,0,0,0}, {27578,27579,27534 ,16206,16207,16164 ,0,0,0}, + {27577,27533,27532 ,15382,15383,16163 ,0,0,0}, {27579,27580,27535 ,16207,16208,16165 ,0,0,0}, + {27578,27534,27533 ,16206,16164,15383 ,0,0,0}, {27580,27581,27493 ,16208,16209,16126 ,0,0,0}, + {27579,27535,27534 ,16207,16165,16164 ,0,0,0}, {27581,27537,27494 ,16209,15378,16127 ,0,0,0}, + {27493,27535,27580 ,16126,16165,16208 ,0,0,0}, {27582,27583,27584 ,16210,16211,16212 ,0,0,0}, + {27494,27493,27581 ,16127,16126,16209 ,0,0,0}, {27538,27582,27539 ,16167,16210,16168 ,0,0,0}, + {27537,27536,27494 ,15378,16166,16127 ,0,0,0}, {27582,27585,27540 ,16210,16213,16169 ,0,0,0}, + {27538,27539,27536 ,16167,16168,16166 ,0,0,0}, {27585,27586,27541 ,16213,16214,16170 ,0,0,0}, + {27582,27540,27539 ,16210,16169,16168 ,0,0,0}, {27586,27587,27542 ,16214,16215,16171 ,0,0,0}, + {27585,27541,27540 ,16213,16170,16169 ,0,0,0}, {27587,27588,27471 ,16215,16216,16105 ,0,0,0}, + {27586,27542,27541 ,16214,16171,16170 ,0,0,0}, {27469,27588,27589 ,16103,16216,16217 ,0,0,0}, + {27471,27542,27587 ,16105,16171,16215 ,0,0,0}, {27589,27543,27546 ,16217,16172,16175 ,0,0,0}, + {27588,27469,27471 ,16216,16103,16105 ,0,0,0}, {27543,27590,27547 ,16172,16218,16176 ,0,0,0}, + {27589,27546,27469 ,16217,16175,16103 ,0,0,0}, {27590,27591,27548 ,16218,15368,16177 ,0,0,0}, + {27543,27547,27546 ,16172,16176,16175 ,0,0,0}, {27591,27592,27549 ,15368,16219,16178 ,0,0,0}, + {27590,27548,27547 ,16218,16177,16176 ,0,0,0}, {27592,27593,27462 ,16219,16220,16097 ,0,0,0}, + {27591,27549,27548 ,15368,16178,16177 ,0,0,0}, {27593,27594,27463 ,16220,16221,16098 ,0,0,0}, + {27462,27549,27592 ,16097,16178,16219 ,0,0,0}, {27594,27550,27553 ,16221,16179,16182 ,0,0,0}, + {27463,27462,27593 ,16098,16097,16220 ,0,0,0}, {27550,27595,27554 ,16179,16222,16183 ,0,0,0}, + {27594,27553,27463 ,16221,16182,16098 ,0,0,0}, {27595,27596,27555 ,16222,16223,16184 ,0,0,0}, + {27550,27554,27553 ,16179,16183,16182 ,0,0,0}, {27596,27597,27556 ,16223,16224,16185 ,0,0,0}, + {27595,27555,27554 ,16222,16184,16183 ,0,0,0}, {27597,27598,27557 ,16224,16225,16186 ,0,0,0}, + {27596,27556,27555 ,16223,16185,16184 ,0,0,0}, {27598,27514,27558 ,16225,16144,16187 ,0,0,0}, + {27557,27556,27597 ,16186,16185,16224 ,0,0,0}, {27599,27600,27601 ,16226,16227,16228 ,0,0,0}, + {27558,27557,27598 ,16187,16186,16225 ,0,0,0}, {27512,27599,27559 ,15354,16226,16188 ,0,0,0}, + {27514,27513,27558 ,16144,16143,16187 ,0,0,0}, {27599,27602,27560 ,16226,16229,16189 ,0,0,0}, + {27512,27559,27513 ,15354,16188,16143 ,0,0,0}, {27602,27603,27561 ,16229,16230,16190 ,0,0,0}, + {27599,27560,27559 ,16226,16189,16188 ,0,0,0}, {27603,27604,27562 ,16230,16231,16191 ,0,0,0}, + {27602,27561,27560 ,16229,16190,16189 ,0,0,0}, {27604,27605,27563 ,16231,15348,16192 ,0,0,0}, + {27603,27562,27561 ,16230,16191,16190 ,0,0,0}, {27605,27606,27564 ,15348,16232,15399 ,0,0,0}, + {27604,27563,27562 ,16231,16192,16191 ,0,0,0}, {27606,27607,27565 ,16232,16233,16193 ,0,0,0}, + {27605,27564,27563 ,15348,15399,16192 ,0,0,0}, {27607,27608,27523 ,16233,16234,16153 ,0,0,0}, + {27606,27565,27564 ,16232,16193,15399 ,0,0,0}, {27608,27609,27438 ,16234,16235,16071 ,0,0,0}, + {27607,27523,27565 ,16233,16153,16193 ,0,0,0}, {27609,27440,27566 ,16235,16073,16194 ,0,0,0}, + {27438,27523,27608 ,16071,16153,16234 ,0,0,0}, {27610,26980,26842 ,16236,15128,15118 ,0,0,0}, + {27609,27566,27438 ,16235,16194,16071 ,0,0,0}, {27442,27425,27440 ,16075,16059,16073 ,0,0,0}, + {27566,27440,27427 ,16194,16073,16060 ,0,0,0}, {26975,27569,27610 ,15113,16197,16236 ,0,0,0}, + {26975,26986,27569 ,15113,15265,16197 ,0,0,0}, {27434,27568,27525 ,16067,16196,16155 ,0,0,0}, + {27444,27610,27568 ,16077,16236,16196 ,0,0,0}, {26984,27569,26986 ,16198,16197,15265 ,0,0,0}, + {27344,27571,27342 ,15995,16200,15993 ,0,0,0}, {27485,27348,27474 ,16118,15999,14800 ,0,0,0}, + {27351,27611,27612 ,16002,16237,16238 ,0,0,0}, {27571,27351,27528 ,16200,16002,16159 ,0,0,0}, + {27613,27571,27344 ,16239,16200,15995 ,0,0,0}, {27352,27612,27614 ,16003,16238,16240 ,0,0,0}, + {27571,27611,27351 ,16200,16237,16002 ,0,0,0}, {27570,27614,27573 ,16199,16240,16202 ,0,0,0}, + {27612,27352,27351 ,16238,16003,16002 ,0,0,0}, {27615,27575,27574 ,16241,16204,16203 ,0,0,0}, + {27614,27570,27352 ,16240,16199,16003 ,0,0,0}, {27616,27576,27615 ,16242,16205,16241 ,0,0,0}, + {27573,27572,27570 ,16202,16201,16199 ,0,0,0}, {27617,27618,27619 ,16243,16244,16245 ,0,0,0}, + {27574,27575,27572 ,16203,16204,16201 ,0,0,0}, {27616,27617,27577 ,16242,16243,15382 ,0,0,0}, + {27615,27576,27575 ,16241,16205,16204 ,0,0,0}, {27617,27620,27578 ,16243,16246,16206 ,0,0,0}, + {27616,27577,27576 ,16242,15382,16205 ,0,0,0}, {27620,27621,27579 ,16246,16247,16207 ,0,0,0}, + {27617,27578,27577 ,16243,16206,15382 ,0,0,0}, {27621,27622,27580 ,16247,16248,16208 ,0,0,0}, + {27620,27579,27578 ,16246,16207,16206 ,0,0,0}, {27622,27623,27581 ,16248,16249,16209 ,0,0,0}, + {27621,27580,27579 ,16247,16208,16207 ,0,0,0}, {27537,27623,27624 ,15378,16249,16250 ,0,0,0}, + {27622,27581,27580 ,16248,16209,16208 ,0,0,0}, {27538,27624,27583 ,16167,16250,16211 ,0,0,0}, + {27623,27537,27581 ,16249,15378,16209 ,0,0,0}, {27625,27626,27627 ,16251,16252,16253 ,0,0,0}, + {27624,27538,27537 ,16250,16167,15378 ,0,0,0}, {27584,27625,27585 ,16212,16251,16213 ,0,0,0}, + {27583,27582,27538 ,16211,16210,16167 ,0,0,0}, {27625,27628,27586 ,16251,16254,16214 ,0,0,0}, + {27584,27585,27582 ,16212,16213,16210 ,0,0,0}, {27628,27629,27587 ,16254,16255,16215 ,0,0,0}, + {27625,27586,27585 ,16251,16214,16213 ,0,0,0}, {27588,27629,27630 ,16216,16255,16256 ,0,0,0}, + {27628,27587,27586 ,16254,16215,16214 ,0,0,0}, {27589,27630,27544 ,16217,16256,16173 ,0,0,0}, + {27588,27587,27629 ,16216,16215,16255 ,0,0,0}, {27631,27632,27633 ,16257,15282,16258 ,0,0,0}, + {27630,27589,27588 ,16256,16217,16216 ,0,0,0}, {27545,27631,27590 ,16174,16257,16218 ,0,0,0}, + {27544,27543,27589 ,16173,16172,16217 ,0,0,0}, {27631,27634,27591 ,16257,16259,15368 ,0,0,0}, + {27545,27590,27543 ,16174,16218,16172 ,0,0,0}, {27634,27635,27592 ,16259,16260,16219 ,0,0,0}, + {27631,27591,27590 ,16257,15368,16218 ,0,0,0}, {27635,27636,27593 ,16260,16261,16220 ,0,0,0}, + {27634,27592,27591 ,16259,16219,15368 ,0,0,0}, {27594,27636,27551 ,16221,16261,16180 ,0,0,0}, + {27593,27592,27635 ,16220,16219,16260 ,0,0,0}, {27637,27638,27639 ,16262,16263,16264 ,0,0,0}, + {27636,27594,27593 ,16261,16221,16220 ,0,0,0}, {27552,27637,27595 ,16181,16262,16222 ,0,0,0}, + {27551,27550,27594 ,16180,16179,16221 ,0,0,0}, {27637,27640,27596 ,16262,16265,16223 ,0,0,0}, + {27552,27595,27550 ,16181,16222,16179 ,0,0,0}, {27640,27641,27597 ,16265,16266,16224 ,0,0,0}, + {27637,27596,27595 ,16262,16223,16222 ,0,0,0}, {27641,27642,27598 ,16266,16267,16225 ,0,0,0}, + {27640,27597,27596 ,16265,16224,16223 ,0,0,0}, {27514,27642,27643 ,16144,16267,16268 ,0,0,0}, + {27641,27598,27597 ,16266,16225,16224 ,0,0,0}, {27512,27643,27600 ,15354,16268,16227 ,0,0,0}, + {27642,27514,27598 ,16267,16144,16225 ,0,0,0}, {27644,27602,27601 ,16269,16229,16228 ,0,0,0}, + {27643,27512,27514 ,16268,15354,16144 ,0,0,0}, {27645,27646,27647 ,16270,16271,15270 ,0,0,0}, + {27600,27599,27512 ,16227,16226,15354 ,0,0,0}, {27644,27645,27603 ,16269,16270,16230 ,0,0,0}, + {27601,27602,27599 ,16228,16229,16226 ,0,0,0}, {27645,27648,27604 ,16270,16272,16231 ,0,0,0}, + {27644,27603,27602 ,16269,16230,16229 ,0,0,0}, {27648,27649,27605 ,16272,16273,15348 ,0,0,0}, + {27645,27604,27603 ,16270,16231,16230 ,0,0,0}, {27649,27650,27606 ,16273,16274,16232 ,0,0,0}, + {27648,27605,27604 ,16272,15348,16231 ,0,0,0}, {27650,27651,27607 ,16274,16275,16233 ,0,0,0}, + {27649,27606,27605 ,16273,16232,15348 ,0,0,0}, {27651,27652,27608 ,16275,16276,16234 ,0,0,0}, + {27650,27607,27606 ,16274,16233,16232 ,0,0,0}, {27652,27653,27609 ,16276,16277,16235 ,0,0,0}, + {27651,27608,27607 ,16275,16234,16233 ,0,0,0}, {27440,27653,27442 ,16073,16277,16075 ,0,0,0}, + {27609,27608,27652 ,16235,16234,16276 ,0,0,0}, {27447,27442,27653 ,16080,16075,16277 ,0,0,0}, + {27440,27609,27653 ,16073,16235,16277 ,0,0,0}, {27444,27567,27610 ,16077,16195,16236 ,0,0,0}, + {27568,27610,27569 ,16196,16236,16197 ,0,0,0}, {27426,27444,27568 ,15392,16077,16196 ,0,0,0}, + {27443,27567,27444 ,16076,16195,16077 ,0,0,0}, {26975,27610,26842 ,15113,16236,15118 ,0,0,0}, + {27348,27613,27344 ,15999,16239,15995 ,0,0,0}, {27356,27350,27349 ,16007,16001,16000 ,0,0,0}, + {27611,27654,27655 ,16237,16278,16279 ,0,0,0}, {27613,27611,27571 ,16239,16237,16200 ,0,0,0}, + {27348,27656,27613 ,15999,16280,16239 ,0,0,0}, {27612,27655,27657 ,16238,16279,16281 ,0,0,0}, + {27613,27654,27611 ,16239,16278,16237 ,0,0,0}, {27614,27657,27658 ,16240,16281,16282 ,0,0,0}, + {27611,27655,27612 ,16237,16279,16238 ,0,0,0}, {27573,27658,27659 ,16202,16282,16283 ,0,0,0}, + {27612,27657,27614 ,16238,16281,16240 ,0,0,0}, {27574,27659,27660 ,16203,16283,16284 ,0,0,0}, + {27614,27658,27573 ,16240,16282,16202 ,0,0,0}, {27615,27660,27661 ,16241,16284,15296 ,0,0,0}, + {27573,27659,27574 ,16202,16283,16203 ,0,0,0}, {27616,27661,27618 ,16242,15296,16244 ,0,0,0}, + {27660,27615,27574 ,16284,16241,16203 ,0,0,0}, {27662,27620,27619 ,15293,16246,16245 ,0,0,0}, + {27661,27616,27615 ,15296,16242,16241 ,0,0,0}, {27663,27664,27662 ,16285,16286,15293 ,0,0,0}, + {27618,27617,27616 ,16244,16243,16242 ,0,0,0}, {27662,27664,27621 ,15293,16286,16247 ,0,0,0}, + {27619,27620,27617 ,16245,16246,16243 ,0,0,0}, {27664,27665,27622 ,16286,15164,16248 ,0,0,0}, + {27662,27621,27620 ,15293,16247,16246 ,0,0,0}, {27623,27665,27666 ,16249,15164,16287 ,0,0,0}, + {27664,27622,27621 ,16286,16248,16247 ,0,0,0}, {27624,27666,27667 ,16250,16287,16288 ,0,0,0}, + {27622,27665,27623 ,16248,15164,16249 ,0,0,0}, {27583,27667,27668 ,16211,16288,16289 ,0,0,0}, + {27623,27666,27624 ,16249,16287,16250 ,0,0,0}, {27584,27668,27626 ,16212,16289,16252 ,0,0,0}, + {27667,27583,27624 ,16288,16211,16250 ,0,0,0}, {27669,27670,27627 ,16290,16291,16253 ,0,0,0}, + {27668,27584,27583 ,16289,16212,16211 ,0,0,0}, {27627,27670,27628 ,16253,16291,16254 ,0,0,0}, + {27626,27625,27584 ,16252,16251,16212 ,0,0,0}, {27670,27671,27629 ,16291,16292,16255 ,0,0,0}, + {27627,27628,27625 ,16253,16254,16251 ,0,0,0}, {27630,27671,27672 ,16256,16292,16293 ,0,0,0}, + {27670,27629,27628 ,16291,16255,16254 ,0,0,0}, {27544,27672,27673 ,16173,16293,16294 ,0,0,0}, + {27629,27671,27630 ,16255,16292,16256 ,0,0,0}, {27545,27673,27632 ,16174,16294,15282 ,0,0,0}, + {27672,27544,27630 ,16293,16173,16256 ,0,0,0}, {27674,27675,27633 ,16295,16296,16258 ,0,0,0}, + {27673,27545,27544 ,16294,16174,16173 ,0,0,0}, {27633,27675,27634 ,16258,16296,16259 ,0,0,0}, + {27632,27631,27545 ,15282,16257,16174 ,0,0,0}, {27675,27676,27635 ,16296,16297,16260 ,0,0,0}, + {27633,27634,27631 ,16258,16259,16257 ,0,0,0}, {27636,27676,27677 ,16261,16297,16298 ,0,0,0}, + {27675,27635,27634 ,16296,16260,16259 ,0,0,0}, {27551,27677,27678 ,16180,16298,16299 ,0,0,0}, + {27635,27676,27636 ,16260,16297,16261 ,0,0,0}, {27552,27678,27638 ,16181,16299,16263 ,0,0,0}, + {27677,27551,27636 ,16298,16180,16261 ,0,0,0}, {27679,27680,27639 ,16300,16301,16264 ,0,0,0}, + {27678,27552,27551 ,16299,16181,16180 ,0,0,0}, {27639,27680,27640 ,16264,16301,16265 ,0,0,0}, + {27638,27637,27552 ,16263,16262,16181 ,0,0,0}, {27680,27681,27641 ,16301,16302,16266 ,0,0,0}, + {27639,27640,27637 ,16264,16265,16262 ,0,0,0}, {27642,27681,27682 ,16267,16302,15083 ,0,0,0}, + {27680,27641,27640 ,16301,16266,16265 ,0,0,0}, {27643,27682,27683 ,16268,15083,16303 ,0,0,0}, + {27641,27681,27642 ,16266,16302,16267 ,0,0,0}, {27600,27683,27684 ,16227,16303,15273 ,0,0,0}, + {27642,27682,27643 ,16267,15083,16268 ,0,0,0}, {27601,27684,27685 ,16228,15273,16304 ,0,0,0}, + {27643,27683,27600 ,16268,16303,16227 ,0,0,0}, {27644,27685,27646 ,16269,16304,16271 ,0,0,0}, + {27684,27601,27600 ,15273,16228,16227 ,0,0,0}, {27686,27648,27647 ,16305,16272,15270 ,0,0,0}, + {27685,27644,27601 ,16304,16269,16228 ,0,0,0}, {27687,27688,27686 ,16306,16307,16305 ,0,0,0}, + {27646,27645,27644 ,16271,16270,16269 ,0,0,0}, {27686,27688,27649 ,16305,16307,16273 ,0,0,0}, + {27647,27648,27645 ,15270,16272,16270 ,0,0,0}, {27688,27689,27650 ,16307,16308,16274 ,0,0,0}, + {27686,27649,27648 ,16305,16273,16272 ,0,0,0}, {27689,27690,27651 ,16308,16309,16275 ,0,0,0}, + {27688,27650,27649 ,16307,16274,16273 ,0,0,0}, {27690,27691,27652 ,16309,15110,16276 ,0,0,0}, + {27689,27651,27650 ,16308,16275,16274 ,0,0,0}, {27653,27691,27447 ,16277,15110,16080 ,0,0,0}, + {27690,27652,27651 ,16309,16276,16275 ,0,0,0}, {27447,27692,27442 ,16080,16310,16075 ,0,0,0}, + {27652,27691,27653 ,16276,15110,16277 ,0,0,0}, {26847,27567,27448 ,16311,16195,16082 ,0,0,0}, + {27567,26980,27610 ,16195,15128,16236 ,0,0,0}, {27425,27443,27444 ,16059,16076,16077 ,0,0,0}, + {27692,27448,27443 ,16310,16082,16076 ,0,0,0}, {26847,26980,27567 ,16311,15128,16195 ,0,0,0}, + {27350,27656,27348 ,16001,16280,15999 ,0,0,0}, {27693,27355,27356 ,16312,16006,16007 ,0,0,0}, + {27694,27654,27656 ,16313,16278,16280 ,0,0,0}, {27656,27654,27613 ,16280,16278,16239 ,0,0,0}, + {27656,27527,27694 ,16280,16158,16313 ,0,0,0}, {27695,27655,27654 ,16314,16279,16278 ,0,0,0}, + {27654,27694,27695 ,16278,16313,16314 ,0,0,0}, {27696,27657,27655 ,16315,16281,16279 ,0,0,0}, + {27655,27695,27696 ,16279,16314,16315 ,0,0,0}, {27697,27658,27657 ,16316,16282,16281 ,0,0,0}, + {27657,27696,27697 ,16281,16315,16316 ,0,0,0}, {27698,27659,27658 ,16317,16283,16282 ,0,0,0}, + {27658,27697,27698 ,16282,16316,16317 ,0,0,0}, {27699,27660,27659 ,16318,16284,16283 ,0,0,0}, + {27659,27698,27699 ,16283,16317,16318 ,0,0,0}, {27700,27661,27660 ,16319,15296,16284 ,0,0,0}, + {27660,27699,27700 ,16284,16318,16319 ,0,0,0}, {27701,27618,27661 ,16320,16244,15296 ,0,0,0}, + {27661,27700,27701 ,15296,16319,16320 ,0,0,0}, {27702,27619,27618 ,16321,16245,16244 ,0,0,0}, + {27618,27701,27702 ,16244,16320,16321 ,0,0,0}, {27703,27662,27619 ,16322,15293,16245 ,0,0,0}, + {27702,27703,27619 ,16321,16322,16245 ,0,0,0}, {27704,27705,27706 ,16323,16324,15168 ,0,0,0}, + {27703,27663,27662 ,16322,16285,15293 ,0,0,0}, {27707,27665,27664 ,16325,15164,16286 ,0,0,0}, + {27663,27707,27664 ,16285,16325,16286 ,0,0,0}, {27708,27666,27665 ,16326,16287,15164 ,0,0,0}, + {27665,27707,27708 ,15164,16325,16326 ,0,0,0}, {27709,27667,27666 ,16327,16288,16287 ,0,0,0}, + {27666,27708,27709 ,16287,16326,16327 ,0,0,0}, {27710,27668,27667 ,16328,16289,16288 ,0,0,0}, + {27667,27709,27710 ,16288,16327,16328 ,0,0,0}, {27711,27626,27668 ,15249,16252,16289 ,0,0,0}, + {27668,27710,27711 ,16289,16328,15249 ,0,0,0}, {27712,27627,27626 ,16329,16253,16252 ,0,0,0}, + {27711,27712,27626 ,15249,16329,16252 ,0,0,0}, {27713,27669,27714 ,16330,16290,16331 ,0,0,0}, + {27712,27669,27627 ,16329,16290,16253 ,0,0,0}, {27713,27671,27670 ,16330,16292,16291 ,0,0,0}, + {27669,27713,27670 ,16290,16330,16291 ,0,0,0}, {27715,27672,27671 ,16332,16293,16292 ,0,0,0}, + {27671,27713,27715 ,16292,16330,16332 ,0,0,0}, {27716,27673,27672 ,16333,16294,16293 ,0,0,0}, + {27672,27715,27716 ,16293,16332,16333 ,0,0,0}, {27717,27632,27673 ,15244,15282,16294 ,0,0,0}, + {27673,27716,27717 ,16294,16333,15244 ,0,0,0}, {27718,27633,27632 ,16334,16258,15282 ,0,0,0}, + {27717,27718,27632 ,15244,16334,15282 ,0,0,0}, {27719,27720,27721 ,15135,15136,16335 ,0,0,0}, + {27718,27674,27633 ,16334,16295,16258 ,0,0,0}, {27722,27676,27675 ,16336,16297,16296 ,0,0,0}, + {27674,27722,27675 ,16295,16336,16296 ,0,0,0}, {27723,27677,27676 ,16337,16298,16297 ,0,0,0}, + {27676,27722,27723 ,16297,16336,16337 ,0,0,0}, {27724,27678,27677 ,16338,16299,16298 ,0,0,0}, + {27677,27723,27724 ,16298,16337,16338 ,0,0,0}, {27725,27638,27678 ,16339,16263,16299 ,0,0,0}, + {27678,27724,27725 ,16299,16338,16339 ,0,0,0}, {27726,27639,27638 ,16340,16264,16263 ,0,0,0}, + {27725,27726,27638 ,16339,16340,16263 ,0,0,0}, {27680,27727,27681 ,16301,16341,16302 ,0,0,0}, + {27726,27679,27639 ,16340,16300,16264 ,0,0,0}, {27728,27729,27727 ,16342,15081,16341 ,0,0,0}, + {27679,27727,27680 ,16300,16341,16301 ,0,0,0}, {27729,27682,27681 ,15081,15083,16302 ,0,0,0}, + {27681,27727,27729 ,16302,16341,15081 ,0,0,0}, {27730,27683,27682 ,16343,16303,15083 ,0,0,0}, + {27682,27729,27730 ,15083,15081,16343 ,0,0,0}, {27731,27684,27683 ,16344,15273,16303 ,0,0,0}, + {27683,27730,27731 ,16303,16343,16344 ,0,0,0}, {27732,27685,27684 ,16345,16304,15273 ,0,0,0}, + {27684,27731,27732 ,15273,16344,16345 ,0,0,0}, {27733,27646,27685 ,16346,16271,16304 ,0,0,0}, + {27685,27732,27733 ,16304,16345,16346 ,0,0,0}, {27734,27647,27646 ,15230,15270,16271 ,0,0,0}, + {27646,27733,27734 ,16271,16346,15230 ,0,0,0}, {27735,27686,27647 ,16347,16305,15270 ,0,0,0}, + {27734,27735,27647 ,15230,16347,15270 ,0,0,0}, {27688,27736,27689 ,16307,16348,16308 ,0,0,0}, + {27735,27687,27686 ,16347,16306,16305 ,0,0,0}, {27689,27737,27690 ,16308,16349,16309 ,0,0,0}, + {27687,27736,27688 ,16306,16348,16307 ,0,0,0}, {27690,27738,27691 ,16309,16350,15110 ,0,0,0}, + {27736,27737,27689 ,16348,16349,16308 ,0,0,0}, {27691,27445,27447 ,15110,16078,16080 ,0,0,0}, + {27737,27738,27690 ,16349,16350,16309 ,0,0,0}, {27446,27450,27449 ,16079,16084,16083 ,0,0,0}, + {27738,27445,27691 ,16350,16078,15110 ,0,0,0}, {27446,27692,27447 ,16079,16310,16080 ,0,0,0}, + {27029,26847,27448 ,16351,16311,16082 ,0,0,0}, {27442,27692,27443 ,16075,16310,16076 ,0,0,0}, + {27692,27446,27449 ,16310,16079,16083 ,0,0,0}, {26844,27029,27448 ,16081,16351,16082 ,0,0,0}, + {27355,27527,27350 ,16006,16158,16001 ,0,0,0}, {27693,27358,27353 ,16312,16009,16004 ,0,0,0}, + {27694,27527,27739 ,16313,16158,15217 ,0,0,0}, {27350,27527,27656 ,16001,16158,16280 ,0,0,0}, + {27527,27354,27739 ,16158,16005,15217 ,0,0,0}, {27695,27694,27740 ,16314,16313,16352 ,0,0,0}, + {27694,27739,27740 ,16313,15217,16352 ,0,0,0}, {27696,27695,27741 ,16315,16314,16353 ,0,0,0}, + {27695,27740,27741 ,16314,16352,16353 ,0,0,0}, {27697,27696,27742 ,16316,16315,15188 ,0,0,0}, + {27696,27741,27742 ,16315,16353,15188 ,0,0,0}, {27698,27697,27743 ,16317,16316,16354 ,0,0,0}, + {27697,27742,27743 ,16316,15188,16354 ,0,0,0}, {27699,27698,27744 ,16318,16317,16355 ,0,0,0}, + {27698,27743,27744 ,16317,16354,16355 ,0,0,0}, {27700,27699,27745 ,16319,16318,16356 ,0,0,0}, + {27699,27744,27745 ,16318,16355,16356 ,0,0,0}, {27701,27700,27746 ,16320,16319,16357 ,0,0,0}, + {27700,27745,27746 ,16319,16356,16357 ,0,0,0}, {27702,27701,27747 ,16321,16320,16358 ,0,0,0}, + {27701,27746,27747 ,16320,16357,16358 ,0,0,0}, {27703,27702,27748 ,16322,16321,15175 ,0,0,0}, + {27702,27747,27748 ,16321,16358,15175 ,0,0,0}, {27663,27703,27749 ,16285,16322,16359 ,0,0,0}, + {27703,27748,27749 ,16322,15175,16359 ,0,0,0}, {27707,27663,27704 ,16325,16285,16323 ,0,0,0}, + {27749,27704,27663 ,16359,16323,16285 ,0,0,0}, {27708,27707,27706 ,16326,16325,15168 ,0,0,0}, + {27707,27704,27706 ,16325,16323,15168 ,0,0,0}, {27709,27708,27750 ,16327,16326,16360 ,0,0,0}, + {27708,27706,27750 ,16326,15168,16360 ,0,0,0}, {27710,27709,27751 ,16328,16327,16361 ,0,0,0}, + {27709,27750,27751 ,16327,16360,16361 ,0,0,0}, {27711,27710,27752 ,15249,16328,16362 ,0,0,0}, + {27710,27751,27752 ,16328,16361,16362 ,0,0,0}, {27712,27711,27753 ,16329,15249,16363 ,0,0,0}, + {27711,27752,27753 ,15249,16362,16363 ,0,0,0}, {27669,27712,27754 ,16290,16329,15155 ,0,0,0}, + {27712,27753,27754 ,16329,16363,15155 ,0,0,0}, {27754,27755,27714 ,15155,15153,16331 ,0,0,0}, + {27754,27714,27669 ,15155,16331,16290 ,0,0,0}, {27715,27713,27756 ,16332,16330,16364 ,0,0,0}, + {27713,27714,27756 ,16330,16331,16364 ,0,0,0}, {27716,27715,27757 ,16333,16332,16365 ,0,0,0}, + {27715,27756,27757 ,16332,16364,16365 ,0,0,0}, {27717,27716,27758 ,15244,16333,16366 ,0,0,0}, + {27716,27757,27758 ,16333,16365,16366 ,0,0,0}, {27718,27717,27759 ,16334,15244,16367 ,0,0,0}, + {27717,27758,27759 ,15244,16366,16367 ,0,0,0}, {27674,27718,27760 ,16295,16334,16368 ,0,0,0}, + {27718,27759,27760 ,16334,16367,16368 ,0,0,0}, {27722,27674,27719 ,16336,16295,15135 ,0,0,0}, + {27760,27719,27674 ,16368,15135,16295 ,0,0,0}, {27723,27722,27721 ,16337,16336,16335 ,0,0,0}, + {27722,27719,27721 ,16336,15135,16335 ,0,0,0}, {27724,27723,27761 ,16338,16337,16369 ,0,0,0}, + {27723,27721,27761 ,16337,16335,16369 ,0,0,0}, {27725,27724,27762 ,16339,16338,16370 ,0,0,0}, + {27724,27761,27762 ,16338,16369,16370 ,0,0,0}, {27726,27725,27763 ,16340,16339,16371 ,0,0,0}, + {27725,27762,27763 ,16339,16370,16371 ,0,0,0}, {27679,27726,27764 ,16300,16340,16372 ,0,0,0}, + {27726,27763,27764 ,16340,16371,16372 ,0,0,0}, {27727,27679,27765 ,16341,16300,15070 ,0,0,0}, + {27679,27764,27765 ,16300,16372,15070 ,0,0,0}, {27728,27765,27766 ,16342,15070,15074 ,0,0,0}, + {27765,27728,27727 ,15070,16342,16341 ,0,0,0}, {27730,27729,27767 ,16343,15081,16373 ,0,0,0}, + {27729,27728,27767 ,15081,16342,16373 ,0,0,0}, {27731,27730,27768 ,16344,16343,15078 ,0,0,0}, + {27730,27767,27768 ,16343,16373,15078 ,0,0,0}, {27732,27731,27769 ,16345,16344,16374 ,0,0,0}, + {27731,27768,27769 ,16344,15078,16374 ,0,0,0}, {27733,27732,27770 ,16346,16345,16375 ,0,0,0}, + {27732,27769,27770 ,16345,16374,16375 ,0,0,0}, {27734,27733,27771 ,15230,16346,16376 ,0,0,0}, + {27733,27770,27771 ,16346,16375,16376 ,0,0,0}, {27735,27734,27772 ,16347,15230,16377 ,0,0,0}, + {27734,27771,27772 ,15230,16376,16377 ,0,0,0}, {27687,27735,27773 ,16306,16347,16378 ,0,0,0}, + {27735,27772,27773 ,16347,16377,16378 ,0,0,0}, {27736,27687,27774 ,16348,16306,16379 ,0,0,0}, + {27687,27773,27774 ,16306,16378,16379 ,0,0,0}, {27737,27736,27775 ,16349,16348,16380 ,0,0,0}, + {27736,27774,27775 ,16348,16379,16380 ,0,0,0}, {27738,27737,27776 ,16350,16349,16381 ,0,0,0}, + {27737,27775,27776 ,16349,16380,16381 ,0,0,0}, {27445,27738,27777 ,16078,16350,16382 ,0,0,0}, + {27738,27776,27777 ,16350,16381,16382 ,0,0,0}, {27778,27446,27445 ,16383,16079,16078 ,0,0,0}, + {27777,27778,27445 ,16382,16383,16078 ,0,0,0}, {27692,27449,27448 ,16310,16083,16082 ,0,0,0}, + {27778,27450,27446 ,16383,16084,16079 ,0,0,0}, {26844,27449,27199 ,16081,16083,16085 ,0,0,0}, + {27353,27355,27693 ,16004,16006,16312 ,0,0,0}, {27362,27359,27353 ,16013,16010,16004 ,0,0,0}, + {27359,27779,27354 ,16010,16384,16005 ,0,0,0}, {27354,27779,27739 ,16005,16384,15217 ,0,0,0}, + {27779,27780,27739 ,16384,15219,15217 ,0,0,0}, {27739,27780,27740 ,15217,15219,16352 ,0,0,0}, + {27780,27781,27740 ,15219,15214,16352 ,0,0,0}, {27740,27781,27741 ,16352,15214,16353 ,0,0,0}, + {27781,27782,27741 ,15214,15193,16353 ,0,0,0}, {27741,27782,27742 ,16353,15193,15188 ,0,0,0}, + {27782,27783,27742 ,15193,16385,15188 ,0,0,0}, {27742,27783,27743 ,15188,16385,16354 ,0,0,0}, + {27783,27784,27743 ,16385,16386,16354 ,0,0,0}, {27743,27784,27744 ,16354,16386,16355 ,0,0,0}, + {27784,27785,27744 ,16386,16387,16355 ,0,0,0}, {27744,27785,27745 ,16355,16387,16356 ,0,0,0}, + {27785,27786,27745 ,16387,16388,16356 ,0,0,0}, {27786,27787,27746 ,16388,16389,16357 ,0,0,0}, + {27786,27746,27745 ,16388,16357,16356 ,0,0,0}, {27787,27788,27747 ,16389,16390,16358 ,0,0,0}, + {27787,27747,27746 ,16389,16358,16357 ,0,0,0}, {27788,27789,27748 ,16390,16391,15175 ,0,0,0}, + {27788,27748,27747 ,16390,15175,16358 ,0,0,0}, {27789,27790,27749 ,16391,15172,16359 ,0,0,0}, + {27789,27749,27748 ,16391,16359,15175 ,0,0,0}, {27790,27791,27704 ,15172,16392,16323 ,0,0,0}, + {27790,27704,27749 ,15172,16323,16359 ,0,0,0}, {27705,27704,27791 ,16324,16323,16392 ,0,0,0}, + {27705,27792,27706 ,16324,15167,15168 ,0,0,0}, {27706,27792,27750 ,15168,15167,16360 ,0,0,0}, + {27792,27793,27750 ,15167,15162,16360 ,0,0,0}, {27750,27793,27751 ,16360,15162,16361 ,0,0,0}, + {27793,27794,27751 ,15162,15159,16361 ,0,0,0}, {27794,27795,27752 ,15159,16393,16362 ,0,0,0}, + {27794,27752,27751 ,15159,16362,16361 ,0,0,0}, {27795,27796,27753 ,16393,15156,16363 ,0,0,0}, + {27795,27753,27752 ,16393,16363,16362 ,0,0,0}, {27796,27755,27754 ,15156,15153,15155 ,0,0,0}, + {27796,27754,27753 ,15156,15155,16363 ,0,0,0}, {27755,27797,27714 ,15153,16394,16331 ,0,0,0}, + {27797,27798,27714 ,16394,15152,16331 ,0,0,0}, {27714,27798,27756 ,16331,15152,16364 ,0,0,0}, + {27798,27799,27756 ,15152,15150,16364 ,0,0,0}, {27756,27799,27757 ,16364,15150,16365 ,0,0,0}, + {27799,27800,27757 ,15150,16395,16365 ,0,0,0}, {27800,27801,27758 ,16395,15142,16366 ,0,0,0}, + {27800,27758,27757 ,16395,16366,16365 ,0,0,0}, {27801,27802,27759 ,15142,16396,16367 ,0,0,0}, + {27801,27759,27758 ,15142,16367,16366 ,0,0,0}, {27802,27803,27760 ,16396,15138,16368 ,0,0,0}, + {27802,27760,27759 ,16396,16368,16367 ,0,0,0}, {27803,27804,27719 ,15138,16397,15135 ,0,0,0}, + {27803,27719,27760 ,15138,15135,16368 ,0,0,0}, {27720,27719,27804 ,15136,15135,16397 ,0,0,0}, + {27720,27805,27721 ,15136,16398,16335 ,0,0,0}, {27721,27805,27761 ,16335,16398,16369 ,0,0,0}, + {27805,27806,27761 ,16398,15077,16369 ,0,0,0}, {27806,27807,27762 ,15077,15065,16370 ,0,0,0}, + {27806,27762,27761 ,15077,16370,16369 ,0,0,0}, {27807,27808,27763 ,15065,16399,16371 ,0,0,0}, + {27807,27763,27762 ,15065,16371,16370 ,0,0,0}, {27808,27809,27764 ,16399,16400,16372 ,0,0,0}, + {27808,27764,27763 ,16399,16372,16371 ,0,0,0}, {27809,27766,27765 ,16400,15074,15070 ,0,0,0}, + {27809,27765,27764 ,16400,15070,16372 ,0,0,0}, {27766,27810,27728 ,15074,16401,16342 ,0,0,0}, + {27810,27811,27728 ,16401,16402,16342 ,0,0,0}, {27728,27811,27767 ,16342,16402,16373 ,0,0,0}, + {27811,27812,27767 ,16402,15075,16373 ,0,0,0}, {27767,27812,27768 ,16373,15075,15078 ,0,0,0}, + {27812,27813,27768 ,15075,15079,15078 ,0,0,0}, {27768,27813,27769 ,15078,15079,16374 ,0,0,0}, + {27813,27814,27769 ,15079,15085,16374 ,0,0,0}, {27814,27815,27770 ,15085,16403,16375 ,0,0,0}, + {27814,27770,27769 ,15085,16375,16374 ,0,0,0}, {27815,27816,27771 ,16403,16404,16376 ,0,0,0}, + {27815,27771,27770 ,16403,16376,16375 ,0,0,0}, {27816,27817,27772 ,16404,16405,16377 ,0,0,0}, + {27816,27772,27771 ,16404,16377,16376 ,0,0,0}, {27817,27818,27773 ,16405,15091,16378 ,0,0,0}, + {27817,27773,27772 ,16405,16378,16377 ,0,0,0}, {27818,27819,27774 ,15091,16406,16379 ,0,0,0}, + {27818,27774,27773 ,15091,16379,16378 ,0,0,0}, {27819,27820,27775 ,16406,16407,16380 ,0,0,0}, + {27819,27775,27774 ,16406,16380,16379 ,0,0,0}, {27820,27821,27776 ,16407,16408,16381 ,0,0,0}, + {27820,27776,27775 ,16407,16381,16380 ,0,0,0}, {27821,27822,27777 ,16408,16409,16382 ,0,0,0}, + {27821,27777,27776 ,16408,16382,16381 ,0,0,0}, {27822,27823,27778 ,16409,16410,16383 ,0,0,0}, + {27822,27778,27777 ,16409,16383,16382 ,0,0,0}, {27451,27778,27823 ,16088,16383,16410 ,0,0,0}, + {27778,27451,27450 ,16383,16088,16084 ,0,0,0}, {26852,27450,27451 ,16086,16084,16088 ,0,0,0}, + {27824,27825,27795 ,16411,16412,14033 ,0,0,0}, {27795,27794,27824 ,14033,14034,16411 ,0,0,0}, + {27826,27827,27828 ,16413,16414,16415 ,0,0,0}, {27829,27793,27792 ,16416,16417,14036 ,0,0,0}, + {27794,27793,27830 ,14034,16417,16418 ,0,0,0}, {27829,27830,27793 ,16416,16418,16417 ,0,0,0}, + {27705,27791,27831 ,13993,16419,16420 ,0,0,0}, {27832,27705,27831 ,13992,13993,16420 ,0,0,0}, + {27792,27705,27832 ,14036,13993,13992 ,0,0,0}, {27831,27790,27833 ,16420,16421,13994 ,0,0,0}, + {27792,27832,27829 ,14036,13992,16416 ,0,0,0}, {27831,27791,27790 ,16420,16419,16421 ,0,0,0}, + {27830,27824,27794 ,16418,16411,14034 ,0,0,0}, {27834,27789,27788 ,13995,14039,14040 ,0,0,0}, + {27834,27833,27789 ,13995,13994,14039 ,0,0,0}, {27835,27834,27788 ,16422,13995,14040 ,0,0,0}, + {27836,27837,27838 ,13907,13956,16423 ,0,0,0}, {27839,27835,27787 ,16424,16422,14041 ,0,0,0}, + {27786,27839,27787 ,16425,16424,14041 ,0,0,0}, {27840,27786,27785 ,13998,16425,16426 ,0,0,0}, + {27839,27786,27840 ,16424,16425,13998 ,0,0,0}, {27841,27840,27785 ,16427,13998,16426 ,0,0,0}, + {27787,27835,27788 ,14041,16422,14040 ,0,0,0}, {27833,27790,27789 ,13994,16421,14039 ,0,0,0}, + {27842,27783,27843 ,16428,14045,14001 ,0,0,0}, {27784,27842,27841 ,16429,16428,16427 ,0,0,0}, + {27782,27844,27843 ,16430,16431,14001 ,0,0,0}, {27784,27783,27842 ,16429,14045,16428 ,0,0,0}, + {27844,27781,27845 ,16431,16432,16433 ,0,0,0}, {27781,27844,27782 ,16432,16431,16430 ,0,0,0}, + {27845,27780,27846 ,16433,16434,16435 ,0,0,0}, {27783,27782,27843 ,14045,16430,14001 ,0,0,0}, + {27781,27780,27845 ,16432,16434,16433 ,0,0,0}, {27845,27847,27848 ,16433,16436,16437 ,0,0,0}, + {27479,27849,27483 ,16438,16439,16116 ,0,0,0}, {27850,27851,27852 ,16440,16441,16442 ,0,0,0}, + {27849,27853,27483 ,16439,16443,16116 ,0,0,0}, {27854,27855,27856 ,16444,13641,16445 ,0,0,0}, + {27849,27479,27854 ,16439,16438,16444 ,0,0,0}, {27846,27780,27779 ,16435,16434,16446 ,0,0,0}, + {27848,27857,27858 ,16437,16447,16448 ,0,0,0}, {27859,27860,27858 ,16449,16450,16448 ,0,0,0}, + {27858,27857,27861 ,16448,16447,16451 ,0,0,0}, {27779,27359,27862 ,16446,16452,16453 ,0,0,0}, + {27863,27864,27865 ,16454,16455,16456 ,0,0,0}, {27864,27866,27867 ,16455,16457,16458 ,0,0,0}, + {27866,27868,27867 ,16457,16459,16458 ,0,0,0}, {27869,27865,27870 ,16460,16456,16461 ,0,0,0}, + {27871,27870,27357 ,16462,16461,16008 ,0,0,0}, {27359,27870,27862 ,16452,16461,16453 ,0,0,0}, + {27870,27362,27357 ,16461,16463,16008 ,0,0,0}, {27871,27869,27870 ,16462,16460,16461 ,0,0,0}, + {27851,27872,27873 ,16441,16464,16465 ,0,0,0}, {27784,27841,27785 ,16429,16427,16426 ,0,0,0}, + {27825,27796,27795 ,16412,16466,14033 ,0,0,0}, {27755,27796,27874 ,13947,16466,16467 ,0,0,0}, + {27825,27874,27796 ,16412,16467,16466 ,0,0,0}, {27875,27797,27755 ,16468,16469,13947 ,0,0,0}, + {27755,27874,27875 ,13947,16467,16468 ,0,0,0}, {27798,27875,27876 ,14030,16468,13987 ,0,0,0}, + {27875,27798,27797 ,16468,14030,16469 ,0,0,0}, {27877,27799,27876 ,16470,16471,13987 ,0,0,0}, + {27798,27876,27799 ,14030,13987,16471 ,0,0,0}, {27800,27799,27877 ,14028,16471,16470 ,0,0,0}, + {27877,27878,27800 ,16470,16472,14028 ,0,0,0}, {27800,27878,27801 ,14028,16472,16473 ,0,0,0}, + {27801,27878,27879 ,16473,16472,16474 ,0,0,0}, {27880,27881,27882 ,16475,16476,16477 ,0,0,0}, + {27883,27802,27879 ,16478,14026,16474 ,0,0,0}, {27801,27879,27802 ,16473,16474,14026 ,0,0,0}, + {27883,27884,27803 ,16478,16479,14025 ,0,0,0}, {27803,27802,27883 ,14025,14026,16478 ,0,0,0}, + {27720,27804,27884 ,13982,16480,16479 ,0,0,0}, {27884,27804,27803 ,16479,16480,14025 ,0,0,0}, + {27885,27805,27720 ,13981,14023,13982 ,0,0,0}, {27720,27884,27885 ,13982,16479,13981 ,0,0,0}, + {27805,27886,27806 ,14023,16481,16482 ,0,0,0}, {27886,27805,27885 ,16481,14023,13981 ,0,0,0}, + {27807,27806,27887 ,14021,16482,16483 ,0,0,0}, {27886,27887,27806 ,16481,16483,16482 ,0,0,0}, + {27888,27807,27887 ,16484,14021,16483 ,0,0,0}, {27888,27808,27807 ,16484,14020,14021 ,0,0,0}, + {27888,27889,27808 ,16484,16485,14020 ,0,0,0}, {27890,27891,27892 ,13890,16486,16487 ,0,0,0}, + {27809,27889,27893 ,14019,16485,13933 ,0,0,0}, {27889,27809,27808 ,16485,14019,14020 ,0,0,0}, + {27894,27766,27893 ,16488,16489,13933 ,0,0,0}, {27809,27893,27766 ,14019,13933,16489 ,0,0,0}, + {27810,27894,27811 ,16490,16488,16491 ,0,0,0}, {27810,27766,27894 ,16490,16489,16488 ,0,0,0}, + {27812,27811,27895 ,16492,16491,16493 ,0,0,0}, {27894,27895,27811 ,16488,16493,16491 ,0,0,0}, + {27896,27813,27812 ,16494,16495,16492 ,0,0,0}, {27812,27895,27896 ,16492,16493,16494 ,0,0,0}, + {27813,27897,27814 ,16495,16496,16497 ,0,0,0}, {27897,27813,27896 ,16496,16495,16494 ,0,0,0}, + {27815,27814,27898 ,16498,16497,16499 ,0,0,0}, {27897,27898,27814 ,16496,16499,16497 ,0,0,0}, + {27899,27815,27898 ,16500,16498,16499 ,0,0,0}, {27899,27816,27815 ,16500,16501,16498 ,0,0,0}, + {27899,27900,27816 ,16500,16502,16501 ,0,0,0}, {27901,27902,27903 ,16503,16504,16505 ,0,0,0}, + {27817,27900,27902 ,16506,16502,16504 ,0,0,0}, {27900,27817,27816 ,16502,16506,16501 ,0,0,0}, + {27904,27818,27902 ,16507,16508,16504 ,0,0,0}, {27817,27902,27818 ,16506,16504,16508 ,0,0,0}, + {27905,27906,27907 ,16509,16510,16511 ,0,0,0}, {27819,27818,27904 ,16512,16508,16507 ,0,0,0}, + {27908,27909,27910 ,16513,16514,16515 ,0,0,0}, {27911,27912,27913 ,16516,16517,16518 ,0,0,0}, + {27914,27915,27916 ,16519,16520,16521 ,0,0,0}, {27917,27918,27919 ,16522,16523,16524 ,0,0,0}, + {27920,27921,27908 ,16525,16526,16513 ,0,0,0}, {27922,27923,27924 ,16527,16528,16529 ,0,0,0}, + {27925,27926,27921 ,16530,16531,16526 ,0,0,0}, {27922,27917,27923 ,16527,16522,16528 ,0,0,0}, + {27921,27927,27928 ,16526,16532,16533 ,0,0,0}, {27431,26982,27924 ,16534,726,16529 ,0,0,0}, + {27929,27819,27904 ,16535,16512,16507 ,0,0,0}, {27819,27929,27820 ,16512,16535,14008 ,0,0,0}, + {27820,27905,27821 ,14008,16509,14007 ,0,0,0}, {27901,27904,27902 ,16503,16507,16504 ,0,0,0}, + {27930,27931,27822 ,16536,16537,16538 ,0,0,0}, {27905,27930,27821 ,16509,16536,14007 ,0,0,0}, + {27928,27930,27907 ,16533,16536,16511 ,0,0,0}, {27821,27930,27822 ,14007,16536,16538 ,0,0,0}, + {27931,27932,27451 ,16537,16539,16540 ,0,0,0}, {27931,27451,27823 ,16537,16540,16541 ,0,0,0}, + {26853,27451,27933 ,16087,16540,16542 ,0,0,0}, {27870,27359,27362 ,16461,16452,16463 ,0,0,0}, + {27863,27865,27869 ,16454,16456,16460 ,0,0,0}, {27873,27872,27934 ,16465,16464,16543 ,0,0,0}, + {27862,27846,27779 ,16453,16435,16446 ,0,0,0}, {27862,27865,27935 ,16453,16456,16544 ,0,0,0}, + {27936,27844,27848 ,16545,16431,16437 ,0,0,0}, {27846,27935,27847 ,16435,16544,16436 ,0,0,0}, + {27937,27843,27936 ,16546,14001,16545 ,0,0,0}, {27847,27845,27846 ,16436,16433,16435 ,0,0,0}, + {27938,27842,27937 ,16547,16428,16546 ,0,0,0}, {27848,27844,27845 ,16437,16431,16433 ,0,0,0}, + {27939,27841,27938 ,16548,16427,16547 ,0,0,0}, {27936,27843,27844 ,16545,14001,16431 ,0,0,0}, + {27940,27840,27939 ,13961,13998,16548 ,0,0,0}, {27937,27842,27843 ,16546,16428,14001 ,0,0,0}, + {27941,27839,27940 ,16549,16424,13961 ,0,0,0}, {27938,27841,27842 ,16547,16427,16428 ,0,0,0}, + {27942,27835,27941 ,16550,16422,16549 ,0,0,0}, {27939,27840,27841 ,16548,13998,16427 ,0,0,0}, + {27942,27943,27834 ,16550,16551,13995 ,0,0,0}, {27839,27840,27940 ,16424,13998,13961 ,0,0,0}, + {27944,27833,27943 ,16552,13994,16551 ,0,0,0}, {27835,27839,27941 ,16422,16424,16549 ,0,0,0}, + {27837,27831,27944 ,13956,16420,16552 ,0,0,0}, {27834,27835,27942 ,13995,16422,16550 ,0,0,0}, + {27945,27832,27837 ,16553,13992,13956 ,0,0,0}, {27833,27834,27943 ,13994,13995,16551 ,0,0,0}, + {27946,27829,27945 ,16554,16416,16553 ,0,0,0}, {27831,27833,27944 ,16420,13994,16552 ,0,0,0}, + {27947,27830,27946 ,16555,16418,16554 ,0,0,0}, {27837,27832,27831 ,13956,13992,16420 ,0,0,0}, + {27948,27824,27947 ,16556,16411,16555 ,0,0,0}, {27945,27829,27832 ,16553,16416,13992 ,0,0,0}, + {27948,27949,27825 ,16556,16557,16412 ,0,0,0}, {27830,27829,27946 ,16418,16416,16554 ,0,0,0}, + {27950,27874,27949 ,16558,16467,16557 ,0,0,0}, {27824,27830,27947 ,16411,16418,16555 ,0,0,0}, + {27951,27875,27950 ,16559,16468,16558 ,0,0,0}, {27825,27824,27948 ,16412,16411,16556 ,0,0,0}, + {27952,27876,27951 ,16560,13987,16559 ,0,0,0}, {27874,27825,27949 ,16467,16412,16557 ,0,0,0}, + {27953,27877,27952 ,16561,16470,16560 ,0,0,0}, {27875,27874,27950 ,16468,16467,16558 ,0,0,0}, + {27954,27878,27953 ,13944,16472,16561 ,0,0,0}, {27951,27876,27875 ,16559,13987,16468 ,0,0,0}, + {27954,27955,27879 ,13944,16562,16474 ,0,0,0}, {27877,27876,27952 ,16470,13987,16560 ,0,0,0}, + {27956,27883,27955 ,16563,16478,16562 ,0,0,0}, {27878,27877,27953 ,16472,16470,16561 ,0,0,0}, + {27880,27884,27956 ,16475,16479,16563 ,0,0,0}, {27879,27878,27954 ,16474,16472,13944 ,0,0,0}, + {27957,27885,27880 ,16564,13981,16475 ,0,0,0}, {27883,27879,27955 ,16478,16474,16562 ,0,0,0}, + {27958,27886,27957 ,16565,16481,16564 ,0,0,0}, {27884,27883,27956 ,16479,16478,16563 ,0,0,0}, + {27959,27887,27958 ,13938,16483,16565 ,0,0,0}, {27880,27885,27884 ,16475,13981,16479 ,0,0,0}, + {27960,27888,27959 ,16566,16484,13938 ,0,0,0}, {27957,27886,27885 ,16564,16481,13981 ,0,0,0}, + {27960,27961,27889 ,16566,16567,16485 ,0,0,0}, {27887,27886,27958 ,16483,16481,16565 ,0,0,0}, + {27962,27893,27961 ,16568,13933,16567 ,0,0,0}, {27888,27887,27959 ,16484,16483,13938 ,0,0,0}, + {27963,27894,27962 ,16569,16488,16568 ,0,0,0}, {27889,27888,27960 ,16485,16484,16566 ,0,0,0}, + {27964,27895,27963 ,16570,16493,16569 ,0,0,0}, {27893,27889,27961 ,13933,16485,16567 ,0,0,0}, + {27965,27896,27964 ,16571,16494,16570 ,0,0,0}, {27962,27894,27893 ,16568,16488,13933 ,0,0,0}, + {27966,27897,27965 ,16572,16496,16571 ,0,0,0}, {27963,27895,27894 ,16569,16493,16488 ,0,0,0}, + {27967,27898,27966 ,16573,16499,16572 ,0,0,0}, {27964,27896,27895 ,16570,16494,16493 ,0,0,0}, + {27968,27899,27967 ,16574,16500,16573 ,0,0,0}, {27965,27897,27896 ,16571,16496,16494 ,0,0,0}, + {27968,27903,27900 ,16574,16505,16502 ,0,0,0}, {27898,27897,27966 ,16499,16496,16572 ,0,0,0}, + {27904,27901,27969 ,16507,16503,16575 ,0,0,0}, {27899,27898,27967 ,16500,16499,16573 ,0,0,0}, + {27925,27907,27913 ,16530,16511,16518 ,0,0,0}, {27900,27899,27968 ,16502,16500,16574 ,0,0,0}, + {27929,27969,27906 ,16535,16575,16510 ,0,0,0}, {27900,27903,27902 ,16502,16505,16504 ,0,0,0}, + {27969,27970,27906 ,16575,16576,16510 ,0,0,0}, {27928,27931,27930 ,16533,16537,16536 ,0,0,0}, + {27929,27905,27820 ,16535,16509,14008 ,0,0,0}, {27969,27929,27904 ,16575,16535,16507 ,0,0,0}, + {27928,27925,27921 ,16533,16530,16526 ,0,0,0}, {27905,27929,27906 ,16509,16535,16510 ,0,0,0}, + {27932,27927,27971 ,16539,16532,16577 ,0,0,0}, {27932,27933,27451 ,16539,16542,16540 ,0,0,0}, + {27822,27931,27823 ,16538,16537,16541 ,0,0,0}, {27932,27931,27927 ,16539,16537,16532 ,0,0,0}, + {27972,27933,27932 ,13920,16542,16539 ,0,0,0}, {27870,27865,27862 ,16461,16456,16453 ,0,0,0}, + {27866,27864,27863 ,16457,16455,16454 ,0,0,0}, {27854,27479,27475 ,16444,16438,16578 ,0,0,0}, + {27862,27935,27846 ,16453,16544,16435 ,0,0,0}, {27973,27935,27864 ,16579,16544,16455 ,0,0,0}, + {27858,27860,27936 ,16448,16450,16545 ,0,0,0}, {27857,27847,27973 ,16447,16436,16579 ,0,0,0}, + {27860,27974,27937 ,16450,16580,16546 ,0,0,0}, {27857,27848,27847 ,16447,16437,16436 ,0,0,0}, + {27974,27975,27938 ,16580,16581,16547 ,0,0,0}, {27858,27936,27848 ,16448,16545,16437 ,0,0,0}, + {27975,27976,27939 ,16581,16582,16548 ,0,0,0}, {27860,27937,27936 ,16450,16546,16545 ,0,0,0}, + {27976,27977,27940 ,16582,13870,13961 ,0,0,0}, {27974,27938,27937 ,16580,16547,16546 ,0,0,0}, + {27977,27978,27941 ,13870,16583,16549 ,0,0,0}, {27975,27939,27938 ,16581,16548,16547 ,0,0,0}, + {27978,27979,27942 ,16583,16584,16550 ,0,0,0}, {27976,27940,27939 ,16582,13961,16548 ,0,0,0}, + {27979,27980,27943 ,16584,13909,16551 ,0,0,0}, {27977,27941,27940 ,13870,16549,13961 ,0,0,0}, + {27980,27838,27944 ,13909,16423,16552 ,0,0,0}, {27942,27941,27978 ,16550,16549,16583 ,0,0,0}, + {27981,27982,27983 ,16585,16586,16587 ,0,0,0}, {27943,27942,27979 ,16551,16550,16584 ,0,0,0}, + {27836,27982,27945 ,13907,16586,16553 ,0,0,0}, {27944,27943,27980 ,16552,16551,13909 ,0,0,0}, + {27982,27981,27946 ,16586,16585,16554 ,0,0,0}, {27837,27944,27838 ,13956,16552,16423 ,0,0,0}, + {27981,27984,27947 ,16585,16588,16555 ,0,0,0}, {27836,27945,27837 ,13907,16553,13956 ,0,0,0}, + {27984,27985,27948 ,16588,16589,16556 ,0,0,0}, {27982,27946,27945 ,16586,16554,16553 ,0,0,0}, + {27985,27986,27949 ,16589,16590,16557 ,0,0,0}, {27981,27947,27946 ,16585,16555,16554 ,0,0,0}, + {27986,27987,27950 ,16590,16591,16558 ,0,0,0}, {27948,27947,27984 ,16556,16555,16588 ,0,0,0}, + {27828,27951,27987 ,16415,16559,16591 ,0,0,0}, {27949,27948,27985 ,16557,16556,16589 ,0,0,0}, + {27828,27827,27952 ,16415,16414,16560 ,0,0,0}, {27950,27949,27986 ,16558,16557,16590 ,0,0,0}, + {27827,27988,27953 ,16414,16592,16561 ,0,0,0}, {27987,27951,27950 ,16591,16559,16558 ,0,0,0}, + {27988,27989,27954 ,16592,13855,13944 ,0,0,0}, {27828,27952,27951 ,16415,16560,16559 ,0,0,0}, + {27989,27990,27955 ,13855,16593,16562 ,0,0,0}, {27827,27953,27952 ,16414,16561,16560 ,0,0,0}, + {27990,27881,27956 ,16593,16476,16563 ,0,0,0}, {27954,27953,27988 ,13944,16561,16592 ,0,0,0}, + {27991,27992,27993 ,16594,13809,16595 ,0,0,0}, {27955,27954,27989 ,16562,13944,13855 ,0,0,0}, + {27882,27994,27957 ,16477,16596,16564 ,0,0,0}, {27956,27955,27990 ,16563,16562,16593 ,0,0,0}, + {27994,27995,27958 ,16596,16597,16565 ,0,0,0}, {27880,27956,27881 ,16475,16563,16476 ,0,0,0}, + {27995,27996,27959 ,16597,16598,13938 ,0,0,0}, {27882,27957,27880 ,16477,16564,16475 ,0,0,0}, + {27996,27997,27960 ,16598,16599,16566 ,0,0,0}, {27994,27958,27957 ,16596,16565,16564 ,0,0,0}, + {27997,27998,27961 ,16599,16600,16567 ,0,0,0}, {27995,27959,27958 ,16597,13938,16565 ,0,0,0}, + {27998,27999,27962 ,16600,16601,16568 ,0,0,0}, {27960,27959,27996 ,16566,13938,16598 ,0,0,0}, + {27999,27890,27963 ,16601,13890,16569 ,0,0,0}, {27961,27960,27997 ,16567,16566,16599 ,0,0,0}, + {27890,27892,27964 ,13890,16487,16570 ,0,0,0}, {27962,27961,27998 ,16568,16567,16600 ,0,0,0}, + {27892,28000,27965 ,16487,13887,16571 ,0,0,0}, {27999,27963,27962 ,16601,16569,16568 ,0,0,0}, + {28000,28001,27966 ,13887,16602,16572 ,0,0,0}, {27890,27964,27963 ,13890,16570,16569 ,0,0,0}, + {28001,28002,27967 ,16602,16603,16573 ,0,0,0}, {27892,27965,27964 ,16487,16571,16570 ,0,0,0}, + {28002,28003,27968 ,16603,13886,16574 ,0,0,0}, {28000,27966,27965 ,13887,16572,16571 ,0,0,0}, + {28003,28004,27903 ,13886,16604,16505 ,0,0,0}, {28001,27967,27966 ,16602,16573,16572 ,0,0,0}, + {28004,28005,27901 ,16604,13884,16503 ,0,0,0}, {28002,27968,27967 ,16603,16574,16573 ,0,0,0}, + {28005,27970,27969 ,13884,16576,16575 ,0,0,0}, {28003,27903,27968 ,13886,16505,16574 ,0,0,0}, + {27970,27913,27906 ,16576,16518,16510 ,0,0,0}, {27901,27903,28004 ,16503,16505,16604 ,0,0,0}, + {28006,28007,28008 ,13701,16605,16606 ,0,0,0}, {28005,27969,27901 ,13884,16575,16503 ,0,0,0}, + {27926,27908,27921 ,16531,16513,16526 ,0,0,0}, {27920,28009,27971 ,16525,16607,16577 ,0,0,0}, + {27905,27907,27930 ,16509,16511,16536 ,0,0,0}, {27913,27907,27906 ,16518,16511,16510 ,0,0,0}, + {28010,27971,28009 ,16608,16577,16607 ,0,0,0}, {27971,27972,27932 ,16577,13920,16539 ,0,0,0}, + {27931,27928,27927 ,16537,16533,16532 ,0,0,0}, {27927,27920,27971 ,16532,16525,16577 ,0,0,0}, + {28010,27972,27971 ,16608,13920,16577 ,0,0,0}, {27864,27935,27865 ,16455,16544,16456 ,0,0,0}, + {28011,27867,27868 ,14200,16458,16459 ,0,0,0}, {28011,27872,27867 ,14200,16464,16458 ,0,0,0}, + {27935,27973,27847 ,16544,16579,16436 ,0,0,0}, {28012,27973,27867 ,16609,16579,16458 ,0,0,0}, + {27860,28013,27974 ,16450,16610,16580 ,0,0,0}, {27861,27857,28012 ,16451,16447,16609 ,0,0,0}, + {27974,28014,27975 ,16580,16611,16581 ,0,0,0}, {27861,27859,27858 ,16451,16449,16448 ,0,0,0}, + {28015,28016,28017 ,16612,16613,16614 ,0,0,0}, {27859,28013,27860 ,16449,16610,16450 ,0,0,0}, + {27976,27975,28018 ,16582,16581,16615 ,0,0,0}, {28013,28014,27974 ,16610,16611,16580 ,0,0,0}, + {27977,27976,28017 ,13870,16582,16614 ,0,0,0}, {28014,28018,27975 ,16611,16615,16581 ,0,0,0}, + {27978,27977,28016 ,16583,13870,16613 ,0,0,0}, {28018,28017,27976 ,16615,16614,16582 ,0,0,0}, + {27979,27978,28019 ,16584,16583,16616 ,0,0,0}, {28017,28016,27977 ,16614,16613,13870 ,0,0,0}, + {27980,27979,28020 ,13909,16584,16617 ,0,0,0}, {28016,28019,27978 ,16613,16616,16583 ,0,0,0}, + {27838,27980,28021 ,16423,13909,16618 ,0,0,0}, {28019,28020,27979 ,16616,16617,16584 ,0,0,0}, + {27836,27838,28022 ,13907,16423,16619 ,0,0,0}, {28020,28021,27980 ,16617,16618,13909 ,0,0,0}, + {27982,27836,28023 ,16586,13907,16620 ,0,0,0}, {28022,27838,28021 ,16619,16423,16618 ,0,0,0}, + {28024,28025,28026 ,16621,16622,16623 ,0,0,0}, {28023,27836,28022 ,16620,13907,16619 ,0,0,0}, + {27984,27981,28027 ,16588,16585,16624 ,0,0,0}, {28023,27983,27982 ,16620,16587,16586 ,0,0,0}, + {27985,27984,28026 ,16589,16588,16623 ,0,0,0}, {27983,28027,27981 ,16587,16624,16585 ,0,0,0}, + {27986,27985,28025 ,16590,16589,16622 ,0,0,0}, {28027,28026,27984 ,16624,16623,16588 ,0,0,0}, + {27987,27986,28028 ,16591,16590,16625 ,0,0,0}, {28026,28025,27985 ,16623,16622,16589 ,0,0,0}, + {27828,27987,28029 ,16415,16591,16626 ,0,0,0}, {28028,27986,28025 ,16625,16590,16622 ,0,0,0}, + {28030,28031,28032 ,16627,16628,16629 ,0,0,0}, {28029,27987,28028 ,16626,16591,16625 ,0,0,0}, + {27988,27827,28033 ,16592,16414,16630 ,0,0,0}, {28029,27826,27828 ,16626,16413,16415 ,0,0,0}, + {27989,27988,28032 ,13855,16592,16629 ,0,0,0}, {27826,28033,27827 ,16413,16630,16414 ,0,0,0}, + {27990,27989,28031 ,16593,13855,16628 ,0,0,0}, {28033,28032,27988 ,16630,16629,16592 ,0,0,0}, + {27881,27990,28034 ,16476,16593,16631 ,0,0,0}, {28032,28031,27989 ,16629,16628,13855 ,0,0,0}, + {27882,27881,28035 ,16477,16476,16632 ,0,0,0}, {28031,28034,27990 ,16628,16631,16593 ,0,0,0}, + {27994,27882,28036 ,16596,16477,16633 ,0,0,0}, {28035,27881,28034 ,16632,16476,16631 ,0,0,0}, + {27995,27994,28037 ,16597,16596,16634 ,0,0,0}, {28036,27882,28035 ,16633,16477,16632 ,0,0,0}, + {27996,27995,27991 ,16598,16597,16594 ,0,0,0}, {28036,28037,27994 ,16633,16634,16596 ,0,0,0}, + {27997,27996,27993 ,16599,16598,16595 ,0,0,0}, {28037,27991,27995 ,16634,16594,16597 ,0,0,0}, + {27998,27997,28038 ,16600,16599,16635 ,0,0,0}, {27991,27993,27996 ,16594,16595,16598 ,0,0,0}, + {27999,27998,28039 ,16601,16600,16636 ,0,0,0}, {27993,28038,27997 ,16595,16635,16599 ,0,0,0}, + {27890,27999,28040 ,13890,16601,16637 ,0,0,0}, {28039,27998,28038 ,16636,16600,16635 ,0,0,0}, + {28041,28042,28043 ,16638,16639,16640 ,0,0,0}, {28040,27999,28039 ,16637,16601,16636 ,0,0,0}, + {28000,27892,28044 ,13887,16487,16641 ,0,0,0}, {28040,27891,27890 ,16637,16486,13890 ,0,0,0}, + {28001,28000,28043 ,16602,13887,16640 ,0,0,0}, {27891,28044,27892 ,16486,16641,16487 ,0,0,0}, + {28002,28001,28042 ,16603,16602,16639 ,0,0,0}, {28044,28043,28000 ,16641,16640,13887 ,0,0,0}, + {28003,28002,28045 ,13886,16603,16642 ,0,0,0}, {28043,28042,28001 ,16640,16639,16602 ,0,0,0}, + {28004,28003,28046 ,16604,13886,16643 ,0,0,0}, {28042,28045,28002 ,16639,16642,16603 ,0,0,0}, + {28005,28004,28047 ,13884,16604,16644 ,0,0,0}, {28045,28046,28003 ,16642,16643,13886 ,0,0,0}, + {27970,28005,28048 ,16576,13884,16645 ,0,0,0}, {28046,28047,28004 ,16643,16644,16604 ,0,0,0}, + {27913,27970,27911 ,16518,16576,16516 ,0,0,0}, {28047,28048,28005 ,16644,16645,13884 ,0,0,0}, + {27925,27913,27912 ,16530,16518,16517 ,0,0,0}, {28048,27911,27970 ,16645,16516,16576 ,0,0,0}, + {28049,27919,28008 ,16646,16524,16606 ,0,0,0}, {28050,27909,27908 ,16647,16514,16513 ,0,0,0}, + {27907,27925,27928 ,16511,16530,16533 ,0,0,0}, {27912,27926,27925 ,16517,16531,16530 ,0,0,0}, + {28051,28009,28007 ,16648,16607,16605 ,0,0,0}, {28051,28052,28009 ,16648,16649,16607 ,0,0,0}, + {27927,27921,27920 ,16532,16526,16525 ,0,0,0}, {27920,27910,28009 ,16525,16515,16607 ,0,0,0}, + {28010,28009,28052 ,16608,16607,16649 ,0,0,0}, {27864,27867,27973 ,16455,16458,16579 ,0,0,0}, + {27934,27872,28011 ,16543,16464,14200 ,0,0,0}, {27861,28053,27859 ,16451,16650,16449 ,0,0,0}, + {27973,28012,27857 ,16579,16609,16447 ,0,0,0}, {27872,28054,28012 ,16464,16651,16609 ,0,0,0}, + {28013,27859,28055 ,16610,16449,16652 ,0,0,0}, {28054,28053,27861 ,16651,16650,16451 ,0,0,0}, + {28014,28013,28056 ,16611,16610,16653 ,0,0,0}, {27859,28053,28055 ,16449,16650,16652 ,0,0,0}, + {28018,28014,28057 ,16615,16611,16654 ,0,0,0}, {28013,28055,28056 ,16610,16652,16653 ,0,0,0}, + {28017,28018,28058 ,16614,16615,16655 ,0,0,0}, {28056,28057,28014 ,16653,16654,16611 ,0,0,0}, + {28059,28019,28016 ,13827,16616,16613 ,0,0,0}, {28057,28058,28018 ,16654,16655,16615 ,0,0,0}, + {28060,28061,28062 ,16656,16657,16658 ,0,0,0}, {28058,28015,28017 ,16655,16612,16614 ,0,0,0}, + {28019,28063,28020 ,16616,16659,16617 ,0,0,0}, {28015,28059,28016 ,16612,13827,16613 ,0,0,0}, + {28020,28061,28021 ,16617,16657,16618 ,0,0,0}, {28059,28063,28019 ,13827,16659,16616 ,0,0,0}, + {28021,28060,28022 ,16618,16656,16619 ,0,0,0}, {28063,28061,28020 ,16659,16657,16617 ,0,0,0}, + {28022,28064,28023 ,16619,16660,16620 ,0,0,0}, {28061,28060,28021 ,16657,16656,16618 ,0,0,0}, + {28023,28065,27983 ,16620,13734,16587 ,0,0,0}, {28060,28064,28022 ,16656,16660,16619 ,0,0,0}, + {28027,27983,28066 ,16624,16587,16661 ,0,0,0}, {28064,28065,28023 ,16660,13734,16620 ,0,0,0}, + {28026,28027,28067 ,16623,16624,16662 ,0,0,0}, {28065,28066,27983 ,13734,16661,16587 ,0,0,0}, + {28068,28069,28070 ,16663,16664,16665 ,0,0,0}, {28066,28067,28027 ,16661,16662,16624 ,0,0,0}, + {28025,28071,28028 ,16622,16666,16625 ,0,0,0}, {28067,28024,28026 ,16662,16621,16623 ,0,0,0}, + {28028,28072,28029 ,16625,16667,16626 ,0,0,0}, {28024,28071,28025 ,16621,16666,16622 ,0,0,0}, + {28029,28073,27826 ,16626,16668,16413 ,0,0,0}, {28071,28072,28028 ,16666,16667,16625 ,0,0,0}, + {28033,27826,28074 ,16630,16413,16669 ,0,0,0}, {28072,28073,28029 ,16667,16668,16626 ,0,0,0}, + {28032,28033,28075 ,16629,16630,16670 ,0,0,0}, {28073,28074,27826 ,16668,16669,16413 ,0,0,0}, + {28076,28077,28078 ,16671,16672,16673 ,0,0,0}, {28074,28075,28033 ,16669,16670,16630 ,0,0,0}, + {28031,28079,28034 ,16628,13813,16631 ,0,0,0}, {28075,28030,28032 ,16670,16627,16629 ,0,0,0}, + {28034,28080,28035 ,16631,16674,16632 ,0,0,0}, {28030,28079,28031 ,16627,13813,16628 ,0,0,0}, + {28035,28081,28036 ,16632,16675,16633 ,0,0,0}, {28079,28080,28034 ,13813,16674,16631 ,0,0,0}, + {28036,28082,28037 ,16633,16676,16634 ,0,0,0}, {28080,28081,28035 ,16674,16675,16632 ,0,0,0}, + {27991,28037,28083 ,16594,16634,16677 ,0,0,0}, {28081,28082,28036 ,16675,16676,16633 ,0,0,0}, + {28084,28085,28086 ,16678,16679,16680 ,0,0,0}, {28082,28083,28037 ,16676,16677,16634 ,0,0,0}, + {27993,28087,28038 ,16595,16681,16635 ,0,0,0}, {28083,27992,27991 ,16677,13809,16594 ,0,0,0}, + {28038,28085,28039 ,16635,16679,16636 ,0,0,0}, {27992,28087,27993 ,13809,16681,16595 ,0,0,0}, + {28039,28084,28040 ,16636,16678,16637 ,0,0,0}, {28087,28085,28038 ,16681,16679,16635 ,0,0,0}, + {28040,28088,27891 ,16637,16682,16486 ,0,0,0}, {28085,28084,28039 ,16679,16678,16636 ,0,0,0}, + {28044,27891,28089 ,16641,16486,13760 ,0,0,0}, {28084,28088,28040 ,16678,16682,16637 ,0,0,0}, + {28043,28044,28090 ,16640,16641,16683 ,0,0,0}, {28088,28089,27891 ,16682,13760,16486 ,0,0,0}, + {28091,28045,28042 ,16684,16642,16639 ,0,0,0}, {28089,28090,28044 ,13760,16683,16641 ,0,0,0}, + {28092,28093,28094 ,16685,13799,13756 ,0,0,0}, {28090,28041,28043 ,16683,16638,16640 ,0,0,0}, + {28045,28095,28046 ,16642,16686,16643 ,0,0,0}, {28041,28091,28042 ,16638,16684,16639 ,0,0,0}, + {28046,28093,28047 ,16643,13799,16644 ,0,0,0}, {28091,28095,28045 ,16684,16686,16642 ,0,0,0}, + {28047,28092,28048 ,16644,16685,16645 ,0,0,0}, {28095,28093,28046 ,16686,13799,16643 ,0,0,0}, + {28048,28096,27911 ,16645,13797,16516 ,0,0,0}, {28093,28092,28047 ,13799,16685,16644 ,0,0,0}, + {27911,28097,27912 ,16516,16687,16517 ,0,0,0}, {28092,28096,28048 ,16685,13797,16645 ,0,0,0}, + {27912,28098,27926 ,16517,16688,16531 ,0,0,0}, {28096,28097,27911 ,13797,16687,16516 ,0,0,0}, + {27926,28050,27908 ,16531,16647,16513 ,0,0,0}, {28098,27912,28097 ,16688,16517,16687 ,0,0,0}, + {27915,27909,28099 ,16520,16514,16689 ,0,0,0}, {27926,28098,28050 ,16531,16688,16647 ,0,0,0}, + {28007,28100,28008 ,16605,13793,16606 ,0,0,0}, {28009,27910,28007 ,16607,16515,16605 ,0,0,0}, + {27920,27908,27910 ,16525,16513,16515 ,0,0,0}, {27910,28100,28007 ,16515,13793,16605 ,0,0,0}, + {28051,28007,28006 ,16648,16605,13701 ,0,0,0}, {27867,27872,28012 ,16458,16464,16609 ,0,0,0}, + {27852,27851,27873 ,16442,16441,16465 ,0,0,0}, {28053,28101,28055 ,16650,13654,16652 ,0,0,0}, + {28012,28054,27861 ,16609,16651,16451 ,0,0,0}, {27851,28102,28054 ,16441,16690,16651 ,0,0,0}, + {28056,28055,28103 ,16653,16652,16691 ,0,0,0}, {28053,28102,28101 ,16650,16690,13654 ,0,0,0}, + {28057,28056,28104 ,16654,16653,16692 ,0,0,0}, {28055,28101,28103 ,16652,13654,16691 ,0,0,0}, + {28058,28057,28105 ,16655,16654,16693 ,0,0,0}, {28056,28103,28104 ,16653,16691,16692 ,0,0,0}, + {28015,28058,28106 ,16612,16655,16694 ,0,0,0}, {28057,28104,28105 ,16654,16692,16693 ,0,0,0}, + {28059,28015,28107 ,13827,16612,16695 ,0,0,0}, {28058,28105,28106 ,16655,16693,16694 ,0,0,0}, + {28063,28059,28108 ,16659,13827,13787 ,0,0,0}, {28015,28106,28107 ,16612,16694,16695 ,0,0,0}, + {28061,28063,28109 ,16657,16659,16696 ,0,0,0}, {28107,28108,28059 ,16695,13787,13827 ,0,0,0}, + {28110,28111,28112 ,16697,16698,16699 ,0,0,0}, {28108,28109,28063 ,13787,16696,16659 ,0,0,0}, + {28060,28113,28064 ,16656,16700,16660 ,0,0,0}, {28109,28062,28061 ,16696,16658,16657 ,0,0,0}, + {28064,28112,28065 ,16660,16699,13734 ,0,0,0}, {28062,28113,28060 ,16658,16700,16656 ,0,0,0}, + {28065,28114,28066 ,13734,16701,16661 ,0,0,0}, {28113,28112,28064 ,16700,16699,16660 ,0,0,0}, + {28067,28066,28115 ,16662,16661,16702 ,0,0,0}, {28112,28114,28065 ,16699,16701,13734 ,0,0,0}, + {28024,28067,28116 ,16621,16662,16703 ,0,0,0}, {28066,28114,28115 ,16661,16701,16702 ,0,0,0}, + {28071,28024,28117 ,16666,16621,16704 ,0,0,0}, {28067,28115,28116 ,16662,16702,16703 ,0,0,0}, + {28072,28071,28118 ,16667,16666,16705 ,0,0,0}, {28116,28117,28024 ,16703,16704,16621 ,0,0,0}, + {28072,28119,28073 ,16667,16706,16668 ,0,0,0}, {28117,28118,28071 ,16704,16705,16666 ,0,0,0}, + {28073,28069,28074 ,16668,16664,16669 ,0,0,0}, {28118,28119,28072 ,16705,16706,16667 ,0,0,0}, + {28075,28074,28120 ,16670,16669,16707 ,0,0,0}, {28119,28069,28073 ,16706,16664,16668 ,0,0,0}, + {28030,28075,28121 ,16627,16670,16708 ,0,0,0}, {28074,28069,28120 ,16669,16664,16707 ,0,0,0}, + {28079,28030,28122 ,13813,16627,16709 ,0,0,0}, {28075,28120,28121 ,16670,16707,16708 ,0,0,0}, + {28080,28079,28123 ,16674,13813,16710 ,0,0,0}, {28121,28122,28030 ,16708,16709,16627 ,0,0,0}, + {28080,28124,28081 ,16674,16711,16675 ,0,0,0}, {28122,28123,28079 ,16709,16710,13813 ,0,0,0}, + {28081,28077,28082 ,16675,16672,16676 ,0,0,0}, {28123,28124,28080 ,16710,16711,16674 ,0,0,0}, + {28083,28082,28125 ,16677,16676,16712 ,0,0,0}, {28124,28077,28081 ,16711,16672,16675 ,0,0,0}, + {27992,28083,28126 ,13809,16677,16713 ,0,0,0}, {28082,28077,28125 ,16676,16672,16712 ,0,0,0}, + {28087,27992,28127 ,16681,13809,16714 ,0,0,0}, {28083,28125,28126 ,16677,16712,16713 ,0,0,0}, + {28085,28087,28128 ,16679,16681,16715 ,0,0,0}, {28126,28127,27992 ,16713,16714,13809 ,0,0,0}, + {28129,28130,28131 ,16716,16717,16718 ,0,0,0}, {28127,28128,28087 ,16714,16715,16681 ,0,0,0}, + {28084,28132,28088 ,16678,16719,16682 ,0,0,0}, {28128,28086,28085 ,16715,16680,16679 ,0,0,0}, + {28088,28131,28089 ,16682,16718,13760 ,0,0,0}, {28086,28132,28084 ,16680,16719,16678 ,0,0,0}, + {28090,28089,28133 ,16683,13760,16720 ,0,0,0}, {28132,28131,28088 ,16719,16718,16682 ,0,0,0}, + {28041,28090,28134 ,16638,16683,16721 ,0,0,0}, {28089,28131,28133 ,13760,16718,16720 ,0,0,0}, + {28091,28041,28135 ,16684,16638,16722 ,0,0,0}, {28090,28133,28134 ,16683,16720,16721 ,0,0,0}, + {28095,28091,28136 ,16686,16684,16723 ,0,0,0}, {28041,28134,28135 ,16638,16721,16722 ,0,0,0}, + {28093,28095,28137 ,13799,16686,16724 ,0,0,0}, {28135,28136,28091 ,16722,16723,16684 ,0,0,0}, + {28138,28096,28092 ,13755,13797,16685 ,0,0,0}, {28136,28137,28095 ,16723,16724,16686 ,0,0,0}, + {28139,28140,28141 ,16725,16726,16727 ,0,0,0}, {28137,28094,28093 ,16724,13756,13799 ,0,0,0}, + {28096,28142,28097 ,13797,16728,16687 ,0,0,0}, {28094,28138,28092 ,13756,13755,16685 ,0,0,0}, + {28097,28141,28098 ,16687,16727,16688 ,0,0,0}, {28138,28142,28096 ,13755,16728,13797 ,0,0,0}, + {28098,28143,28050 ,16688,16729,16647 ,0,0,0}, {28142,28141,28097 ,16728,16727,16687 ,0,0,0}, + {28050,28099,27909 ,16647,16689,16514 ,0,0,0}, {28141,28143,28098 ,16727,16729,16688 ,0,0,0}, + {27909,27915,28100 ,16514,16520,13793 ,0,0,0}, {28050,28143,28099 ,16647,16729,16689 ,0,0,0}, + {28144,28008,27919 ,16730,16606,16524 ,0,0,0}, {28145,28006,28008 ,13563,13701,16606 ,0,0,0}, + {27910,27909,28100 ,16515,16514,13793 ,0,0,0}, {28100,28049,28008 ,13793,16646,16606 ,0,0,0}, + {28144,28145,28008 ,16730,13563,16606 ,0,0,0}, {27872,27851,28054 ,16464,16441,16651 ,0,0,0}, + {28146,27850,27852 ,16731,16440,16442 ,0,0,0}, {28103,28101,27856 ,16691,13654,16445 ,0,0,0}, + {28054,28102,28053 ,16651,16690,16650 ,0,0,0}, {27850,28147,28102 ,16440,16732,16690 ,0,0,0}, + {28104,28103,28148 ,16692,16691,16733 ,0,0,0}, {28101,28147,27856 ,13654,16732,16445 ,0,0,0}, + {28149,28148,28150 ,16734,16733,16735 ,0,0,0}, {28103,27856,28148 ,16691,16445,16733 ,0,0,0}, + {28149,28151,28105 ,16734,16736,16693 ,0,0,0}, {28105,28104,28149 ,16693,16692,16734 ,0,0,0}, + {28151,28152,28106 ,16736,16737,16694 ,0,0,0}, {28106,28105,28151 ,16694,16693,16736 ,0,0,0}, + {28152,28153,28107 ,16737,16738,16695 ,0,0,0}, {28107,28106,28152 ,16695,16694,16737 ,0,0,0}, + {28153,28154,28108 ,16738,16739,13787 ,0,0,0}, {28108,28107,28153 ,13787,16695,16738 ,0,0,0}, + {28154,28155,28109 ,16739,16740,16696 ,0,0,0}, {28109,28108,28154 ,16696,13787,16739 ,0,0,0}, + {28155,28156,28062 ,16740,16741,16658 ,0,0,0}, {28062,28109,28155 ,16658,16696,16740 ,0,0,0}, + {28156,28110,28113 ,16741,16697,16700 ,0,0,0}, {28062,28156,28113 ,16658,16741,16700 ,0,0,0}, + {27466,28157,28158 ,16742,16743,13617 ,0,0,0}, {28113,28110,28112 ,16700,16697,16699 ,0,0,0}, + {28114,28159,28115 ,16701,16744,16702 ,0,0,0}, {28112,28111,28114 ,16699,16698,16701 ,0,0,0}, + {28160,28159,28158 ,16745,16744,13617 ,0,0,0}, {28111,28159,28114 ,16698,16744,16701 ,0,0,0}, + {28160,28161,28116 ,16745,16746,16703 ,0,0,0}, {28116,28115,28160 ,16703,16702,16745 ,0,0,0}, + {28161,28162,28117 ,16746,16747,16704 ,0,0,0}, {28117,28116,28161 ,16704,16703,16746 ,0,0,0}, + {28162,28163,28118 ,16747,16748,16705 ,0,0,0}, {28118,28117,28162 ,16705,16704,16747 ,0,0,0}, + {28163,28070,28119 ,16748,16665,16706 ,0,0,0}, {28118,28163,28119 ,16705,16748,16706 ,0,0,0}, + {28164,28165,28166 ,13610,13730,13608 ,0,0,0}, {28119,28070,28069 ,16706,16665,16664 ,0,0,0}, + {28068,28165,28120 ,16663,13730,16707 ,0,0,0}, {28069,28068,28120 ,16664,16663,16707 ,0,0,0}, + {28165,28167,28121 ,13730,16749,16708 ,0,0,0}, {28121,28120,28165 ,16708,16707,13730 ,0,0,0}, + {28167,28168,28122 ,16749,16750,16709 ,0,0,0}, {28122,28121,28167 ,16709,16708,16749 ,0,0,0}, + {28168,28169,28123 ,16750,16751,16710 ,0,0,0}, {28123,28122,28168 ,16710,16709,16750 ,0,0,0}, + {28169,28078,28124 ,16751,16673,16711 ,0,0,0}, {28123,28169,28124 ,16710,16751,16711 ,0,0,0}, + {28170,27457,28171 ,13596,16752,13595 ,0,0,0}, {28124,28078,28077 ,16711,16673,16672 ,0,0,0}, + {28126,28125,28172 ,16713,16712,16753 ,0,0,0}, {28077,28076,28125 ,16672,16671,16712 ,0,0,0}, + {28173,28172,28170 ,16754,16753,13596 ,0,0,0}, {28125,28076,28172 ,16712,16671,16753 ,0,0,0}, + {28173,28174,28127 ,16754,16755,16714 ,0,0,0}, {28127,28126,28173 ,16714,16713,16754 ,0,0,0}, + {28174,28175,28128 ,16755,16756,16715 ,0,0,0}, {28128,28127,28174 ,16715,16714,16755 ,0,0,0}, + {28175,28176,28086 ,16756,16757,16680 ,0,0,0}, {28086,28128,28175 ,16680,16715,16756 ,0,0,0}, + {28176,28129,28132 ,16757,16716,16719 ,0,0,0}, {28086,28176,28132 ,16680,16757,16719 ,0,0,0}, + {28177,28178,28179 ,16758,16759,16760 ,0,0,0}, {28132,28129,28131 ,16719,16716,16718 ,0,0,0}, + {28130,28178,28133 ,16717,16759,16720 ,0,0,0}, {28131,28130,28133 ,16718,16717,16720 ,0,0,0}, + {28178,28180,28134 ,16759,16761,16721 ,0,0,0}, {28134,28133,28178 ,16721,16720,16759 ,0,0,0}, + {28180,28181,28135 ,16761,13717,16722 ,0,0,0}, {28135,28134,28180 ,16722,16721,16761 ,0,0,0}, + {28181,28182,28136 ,13717,16762,16723 ,0,0,0}, {28136,28135,28181 ,16723,16722,13717 ,0,0,0}, + {28182,28183,28137 ,16762,16763,16724 ,0,0,0}, {28137,28136,28182 ,16724,16723,16762 ,0,0,0}, + {28183,28184,28094 ,16763,16764,13756 ,0,0,0}, {28094,28137,28183 ,13756,16724,16763 ,0,0,0}, + {28184,28185,28138 ,16764,16765,13755 ,0,0,0}, {28138,28094,28184 ,13755,13756,16764 ,0,0,0}, + {28185,28139,28142 ,16765,16725,16728 ,0,0,0}, {28138,28185,28142 ,13755,16765,16728 ,0,0,0}, + {28143,28140,28186 ,16729,16726,16766 ,0,0,0}, {28142,28139,28141 ,16728,16725,16727 ,0,0,0}, + {27916,27915,28099 ,16521,16520,16689 ,0,0,0}, {28141,28140,28143 ,16727,16726,16729 ,0,0,0}, + {27914,28049,27915 ,16519,16646,16520 ,0,0,0}, {28143,28186,28099 ,16729,16766,16689 ,0,0,0}, + {28187,27923,27917 ,16767,16528,16522 ,0,0,0}, {28186,27916,28099 ,16766,16521,16689 ,0,0,0}, + {27914,28188,28189 ,16519,16768,16769 ,0,0,0}, {28190,28144,27919 ,16770,16730,16524 ,0,0,0}, + {28100,27915,28049 ,13793,16520,16646 ,0,0,0}, {27919,28049,28189 ,16524,16646,16769 ,0,0,0}, + {27918,28190,27919 ,16523,16770,16524 ,0,0,0}, {27851,27850,28102 ,16441,16440,16690 ,0,0,0}, + {28146,27853,27849 ,16731,16443,16439 ,0,0,0}, {28147,27849,27854 ,16732,16439,16444 ,0,0,0}, + {28102,28147,28101 ,16690,16732,13654 ,0,0,0}, {27856,28147,27854 ,16445,16732,16444 ,0,0,0}, + {27855,28150,28148 ,13641,16735,16733 ,0,0,0}, {28148,27856,27855 ,16733,16445,13641 ,0,0,0}, + {28150,28191,28149 ,16735,16771,16734 ,0,0,0}, {28192,28151,28191 ,16772,16736,16771 ,0,0,0}, + {28104,28148,28149 ,16692,16733,16734 ,0,0,0}, {28151,28149,28191 ,16736,16734,16771 ,0,0,0}, + {28193,28152,28192 ,16773,16737,16772 ,0,0,0}, {28152,28151,28192 ,16737,16736,16772 ,0,0,0}, + {28194,28153,28193 ,16774,16738,16773 ,0,0,0}, {28153,28152,28193 ,16738,16737,16773 ,0,0,0}, + {28195,28154,28194 ,16775,16739,16774 ,0,0,0}, {28154,28153,28194 ,16739,16738,16774 ,0,0,0}, + {28196,28155,28195 ,16776,16740,16775 ,0,0,0}, {28155,28154,28195 ,16740,16739,16775 ,0,0,0}, + {28197,28156,28196 ,13624,16741,16776 ,0,0,0}, {28156,28155,28196 ,16741,16740,16776 ,0,0,0}, + {28198,28110,28197 ,13626,16697,13624 ,0,0,0}, {28110,28156,28197 ,16697,16741,13624 ,0,0,0}, + {28199,28111,28198 ,16777,16698,13626 ,0,0,0}, {28111,28110,28198 ,16698,16697,13626 ,0,0,0}, + {28158,28159,28199 ,13617,16744,16777 ,0,0,0}, {28111,28199,28159 ,16698,16777,16744 ,0,0,0}, + {28158,28157,28160 ,13617,16743,16745 ,0,0,0}, {28200,28161,28157 ,16778,16746,16743 ,0,0,0}, + {28115,28159,28160 ,16702,16744,16745 ,0,0,0}, {28161,28160,28157 ,16746,16745,16743 ,0,0,0}, + {28201,28162,28200 ,16779,16747,16778 ,0,0,0}, {28162,28161,28200 ,16747,16746,16778 ,0,0,0}, + {28202,28163,28201 ,16780,16748,16779 ,0,0,0}, {28163,28162,28201 ,16748,16747,16779 ,0,0,0}, + {28203,28070,28202 ,16781,16665,16780 ,0,0,0}, {28070,28163,28202 ,16665,16748,16780 ,0,0,0}, + {28166,28068,28203 ,13608,16663,16781 ,0,0,0}, {28068,28070,28203 ,16663,16665,16781 ,0,0,0}, + {28166,27381,28164 ,13608,13677,13610 ,0,0,0}, {28068,28166,28165 ,16663,13608,13730 ,0,0,0}, + {28204,28167,28164 ,16782,16749,13610 ,0,0,0}, {28167,28165,28164 ,16749,13730,13610 ,0,0,0}, + {28205,28168,28204 ,16783,16750,16782 ,0,0,0}, {28168,28167,28204 ,16750,16749,16782 ,0,0,0}, + {28206,28169,28205 ,13679,16751,16783 ,0,0,0}, {28169,28168,28205 ,16751,16750,16783 ,0,0,0}, + {28207,28078,28206 ,16784,16673,13679 ,0,0,0}, {28078,28169,28206 ,16673,16751,13679 ,0,0,0}, + {28208,28076,28207 ,16785,16671,16784 ,0,0,0}, {28076,28078,28207 ,16671,16673,16784 ,0,0,0}, + {28170,28172,28208 ,13596,16753,16785 ,0,0,0}, {28076,28208,28172 ,16671,16785,16753 ,0,0,0}, + {28170,28171,28173 ,13596,13595,16754 ,0,0,0}, {28209,28174,28171 ,16786,16755,13595 ,0,0,0}, + {28126,28172,28173 ,16713,16753,16754 ,0,0,0}, {28174,28173,28171 ,16755,16754,13595 ,0,0,0}, + {28210,28175,28209 ,16787,16756,16786 ,0,0,0}, {28175,28174,28209 ,16756,16755,16786 ,0,0,0}, + {28211,28176,28210 ,16788,16757,16787 ,0,0,0}, {28176,28175,28210 ,16757,16756,16787 ,0,0,0}, + {28212,28129,28211 ,16789,16716,16788 ,0,0,0}, {28129,28176,28211 ,16716,16757,16788 ,0,0,0}, + {28179,28130,28212 ,16760,16717,16789 ,0,0,0}, {28130,28129,28212 ,16717,16716,16789 ,0,0,0}, + {28179,27403,28177 ,16760,13686,16758 ,0,0,0}, {28130,28179,28178 ,16717,16760,16759 ,0,0,0}, + {28213,28180,28177 ,16790,16761,16758 ,0,0,0}, {28180,28178,28177 ,16761,16759,16758 ,0,0,0}, + {28214,28181,28213 ,16791,13717,16790 ,0,0,0}, {28181,28180,28213 ,13717,16761,16790 ,0,0,0}, + {28215,28182,28214 ,16792,16762,16791 ,0,0,0}, {28182,28181,28214 ,16762,13717,16791 ,0,0,0}, + {28216,28183,28215 ,16793,16763,16792 ,0,0,0}, {28183,28182,28215 ,16763,16762,16792 ,0,0,0}, + {28217,28184,28216 ,16794,16764,16793 ,0,0,0}, {28184,28183,28216 ,16764,16763,16793 ,0,0,0}, + {28218,28185,28217 ,16795,16765,16794 ,0,0,0}, {28185,28184,28217 ,16765,16764,16794 ,0,0,0}, + {28219,28139,28218 ,16796,16725,16795 ,0,0,0}, {28139,28185,28218 ,16725,16765,16795 ,0,0,0}, + {28220,28140,28219 ,13546,16726,16796 ,0,0,0}, {28140,28139,28219 ,16726,16725,16796 ,0,0,0}, + {28221,28186,28220 ,16797,16766,13546 ,0,0,0}, {28186,28140,28220 ,16766,16726,13546 ,0,0,0}, + {28222,27916,28221 ,13560,16521,16797 ,0,0,0}, {27916,28186,28221 ,16521,16766,16797 ,0,0,0}, + {28222,28188,27914 ,13560,16768,16519 ,0,0,0}, {27914,27916,28222 ,16519,16521,13560 ,0,0,0}, + {28188,28187,28189 ,16768,16767,16769 ,0,0,0}, {27919,28189,27917 ,16524,16769,16522 ,0,0,0}, + {28049,27914,28189 ,16646,16519,16769 ,0,0,0}, {28187,27917,28189 ,16767,16522,16769 ,0,0,0}, + {27918,27917,27922 ,16523,16522,16527 ,0,0,0}, {28147,27850,27849 ,16732,16440,16439 ,0,0,0}, + {27849,27850,28146 ,16439,16440,16731 ,0,0,0}, {27475,27473,27854 ,16578,16798,16444 ,0,0,0}, + {27854,27473,27855 ,16444,16798,13641 ,0,0,0}, {27473,27341,27855 ,16798,13645,13641 ,0,0,0}, + {27855,27341,28150 ,13641,13645,16735 ,0,0,0}, {27341,27340,28150 ,13645,13639,16735 ,0,0,0}, + {28150,27340,28191 ,16735,13639,16771 ,0,0,0}, {27340,27361,28191 ,13639,13634,16771 ,0,0,0}, + {28191,27361,28192 ,16771,13634,16772 ,0,0,0}, {27361,27331,28192 ,13634,16799,16772 ,0,0,0}, + {28192,27331,28193 ,16772,16799,16773 ,0,0,0}, {27331,27366,28193 ,16799,16800,16773 ,0,0,0}, + {28193,27366,28194 ,16773,16800,16774 ,0,0,0}, {27366,27363,28194 ,16800,16801,16774 ,0,0,0}, + {28194,27363,28195 ,16774,16801,16775 ,0,0,0}, {27363,27368,28195 ,16801,16802,16775 ,0,0,0}, + {27368,27370,28196 ,16802,16803,16776 ,0,0,0}, {27368,28196,28195 ,16802,16776,16775 ,0,0,0}, + {27370,27336,28197 ,16803,13625,13624 ,0,0,0}, {27370,28197,28196 ,16803,13624,16776 ,0,0,0}, + {27336,27335,28198 ,13625,16804,13626 ,0,0,0}, {27336,28198,28197 ,13625,13626,13624 ,0,0,0}, + {27335,27372,28199 ,16804,13621,16777 ,0,0,0}, {27335,28199,28198 ,16804,16777,13626 ,0,0,0}, + {27372,27467,28158 ,13621,16805,13617 ,0,0,0}, {27372,28158,28199 ,13621,13617,16777 ,0,0,0}, + {27466,28158,27467 ,16742,13617,16805 ,0,0,0}, {27466,27375,28157 ,16742,16806,16743 ,0,0,0}, + {28157,27375,28200 ,16743,16806,16778 ,0,0,0}, {27375,27380,28200 ,16806,13612,16778 ,0,0,0}, + {28200,27380,28201 ,16778,13612,16779 ,0,0,0}, {27380,27378,28201 ,13612,13613,16779 ,0,0,0}, + {27378,27377,28202 ,13613,13614,16780 ,0,0,0}, {27378,28202,28201 ,13613,16780,16779 ,0,0,0}, + {27377,27465,28203 ,13614,13607,16781 ,0,0,0}, {27377,28203,28202 ,13614,16781,16780 ,0,0,0}, + {27465,27381,28166 ,13607,13677,13608 ,0,0,0}, {27465,28166,28203 ,13607,13608,16781 ,0,0,0}, + {27381,27464,28164 ,13677,16807,13610 ,0,0,0}, {27464,27460,28164 ,16807,13602,13610 ,0,0,0}, + {28164,27460,28204 ,13610,13602,16782 ,0,0,0}, {27460,27385,28204 ,13602,16808,16782 ,0,0,0}, + {28204,27385,28205 ,16782,16808,16783 ,0,0,0}, {27385,27387,28205 ,16808,16809,16783 ,0,0,0}, + {27387,27392,28206 ,16809,16810,13679 ,0,0,0}, {27387,28206,28205 ,16809,13679,16783 ,0,0,0}, + {27392,27390,28207 ,16810,13598,16784 ,0,0,0}, {27392,28207,28206 ,16810,16784,13679 ,0,0,0}, + {27390,27389,28208 ,13598,13680,16785 ,0,0,0}, {27390,28208,28207 ,13598,16785,16784 ,0,0,0}, + {27389,27458,28170 ,13680,16811,13596 ,0,0,0}, {27389,28170,28208 ,13680,13596,16785 ,0,0,0}, + {27457,28170,27458 ,16752,13596,16811 ,0,0,0}, {27457,27394,28171 ,16752,16812,13595 ,0,0,0}, + {28171,27394,28209 ,13595,16812,16786 ,0,0,0}, {27394,27401,28209 ,16812,13590,16786 ,0,0,0}, + {27401,27400,28210 ,13590,13591,16787 ,0,0,0}, {27401,28210,28209 ,13590,16787,16786 ,0,0,0}, + {27400,27399,28211 ,13591,16813,16788 ,0,0,0}, {27400,28211,28210 ,13591,16788,16787 ,0,0,0}, + {27399,27454,28212 ,16813,16814,16789 ,0,0,0}, {27399,28212,28211 ,16813,16789,16788 ,0,0,0}, + {27454,27403,28179 ,16814,13686,16760 ,0,0,0}, {27454,28179,28212 ,16814,16760,16789 ,0,0,0}, + {27403,27402,28177 ,13686,16815,16758 ,0,0,0}, {27402,27408,28177 ,16815,16816,16758 ,0,0,0}, + {28177,27408,28213 ,16758,16816,16790 ,0,0,0}, {27408,27407,28213 ,16816,13549,16790 ,0,0,0}, + {28213,27407,28214 ,16790,13549,16791 ,0,0,0}, {27407,27412,28214 ,13549,13550,16791 ,0,0,0}, + {28214,27412,28215 ,16791,13550,16792 ,0,0,0}, {27412,27410,28215 ,13550,16817,16792 ,0,0,0}, + {27410,27417,28216 ,16817,16818,16793 ,0,0,0}, {27410,28216,28215 ,16817,16793,16792 ,0,0,0}, + {27417,27414,28217 ,16818,16819,16794 ,0,0,0}, {27417,28217,28216 ,16818,16794,16793 ,0,0,0}, + {27414,27421,28218 ,16819,16820,16795 ,0,0,0}, {27414,28218,28217 ,16819,16795,16794 ,0,0,0}, + {27421,27418,28219 ,16820,13545,16796 ,0,0,0}, {27421,28219,28218 ,16820,16796,16795 ,0,0,0}, + {27418,27423,28220 ,13545,16821,13546 ,0,0,0}, {27418,28220,28219 ,13545,13546,16796 ,0,0,0}, + {27423,27422,28221 ,16821,16822,16797 ,0,0,0}, {27423,28221,28220 ,16821,16797,13546 ,0,0,0}, + {27422,27436,28222 ,16822,16823,13560 ,0,0,0}, {27422,28222,28221 ,16822,13560,16797 ,0,0,0}, + {27436,27435,28188 ,16823,16824,16768 ,0,0,0}, {27436,28188,28222 ,16823,16768,13560 ,0,0,0}, + {27435,27429,28187 ,16824,16825,16767 ,0,0,0}, {27435,28187,28188 ,16824,16767,16768 ,0,0,0}, + {27429,27431,27923 ,16825,16534,16528 ,0,0,0}, {27429,27923,28187 ,16825,16528,16767 ,0,0,0}, + {27924,27923,27431 ,16529,16528,16534 ,0,0,0}, {28223,28224,28225 ,16826,16827,16828 ,0,0,0}, + {28226,27300,27299 ,16829,14541,16830 ,0,0,0}, {28226,28227,27300 ,16829,16831,14541 ,0,0,0}, + {28228,27298,28229 ,16832,16833,14499 ,0,0,0}, {27299,28228,28226 ,16830,16832,16829 ,0,0,0}, + {28228,27299,27298 ,16832,16830,16833 ,0,0,0}, {27296,28230,27297 ,16834,16835,16836 ,0,0,0}, + {27211,27297,28230 ,14500,16836,16835 ,0,0,0}, {27211,28230,28229 ,14500,16835,14499 ,0,0,0}, + {27296,27295,28231 ,16834,14546,16837 ,0,0,0}, {27211,28229,27298 ,14500,14499,16833 ,0,0,0}, + {28230,27296,28231 ,16835,16834,16837 ,0,0,0}, {27301,27300,28227 ,14540,14541,16831 ,0,0,0}, + {28232,27294,28233 ,14502,14547,16838 ,0,0,0}, {28232,27295,27294 ,14502,14546,14547 ,0,0,0}, + {28234,28235,28236 ,14462,16839,14414 ,0,0,0}, {28237,28233,27293 ,16840,16838,14548 ,0,0,0}, + {27294,27293,28233 ,14547,14548,16838 ,0,0,0}, {28238,28237,27292 ,16841,16840,16842 ,0,0,0}, + {28238,27291,28239 ,16841,16843,16844 ,0,0,0}, {27292,27291,28238 ,16842,16843,16841 ,0,0,0}, + {28239,27291,27290 ,16844,16843,16845 ,0,0,0}, {27293,27292,28237 ,14548,16842,16840 ,0,0,0}, + {28231,27295,28232 ,16837,14546,14502 ,0,0,0}, {27289,27288,28240 ,14552,16846,16847 ,0,0,0}, + {27289,28241,27290 ,14552,16848,16845 ,0,0,0}, {27287,28242,27288 ,16849,16850,16846 ,0,0,0}, + {27289,28240,28241 ,14552,16847,16848 ,0,0,0}, {27287,27286,28243 ,16849,16851,16852 ,0,0,0}, + {28243,28242,27287 ,16852,16850,16849 ,0,0,0}, {27924,26982,26979 ,16853,15691,16854 ,0,0,0}, + {27288,28242,28240 ,16846,16850,16847 ,0,0,0}, {28243,27286,28244 ,16852,16851,16855 ,0,0,0}, + {28245,27924,26979 ,16856,16853,16854 ,0,0,0}, {28246,28247,28243 ,16857,16858,16852 ,0,0,0}, + {28248,28249,28250 ,16859,16860,16861 ,0,0,0}, {28251,28252,28253 ,16862,16863,14423 ,0,0,0}, + {28254,28255,28144 ,16864,16865,14341 ,0,0,0}, {28254,27918,28256 ,16864,16866,16867 ,0,0,0}, + {28244,27286,27285 ,16855,16851,16868 ,0,0,0}, {28245,26979,28250 ,16856,16854,16861 ,0,0,0}, + {28247,28257,28253 ,16858,16869,14423 ,0,0,0}, {28145,28255,28258 ,14340,16865,16870 ,0,0,0}, + {28259,27972,28260 ,16871,16872,16873 ,0,0,0}, {26848,28261,27285 ,16874,16875,16868 ,0,0,0}, + {28262,28051,28258 ,16876,16877,16870 ,0,0,0}, {28052,28051,28262 ,16878,16877,16876 ,0,0,0}, + {28145,28258,28006 ,14340,16870,14339 ,0,0,0}, {26853,27933,26851 ,15589,16879,16880 ,0,0,0}, + {26848,28259,28261 ,16874,16871,16875 ,0,0,0}, {27972,28259,27933 ,16872,16871,16879 ,0,0,0}, + {28259,26851,27933 ,16871,16880,16879 ,0,0,0}, {28257,28263,28253 ,16869,16881,14423 ,0,0,0}, + {28241,28239,27290 ,16848,16844,16845 ,0,0,0}, {28264,27301,28227 ,16882,14540,16831 ,0,0,0}, + {27302,28264,28265 ,16883,16882,16884 ,0,0,0}, {28264,27302,27301 ,16882,16883,14540 ,0,0,0}, + {28266,27261,28265 ,14452,14453,16884 ,0,0,0}, {27302,28265,27261 ,16883,16884,14453 ,0,0,0}, + {27303,28266,27304 ,16885,14452,14537 ,0,0,0}, {27303,27261,28266 ,16885,14453,14452 ,0,0,0}, + {27305,27304,28267 ,16886,14537,16887 ,0,0,0}, {28266,28267,27304 ,14452,16887,14537 ,0,0,0}, + {28268,27306,27305 ,16888,14535,16886 ,0,0,0}, {27305,28267,28268 ,16886,16887,16888 ,0,0,0}, + {28268,28269,27306 ,16888,16889,14535 ,0,0,0}, {27306,28269,27307 ,14535,16889,16890 ,0,0,0}, + {27307,28269,28270 ,16890,16889,16891 ,0,0,0}, {28271,28272,28273 ,16892,16893,16894 ,0,0,0}, + {28274,27308,28270 ,16895,14533,16891 ,0,0,0}, {27307,28270,27308 ,16890,16891,14533 ,0,0,0}, + {28274,28275,27309 ,16895,16896,14532 ,0,0,0}, {27309,27308,28274 ,14532,14533,16895 ,0,0,0}, + {27226,27310,28275 ,14489,16897,16896 ,0,0,0}, {28275,27310,27309 ,16896,16897,14532 ,0,0,0}, + {28276,27311,27226 ,14488,14530,14489 ,0,0,0}, {27226,28275,28276 ,14489,16896,14488 ,0,0,0}, + {27311,28277,27312 ,14530,16898,16899 ,0,0,0}, {28277,27311,28276 ,16898,14530,14488 ,0,0,0}, + {27313,27312,28278 ,14528,16899,16900 ,0,0,0}, {28277,28278,27312 ,16898,16900,16899 ,0,0,0}, + {28279,27313,28278 ,16901,14528,16900 ,0,0,0}, {28279,27314,27313 ,16901,14527,14528 ,0,0,0}, + {28279,28280,27314 ,16901,16902,14527 ,0,0,0}, {28281,28282,28283 ,14397,16903,16904 ,0,0,0}, + {27315,28280,28284 ,14526,16902,14439 ,0,0,0}, {28280,27315,27314 ,16902,14526,14527 ,0,0,0}, + {28285,27272,28284 ,16905,16906,14439 ,0,0,0}, {27315,28284,27272 ,14526,14439,16906 ,0,0,0}, + {27316,28285,27317 ,16907,16905,14524 ,0,0,0}, {27316,27272,28285 ,16907,16906,16905 ,0,0,0}, + {27318,27317,28286 ,16908,14524,16909 ,0,0,0}, {28285,28286,27317 ,16905,16909,14524 ,0,0,0}, + {28287,27319,27318 ,14482,16910,16908 ,0,0,0}, {27318,28286,28287 ,16908,16909,14482 ,0,0,0}, + {27319,28288,27320 ,16910,16911,16912 ,0,0,0}, {28288,27319,28287 ,16911,16910,14482 ,0,0,0}, + {27321,27320,28289 ,16913,16912,16914 ,0,0,0}, {28288,28289,27320 ,16911,16914,16912 ,0,0,0}, + {28290,27321,28289 ,16915,16913,16914 ,0,0,0}, {28290,27322,27321 ,16915,16916,16913 ,0,0,0}, + {28290,28291,27322 ,16915,16917,16916 ,0,0,0}, {28292,28293,28294 ,16918,16919,16920 ,0,0,0}, + {27323,28291,28293 ,16921,16917,16919 ,0,0,0}, {28291,27323,27322 ,16917,16921,16916 ,0,0,0}, + {28295,27324,28293 ,14476,16922,16919 ,0,0,0}, {27323,28293,27324 ,16921,16919,16922 ,0,0,0}, + {28296,28297,28298 ,16923,16924,16925 ,0,0,0}, {27325,27324,28295 ,14516,16922,14476 ,0,0,0}, + {28299,28300,28301 ,16926,16927,16928 ,0,0,0}, {28302,28303,28304 ,16929,16930,16931 ,0,0,0}, + {28305,28299,28306 ,16932,16926,16933 ,0,0,0}, {28307,28308,28309 ,16934,16935,16936 ,0,0,0}, + {28310,28311,28312 ,16937,16938,16939 ,0,0,0}, {28307,28313,28314 ,16934,16940,16941 ,0,0,0}, + {28315,28316,28317 ,16942,16943,16944 ,0,0,0}, {28314,28313,28318 ,16941,16940,16945 ,0,0,0}, + {27326,27325,28319 ,14515,14516,16946 ,0,0,0}, {26916,28318,28313 ,15634,16945,16940 ,0,0,0}, + {28320,28321,28322 ,16947,14473,16948 ,0,0,0}, {27325,28295,28319 ,14516,14476,16946 ,0,0,0}, + {27326,28304,27327 ,14515,16931,14514 ,0,0,0}, {28292,28295,28293 ,16918,14476,16919 ,0,0,0}, + {27328,27327,28321 ,16949,14514,14473 ,0,0,0}, {28304,28321,27327 ,16931,14473,14514 ,0,0,0}, + {27329,28320,27330 ,16950,16947,16951 ,0,0,0}, {27328,28321,28320 ,16949,14473,16947 ,0,0,0}, + {27330,28323,26950 ,16951,16952,15664 ,0,0,0}, {28320,28323,27330 ,16947,16952,16951 ,0,0,0}, + {26851,28259,26848 ,16880,16871,16874 ,0,0,0}, {28010,28260,27972 ,16953,16873,16872 ,0,0,0}, + {28010,28262,28260 ,16953,16876,16873 ,0,0,0}, {28261,28244,27285 ,16875,16855,16868 ,0,0,0}, + {28261,28260,28324 ,16875,16873,16954 ,0,0,0}, {28325,28242,28247 ,16955,16850,16858 ,0,0,0}, + {28244,28324,28246 ,16855,16954,16857 ,0,0,0}, {28326,28240,28325 ,16956,16847,16955 ,0,0,0}, + {28246,28243,28244 ,16857,16852,16855 ,0,0,0}, {28327,28241,28326 ,16957,16848,16956 ,0,0,0}, + {28247,28242,28243 ,16858,16850,16852 ,0,0,0}, {28328,28239,28327 ,16958,16844,16957 ,0,0,0}, + {28325,28240,28242 ,16955,16847,16850 ,0,0,0}, {28329,28238,28328 ,14467,16841,16958 ,0,0,0}, + {28326,28241,28240 ,16956,16848,16847 ,0,0,0}, {28330,28237,28329 ,16959,16840,14467 ,0,0,0}, + {28327,28239,28241 ,16957,16844,16848 ,0,0,0}, {28331,28233,28330 ,16960,16838,16959 ,0,0,0}, + {28328,28238,28239 ,16958,16841,16844 ,0,0,0}, {28331,28332,28232 ,16960,16961,14502 ,0,0,0}, + {28237,28238,28329 ,16840,16841,14467 ,0,0,0}, {28333,28231,28332 ,16962,16837,16961 ,0,0,0}, + {28233,28237,28330 ,16838,16840,16959 ,0,0,0}, {28234,28230,28333 ,14462,16835,16962 ,0,0,0}, + {28232,28233,28331 ,14502,16838,16960 ,0,0,0}, {28334,28229,28234 ,16963,14499,14462 ,0,0,0}, + {28231,28232,28332 ,16837,14502,16961 ,0,0,0}, {28335,28228,28334 ,16964,16832,16963 ,0,0,0}, + {28230,28231,28333 ,16835,16837,16962 ,0,0,0}, {28336,28226,28335 ,16965,16829,16964 ,0,0,0}, + {28234,28229,28230 ,14462,14499,16835 ,0,0,0}, {28337,28227,28336 ,16966,16831,16965 ,0,0,0}, + {28334,28228,28229 ,16963,16832,14499 ,0,0,0}, {28337,28338,28264 ,16966,16967,16882 ,0,0,0}, + {28226,28228,28335 ,16829,16832,16964 ,0,0,0}, {28339,28265,28338 ,16968,16884,16967 ,0,0,0}, + {28227,28226,28336 ,16831,16829,16965 ,0,0,0}, {28340,28266,28339 ,16969,14452,16968 ,0,0,0}, + {28264,28227,28337 ,16882,16831,16966 ,0,0,0}, {28341,28267,28340 ,16970,16887,16969 ,0,0,0}, + {28265,28264,28338 ,16884,16882,16967 ,0,0,0}, {28342,28268,28341 ,16971,16888,16970 ,0,0,0}, + {28266,28265,28339 ,14452,16884,16968 ,0,0,0}, {28343,28269,28342 ,14450,16889,16971 ,0,0,0}, + {28340,28267,28266 ,16969,16887,14452 ,0,0,0}, {28343,28344,28270 ,14450,16972,16891 ,0,0,0}, + {28268,28267,28341 ,16888,16887,16970 ,0,0,0}, {28345,28274,28344 ,16973,16895,16972 ,0,0,0}, + {28269,28268,28342 ,16889,16888,16971 ,0,0,0}, {28271,28275,28345 ,16892,16896,16973 ,0,0,0}, + {28270,28269,28343 ,16891,16889,14450 ,0,0,0}, {28346,28276,28271 ,16974,14488,16892 ,0,0,0}, + {28274,28270,28344 ,16895,16891,16972 ,0,0,0}, {28347,28277,28346 ,16975,16898,16974 ,0,0,0}, + {28275,28274,28345 ,16896,16895,16973 ,0,0,0}, {28348,28278,28347 ,14444,16900,16975 ,0,0,0}, + {28271,28276,28275 ,16892,14488,16896 ,0,0,0}, {28349,28279,28348 ,16976,16901,14444 ,0,0,0}, + {28346,28277,28276 ,16974,16898,14488 ,0,0,0}, {28349,28350,28280 ,16976,16977,16902 ,0,0,0}, + {28278,28277,28347 ,16900,16898,16975 ,0,0,0}, {28351,28284,28350 ,16978,14439,16977 ,0,0,0}, + {28279,28278,28348 ,16901,16900,14444 ,0,0,0}, {28352,28285,28351 ,16979,16905,16978 ,0,0,0}, + {28280,28279,28349 ,16902,16901,16976 ,0,0,0}, {28353,28286,28352 ,16980,16909,16979 ,0,0,0}, + {28284,28280,28350 ,14439,16902,16977 ,0,0,0}, {28354,28287,28353 ,16981,14482,16980 ,0,0,0}, + {28351,28285,28284 ,16978,16905,14439 ,0,0,0}, {28355,28288,28354 ,16982,16911,16981 ,0,0,0}, + {28352,28286,28285 ,16979,16909,16905 ,0,0,0}, {28356,28289,28355 ,16983,16914,16982 ,0,0,0}, + {28353,28287,28286 ,16980,14482,16909 ,0,0,0}, {28357,28290,28356 ,16984,16915,16983 ,0,0,0}, + {28354,28288,28287 ,16981,16911,14482 ,0,0,0}, {28357,28294,28291 ,16984,16920,16917 ,0,0,0}, + {28289,28288,28355 ,16914,16911,16982 ,0,0,0}, {28295,28292,28358 ,14476,16918,16985 ,0,0,0}, + {28290,28289,28356 ,16915,16914,16983 ,0,0,0}, {28312,28303,28316 ,16939,16930,16943 ,0,0,0}, + {28291,28290,28357 ,16917,16915,16984 ,0,0,0}, {28302,28319,28358 ,16929,16946,16985 ,0,0,0}, + {28293,28291,28294 ,16919,16917,16920 ,0,0,0}, {28302,28358,28359 ,16929,16985,16986 ,0,0,0}, + {28311,28322,28312 ,16938,16948,16939 ,0,0,0}, {28319,28304,27326 ,16946,16931,14515 ,0,0,0}, + {28319,28295,28358 ,16946,14476,16985 ,0,0,0}, {28360,28323,28361 ,16987,16952,16988 ,0,0,0}, + {28319,28302,28304 ,16946,16929,16931 ,0,0,0}, {28322,28321,28303 ,16948,14473,16930 ,0,0,0}, + {28362,28363,28323 ,16989,16990,16952 ,0,0,0}, {27328,28320,27329 ,16949,16947,16950 ,0,0,0}, + {28320,28361,28323 ,16947,16988,16952 ,0,0,0}, {26950,28323,28363 ,15664,16952,16990 ,0,0,0}, + {28259,28260,28261 ,16871,16873,16875 ,0,0,0}, {28052,28262,28010 ,16878,16876,16953 ,0,0,0}, + {28144,28190,28254 ,14341,14342,16864 ,0,0,0}, {28261,28324,28244 ,16875,16954,16855 ,0,0,0}, + {28324,28262,28364 ,16954,16876,16991 ,0,0,0}, {28253,28252,28325 ,14423,16863,16955 ,0,0,0}, + {28257,28246,28364 ,16869,16857,16991 ,0,0,0}, {28252,28365,28326 ,16863,16992,16956 ,0,0,0}, + {28257,28247,28246 ,16869,16858,16857 ,0,0,0}, {28365,28366,28327 ,16992,16993,16957 ,0,0,0}, + {28253,28325,28247 ,14423,16955,16858 ,0,0,0}, {28366,28367,28328 ,16993,16994,16958 ,0,0,0}, + {28252,28326,28325 ,16863,16956,16955 ,0,0,0}, {28367,28368,28329 ,16994,14379,14467 ,0,0,0}, + {28365,28327,28326 ,16992,16957,16956 ,0,0,0}, {28368,28369,28330 ,14379,16995,16959 ,0,0,0}, + {28366,28328,28327 ,16993,16958,16957 ,0,0,0}, {28369,28370,28331 ,16995,16996,16960 ,0,0,0}, + {28367,28329,28328 ,16994,14467,16958 ,0,0,0}, {28370,28371,28332 ,16996,14416,16961 ,0,0,0}, + {28368,28330,28329 ,14379,16959,14467 ,0,0,0}, {28371,28235,28333 ,14416,16839,16962 ,0,0,0}, + {28331,28330,28369 ,16960,16959,16995 ,0,0,0}, {28372,28373,28374 ,16997,16998,16999 ,0,0,0}, + {28332,28331,28370 ,16961,16960,16996 ,0,0,0}, {28236,28373,28334 ,14414,16998,16963 ,0,0,0}, + {28333,28332,28371 ,16962,16961,14416 ,0,0,0}, {28373,28372,28335 ,16998,16997,16964 ,0,0,0}, + {28234,28333,28235 ,14462,16962,16839 ,0,0,0}, {28372,28375,28336 ,16997,17000,16965 ,0,0,0}, + {28236,28334,28234 ,14414,16963,14462 ,0,0,0}, {28375,28376,28337 ,17000,17001,16966 ,0,0,0}, + {28373,28335,28334 ,16998,16964,16963 ,0,0,0}, {28376,28377,28338 ,17001,17002,16967 ,0,0,0}, + {28372,28336,28335 ,16997,16965,16964 ,0,0,0}, {28377,28378,28339 ,17002,17003,16968 ,0,0,0}, + {28337,28336,28375 ,16966,16965,17000 ,0,0,0}, {28224,28340,28378 ,16827,16969,17003 ,0,0,0}, + {28338,28337,28376 ,16967,16966,17001 ,0,0,0}, {28224,28223,28341 ,16827,16826,16970 ,0,0,0}, + {28339,28338,28377 ,16968,16967,17002 ,0,0,0}, {28223,28379,28342 ,16826,17004,16971 ,0,0,0}, + {28378,28340,28339 ,17003,16969,16968 ,0,0,0}, {28379,28380,28343 ,17004,14364,14450 ,0,0,0}, + {28224,28341,28340 ,16827,16970,16969 ,0,0,0}, {28380,28381,28344 ,14364,17005,16972 ,0,0,0}, + {28223,28342,28341 ,16826,16971,16970 ,0,0,0}, {28381,28272,28345 ,17005,16893,16973 ,0,0,0}, + {28343,28342,28379 ,14450,16971,17004 ,0,0,0}, {28382,28383,28384 ,17006,17007,17008 ,0,0,0}, + {28344,28343,28380 ,16972,14450,14364 ,0,0,0}, {28273,28385,28346 ,16894,17009,16974 ,0,0,0}, + {28345,28344,28381 ,16973,16972,17005 ,0,0,0}, {28385,28386,28347 ,17009,17010,16975 ,0,0,0}, + {28271,28345,28272 ,16892,16973,16893 ,0,0,0}, {28386,28387,28348 ,17010,17011,14444 ,0,0,0}, + {28273,28346,28271 ,16894,16974,16892 ,0,0,0}, {28387,28388,28349 ,17011,17012,16976 ,0,0,0}, + {28385,28347,28346 ,17009,16975,16974 ,0,0,0}, {28388,28389,28350 ,17012,17013,16977 ,0,0,0}, + {28386,28348,28347 ,17010,14444,16975 ,0,0,0}, {28389,28390,28351 ,17013,17014,16978 ,0,0,0}, + {28349,28348,28387 ,16976,14444,17011 ,0,0,0}, {28390,28281,28352 ,17014,14397,16979 ,0,0,0}, + {28350,28349,28388 ,16977,16976,17012 ,0,0,0}, {28281,28283,28353 ,14397,16904,16980 ,0,0,0}, + {28351,28350,28389 ,16978,16977,17013 ,0,0,0}, {28283,28391,28354 ,16904,14394,16981 ,0,0,0}, + {28390,28352,28351 ,17014,16979,16978 ,0,0,0}, {28391,28392,28355 ,14394,17015,16982 ,0,0,0}, + {28281,28353,28352 ,14397,16980,16979 ,0,0,0}, {28392,28393,28356 ,17015,17016,16983 ,0,0,0}, + {28283,28354,28353 ,16904,16981,16980 ,0,0,0}, {28393,28394,28357 ,17016,14393,16984 ,0,0,0}, + {28391,28355,28354 ,14394,16982,16981 ,0,0,0}, {28394,28395,28294 ,14393,17017,16920 ,0,0,0}, + {28392,28356,28355 ,17015,16983,16982 ,0,0,0}, {28395,28396,28292 ,17017,17018,16918 ,0,0,0}, + {28393,28357,28356 ,17016,16984,16983 ,0,0,0}, {28396,28359,28358 ,17018,16986,16985 ,0,0,0}, + {28394,28294,28357 ,14393,16920,16984 ,0,0,0}, {28359,28316,28302 ,16986,16943,16929 ,0,0,0}, + {28292,28294,28395 ,16918,16920,17017 ,0,0,0}, {28397,28311,28398 ,17019,16938,17020 ,0,0,0}, + {28292,28396,28358 ,16918,17018,16985 ,0,0,0}, {28322,28311,28361 ,16948,16938,16988 ,0,0,0}, + {28310,28398,28311 ,16937,17020,16938 ,0,0,0}, {28304,28303,28321 ,16931,16930,14473 ,0,0,0}, + {28316,28303,28302 ,16943,16930,16929 ,0,0,0}, {28399,28360,28296 ,17021,16987,16923 ,0,0,0}, + {28360,28362,28323 ,16987,16989,16952 ,0,0,0}, {28320,28322,28361 ,16947,16948,16988 ,0,0,0}, + {28360,28361,28397 ,16987,16988,17019 ,0,0,0}, {28399,28362,28360 ,17021,16989,16987 ,0,0,0}, + {28260,28262,28324 ,16873,16876,16954 ,0,0,0}, {28006,28258,28051 ,14339,16870,16877 ,0,0,0}, + {26977,28250,26979 ,17022,16861,16854 ,0,0,0}, {28324,28364,28246 ,16954,16991,16857 ,0,0,0}, + {28364,28258,28400 ,16991,16870,17023 ,0,0,0}, {28252,28401,28365 ,16863,17024,16992 ,0,0,0}, + {28263,28257,28400 ,16881,16869,17023 ,0,0,0}, {28365,28402,28366 ,16992,17025,16993 ,0,0,0}, + {28263,28251,28253 ,16881,16862,14423 ,0,0,0}, {28403,28404,28405 ,17026,17027,17028 ,0,0,0}, + {28251,28401,28252 ,16862,17024,16863 ,0,0,0}, {28367,28366,28406 ,16994,16993,17029 ,0,0,0}, + {28401,28402,28365 ,17024,17025,16992 ,0,0,0}, {28368,28367,28405 ,14379,16994,17028 ,0,0,0}, + {28402,28406,28366 ,17025,17029,16993 ,0,0,0}, {28369,28368,28404 ,16995,14379,17027 ,0,0,0}, + {28406,28405,28367 ,17029,17028,16994 ,0,0,0}, {28370,28369,28407 ,16996,16995,17030 ,0,0,0}, + {28405,28404,28368 ,17028,17027,14379 ,0,0,0}, {28371,28370,28408 ,14416,16996,17031 ,0,0,0}, + {28404,28407,28369 ,17027,17030,16995 ,0,0,0}, {28235,28371,28409 ,16839,14416,17032 ,0,0,0}, + {28407,28408,28370 ,17030,17031,16996 ,0,0,0}, {28236,28235,28410 ,14414,16839,17033 ,0,0,0}, + {28408,28409,28371 ,17031,17032,14416 ,0,0,0}, {28373,28236,28411 ,16998,14414,17034 ,0,0,0}, + {28410,28235,28409 ,17033,16839,17032 ,0,0,0}, {28412,28413,28414 ,17035,17036,17037 ,0,0,0}, + {28411,28236,28410 ,17034,14414,17033 ,0,0,0}, {28375,28372,28415 ,17000,16997,17038 ,0,0,0}, + {28411,28374,28373 ,17034,16999,16998 ,0,0,0}, {28376,28375,28414 ,17001,17000,17037 ,0,0,0}, + {28374,28415,28372 ,16999,17038,16997 ,0,0,0}, {28377,28376,28413 ,17002,17001,17036 ,0,0,0}, + {28415,28414,28375 ,17038,17037,17000 ,0,0,0}, {28378,28377,28416 ,17003,17002,17039 ,0,0,0}, + {28414,28413,28376 ,17037,17036,17001 ,0,0,0}, {28224,28378,28417 ,16827,17003,17040 ,0,0,0}, + {28416,28377,28413 ,17039,17002,17036 ,0,0,0}, {28418,28419,28420 ,17041,17042,17043 ,0,0,0}, + {28417,28378,28416 ,17040,17003,17039 ,0,0,0}, {28379,28223,28421 ,17004,16826,17044 ,0,0,0}, + {28417,28225,28224 ,17040,16828,16827 ,0,0,0}, {28380,28379,28420 ,14364,17004,17043 ,0,0,0}, + {28225,28421,28223 ,16828,17044,16826 ,0,0,0}, {28381,28380,28419 ,17005,14364,17042 ,0,0,0}, + {28421,28420,28379 ,17044,17043,17004 ,0,0,0}, {28272,28381,28422 ,16893,17005,17045 ,0,0,0}, + {28420,28419,28380 ,17043,17042,14364 ,0,0,0}, {28273,28272,28423 ,16894,16893,17046 ,0,0,0}, + {28419,28422,28381 ,17042,17045,17005 ,0,0,0}, {28385,28273,28424 ,17009,16894,17047 ,0,0,0}, + {28423,28272,28422 ,17046,16893,17045 ,0,0,0}, {28386,28385,28425 ,17010,17009,17048 ,0,0,0}, + {28424,28273,28423 ,17047,16894,17046 ,0,0,0}, {28387,28386,28382 ,17011,17010,17006 ,0,0,0}, + {28424,28425,28385 ,17047,17048,17009 ,0,0,0}, {28388,28387,28384 ,17012,17011,17008 ,0,0,0}, + {28425,28382,28386 ,17048,17006,17010 ,0,0,0}, {28389,28388,28426 ,17013,17012,17049 ,0,0,0}, + {28382,28384,28387 ,17006,17008,17011 ,0,0,0}, {28390,28389,28427 ,17014,17013,17050 ,0,0,0}, + {28384,28426,28388 ,17008,17049,17012 ,0,0,0}, {28281,28390,28428 ,14397,17014,17051 ,0,0,0}, + {28427,28389,28426 ,17050,17013,17049 ,0,0,0}, {28429,28430,28431 ,17052,17053,17054 ,0,0,0}, + {28428,28390,28427 ,17051,17014,17050 ,0,0,0}, {28391,28283,28432 ,14394,16904,17055 ,0,0,0}, + {28428,28282,28281 ,17051,16903,14397 ,0,0,0}, {28392,28391,28431 ,17015,14394,17054 ,0,0,0}, + {28282,28432,28283 ,16903,17055,16904 ,0,0,0}, {28393,28392,28430 ,17016,17015,17053 ,0,0,0}, + {28432,28431,28391 ,17055,17054,14394 ,0,0,0}, {28394,28393,28433 ,14393,17016,17056 ,0,0,0}, + {28431,28430,28392 ,17054,17053,17015 ,0,0,0}, {28395,28394,28434 ,17017,14393,17057 ,0,0,0}, + {28430,28433,28393 ,17053,17056,17016 ,0,0,0}, {28396,28395,28435 ,17018,17017,17058 ,0,0,0}, + {28433,28434,28394 ,17056,17057,14393 ,0,0,0}, {28359,28396,28436 ,16986,17018,17059 ,0,0,0}, + {28434,28435,28395 ,17057,17058,17017 ,0,0,0}, {28316,28359,28317 ,16943,16986,16944 ,0,0,0}, + {28435,28436,28396 ,17058,17059,17018 ,0,0,0}, {28312,28316,28315 ,16939,16943,16942 ,0,0,0}, + {28436,28317,28359 ,17059,16944,16986 ,0,0,0}, {28297,28398,28300 ,16924,17020,16927 ,0,0,0}, + {28398,28437,28300 ,17020,17060,16927 ,0,0,0}, {28303,28312,28322 ,16930,16939,16948 ,0,0,0}, + {28315,28310,28312 ,16942,16937,16939 ,0,0,0}, {28438,28296,28298 ,17061,16923,16925 ,0,0,0}, + {28360,28397,28296 ,16987,17019,16923 ,0,0,0}, {28361,28311,28397 ,16988,16938,17019 ,0,0,0}, + {28397,28297,28296 ,17019,16924,16923 ,0,0,0}, {28399,28296,28438 ,17021,16923,17061 ,0,0,0}, + {28258,28364,28262 ,16870,16991,16876 ,0,0,0}, {28144,28255,28145 ,14341,16865,14340 ,0,0,0}, + {28263,28439,28251 ,16881,17062,16862 ,0,0,0}, {28364,28400,28257 ,16991,17023,16869 ,0,0,0}, + {28255,28440,28400 ,16865,17063,17023 ,0,0,0}, {28401,28251,28441 ,17024,16862,17064 ,0,0,0}, + {28440,28439,28263 ,17063,17062,16881 ,0,0,0}, {28402,28401,28442 ,17025,17024,17065 ,0,0,0}, + {28251,28439,28441 ,16862,17062,17064 ,0,0,0}, {28406,28402,28443 ,17029,17025,17066 ,0,0,0}, + {28401,28441,28442 ,17024,17064,17065 ,0,0,0}, {28405,28406,28444 ,17028,17029,17067 ,0,0,0}, + {28442,28443,28402 ,17065,17066,17025 ,0,0,0}, {28445,28407,28404 ,14333,17030,17027 ,0,0,0}, + {28443,28444,28406 ,17066,17067,17029 ,0,0,0}, {28446,28447,28448 ,17068,17069,17070 ,0,0,0}, + {28444,28403,28405 ,17067,17026,17028 ,0,0,0}, {28407,28449,28408 ,17030,17071,17031 ,0,0,0}, + {28403,28445,28404 ,17026,14333,17027 ,0,0,0}, {28408,28447,28409 ,17031,17069,17032 ,0,0,0}, + {28445,28449,28407 ,14333,17071,17030 ,0,0,0}, {28409,28446,28410 ,17032,17068,17033 ,0,0,0}, + {28449,28447,28408 ,17071,17069,17031 ,0,0,0}, {28410,28450,28411 ,17033,17072,17034 ,0,0,0}, + {28447,28446,28409 ,17069,17068,17032 ,0,0,0}, {28411,28451,28374 ,17034,14238,16999 ,0,0,0}, + {28446,28450,28410 ,17068,17072,17033 ,0,0,0}, {28415,28374,28452 ,17038,16999,17073 ,0,0,0}, + {28450,28451,28411 ,17072,14238,17034 ,0,0,0}, {28414,28415,28453 ,17037,17038,17074 ,0,0,0}, + {28451,28452,28374 ,14238,17073,16999 ,0,0,0}, {28454,28455,28456 ,17075,17076,17077 ,0,0,0}, + {28452,28453,28415 ,17073,17074,17038 ,0,0,0}, {28413,28457,28416 ,17036,17078,17039 ,0,0,0}, + {28453,28412,28414 ,17074,17035,17037 ,0,0,0}, {28416,28458,28417 ,17039,17079,17040 ,0,0,0}, + {28412,28457,28413 ,17035,17078,17036 ,0,0,0}, {28417,28459,28225 ,17040,17080,16828 ,0,0,0}, + {28457,28458,28416 ,17078,17079,17039 ,0,0,0}, {28421,28225,28460 ,17044,16828,17081 ,0,0,0}, + {28458,28459,28417 ,17079,17080,17040 ,0,0,0}, {28420,28421,28461 ,17043,17044,17082 ,0,0,0}, + {28459,28460,28225 ,17080,17081,16828 ,0,0,0}, {28462,28463,28464 ,17083,17084,17085 ,0,0,0}, + {28460,28461,28421 ,17081,17082,17044 ,0,0,0}, {28419,28465,28422 ,17042,14319,17045 ,0,0,0}, + {28461,28418,28420 ,17082,17041,17043 ,0,0,0}, {28422,28466,28423 ,17045,17086,17046 ,0,0,0}, + {28418,28465,28419 ,17041,14319,17042 ,0,0,0}, {28423,28467,28424 ,17046,17087,17047 ,0,0,0}, + {28465,28466,28422 ,14319,17086,17045 ,0,0,0}, {28424,28468,28425 ,17047,17088,17048 ,0,0,0}, + {28466,28467,28423 ,17086,17087,17046 ,0,0,0}, {28382,28425,28469 ,17006,17048,17089 ,0,0,0}, + {28467,28468,28424 ,17087,17088,17047 ,0,0,0}, {28470,28471,28472 ,17090,17091,17092 ,0,0,0}, + {28468,28469,28425 ,17088,17089,17048 ,0,0,0}, {28384,28473,28426 ,17008,17093,17049 ,0,0,0}, + {28469,28383,28382 ,17089,17007,17006 ,0,0,0}, {28426,28471,28427 ,17049,17091,17050 ,0,0,0}, + {28383,28473,28384 ,17007,17093,17008 ,0,0,0}, {28427,28470,28428 ,17050,17090,17051 ,0,0,0}, + {28473,28471,28426 ,17093,17091,17049 ,0,0,0}, {28428,28474,28282 ,17051,17094,16903 ,0,0,0}, + {28471,28470,28427 ,17091,17090,17050 ,0,0,0}, {28432,28282,28475 ,17055,16903,14264 ,0,0,0}, + {28470,28474,28428 ,17090,17094,17051 ,0,0,0}, {28431,28432,28476 ,17054,17055,17095 ,0,0,0}, + {28474,28475,28282 ,17094,14264,16903 ,0,0,0}, {28477,28433,28430 ,17096,17056,17053 ,0,0,0}, + {28475,28476,28432 ,14264,17095,17055 ,0,0,0}, {28478,28479,28480 ,17097,14305,14260 ,0,0,0}, + {28476,28429,28431 ,17095,17052,17054 ,0,0,0}, {28433,28481,28434 ,17056,17098,17057 ,0,0,0}, + {28429,28477,28430 ,17052,17096,17053 ,0,0,0}, {28434,28479,28435 ,17057,14305,17058 ,0,0,0}, + {28477,28481,28433 ,17096,17098,17056 ,0,0,0}, {28435,28478,28436 ,17058,17097,17059 ,0,0,0}, + {28481,28479,28434 ,17098,14305,17057 ,0,0,0}, {28436,28482,28317 ,17059,17099,16944 ,0,0,0}, + {28479,28478,28435 ,14305,17097,17058 ,0,0,0}, {28317,28483,28315 ,16944,17100,16942 ,0,0,0}, + {28478,28482,28436 ,17097,17099,17059 ,0,0,0}, {28315,28484,28310 ,16942,17101,16937 ,0,0,0}, + {28482,28483,28317 ,17099,17100,16944 ,0,0,0}, {28310,28437,28398 ,16937,17060,17020 ,0,0,0}, + {28484,28315,28483 ,17101,16942,17100 ,0,0,0}, {28485,28486,28298 ,17102,17103,16925 ,0,0,0}, + {28310,28484,28437 ,16937,17101,17060 ,0,0,0}, {28487,28298,28486 ,17104,16925,17103 ,0,0,0}, + {28488,28438,28298 ,17105,17061,16925 ,0,0,0}, {28397,28398,28297 ,17019,17020,16924 ,0,0,0}, + {28297,28485,28298 ,16924,17102,16925 ,0,0,0}, {28487,28488,28298 ,17104,17105,16925 ,0,0,0}, + {28255,28400,28258 ,16865,17023,16870 ,0,0,0}, {27918,28254,28190 ,16866,16864,14342 ,0,0,0}, + {28439,28489,28441 ,17062,14147,17064 ,0,0,0}, {28400,28440,28263 ,17023,17063,16881 ,0,0,0}, + {28254,28490,28440 ,16864,17106,17063 ,0,0,0}, {28442,28441,28491 ,17065,17064,17107 ,0,0,0}, + {28439,28490,28489 ,17062,17106,14147 ,0,0,0}, {28443,28442,28492 ,17066,17065,17108 ,0,0,0}, + {28441,28489,28491 ,17064,14147,17107 ,0,0,0}, {28444,28443,28493 ,17067,17066,17109 ,0,0,0}, + {28442,28491,28492 ,17065,17107,17108 ,0,0,0}, {28403,28444,28494 ,17026,17067,17110 ,0,0,0}, + {28443,28492,28493 ,17066,17108,17109 ,0,0,0}, {28445,28403,28495 ,14333,17026,17111 ,0,0,0}, + {28444,28493,28494 ,17067,17109,17110 ,0,0,0}, {28449,28445,28496 ,17071,14333,14291 ,0,0,0}, + {28403,28494,28495 ,17026,17110,17111 ,0,0,0}, {28447,28449,28497 ,17069,17071,17112 ,0,0,0}, + {28495,28496,28445 ,17111,14291,14333 ,0,0,0}, {28498,28499,28500 ,17113,17114,17115 ,0,0,0}, + {28496,28497,28449 ,14291,17112,17071 ,0,0,0}, {28446,28501,28450 ,17068,17116,17072 ,0,0,0}, + {28497,28448,28447 ,17112,17070,17069 ,0,0,0}, {28450,28500,28451 ,17072,17115,14238 ,0,0,0}, + {28448,28501,28446 ,17070,17116,17068 ,0,0,0}, {28451,28502,28452 ,14238,17117,17073 ,0,0,0}, + {28501,28500,28450 ,17116,17115,17072 ,0,0,0}, {28453,28452,28503 ,17074,17073,17118 ,0,0,0}, + {28500,28502,28451 ,17115,17117,14238 ,0,0,0}, {28412,28453,28504 ,17035,17074,17119 ,0,0,0}, + {28452,28502,28503 ,17073,17117,17118 ,0,0,0}, {28457,28412,28505 ,17078,17035,17120 ,0,0,0}, + {28453,28503,28504 ,17074,17118,17119 ,0,0,0}, {28458,28457,28506 ,17079,17078,17121 ,0,0,0}, + {28504,28505,28412 ,17119,17120,17035 ,0,0,0}, {28458,28507,28459 ,17079,17122,17080 ,0,0,0}, + {28505,28506,28457 ,17120,17121,17078 ,0,0,0}, {28459,28455,28460 ,17080,17076,17081 ,0,0,0}, + {28506,28507,28458 ,17121,17122,17079 ,0,0,0}, {28461,28460,28508 ,17082,17081,17123 ,0,0,0}, + {28507,28455,28459 ,17122,17076,17080 ,0,0,0}, {28418,28461,28509 ,17041,17082,17124 ,0,0,0}, + {28460,28455,28508 ,17081,17076,17123 ,0,0,0}, {28465,28418,28510 ,14319,17041,17125 ,0,0,0}, + {28461,28508,28509 ,17082,17123,17124 ,0,0,0}, {28466,28465,28511 ,17086,14319,17126 ,0,0,0}, + {28509,28510,28418 ,17124,17125,17041 ,0,0,0}, {28466,28512,28467 ,17086,17127,17087 ,0,0,0}, + {28510,28511,28465 ,17125,17126,14319 ,0,0,0}, {28467,28463,28468 ,17087,17084,17088 ,0,0,0}, + {28511,28512,28466 ,17126,17127,17086 ,0,0,0}, {28469,28468,28513 ,17089,17088,17128 ,0,0,0}, + {28512,28463,28467 ,17127,17084,17087 ,0,0,0}, {28383,28469,28514 ,17007,17089,17129 ,0,0,0}, + {28468,28463,28513 ,17088,17084,17128 ,0,0,0}, {28473,28383,28515 ,17093,17007,17130 ,0,0,0}, + {28469,28513,28514 ,17089,17128,17129 ,0,0,0}, {28471,28473,28516 ,17091,17093,17131 ,0,0,0}, + {28514,28515,28383 ,17129,17130,17007 ,0,0,0}, {28517,28518,28519 ,17132,17133,17134 ,0,0,0}, + {28515,28516,28473 ,17130,17131,17093 ,0,0,0}, {28470,28520,28474 ,17090,17135,17094 ,0,0,0}, + {28516,28472,28471 ,17131,17092,17091 ,0,0,0}, {28474,28519,28475 ,17094,17134,14264 ,0,0,0}, + {28472,28520,28470 ,17092,17135,17090 ,0,0,0}, {28476,28475,28521 ,17095,14264,17136 ,0,0,0}, + {28520,28519,28474 ,17135,17134,17094 ,0,0,0}, {28429,28476,28522 ,17052,17095,17137 ,0,0,0}, + {28475,28519,28521 ,14264,17134,17136 ,0,0,0}, {28477,28429,28523 ,17096,17052,17138 ,0,0,0}, + {28476,28521,28522 ,17095,17136,17137 ,0,0,0}, {28481,28477,28524 ,17098,17096,17139 ,0,0,0}, + {28429,28522,28523 ,17052,17137,17138 ,0,0,0}, {28479,28481,28525 ,14305,17098,17140 ,0,0,0}, + {28523,28524,28477 ,17138,17139,17096 ,0,0,0}, {28526,28482,28478 ,17141,17099,17097 ,0,0,0}, + {28524,28525,28481 ,17139,17140,17098 ,0,0,0}, {28527,28528,28529 ,17142,17143,17144 ,0,0,0}, + {28525,28480,28479 ,17140,14260,14305 ,0,0,0}, {28482,28530,28483 ,17099,17145,17100 ,0,0,0}, + {28480,28526,28478 ,14260,17141,17097 ,0,0,0}, {28483,28529,28484 ,17100,17144,17101 ,0,0,0}, + {28526,28530,28482 ,17141,17145,17099 ,0,0,0}, {28484,28531,28437 ,17101,17146,17060 ,0,0,0}, + {28530,28529,28483 ,17145,17144,17100 ,0,0,0}, {28437,28301,28300 ,17060,16928,16927 ,0,0,0}, + {28529,28531,28484 ,17144,17146,17101 ,0,0,0}, {28300,28299,28485 ,16927,16926,17102 ,0,0,0}, + {28301,28437,28531 ,16928,17060,17146 ,0,0,0}, {28486,28532,28309 ,17103,17147,16936 ,0,0,0}, + {28533,28534,28486 ,17148,17149,17103 ,0,0,0}, {28297,28300,28485 ,16924,16927,17102 ,0,0,0}, + {28485,28532,28486 ,17102,17147,17103 ,0,0,0}, {28487,28486,28534 ,17104,17103,17149 ,0,0,0}, + {28255,28254,28440 ,16865,16864,17063 ,0,0,0}, {27922,28256,27918 ,17150,16867,16866 ,0,0,0}, + {28491,28489,28249 ,17107,14147,16860 ,0,0,0}, {28440,28490,28439 ,17063,17106,17062 ,0,0,0}, + {28256,28535,28490 ,16867,17151,17106 ,0,0,0}, {28492,28491,28536 ,17108,17107,17152 ,0,0,0}, + {28489,28535,28249 ,14147,17151,16860 ,0,0,0}, {28537,28536,28538 ,17153,17152,17154 ,0,0,0}, + {28491,28249,28536 ,17107,16860,17152 ,0,0,0}, {28537,28539,28493 ,17153,17155,17109 ,0,0,0}, + {28493,28492,28537 ,17109,17108,17153 ,0,0,0}, {28539,28540,28494 ,17155,17156,17110 ,0,0,0}, + {28494,28493,28539 ,17110,17109,17155 ,0,0,0}, {28540,28541,28495 ,17156,17157,17111 ,0,0,0}, + {28495,28494,28540 ,17111,17110,17156 ,0,0,0}, {28541,28542,28496 ,17157,17158,14291 ,0,0,0}, + {28496,28495,28541 ,14291,17111,17157 ,0,0,0}, {28542,28543,28497 ,17158,17159,17112 ,0,0,0}, + {28497,28496,28542 ,17112,14291,17158 ,0,0,0}, {28543,28544,28448 ,17159,17160,17070 ,0,0,0}, + {28448,28497,28543 ,17070,17112,17159 ,0,0,0}, {28544,28498,28501 ,17160,17113,17116 ,0,0,0}, + {28448,28544,28501 ,17070,17160,17116 ,0,0,0}, {26965,28545,28546 ,17161,17162,17163 ,0,0,0}, + {28501,28498,28500 ,17116,17113,17115 ,0,0,0}, {28502,28547,28503 ,17117,17164,17118 ,0,0,0}, + {28500,28499,28502 ,17115,17114,17117 ,0,0,0}, {28548,28547,28546 ,17165,17164,17163 ,0,0,0}, + {28499,28547,28502 ,17114,17164,17117 ,0,0,0}, {28548,28549,28504 ,17165,17166,17119 ,0,0,0}, + {28504,28503,28548 ,17119,17118,17165 ,0,0,0}, {28549,28550,28505 ,17166,17167,17120 ,0,0,0}, + {28505,28504,28549 ,17120,17119,17166 ,0,0,0}, {28550,28551,28506 ,17167,17168,17121 ,0,0,0}, + {28506,28505,28550 ,17121,17120,17167 ,0,0,0}, {28551,28456,28507 ,17168,17077,17122 ,0,0,0}, + {28506,28551,28507 ,17121,17168,17122 ,0,0,0}, {28552,28553,28554 ,14118,14234,14116 ,0,0,0}, + {28507,28456,28455 ,17122,17077,17076 ,0,0,0}, {28454,28553,28508 ,17075,14234,17123 ,0,0,0}, + {28455,28454,28508 ,17076,17075,17123 ,0,0,0}, {28553,28555,28509 ,14234,17169,17124 ,0,0,0}, + {28509,28508,28553 ,17124,17123,14234 ,0,0,0}, {28555,28556,28510 ,17169,17170,17125 ,0,0,0}, + {28510,28509,28555 ,17125,17124,17169 ,0,0,0}, {28556,28557,28511 ,17170,17171,17126 ,0,0,0}, + {28511,28510,28556 ,17126,17125,17170 ,0,0,0}, {28557,28464,28512 ,17171,17085,17127 ,0,0,0}, + {28511,28557,28512 ,17126,17171,17127 ,0,0,0}, {28558,26956,28559 ,17172,17173,14103 ,0,0,0}, + {28512,28464,28463 ,17127,17085,17084 ,0,0,0}, {28514,28513,28560 ,17129,17128,17174 ,0,0,0}, + {28463,28462,28513 ,17084,17083,17128 ,0,0,0}, {28561,28560,28558 ,17175,17174,17172 ,0,0,0}, + {28513,28462,28560 ,17128,17083,17174 ,0,0,0}, {28561,28562,28515 ,17175,17176,17130 ,0,0,0}, + {28515,28514,28561 ,17130,17129,17175 ,0,0,0}, {28562,28563,28516 ,17176,17177,17131 ,0,0,0}, + {28516,28515,28562 ,17131,17130,17176 ,0,0,0}, {28563,28564,28472 ,17177,17178,17092 ,0,0,0}, + {28472,28516,28563 ,17092,17131,17177 ,0,0,0}, {28564,28517,28520 ,17178,17132,17135 ,0,0,0}, + {28472,28564,28520 ,17092,17178,17135 ,0,0,0}, {28565,28566,28567 ,17179,17180,17181 ,0,0,0}, + {28520,28517,28519 ,17135,17132,17134 ,0,0,0}, {28518,28566,28521 ,17133,17180,17136 ,0,0,0}, + {28519,28518,28521 ,17134,17133,17136 ,0,0,0}, {28566,28568,28522 ,17180,17182,17137 ,0,0,0}, + {28522,28521,28566 ,17137,17136,17180 ,0,0,0}, {28568,28569,28523 ,17182,14221,17138 ,0,0,0}, + {28523,28522,28568 ,17138,17137,17182 ,0,0,0}, {28569,28570,28524 ,14221,17183,17139 ,0,0,0}, + {28524,28523,28569 ,17139,17138,14221 ,0,0,0}, {28570,28571,28525 ,17183,17184,17140 ,0,0,0}, + {28525,28524,28570 ,17140,17139,17183 ,0,0,0}, {28571,28572,28480 ,17184,17185,14260 ,0,0,0}, + {28480,28525,28571 ,14260,17140,17184 ,0,0,0}, {28572,28573,28526 ,17185,17186,17141 ,0,0,0}, + {28526,28480,28572 ,17141,14260,17185 ,0,0,0}, {28573,28527,28530 ,17186,17142,17145 ,0,0,0}, + {28526,28573,28530 ,17141,17186,17145 ,0,0,0}, {28531,28528,28574 ,17146,17143,17187 ,0,0,0}, + {28530,28527,28529 ,17145,17142,17144 ,0,0,0}, {28306,28299,28301 ,16933,16926,16928 ,0,0,0}, + {28529,28528,28531 ,17144,17143,17146 ,0,0,0}, {28305,28532,28299 ,16932,17147,16926 ,0,0,0}, + {28531,28574,28301 ,17146,17187,16928 ,0,0,0}, {28313,28307,28575 ,16940,16934,17188 ,0,0,0}, + {28574,28306,28301 ,17187,16933,16928 ,0,0,0}, {28305,28576,28577 ,16932,17189,17190 ,0,0,0}, + {28309,28533,28486 ,16936,17148,17103 ,0,0,0}, {28485,28299,28532 ,17102,16926,17147 ,0,0,0}, + {28309,28532,28577 ,16936,17147,17190 ,0,0,0}, {28308,28533,28309 ,16935,17148,16936 ,0,0,0}, + {28254,28256,28490 ,16864,16867,17106 ,0,0,0}, {27922,27924,28245 ,17150,16853,16856 ,0,0,0}, + {28535,28245,28250 ,17151,16856,16861 ,0,0,0}, {28490,28535,28489 ,17106,17151,14147 ,0,0,0}, + {28249,28535,28250 ,16860,17151,16861 ,0,0,0}, {28248,28538,28536 ,16859,17154,17152 ,0,0,0}, + {28536,28249,28248 ,17152,16860,16859 ,0,0,0}, {28538,28578,28537 ,17154,17191,17153 ,0,0,0}, + {28579,28539,28578 ,17192,17155,17191 ,0,0,0}, {28492,28536,28537 ,17108,17152,17153 ,0,0,0}, + {28539,28537,28578 ,17155,17153,17191 ,0,0,0}, {28580,28540,28579 ,17193,17156,17192 ,0,0,0}, + {28540,28539,28579 ,17156,17155,17192 ,0,0,0}, {28581,28541,28580 ,17194,17157,17193 ,0,0,0}, + {28541,28540,28580 ,17157,17156,17193 ,0,0,0}, {28582,28542,28581 ,17195,17158,17194 ,0,0,0}, + {28542,28541,28581 ,17158,17157,17194 ,0,0,0}, {28583,28543,28582 ,17196,17159,17195 ,0,0,0}, + {28543,28542,28582 ,17159,17158,17195 ,0,0,0}, {28584,28544,28583 ,17197,17160,17196 ,0,0,0}, + {28544,28543,28583 ,17160,17159,17196 ,0,0,0}, {28585,28498,28584 ,14134,17113,17197 ,0,0,0}, + {28498,28544,28584 ,17113,17160,17197 ,0,0,0}, {28586,28499,28585 ,17198,17114,14134 ,0,0,0}, + {28499,28498,28585 ,17114,17113,14134 ,0,0,0}, {28546,28547,28586 ,17163,17164,17198 ,0,0,0}, + {28499,28586,28547 ,17114,17198,17164 ,0,0,0}, {28546,28545,28548 ,17163,17162,17165 ,0,0,0}, + {28587,28549,28545 ,17199,17166,17162 ,0,0,0}, {28503,28547,28548 ,17118,17164,17165 ,0,0,0}, + {28549,28548,28545 ,17166,17165,17162 ,0,0,0}, {28588,28550,28587 ,17200,17167,17199 ,0,0,0}, + {28550,28549,28587 ,17167,17166,17199 ,0,0,0}, {28589,28551,28588 ,17201,17168,17200 ,0,0,0}, + {28551,28550,28588 ,17168,17167,17200 ,0,0,0}, {28590,28456,28589 ,17202,17077,17201 ,0,0,0}, + {28456,28551,28589 ,17077,17168,17201 ,0,0,0}, {28554,28454,28590 ,14116,17075,17202 ,0,0,0}, + {28454,28456,28590 ,17075,17077,17202 ,0,0,0}, {28554,26873,28552 ,14116,14183,14118 ,0,0,0}, + {28454,28554,28553 ,17075,14116,14234 ,0,0,0}, {28591,28555,28552 ,17203,17169,14118 ,0,0,0}, + {28555,28553,28552 ,17169,14234,14118 ,0,0,0}, {28592,28556,28591 ,17204,17170,17203 ,0,0,0}, + {28556,28555,28591 ,17170,17169,17203 ,0,0,0}, {28593,28557,28592 ,14185,17171,17204 ,0,0,0}, + {28557,28556,28592 ,17171,17170,17204 ,0,0,0}, {28594,28464,28593 ,17205,17085,14185 ,0,0,0}, + {28464,28557,28593 ,17085,17171,14185 ,0,0,0}, {28595,28462,28594 ,17206,17083,17205 ,0,0,0}, + {28462,28464,28594 ,17083,17085,17205 ,0,0,0}, {28558,28560,28595 ,17172,17174,17206 ,0,0,0}, + {28462,28595,28560 ,17083,17206,17174 ,0,0,0}, {28558,28559,28561 ,17172,14103,17175 ,0,0,0}, + {28596,28562,28559 ,17207,17176,14103 ,0,0,0}, {28514,28560,28561 ,17129,17174,17175 ,0,0,0}, + {28562,28561,28559 ,17176,17175,14103 ,0,0,0}, {28597,28563,28596 ,17208,17177,17207 ,0,0,0}, + {28563,28562,28596 ,17177,17176,17207 ,0,0,0}, {28598,28564,28597 ,17209,17178,17208 ,0,0,0}, + {28564,28563,28597 ,17178,17177,17208 ,0,0,0}, {28599,28517,28598 ,17210,17132,17209 ,0,0,0}, + {28517,28564,28598 ,17132,17178,17209 ,0,0,0}, {28567,28518,28599 ,17181,17133,17210 ,0,0,0}, + {28518,28517,28599 ,17133,17132,17210 ,0,0,0}, {28567,26895,28565 ,17181,14192,17179 ,0,0,0}, + {28518,28567,28566 ,17133,17181,17180 ,0,0,0}, {28600,28568,28565 ,14092,17182,17179 ,0,0,0}, + {28568,28566,28565 ,17182,17180,17179 ,0,0,0}, {28601,28569,28600 ,17211,14221,14092 ,0,0,0}, + {28569,28568,28600 ,14221,17182,14092 ,0,0,0}, {28602,28570,28601 ,17212,17183,17211 ,0,0,0}, + {28570,28569,28601 ,17183,14221,17211 ,0,0,0}, {28603,28571,28602 ,17213,17184,17212 ,0,0,0}, + {28571,28570,28602 ,17184,17183,17212 ,0,0,0}, {28604,28572,28603 ,17214,17185,17213 ,0,0,0}, + {28572,28571,28603 ,17185,17184,17213 ,0,0,0}, {28605,28573,28604 ,17215,17186,17214 ,0,0,0}, + {28573,28572,28604 ,17186,17185,17214 ,0,0,0}, {28606,28527,28605 ,17216,17142,17215 ,0,0,0}, + {28527,28573,28605 ,17142,17186,17215 ,0,0,0}, {28607,28528,28606 ,14053,17143,17216 ,0,0,0}, + {28528,28527,28606 ,17143,17142,17216 ,0,0,0}, {28608,28574,28607 ,17217,17187,14053 ,0,0,0}, + {28574,28528,28607 ,17187,17143,14053 ,0,0,0}, {28609,28306,28608 ,17218,16933,17217 ,0,0,0}, + {28306,28574,28608 ,16933,17187,17217 ,0,0,0}, {28609,28576,28305 ,17218,17189,16932 ,0,0,0}, + {28305,28306,28609 ,16932,16933,17218 ,0,0,0}, {28576,28575,28577 ,17189,17188,17190 ,0,0,0}, + {28309,28577,28307 ,16936,17190,16934 ,0,0,0}, {28532,28305,28577 ,17147,16932,17190 ,0,0,0}, + {28575,28307,28577 ,17188,16934,17190 ,0,0,0}, {28308,28307,28314 ,16935,16934,16941 ,0,0,0}, + {28535,28256,28245 ,17151,16867,16856 ,0,0,0}, {28245,28256,27922 ,16856,16867,17150 ,0,0,0}, + {26977,26973,28250 ,17022,17219,16861 ,0,0,0}, {28250,26973,28248 ,16861,17219,16859 ,0,0,0}, + {26973,26972,28248 ,17219,17220,16859 ,0,0,0}, {28248,26972,28538 ,16859,17220,17154 ,0,0,0}, + {26972,26971,28538 ,17220,14143,17154 ,0,0,0}, {28538,26971,28578 ,17154,14143,17191 ,0,0,0}, + {26971,26834,28578 ,14143,14144,17191 ,0,0,0}, {28578,26834,28579 ,17191,14144,17192 ,0,0,0}, + {26834,26824,28579 ,14144,17221,17192 ,0,0,0}, {28579,26824,28580 ,17192,17221,17193 ,0,0,0}, + {26824,26857,28580 ,17221,17222,17193 ,0,0,0}, {28580,26857,28581 ,17193,17222,17194 ,0,0,0}, + {26857,26854,28581 ,17222,17223,17194 ,0,0,0}, {28581,26854,28582 ,17194,17223,17195 ,0,0,0}, + {26854,26859,28582 ,17223,17224,17195 ,0,0,0}, {26859,26862,28583 ,17224,17225,17196 ,0,0,0}, + {26859,28583,28582 ,17224,17196,17195 ,0,0,0}, {26862,26829,28584 ,17225,14133,17197 ,0,0,0}, + {26862,28584,28583 ,17225,17197,17196 ,0,0,0}, {26829,26828,28585 ,14133,17226,14134 ,0,0,0}, + {26829,28585,28584 ,14133,14134,17197 ,0,0,0}, {26828,26864,28586 ,17226,17227,17198 ,0,0,0}, + {26828,28586,28585 ,17226,17198,14134 ,0,0,0}, {26864,26966,28546 ,17227,17228,17163 ,0,0,0}, + {26864,28546,28586 ,17227,17163,17198 ,0,0,0}, {26965,28546,26966 ,17161,17163,17228 ,0,0,0}, + {26965,26867,28545 ,17161,14180,17162 ,0,0,0}, {28545,26867,28587 ,17162,14180,17199 ,0,0,0}, + {26867,26872,28587 ,14180,14120,17199 ,0,0,0}, {28587,26872,28588 ,17199,14120,17200 ,0,0,0}, + {26872,26870,28588 ,14120,14121,17200 ,0,0,0}, {26870,26869,28589 ,14121,14122,17201 ,0,0,0}, + {26870,28589,28588 ,14121,17201,17200 ,0,0,0}, {26869,26964,28590 ,14122,14115,17202 ,0,0,0}, + {26869,28590,28589 ,14122,17202,17201 ,0,0,0}, {26964,26873,28554 ,14115,14183,14116 ,0,0,0}, + {26964,28554,28590 ,14115,14116,17202 ,0,0,0}, {26873,26963,28552 ,14183,17229,14118 ,0,0,0}, + {26963,26959,28552 ,17229,14110,14118 ,0,0,0}, {28552,26959,28591 ,14118,14110,17203 ,0,0,0}, + {26959,26877,28591 ,14110,17230,17203 ,0,0,0}, {28591,26877,28592 ,17203,17230,17204 ,0,0,0}, + {26877,26879,28592 ,17230,17231,17204 ,0,0,0}, {26879,26884,28593 ,17231,17232,14185 ,0,0,0}, + {26879,28593,28592 ,17231,14185,17204 ,0,0,0}, {26884,26882,28594 ,17232,14106,17205 ,0,0,0}, + {26884,28594,28593 ,17232,17205,14185 ,0,0,0}, {26882,26881,28595 ,14106,14186,17206 ,0,0,0}, + {26882,28595,28594 ,14106,17206,17205 ,0,0,0}, {26881,26957,28558 ,14186,17233,17172 ,0,0,0}, + {26881,28558,28595 ,14186,17172,17206 ,0,0,0}, {26956,28558,26957 ,17173,17172,17233 ,0,0,0}, + {26956,26886,28559 ,17173,17234,14103 ,0,0,0}, {28559,26886,28596 ,14103,17234,17207 ,0,0,0}, + {26886,26893,28596 ,17234,14098,17207 ,0,0,0}, {26893,26892,28597 ,14098,14099,17208 ,0,0,0}, + {26893,28597,28596 ,14098,17208,17207 ,0,0,0}, {26892,26891,28598 ,14099,17235,17209 ,0,0,0}, + {26892,28598,28597 ,14099,17209,17208 ,0,0,0}, {26891,26953,28599 ,17235,14096,17210 ,0,0,0}, + {26891,28599,28598 ,17235,17210,17209 ,0,0,0}, {26953,26895,28567 ,14096,14192,17181 ,0,0,0}, + {26953,28567,28599 ,14096,17181,17210 ,0,0,0}, {26895,26894,28565 ,14192,17236,17179 ,0,0,0}, + {26894,26900,28565 ,17236,17237,17179 ,0,0,0}, {28565,26900,28600 ,17179,17237,14092 ,0,0,0}, + {26900,26899,28600 ,17237,14056,14092 ,0,0,0}, {28600,26899,28601 ,14092,14056,17211 ,0,0,0}, + {26899,26904,28601 ,14056,14057,17211 ,0,0,0}, {28601,26904,28602 ,17211,14057,17212 ,0,0,0}, + {26904,26902,28602 ,14057,17238,17212 ,0,0,0}, {26902,26910,28603 ,17238,17239,17213 ,0,0,0}, + {26902,28603,28602 ,17238,17213,17212 ,0,0,0}, {26910,26906,28604 ,17239,17240,17214 ,0,0,0}, + {26910,28604,28603 ,17239,17214,17213 ,0,0,0}, {26906,26908,28605 ,17240,17241,17215 ,0,0,0}, + {26906,28605,28604 ,17240,17215,17214 ,0,0,0}, {26908,26911,28606 ,17241,14052,17216 ,0,0,0}, + {26908,28606,28605 ,17241,17216,17215 ,0,0,0}, {26911,26913,28607 ,14052,17242,14053 ,0,0,0}, + {26911,28607,28606 ,14052,14053,17216 ,0,0,0}, {26913,26918,28608 ,17242,17243,17217 ,0,0,0}, + {26913,28608,28607 ,17242,17217,14053 ,0,0,0}, {26918,26924,28609 ,17243,17244,17218 ,0,0,0}, + {26918,28609,28608 ,17243,17218,17217 ,0,0,0}, {26924,26925,28576 ,17244,17245,17189 ,0,0,0}, + {26924,28576,28609 ,17244,17189,17218 ,0,0,0}, {26925,26923,28575 ,17245,17246,17188 ,0,0,0}, + {26925,28575,28576 ,17245,17188,17189 ,0,0,0}, {26923,26917,28313 ,17246,17247,16940 ,0,0,0}, + {26923,28313,28575 ,17246,16940,17188 ,0,0,0}, {28313,26917,26916 ,16940,17247,15634 ,0,0,0}, + {28146,27852,27873 ,17248,17248,17248 ,0,0,0}, {27482,27869,27478 ,17248,17248,17248 ,0,0,0}, + {27868,27873,27934 ,17248,17248,17248 ,0,0,0}, {28146,27873,27853 ,17248,17248,17248 ,0,0,0}, + {27868,27934,28011 ,17248,17248,17248 ,0,0,0}, {27853,27868,27483 ,17248,17248,17248 ,0,0,0}, + {27873,27868,27853 ,17248,17248,17248 ,0,0,0}, {27343,27478,27869 ,17248,17248,17248 ,0,0,0}, + {27482,27866,27863 ,17248,17248,17248 ,0,0,0}, {27349,27358,27693 ,17248,17248,17248 ,0,0,0}, + {27484,27343,27869 ,17248,17248,17248 ,0,0,0}, {27485,27484,27349 ,17248,17248,17248 ,0,0,0}, + {27484,27485,27474 ,17248,17248,17248 ,0,0,0}, {27356,27349,27693 ,17248,17248,17248 ,0,0,0}, + {27357,27358,27484 ,17248,17248,17248 ,0,0,0}, {27358,27349,27484 ,17248,17248,17248 ,0,0,0}, + {27871,27484,27869 ,17248,17248,17248 ,0,0,0}, {27871,27357,27484 ,17248,17248,17248 ,0,0,0}, + {27869,27482,27863 ,17248,17248,17248 ,0,0,0}, {27866,27482,27868 ,17248,17248,17248 ,0,0,0}, + {27483,27868,27481 ,17248,17248,17248 ,0,0,0}, {27482,27481,27868 ,17248,17248,17248 ,0,0,0}, + {28533,28308,28314 ,17249,17249,17249 ,0,0,0}, {28362,28399,27112 ,17249,17249,17249 ,0,0,0}, + {28318,28534,28314 ,17249,17249,17249 ,0,0,0}, {28438,28488,27028 ,17249,17249,17249 ,0,0,0}, + {28487,28534,28488 ,17249,17249,17249 ,0,0,0}, {28534,28318,26916 ,17249,17249,17249 ,0,0,0}, + {28533,28314,28534 ,17249,17249,17249 ,0,0,0}, {27028,28488,28534 ,17249,17249,17249 ,0,0,0}, + {28534,26916,27028 ,17249,17249,17249 ,0,0,0}, {27027,28438,27028 ,17249,17249,17249 ,0,0,0}, + {27027,27070,28438 ,17249,17249,17249 ,0,0,0}, {28399,28438,27112 ,17249,17249,17249 ,0,0,0}, + {27070,27112,28438 ,17249,17249,17249 ,0,0,0}, {28363,28362,27112 ,17249,17249,17249 ,0,0,0}, + {27156,27198,27157 ,17249,17249,17249 ,0,0,0}, {27157,28363,27112 ,17249,17249,17249 ,0,0,0}, + {28363,27157,27198 ,17249,17249,17249 ,0,0,0}, {26949,27197,26944 ,17249,17249,17249 ,0,0,0}, + {28363,27198,26950 ,17249,17249,17249 ,0,0,0}, {27198,26949,26948 ,17249,17249,17249 ,0,0,0}, + {26949,27198,27197 ,17249,17249,17249 ,0,0,0}, {27198,26948,26950 ,17249,17249,17249 ,0,0,0} +// Landegestell.prt + , {28610,28611,28612 ,11524,11525,11526 ,0,0,0}, {28613,28614,28615 ,11527,11528,11529 ,0,0,0}, + {28616,28617,28618 ,11530,11531,11532 ,0,0,0}, {28619,28611,28620 ,11533,11525,11534 ,0,0,0}, + {28621,28618,28622 ,11535,11532,11536 ,0,0,0}, {28623,28624,28625 ,11537,11538,11539 ,0,0,0}, + {28626,28627,28628 ,11540,11541,11542 ,0,0,0}, {28629,28622,28617 ,11543,11536,11531 ,0,0,0}, + {28630,28631,28632 ,11544,11545,11546 ,0,0,0}, {28626,28633,28632 ,11540,11547,11546 ,0,0,0}, + {28634,28635,28636 ,11548,11549,11550 ,0,0,0}, {28636,28635,28631 ,11550,11549,11545 ,0,0,0}, + {28637,28636,28638 ,11551,11550,11552 ,0,0,0}, {28620,28611,28610 ,11534,11525,11524 ,0,0,0}, + {28638,28639,28637 ,11552,11553,11551 ,0,0,0}, {28640,28641,28642 ,11554,11555,11556 ,0,0,0}, + {28612,28643,28610 ,11526,11557,11524 ,0,0,0}, {28644,28645,28642 ,11558,11559,11556 ,0,0,0}, + {28646,28647,28644 ,11560,11561,11558 ,0,0,0}, {28647,28648,28644 ,11561,11562,11558 ,0,0,0}, + {28642,28645,28640 ,11556,11559,11554 ,0,0,0}, {28649,28650,28614 ,11563,11564,11528 ,0,0,0}, + {28651,28652,28653 ,11565,11566,11567 ,0,0,0}, {28649,28654,28650 ,11563,11568,11564 ,0,0,0}, + {28655,28656,28657 ,11569,11570,11571 ,0,0,0}, {28652,28658,28653 ,11566,11572,11567 ,0,0,0}, + {28659,28660,28661 ,11573,11574,11575 ,0,0,0}, {28655,28657,28662 ,11569,11571,11576 ,0,0,0}, + {28663,28664,28665 ,11577,11578,11579 ,0,0,0}, {28664,28663,28666 ,11578,11577,11580 ,0,0,0}, + {28667,28668,28669 ,11581,11582,11583 ,0,0,0}, {28670,28671,28668 ,11584,11585,11582 ,0,0,0}, + {28672,28673,28674 ,11586,11587,11588 ,0,0,0}, {28667,28669,28675 ,11581,11583,11589 ,0,0,0}, + {28676,28677,28678 ,11590,11591,11592 ,0,0,0}, {28672,28674,28679 ,11586,11588,11593 ,0,0,0}, + {28680,28681,28682 ,11594,11595,11596 ,0,0,0}, {28683,28677,28676 ,11597,11591,11590 ,0,0,0}, + {28684,28685,28686 ,11598,11599,11600 ,0,0,0}, {28686,28682,28684 ,11600,11596,11598 ,0,0,0}, + {28687,28688,28689 ,11601,11602,11603 ,0,0,0}, {28690,28685,28691 ,11604,11599,11605 ,0,0,0}, + {28692,28693,28694 ,11606,11607,11608 ,0,0,0}, {28695,28692,28696 ,11609,11606,11610 ,0,0,0}, + {28697,28698,28699 ,11611,11612,11613 ,0,0,0}, {28700,28697,28694 ,11614,11611,11608 ,0,0,0}, + {28701,28702,28703 ,11615,11616,11617 ,0,0,0}, {28704,28699,28705 ,11618,11613,11619 ,0,0,0}, + {28706,28707,28708 ,11620,11621,11622 ,0,0,0}, {28703,28709,28701 ,11617,11623,11615 ,0,0,0}, + {28710,28706,28711 ,11624,11620,11625 ,0,0,0}, {28701,28709,28712 ,11615,11623,11626 ,0,0,0}, + {28713,28710,28704 ,11627,11624,11618 ,0,0,0}, {28706,28710,28713 ,11620,11624,11627 ,0,0,0}, + {28714,28715,28716 ,11628,11629,11630 ,0,0,0}, {28717,28700,28718 ,11631,11614,11632 ,0,0,0}, + {28719,28720,28721 ,11633,11634,11635 ,0,0,0}, {28717,28718,28722 ,11631,11632,11636 ,0,0,0}, + {28723,28724,28725 ,11637,11638,11639 ,0,0,0}, {28721,28726,28727 ,11635,11640,11641 ,0,0,0}, + {28728,28729,28725 ,11642,11643,11639 ,0,0,0}, {28730,28731,28732 ,11644,11645,11646 ,0,0,0}, + {28733,28734,28735 ,11647,11648,11649 ,0,0,0}, {28735,28732,28733 ,11649,11646,11647 ,0,0,0}, + {28734,28733,28736 ,11648,11647,11650 ,0,0,0}, {28705,28699,28698 ,11619,11613,11612 ,0,0,0}, + {28706,28712,28711 ,11620,11626,11625 ,0,0,0}, {28700,28694,28693 ,11614,11608,11607 ,0,0,0}, + {28700,28698,28697 ,11614,11612,11611 ,0,0,0}, {28695,28696,28687 ,11609,11610,11601 ,0,0,0}, + {28692,28695,28693 ,11606,11609,11607 ,0,0,0}, {28689,28688,28690 ,11603,11602,11604 ,0,0,0}, + {28696,28688,28687 ,11610,11602,11601 ,0,0,0}, {28689,28690,28691 ,11603,11604,11605 ,0,0,0}, + {28737,28695,28687 ,11651,11609,11601 ,0,0,0}, {28686,28680,28682 ,11600,11594,11596 ,0,0,0}, + {28685,28684,28691 ,11599,11598,11605 ,0,0,0}, {28676,28678,28738 ,11590,11592,11652 ,0,0,0}, + {28739,28683,28740 ,11653,11597,11654 ,0,0,0}, {28682,28681,28740 ,11596,11595,11654 ,0,0,0}, + {28677,28683,28739 ,11591,11597,11653 ,0,0,0}, {28681,28739,28740 ,11595,11653,11654 ,0,0,0}, + {28738,28678,28679 ,11652,11592,11593 ,0,0,0}, {28741,28676,28738 ,11655,11590,11652 ,0,0,0}, + {28679,28674,28738 ,11593,11588,11652 ,0,0,0}, {28675,28673,28742 ,11589,11587,11656 ,0,0,0}, + {28672,28742,28673 ,11586,11656,11587 ,0,0,0}, {28743,28675,28742 ,11657,11589,11656 ,0,0,0}, + {28671,28669,28668 ,11585,11583,11582 ,0,0,0}, {28667,28675,28743 ,11581,11589,11657 ,0,0,0}, + {28670,28744,28671 ,11584,11658,11585 ,0,0,0}, {28665,28664,28744 ,11579,11578,11658 ,0,0,0}, + {28744,28670,28665 ,11658,11584,11579 ,0,0,0}, {28666,28745,28661 ,11580,11659,11575 ,0,0,0}, + {28746,28747,28748 ,11660,11661,11662 ,0,0,0}, {28661,28745,28749 ,11575,11659,11663 ,0,0,0}, + {28745,28666,28663 ,11659,11580,11577 ,0,0,0}, {28750,28662,28660 ,11664,11576,11574 ,0,0,0}, + {28659,28661,28749 ,11573,11575,11663 ,0,0,0}, {28662,28750,28655 ,11576,11664,11569 ,0,0,0}, + {28750,28660,28659 ,11664,11574,11573 ,0,0,0}, {28654,28751,28752 ,11568,11665,11666 ,0,0,0}, + {28656,28658,28753 ,11570,11572,11667 ,0,0,0}, {28657,28656,28753 ,11571,11570,11667 ,0,0,0}, + {28753,28658,28652 ,11667,11572,11566 ,0,0,0}, {28754,28755,28756 ,11668,11669,11670 ,0,0,0}, + {28751,28651,28653 ,11665,11565,11567 ,0,0,0}, {28643,28612,28641 ,11557,11526,11555 ,0,0,0}, + {28654,28651,28751 ,11568,11565,11665 ,0,0,0}, {28654,28752,28650 ,11568,11666,11564 ,0,0,0}, + {28614,28613,28649 ,11528,11527,11563 ,0,0,0}, {28648,28647,28615 ,11562,11561,11529 ,0,0,0}, + {28615,28647,28613 ,11529,11561,11527 ,0,0,0}, {28640,28643,28641 ,11554,11557,11555 ,0,0,0}, + {28648,28645,28644 ,11562,11559,11558 ,0,0,0}, {28625,28757,28758 ,11539,11671,11672 ,0,0,0}, + {28619,28620,28757 ,11533,11534,11671 ,0,0,0}, {28758,28623,28625 ,11672,11537,11539 ,0,0,0}, + {28619,28757,28625 ,11533,11671,11539 ,0,0,0}, {28758,28759,28623 ,11672,11673,11537 ,0,0,0}, + {28760,28761,28627 ,11674,11675,11541 ,0,0,0}, {28623,28759,28762 ,11537,11673,11676 ,0,0,0}, + {28762,28759,28763 ,11676,11673,11677 ,0,0,0}, {28764,28762,28765 ,11678,11676,11679 ,0,0,0}, + {28763,28765,28762 ,11677,11679,11676 ,0,0,0}, {28628,28766,28626 ,11542,11680,11540 ,0,0,0}, + {28767,28764,28765 ,11681,11678,11679 ,0,0,0}, {28768,28767,28765 ,11682,11681,11679 ,0,0,0}, + {28764,28767,28769 ,11678,11681,11683 ,0,0,0}, {28770,28771,28769 ,11684,11685,11683 ,0,0,0}, + {28761,28760,28772 ,11675,11674,11686 ,0,0,0}, {28769,28771,28764 ,11683,11685,11678 ,0,0,0}, + {28770,28760,28771 ,11684,11674,11685 ,0,0,0}, {28764,28773,28762 ,11678,11687,11676 ,0,0,0}, + {28774,28619,28625 ,11688,11533,11539 ,0,0,0}, {28762,28616,28623 ,11676,11530,11537 ,0,0,0}, + {28775,28611,28619 ,11689,11525,11533 ,0,0,0}, {28624,28623,28616 ,11538,11537,11530 ,0,0,0}, + {28776,28612,28611 ,11690,11526,11525 ,0,0,0}, {28774,28625,28624 ,11688,11539,11538 ,0,0,0}, + {28777,28641,28612 ,11691,11555,11526 ,0,0,0}, {28775,28619,28774 ,11689,11533,11688 ,0,0,0}, + {28778,28642,28641 ,11692,11556,11555 ,0,0,0}, {28776,28611,28775 ,11690,11525,11689 ,0,0,0}, + {28779,28644,28642 ,11693,11558,11556 ,0,0,0}, {28612,28776,28777 ,11526,11690,11691 ,0,0,0}, + {28780,28781,28782 ,11694,11695,11696 ,0,0,0}, {28641,28777,28778 ,11555,11691,11692 ,0,0,0}, + {28782,28613,28647 ,11696,11527,11561 ,0,0,0}, {28642,28778,28779 ,11556,11692,11693 ,0,0,0}, + {28783,28649,28613 ,11697,11563,11527 ,0,0,0}, {28644,28779,28646 ,11558,11693,11560 ,0,0,0}, + {28784,28654,28649 ,11698,11568,11563 ,0,0,0}, {28647,28646,28782 ,11561,11560,11696 ,0,0,0}, + {28785,28651,28654 ,11699,11565,11568 ,0,0,0}, {28613,28782,28783 ,11527,11696,11697 ,0,0,0}, + {28786,28652,28651 ,11700,11566,11565 ,0,0,0}, {28784,28649,28783 ,11698,11563,11697 ,0,0,0}, + {28787,28753,28652 ,11701,11667,11566 ,0,0,0}, {28785,28654,28784 ,11699,11568,11698 ,0,0,0}, + {28788,28657,28753 ,11702,11571,11667 ,0,0,0}, {28651,28785,28786 ,11565,11699,11700 ,0,0,0}, + {28755,28662,28657 ,11669,11576,11571 ,0,0,0}, {28652,28786,28787 ,11566,11700,11701 ,0,0,0}, + {28789,28660,28662 ,11703,11574,11576 ,0,0,0}, {28753,28787,28788 ,11667,11701,11702 ,0,0,0}, + {28790,28661,28660 ,11704,11575,11574 ,0,0,0}, {28657,28788,28755 ,11571,11702,11669 ,0,0,0}, + {28791,28666,28661 ,11705,11580,11575 ,0,0,0}, {28789,28662,28755 ,11703,11576,11669 ,0,0,0}, + {28792,28664,28666 ,11706,11578,11580 ,0,0,0}, {28790,28660,28789 ,11704,11574,11703 ,0,0,0}, + {28793,28744,28664 ,11707,11658,11578 ,0,0,0}, {28661,28790,28791 ,11575,11704,11705 ,0,0,0}, + {28671,28744,28746 ,11585,11658,11660 ,0,0,0}, {28666,28791,28792 ,11580,11705,11706 ,0,0,0}, + {28794,28669,28671 ,11708,11583,11585 ,0,0,0}, {28664,28792,28793 ,11578,11706,11707 ,0,0,0}, + {28795,28675,28669 ,11709,11589,11583 ,0,0,0}, {28744,28793,28746 ,11658,11707,11660 ,0,0,0}, + {28796,28673,28675 ,11710,11587,11589 ,0,0,0}, {28794,28671,28746 ,11708,11585,11660 ,0,0,0}, + {28797,28674,28673 ,11711,11588,11587 ,0,0,0}, {28795,28669,28794 ,11709,11583,11708 ,0,0,0}, + {28798,28738,28674 ,11712,11652,11588 ,0,0,0}, {28675,28795,28796 ,11589,11709,11710 ,0,0,0}, + {28799,28800,28801 ,11713,11714,11715 ,0,0,0}, {28673,28796,28797 ,11587,11710,11711 ,0,0,0}, + {28802,28683,28676 ,11716,11597,11590 ,0,0,0}, {28674,28797,28798 ,11588,11711,11712 ,0,0,0}, + {28803,28740,28683 ,11717,11654,11597 ,0,0,0}, {28738,28798,28741 ,11652,11712,11655 ,0,0,0}, + {28804,28682,28740 ,11718,11596,11654 ,0,0,0}, {28676,28741,28802 ,11590,11655,11716 ,0,0,0}, + {28805,28684,28682 ,11719,11598,11596 ,0,0,0}, {28803,28683,28802 ,11717,11597,11716 ,0,0,0}, + {28806,28691,28684 ,11720,11605,11598 ,0,0,0}, {28804,28740,28803 ,11718,11654,11717 ,0,0,0}, + {28807,28689,28691 ,11721,11603,11605 ,0,0,0}, {28805,28682,28804 ,11719,11596,11718 ,0,0,0}, + {28808,28687,28689 ,11722,11601,11603 ,0,0,0}, {28684,28805,28806 ,11598,11719,11720 ,0,0,0}, + {28695,28809,28693 ,11609,11723,11607 ,0,0,0}, {28691,28806,28807 ,11605,11720,11721 ,0,0,0}, + {28718,28810,28722 ,11632,11724,11636 ,0,0,0}, {28689,28807,28808 ,11603,11721,11722 ,0,0,0}, + {28718,28700,28693 ,11632,11614,11607 ,0,0,0}, {28687,28808,28737 ,11601,11722,11651 ,0,0,0}, + {28717,28698,28700 ,11631,11612,11614 ,0,0,0}, {28695,28737,28809 ,11609,11651,11723 ,0,0,0}, + {28705,28698,28811 ,11619,11612,11725 ,0,0,0}, {28809,28718,28693 ,11723,11632,11607 ,0,0,0}, + {28720,28707,28713 ,11634,11621,11627 ,0,0,0}, {28707,28720,28719 ,11621,11634,11633 ,0,0,0}, + {28705,28713,28704 ,11619,11627,11618 ,0,0,0}, {28698,28717,28811 ,11612,11631,11725 ,0,0,0}, + {28701,28712,28812 ,11615,11626,11726 ,0,0,0}, {28705,28720,28713 ,11619,11634,11627 ,0,0,0}, + {28706,28713,28707 ,11620,11627,11621 ,0,0,0}, {28813,28814,28701 ,11727,11728,11615 ,0,0,0}, + {28711,28712,28709 ,11625,11626,11623 ,0,0,0}, {28708,28812,28712 ,11622,11726,11626 ,0,0,0}, + {28702,28701,28814 ,11616,11615,11728 ,0,0,0}, {28771,28773,28764 ,11685,11687,11678 ,0,0,0}, + {28772,28760,28770 ,11686,11674,11684 ,0,0,0}, {28633,28815,28632 ,11547,11729,11546 ,0,0,0}, + {28773,28616,28762 ,11687,11530,11676 ,0,0,0}, {28771,28816,28773 ,11685,11730,11687 ,0,0,0}, + {28624,28618,28817 ,11538,11532,11731 ,0,0,0}, {28617,28616,28773 ,11531,11530,11687 ,0,0,0}, + {28774,28817,28818 ,11688,11731,11732 ,0,0,0}, {28618,28624,28616 ,11532,11538,11530 ,0,0,0}, + {28775,28818,28819 ,11689,11732,11733 ,0,0,0}, {28817,28774,28624 ,11731,11688,11538 ,0,0,0}, + {28776,28819,28820 ,11690,11733,11734 ,0,0,0}, {28818,28775,28774 ,11732,11689,11688 ,0,0,0}, + {28777,28820,28821 ,11691,11734,11735 ,0,0,0}, {28819,28776,28775 ,11733,11690,11689 ,0,0,0}, + {28778,28821,28822 ,11692,11735,11736 ,0,0,0}, {28820,28777,28776 ,11734,11691,11690 ,0,0,0}, + {28779,28822,28823 ,11693,11736,11737 ,0,0,0}, {28821,28778,28777 ,11735,11692,11691 ,0,0,0}, + {28646,28823,28780 ,11560,11737,11694 ,0,0,0}, {28779,28778,28822 ,11693,11692,11736 ,0,0,0}, + {28824,28825,28826 ,11738,11739,11740 ,0,0,0}, {28646,28779,28823 ,11560,11693,11737 ,0,0,0}, + {28783,28781,28824 ,11697,11695,11738 ,0,0,0}, {28782,28646,28780 ,11696,11560,11694 ,0,0,0}, + {28784,28824,28827 ,11698,11738,11741 ,0,0,0}, {28783,28782,28781 ,11697,11696,11695 ,0,0,0}, + {28785,28827,28828 ,11699,11741,11742 ,0,0,0}, {28824,28784,28783 ,11738,11698,11697 ,0,0,0}, + {28786,28828,28829 ,11700,11742,11743 ,0,0,0}, {28827,28785,28784 ,11741,11699,11698 ,0,0,0}, + {28787,28829,28830 ,11701,11743,11744 ,0,0,0}, {28828,28786,28785 ,11742,11700,11699 ,0,0,0}, + {28788,28830,28756 ,11702,11744,11670 ,0,0,0}, {28787,28786,28829 ,11701,11700,11743 ,0,0,0}, + {28831,28832,28833 ,11745,11746,11747 ,0,0,0}, {28788,28787,28830 ,11702,11701,11744 ,0,0,0}, + {28789,28754,28834 ,11703,11668,11748 ,0,0,0}, {28755,28788,28756 ,11669,11702,11670 ,0,0,0}, + {28790,28834,28835 ,11704,11748,11749 ,0,0,0}, {28754,28789,28755 ,11668,11703,11669 ,0,0,0}, + {28791,28835,28836 ,11705,11749,11750 ,0,0,0}, {28834,28790,28789 ,11748,11704,11703 ,0,0,0}, + {28792,28836,28837 ,11706,11750,11751 ,0,0,0}, {28835,28791,28790 ,11749,11705,11704 ,0,0,0}, + {28793,28837,28747 ,11707,11751,11661 ,0,0,0}, {28792,28791,28836 ,11706,11705,11750 ,0,0,0}, + {28838,28839,28840 ,11752,11753,11754 ,0,0,0}, {28793,28792,28837 ,11707,11706,11751 ,0,0,0}, + {28794,28748,28841 ,11708,11662,11755 ,0,0,0}, {28746,28793,28747 ,11660,11707,11661 ,0,0,0}, + {28795,28841,28842 ,11709,11755,11756 ,0,0,0}, {28794,28746,28748 ,11708,11660,11662 ,0,0,0}, + {28796,28842,28843 ,11710,11756,11757 ,0,0,0}, {28841,28795,28794 ,11755,11709,11708 ,0,0,0}, + {28797,28843,28844 ,11711,11757,11758 ,0,0,0}, {28842,28796,28795 ,11756,11710,11709 ,0,0,0}, + {28798,28844,28845 ,11712,11758,11759 ,0,0,0}, {28843,28797,28796 ,11757,11711,11710 ,0,0,0}, + {28741,28845,28846 ,11655,11759,11760 ,0,0,0}, {28798,28797,28844 ,11712,11711,11758 ,0,0,0}, + {28802,28846,28800 ,11716,11760,11714 ,0,0,0}, {28741,28798,28845 ,11655,11712,11759 ,0,0,0}, + {28803,28800,28847 ,11717,11714,11761 ,0,0,0}, {28802,28741,28846 ,11716,11655,11760 ,0,0,0}, + {28804,28847,28848 ,11718,11761,11762 ,0,0,0}, {28800,28803,28802 ,11714,11717,11716 ,0,0,0}, + {28805,28848,28849 ,11719,11762,11763 ,0,0,0}, {28847,28804,28803 ,11761,11718,11717 ,0,0,0}, + {28806,28849,28850 ,11720,11763,11764 ,0,0,0}, {28848,28805,28804 ,11762,11719,11718 ,0,0,0}, + {28807,28850,28851 ,11721,11764,11765 ,0,0,0}, {28849,28806,28805 ,11763,11720,11719 ,0,0,0}, + {28808,28851,28852 ,11722,11765,11766 ,0,0,0}, {28850,28807,28806 ,11764,11721,11720 ,0,0,0}, + {28737,28852,28853 ,11651,11766,11767 ,0,0,0}, {28851,28808,28807 ,11765,11722,11721 ,0,0,0}, + {28809,28853,28810 ,11723,11767,11724 ,0,0,0}, {28737,28808,28852 ,11651,11722,11766 ,0,0,0}, + {28854,28717,28722 ,11768,11631,11636 ,0,0,0}, {28809,28737,28853 ,11723,11651,11767 ,0,0,0}, + {28727,28723,28855 ,11641,11637,11769 ,0,0,0}, {28718,28809,28810 ,11632,11723,11724 ,0,0,0}, + {28854,28721,28811 ,11768,11635,11725 ,0,0,0}, {28714,28707,28719 ,11628,11621,11633 ,0,0,0}, + {28811,28720,28705 ,11725,11634,11619 ,0,0,0}, {28854,28811,28717 ,11768,11725,11631 ,0,0,0}, + {28727,28719,28721 ,11641,11633,11635 ,0,0,0}, {28811,28721,28720 ,11725,11635,11634 ,0,0,0}, + {28856,28812,28716 ,11770,11726,11630 ,0,0,0}, {28812,28813,28701 ,11726,11727,11615 ,0,0,0}, + {28706,28708,28712 ,11620,11622,11626 ,0,0,0}, {28708,28714,28716 ,11622,11628,11630 ,0,0,0}, + {28856,28813,28812 ,11770,11727,11726 ,0,0,0}, {28760,28816,28771 ,11674,11730,11685 ,0,0,0}, + {28628,28627,28761 ,11542,11541,11675 ,0,0,0}, {28631,28635,28857 ,11545,11549,11771 ,0,0,0}, + {28816,28617,28773 ,11730,11531,11687 ,0,0,0}, {28760,28858,28816 ,11674,11772,11730 ,0,0,0}, + {28859,28860,28861 ,11773,11774,11775 ,0,0,0}, {28629,28617,28816 ,11543,11531,11730 ,0,0,0}, + {28621,28859,28817 ,11535,11773,11731 ,0,0,0}, {28622,28618,28617 ,11536,11532,11531 ,0,0,0}, + {28859,28862,28818 ,11773,11776,11732 ,0,0,0}, {28621,28817,28618 ,11535,11731,11532 ,0,0,0}, + {28862,28863,28819 ,11776,11777,11733 ,0,0,0}, {28859,28818,28817 ,11773,11732,11731 ,0,0,0}, + {28863,28864,28820 ,11777,11778,11734 ,0,0,0}, {28862,28819,28818 ,11776,11733,11732 ,0,0,0}, + {28864,28865,28821 ,11778,11779,11735 ,0,0,0}, {28863,28820,28819 ,11777,11734,11733 ,0,0,0}, + {28865,28866,28822 ,11779,11780,11736 ,0,0,0}, {28864,28821,28820 ,11778,11735,11734 ,0,0,0}, + {28866,28867,28823 ,11780,11781,11737 ,0,0,0}, {28865,28822,28821 ,11779,11736,11735 ,0,0,0}, + {28867,28868,28780 ,11781,11782,11694 ,0,0,0}, {28866,28823,28822 ,11780,11737,11736 ,0,0,0}, + {28868,28825,28781 ,11782,11739,11695 ,0,0,0}, {28780,28823,28867 ,11694,11737,11781 ,0,0,0}, + {28869,28870,28871 ,11783,11784,11785 ,0,0,0}, {28781,28780,28868 ,11695,11694,11782 ,0,0,0}, + {28826,28869,28827 ,11740,11783,11741 ,0,0,0}, {28825,28824,28781 ,11739,11738,11695 ,0,0,0}, + {28869,28872,28828 ,11783,11786,11742 ,0,0,0}, {28826,28827,28824 ,11740,11741,11738 ,0,0,0}, + {28872,28873,28829 ,11786,11787,11743 ,0,0,0}, {28869,28828,28827 ,11783,11742,11741 ,0,0,0}, + {28873,28874,28830 ,11787,11788,11744 ,0,0,0}, {28872,28829,28828 ,11786,11743,11742 ,0,0,0}, + {28874,28875,28756 ,11788,11789,11670 ,0,0,0}, {28873,28830,28829 ,11787,11744,11743 ,0,0,0}, + {28754,28875,28876 ,11668,11789,11790 ,0,0,0}, {28756,28830,28874 ,11670,11744,11788 ,0,0,0}, + {28876,28831,28834 ,11790,11745,11748 ,0,0,0}, {28875,28754,28756 ,11789,11668,11670 ,0,0,0}, + {28831,28877,28835 ,11745,11791,11749 ,0,0,0}, {28876,28834,28754 ,11790,11748,11668 ,0,0,0}, + {28877,28878,28836 ,11791,11792,11750 ,0,0,0}, {28831,28835,28834 ,11745,11749,11748 ,0,0,0}, + {28878,28879,28837 ,11792,11793,11751 ,0,0,0}, {28877,28836,28835 ,11791,11750,11749 ,0,0,0}, + {28879,28880,28747 ,11793,11794,11661 ,0,0,0}, {28878,28837,28836 ,11792,11751,11750 ,0,0,0}, + {28880,28881,28748 ,11794,11795,11662 ,0,0,0}, {28747,28837,28879 ,11661,11751,11793 ,0,0,0}, + {28881,28838,28841 ,11795,11752,11755 ,0,0,0}, {28748,28747,28880 ,11662,11661,11794 ,0,0,0}, + {28838,28882,28842 ,11752,11796,11756 ,0,0,0}, {28881,28841,28748 ,11795,11755,11662 ,0,0,0}, + {28882,28883,28843 ,11796,11797,11757 ,0,0,0}, {28838,28842,28841 ,11752,11756,11755 ,0,0,0}, + {28883,28884,28844 ,11797,11798,11758 ,0,0,0}, {28882,28843,28842 ,11796,11757,11756 ,0,0,0}, + {28884,28885,28845 ,11798,11799,11759 ,0,0,0}, {28883,28844,28843 ,11797,11758,11757 ,0,0,0}, + {28885,28801,28846 ,11799,11715,11760 ,0,0,0}, {28845,28844,28884 ,11759,11758,11798 ,0,0,0}, + {28886,28887,28888 ,11800,11801,11802 ,0,0,0}, {28846,28845,28885 ,11760,11759,11799 ,0,0,0}, + {28799,28886,28847 ,11713,11800,11761 ,0,0,0}, {28801,28800,28846 ,11715,11714,11760 ,0,0,0}, + {28886,28889,28848 ,11800,11803,11762 ,0,0,0}, {28799,28847,28800 ,11713,11761,11714 ,0,0,0}, + {28889,28890,28849 ,11803,11804,11763 ,0,0,0}, {28886,28848,28847 ,11800,11762,11761 ,0,0,0}, + {28890,28891,28850 ,11804,11805,11764 ,0,0,0}, {28889,28849,28848 ,11803,11763,11762 ,0,0,0}, + {28891,28892,28851 ,11805,11806,11765 ,0,0,0}, {28890,28850,28849 ,11804,11764,11763 ,0,0,0}, + {28892,28893,28852 ,11806,11807,11766 ,0,0,0}, {28891,28851,28850 ,11805,11765,11764 ,0,0,0}, + {28893,28894,28853 ,11807,11808,11767 ,0,0,0}, {28892,28852,28851 ,11806,11766,11765 ,0,0,0}, + {28894,28895,28810 ,11808,11809,11724 ,0,0,0}, {28893,28853,28852 ,11807,11767,11766 ,0,0,0}, + {28895,28896,28722 ,11809,11810,11636 ,0,0,0}, {28894,28810,28853 ,11808,11724,11767 ,0,0,0}, + {28896,28726,28854 ,11810,11640,11768 ,0,0,0}, {28722,28810,28895 ,11636,11724,11809 ,0,0,0}, + {28897,28719,28727 ,11811,11633,11641 ,0,0,0}, {28722,28896,28854 ,11636,11810,11768 ,0,0,0}, + {28726,28723,28727 ,11640,11637,11641 ,0,0,0}, {28854,28726,28721 ,11768,11640,11635 ,0,0,0}, + {28898,28716,28715 ,11812,11630,11629 ,0,0,0}, {28708,28716,28812 ,11622,11630,11726 ,0,0,0}, + {28707,28714,28708 ,11621,11628,11622 ,0,0,0}, {28897,28715,28714 ,11811,11629,11628 ,0,0,0}, + {28856,28716,28898 ,11770,11630,11812 ,0,0,0}, {28858,28760,28627 ,11772,11674,11541 ,0,0,0}, + {28633,28626,28766 ,11547,11540,11680 ,0,0,0}, {28629,28899,28900 ,11543,11813,11814 ,0,0,0}, + {28858,28629,28816 ,11772,11543,11730 ,0,0,0}, {28901,28858,28627 ,11815,11772,11541 ,0,0,0}, + {28622,28900,28902 ,11536,11814,11816 ,0,0,0}, {28858,28899,28629 ,11772,11813,11543 ,0,0,0}, + {28621,28902,28860 ,11535,11816,11774 ,0,0,0}, {28900,28622,28629 ,11814,11536,11543 ,0,0,0}, + {28903,28862,28861 ,11817,11776,11775 ,0,0,0}, {28902,28621,28622 ,11816,11535,11536 ,0,0,0}, + {28904,28863,28903 ,11818,11777,11817 ,0,0,0}, {28860,28859,28621 ,11774,11773,11535 ,0,0,0}, + {28905,28906,28907 ,11819,11820,11821 ,0,0,0}, {28861,28862,28859 ,11775,11776,11773 ,0,0,0}, + {28904,28905,28864 ,11818,11819,11778 ,0,0,0}, {28903,28863,28862 ,11817,11777,11776 ,0,0,0}, + {28905,28908,28865 ,11819,11822,11779 ,0,0,0}, {28904,28864,28863 ,11818,11778,11777 ,0,0,0}, + {28908,28909,28866 ,11822,11823,11780 ,0,0,0}, {28905,28865,28864 ,11819,11779,11778 ,0,0,0}, + {28909,28910,28867 ,11823,11824,11781 ,0,0,0}, {28908,28866,28865 ,11822,11780,11779 ,0,0,0}, + {28910,28911,28868 ,11824,11825,11782 ,0,0,0}, {28909,28867,28866 ,11823,11781,11780 ,0,0,0}, + {28825,28911,28912 ,11739,11825,11826 ,0,0,0}, {28910,28868,28867 ,11824,11782,11781 ,0,0,0}, + {28826,28912,28870 ,11740,11826,11784 ,0,0,0}, {28911,28825,28868 ,11825,11739,11782 ,0,0,0}, + {28913,28914,28915 ,11827,11828,11829 ,0,0,0}, {28912,28826,28825 ,11826,11740,11739 ,0,0,0}, + {28871,28913,28872 ,11785,11827,11786 ,0,0,0}, {28870,28869,28826 ,11784,11783,11740 ,0,0,0}, + {28913,28916,28873 ,11827,11830,11787 ,0,0,0}, {28871,28872,28869 ,11785,11786,11783 ,0,0,0}, + {28916,28917,28874 ,11830,11831,11788 ,0,0,0}, {28913,28873,28872 ,11827,11787,11786 ,0,0,0}, + {28875,28917,28918 ,11789,11831,11832 ,0,0,0}, {28916,28874,28873 ,11830,11788,11787 ,0,0,0}, + {28876,28918,28832 ,11790,11832,11746 ,0,0,0}, {28875,28874,28917 ,11789,11788,11831 ,0,0,0}, + {28919,28920,28921 ,11833,11834,11835 ,0,0,0}, {28918,28876,28875 ,11832,11790,11789 ,0,0,0}, + {28833,28919,28877 ,11747,11833,11791 ,0,0,0}, {28832,28831,28876 ,11746,11745,11790 ,0,0,0}, + {28919,28922,28878 ,11833,11836,11792 ,0,0,0}, {28833,28877,28831 ,11747,11791,11745 ,0,0,0}, + {28922,28923,28879 ,11836,11837,11793 ,0,0,0}, {28919,28878,28877 ,11833,11792,11791 ,0,0,0}, + {28923,28924,28880 ,11837,11838,11794 ,0,0,0}, {28922,28879,28878 ,11836,11793,11792 ,0,0,0}, + {28881,28924,28839 ,11795,11838,11753 ,0,0,0}, {28880,28879,28923 ,11794,11793,11837 ,0,0,0}, + {28925,28926,28927 ,11839,11840,11841 ,0,0,0}, {28924,28881,28880 ,11838,11795,11794 ,0,0,0}, + {28840,28925,28882 ,11754,11839,11796 ,0,0,0}, {28839,28838,28881 ,11753,11752,11795 ,0,0,0}, + {28925,28928,28883 ,11839,11842,11797 ,0,0,0}, {28840,28882,28838 ,11754,11796,11752 ,0,0,0}, + {28928,28929,28884 ,11842,11843,11798 ,0,0,0}, {28925,28883,28882 ,11839,11797,11796 ,0,0,0}, + {28929,28930,28885 ,11843,11844,11799 ,0,0,0}, {28928,28884,28883 ,11842,11798,11797 ,0,0,0}, + {28801,28930,28931 ,11715,11844,11845 ,0,0,0}, {28929,28885,28884 ,11843,11799,11798 ,0,0,0}, + {28799,28931,28887 ,11713,11845,11801 ,0,0,0}, {28930,28801,28885 ,11844,11715,11799 ,0,0,0}, + {28932,28889,28888 ,11846,11803,11802 ,0,0,0}, {28931,28799,28801 ,11845,11713,11715 ,0,0,0}, + {28933,28934,28935 ,11847,11848,11849 ,0,0,0}, {28887,28886,28799 ,11801,11800,11713 ,0,0,0}, + {28932,28933,28890 ,11846,11847,11804 ,0,0,0}, {28888,28889,28886 ,11802,11803,11800 ,0,0,0}, + {28933,28936,28891 ,11847,11850,11805 ,0,0,0}, {28932,28890,28889 ,11846,11804,11803 ,0,0,0}, + {28936,28937,28892 ,11850,11851,11806 ,0,0,0}, {28933,28891,28890 ,11847,11805,11804 ,0,0,0}, + {28937,28938,28893 ,11851,11852,11807 ,0,0,0}, {28936,28892,28891 ,11850,11806,11805 ,0,0,0}, + {28938,28939,28894 ,11852,11853,11808 ,0,0,0}, {28937,28893,28892 ,11851,11807,11806 ,0,0,0}, + {28939,28940,28895 ,11853,11854,11809 ,0,0,0}, {28938,28894,28893 ,11852,11808,11807 ,0,0,0}, + {28940,28724,28896 ,11854,11638,11810 ,0,0,0}, {28939,28895,28894 ,11853,11809,11808 ,0,0,0}, + {28726,28724,28723 ,11640,11638,11637 ,0,0,0}, {28895,28940,28896 ,11809,11854,11810 ,0,0,0}, + {28941,28715,28897 ,11855,11629,11811 ,0,0,0}, {28726,28896,28724 ,11640,11810,11638 ,0,0,0}, + {28942,28715,28941 ,11856,11629,11855 ,0,0,0}, {28943,28898,28715 ,11857,11812,11629 ,0,0,0}, + {28719,28897,28714 ,11633,11811,11628 ,0,0,0}, {28855,28941,28897 ,11769,11855,11811 ,0,0,0}, + {28942,28943,28715 ,11856,11857,11629 ,0,0,0}, {28901,28627,28626 ,11815,11541,11540 ,0,0,0}, + {28630,28632,28815 ,11544,11546,11729 ,0,0,0}, {28899,28944,28945 ,11813,11858,11859 ,0,0,0}, + {28901,28899,28858 ,11815,11813,11772 ,0,0,0}, {28626,28946,28901 ,11540,11860,11815 ,0,0,0}, + {28900,28945,28947 ,11814,11859,11861 ,0,0,0}, {28901,28944,28899 ,11815,11858,11813 ,0,0,0}, + {28902,28947,28948 ,11816,11861,11862 ,0,0,0}, {28899,28945,28900 ,11813,11859,11814 ,0,0,0}, + {28860,28948,28949 ,11774,11862,11863 ,0,0,0}, {28900,28947,28902 ,11814,11861,11816 ,0,0,0}, + {28861,28949,28950 ,11775,11863,11864 ,0,0,0}, {28902,28948,28860 ,11816,11862,11774 ,0,0,0}, + {28903,28950,28951 ,11817,11864,11865 ,0,0,0}, {28860,28949,28861 ,11774,11863,11775 ,0,0,0}, + {28904,28951,28906 ,11818,11865,11820 ,0,0,0}, {28950,28903,28861 ,11864,11817,11775 ,0,0,0}, + {28952,28908,28907 ,11866,11822,11821 ,0,0,0}, {28951,28904,28903 ,11865,11818,11817 ,0,0,0}, + {28953,28954,28952 ,11867,11868,11866 ,0,0,0}, {28906,28905,28904 ,11820,11819,11818 ,0,0,0}, + {28952,28954,28909 ,11866,11868,11823 ,0,0,0}, {28907,28908,28905 ,11821,11822,11819 ,0,0,0}, + {28954,28955,28910 ,11868,11869,11824 ,0,0,0}, {28952,28909,28908 ,11866,11823,11822 ,0,0,0}, + {28911,28955,28956 ,11825,11869,11870 ,0,0,0}, {28954,28910,28909 ,11868,11824,11823 ,0,0,0}, + {28912,28956,28957 ,11826,11870,11871 ,0,0,0}, {28910,28955,28911 ,11824,11869,11825 ,0,0,0}, + {28870,28957,28958 ,11784,11871,11872 ,0,0,0}, {28911,28956,28912 ,11825,11870,11826 ,0,0,0}, + {28871,28958,28914 ,11785,11872,11828 ,0,0,0}, {28957,28870,28912 ,11871,11784,11826 ,0,0,0}, + {28959,28960,28915 ,11873,11874,11829 ,0,0,0}, {28958,28871,28870 ,11872,11785,11784 ,0,0,0}, + {28915,28960,28916 ,11829,11874,11830 ,0,0,0}, {28914,28913,28871 ,11828,11827,11785 ,0,0,0}, + {28960,28961,28917 ,11874,11875,11831 ,0,0,0}, {28915,28916,28913 ,11829,11830,11827 ,0,0,0}, + {28918,28961,28962 ,11832,11875,11876 ,0,0,0}, {28960,28917,28916 ,11874,11831,11830 ,0,0,0}, + {28832,28962,28963 ,11746,11876,11877 ,0,0,0}, {28917,28961,28918 ,11831,11875,11832 ,0,0,0}, + {28833,28963,28920 ,11747,11877,11834 ,0,0,0}, {28962,28832,28918 ,11876,11746,11832 ,0,0,0}, + {28964,28965,28921 ,11878,11879,11835 ,0,0,0}, {28963,28833,28832 ,11877,11747,11746 ,0,0,0}, + {28921,28965,28922 ,11835,11879,11836 ,0,0,0}, {28920,28919,28833 ,11834,11833,11747 ,0,0,0}, + {28965,28966,28923 ,11879,11880,11837 ,0,0,0}, {28921,28922,28919 ,11835,11836,11833 ,0,0,0}, + {28924,28966,28967 ,11838,11880,11881 ,0,0,0}, {28965,28923,28922 ,11879,11837,11836 ,0,0,0}, + {28839,28967,28968 ,11753,11881,11882 ,0,0,0}, {28923,28966,28924 ,11837,11880,11838 ,0,0,0}, + {28840,28968,28926 ,11754,11882,11840 ,0,0,0}, {28967,28839,28924 ,11881,11753,11838 ,0,0,0}, + {28969,28970,28927 ,11883,11884,11841 ,0,0,0}, {28968,28840,28839 ,11882,11754,11753 ,0,0,0}, + {28927,28970,28928 ,11841,11884,11842 ,0,0,0}, {28926,28925,28840 ,11840,11839,11754 ,0,0,0}, + {28970,28971,28929 ,11884,11885,11843 ,0,0,0}, {28927,28928,28925 ,11841,11842,11839 ,0,0,0}, + {28930,28971,28972 ,11844,11885,11886 ,0,0,0}, {28970,28929,28928 ,11884,11843,11842 ,0,0,0}, + {28931,28972,28973 ,11845,11886,11887 ,0,0,0}, {28929,28971,28930 ,11843,11885,11844 ,0,0,0}, + {28887,28973,28974 ,11801,11887,11888 ,0,0,0}, {28930,28972,28931 ,11844,11886,11845 ,0,0,0}, + {28888,28974,28975 ,11802,11888,11889 ,0,0,0}, {28931,28973,28887 ,11845,11887,11801 ,0,0,0}, + {28932,28975,28934 ,11846,11889,11848 ,0,0,0}, {28974,28888,28887 ,11888,11802,11801 ,0,0,0}, + {28976,28936,28935 ,11890,11850,11849 ,0,0,0}, {28975,28932,28888 ,11889,11846,11802 ,0,0,0}, + {28977,28978,28976 ,11891,11892,11890 ,0,0,0}, {28934,28933,28932 ,11848,11847,11846 ,0,0,0}, + {28976,28978,28937 ,11890,11892,11851 ,0,0,0}, {28935,28936,28933 ,11849,11850,11847 ,0,0,0}, + {28978,28979,28938 ,11892,11893,11852 ,0,0,0}, {28976,28937,28936 ,11890,11851,11850 ,0,0,0}, + {28979,28980,28939 ,11893,11894,11853 ,0,0,0}, {28978,28938,28937 ,11892,11852,11851 ,0,0,0}, + {28980,28981,28940 ,11894,11895,11854 ,0,0,0}, {28979,28939,28938 ,11893,11853,11852 ,0,0,0}, + {28724,28981,28725 ,11638,11895,11639 ,0,0,0}, {28980,28940,28939 ,11894,11854,11853 ,0,0,0}, + {28725,28982,28723 ,11639,11896,11637 ,0,0,0}, {28724,28940,28981 ,11638,11854,11895 ,0,0,0}, + {28983,28941,28731 ,11897,11855,11645 ,0,0,0}, {28983,28984,28941 ,11897,11898,11855 ,0,0,0}, + {28727,28855,28897 ,11641,11769,11811 ,0,0,0}, {28982,28731,28855 ,11896,11645,11769 ,0,0,0}, + {28942,28941,28984 ,11856,11855,11898 ,0,0,0}, {28632,28946,28626 ,11546,11860,11540 ,0,0,0}, + {28985,28631,28630 ,11899,11545,11544 ,0,0,0}, {28986,28944,28946 ,11900,11858,11860 ,0,0,0}, + {28946,28944,28901 ,11860,11858,11815 ,0,0,0}, {28946,28857,28986 ,11860,11771,11900 ,0,0,0}, + {28987,28945,28944 ,11901,11859,11858 ,0,0,0}, {28944,28986,28987 ,11858,11900,11901 ,0,0,0}, + {28988,28947,28945 ,11902,11861,11859 ,0,0,0}, {28945,28987,28988 ,11859,11901,11902 ,0,0,0}, + {28989,28948,28947 ,11903,11862,11861 ,0,0,0}, {28947,28988,28989 ,11861,11902,11903 ,0,0,0}, + {28990,28949,28948 ,11904,11863,11862 ,0,0,0}, {28948,28989,28990 ,11862,11903,11904 ,0,0,0}, + {28991,28950,28949 ,11905,11864,11863 ,0,0,0}, {28949,28990,28991 ,11863,11904,11905 ,0,0,0}, + {28992,28951,28950 ,11906,11865,11864 ,0,0,0}, {28950,28991,28992 ,11864,11905,11906 ,0,0,0}, + {28993,28906,28951 ,11907,11820,11865 ,0,0,0}, {28951,28992,28993 ,11865,11906,11907 ,0,0,0}, + {28994,28907,28906 ,11908,11821,11820 ,0,0,0}, {28906,28993,28994 ,11820,11907,11908 ,0,0,0}, + {28995,28952,28907 ,11909,11866,11821 ,0,0,0}, {28994,28995,28907 ,11908,11909,11821 ,0,0,0}, + {28996,28997,28998 ,11910,11911,11912 ,0,0,0}, {28995,28953,28952 ,11909,11867,11866 ,0,0,0}, + {28999,28955,28954 ,11913,11869,11868 ,0,0,0}, {28953,28999,28954 ,11867,11913,11868 ,0,0,0}, + {29000,28956,28955 ,11914,11870,11869 ,0,0,0}, {28955,28999,29000 ,11869,11913,11914 ,0,0,0}, + {29001,28957,28956 ,11915,11871,11870 ,0,0,0}, {28956,29000,29001 ,11870,11914,11915 ,0,0,0}, + {29002,28958,28957 ,11916,11872,11871 ,0,0,0}, {28957,29001,29002 ,11871,11915,11916 ,0,0,0}, + {29003,28914,28958 ,11917,11828,11872 ,0,0,0}, {28958,29002,29003 ,11872,11916,11917 ,0,0,0}, + {29004,28915,28914 ,11918,11829,11828 ,0,0,0}, {29003,29004,28914 ,11917,11918,11828 ,0,0,0}, + {29005,28959,29006 ,11919,11873,11920 ,0,0,0}, {29004,28959,28915 ,11918,11873,11829 ,0,0,0}, + {29005,28961,28960 ,11919,11875,11874 ,0,0,0}, {28959,29005,28960 ,11873,11919,11874 ,0,0,0}, + {29007,28962,28961 ,11921,11876,11875 ,0,0,0}, {28961,29005,29007 ,11875,11919,11921 ,0,0,0}, + {29008,28963,28962 ,11922,11877,11876 ,0,0,0}, {28962,29007,29008 ,11876,11921,11922 ,0,0,0}, + {29009,28920,28963 ,11923,11834,11877 ,0,0,0}, {28963,29008,29009 ,11877,11922,11923 ,0,0,0}, + {29010,28921,28920 ,11924,11835,11834 ,0,0,0}, {29009,29010,28920 ,11923,11924,11834 ,0,0,0}, + {29011,29012,29013 ,11925,11926,11927 ,0,0,0}, {29010,28964,28921 ,11924,11878,11835 ,0,0,0}, + {29014,28966,28965 ,11928,11880,11879 ,0,0,0}, {28964,29014,28965 ,11878,11928,11879 ,0,0,0}, + {29015,28967,28966 ,11929,11881,11880 ,0,0,0}, {28966,29014,29015 ,11880,11928,11929 ,0,0,0}, + {29016,28968,28967 ,11930,11882,11881 ,0,0,0}, {28967,29015,29016 ,11881,11929,11930 ,0,0,0}, + {29017,28926,28968 ,11931,11840,11882 ,0,0,0}, {28968,29016,29017 ,11882,11930,11931 ,0,0,0}, + {29018,28927,28926 ,11932,11841,11840 ,0,0,0}, {29017,29018,28926 ,11931,11932,11840 ,0,0,0}, + {28970,29019,28971 ,11884,11933,11885 ,0,0,0}, {29018,28969,28927 ,11932,11883,11841 ,0,0,0}, + {29020,29021,29019 ,11934,11935,11933 ,0,0,0}, {28969,29019,28970 ,11883,11933,11884 ,0,0,0}, + {29021,28972,28971 ,11935,11886,11885 ,0,0,0}, {28971,29019,29021 ,11885,11933,11935 ,0,0,0}, + {29022,28973,28972 ,11936,11887,11886 ,0,0,0}, {28972,29021,29022 ,11886,11935,11936 ,0,0,0}, + {29023,28974,28973 ,11937,11888,11887 ,0,0,0}, {28973,29022,29023 ,11887,11936,11937 ,0,0,0}, + {29024,28975,28974 ,11938,11889,11888 ,0,0,0}, {28974,29023,29024 ,11888,11937,11938 ,0,0,0}, + {29025,28934,28975 ,11939,11848,11889 ,0,0,0}, {28975,29024,29025 ,11889,11938,11939 ,0,0,0}, + {29026,28935,28934 ,11940,11849,11848 ,0,0,0}, {28934,29025,29026 ,11848,11939,11940 ,0,0,0}, + {29027,28976,28935 ,11941,11890,11849 ,0,0,0}, {29026,29027,28935 ,11940,11941,11849 ,0,0,0}, + {28978,29028,28979 ,11892,11942,11893 ,0,0,0}, {29027,28977,28976 ,11941,11891,11890 ,0,0,0}, + {28979,29029,28980 ,11893,11943,11894 ,0,0,0}, {28977,29028,28978 ,11891,11942,11892 ,0,0,0}, + {28980,29030,28981 ,11894,11944,11895 ,0,0,0}, {29028,29029,28979 ,11942,11943,11893 ,0,0,0}, + {28981,28728,28725 ,11895,11642,11639 ,0,0,0}, {29029,29030,28980 ,11943,11944,11894 ,0,0,0}, + {28733,28732,28729 ,11647,11646,11643 ,0,0,0}, {29030,28728,28981 ,11944,11642,11895 ,0,0,0}, + {28729,28982,28725 ,11643,11896,11639 ,0,0,0}, {28855,28731,28941 ,11769,11645,11855 ,0,0,0}, + {28723,28982,28855 ,11637,11896,11769 ,0,0,0}, {28982,28729,28732 ,11896,11643,11646 ,0,0,0}, + {28983,28731,28730 ,11897,11645,11644 ,0,0,0}, {28631,28857,28632 ,11545,11771,11546 ,0,0,0}, + {28985,28638,28636 ,11899,11552,11550 ,0,0,0}, {28986,28857,29031 ,11900,11771,11945 ,0,0,0}, + {28632,28857,28946 ,11546,11771,11860 ,0,0,0}, {28857,28635,29031 ,11771,11549,11945 ,0,0,0}, + {28987,28986,29032 ,11901,11900,11946 ,0,0,0}, {28986,29031,29032 ,11900,11945,11946 ,0,0,0}, + {28988,28987,29033 ,11902,11901,11947 ,0,0,0}, {28987,29032,29033 ,11901,11946,11947 ,0,0,0}, + {28989,28988,29034 ,11903,11902,11948 ,0,0,0}, {28988,29033,29034 ,11902,11947,11948 ,0,0,0}, + {28990,28989,29035 ,11904,11903,11949 ,0,0,0}, {28989,29034,29035 ,11903,11948,11949 ,0,0,0}, + {28991,28990,29036 ,11905,11904,11950 ,0,0,0}, {28990,29035,29036 ,11904,11949,11950 ,0,0,0}, + {28992,28991,29037 ,11906,11905,11951 ,0,0,0}, {28991,29036,29037 ,11905,11950,11951 ,0,0,0}, + {28993,28992,29038 ,11907,11906,11952 ,0,0,0}, {28992,29037,29038 ,11906,11951,11952 ,0,0,0}, + {28994,28993,29039 ,11908,11907,11953 ,0,0,0}, {28993,29038,29039 ,11907,11952,11953 ,0,0,0}, + {28995,28994,29040 ,11909,11908,11954 ,0,0,0}, {28994,29039,29040 ,11908,11953,11954 ,0,0,0}, + {28953,28995,29041 ,11867,11909,11955 ,0,0,0}, {28995,29040,29041 ,11909,11954,11955 ,0,0,0}, + {28999,28953,28996 ,11913,11867,11910 ,0,0,0}, {29041,28996,28953 ,11955,11910,11867 ,0,0,0}, + {29000,28999,28998 ,11914,11913,11912 ,0,0,0}, {28999,28996,28998 ,11913,11910,11912 ,0,0,0}, + {29001,29000,29042 ,11915,11914,11956 ,0,0,0}, {29000,28998,29042 ,11914,11912,11956 ,0,0,0}, + {29002,29001,29043 ,11916,11915,11957 ,0,0,0}, {29001,29042,29043 ,11915,11956,11957 ,0,0,0}, + {29003,29002,29044 ,11917,11916,11958 ,0,0,0}, {29002,29043,29044 ,11916,11957,11958 ,0,0,0}, + {29004,29003,29045 ,11918,11917,11959 ,0,0,0}, {29003,29044,29045 ,11917,11958,11959 ,0,0,0}, + {28959,29004,29046 ,11873,11918,11960 ,0,0,0}, {29004,29045,29046 ,11918,11959,11960 ,0,0,0}, + {29046,29047,29006 ,11960,11961,11920 ,0,0,0}, {29046,29006,28959 ,11960,11920,11873 ,0,0,0}, + {29007,29005,29048 ,11921,11919,11962 ,0,0,0}, {29005,29006,29048 ,11919,11920,11962 ,0,0,0}, + {29008,29007,29049 ,11922,11921,11963 ,0,0,0}, {29007,29048,29049 ,11921,11962,11963 ,0,0,0}, + {29009,29008,29050 ,11923,11922,11964 ,0,0,0}, {29008,29049,29050 ,11922,11963,11964 ,0,0,0}, + {29010,29009,29051 ,11924,11923,11965 ,0,0,0}, {29009,29050,29051 ,11923,11964,11965 ,0,0,0}, + {28964,29010,29052 ,11878,11924,11966 ,0,0,0}, {29010,29051,29052 ,11924,11965,11966 ,0,0,0}, + {29014,28964,29011 ,11928,11878,11925 ,0,0,0}, {29052,29011,28964 ,11966,11925,11878 ,0,0,0}, + {29015,29014,29013 ,11929,11928,11927 ,0,0,0}, {29014,29011,29013 ,11928,11925,11927 ,0,0,0}, + {29016,29015,29053 ,11930,11929,11967 ,0,0,0}, {29015,29013,29053 ,11929,11927,11967 ,0,0,0}, + {29017,29016,29054 ,11931,11930,11968 ,0,0,0}, {29016,29053,29054 ,11930,11967,11968 ,0,0,0}, + {29018,29017,29055 ,11932,11931,11969 ,0,0,0}, {29017,29054,29055 ,11931,11968,11969 ,0,0,0}, + {28969,29018,29056 ,11883,11932,11970 ,0,0,0}, {29018,29055,29056 ,11932,11969,11970 ,0,0,0}, + {29019,28969,29057 ,11933,11883,11971 ,0,0,0}, {28969,29056,29057 ,11883,11970,11971 ,0,0,0}, + {29020,29057,29058 ,11934,11971,11972 ,0,0,0}, {29057,29020,29019 ,11971,11934,11933 ,0,0,0}, + {29022,29021,29059 ,11936,11935,11973 ,0,0,0}, {29021,29020,29059 ,11935,11934,11973 ,0,0,0}, + {29023,29022,29060 ,11937,11936,11974 ,0,0,0}, {29022,29059,29060 ,11936,11973,11974 ,0,0,0}, + {29024,29023,29061 ,11938,11937,11975 ,0,0,0}, {29023,29060,29061 ,11937,11974,11975 ,0,0,0}, + {29025,29024,29062 ,11939,11938,11976 ,0,0,0}, {29024,29061,29062 ,11938,11975,11976 ,0,0,0}, + {29026,29025,29063 ,11940,11939,11977 ,0,0,0}, {29025,29062,29063 ,11939,11976,11977 ,0,0,0}, + {29027,29026,29064 ,11941,11940,11978 ,0,0,0}, {29026,29063,29064 ,11940,11977,11978 ,0,0,0}, + {28977,29027,29065 ,11891,11941,11979 ,0,0,0}, {29027,29064,29065 ,11941,11978,11979 ,0,0,0}, + {29028,28977,29066 ,11942,11891,11980 ,0,0,0}, {28977,29065,29066 ,11891,11979,11980 ,0,0,0}, + {29029,29028,29067 ,11943,11942,11981 ,0,0,0}, {29028,29066,29067 ,11942,11980,11981 ,0,0,0}, + {29030,29029,29068 ,11944,11943,11982 ,0,0,0}, {29029,29067,29068 ,11943,11981,11982 ,0,0,0}, + {28728,29030,29069 ,11642,11944,11983 ,0,0,0}, {29030,29068,29069 ,11944,11982,11983 ,0,0,0}, + {29070,28729,28728 ,11984,11643,11642 ,0,0,0}, {29070,28728,29069 ,11984,11642,11983 ,0,0,0}, + {28982,28732,28731 ,11896,11646,11645 ,0,0,0}, {29070,28733,28729 ,11984,11647,11643 ,0,0,0}, + {28730,28732,28735 ,11644,11646,11649 ,0,0,0}, {28636,28631,28985 ,11550,11545,11899 ,0,0,0}, + {28637,28634,28636 ,11551,11548,11550 ,0,0,0}, {28634,29071,28635 ,11548,11985,11549 ,0,0,0}, + {28635,29071,29031 ,11549,11985,11945 ,0,0,0}, {29071,29072,29031 ,11985,11986,11945 ,0,0,0}, + {29031,29072,29032 ,11945,11986,11946 ,0,0,0}, {29072,29073,29032 ,11986,11987,11946 ,0,0,0}, + {29032,29073,29033 ,11946,11987,11947 ,0,0,0}, {29073,29074,29033 ,11987,11988,11947 ,0,0,0}, + {29033,29074,29034 ,11947,11988,11948 ,0,0,0}, {29074,29075,29034 ,11988,11989,11948 ,0,0,0}, + {29034,29075,29035 ,11948,11989,11949 ,0,0,0}, {29075,29076,29035 ,11989,11990,11949 ,0,0,0}, + {29035,29076,29036 ,11949,11990,11950 ,0,0,0}, {29076,29077,29036 ,11990,11991,11950 ,0,0,0}, + {29036,29077,29037 ,11950,11991,11951 ,0,0,0}, {29077,29078,29037 ,11991,11992,11951 ,0,0,0}, + {29078,29079,29038 ,11992,11993,11952 ,0,0,0}, {29078,29038,29037 ,11992,11952,11951 ,0,0,0}, + {29079,29080,29039 ,11993,11994,11953 ,0,0,0}, {29079,29039,29038 ,11993,11953,11952 ,0,0,0}, + {29080,29081,29040 ,11994,11995,11954 ,0,0,0}, {29080,29040,29039 ,11994,11954,11953 ,0,0,0}, + {29081,29082,29041 ,11995,11996,11955 ,0,0,0}, {29081,29041,29040 ,11995,11955,11954 ,0,0,0}, + {29082,29083,28996 ,11996,11997,11910 ,0,0,0}, {29082,28996,29041 ,11996,11910,11955 ,0,0,0}, + {28997,28996,29083 ,11911,11910,11997 ,0,0,0}, {28997,29084,28998 ,11911,11998,11912 ,0,0,0}, + {28998,29084,29042 ,11912,11998,11956 ,0,0,0}, {29084,29085,29042 ,11998,11999,11956 ,0,0,0}, + {29042,29085,29043 ,11956,11999,11957 ,0,0,0}, {29085,29086,29043 ,11999,12000,11957 ,0,0,0}, + {29086,29087,29044 ,12000,12001,11958 ,0,0,0}, {29086,29044,29043 ,12000,11958,11957 ,0,0,0}, + {29087,29088,29045 ,12001,12002,11959 ,0,0,0}, {29087,29045,29044 ,12001,11959,11958 ,0,0,0}, + {29088,29047,29046 ,12002,11961,11960 ,0,0,0}, {29088,29046,29045 ,12002,11960,11959 ,0,0,0}, + {29047,29089,29006 ,11961,12003,11920 ,0,0,0}, {29089,29090,29006 ,12003,12004,11920 ,0,0,0}, + {29006,29090,29048 ,11920,12004,11962 ,0,0,0}, {29090,29091,29048 ,12004,12005,11962 ,0,0,0}, + {29048,29091,29049 ,11962,12005,11963 ,0,0,0}, {29091,29092,29049 ,12005,12006,11963 ,0,0,0}, + {29092,29093,29050 ,12006,12007,11964 ,0,0,0}, {29092,29050,29049 ,12006,11964,11963 ,0,0,0}, + {29093,29094,29051 ,12007,12008,11965 ,0,0,0}, {29093,29051,29050 ,12007,11965,11964 ,0,0,0}, + {29094,29095,29052 ,12008,12009,11966 ,0,0,0}, {29094,29052,29051 ,12008,11966,11965 ,0,0,0}, + {29095,29096,29011 ,12009,12010,11925 ,0,0,0}, {29095,29011,29052 ,12009,11925,11966 ,0,0,0}, + {29012,29011,29096 ,11926,11925,12010 ,0,0,0}, {29012,29097,29013 ,11926,12011,11927 ,0,0,0}, + {29013,29097,29053 ,11927,12011,11967 ,0,0,0}, {29097,29098,29053 ,12011,12012,11967 ,0,0,0}, + {29098,29099,29054 ,12012,12013,11968 ,0,0,0}, {29098,29054,29053 ,12012,11968,11967 ,0,0,0}, + {29099,29100,29055 ,12013,12014,11969 ,0,0,0}, {29099,29055,29054 ,12013,11969,11968 ,0,0,0}, + {29100,29101,29056 ,12014,12015,11970 ,0,0,0}, {29100,29056,29055 ,12014,11970,11969 ,0,0,0}, + {29101,29058,29057 ,12015,11972,11971 ,0,0,0}, {29101,29057,29056 ,12015,11971,11970 ,0,0,0}, + {29058,29102,29020 ,11972,12016,11934 ,0,0,0}, {29102,29103,29020 ,12016,12017,11934 ,0,0,0}, + {29020,29103,29059 ,11934,12017,11973 ,0,0,0}, {29103,29104,29059 ,12017,12018,11973 ,0,0,0}, + {29059,29104,29060 ,11973,12018,11974 ,0,0,0}, {29104,29105,29060 ,12018,12019,11974 ,0,0,0}, + {29060,29105,29061 ,11974,12019,11975 ,0,0,0}, {29105,29106,29061 ,12019,12020,11975 ,0,0,0}, + {29106,29107,29062 ,12020,12021,11976 ,0,0,0}, {29106,29062,29061 ,12020,11976,11975 ,0,0,0}, + {29107,29108,29063 ,12021,12022,11977 ,0,0,0}, {29107,29063,29062 ,12021,11977,11976 ,0,0,0}, + {29108,29109,29064 ,12022,12023,11978 ,0,0,0}, {29108,29064,29063 ,12022,11978,11977 ,0,0,0}, + {29109,29110,29065 ,12023,12024,11979 ,0,0,0}, {29109,29065,29064 ,12023,11979,11978 ,0,0,0}, + {29110,29111,29066 ,12024,12025,11980 ,0,0,0}, {29110,29066,29065 ,12024,11980,11979 ,0,0,0}, + {29111,29112,29067 ,12025,12026,11981 ,0,0,0}, {29111,29067,29066 ,12025,11981,11980 ,0,0,0}, + {29112,29113,29068 ,12026,12027,11982 ,0,0,0}, {29112,29068,29067 ,12026,11982,11981 ,0,0,0}, + {29113,29114,29069 ,12027,12028,11983 ,0,0,0}, {29113,29069,29068 ,12027,11983,11982 ,0,0,0}, + {29114,29115,29070 ,12028,12029,11984 ,0,0,0}, {29114,29070,29069 ,12028,11984,11983 ,0,0,0}, + {29116,29070,29115 ,12030,11984,12029 ,0,0,0}, {29070,29116,28733 ,11984,12030,11647 ,0,0,0}, + {28733,29116,28736 ,11647,12030,11650 ,0,0,0}, {29117,29118,29119 ,12031,12032,12033 ,0,0,0}, + {29120,29121,29122 ,12034,12035,12036 ,0,0,0}, {29123,29124,29125 ,12037,12038,12039 ,0,0,0}, + {29126,29127,29123 ,12040,12041,12037 ,0,0,0}, {29128,29129,29130 ,12042,12043,12044 ,0,0,0}, + {29131,29132,29133 ,12045,12046,12047 ,0,0,0}, {29134,29135,29136 ,12048,12049,12050 ,0,0,0}, + {29137,29138,29131 ,12051,12052,12045 ,0,0,0}, {29139,29140,29141 ,12053,12054,12055 ,0,0,0}, + {29141,29136,29142 ,12055,12050,12056 ,0,0,0}, {29143,29139,29144 ,12057,12053,12058 ,0,0,0}, + {29140,29139,29145 ,12054,12053,12059 ,0,0,0}, {29126,29146,29147 ,12040,12060,12061 ,0,0,0}, + {29143,29148,29139 ,12057,12062,12053 ,0,0,0}, {29149,29150,29151 ,12063,12064,12065 ,0,0,0}, + {29150,29152,29119 ,12064,12066,12033 ,0,0,0}, {29153,29154,29151 ,12067,12068,12065 ,0,0,0}, + {29152,29150,29149 ,12066,12064,12063 ,0,0,0}, {29155,29156,29153 ,12069,12070,12067 ,0,0,0}, + {29151,29154,29149 ,12065,12068,12063 ,0,0,0}, {29157,29158,29121 ,12071,12072,12035 ,0,0,0}, + {29159,29160,29161 ,12073,12074,12075 ,0,0,0}, {29157,29162,29158 ,12071,12076,12072 ,0,0,0}, + {29163,29164,29165 ,12077,12078,12079 ,0,0,0}, {29160,29166,29161 ,12074,12080,12075 ,0,0,0}, + {29167,29168,29169 ,12081,12082,12083 ,0,0,0}, {29163,29165,29170 ,12077,12079,12084 ,0,0,0}, + {29171,29172,29173 ,12085,12086,12087 ,0,0,0}, {29172,29171,29174 ,12086,12085,12088 ,0,0,0}, + {29175,29176,29177 ,12089,12090,12091 ,0,0,0}, {29178,29179,29176 ,12092,12093,12090 ,0,0,0}, + {29180,29181,29182 ,12094,12095,12096 ,0,0,0}, {29175,29177,29183 ,12089,12091,12097 ,0,0,0}, + {29184,29185,29186 ,12098,12099,12100 ,0,0,0}, {29180,29182,29187 ,12094,12096,12101 ,0,0,0}, + {29188,29189,29190 ,12102,12103,12104 ,0,0,0}, {29191,29185,29184 ,12105,12099,12098 ,0,0,0}, + {29192,29193,29194 ,12106,12107,12108 ,0,0,0}, {29194,29190,29192 ,12108,12104,12106 ,0,0,0}, + {29195,29196,29197 ,12109,12110,12111 ,0,0,0}, {29198,29193,29199 ,12112,12107,12113 ,0,0,0}, + {29200,29201,29202 ,12114,12115,12116 ,0,0,0}, {29201,29200,29203 ,12115,12114,12117 ,0,0,0}, + {29204,29205,29206 ,12118,12119,12120 ,0,0,0}, {29202,29205,29207 ,12116,12119,12121 ,0,0,0}, + {29208,29209,29210 ,12122,12123,12124 ,0,0,0}, {29211,29212,29213 ,12125,12126,12127 ,0,0,0}, + {29214,29215,29216 ,12128,12129,12130 ,0,0,0}, {29215,29214,29217 ,12129,12128,12131 ,0,0,0}, + {29218,29219,29220 ,12132,12133,12134 ,0,0,0}, {29221,29222,29218 ,12135,12136,12132 ,0,0,0}, + {29219,29218,29222 ,12133,12132,12136 ,0,0,0}, {29219,29222,29208 ,12133,12136,12122 ,0,0,0}, + {29223,29224,29225 ,12137,12138,12139 ,0,0,0}, {29206,29210,29209 ,12120,12124,12123 ,0,0,0}, + {29226,29211,29213 ,12140,12125,12127 ,0,0,0}, {29212,29227,29213 ,12126,12141,12127 ,0,0,0}, + {29228,29229,29211 ,12142,12143,12125 ,0,0,0}, {29211,29230,29212 ,12125,12144,12126 ,0,0,0}, + {29231,29232,29233 ,12145,12146,12147 ,0,0,0}, {28630,29234,29235 ,12148,12149,12150 ,0,0,0}, + {29235,29236,28985 ,12150,12151,12152 ,0,0,0}, {29236,28638,28985 ,12151,12153,12152 ,0,0,0}, + {28639,28638,29237 ,730,12153,12154 ,0,0,0}, {29225,29205,29223 ,12139,12119,12137 ,0,0,0}, + {29216,29221,29218 ,12130,12135,12132 ,0,0,0}, {29206,29209,29204 ,12120,12123,12118 ,0,0,0}, + {28768,29217,28767 ,12155,12131,12156 ,0,0,0}, {29200,29202,29207 ,12114,12116,12121 ,0,0,0}, + {29205,29204,29207 ,12119,12118,12121 ,0,0,0}, {29195,29203,29196 ,12109,12117,12110 ,0,0,0}, + {29201,29203,29195 ,12115,12117,12109 ,0,0,0}, {29195,29238,29201 ,12109,12157,12115 ,0,0,0}, + {29196,29198,29197 ,12110,12112,12111 ,0,0,0}, {29199,29193,29192 ,12113,12107,12106 ,0,0,0}, + {29198,29199,29197 ,12112,12113,12111 ,0,0,0}, {29188,29190,29194 ,12102,12104,12108 ,0,0,0}, + {29184,29186,29239 ,12098,12100,12158 ,0,0,0}, {29240,29191,29241 ,12159,12105,12160 ,0,0,0}, + {29190,29189,29241 ,12104,12103,12160 ,0,0,0}, {29185,29191,29240 ,12099,12105,12159 ,0,0,0}, + {29189,29240,29241 ,12103,12159,12160 ,0,0,0}, {29239,29186,29187 ,12158,12100,12101 ,0,0,0}, + {29242,29184,29239 ,12161,12098,12158 ,0,0,0}, {29187,29182,29239 ,12101,12096,12158 ,0,0,0}, + {29183,29181,29243 ,12097,12095,12162 ,0,0,0}, {29180,29243,29181 ,12094,12162,12095 ,0,0,0}, + {29244,29183,29243 ,12163,12097,12162 ,0,0,0}, {29179,29177,29176 ,12093,12091,12090 ,0,0,0}, + {29175,29183,29244 ,12089,12097,12163 ,0,0,0}, {29178,29245,29179 ,12092,12164,12093 ,0,0,0}, + {29173,29172,29245 ,12087,12086,12164 ,0,0,0}, {29245,29178,29173 ,12164,12092,12087 ,0,0,0}, + {29174,29246,29169 ,12088,12165,12083 ,0,0,0}, {29247,29248,29249 ,12166,12167,12168 ,0,0,0}, + {29169,29246,29250 ,12083,12165,12169 ,0,0,0}, {29246,29174,29171 ,12165,12088,12085 ,0,0,0}, + {29251,29170,29168 ,12170,12084,12082 ,0,0,0}, {29167,29169,29250 ,12081,12083,12169 ,0,0,0}, + {29170,29251,29163 ,12084,12170,12077 ,0,0,0}, {29251,29168,29167 ,12170,12082,12081 ,0,0,0}, + {29162,29252,29253 ,12076,12171,12172 ,0,0,0}, {29164,29166,29254 ,12078,12080,12173 ,0,0,0}, + {29165,29164,29254 ,12079,12078,12173 ,0,0,0}, {29254,29166,29160 ,12173,12080,12074 ,0,0,0}, + {29255,29256,29257 ,12174,12175,12176 ,0,0,0}, {29252,29159,29161 ,12171,12073,12075 ,0,0,0}, + {29119,29152,29117 ,12033,12066,12031 ,0,0,0}, {29162,29159,29252 ,12076,12073,12171 ,0,0,0}, + {29162,29253,29158 ,12076,12172,12072 ,0,0,0}, {29121,29120,29157 ,12035,12034,12071 ,0,0,0}, + {29156,29155,29122 ,12070,12069,12036 ,0,0,0}, {29122,29155,29120 ,12036,12069,12034 ,0,0,0}, + {29258,29155,29153 ,12177,12069,12067 ,0,0,0}, {29156,29154,29153 ,12070,12068,12067 ,0,0,0}, + {29118,29147,29146 ,12032,12061,12060 ,0,0,0}, {29117,29147,29118 ,12031,12061,12032 ,0,0,0}, + {29127,29124,29123 ,12041,12038,12037 ,0,0,0}, {29126,29123,29146 ,12040,12037,12060 ,0,0,0}, + {29127,29259,29124 ,12041,12178,12038 ,0,0,0}, {29130,29260,29134 ,12044,12179,12048 ,0,0,0}, + {29261,29262,29259 ,12180,12181,12178 ,0,0,0}, {29128,29263,29264 ,12042,12182,12183 ,0,0,0}, + {29262,29265,29266 ,12181,12184,12185 ,0,0,0}, {29261,29265,29262 ,12180,12184,12181 ,0,0,0}, + {29262,29124,29259 ,12181,12038,12178 ,0,0,0}, {29266,29267,29268 ,12185,12186,12187 ,0,0,0}, + {29267,29266,29269 ,12186,12185,12188 ,0,0,0}, {29265,29269,29266 ,12184,12188,12185 ,0,0,0}, + {29264,29263,29268 ,12183,12182,12187 ,0,0,0}, {29270,29130,29129 ,12189,12044,12043 ,0,0,0}, + {29266,29268,29263 ,12185,12187,12182 ,0,0,0}, {29135,29134,29271 ,12049,12048,12190 ,0,0,0}, + {29266,29272,29262 ,12185,12191,12181 ,0,0,0}, {29273,29146,29123 ,12192,12060,12037 ,0,0,0}, + {29262,29133,29124 ,12181,12047,12038 ,0,0,0}, {29274,29118,29146 ,12193,12032,12060 ,0,0,0}, + {29125,29124,29133 ,12039,12038,12047 ,0,0,0}, {29275,29119,29118 ,12194,12033,12032 ,0,0,0}, + {29273,29123,29125 ,12192,12037,12039 ,0,0,0}, {29276,29150,29119 ,12195,12064,12033 ,0,0,0}, + {29274,29146,29273 ,12193,12060,12192 ,0,0,0}, {29277,29151,29150 ,12196,12065,12064 ,0,0,0}, + {29275,29118,29274 ,12194,12032,12193 ,0,0,0}, {29278,29153,29151 ,12197,12067,12065 ,0,0,0}, + {29119,29275,29276 ,12033,12194,12195 ,0,0,0}, {29279,29280,29281 ,12198,12199,12200 ,0,0,0}, + {29150,29276,29277 ,12064,12195,12196 ,0,0,0}, {29281,29120,29155 ,12200,12034,12069 ,0,0,0}, + {29151,29277,29278 ,12065,12196,12197 ,0,0,0}, {29282,29157,29120 ,12201,12071,12034 ,0,0,0}, + {29153,29278,29258 ,12067,12197,12177 ,0,0,0}, {29283,29162,29157 ,12202,12076,12071 ,0,0,0}, + {29155,29258,29281 ,12069,12177,12200 ,0,0,0}, {29284,29159,29162 ,12203,12073,12076 ,0,0,0}, + {29120,29281,29282 ,12034,12200,12201 ,0,0,0}, {29285,29160,29159 ,12204,12074,12073 ,0,0,0}, + {29283,29157,29282 ,12202,12071,12201 ,0,0,0}, {29286,29254,29160 ,12205,12173,12074 ,0,0,0}, + {29284,29162,29283 ,12203,12076,12202 ,0,0,0}, {29287,29165,29254 ,12206,12079,12173 ,0,0,0}, + {29159,29284,29285 ,12073,12203,12204 ,0,0,0}, {29256,29170,29165 ,12175,12084,12079 ,0,0,0}, + {29160,29285,29286 ,12074,12204,12205 ,0,0,0}, {29288,29168,29170 ,12207,12082,12084 ,0,0,0}, + {29254,29286,29287 ,12173,12205,12206 ,0,0,0}, {29289,29169,29168 ,12208,12083,12082 ,0,0,0}, + {29165,29287,29256 ,12079,12206,12175 ,0,0,0}, {29290,29174,29169 ,12209,12088,12083 ,0,0,0}, + {29288,29170,29256 ,12207,12084,12175 ,0,0,0}, {29291,29172,29174 ,12210,12086,12088 ,0,0,0}, + {29289,29168,29288 ,12208,12082,12207 ,0,0,0}, {29292,29245,29172 ,12211,12164,12086 ,0,0,0}, + {29169,29289,29290 ,12083,12208,12209 ,0,0,0}, {29179,29245,29247 ,12093,12164,12166 ,0,0,0}, + {29174,29290,29291 ,12088,12209,12210 ,0,0,0}, {29293,29177,29179 ,12212,12091,12093 ,0,0,0}, + {29172,29291,29292 ,12086,12210,12211 ,0,0,0}, {29294,29183,29177 ,12213,12097,12091 ,0,0,0}, + {29245,29292,29247 ,12164,12211,12166 ,0,0,0}, {29295,29181,29183 ,12214,12095,12097 ,0,0,0}, + {29293,29179,29247 ,12212,12093,12166 ,0,0,0}, {29296,29182,29181 ,12215,12096,12095 ,0,0,0}, + {29294,29177,29293 ,12213,12091,12212 ,0,0,0}, {29297,29239,29182 ,12216,12158,12096 ,0,0,0}, + {29183,29294,29295 ,12097,12213,12214 ,0,0,0}, {29298,29299,29300 ,12217,12218,12219 ,0,0,0}, + {29181,29295,29296 ,12095,12214,12215 ,0,0,0}, {29301,29191,29184 ,12220,12105,12098 ,0,0,0}, + {29182,29296,29297 ,12096,12215,12216 ,0,0,0}, {29302,29241,29191 ,12221,12160,12105 ,0,0,0}, + {29239,29297,29242 ,12158,12216,12161 ,0,0,0}, {29303,29190,29241 ,12222,12104,12160 ,0,0,0}, + {29184,29242,29301 ,12098,12161,12220 ,0,0,0}, {29304,29192,29190 ,12223,12106,12104 ,0,0,0}, + {29302,29191,29301 ,12221,12105,12220 ,0,0,0}, {29305,29199,29192 ,12224,12113,12106 ,0,0,0}, + {29303,29241,29302 ,12222,12160,12221 ,0,0,0}, {29306,29197,29199 ,12225,12111,12113 ,0,0,0}, + {29304,29190,29303 ,12223,12104,12222 ,0,0,0}, {29307,29195,29197 ,12226,12109,12111 ,0,0,0}, + {29192,29304,29305 ,12106,12223,12224 ,0,0,0}, {29201,29308,29202 ,12115,12227,12116 ,0,0,0}, + {29199,29305,29306 ,12113,12224,12225 ,0,0,0}, {29223,29309,29224 ,12137,12228,12138 ,0,0,0}, + {29197,29306,29307 ,12111,12225,12226 ,0,0,0}, {29223,29205,29202 ,12137,12119,12116 ,0,0,0}, + {29195,29307,29238 ,12109,12226,12157 ,0,0,0}, {29225,29206,29205 ,12139,12120,12119 ,0,0,0}, + {29201,29238,29308 ,12115,12157,12227 ,0,0,0}, {29210,29206,29310 ,12124,12120,12229 ,0,0,0}, + {29223,29202,29308 ,12137,12116,12227 ,0,0,0}, {29227,29220,29219 ,12141,12134,12133 ,0,0,0}, + {29311,29218,29220 ,12230,12132,12134 ,0,0,0}, {29210,29219,29208 ,12124,12133,12122 ,0,0,0}, + {29310,29206,29225 ,12229,12120,12139 ,0,0,0}, {29227,29212,29220 ,12141,12126,12134 ,0,0,0}, + {29219,29210,29227 ,12133,12124,12141 ,0,0,0}, {29216,29312,29214 ,12130,12231,12128 ,0,0,0}, + {29214,28767,29217 ,12128,12156,12131 ,0,0,0}, {29221,29216,29215 ,12135,12130,12129 ,0,0,0}, + {29216,29311,29312 ,12130,12230,12231 ,0,0,0}, {28769,28767,29214 ,12232,12156,12128 ,0,0,0}, + {29263,29272,29266 ,12182,12191,12185 ,0,0,0}, {29129,29128,29264 ,12043,12042,12183 ,0,0,0}, + {29313,29141,29140 ,12233,12055,12054 ,0,0,0}, {29272,29133,29262 ,12191,12047,12181 ,0,0,0}, + {29272,29263,29314 ,12191,12182,12234 ,0,0,0}, {29125,29132,29315 ,12039,12046,12235 ,0,0,0}, + {29131,29133,29272 ,12045,12047,12191 ,0,0,0}, {29273,29315,29316 ,12192,12235,12236 ,0,0,0}, + {29132,29125,29133 ,12046,12039,12047 ,0,0,0}, {29274,29316,29317 ,12193,12236,12237 ,0,0,0}, + {29315,29273,29125 ,12235,12192,12039 ,0,0,0}, {29275,29317,29318 ,12194,12237,12238 ,0,0,0}, + {29316,29274,29273 ,12236,12193,12192 ,0,0,0}, {29276,29318,29319 ,12195,12238,12239 ,0,0,0}, + {29317,29275,29274 ,12237,12194,12193 ,0,0,0}, {29277,29319,29320 ,12196,12239,12240 ,0,0,0}, + {29318,29276,29275 ,12238,12195,12194 ,0,0,0}, {29278,29320,29321 ,12197,12240,12241 ,0,0,0}, + {29319,29277,29276 ,12239,12196,12195 ,0,0,0}, {29258,29321,29279 ,12177,12241,12198 ,0,0,0}, + {29278,29277,29320 ,12197,12196,12240 ,0,0,0}, {29322,29323,29324 ,12242,12243,12244 ,0,0,0}, + {29258,29278,29321 ,12177,12197,12241 ,0,0,0}, {29282,29280,29322 ,12201,12199,12242 ,0,0,0}, + {29281,29258,29279 ,12200,12177,12198 ,0,0,0}, {29283,29322,29325 ,12202,12242,12245 ,0,0,0}, + {29282,29281,29280 ,12201,12200,12199 ,0,0,0}, {29284,29325,29326 ,12203,12245,12246 ,0,0,0}, + {29322,29283,29282 ,12242,12202,12201 ,0,0,0}, {29285,29326,29327 ,12204,12246,12247 ,0,0,0}, + {29325,29284,29283 ,12245,12203,12202 ,0,0,0}, {29286,29327,29328 ,12205,12247,12248 ,0,0,0}, + {29326,29285,29284 ,12246,12204,12203 ,0,0,0}, {29287,29328,29257 ,12206,12248,12176 ,0,0,0}, + {29286,29285,29327 ,12205,12204,12247 ,0,0,0}, {29329,29330,29331 ,12249,12250,12251 ,0,0,0}, + {29287,29286,29328 ,12206,12205,12248 ,0,0,0}, {29288,29255,29332 ,12207,12174,12252 ,0,0,0}, + {29256,29287,29257 ,12175,12206,12176 ,0,0,0}, {29289,29332,29333 ,12208,12252,12253 ,0,0,0}, + {29255,29288,29256 ,12174,12207,12175 ,0,0,0}, {29290,29333,29334 ,12209,12253,12254 ,0,0,0}, + {29332,29289,29288 ,12252,12208,12207 ,0,0,0}, {29291,29334,29335 ,12210,12254,12255 ,0,0,0}, + {29333,29290,29289 ,12253,12209,12208 ,0,0,0}, {29292,29335,29248 ,12211,12255,12167 ,0,0,0}, + {29291,29290,29334 ,12210,12209,12254 ,0,0,0}, {29336,29337,29338 ,12256,12257,12258 ,0,0,0}, + {29292,29291,29335 ,12211,12210,12255 ,0,0,0}, {29293,29249,29339 ,12212,12168,12259 ,0,0,0}, + {29247,29292,29248 ,12166,12211,12167 ,0,0,0}, {29294,29339,29340 ,12213,12259,12260 ,0,0,0}, + {29293,29247,29249 ,12212,12166,12168 ,0,0,0}, {29295,29340,29341 ,12214,12260,12261 ,0,0,0}, + {29339,29294,29293 ,12259,12213,12212 ,0,0,0}, {29296,29341,29342 ,12215,12261,12262 ,0,0,0}, + {29340,29295,29294 ,12260,12214,12213 ,0,0,0}, {29297,29342,29343 ,12216,12262,12263 ,0,0,0}, + {29341,29296,29295 ,12261,12215,12214 ,0,0,0}, {29242,29343,29344 ,12161,12263,12264 ,0,0,0}, + {29297,29296,29342 ,12216,12215,12262 ,0,0,0}, {29301,29344,29299 ,12220,12264,12218 ,0,0,0}, + {29242,29297,29343 ,12161,12216,12263 ,0,0,0}, {29302,29299,29345 ,12221,12218,12265 ,0,0,0}, + {29301,29242,29344 ,12220,12161,12264 ,0,0,0}, {29303,29345,29346 ,12222,12265,12266 ,0,0,0}, + {29299,29302,29301 ,12218,12221,12220 ,0,0,0}, {29304,29346,29347 ,12223,12266,12267 ,0,0,0}, + {29345,29303,29302 ,12265,12222,12221 ,0,0,0}, {29305,29347,29348 ,12224,12267,12268 ,0,0,0}, + {29346,29304,29303 ,12266,12223,12222 ,0,0,0}, {29306,29348,29349 ,12225,12268,12269 ,0,0,0}, + {29347,29305,29304 ,12267,12224,12223 ,0,0,0}, {29307,29349,29350 ,12226,12269,12270 ,0,0,0}, + {29348,29306,29305 ,12268,12225,12224 ,0,0,0}, {29238,29350,29351 ,12157,12270,12271 ,0,0,0}, + {29349,29307,29306 ,12269,12226,12225 ,0,0,0}, {29308,29351,29309 ,12227,12271,12228 ,0,0,0}, + {29238,29307,29350 ,12157,12226,12270 ,0,0,0}, {29352,29225,29224 ,12272,12139,12138 ,0,0,0}, + {29308,29238,29351 ,12227,12157,12271 ,0,0,0}, {29234,29353,29229 ,12149,12273,12143 ,0,0,0}, + {29223,29308,29309 ,12137,12227,12228 ,0,0,0}, {29352,29213,29310 ,12272,12127,12229 ,0,0,0}, + {29212,29354,29220 ,12126,12274,12134 ,0,0,0}, {29310,29227,29210 ,12229,12141,12124 ,0,0,0}, + {29352,29310,29225 ,12272,12229,12139 ,0,0,0}, {29355,29312,29311 ,12275,12231,12230 ,0,0,0}, + {29310,29213,29227 ,12229,12127,12141 ,0,0,0}, {28770,29312,29355 ,12276,12231,12275 ,0,0,0}, + {29312,28769,29214 ,12231,12232,12128 ,0,0,0}, {29218,29311,29216 ,12132,12230,12130 ,0,0,0}, + {29354,29355,29311 ,12274,12275,12230 ,0,0,0}, {28770,28769,29312 ,12276,12232,12231 ,0,0,0}, + {29314,29263,29128 ,12234,12182,12042 ,0,0,0}, {29260,29130,29270 ,12179,12044,12189 ,0,0,0}, + {29356,29132,29138 ,12277,12046,12052 ,0,0,0}, {29314,29131,29272 ,12234,12045,12191 ,0,0,0}, + {29314,29128,29357 ,12234,12042,12278 ,0,0,0}, {29358,29359,29360 ,12279,12280,12281 ,0,0,0}, + {29137,29131,29314 ,12051,12045,12234 ,0,0,0}, {29356,29358,29315 ,12277,12279,12235 ,0,0,0}, + {29138,29132,29131 ,12052,12046,12045 ,0,0,0}, {29358,29361,29316 ,12279,12282,12236 ,0,0,0}, + {29356,29315,29132 ,12277,12235,12046 ,0,0,0}, {29361,29362,29317 ,12282,12283,12237 ,0,0,0}, + {29358,29316,29315 ,12279,12236,12235 ,0,0,0}, {29362,29363,29318 ,12283,12284,12238 ,0,0,0}, + {29361,29317,29316 ,12282,12237,12236 ,0,0,0}, {29363,29364,29319 ,12284,12285,12239 ,0,0,0}, + {29362,29318,29317 ,12283,12238,12237 ,0,0,0}, {29364,29365,29320 ,12285,12286,12240 ,0,0,0}, + {29363,29319,29318 ,12284,12239,12238 ,0,0,0}, {29365,29366,29321 ,12286,12287,12241 ,0,0,0}, + {29364,29320,29319 ,12285,12240,12239 ,0,0,0}, {29366,29367,29279 ,12287,12288,12198 ,0,0,0}, + {29365,29321,29320 ,12286,12241,12240 ,0,0,0}, {29367,29323,29280 ,12288,12243,12199 ,0,0,0}, + {29279,29321,29366 ,12198,12241,12287 ,0,0,0}, {29368,29369,29370 ,12289,12290,12291 ,0,0,0}, + {29280,29279,29367 ,12199,12198,12288 ,0,0,0}, {29324,29368,29325 ,12244,12289,12245 ,0,0,0}, + {29323,29322,29280 ,12243,12242,12199 ,0,0,0}, {29368,29371,29326 ,12289,12292,12246 ,0,0,0}, + {29324,29325,29322 ,12244,12245,12242 ,0,0,0}, {29371,29372,29327 ,12292,12293,12247 ,0,0,0}, + {29368,29326,29325 ,12289,12246,12245 ,0,0,0}, {29372,29373,29328 ,12293,12294,12248 ,0,0,0}, + {29371,29327,29326 ,12292,12247,12246 ,0,0,0}, {29373,29374,29257 ,12294,12295,12176 ,0,0,0}, + {29372,29328,29327 ,12293,12248,12247 ,0,0,0}, {29255,29374,29375 ,12174,12295,12296 ,0,0,0}, + {29257,29328,29373 ,12176,12248,12294 ,0,0,0}, {29375,29329,29332 ,12296,12249,12252 ,0,0,0}, + {29374,29255,29257 ,12295,12174,12176 ,0,0,0}, {29329,29376,29333 ,12249,12297,12253 ,0,0,0}, + {29375,29332,29255 ,12296,12252,12174 ,0,0,0}, {29376,29377,29334 ,12297,12298,12254 ,0,0,0}, + {29329,29333,29332 ,12249,12253,12252 ,0,0,0}, {29377,29378,29335 ,12298,12299,12255 ,0,0,0}, + {29376,29334,29333 ,12297,12254,12253 ,0,0,0}, {29378,29379,29248 ,12299,12300,12167 ,0,0,0}, + {29377,29335,29334 ,12298,12255,12254 ,0,0,0}, {29379,29380,29249 ,12300,12301,12168 ,0,0,0}, + {29248,29335,29378 ,12167,12255,12299 ,0,0,0}, {29380,29336,29339 ,12301,12256,12259 ,0,0,0}, + {29249,29248,29379 ,12168,12167,12300 ,0,0,0}, {29336,29381,29340 ,12256,12302,12260 ,0,0,0}, + {29380,29339,29249 ,12301,12259,12168 ,0,0,0}, {29381,29382,29341 ,12302,12303,12261 ,0,0,0}, + {29336,29340,29339 ,12256,12260,12259 ,0,0,0}, {29382,29383,29342 ,12303,12304,12262 ,0,0,0}, + {29381,29341,29340 ,12302,12261,12260 ,0,0,0}, {29383,29384,29343 ,12304,12305,12263 ,0,0,0}, + {29382,29342,29341 ,12303,12262,12261 ,0,0,0}, {29384,29300,29344 ,12305,12219,12264 ,0,0,0}, + {29343,29342,29383 ,12263,12262,12304 ,0,0,0}, {29385,29386,29387 ,12306,12307,12308 ,0,0,0}, + {29344,29343,29384 ,12264,12263,12305 ,0,0,0}, {29298,29385,29345 ,12217,12306,12265 ,0,0,0}, + {29300,29299,29344 ,12219,12218,12264 ,0,0,0}, {29385,29388,29346 ,12306,12309,12266 ,0,0,0}, + {29298,29345,29299 ,12217,12265,12218 ,0,0,0}, {29388,29389,29347 ,12309,12310,12267 ,0,0,0}, + {29385,29346,29345 ,12306,12266,12265 ,0,0,0}, {29389,29390,29348 ,12310,12311,12268 ,0,0,0}, + {29388,29347,29346 ,12309,12267,12266 ,0,0,0}, {29390,29391,29349 ,12311,12312,12269 ,0,0,0}, + {29389,29348,29347 ,12310,12268,12267 ,0,0,0}, {29391,29392,29350 ,12312,12313,12270 ,0,0,0}, + {29390,29349,29348 ,12311,12269,12268 ,0,0,0}, {29392,29393,29351 ,12313,12314,12271 ,0,0,0}, + {29391,29350,29349 ,12312,12270,12269 ,0,0,0}, {29393,29394,29309 ,12314,12315,12228 ,0,0,0}, + {29392,29351,29350 ,12313,12271,12270 ,0,0,0}, {29394,29395,29224 ,12315,12316,12138 ,0,0,0}, + {29393,29309,29351 ,12314,12228,12271 ,0,0,0}, {29395,29226,29352 ,12316,12140,12272 ,0,0,0}, + {29224,29309,29394 ,12138,12228,12315 ,0,0,0}, {29396,28766,28628 ,12317,12318,12319 ,0,0,0}, + {29395,29352,29224 ,12316,12272,12138 ,0,0,0}, {29228,29211,29226 ,12142,12125,12140 ,0,0,0}, + {29352,29226,29213 ,12272,12140,12127 ,0,0,0}, {28761,29355,29396 ,12320,12275,12317 ,0,0,0}, + {28761,28772,29355 ,12320,12321,12275 ,0,0,0}, {29220,29354,29311 ,12134,12274,12230 ,0,0,0}, + {29230,29396,29354 ,12144,12317,12274 ,0,0,0}, {28770,29355,28772 ,12276,12275,12321 ,0,0,0}, + {29130,29357,29128 ,12044,12278,12042 ,0,0,0}, {29271,29134,29260 ,12190,12048,12179 ,0,0,0}, + {29137,29397,29398 ,12051,12322,12323 ,0,0,0}, {29357,29137,29314 ,12278,12051,12234 ,0,0,0}, + {29399,29357,29130 ,12324,12278,12044 ,0,0,0}, {29138,29398,29400 ,12052,12323,12325 ,0,0,0}, + {29357,29397,29137 ,12278,12322,12051 ,0,0,0}, {29356,29400,29359 ,12277,12325,12280 ,0,0,0}, + {29398,29138,29137 ,12323,12052,12051 ,0,0,0}, {29401,29361,29360 ,12326,12282,12281 ,0,0,0}, + {29400,29356,29138 ,12325,12277,12052 ,0,0,0}, {29402,29362,29401 ,12327,12283,12326 ,0,0,0}, + {29359,29358,29356 ,12280,12279,12277 ,0,0,0}, {29403,29404,29405 ,12328,12329,12330 ,0,0,0}, + {29360,29361,29358 ,12281,12282,12279 ,0,0,0}, {29402,29403,29363 ,12327,12328,12284 ,0,0,0}, + {29401,29362,29361 ,12326,12283,12282 ,0,0,0}, {29403,29406,29364 ,12328,12331,12285 ,0,0,0}, + {29402,29363,29362 ,12327,12284,12283 ,0,0,0}, {29406,29407,29365 ,12331,12332,12286 ,0,0,0}, + {29403,29364,29363 ,12328,12285,12284 ,0,0,0}, {29407,29408,29366 ,12332,12333,12287 ,0,0,0}, + {29406,29365,29364 ,12331,12286,12285 ,0,0,0}, {29408,29409,29367 ,12333,12334,12288 ,0,0,0}, + {29407,29366,29365 ,12332,12287,12286 ,0,0,0}, {29323,29409,29410 ,12243,12334,12335 ,0,0,0}, + {29408,29367,29366 ,12333,12288,12287 ,0,0,0}, {29324,29410,29369 ,12244,12335,12290 ,0,0,0}, + {29409,29323,29367 ,12334,12243,12288 ,0,0,0}, {29411,29412,29413 ,12336,12337,12338 ,0,0,0}, + {29410,29324,29323 ,12335,12244,12243 ,0,0,0}, {29370,29411,29371 ,12291,12336,12292 ,0,0,0}, + {29369,29368,29324 ,12290,12289,12244 ,0,0,0}, {29411,29414,29372 ,12336,12339,12293 ,0,0,0}, + {29370,29371,29368 ,12291,12292,12289 ,0,0,0}, {29414,29415,29373 ,12339,12340,12294 ,0,0,0}, + {29411,29372,29371 ,12336,12293,12292 ,0,0,0}, {29374,29415,29416 ,12295,12340,12341 ,0,0,0}, + {29414,29373,29372 ,12339,12294,12293 ,0,0,0}, {29375,29416,29330 ,12296,12341,12250 ,0,0,0}, + {29374,29373,29415 ,12295,12294,12340 ,0,0,0}, {29417,29418,29419 ,12342,12343,12344 ,0,0,0}, + {29416,29375,29374 ,12341,12296,12295 ,0,0,0}, {29331,29417,29376 ,12251,12342,12297 ,0,0,0}, + {29330,29329,29375 ,12250,12249,12296 ,0,0,0}, {29417,29420,29377 ,12342,12345,12298 ,0,0,0}, + {29331,29376,29329 ,12251,12297,12249 ,0,0,0}, {29420,29421,29378 ,12345,12346,12299 ,0,0,0}, + {29417,29377,29376 ,12342,12298,12297 ,0,0,0}, {29421,29422,29379 ,12346,12347,12300 ,0,0,0}, + {29420,29378,29377 ,12345,12299,12298 ,0,0,0}, {29380,29422,29337 ,12301,12347,12257 ,0,0,0}, + {29379,29378,29421 ,12300,12299,12346 ,0,0,0}, {29423,29424,29425 ,12348,12349,12350 ,0,0,0}, + {29422,29380,29379 ,12347,12301,12300 ,0,0,0}, {29338,29423,29381 ,12258,12348,12302 ,0,0,0}, + {29337,29336,29380 ,12257,12256,12301 ,0,0,0}, {29423,29426,29382 ,12348,12351,12303 ,0,0,0}, + {29338,29381,29336 ,12258,12302,12256 ,0,0,0}, {29426,29427,29383 ,12351,12352,12304 ,0,0,0}, + {29423,29382,29381 ,12348,12303,12302 ,0,0,0}, {29427,29428,29384 ,12352,12353,12305 ,0,0,0}, + {29426,29383,29382 ,12351,12304,12303 ,0,0,0}, {29300,29428,29429 ,12219,12353,12354 ,0,0,0}, + {29427,29384,29383 ,12352,12305,12304 ,0,0,0}, {29298,29429,29386 ,12217,12354,12307 ,0,0,0}, + {29428,29300,29384 ,12353,12219,12305 ,0,0,0}, {29430,29388,29387 ,12355,12309,12308 ,0,0,0}, + {29429,29298,29300 ,12354,12217,12219 ,0,0,0}, {29431,29432,29433 ,12356,12357,12358 ,0,0,0}, + {29386,29385,29298 ,12307,12306,12217 ,0,0,0}, {29430,29431,29389 ,12355,12356,12310 ,0,0,0}, + {29387,29388,29385 ,12308,12309,12306 ,0,0,0}, {29431,29434,29390 ,12356,12359,12311 ,0,0,0}, + {29430,29389,29388 ,12355,12310,12309 ,0,0,0}, {29434,29435,29391 ,12359,12360,12312 ,0,0,0}, + {29431,29390,29389 ,12356,12311,12310 ,0,0,0}, {29435,29436,29392 ,12360,12361,12313 ,0,0,0}, + {29434,29391,29390 ,12359,12312,12311 ,0,0,0}, {29436,29437,29393 ,12361,12362,12314 ,0,0,0}, + {29435,29392,29391 ,12360,12313,12312 ,0,0,0}, {29437,29438,29394 ,12362,12363,12315 ,0,0,0}, + {29436,29393,29392 ,12361,12314,12313 ,0,0,0}, {29438,29439,29395 ,12363,12364,12316 ,0,0,0}, + {29437,29394,29393 ,12362,12315,12314 ,0,0,0}, {29226,29439,29228 ,12140,12364,12142 ,0,0,0}, + {29395,29394,29438 ,12316,12315,12363 ,0,0,0}, {29233,29228,29439 ,12147,12142,12364 ,0,0,0}, + {29226,29395,29439 ,12140,12316,12364 ,0,0,0}, {29230,29353,29396 ,12144,12273,12317 ,0,0,0}, + {29354,29396,29355 ,12274,12317,12275 ,0,0,0}, {29212,29230,29354 ,12126,12144,12274 ,0,0,0}, + {29229,29353,29230 ,12143,12273,12144 ,0,0,0}, {28761,29396,28628 ,12320,12317,12319 ,0,0,0}, + {29134,29399,29130 ,12048,12324,12044 ,0,0,0}, {29142,29136,29135 ,12056,12050,12049 ,0,0,0}, + {29397,29440,29441 ,12322,12365,12366 ,0,0,0}, {29399,29397,29357 ,12324,12322,12278 ,0,0,0}, + {29134,29442,29399 ,12048,12367,12324 ,0,0,0}, {29398,29441,29443 ,12323,12366,12368 ,0,0,0}, + {29399,29440,29397 ,12324,12365,12322 ,0,0,0}, {29400,29443,29444 ,12325,12368,12369 ,0,0,0}, + {29397,29441,29398 ,12322,12366,12323 ,0,0,0}, {29359,29444,29445 ,12280,12369,12370 ,0,0,0}, + {29398,29443,29400 ,12323,12368,12325 ,0,0,0}, {29360,29445,29446 ,12281,12370,12371 ,0,0,0}, + {29400,29444,29359 ,12325,12369,12280 ,0,0,0}, {29401,29446,29447 ,12326,12371,12372 ,0,0,0}, + {29359,29445,29360 ,12280,12370,12281 ,0,0,0}, {29402,29447,29404 ,12327,12372,12329 ,0,0,0}, + {29446,29401,29360 ,12371,12326,12281 ,0,0,0}, {29448,29406,29405 ,12373,12331,12330 ,0,0,0}, + {29447,29402,29401 ,12372,12327,12326 ,0,0,0}, {29449,29450,29448 ,12374,12375,12373 ,0,0,0}, + {29404,29403,29402 ,12329,12328,12327 ,0,0,0}, {29448,29450,29407 ,12373,12375,12332 ,0,0,0}, + {29405,29406,29403 ,12330,12331,12328 ,0,0,0}, {29450,29451,29408 ,12375,12376,12333 ,0,0,0}, + {29448,29407,29406 ,12373,12332,12331 ,0,0,0}, {29409,29451,29452 ,12334,12376,12377 ,0,0,0}, + {29450,29408,29407 ,12375,12333,12332 ,0,0,0}, {29410,29452,29453 ,12335,12377,12378 ,0,0,0}, + {29408,29451,29409 ,12333,12376,12334 ,0,0,0}, {29369,29453,29454 ,12290,12378,12379 ,0,0,0}, + {29409,29452,29410 ,12334,12377,12335 ,0,0,0}, {29370,29454,29412 ,12291,12379,12337 ,0,0,0}, + {29453,29369,29410 ,12378,12290,12335 ,0,0,0}, {29455,29456,29413 ,12380,12381,12338 ,0,0,0}, + {29454,29370,29369 ,12379,12291,12290 ,0,0,0}, {29413,29456,29414 ,12338,12381,12339 ,0,0,0}, + {29412,29411,29370 ,12337,12336,12291 ,0,0,0}, {29456,29457,29415 ,12381,12382,12340 ,0,0,0}, + {29413,29414,29411 ,12338,12339,12336 ,0,0,0}, {29416,29457,29458 ,12341,12382,12383 ,0,0,0}, + {29456,29415,29414 ,12381,12340,12339 ,0,0,0}, {29330,29458,29459 ,12250,12383,12384 ,0,0,0}, + {29415,29457,29416 ,12340,12382,12341 ,0,0,0}, {29331,29459,29418 ,12251,12384,12343 ,0,0,0}, + {29458,29330,29416 ,12383,12250,12341 ,0,0,0}, {29460,29461,29419 ,12385,12386,12344 ,0,0,0}, + {29459,29331,29330 ,12384,12251,12250 ,0,0,0}, {29419,29461,29420 ,12344,12386,12345 ,0,0,0}, + {29418,29417,29331 ,12343,12342,12251 ,0,0,0}, {29461,29462,29421 ,12386,12387,12346 ,0,0,0}, + {29419,29420,29417 ,12344,12345,12342 ,0,0,0}, {29422,29462,29463 ,12347,12387,12388 ,0,0,0}, + {29461,29421,29420 ,12386,12346,12345 ,0,0,0}, {29337,29463,29464 ,12257,12388,12389 ,0,0,0}, + {29421,29462,29422 ,12346,12387,12347 ,0,0,0}, {29338,29464,29424 ,12258,12389,12349 ,0,0,0}, + {29463,29337,29422 ,12388,12257,12347 ,0,0,0}, {29465,29466,29425 ,12390,12391,12350 ,0,0,0}, + {29464,29338,29337 ,12389,12258,12257 ,0,0,0}, {29425,29466,29426 ,12350,12391,12351 ,0,0,0}, + {29424,29423,29338 ,12349,12348,12258 ,0,0,0}, {29466,29467,29427 ,12391,12392,12352 ,0,0,0}, + {29425,29426,29423 ,12350,12351,12348 ,0,0,0}, {29428,29467,29468 ,12353,12392,12393 ,0,0,0}, + {29466,29427,29426 ,12391,12352,12351 ,0,0,0}, {29429,29468,29469 ,12354,12393,12394 ,0,0,0}, + {29427,29467,29428 ,12352,12392,12353 ,0,0,0}, {29386,29469,29470 ,12307,12394,12395 ,0,0,0}, + {29428,29468,29429 ,12353,12393,12354 ,0,0,0}, {29387,29470,29471 ,12308,12395,12396 ,0,0,0}, + {29429,29469,29386 ,12354,12394,12307 ,0,0,0}, {29430,29471,29432 ,12355,12396,12357 ,0,0,0}, + {29470,29387,29386 ,12395,12308,12307 ,0,0,0}, {29472,29434,29433 ,12397,12359,12358 ,0,0,0}, + {29471,29430,29387 ,12396,12355,12308 ,0,0,0}, {29473,29474,29472 ,12398,12399,12397 ,0,0,0}, + {29432,29431,29430 ,12357,12356,12355 ,0,0,0}, {29472,29474,29435 ,12397,12399,12360 ,0,0,0}, + {29433,29434,29431 ,12358,12359,12356 ,0,0,0}, {29474,29475,29436 ,12399,12400,12361 ,0,0,0}, + {29472,29435,29434 ,12397,12360,12359 ,0,0,0}, {29475,29476,29437 ,12400,12401,12362 ,0,0,0}, + {29474,29436,29435 ,12399,12361,12360 ,0,0,0}, {29476,29477,29438 ,12401,12402,12363 ,0,0,0}, + {29475,29437,29436 ,12400,12362,12361 ,0,0,0}, {29439,29477,29233 ,12364,12402,12147 ,0,0,0}, + {29476,29438,29437 ,12401,12363,12362 ,0,0,0}, {29233,29478,29228 ,12147,12403,12142 ,0,0,0}, + {29438,29477,29439 ,12363,12402,12364 ,0,0,0}, {28633,29353,29234 ,12404,12273,12149 ,0,0,0}, + {29353,28766,29396 ,12273,12318,12317 ,0,0,0}, {29211,29229,29230 ,12125,12143,12144 ,0,0,0}, + {29478,29234,29229 ,12403,12149,12143 ,0,0,0}, {28633,28766,29353 ,12404,12318,12273 ,0,0,0}, + {29136,29442,29134 ,12050,12367,12048 ,0,0,0}, {29479,29141,29142 ,12405,12055,12056 ,0,0,0}, + {29480,29440,29442 ,12406,12365,12367 ,0,0,0}, {29442,29440,29399 ,12367,12365,12324 ,0,0,0}, + {29442,29313,29480 ,12367,12233,12406 ,0,0,0}, {29481,29441,29440 ,12407,12366,12365 ,0,0,0}, + {29440,29480,29481 ,12365,12406,12407 ,0,0,0}, {29482,29443,29441 ,12408,12368,12366 ,0,0,0}, + {29441,29481,29482 ,12366,12407,12408 ,0,0,0}, {29483,29444,29443 ,12409,12369,12368 ,0,0,0}, + {29443,29482,29483 ,12368,12408,12409 ,0,0,0}, {29484,29445,29444 ,12410,12370,12369 ,0,0,0}, + {29444,29483,29484 ,12369,12409,12410 ,0,0,0}, {29485,29446,29445 ,12411,12371,12370 ,0,0,0}, + {29445,29484,29485 ,12370,12410,12411 ,0,0,0}, {29486,29447,29446 ,12412,12372,12371 ,0,0,0}, + {29446,29485,29486 ,12371,12411,12412 ,0,0,0}, {29487,29404,29447 ,12413,12329,12372 ,0,0,0}, + {29447,29486,29487 ,12372,12412,12413 ,0,0,0}, {29488,29405,29404 ,12414,12330,12329 ,0,0,0}, + {29404,29487,29488 ,12329,12413,12414 ,0,0,0}, {29489,29448,29405 ,12415,12373,12330 ,0,0,0}, + {29488,29489,29405 ,12414,12415,12330 ,0,0,0}, {29490,29491,29492 ,12416,12417,12418 ,0,0,0}, + {29489,29449,29448 ,12415,12374,12373 ,0,0,0}, {29493,29451,29450 ,12419,12376,12375 ,0,0,0}, + {29449,29493,29450 ,12374,12419,12375 ,0,0,0}, {29494,29452,29451 ,12420,12377,12376 ,0,0,0}, + {29451,29493,29494 ,12376,12419,12420 ,0,0,0}, {29495,29453,29452 ,12421,12378,12377 ,0,0,0}, + {29452,29494,29495 ,12377,12420,12421 ,0,0,0}, {29496,29454,29453 ,12422,12379,12378 ,0,0,0}, + {29453,29495,29496 ,12378,12421,12422 ,0,0,0}, {29497,29412,29454 ,12423,12337,12379 ,0,0,0}, + {29454,29496,29497 ,12379,12422,12423 ,0,0,0}, {29498,29413,29412 ,12424,12338,12337 ,0,0,0}, + {29497,29498,29412 ,12423,12424,12337 ,0,0,0}, {29499,29455,29500 ,12425,12380,12426 ,0,0,0}, + {29498,29455,29413 ,12424,12380,12338 ,0,0,0}, {29499,29457,29456 ,12425,12382,12381 ,0,0,0}, + {29455,29499,29456 ,12380,12425,12381 ,0,0,0}, {29501,29458,29457 ,12427,12383,12382 ,0,0,0}, + {29457,29499,29501 ,12382,12425,12427 ,0,0,0}, {29502,29459,29458 ,12428,12384,12383 ,0,0,0}, + {29458,29501,29502 ,12383,12427,12428 ,0,0,0}, {29503,29418,29459 ,12429,12343,12384 ,0,0,0}, + {29459,29502,29503 ,12384,12428,12429 ,0,0,0}, {29504,29419,29418 ,12430,12344,12343 ,0,0,0}, + {29503,29504,29418 ,12429,12430,12343 ,0,0,0}, {29505,29506,29507 ,12431,12432,12433 ,0,0,0}, + {29504,29460,29419 ,12430,12385,12344 ,0,0,0}, {29508,29462,29461 ,12434,12387,12386 ,0,0,0}, + {29460,29508,29461 ,12385,12434,12386 ,0,0,0}, {29509,29463,29462 ,12435,12388,12387 ,0,0,0}, + {29462,29508,29509 ,12387,12434,12435 ,0,0,0}, {29510,29464,29463 ,12436,12389,12388 ,0,0,0}, + {29463,29509,29510 ,12388,12435,12436 ,0,0,0}, {29511,29424,29464 ,12437,12349,12389 ,0,0,0}, + {29464,29510,29511 ,12389,12436,12437 ,0,0,0}, {29512,29425,29424 ,12438,12350,12349 ,0,0,0}, + {29511,29512,29424 ,12437,12438,12349 ,0,0,0}, {29466,29513,29467 ,12391,12439,12392 ,0,0,0}, + {29512,29465,29425 ,12438,12390,12350 ,0,0,0}, {29514,29515,29513 ,12440,12441,12439 ,0,0,0}, + {29465,29513,29466 ,12390,12439,12391 ,0,0,0}, {29515,29468,29467 ,12441,12393,12392 ,0,0,0}, + {29467,29513,29515 ,12392,12439,12441 ,0,0,0}, {29516,29469,29468 ,12442,12394,12393 ,0,0,0}, + {29468,29515,29516 ,12393,12441,12442 ,0,0,0}, {29517,29470,29469 ,12443,12395,12394 ,0,0,0}, + {29469,29516,29517 ,12394,12442,12443 ,0,0,0}, {29518,29471,29470 ,12444,12396,12395 ,0,0,0}, + {29470,29517,29518 ,12395,12443,12444 ,0,0,0}, {29519,29432,29471 ,12445,12357,12396 ,0,0,0}, + {29471,29518,29519 ,12396,12444,12445 ,0,0,0}, {29520,29433,29432 ,12446,12358,12357 ,0,0,0}, + {29432,29519,29520 ,12357,12445,12446 ,0,0,0}, {29521,29472,29433 ,12447,12397,12358 ,0,0,0}, + {29520,29521,29433 ,12446,12447,12358 ,0,0,0}, {29474,29522,29475 ,12399,12448,12400 ,0,0,0}, + {29521,29473,29472 ,12447,12398,12397 ,0,0,0}, {29475,29523,29476 ,12400,12449,12401 ,0,0,0}, + {29473,29522,29474 ,12398,12448,12399 ,0,0,0}, {29476,29524,29477 ,12401,12450,12402 ,0,0,0}, + {29522,29523,29475 ,12448,12449,12400 ,0,0,0}, {29477,29231,29233 ,12402,12145,12147 ,0,0,0}, + {29523,29524,29476 ,12449,12450,12401 ,0,0,0}, {29232,29236,29235 ,12146,12151,12150 ,0,0,0}, + {29524,29231,29477 ,12450,12145,12402 ,0,0,0}, {29232,29478,29233 ,12146,12403,12147 ,0,0,0}, + {28815,28633,29234 ,12451,12404,12149 ,0,0,0}, {29228,29478,29229 ,12142,12403,12143 ,0,0,0}, + {29478,29232,29235 ,12403,12146,12150 ,0,0,0}, {28630,28815,29234 ,12148,12451,12149 ,0,0,0}, + {29141,29313,29136 ,12055,12233,12050 ,0,0,0}, {29479,29144,29139 ,12405,12058,12053 ,0,0,0}, + {29480,29313,29525 ,12406,12233,12452 ,0,0,0}, {29136,29313,29442 ,12050,12233,12367 ,0,0,0}, + {29313,29140,29525 ,12233,12054,12452 ,0,0,0}, {29481,29480,29526 ,12407,12406,12453 ,0,0,0}, + {29480,29525,29526 ,12406,12452,12453 ,0,0,0}, {29482,29481,29527 ,12408,12407,12454 ,0,0,0}, + {29481,29526,29527 ,12407,12453,12454 ,0,0,0}, {29483,29482,29528 ,12409,12408,12455 ,0,0,0}, + {29482,29527,29528 ,12408,12454,12455 ,0,0,0}, {29484,29483,29529 ,12410,12409,12456 ,0,0,0}, + {29483,29528,29529 ,12409,12455,12456 ,0,0,0}, {29485,29484,29530 ,12411,12410,12457 ,0,0,0}, + {29484,29529,29530 ,12410,12456,12457 ,0,0,0}, {29486,29485,29531 ,12412,12411,12458 ,0,0,0}, + {29485,29530,29531 ,12411,12457,12458 ,0,0,0}, {29487,29486,29532 ,12413,12412,12459 ,0,0,0}, + {29486,29531,29532 ,12412,12458,12459 ,0,0,0}, {29488,29487,29533 ,12414,12413,12460 ,0,0,0}, + {29487,29532,29533 ,12413,12459,12460 ,0,0,0}, {29489,29488,29534 ,12415,12414,12461 ,0,0,0}, + {29488,29533,29534 ,12414,12460,12461 ,0,0,0}, {29449,29489,29535 ,12374,12415,12462 ,0,0,0}, + {29489,29534,29535 ,12415,12461,12462 ,0,0,0}, {29493,29449,29490 ,12419,12374,12416 ,0,0,0}, + {29535,29490,29449 ,12462,12416,12374 ,0,0,0}, {29494,29493,29492 ,12420,12419,12418 ,0,0,0}, + {29493,29490,29492 ,12419,12416,12418 ,0,0,0}, {29495,29494,29536 ,12421,12420,12463 ,0,0,0}, + {29494,29492,29536 ,12420,12418,12463 ,0,0,0}, {29496,29495,29537 ,12422,12421,12464 ,0,0,0}, + {29495,29536,29537 ,12421,12463,12464 ,0,0,0}, {29497,29496,29538 ,12423,12422,12465 ,0,0,0}, + {29496,29537,29538 ,12422,12464,12465 ,0,0,0}, {29498,29497,29539 ,12424,12423,12466 ,0,0,0}, + {29497,29538,29539 ,12423,12465,12466 ,0,0,0}, {29455,29498,29540 ,12380,12424,12467 ,0,0,0}, + {29498,29539,29540 ,12424,12466,12467 ,0,0,0}, {29540,29541,29500 ,12467,12468,12426 ,0,0,0}, + {29540,29500,29455 ,12467,12426,12380 ,0,0,0}, {29501,29499,29542 ,12427,12425,12469 ,0,0,0}, + {29499,29500,29542 ,12425,12426,12469 ,0,0,0}, {29502,29501,29543 ,12428,12427,12470 ,0,0,0}, + {29501,29542,29543 ,12427,12469,12470 ,0,0,0}, {29503,29502,29544 ,12429,12428,12471 ,0,0,0}, + {29502,29543,29544 ,12428,12470,12471 ,0,0,0}, {29504,29503,29545 ,12430,12429,12472 ,0,0,0}, + {29503,29544,29545 ,12429,12471,12472 ,0,0,0}, {29460,29504,29546 ,12385,12430,12473 ,0,0,0}, + {29504,29545,29546 ,12430,12472,12473 ,0,0,0}, {29508,29460,29505 ,12434,12385,12431 ,0,0,0}, + {29546,29505,29460 ,12473,12431,12385 ,0,0,0}, {29509,29508,29507 ,12435,12434,12433 ,0,0,0}, + {29508,29505,29507 ,12434,12431,12433 ,0,0,0}, {29510,29509,29547 ,12436,12435,12474 ,0,0,0}, + {29509,29507,29547 ,12435,12433,12474 ,0,0,0}, {29511,29510,29548 ,12437,12436,12475 ,0,0,0}, + {29510,29547,29548 ,12436,12474,12475 ,0,0,0}, {29512,29511,29549 ,12438,12437,12476 ,0,0,0}, + {29511,29548,29549 ,12437,12475,12476 ,0,0,0}, {29465,29512,29550 ,12390,12438,12477 ,0,0,0}, + {29512,29549,29550 ,12438,12476,12477 ,0,0,0}, {29513,29465,29551 ,12439,12390,12478 ,0,0,0}, + {29465,29550,29551 ,12390,12477,12478 ,0,0,0}, {29514,29551,29552 ,12440,12478,12479 ,0,0,0}, + {29551,29514,29513 ,12478,12440,12439 ,0,0,0}, {29516,29515,29553 ,12442,12441,12480 ,0,0,0}, + {29515,29514,29553 ,12441,12440,12480 ,0,0,0}, {29517,29516,29554 ,12443,12442,12481 ,0,0,0}, + {29516,29553,29554 ,12442,12480,12481 ,0,0,0}, {29518,29517,29555 ,12444,12443,12482 ,0,0,0}, + {29517,29554,29555 ,12443,12481,12482 ,0,0,0}, {29519,29518,29556 ,12445,12444,12483 ,0,0,0}, + {29518,29555,29556 ,12444,12482,12483 ,0,0,0}, {29520,29519,29557 ,12446,12445,12484 ,0,0,0}, + {29519,29556,29557 ,12445,12483,12484 ,0,0,0}, {29521,29520,29558 ,12447,12446,12485 ,0,0,0}, + {29520,29557,29558 ,12446,12484,12485 ,0,0,0}, {29473,29521,29559 ,12398,12447,12486 ,0,0,0}, + {29521,29558,29559 ,12447,12485,12486 ,0,0,0}, {29522,29473,29560 ,12448,12398,12487 ,0,0,0}, + {29473,29559,29560 ,12398,12486,12487 ,0,0,0}, {29523,29522,29561 ,12449,12448,12488 ,0,0,0}, + {29522,29560,29561 ,12448,12487,12488 ,0,0,0}, {29524,29523,29562 ,12450,12449,12489 ,0,0,0}, + {29523,29561,29562 ,12449,12488,12489 ,0,0,0}, {29231,29524,29563 ,12145,12450,12490 ,0,0,0}, + {29524,29562,29563 ,12450,12489,12490 ,0,0,0}, {29564,29232,29231 ,12491,12146,12145 ,0,0,0}, + {29563,29564,29231 ,12490,12491,12145 ,0,0,0}, {29478,29235,29234 ,12403,12150,12149 ,0,0,0}, + {29564,29236,29232 ,12491,12151,12146 ,0,0,0}, {28630,29235,28985 ,12148,12150,12152 ,0,0,0}, + {29139,29141,29479 ,12053,12055,12405 ,0,0,0}, {29148,29145,29139 ,12062,12059,12053 ,0,0,0}, + {29145,29565,29140 ,12059,12492,12054 ,0,0,0}, {29140,29565,29525 ,12054,12492,12452 ,0,0,0}, + {29565,29566,29525 ,12492,12493,12452 ,0,0,0}, {29525,29566,29526 ,12452,12493,12453 ,0,0,0}, + {29566,29567,29526 ,12493,12494,12453 ,0,0,0}, {29526,29567,29527 ,12453,12494,12454 ,0,0,0}, + {29567,29568,29527 ,12494,12495,12454 ,0,0,0}, {29527,29568,29528 ,12454,12495,12455 ,0,0,0}, + {29568,29569,29528 ,12495,12496,12455 ,0,0,0}, {29528,29569,29529 ,12455,12496,12456 ,0,0,0}, + {29569,29570,29529 ,12496,12497,12456 ,0,0,0}, {29529,29570,29530 ,12456,12497,12457 ,0,0,0}, + {29570,29571,29530 ,12497,12498,12457 ,0,0,0}, {29530,29571,29531 ,12457,12498,12458 ,0,0,0}, + {29571,29572,29531 ,12498,12499,12458 ,0,0,0}, {29572,29573,29532 ,12499,12500,12459 ,0,0,0}, + {29572,29532,29531 ,12499,12459,12458 ,0,0,0}, {29573,29574,29533 ,12500,12501,12460 ,0,0,0}, + {29573,29533,29532 ,12500,12460,12459 ,0,0,0}, {29574,29575,29534 ,12501,12502,12461 ,0,0,0}, + {29574,29534,29533 ,12501,12461,12460 ,0,0,0}, {29575,29576,29535 ,12502,12503,12462 ,0,0,0}, + {29575,29535,29534 ,12502,12462,12461 ,0,0,0}, {29576,29577,29490 ,12503,12504,12416 ,0,0,0}, + {29576,29490,29535 ,12503,12416,12462 ,0,0,0}, {29491,29490,29577 ,12417,12416,12504 ,0,0,0}, + {29491,29578,29492 ,12417,12505,12418 ,0,0,0}, {29492,29578,29536 ,12418,12505,12463 ,0,0,0}, + {29578,29579,29536 ,12505,12506,12463 ,0,0,0}, {29536,29579,29537 ,12463,12506,12464 ,0,0,0}, + {29579,29580,29537 ,12506,12507,12464 ,0,0,0}, {29580,29581,29538 ,12507,12508,12465 ,0,0,0}, + {29580,29538,29537 ,12507,12465,12464 ,0,0,0}, {29581,29582,29539 ,12508,12509,12466 ,0,0,0}, + {29581,29539,29538 ,12508,12466,12465 ,0,0,0}, {29582,29541,29540 ,12509,12468,12467 ,0,0,0}, + {29582,29540,29539 ,12509,12467,12466 ,0,0,0}, {29541,29583,29500 ,12468,12510,12426 ,0,0,0}, + {29583,29584,29500 ,12510,12511,12426 ,0,0,0}, {29500,29584,29542 ,12426,12511,12469 ,0,0,0}, + {29584,29585,29542 ,12511,12512,12469 ,0,0,0}, {29542,29585,29543 ,12469,12512,12470 ,0,0,0}, + {29585,29586,29543 ,12512,12513,12470 ,0,0,0}, {29586,29587,29544 ,12513,12514,12471 ,0,0,0}, + {29586,29544,29543 ,12513,12471,12470 ,0,0,0}, {29587,29588,29545 ,12514,12515,12472 ,0,0,0}, + {29587,29545,29544 ,12514,12472,12471 ,0,0,0}, {29588,29589,29546 ,12515,12516,12473 ,0,0,0}, + {29588,29546,29545 ,12515,12473,12472 ,0,0,0}, {29589,29590,29505 ,12516,12517,12431 ,0,0,0}, + {29589,29505,29546 ,12516,12431,12473 ,0,0,0}, {29506,29505,29590 ,12432,12431,12517 ,0,0,0}, + {29506,29591,29507 ,12432,12518,12433 ,0,0,0}, {29507,29591,29547 ,12433,12518,12474 ,0,0,0}, + {29591,29592,29547 ,12518,12519,12474 ,0,0,0}, {29592,29593,29548 ,12519,12520,12475 ,0,0,0}, + {29592,29548,29547 ,12519,12475,12474 ,0,0,0}, {29593,29594,29549 ,12520,12521,12476 ,0,0,0}, + {29593,29549,29548 ,12520,12476,12475 ,0,0,0}, {29594,29595,29550 ,12521,12522,12477 ,0,0,0}, + {29594,29550,29549 ,12521,12477,12476 ,0,0,0}, {29595,29552,29551 ,12522,12479,12478 ,0,0,0}, + {29595,29551,29550 ,12522,12478,12477 ,0,0,0}, {29552,29596,29514 ,12479,12523,12440 ,0,0,0}, + {29596,29597,29514 ,12523,12524,12440 ,0,0,0}, {29514,29597,29553 ,12440,12524,12480 ,0,0,0}, + {29597,29598,29553 ,12524,12525,12480 ,0,0,0}, {29553,29598,29554 ,12480,12525,12481 ,0,0,0}, + {29598,29599,29554 ,12525,12526,12481 ,0,0,0}, {29554,29599,29555 ,12481,12526,12482 ,0,0,0}, + {29599,29600,29555 ,12526,12527,12482 ,0,0,0}, {29600,29601,29556 ,12527,12528,12483 ,0,0,0}, + {29600,29556,29555 ,12527,12483,12482 ,0,0,0}, {29601,29602,29557 ,12528,12529,12484 ,0,0,0}, + {29601,29557,29556 ,12528,12484,12483 ,0,0,0}, {29602,29603,29558 ,12529,12530,12485 ,0,0,0}, + {29602,29558,29557 ,12529,12485,12484 ,0,0,0}, {29603,29604,29559 ,12530,12531,12486 ,0,0,0}, + {29603,29559,29558 ,12530,12486,12485 ,0,0,0}, {29604,29605,29560 ,12531,12532,12487 ,0,0,0}, + {29604,29560,29559 ,12531,12487,12486 ,0,0,0}, {29605,29606,29561 ,12532,12533,12488 ,0,0,0}, + {29605,29561,29560 ,12532,12488,12487 ,0,0,0}, {29606,29607,29562 ,12533,12534,12489 ,0,0,0}, + {29606,29562,29561 ,12533,12489,12488 ,0,0,0}, {29607,29608,29563 ,12534,12535,12490 ,0,0,0}, + {29607,29563,29562 ,12534,12490,12489 ,0,0,0}, {29608,29609,29564 ,12535,12536,12491 ,0,0,0}, + {29608,29564,29563 ,12535,12491,12490 ,0,0,0}, {29237,29564,29609 ,12154,12491,12536 ,0,0,0}, + {29564,29237,29236 ,12491,12154,12151 ,0,0,0}, {28638,29236,29237 ,12153,12151,12154 ,0,0,0}, + {29610,29611,29581 ,12537,12538,12539 ,0,0,0}, {29581,29580,29610 ,12539,12540,12537 ,0,0,0}, + {29612,29613,29614 ,12541,12542,12543 ,0,0,0}, {29615,29579,29578 ,12544,12545,12546 ,0,0,0}, + {29580,29579,29616 ,12540,12545,12547 ,0,0,0}, {29615,29616,29579 ,12544,12547,12545 ,0,0,0}, + {29491,29577,29617 ,12548,12549,12550 ,0,0,0}, {29618,29491,29617 ,12551,12548,12550 ,0,0,0}, + {29578,29491,29618 ,12546,12548,12551 ,0,0,0}, {29617,29576,29619 ,12550,12552,12553 ,0,0,0}, + {29578,29618,29615 ,12546,12551,12544 ,0,0,0}, {29617,29577,29576 ,12550,12549,12552 ,0,0,0}, + {29616,29610,29580 ,12547,12537,12540 ,0,0,0}, {29620,29575,29574 ,12554,12555,12556 ,0,0,0}, + {29620,29619,29575 ,12554,12553,12555 ,0,0,0}, {29621,29620,29574 ,12557,12554,12556 ,0,0,0}, + {29622,29623,29624 ,12558,12559,12560 ,0,0,0}, {29625,29621,29573 ,12561,12557,12562 ,0,0,0}, + {29572,29625,29573 ,12563,12561,12562 ,0,0,0}, {29626,29572,29571 ,12564,12563,12565 ,0,0,0}, + {29625,29572,29626 ,12561,12563,12564 ,0,0,0}, {29627,29626,29571 ,12566,12564,12565 ,0,0,0}, + {29573,29621,29574 ,12562,12557,12556 ,0,0,0}, {29619,29576,29575 ,12553,12552,12555 ,0,0,0}, + {29628,29569,29629 ,12567,12568,12569 ,0,0,0}, {29570,29628,29627 ,12570,12567,12566 ,0,0,0}, + {29568,29630,29629 ,12571,12572,12569 ,0,0,0}, {29570,29569,29628 ,12570,12568,12567 ,0,0,0}, + {29630,29567,29631 ,12572,12573,12574 ,0,0,0}, {29567,29630,29568 ,12573,12572,12571 ,0,0,0}, + {29631,29566,29632 ,12574,12575,12576 ,0,0,0}, {29569,29568,29629 ,12568,12571,12569 ,0,0,0}, + {29567,29566,29631 ,12573,12575,12574 ,0,0,0}, {29631,29633,29634 ,12574,12577,12578 ,0,0,0}, + {29265,29635,29269 ,12579,12580,12188 ,0,0,0}, {29636,29637,29638 ,12581,12582,12583 ,0,0,0}, + {29635,29639,29269 ,12580,12584,12188 ,0,0,0}, {29640,29641,29642 ,12585,12586,12587 ,0,0,0}, + {29635,29265,29640 ,12580,12579,12585 ,0,0,0}, {29632,29566,29565 ,12576,12575,12588 ,0,0,0}, + {29634,29643,29644 ,12578,12589,12590 ,0,0,0}, {29645,29646,29644 ,12591,12592,12590 ,0,0,0}, + {29644,29643,29647 ,12590,12589,12593 ,0,0,0}, {29565,29145,29648 ,12588,12594,12595 ,0,0,0}, + {29649,29650,29651 ,12596,12597,12598 ,0,0,0}, {29650,29652,29653 ,12597,12599,12600 ,0,0,0}, + {29652,29654,29653 ,12599,12601,12600 ,0,0,0}, {29655,29651,29656 ,12602,12598,12603 ,0,0,0}, + {29657,29656,29143 ,12604,12603,12057 ,0,0,0}, {29145,29656,29648 ,12594,12603,12595 ,0,0,0}, + {29656,29148,29143 ,12603,12605,12057 ,0,0,0}, {29657,29655,29656 ,12604,12602,12603 ,0,0,0}, + {29637,29658,29659 ,12582,12606,12607 ,0,0,0}, {29570,29627,29571 ,12570,12566,12565 ,0,0,0}, + {29611,29582,29581 ,12538,12608,12539 ,0,0,0}, {29541,29582,29660 ,12609,12608,12610 ,0,0,0}, + {29611,29660,29582 ,12538,12610,12608 ,0,0,0}, {29661,29583,29541 ,12611,12612,12609 ,0,0,0}, + {29541,29660,29661 ,12609,12610,12611 ,0,0,0}, {29584,29661,29662 ,12613,12611,12614 ,0,0,0}, + {29661,29584,29583 ,12611,12613,12612 ,0,0,0}, {29663,29585,29662 ,12615,12616,12614 ,0,0,0}, + {29584,29662,29585 ,12613,12614,12616 ,0,0,0}, {29586,29585,29663 ,12617,12616,12615 ,0,0,0}, + {29663,29664,29586 ,12615,12618,12617 ,0,0,0}, {29586,29664,29587 ,12617,12618,12619 ,0,0,0}, + {29587,29664,29665 ,12619,12618,12620 ,0,0,0}, {29666,29667,29668 ,12621,12622,12623 ,0,0,0}, + {29669,29588,29665 ,12624,12625,12620 ,0,0,0}, {29587,29665,29588 ,12619,12620,12625 ,0,0,0}, + {29669,29670,29589 ,12624,12626,12627 ,0,0,0}, {29589,29588,29669 ,12627,12625,12624 ,0,0,0}, + {29506,29590,29670 ,12628,12629,12626 ,0,0,0}, {29670,29590,29589 ,12626,12629,12627 ,0,0,0}, + {29671,29591,29506 ,12630,12631,12628 ,0,0,0}, {29506,29670,29671 ,12628,12626,12630 ,0,0,0}, + {29591,29672,29592 ,12631,12632,12633 ,0,0,0}, {29672,29591,29671 ,12632,12631,12630 ,0,0,0}, + {29593,29592,29673 ,12634,12633,12635 ,0,0,0}, {29672,29673,29592 ,12632,12635,12633 ,0,0,0}, + {29674,29593,29673 ,12636,12634,12635 ,0,0,0}, {29674,29594,29593 ,12636,12637,12634 ,0,0,0}, + {29674,29675,29594 ,12636,12638,12637 ,0,0,0}, {29676,29677,29678 ,12639,12640,12641 ,0,0,0}, + {29595,29675,29679 ,12642,12638,12643 ,0,0,0}, {29675,29595,29594 ,12638,12642,12637 ,0,0,0}, + {29680,29552,29679 ,12644,12645,12643 ,0,0,0}, {29595,29679,29552 ,12642,12643,12645 ,0,0,0}, + {29596,29680,29597 ,12646,12644,12647 ,0,0,0}, {29596,29552,29680 ,12646,12645,12644 ,0,0,0}, + {29598,29597,29681 ,12648,12647,12649 ,0,0,0}, {29680,29681,29597 ,12644,12649,12647 ,0,0,0}, + {29682,29599,29598 ,12650,12651,12648 ,0,0,0}, {29598,29681,29682 ,12648,12649,12650 ,0,0,0}, + {29599,29683,29600 ,12651,12652,12653 ,0,0,0}, {29683,29599,29682 ,12652,12651,12650 ,0,0,0}, + {29601,29600,29684 ,12654,12653,12655 ,0,0,0}, {29683,29684,29600 ,12652,12655,12653 ,0,0,0}, + {29685,29601,29684 ,12656,12654,12655 ,0,0,0}, {29685,29602,29601 ,12656,12657,12654 ,0,0,0}, + {29685,29686,29602 ,12656,12658,12657 ,0,0,0}, {29687,29688,29689 ,12659,12660,12661 ,0,0,0}, + {29603,29686,29688 ,12662,12658,12660 ,0,0,0}, {29686,29603,29602 ,12658,12662,12657 ,0,0,0}, + {29690,29604,29688 ,12663,12664,12660 ,0,0,0}, {29603,29688,29604 ,12662,12660,12664 ,0,0,0}, + {29691,29692,29693 ,12665,12666,12667 ,0,0,0}, {29605,29604,29690 ,12668,12664,12663 ,0,0,0}, + {29694,29695,29696 ,12669,12670,12671 ,0,0,0}, {29697,29698,29699 ,12672,12673,12674 ,0,0,0}, + {29700,29701,29702 ,12675,12676,12677 ,0,0,0}, {29703,29704,29705 ,12678,12679,12680 ,0,0,0}, + {29706,29707,29694 ,12681,12682,12669 ,0,0,0}, {29708,29709,29710 ,12683,12684,12685 ,0,0,0}, + {29711,29712,29707 ,12686,12687,12682 ,0,0,0}, {29708,29703,29709 ,12683,12678,12684 ,0,0,0}, + {29707,29713,29714 ,12682,12688,12689 ,0,0,0}, {29217,28768,29710 ,12690,726,12685 ,0,0,0}, + {29715,29605,29690 ,12691,12668,12663 ,0,0,0}, {29605,29715,29606 ,12668,12691,12692 ,0,0,0}, + {29606,29691,29607 ,12692,12665,12693 ,0,0,0}, {29687,29690,29688 ,12659,12663,12660 ,0,0,0}, + {29716,29717,29608 ,12694,12695,12696 ,0,0,0}, {29691,29716,29607 ,12665,12694,12693 ,0,0,0}, + {29714,29716,29693 ,12689,12694,12667 ,0,0,0}, {29607,29716,29608 ,12693,12694,12696 ,0,0,0}, + {29717,29718,29237 ,12695,12697,12698 ,0,0,0}, {29717,29237,29609 ,12695,12698,12699 ,0,0,0}, + {28639,29237,29719 ,730,12698,12700 ,0,0,0}, {29656,29145,29148 ,12603,12594,12605 ,0,0,0}, + {29649,29651,29655 ,12596,12598,12602 ,0,0,0}, {29659,29658,29720 ,12607,12606,12701 ,0,0,0}, + {29648,29632,29565 ,12595,12576,12588 ,0,0,0}, {29648,29651,29721 ,12595,12598,12702 ,0,0,0}, + {29722,29630,29634 ,12703,12572,12578 ,0,0,0}, {29632,29721,29633 ,12576,12702,12577 ,0,0,0}, + {29723,29629,29722 ,12704,12569,12703 ,0,0,0}, {29633,29631,29632 ,12577,12574,12576 ,0,0,0}, + {29724,29628,29723 ,12705,12567,12704 ,0,0,0}, {29634,29630,29631 ,12578,12572,12574 ,0,0,0}, + {29725,29627,29724 ,12706,12566,12705 ,0,0,0}, {29722,29629,29630 ,12703,12569,12572 ,0,0,0}, + {29726,29626,29725 ,12707,12564,12706 ,0,0,0}, {29723,29628,29629 ,12704,12567,12569 ,0,0,0}, + {29727,29625,29726 ,12708,12561,12707 ,0,0,0}, {29724,29627,29628 ,12705,12566,12567 ,0,0,0}, + {29728,29621,29727 ,12709,12557,12708 ,0,0,0}, {29725,29626,29627 ,12706,12564,12566 ,0,0,0}, + {29728,29729,29620 ,12709,12710,12554 ,0,0,0}, {29625,29626,29726 ,12561,12564,12707 ,0,0,0}, + {29730,29619,29729 ,12711,12553,12710 ,0,0,0}, {29621,29625,29727 ,12557,12561,12708 ,0,0,0}, + {29623,29617,29730 ,12559,12550,12711 ,0,0,0}, {29620,29621,29728 ,12554,12557,12709 ,0,0,0}, + {29731,29618,29623 ,12712,12551,12559 ,0,0,0}, {29619,29620,29729 ,12553,12554,12710 ,0,0,0}, + {29732,29615,29731 ,12713,12544,12712 ,0,0,0}, {29617,29619,29730 ,12550,12553,12711 ,0,0,0}, + {29733,29616,29732 ,12714,12547,12713 ,0,0,0}, {29623,29618,29617 ,12559,12551,12550 ,0,0,0}, + {29734,29610,29733 ,12715,12537,12714 ,0,0,0}, {29731,29615,29618 ,12712,12544,12551 ,0,0,0}, + {29734,29735,29611 ,12715,12716,12538 ,0,0,0}, {29616,29615,29732 ,12547,12544,12713 ,0,0,0}, + {29736,29660,29735 ,12717,12610,12716 ,0,0,0}, {29610,29616,29733 ,12537,12547,12714 ,0,0,0}, + {29737,29661,29736 ,12718,12611,12717 ,0,0,0}, {29611,29610,29734 ,12538,12537,12715 ,0,0,0}, + {29738,29662,29737 ,12719,12614,12718 ,0,0,0}, {29660,29611,29735 ,12610,12538,12716 ,0,0,0}, + {29739,29663,29738 ,12720,12615,12719 ,0,0,0}, {29661,29660,29736 ,12611,12610,12717 ,0,0,0}, + {29740,29664,29739 ,12721,12618,12720 ,0,0,0}, {29737,29662,29661 ,12718,12614,12611 ,0,0,0}, + {29740,29741,29665 ,12721,12722,12620 ,0,0,0}, {29663,29662,29738 ,12615,12614,12719 ,0,0,0}, + {29742,29669,29741 ,12723,12624,12722 ,0,0,0}, {29664,29663,29739 ,12618,12615,12720 ,0,0,0}, + {29666,29670,29742 ,12621,12626,12723 ,0,0,0}, {29665,29664,29740 ,12620,12618,12721 ,0,0,0}, + {29743,29671,29666 ,12724,12630,12621 ,0,0,0}, {29669,29665,29741 ,12624,12620,12722 ,0,0,0}, + {29744,29672,29743 ,12725,12632,12724 ,0,0,0}, {29670,29669,29742 ,12626,12624,12723 ,0,0,0}, + {29745,29673,29744 ,12726,12635,12725 ,0,0,0}, {29666,29671,29670 ,12621,12630,12626 ,0,0,0}, + {29746,29674,29745 ,12727,12636,12726 ,0,0,0}, {29743,29672,29671 ,12724,12632,12630 ,0,0,0}, + {29746,29747,29675 ,12727,12728,12638 ,0,0,0}, {29673,29672,29744 ,12635,12632,12725 ,0,0,0}, + {29748,29679,29747 ,12729,12643,12728 ,0,0,0}, {29674,29673,29745 ,12636,12635,12726 ,0,0,0}, + {29749,29680,29748 ,12730,12644,12729 ,0,0,0}, {29675,29674,29746 ,12638,12636,12727 ,0,0,0}, + {29750,29681,29749 ,12731,12649,12730 ,0,0,0}, {29679,29675,29747 ,12643,12638,12728 ,0,0,0}, + {29751,29682,29750 ,12732,12650,12731 ,0,0,0}, {29748,29680,29679 ,12729,12644,12643 ,0,0,0}, + {29752,29683,29751 ,12733,12652,12732 ,0,0,0}, {29749,29681,29680 ,12730,12649,12644 ,0,0,0}, + {29753,29684,29752 ,12734,12655,12733 ,0,0,0}, {29750,29682,29681 ,12731,12650,12649 ,0,0,0}, + {29754,29685,29753 ,12735,12656,12734 ,0,0,0}, {29751,29683,29682 ,12732,12652,12650 ,0,0,0}, + {29754,29689,29686 ,12735,12661,12658 ,0,0,0}, {29684,29683,29752 ,12655,12652,12733 ,0,0,0}, + {29690,29687,29755 ,12663,12659,12736 ,0,0,0}, {29685,29684,29753 ,12656,12655,12734 ,0,0,0}, + {29711,29693,29699 ,12686,12667,12674 ,0,0,0}, {29686,29685,29754 ,12658,12656,12735 ,0,0,0}, + {29715,29755,29692 ,12691,12736,12666 ,0,0,0}, {29686,29689,29688 ,12658,12661,12660 ,0,0,0}, + {29755,29756,29692 ,12736,12737,12666 ,0,0,0}, {29714,29717,29716 ,12689,12695,12694 ,0,0,0}, + {29715,29691,29606 ,12691,12665,12692 ,0,0,0}, {29755,29715,29690 ,12736,12691,12663 ,0,0,0}, + {29714,29711,29707 ,12689,12686,12682 ,0,0,0}, {29691,29715,29692 ,12665,12691,12666 ,0,0,0}, + {29718,29713,29757 ,12697,12688,12738 ,0,0,0}, {29718,29719,29237 ,12697,12700,12698 ,0,0,0}, + {29608,29717,29609 ,12696,12695,12699 ,0,0,0}, {29718,29717,29713 ,12697,12695,12688 ,0,0,0}, + {29758,29719,29718 ,12739,12700,12697 ,0,0,0}, {29656,29651,29648 ,12603,12598,12595 ,0,0,0}, + {29652,29650,29649 ,12599,12597,12596 ,0,0,0}, {29640,29265,29261 ,12585,12579,12740 ,0,0,0}, + {29648,29721,29632 ,12595,12702,12576 ,0,0,0}, {29759,29721,29650 ,12741,12702,12597 ,0,0,0}, + {29644,29646,29722 ,12590,12592,12703 ,0,0,0}, {29643,29633,29759 ,12589,12577,12741 ,0,0,0}, + {29646,29760,29723 ,12592,12742,12704 ,0,0,0}, {29643,29634,29633 ,12589,12578,12577 ,0,0,0}, + {29760,29761,29724 ,12742,12743,12705 ,0,0,0}, {29644,29722,29634 ,12590,12703,12578 ,0,0,0}, + {29761,29762,29725 ,12743,12744,12706 ,0,0,0}, {29646,29723,29722 ,12592,12704,12703 ,0,0,0}, + {29762,29763,29726 ,12744,12745,12707 ,0,0,0}, {29760,29724,29723 ,12742,12705,12704 ,0,0,0}, + {29763,29764,29727 ,12745,12746,12708 ,0,0,0}, {29761,29725,29724 ,12743,12706,12705 ,0,0,0}, + {29764,29765,29728 ,12746,12747,12709 ,0,0,0}, {29762,29726,29725 ,12744,12707,12706 ,0,0,0}, + {29765,29766,29729 ,12747,12748,12710 ,0,0,0}, {29763,29727,29726 ,12745,12708,12707 ,0,0,0}, + {29766,29624,29730 ,12748,12560,12711 ,0,0,0}, {29728,29727,29764 ,12709,12708,12746 ,0,0,0}, + {29767,29768,29769 ,12749,12750,12751 ,0,0,0}, {29729,29728,29765 ,12710,12709,12747 ,0,0,0}, + {29622,29768,29731 ,12558,12750,12712 ,0,0,0}, {29730,29729,29766 ,12711,12710,12748 ,0,0,0}, + {29768,29767,29732 ,12750,12749,12713 ,0,0,0}, {29623,29730,29624 ,12559,12711,12560 ,0,0,0}, + {29767,29770,29733 ,12749,12752,12714 ,0,0,0}, {29622,29731,29623 ,12558,12712,12559 ,0,0,0}, + {29770,29771,29734 ,12752,12753,12715 ,0,0,0}, {29768,29732,29731 ,12750,12713,12712 ,0,0,0}, + {29771,29772,29735 ,12753,12754,12716 ,0,0,0}, {29767,29733,29732 ,12749,12714,12713 ,0,0,0}, + {29772,29773,29736 ,12754,12755,12717 ,0,0,0}, {29734,29733,29770 ,12715,12714,12752 ,0,0,0}, + {29614,29737,29773 ,12543,12718,12755 ,0,0,0}, {29735,29734,29771 ,12716,12715,12753 ,0,0,0}, + {29614,29613,29738 ,12543,12542,12719 ,0,0,0}, {29736,29735,29772 ,12717,12716,12754 ,0,0,0}, + {29613,29774,29739 ,12542,12756,12720 ,0,0,0}, {29773,29737,29736 ,12755,12718,12717 ,0,0,0}, + {29774,29775,29740 ,12756,12757,12721 ,0,0,0}, {29614,29738,29737 ,12543,12719,12718 ,0,0,0}, + {29775,29776,29741 ,12757,12758,12722 ,0,0,0}, {29613,29739,29738 ,12542,12720,12719 ,0,0,0}, + {29776,29667,29742 ,12758,12622,12723 ,0,0,0}, {29740,29739,29774 ,12721,12720,12756 ,0,0,0}, + {29777,29778,29779 ,12759,12760,12761 ,0,0,0}, {29741,29740,29775 ,12722,12721,12757 ,0,0,0}, + {29668,29780,29743 ,12623,12762,12724 ,0,0,0}, {29742,29741,29776 ,12723,12722,12758 ,0,0,0}, + {29780,29781,29744 ,12762,12763,12725 ,0,0,0}, {29666,29742,29667 ,12621,12723,12622 ,0,0,0}, + {29781,29782,29745 ,12763,12764,12726 ,0,0,0}, {29668,29743,29666 ,12623,12724,12621 ,0,0,0}, + {29782,29783,29746 ,12764,12765,12727 ,0,0,0}, {29780,29744,29743 ,12762,12725,12724 ,0,0,0}, + {29783,29784,29747 ,12765,12766,12728 ,0,0,0}, {29781,29745,29744 ,12763,12726,12725 ,0,0,0}, + {29784,29785,29748 ,12766,12767,12729 ,0,0,0}, {29746,29745,29782 ,12727,12726,12764 ,0,0,0}, + {29785,29676,29749 ,12767,12639,12730 ,0,0,0}, {29747,29746,29783 ,12728,12727,12765 ,0,0,0}, + {29676,29678,29750 ,12639,12641,12731 ,0,0,0}, {29748,29747,29784 ,12729,12728,12766 ,0,0,0}, + {29678,29786,29751 ,12641,12768,12732 ,0,0,0}, {29785,29749,29748 ,12767,12730,12729 ,0,0,0}, + {29786,29787,29752 ,12768,12769,12733 ,0,0,0}, {29676,29750,29749 ,12639,12731,12730 ,0,0,0}, + {29787,29788,29753 ,12769,12770,12734 ,0,0,0}, {29678,29751,29750 ,12641,12732,12731 ,0,0,0}, + {29788,29789,29754 ,12770,12771,12735 ,0,0,0}, {29786,29752,29751 ,12768,12733,12732 ,0,0,0}, + {29789,29790,29689 ,12771,12772,12661 ,0,0,0}, {29787,29753,29752 ,12769,12734,12733 ,0,0,0}, + {29790,29791,29687 ,12772,12773,12659 ,0,0,0}, {29788,29754,29753 ,12770,12735,12734 ,0,0,0}, + {29791,29756,29755 ,12773,12737,12736 ,0,0,0}, {29789,29689,29754 ,12771,12661,12735 ,0,0,0}, + {29756,29699,29692 ,12737,12674,12666 ,0,0,0}, {29687,29689,29790 ,12659,12661,12772 ,0,0,0}, + {29792,29793,29794 ,12774,12775,12776 ,0,0,0}, {29791,29755,29687 ,12773,12736,12659 ,0,0,0}, + {29712,29694,29707 ,12687,12669,12682 ,0,0,0}, {29706,29795,29757 ,12681,12777,12738 ,0,0,0}, + {29691,29693,29716 ,12665,12667,12694 ,0,0,0}, {29699,29693,29692 ,12674,12667,12666 ,0,0,0}, + {29796,29757,29795 ,12778,12738,12777 ,0,0,0}, {29757,29758,29718 ,12738,12739,12697 ,0,0,0}, + {29717,29714,29713 ,12695,12689,12688 ,0,0,0}, {29713,29706,29757 ,12688,12681,12738 ,0,0,0}, + {29796,29758,29757 ,12778,12739,12738 ,0,0,0}, {29650,29721,29651 ,12597,12702,12598 ,0,0,0}, + {29797,29653,29654 ,12779,12600,12601 ,0,0,0}, {29797,29658,29653 ,12779,12606,12600 ,0,0,0}, + {29721,29759,29633 ,12702,12741,12577 ,0,0,0}, {29798,29759,29653 ,12780,12741,12600 ,0,0,0}, + {29646,29799,29760 ,12592,12781,12742 ,0,0,0}, {29647,29643,29798 ,12593,12589,12780 ,0,0,0}, + {29760,29800,29761 ,12742,12782,12743 ,0,0,0}, {29647,29645,29644 ,12593,12591,12590 ,0,0,0}, + {29801,29802,29803 ,12783,12784,12785 ,0,0,0}, {29645,29799,29646 ,12591,12781,12592 ,0,0,0}, + {29762,29761,29804 ,12744,12743,12786 ,0,0,0}, {29799,29800,29760 ,12781,12782,12742 ,0,0,0}, + {29763,29762,29803 ,12745,12744,12785 ,0,0,0}, {29800,29804,29761 ,12782,12786,12743 ,0,0,0}, + {29764,29763,29802 ,12746,12745,12784 ,0,0,0}, {29804,29803,29762 ,12786,12785,12744 ,0,0,0}, + {29765,29764,29805 ,12747,12746,12787 ,0,0,0}, {29803,29802,29763 ,12785,12784,12745 ,0,0,0}, + {29766,29765,29806 ,12748,12747,12788 ,0,0,0}, {29802,29805,29764 ,12784,12787,12746 ,0,0,0}, + {29624,29766,29807 ,12560,12748,12789 ,0,0,0}, {29805,29806,29765 ,12787,12788,12747 ,0,0,0}, + {29622,29624,29808 ,12558,12560,12790 ,0,0,0}, {29806,29807,29766 ,12788,12789,12748 ,0,0,0}, + {29768,29622,29809 ,12750,12558,12791 ,0,0,0}, {29808,29624,29807 ,12790,12560,12789 ,0,0,0}, + {29810,29811,29812 ,12792,12793,12794 ,0,0,0}, {29809,29622,29808 ,12791,12558,12790 ,0,0,0}, + {29770,29767,29813 ,12752,12749,12795 ,0,0,0}, {29809,29769,29768 ,12791,12751,12750 ,0,0,0}, + {29771,29770,29812 ,12753,12752,12794 ,0,0,0}, {29769,29813,29767 ,12751,12795,12749 ,0,0,0}, + {29772,29771,29811 ,12754,12753,12793 ,0,0,0}, {29813,29812,29770 ,12795,12794,12752 ,0,0,0}, + {29773,29772,29814 ,12755,12754,12796 ,0,0,0}, {29812,29811,29771 ,12794,12793,12753 ,0,0,0}, + {29614,29773,29815 ,12543,12755,12797 ,0,0,0}, {29814,29772,29811 ,12796,12754,12793 ,0,0,0}, + {29816,29817,29818 ,12798,12799,12800 ,0,0,0}, {29815,29773,29814 ,12797,12755,12796 ,0,0,0}, + {29774,29613,29819 ,12756,12542,12801 ,0,0,0}, {29815,29612,29614 ,12797,12541,12543 ,0,0,0}, + {29775,29774,29818 ,12757,12756,12800 ,0,0,0}, {29612,29819,29613 ,12541,12801,12542 ,0,0,0}, + {29776,29775,29817 ,12758,12757,12799 ,0,0,0}, {29819,29818,29774 ,12801,12800,12756 ,0,0,0}, + {29667,29776,29820 ,12622,12758,12802 ,0,0,0}, {29818,29817,29775 ,12800,12799,12757 ,0,0,0}, + {29668,29667,29821 ,12623,12622,12803 ,0,0,0}, {29817,29820,29776 ,12799,12802,12758 ,0,0,0}, + {29780,29668,29822 ,12762,12623,12804 ,0,0,0}, {29821,29667,29820 ,12803,12622,12802 ,0,0,0}, + {29781,29780,29823 ,12763,12762,12805 ,0,0,0}, {29822,29668,29821 ,12804,12623,12803 ,0,0,0}, + {29782,29781,29777 ,12764,12763,12759 ,0,0,0}, {29822,29823,29780 ,12804,12805,12762 ,0,0,0}, + {29783,29782,29779 ,12765,12764,12761 ,0,0,0}, {29823,29777,29781 ,12805,12759,12763 ,0,0,0}, + {29784,29783,29824 ,12766,12765,12806 ,0,0,0}, {29777,29779,29782 ,12759,12761,12764 ,0,0,0}, + {29785,29784,29825 ,12767,12766,12807 ,0,0,0}, {29779,29824,29783 ,12761,12806,12765 ,0,0,0}, + {29676,29785,29826 ,12639,12767,12808 ,0,0,0}, {29825,29784,29824 ,12807,12766,12806 ,0,0,0}, + {29827,29828,29829 ,12809,12810,12811 ,0,0,0}, {29826,29785,29825 ,12808,12767,12807 ,0,0,0}, + {29786,29678,29830 ,12768,12641,12812 ,0,0,0}, {29826,29677,29676 ,12808,12640,12639 ,0,0,0}, + {29787,29786,29829 ,12769,12768,12811 ,0,0,0}, {29677,29830,29678 ,12640,12812,12641 ,0,0,0}, + {29788,29787,29828 ,12770,12769,12810 ,0,0,0}, {29830,29829,29786 ,12812,12811,12768 ,0,0,0}, + {29789,29788,29831 ,12771,12770,12813 ,0,0,0}, {29829,29828,29787 ,12811,12810,12769 ,0,0,0}, + {29790,29789,29832 ,12772,12771,12814 ,0,0,0}, {29828,29831,29788 ,12810,12813,12770 ,0,0,0}, + {29791,29790,29833 ,12773,12772,12815 ,0,0,0}, {29831,29832,29789 ,12813,12814,12771 ,0,0,0}, + {29756,29791,29834 ,12737,12773,12816 ,0,0,0}, {29832,29833,29790 ,12814,12815,12772 ,0,0,0}, + {29699,29756,29697 ,12674,12737,12672 ,0,0,0}, {29833,29834,29791 ,12815,12816,12773 ,0,0,0}, + {29711,29699,29698 ,12686,12674,12673 ,0,0,0}, {29834,29697,29756 ,12816,12672,12737 ,0,0,0}, + {29835,29705,29794 ,12817,12680,12776 ,0,0,0}, {29836,29695,29694 ,12818,12670,12669 ,0,0,0}, + {29693,29711,29714 ,12667,12686,12689 ,0,0,0}, {29698,29712,29711 ,12673,12687,12686 ,0,0,0}, + {29837,29795,29793 ,12819,12777,12775 ,0,0,0}, {29837,29838,29795 ,12819,12820,12777 ,0,0,0}, + {29713,29707,29706 ,12688,12682,12681 ,0,0,0}, {29706,29696,29795 ,12681,12671,12777 ,0,0,0}, + {29796,29795,29838 ,12778,12777,12820 ,0,0,0}, {29650,29653,29759 ,12597,12600,12741 ,0,0,0}, + {29720,29658,29797 ,12701,12606,12779 ,0,0,0}, {29647,29839,29645 ,12593,12821,12591 ,0,0,0}, + {29759,29798,29643 ,12741,12780,12589 ,0,0,0}, {29658,29840,29798 ,12606,12822,12780 ,0,0,0}, + {29799,29645,29841 ,12781,12591,12823 ,0,0,0}, {29840,29839,29647 ,12822,12821,12593 ,0,0,0}, + {29800,29799,29842 ,12782,12781,12824 ,0,0,0}, {29645,29839,29841 ,12591,12821,12823 ,0,0,0}, + {29804,29800,29843 ,12786,12782,12825 ,0,0,0}, {29799,29841,29842 ,12781,12823,12824 ,0,0,0}, + {29803,29804,29844 ,12785,12786,12826 ,0,0,0}, {29842,29843,29800 ,12824,12825,12782 ,0,0,0}, + {29845,29805,29802 ,12827,12787,12784 ,0,0,0}, {29843,29844,29804 ,12825,12826,12786 ,0,0,0}, + {29846,29847,29848 ,12828,12829,12830 ,0,0,0}, {29844,29801,29803 ,12826,12783,12785 ,0,0,0}, + {29805,29849,29806 ,12787,12831,12788 ,0,0,0}, {29801,29845,29802 ,12783,12827,12784 ,0,0,0}, + {29806,29847,29807 ,12788,12829,12789 ,0,0,0}, {29845,29849,29805 ,12827,12831,12787 ,0,0,0}, + {29807,29846,29808 ,12789,12828,12790 ,0,0,0}, {29849,29847,29806 ,12831,12829,12788 ,0,0,0}, + {29808,29850,29809 ,12790,12832,12791 ,0,0,0}, {29847,29846,29807 ,12829,12828,12789 ,0,0,0}, + {29809,29851,29769 ,12791,12833,12751 ,0,0,0}, {29846,29850,29808 ,12828,12832,12790 ,0,0,0}, + {29813,29769,29852 ,12795,12751,12834 ,0,0,0}, {29850,29851,29809 ,12832,12833,12791 ,0,0,0}, + {29812,29813,29853 ,12794,12795,12835 ,0,0,0}, {29851,29852,29769 ,12833,12834,12751 ,0,0,0}, + {29854,29855,29856 ,12836,12837,12838 ,0,0,0}, {29852,29853,29813 ,12834,12835,12795 ,0,0,0}, + {29811,29857,29814 ,12793,12839,12796 ,0,0,0}, {29853,29810,29812 ,12835,12792,12794 ,0,0,0}, + {29814,29858,29815 ,12796,12840,12797 ,0,0,0}, {29810,29857,29811 ,12792,12839,12793 ,0,0,0}, + {29815,29859,29612 ,12797,12841,12541 ,0,0,0}, {29857,29858,29814 ,12839,12840,12796 ,0,0,0}, + {29819,29612,29860 ,12801,12541,12842 ,0,0,0}, {29858,29859,29815 ,12840,12841,12797 ,0,0,0}, + {29818,29819,29861 ,12800,12801,12843 ,0,0,0}, {29859,29860,29612 ,12841,12842,12541 ,0,0,0}, + {29862,29863,29864 ,12844,12845,12846 ,0,0,0}, {29860,29861,29819 ,12842,12843,12801 ,0,0,0}, + {29817,29865,29820 ,12799,12847,12802 ,0,0,0}, {29861,29816,29818 ,12843,12798,12800 ,0,0,0}, + {29820,29866,29821 ,12802,12848,12803 ,0,0,0}, {29816,29865,29817 ,12798,12847,12799 ,0,0,0}, + {29821,29867,29822 ,12803,12849,12804 ,0,0,0}, {29865,29866,29820 ,12847,12848,12802 ,0,0,0}, + {29822,29868,29823 ,12804,12850,12805 ,0,0,0}, {29866,29867,29821 ,12848,12849,12803 ,0,0,0}, + {29777,29823,29869 ,12759,12805,12851 ,0,0,0}, {29867,29868,29822 ,12849,12850,12804 ,0,0,0}, + {29870,29871,29872 ,12852,12853,12854 ,0,0,0}, {29868,29869,29823 ,12850,12851,12805 ,0,0,0}, + {29779,29873,29824 ,12761,12855,12806 ,0,0,0}, {29869,29778,29777 ,12851,12760,12759 ,0,0,0}, + {29824,29871,29825 ,12806,12853,12807 ,0,0,0}, {29778,29873,29779 ,12760,12855,12761 ,0,0,0}, + {29825,29870,29826 ,12807,12852,12808 ,0,0,0}, {29873,29871,29824 ,12855,12853,12806 ,0,0,0}, + {29826,29874,29677 ,12808,12856,12640 ,0,0,0}, {29871,29870,29825 ,12853,12852,12807 ,0,0,0}, + {29830,29677,29875 ,12812,12640,12857 ,0,0,0}, {29870,29874,29826 ,12852,12856,12808 ,0,0,0}, + {29829,29830,29876 ,12811,12812,12858 ,0,0,0}, {29874,29875,29677 ,12856,12857,12640 ,0,0,0}, + {29877,29831,29828 ,12859,12813,12810 ,0,0,0}, {29875,29876,29830 ,12857,12858,12812 ,0,0,0}, + {29878,29879,29880 ,12860,12861,12862 ,0,0,0}, {29876,29827,29829 ,12858,12809,12811 ,0,0,0}, + {29831,29881,29832 ,12813,12863,12814 ,0,0,0}, {29827,29877,29828 ,12809,12859,12810 ,0,0,0}, + {29832,29879,29833 ,12814,12861,12815 ,0,0,0}, {29877,29881,29831 ,12859,12863,12813 ,0,0,0}, + {29833,29878,29834 ,12815,12860,12816 ,0,0,0}, {29881,29879,29832 ,12863,12861,12814 ,0,0,0}, + {29834,29882,29697 ,12816,12864,12672 ,0,0,0}, {29879,29878,29833 ,12861,12860,12815 ,0,0,0}, + {29697,29883,29698 ,12672,12865,12673 ,0,0,0}, {29878,29882,29834 ,12860,12864,12816 ,0,0,0}, + {29698,29884,29712 ,12673,12866,12687 ,0,0,0}, {29882,29883,29697 ,12864,12865,12672 ,0,0,0}, + {29712,29836,29694 ,12687,12818,12669 ,0,0,0}, {29884,29698,29883 ,12866,12673,12865 ,0,0,0}, + {29701,29695,29885 ,12676,12670,12867 ,0,0,0}, {29712,29884,29836 ,12687,12866,12818 ,0,0,0}, + {29793,29886,29794 ,12775,12868,12776 ,0,0,0}, {29795,29696,29793 ,12777,12671,12775 ,0,0,0}, + {29706,29694,29696 ,12681,12669,12671 ,0,0,0}, {29696,29886,29793 ,12671,12868,12775 ,0,0,0}, + {29837,29793,29792 ,12819,12775,12774 ,0,0,0}, {29653,29658,29798 ,12600,12606,12780 ,0,0,0}, + {29638,29637,29659 ,12583,12582,12607 ,0,0,0}, {29839,29887,29841 ,12821,12869,12823 ,0,0,0}, + {29798,29840,29647 ,12780,12822,12593 ,0,0,0}, {29637,29888,29840 ,12582,12870,12822 ,0,0,0}, + {29842,29841,29889 ,12824,12823,12871 ,0,0,0}, {29839,29888,29887 ,12821,12870,12869 ,0,0,0}, + {29843,29842,29890 ,12825,12824,12872 ,0,0,0}, {29841,29887,29889 ,12823,12869,12871 ,0,0,0}, + {29844,29843,29891 ,12826,12825,12873 ,0,0,0}, {29842,29889,29890 ,12824,12871,12872 ,0,0,0}, + {29801,29844,29892 ,12783,12826,12874 ,0,0,0}, {29843,29890,29891 ,12825,12872,12873 ,0,0,0}, + {29845,29801,29893 ,12827,12783,12875 ,0,0,0}, {29844,29891,29892 ,12826,12873,12874 ,0,0,0}, + {29849,29845,29894 ,12831,12827,12876 ,0,0,0}, {29801,29892,29893 ,12783,12874,12875 ,0,0,0}, + {29847,29849,29895 ,12829,12831,12877 ,0,0,0}, {29893,29894,29845 ,12875,12876,12827 ,0,0,0}, + {29896,29897,29898 ,12878,12879,12880 ,0,0,0}, {29894,29895,29849 ,12876,12877,12831 ,0,0,0}, + {29846,29899,29850 ,12828,12881,12832 ,0,0,0}, {29895,29848,29847 ,12877,12830,12829 ,0,0,0}, + {29850,29898,29851 ,12832,12880,12833 ,0,0,0}, {29848,29899,29846 ,12830,12881,12828 ,0,0,0}, + {29851,29900,29852 ,12833,12882,12834 ,0,0,0}, {29899,29898,29850 ,12881,12880,12832 ,0,0,0}, + {29853,29852,29901 ,12835,12834,12883 ,0,0,0}, {29898,29900,29851 ,12880,12882,12833 ,0,0,0}, + {29810,29853,29902 ,12792,12835,12884 ,0,0,0}, {29852,29900,29901 ,12834,12882,12883 ,0,0,0}, + {29857,29810,29903 ,12839,12792,12885 ,0,0,0}, {29853,29901,29902 ,12835,12883,12884 ,0,0,0}, + {29858,29857,29904 ,12840,12839,12886 ,0,0,0}, {29902,29903,29810 ,12884,12885,12792 ,0,0,0}, + {29858,29905,29859 ,12840,12887,12841 ,0,0,0}, {29903,29904,29857 ,12885,12886,12839 ,0,0,0}, + {29859,29855,29860 ,12841,12837,12842 ,0,0,0}, {29904,29905,29858 ,12886,12887,12840 ,0,0,0}, + {29861,29860,29906 ,12843,12842,12888 ,0,0,0}, {29905,29855,29859 ,12887,12837,12841 ,0,0,0}, + {29816,29861,29907 ,12798,12843,12889 ,0,0,0}, {29860,29855,29906 ,12842,12837,12888 ,0,0,0}, + {29865,29816,29908 ,12847,12798,12890 ,0,0,0}, {29861,29906,29907 ,12843,12888,12889 ,0,0,0}, + {29866,29865,29909 ,12848,12847,12891 ,0,0,0}, {29907,29908,29816 ,12889,12890,12798 ,0,0,0}, + {29866,29910,29867 ,12848,12892,12849 ,0,0,0}, {29908,29909,29865 ,12890,12891,12847 ,0,0,0}, + {29867,29863,29868 ,12849,12845,12850 ,0,0,0}, {29909,29910,29866 ,12891,12892,12848 ,0,0,0}, + {29869,29868,29911 ,12851,12850,12893 ,0,0,0}, {29910,29863,29867 ,12892,12845,12849 ,0,0,0}, + {29778,29869,29912 ,12760,12851,12894 ,0,0,0}, {29868,29863,29911 ,12850,12845,12893 ,0,0,0}, + {29873,29778,29913 ,12855,12760,12895 ,0,0,0}, {29869,29911,29912 ,12851,12893,12894 ,0,0,0}, + {29871,29873,29914 ,12853,12855,12896 ,0,0,0}, {29912,29913,29778 ,12894,12895,12760 ,0,0,0}, + {29915,29916,29917 ,12897,12898,12899 ,0,0,0}, {29913,29914,29873 ,12895,12896,12855 ,0,0,0}, + {29870,29918,29874 ,12852,12900,12856 ,0,0,0}, {29914,29872,29871 ,12896,12854,12853 ,0,0,0}, + {29874,29917,29875 ,12856,12899,12857 ,0,0,0}, {29872,29918,29870 ,12854,12900,12852 ,0,0,0}, + {29876,29875,29919 ,12858,12857,12901 ,0,0,0}, {29918,29917,29874 ,12900,12899,12856 ,0,0,0}, + {29827,29876,29920 ,12809,12858,12902 ,0,0,0}, {29875,29917,29919 ,12857,12899,12901 ,0,0,0}, + {29877,29827,29921 ,12859,12809,12903 ,0,0,0}, {29876,29919,29920 ,12858,12901,12902 ,0,0,0}, + {29881,29877,29922 ,12863,12859,12904 ,0,0,0}, {29827,29920,29921 ,12809,12902,12903 ,0,0,0}, + {29879,29881,29923 ,12861,12863,12905 ,0,0,0}, {29921,29922,29877 ,12903,12904,12859 ,0,0,0}, + {29924,29882,29878 ,12906,12864,12860 ,0,0,0}, {29922,29923,29881 ,12904,12905,12863 ,0,0,0}, + {29925,29926,29927 ,12907,12908,12909 ,0,0,0}, {29923,29880,29879 ,12905,12862,12861 ,0,0,0}, + {29882,29928,29883 ,12864,12910,12865 ,0,0,0}, {29880,29924,29878 ,12862,12906,12860 ,0,0,0}, + {29883,29927,29884 ,12865,12909,12866 ,0,0,0}, {29924,29928,29882 ,12906,12910,12864 ,0,0,0}, + {29884,29929,29836 ,12866,12911,12818 ,0,0,0}, {29928,29927,29883 ,12910,12909,12865 ,0,0,0}, + {29836,29885,29695 ,12818,12867,12670 ,0,0,0}, {29927,29929,29884 ,12909,12911,12866 ,0,0,0}, + {29695,29701,29886 ,12670,12676,12868 ,0,0,0}, {29836,29929,29885 ,12818,12911,12867 ,0,0,0}, + {29930,29794,29705 ,12912,12776,12680 ,0,0,0}, {29931,29792,29794 ,12913,12774,12776 ,0,0,0}, + {29696,29695,29886 ,12671,12670,12868 ,0,0,0}, {29886,29835,29794 ,12868,12817,12776 ,0,0,0}, + {29930,29931,29794 ,12912,12913,12776 ,0,0,0}, {29658,29637,29840 ,12606,12582,12822 ,0,0,0}, + {29932,29636,29638 ,12914,12581,12583 ,0,0,0}, {29889,29887,29642 ,12871,12869,12587 ,0,0,0}, + {29840,29888,29839 ,12822,12870,12821 ,0,0,0}, {29636,29933,29888 ,12581,12915,12870 ,0,0,0}, + {29890,29889,29934 ,12872,12871,12916 ,0,0,0}, {29887,29933,29642 ,12869,12915,12587 ,0,0,0}, + {29935,29934,29936 ,12917,12916,12918 ,0,0,0}, {29889,29642,29934 ,12871,12587,12916 ,0,0,0}, + {29935,29937,29891 ,12917,12919,12873 ,0,0,0}, {29891,29890,29935 ,12873,12872,12917 ,0,0,0}, + {29937,29938,29892 ,12919,12920,12874 ,0,0,0}, {29892,29891,29937 ,12874,12873,12919 ,0,0,0}, + {29938,29939,29893 ,12920,12921,12875 ,0,0,0}, {29893,29892,29938 ,12875,12874,12920 ,0,0,0}, + {29939,29940,29894 ,12921,12922,12876 ,0,0,0}, {29894,29893,29939 ,12876,12875,12921 ,0,0,0}, + {29940,29941,29895 ,12922,12923,12877 ,0,0,0}, {29895,29894,29940 ,12877,12876,12922 ,0,0,0}, + {29941,29942,29848 ,12923,12924,12830 ,0,0,0}, {29848,29895,29941 ,12830,12877,12923 ,0,0,0}, + {29942,29896,29899 ,12924,12878,12881 ,0,0,0}, {29848,29942,29899 ,12830,12924,12881 ,0,0,0}, + {29252,29943,29944 ,12925,12926,12927 ,0,0,0}, {29899,29896,29898 ,12881,12878,12880 ,0,0,0}, + {29900,29945,29901 ,12882,12928,12883 ,0,0,0}, {29898,29897,29900 ,12880,12879,12882 ,0,0,0}, + {29946,29945,29944 ,12929,12928,12927 ,0,0,0}, {29897,29945,29900 ,12879,12928,12882 ,0,0,0}, + {29946,29947,29902 ,12929,12930,12884 ,0,0,0}, {29902,29901,29946 ,12884,12883,12929 ,0,0,0}, + {29947,29948,29903 ,12930,12931,12885 ,0,0,0}, {29903,29902,29947 ,12885,12884,12930 ,0,0,0}, + {29948,29949,29904 ,12931,12932,12886 ,0,0,0}, {29904,29903,29948 ,12886,12885,12931 ,0,0,0}, + {29949,29856,29905 ,12932,12838,12887 ,0,0,0}, {29904,29949,29905 ,12886,12932,12887 ,0,0,0}, + {29950,29951,29952 ,12933,12934,12935 ,0,0,0}, {29905,29856,29855 ,12887,12838,12837 ,0,0,0}, + {29854,29951,29906 ,12836,12934,12888 ,0,0,0}, {29855,29854,29906 ,12837,12836,12888 ,0,0,0}, + {29951,29953,29907 ,12934,12936,12889 ,0,0,0}, {29907,29906,29951 ,12889,12888,12934 ,0,0,0}, + {29953,29954,29908 ,12936,12937,12890 ,0,0,0}, {29908,29907,29953 ,12890,12889,12936 ,0,0,0}, + {29954,29955,29909 ,12937,12938,12891 ,0,0,0}, {29909,29908,29954 ,12891,12890,12937 ,0,0,0}, + {29955,29864,29910 ,12938,12846,12892 ,0,0,0}, {29909,29955,29910 ,12891,12938,12892 ,0,0,0}, + {29956,29243,29957 ,12939,12940,12941 ,0,0,0}, {29910,29864,29863 ,12892,12846,12845 ,0,0,0}, + {29912,29911,29958 ,12894,12893,12942 ,0,0,0}, {29863,29862,29911 ,12845,12844,12893 ,0,0,0}, + {29959,29958,29956 ,12943,12942,12939 ,0,0,0}, {29911,29862,29958 ,12893,12844,12942 ,0,0,0}, + {29959,29960,29913 ,12943,12944,12895 ,0,0,0}, {29913,29912,29959 ,12895,12894,12943 ,0,0,0}, + {29960,29961,29914 ,12944,12945,12896 ,0,0,0}, {29914,29913,29960 ,12896,12895,12944 ,0,0,0}, + {29961,29962,29872 ,12945,12946,12854 ,0,0,0}, {29872,29914,29961 ,12854,12896,12945 ,0,0,0}, + {29962,29915,29918 ,12946,12897,12900 ,0,0,0}, {29872,29962,29918 ,12854,12946,12900 ,0,0,0}, + {29963,29964,29965 ,12947,12948,12949 ,0,0,0}, {29918,29915,29917 ,12900,12897,12899 ,0,0,0}, + {29916,29964,29919 ,12898,12948,12901 ,0,0,0}, {29917,29916,29919 ,12899,12898,12901 ,0,0,0}, + {29964,29966,29920 ,12948,12950,12902 ,0,0,0}, {29920,29919,29964 ,12902,12901,12948 ,0,0,0}, + {29966,29967,29921 ,12950,12951,12903 ,0,0,0}, {29921,29920,29966 ,12903,12902,12950 ,0,0,0}, + {29967,29968,29922 ,12951,12952,12904 ,0,0,0}, {29922,29921,29967 ,12904,12903,12951 ,0,0,0}, + {29968,29969,29923 ,12952,12953,12905 ,0,0,0}, {29923,29922,29968 ,12905,12904,12952 ,0,0,0}, + {29969,29970,29880 ,12953,12954,12862 ,0,0,0}, {29880,29923,29969 ,12862,12905,12953 ,0,0,0}, + {29970,29971,29924 ,12954,12955,12906 ,0,0,0}, {29924,29880,29970 ,12906,12862,12954 ,0,0,0}, + {29971,29925,29928 ,12955,12907,12910 ,0,0,0}, {29924,29971,29928 ,12906,12955,12910 ,0,0,0}, + {29929,29926,29972 ,12911,12908,12956 ,0,0,0}, {29928,29925,29927 ,12910,12907,12909 ,0,0,0}, + {29702,29701,29885 ,12677,12676,12867 ,0,0,0}, {29927,29926,29929 ,12909,12908,12911 ,0,0,0}, + {29700,29835,29701 ,12675,12817,12676 ,0,0,0}, {29929,29972,29885 ,12911,12956,12867 ,0,0,0}, + {29973,29709,29703 ,12957,12684,12678 ,0,0,0}, {29972,29702,29885 ,12956,12677,12867 ,0,0,0}, + {29700,29974,29975 ,12675,12958,12959 ,0,0,0}, {29976,29930,29705 ,12960,12912,12680 ,0,0,0}, + {29886,29701,29835 ,12868,12676,12817 ,0,0,0}, {29705,29835,29975 ,12680,12817,12959 ,0,0,0}, + {29704,29976,29705 ,12679,12960,12680 ,0,0,0}, {29637,29636,29888 ,12582,12581,12870 ,0,0,0}, + {29932,29639,29635 ,12914,12584,12580 ,0,0,0}, {29933,29635,29640 ,12915,12580,12585 ,0,0,0}, + {29888,29933,29887 ,12870,12915,12869 ,0,0,0}, {29642,29933,29640 ,12587,12915,12585 ,0,0,0}, + {29641,29936,29934 ,12586,12918,12916 ,0,0,0}, {29934,29642,29641 ,12916,12587,12586 ,0,0,0}, + {29936,29977,29935 ,12918,12961,12917 ,0,0,0}, {29978,29937,29977 ,12962,12919,12961 ,0,0,0}, + {29890,29934,29935 ,12872,12916,12917 ,0,0,0}, {29937,29935,29977 ,12919,12917,12961 ,0,0,0}, + {29979,29938,29978 ,12963,12920,12962 ,0,0,0}, {29938,29937,29978 ,12920,12919,12962 ,0,0,0}, + {29980,29939,29979 ,12964,12921,12963 ,0,0,0}, {29939,29938,29979 ,12921,12920,12963 ,0,0,0}, + {29981,29940,29980 ,12965,12922,12964 ,0,0,0}, {29940,29939,29980 ,12922,12921,12964 ,0,0,0}, + {29982,29941,29981 ,12966,12923,12965 ,0,0,0}, {29941,29940,29981 ,12923,12922,12965 ,0,0,0}, + {29983,29942,29982 ,12967,12924,12966 ,0,0,0}, {29942,29941,29982 ,12924,12923,12966 ,0,0,0}, + {29984,29896,29983 ,12968,12878,12967 ,0,0,0}, {29896,29942,29983 ,12878,12924,12967 ,0,0,0}, + {29985,29897,29984 ,12969,12879,12968 ,0,0,0}, {29897,29896,29984 ,12879,12878,12968 ,0,0,0}, + {29944,29945,29985 ,12927,12928,12969 ,0,0,0}, {29897,29985,29945 ,12879,12969,12928 ,0,0,0}, + {29944,29943,29946 ,12927,12926,12929 ,0,0,0}, {29986,29947,29943 ,12970,12930,12926 ,0,0,0}, + {29901,29945,29946 ,12883,12928,12929 ,0,0,0}, {29947,29946,29943 ,12930,12929,12926 ,0,0,0}, + {29987,29948,29986 ,12971,12931,12970 ,0,0,0}, {29948,29947,29986 ,12931,12930,12970 ,0,0,0}, + {29988,29949,29987 ,12972,12932,12971 ,0,0,0}, {29949,29948,29987 ,12932,12931,12971 ,0,0,0}, + {29989,29856,29988 ,12973,12838,12972 ,0,0,0}, {29856,29949,29988 ,12838,12932,12972 ,0,0,0}, + {29952,29854,29989 ,12935,12836,12973 ,0,0,0}, {29854,29856,29989 ,12836,12838,12973 ,0,0,0}, + {29952,29167,29950 ,12935,12974,12933 ,0,0,0}, {29854,29952,29951 ,12836,12935,12934 ,0,0,0}, + {29990,29953,29950 ,12975,12936,12933 ,0,0,0}, {29953,29951,29950 ,12936,12934,12933 ,0,0,0}, + {29991,29954,29990 ,12976,12937,12975 ,0,0,0}, {29954,29953,29990 ,12937,12936,12975 ,0,0,0}, + {29992,29955,29991 ,12977,12938,12976 ,0,0,0}, {29955,29954,29991 ,12938,12937,12976 ,0,0,0}, + {29993,29864,29992 ,12978,12846,12977 ,0,0,0}, {29864,29955,29992 ,12846,12938,12977 ,0,0,0}, + {29994,29862,29993 ,12979,12844,12978 ,0,0,0}, {29862,29864,29993 ,12844,12846,12978 ,0,0,0}, + {29956,29958,29994 ,12939,12942,12979 ,0,0,0}, {29862,29994,29958 ,12844,12979,12942 ,0,0,0}, + {29956,29957,29959 ,12939,12941,12943 ,0,0,0}, {29995,29960,29957 ,12980,12944,12941 ,0,0,0}, + {29912,29958,29959 ,12894,12942,12943 ,0,0,0}, {29960,29959,29957 ,12944,12943,12941 ,0,0,0}, + {29996,29961,29995 ,12981,12945,12980 ,0,0,0}, {29961,29960,29995 ,12945,12944,12980 ,0,0,0}, + {29997,29962,29996 ,12982,12946,12981 ,0,0,0}, {29962,29961,29996 ,12946,12945,12981 ,0,0,0}, + {29998,29915,29997 ,12983,12897,12982 ,0,0,0}, {29915,29962,29997 ,12897,12946,12982 ,0,0,0}, + {29965,29916,29998 ,12949,12898,12983 ,0,0,0}, {29916,29915,29998 ,12898,12897,12983 ,0,0,0}, + {29965,29189,29963 ,12949,12984,12947 ,0,0,0}, {29916,29965,29964 ,12898,12949,12948 ,0,0,0}, + {29999,29966,29963 ,12985,12950,12947 ,0,0,0}, {29966,29964,29963 ,12950,12948,12947 ,0,0,0}, + {30000,29967,29999 ,12986,12951,12985 ,0,0,0}, {29967,29966,29999 ,12951,12950,12985 ,0,0,0}, + {30001,29968,30000 ,12987,12952,12986 ,0,0,0}, {29968,29967,30000 ,12952,12951,12986 ,0,0,0}, + {30002,29969,30001 ,12988,12953,12987 ,0,0,0}, {29969,29968,30001 ,12953,12952,12987 ,0,0,0}, + {30003,29970,30002 ,12989,12954,12988 ,0,0,0}, {29970,29969,30002 ,12954,12953,12988 ,0,0,0}, + {30004,29971,30003 ,12990,12955,12989 ,0,0,0}, {29971,29970,30003 ,12955,12954,12989 ,0,0,0}, + {30005,29925,30004 ,12991,12907,12990 ,0,0,0}, {29925,29971,30004 ,12907,12955,12990 ,0,0,0}, + {30006,29926,30005 ,12992,12908,12991 ,0,0,0}, {29926,29925,30005 ,12908,12907,12991 ,0,0,0}, + {30007,29972,30006 ,12993,12956,12992 ,0,0,0}, {29972,29926,30006 ,12956,12908,12992 ,0,0,0}, + {30008,29702,30007 ,12994,12677,12993 ,0,0,0}, {29702,29972,30007 ,12677,12956,12993 ,0,0,0}, + {30008,29974,29700 ,12994,12958,12675 ,0,0,0}, {29700,29702,30008 ,12675,12677,12994 ,0,0,0}, + {29974,29973,29975 ,12958,12957,12959 ,0,0,0}, {29705,29975,29703 ,12680,12959,12678 ,0,0,0}, + {29835,29700,29975 ,12817,12675,12959 ,0,0,0}, {29973,29703,29975 ,12957,12678,12959 ,0,0,0}, + {29704,29703,29708 ,12679,12678,12683 ,0,0,0}, {29933,29636,29635 ,12915,12581,12580 ,0,0,0}, + {29635,29636,29932 ,12580,12581,12914 ,0,0,0}, {29261,29259,29640 ,12740,12995,12585 ,0,0,0}, + {29640,29259,29641 ,12585,12995,12586 ,0,0,0}, {29259,29127,29641 ,12995,12996,12586 ,0,0,0}, + {29641,29127,29936 ,12586,12996,12918 ,0,0,0}, {29127,29126,29936 ,12996,12997,12918 ,0,0,0}, + {29936,29126,29977 ,12918,12997,12961 ,0,0,0}, {29126,29147,29977 ,12997,12998,12961 ,0,0,0}, + {29977,29147,29978 ,12961,12998,12962 ,0,0,0}, {29147,29117,29978 ,12998,12999,12962 ,0,0,0}, + {29978,29117,29979 ,12962,12999,12963 ,0,0,0}, {29117,29152,29979 ,12999,13000,12963 ,0,0,0}, + {29979,29152,29980 ,12963,13000,12964 ,0,0,0}, {29152,29149,29980 ,13000,13001,12964 ,0,0,0}, + {29980,29149,29981 ,12964,13001,12965 ,0,0,0}, {29149,29154,29981 ,13001,13002,12965 ,0,0,0}, + {29154,29156,29982 ,13002,13003,12966 ,0,0,0}, {29154,29982,29981 ,13002,12966,12965 ,0,0,0}, + {29156,29122,29983 ,13003,13004,12967 ,0,0,0}, {29156,29983,29982 ,13003,12967,12966 ,0,0,0}, + {29122,29121,29984 ,13004,13005,12968 ,0,0,0}, {29122,29984,29983 ,13004,12968,12967 ,0,0,0}, + {29121,29158,29985 ,13005,13006,12969 ,0,0,0}, {29121,29985,29984 ,13005,12969,12968 ,0,0,0}, + {29158,29253,29944 ,13006,13007,12927 ,0,0,0}, {29158,29944,29985 ,13006,12927,12969 ,0,0,0}, + {29252,29944,29253 ,12925,12927,13007 ,0,0,0}, {29252,29161,29943 ,12925,13008,12926 ,0,0,0}, + {29943,29161,29986 ,12926,13008,12970 ,0,0,0}, {29161,29166,29986 ,13008,13009,12970 ,0,0,0}, + {29986,29166,29987 ,12970,13009,12971 ,0,0,0}, {29166,29164,29987 ,13009,13010,12971 ,0,0,0}, + {29164,29163,29988 ,13010,13011,12972 ,0,0,0}, {29164,29988,29987 ,13010,12972,12971 ,0,0,0}, + {29163,29251,29989 ,13011,13012,12973 ,0,0,0}, {29163,29989,29988 ,13011,12973,12972 ,0,0,0}, + {29251,29167,29952 ,13012,12974,12935 ,0,0,0}, {29251,29952,29989 ,13012,12935,12973 ,0,0,0}, + {29167,29250,29950 ,12974,13013,12933 ,0,0,0}, {29250,29246,29950 ,13013,13014,12933 ,0,0,0}, + {29950,29246,29990 ,12933,13014,12975 ,0,0,0}, {29246,29171,29990 ,13014,13015,12975 ,0,0,0}, + {29990,29171,29991 ,12975,13015,12976 ,0,0,0}, {29171,29173,29991 ,13015,13016,12976 ,0,0,0}, + {29173,29178,29992 ,13016,13017,12977 ,0,0,0}, {29173,29992,29991 ,13016,12977,12976 ,0,0,0}, + {29178,29176,29993 ,13017,13018,12978 ,0,0,0}, {29178,29993,29992 ,13017,12978,12977 ,0,0,0}, + {29176,29175,29994 ,13018,13019,12979 ,0,0,0}, {29176,29994,29993 ,13018,12979,12978 ,0,0,0}, + {29175,29244,29956 ,13019,13020,12939 ,0,0,0}, {29175,29956,29994 ,13019,12939,12979 ,0,0,0}, + {29243,29956,29244 ,12940,12939,13020 ,0,0,0}, {29243,29180,29957 ,12940,13021,12941 ,0,0,0}, + {29957,29180,29995 ,12941,13021,12980 ,0,0,0}, {29180,29187,29995 ,13021,13022,12980 ,0,0,0}, + {29187,29186,29996 ,13022,13023,12981 ,0,0,0}, {29187,29996,29995 ,13022,12981,12980 ,0,0,0}, + {29186,29185,29997 ,13023,13024,12982 ,0,0,0}, {29186,29997,29996 ,13023,12982,12981 ,0,0,0}, + {29185,29240,29998 ,13024,13025,12983 ,0,0,0}, {29185,29998,29997 ,13024,12983,12982 ,0,0,0}, + {29240,29189,29965 ,13025,12984,12949 ,0,0,0}, {29240,29965,29998 ,13025,12949,12983 ,0,0,0}, + {29189,29188,29963 ,12984,13026,12947 ,0,0,0}, {29188,29194,29963 ,13026,13027,12947 ,0,0,0}, + {29963,29194,29999 ,12947,13027,12985 ,0,0,0}, {29194,29193,29999 ,13027,13028,12985 ,0,0,0}, + {29999,29193,30000 ,12985,13028,12986 ,0,0,0}, {29193,29198,30000 ,13028,13029,12986 ,0,0,0}, + {30000,29198,30001 ,12986,13029,12987 ,0,0,0}, {29198,29196,30001 ,13029,13030,12987 ,0,0,0}, + {29196,29203,30002 ,13030,13031,12988 ,0,0,0}, {29196,30002,30001 ,13030,12988,12987 ,0,0,0}, + {29203,29200,30003 ,13031,13032,12989 ,0,0,0}, {29203,30003,30002 ,13031,12989,12988 ,0,0,0}, + {29200,29207,30004 ,13032,13033,12990 ,0,0,0}, {29200,30004,30003 ,13032,12990,12989 ,0,0,0}, + {29207,29204,30005 ,13033,13034,12991 ,0,0,0}, {29207,30005,30004 ,13033,12991,12990 ,0,0,0}, + {29204,29209,30006 ,13034,13035,12992 ,0,0,0}, {29204,30006,30005 ,13034,12992,12991 ,0,0,0}, + {29209,29208,30007 ,13035,13036,12993 ,0,0,0}, {29209,30007,30006 ,13035,12993,12992 ,0,0,0}, + {29208,29222,30008 ,13036,13037,12994 ,0,0,0}, {29208,30008,30007 ,13036,12994,12993 ,0,0,0}, + {29222,29221,29974 ,13037,13038,12958 ,0,0,0}, {29222,29974,30008 ,13037,12958,12994 ,0,0,0}, + {29221,29215,29973 ,13038,13039,12957 ,0,0,0}, {29221,29973,29974 ,13038,12957,12958 ,0,0,0}, + {29215,29217,29709 ,13039,12690,12684 ,0,0,0}, {29215,29709,29973 ,13039,12684,12957 ,0,0,0}, + {29710,29709,29217 ,12685,12684,12690 ,0,0,0}, {30009,30010,30011 ,13040,13041,13042 ,0,0,0}, + {30012,29086,29085 ,13043,13044,13045 ,0,0,0}, {30012,30013,29086 ,13043,13046,13044 ,0,0,0}, + {30014,29084,30015 ,13047,13048,13049 ,0,0,0}, {29085,30014,30012 ,13045,13047,13043 ,0,0,0}, + {30014,29085,29084 ,13047,13045,13048 ,0,0,0}, {29082,30016,29083 ,13050,13051,13052 ,0,0,0}, + {28997,29083,30016 ,13053,13052,13051 ,0,0,0}, {28997,30016,30015 ,13053,13051,13049 ,0,0,0}, + {29082,29081,30017 ,13050,13054,13055 ,0,0,0}, {28997,30015,29084 ,13053,13049,13048 ,0,0,0}, + {30016,29082,30017 ,13051,13050,13055 ,0,0,0}, {29087,29086,30013 ,13056,13044,13046 ,0,0,0}, + {30018,29080,30019 ,13057,13058,13059 ,0,0,0}, {30018,29081,29080 ,13057,13054,13058 ,0,0,0}, + {30020,30021,30022 ,13060,13061,13062 ,0,0,0}, {30023,30019,29079 ,13063,13059,13064 ,0,0,0}, + {29080,29079,30019 ,13058,13064,13059 ,0,0,0}, {30024,30023,29078 ,13065,13063,13066 ,0,0,0}, + {30024,29077,30025 ,13065,13067,13068 ,0,0,0}, {29078,29077,30024 ,13066,13067,13065 ,0,0,0}, + {30025,29077,29076 ,13068,13067,13069 ,0,0,0}, {29079,29078,30023 ,13064,13066,13063 ,0,0,0}, + {30017,29081,30018 ,13055,13054,13057 ,0,0,0}, {29075,29074,30026 ,13070,13071,13072 ,0,0,0}, + {29075,30027,29076 ,13070,13073,13069 ,0,0,0}, {29073,30028,29074 ,13074,13075,13071 ,0,0,0}, + {29075,30026,30027 ,13070,13072,13073 ,0,0,0}, {29073,29072,30029 ,13074,13076,13077 ,0,0,0}, + {30029,30028,29073 ,13077,13075,13074 ,0,0,0}, {29710,28768,28765 ,13078,11682,13079 ,0,0,0}, + {29074,30028,30026 ,13071,13075,13072 ,0,0,0}, {30029,29072,30030 ,13077,13076,13080 ,0,0,0}, + {30031,29710,28765 ,13081,13078,13079 ,0,0,0}, {30032,30033,30029 ,13082,13083,13077 ,0,0,0}, + {30034,30035,30036 ,13084,13085,13086 ,0,0,0}, {30037,30038,30039 ,13087,13088,13089 ,0,0,0}, + {30040,30041,29930 ,13090,13091,13092 ,0,0,0}, {30040,29704,30042 ,13090,13093,13094 ,0,0,0}, + {30030,29072,29071 ,13080,13076,13095 ,0,0,0}, {30031,28765,30036 ,13081,13079,13086 ,0,0,0}, + {30033,30043,30039 ,13083,13096,13089 ,0,0,0}, {29931,30041,30044 ,13097,13091,13098 ,0,0,0}, + {30045,29758,30046 ,13099,13100,13101 ,0,0,0}, {28634,30047,29071 ,13102,13103,13095 ,0,0,0}, + {30048,29837,30044 ,13104,13105,13098 ,0,0,0}, {29838,29837,30048 ,13106,13105,13104 ,0,0,0}, + {29931,30044,29792 ,13097,13098,13107 ,0,0,0}, {28639,29719,28637 ,11553,13108,13109 ,0,0,0}, + {28634,30045,30047 ,13102,13099,13103 ,0,0,0}, {29758,30045,29719 ,13100,13099,13108 ,0,0,0}, + {30045,28637,29719 ,13099,13109,13108 ,0,0,0}, {30043,30049,30039 ,13096,13110,13089 ,0,0,0}, + {30027,30025,29076 ,13073,13068,13069 ,0,0,0}, {30050,29087,30013 ,13111,13056,13046 ,0,0,0}, + {29088,30050,30051 ,13112,13111,13113 ,0,0,0}, {30050,29088,29087 ,13111,13112,13056 ,0,0,0}, + {30052,29047,30051 ,13114,13115,13113 ,0,0,0}, {29088,30051,29047 ,13112,13113,13115 ,0,0,0}, + {29089,30052,29090 ,13116,13114,13117 ,0,0,0}, {29089,29047,30052 ,13116,13115,13114 ,0,0,0}, + {29091,29090,30053 ,13118,13117,13119 ,0,0,0}, {30052,30053,29090 ,13114,13119,13117 ,0,0,0}, + {30054,29092,29091 ,13120,13121,13118 ,0,0,0}, {29091,30053,30054 ,13118,13119,13120 ,0,0,0}, + {30054,30055,29092 ,13120,13122,13121 ,0,0,0}, {29092,30055,29093 ,13121,13122,13123 ,0,0,0}, + {29093,30055,30056 ,13123,13122,13124 ,0,0,0}, {30057,30058,30059 ,13125,13126,13127 ,0,0,0}, + {30060,29094,30056 ,13128,13129,13124 ,0,0,0}, {29093,30056,29094 ,13123,13124,13129 ,0,0,0}, + {30060,30061,29095 ,13128,13130,13131 ,0,0,0}, {29095,29094,30060 ,13131,13129,13128 ,0,0,0}, + {29012,29096,30061 ,13132,13133,13130 ,0,0,0}, {30061,29096,29095 ,13130,13133,13131 ,0,0,0}, + {30062,29097,29012 ,13134,13135,13132 ,0,0,0}, {29012,30061,30062 ,13132,13130,13134 ,0,0,0}, + {29097,30063,29098 ,13135,13136,13137 ,0,0,0}, {30063,29097,30062 ,13136,13135,13134 ,0,0,0}, + {29099,29098,30064 ,13138,13137,13139 ,0,0,0}, {30063,30064,29098 ,13136,13139,13137 ,0,0,0}, + {30065,29099,30064 ,13140,13138,13139 ,0,0,0}, {30065,29100,29099 ,13140,13141,13138 ,0,0,0}, + {30065,30066,29100 ,13140,13142,13141 ,0,0,0}, {30067,30068,30069 ,13143,13144,13145 ,0,0,0}, + {29101,30066,30070 ,13146,13142,13147 ,0,0,0}, {30066,29101,29100 ,13142,13146,13141 ,0,0,0}, + {30071,29058,30070 ,13148,13149,13147 ,0,0,0}, {29101,30070,29058 ,13146,13147,13149 ,0,0,0}, + {29102,30071,29103 ,13150,13148,13151 ,0,0,0}, {29102,29058,30071 ,13150,13149,13148 ,0,0,0}, + {29104,29103,30072 ,13152,13151,13153 ,0,0,0}, {30071,30072,29103 ,13148,13153,13151 ,0,0,0}, + {30073,29105,29104 ,13154,13155,13152 ,0,0,0}, {29104,30072,30073 ,13152,13153,13154 ,0,0,0}, + {29105,30074,29106 ,13155,13156,13157 ,0,0,0}, {30074,29105,30073 ,13156,13155,13154 ,0,0,0}, + {29107,29106,30075 ,13158,13157,13159 ,0,0,0}, {30074,30075,29106 ,13156,13159,13157 ,0,0,0}, + {30076,29107,30075 ,13160,13158,13159 ,0,0,0}, {30076,29108,29107 ,13160,13161,13158 ,0,0,0}, + {30076,30077,29108 ,13160,13162,13161 ,0,0,0}, {30078,30079,30080 ,13163,13164,13165 ,0,0,0}, + {29109,30077,30079 ,13166,13162,13164 ,0,0,0}, {30077,29109,29108 ,13162,13166,13161 ,0,0,0}, + {30081,29110,30079 ,13167,13168,13164 ,0,0,0}, {29109,30079,29110 ,13166,13164,13168 ,0,0,0}, + {30082,30083,30084 ,13169,13170,13171 ,0,0,0}, {29111,29110,30081 ,13172,13168,13167 ,0,0,0}, + {30085,30086,30087 ,13173,13174,13175 ,0,0,0}, {30088,30089,30090 ,13176,13177,13178 ,0,0,0}, + {30091,30085,30092 ,13179,13173,13180 ,0,0,0}, {30093,30094,30095 ,13181,13182,13183 ,0,0,0}, + {30096,30097,30098 ,13184,13185,13186 ,0,0,0}, {30093,30099,30100 ,13181,13187,13188 ,0,0,0}, + {30101,30102,30103 ,13189,13190,13191 ,0,0,0}, {30100,30099,30104 ,13188,13187,13192 ,0,0,0}, + {29112,29111,30105 ,13193,13172,13194 ,0,0,0}, {28702,30104,30099 ,11616,13192,13187 ,0,0,0}, + {30106,30107,30108 ,13195,13196,13197 ,0,0,0}, {29111,30081,30105 ,13172,13167,13194 ,0,0,0}, + {29112,30090,29113 ,13193,13178,13198 ,0,0,0}, {30078,30081,30079 ,13163,13167,13164 ,0,0,0}, + {29114,29113,30107 ,13199,13198,13196 ,0,0,0}, {30090,30107,29113 ,13178,13196,13198 ,0,0,0}, + {29115,30106,29116 ,13200,13195,13201 ,0,0,0}, {29114,30107,30106 ,13199,13196,13195 ,0,0,0}, + {29116,30109,28736 ,13201,13202,11650 ,0,0,0}, {30106,30109,29116 ,13195,13202,13201 ,0,0,0}, + {28637,30045,28634 ,13109,13099,13102 ,0,0,0}, {29796,30046,29758 ,13203,13101,13100 ,0,0,0}, + {29796,30048,30046 ,13203,13104,13101 ,0,0,0}, {30047,30030,29071 ,13103,13080,13095 ,0,0,0}, + {30047,30046,30110 ,13103,13101,13204 ,0,0,0}, {30111,30028,30033 ,13205,13075,13083 ,0,0,0}, + {30030,30110,30032 ,13080,13204,13082 ,0,0,0}, {30112,30026,30111 ,13206,13072,13205 ,0,0,0}, + {30032,30029,30030 ,13082,13077,13080 ,0,0,0}, {30113,30027,30112 ,13207,13073,13206 ,0,0,0}, + {30033,30028,30029 ,13083,13075,13077 ,0,0,0}, {30114,30025,30113 ,13208,13068,13207 ,0,0,0}, + {30111,30026,30028 ,13205,13072,13075 ,0,0,0}, {30115,30024,30114 ,13209,13065,13208 ,0,0,0}, + {30112,30027,30026 ,13206,13073,13072 ,0,0,0}, {30116,30023,30115 ,13210,13063,13209 ,0,0,0}, + {30113,30025,30027 ,13207,13068,13073 ,0,0,0}, {30117,30019,30116 ,13211,13059,13210 ,0,0,0}, + {30114,30024,30025 ,13208,13065,13068 ,0,0,0}, {30117,30118,30018 ,13211,13212,13057 ,0,0,0}, + {30023,30024,30115 ,13063,13065,13209 ,0,0,0}, {30119,30017,30118 ,13213,13055,13212 ,0,0,0}, + {30019,30023,30116 ,13059,13063,13210 ,0,0,0}, {30020,30016,30119 ,13060,13051,13213 ,0,0,0}, + {30018,30019,30117 ,13057,13059,13211 ,0,0,0}, {30120,30015,30020 ,13214,13049,13060 ,0,0,0}, + {30017,30018,30118 ,13055,13057,13212 ,0,0,0}, {30121,30014,30120 ,13215,13047,13214 ,0,0,0}, + {30016,30017,30119 ,13051,13055,13213 ,0,0,0}, {30122,30012,30121 ,13216,13043,13215 ,0,0,0}, + {30020,30015,30016 ,13060,13049,13051 ,0,0,0}, {30123,30013,30122 ,13217,13046,13216 ,0,0,0}, + {30120,30014,30015 ,13214,13047,13049 ,0,0,0}, {30123,30124,30050 ,13217,13218,13111 ,0,0,0}, + {30012,30014,30121 ,13043,13047,13215 ,0,0,0}, {30125,30051,30124 ,13219,13113,13218 ,0,0,0}, + {30013,30012,30122 ,13046,13043,13216 ,0,0,0}, {30126,30052,30125 ,13220,13114,13219 ,0,0,0}, + {30050,30013,30123 ,13111,13046,13217 ,0,0,0}, {30127,30053,30126 ,13221,13119,13220 ,0,0,0}, + {30051,30050,30124 ,13113,13111,13218 ,0,0,0}, {30128,30054,30127 ,13222,13120,13221 ,0,0,0}, + {30052,30051,30125 ,13114,13113,13219 ,0,0,0}, {30129,30055,30128 ,13223,13122,13222 ,0,0,0}, + {30126,30053,30052 ,13220,13119,13114 ,0,0,0}, {30129,30130,30056 ,13223,13224,13124 ,0,0,0}, + {30054,30053,30127 ,13120,13119,13221 ,0,0,0}, {30131,30060,30130 ,13225,13128,13224 ,0,0,0}, + {30055,30054,30128 ,13122,13120,13222 ,0,0,0}, {30057,30061,30131 ,13125,13130,13225 ,0,0,0}, + {30056,30055,30129 ,13124,13122,13223 ,0,0,0}, {30132,30062,30057 ,13226,13134,13125 ,0,0,0}, + {30060,30056,30130 ,13128,13124,13224 ,0,0,0}, {30133,30063,30132 ,13227,13136,13226 ,0,0,0}, + {30061,30060,30131 ,13130,13128,13225 ,0,0,0}, {30134,30064,30133 ,13228,13139,13227 ,0,0,0}, + {30057,30062,30061 ,13125,13134,13130 ,0,0,0}, {30135,30065,30134 ,13229,13140,13228 ,0,0,0}, + {30132,30063,30062 ,13226,13136,13134 ,0,0,0}, {30135,30136,30066 ,13229,13230,13142 ,0,0,0}, + {30064,30063,30133 ,13139,13136,13227 ,0,0,0}, {30137,30070,30136 ,13231,13147,13230 ,0,0,0}, + {30065,30064,30134 ,13140,13139,13228 ,0,0,0}, {30138,30071,30137 ,13232,13148,13231 ,0,0,0}, + {30066,30065,30135 ,13142,13140,13229 ,0,0,0}, {30139,30072,30138 ,13233,13153,13232 ,0,0,0}, + {30070,30066,30136 ,13147,13142,13230 ,0,0,0}, {30140,30073,30139 ,13234,13154,13233 ,0,0,0}, + {30137,30071,30070 ,13231,13148,13147 ,0,0,0}, {30141,30074,30140 ,13235,13156,13234 ,0,0,0}, + {30138,30072,30071 ,13232,13153,13148 ,0,0,0}, {30142,30075,30141 ,13236,13159,13235 ,0,0,0}, + {30139,30073,30072 ,13233,13154,13153 ,0,0,0}, {30143,30076,30142 ,13237,13160,13236 ,0,0,0}, + {30140,30074,30073 ,13234,13156,13154 ,0,0,0}, {30143,30080,30077 ,13237,13165,13162 ,0,0,0}, + {30075,30074,30141 ,13159,13156,13235 ,0,0,0}, {30081,30078,30144 ,13167,13163,13238 ,0,0,0}, + {30076,30075,30142 ,13160,13159,13236 ,0,0,0}, {30098,30089,30102 ,13186,13177,13190 ,0,0,0}, + {30077,30076,30143 ,13162,13160,13237 ,0,0,0}, {30088,30105,30144 ,13176,13194,13238 ,0,0,0}, + {30079,30077,30080 ,13164,13162,13165 ,0,0,0}, {30088,30144,30145 ,13176,13238,13239 ,0,0,0}, + {30097,30108,30098 ,13185,13197,13186 ,0,0,0}, {30105,30090,29112 ,13194,13178,13193 ,0,0,0}, + {30105,30081,30144 ,13194,13167,13238 ,0,0,0}, {30146,30109,30147 ,13240,13202,13241 ,0,0,0}, + {30105,30088,30090 ,13194,13176,13178 ,0,0,0}, {30108,30107,30089 ,13197,13196,13177 ,0,0,0}, + {30148,30149,30109 ,13242,13243,13202 ,0,0,0}, {29114,30106,29115 ,13199,13195,13200 ,0,0,0}, + {30106,30147,30109 ,13195,13241,13202 ,0,0,0}, {28736,30109,30149 ,11650,13202,13243 ,0,0,0}, + {30045,30046,30047 ,13099,13101,13103 ,0,0,0}, {29838,30048,29796 ,13106,13104,13203 ,0,0,0}, + {29930,29976,30040 ,13092,13244,13090 ,0,0,0}, {30047,30110,30030 ,13103,13204,13080 ,0,0,0}, + {30110,30048,30150 ,13204,13104,13245 ,0,0,0}, {30039,30038,30111 ,13089,13088,13205 ,0,0,0}, + {30043,30032,30150 ,13096,13082,13245 ,0,0,0}, {30038,30151,30112 ,13088,13246,13206 ,0,0,0}, + {30043,30033,30032 ,13096,13083,13082 ,0,0,0}, {30151,30152,30113 ,13246,13247,13207 ,0,0,0}, + {30039,30111,30033 ,13089,13205,13083 ,0,0,0}, {30152,30153,30114 ,13247,13248,13208 ,0,0,0}, + {30038,30112,30111 ,13088,13206,13205 ,0,0,0}, {30153,30154,30115 ,13248,13249,13209 ,0,0,0}, + {30151,30113,30112 ,13246,13207,13206 ,0,0,0}, {30154,30155,30116 ,13249,13250,13210 ,0,0,0}, + {30152,30114,30113 ,13247,13208,13207 ,0,0,0}, {30155,30156,30117 ,13250,13251,13211 ,0,0,0}, + {30153,30115,30114 ,13248,13209,13208 ,0,0,0}, {30156,30157,30118 ,13251,13252,13212 ,0,0,0}, + {30154,30116,30115 ,13249,13210,13209 ,0,0,0}, {30157,30021,30119 ,13252,13061,13213 ,0,0,0}, + {30117,30116,30155 ,13211,13210,13250 ,0,0,0}, {30158,30159,30160 ,13253,13254,13255 ,0,0,0}, + {30118,30117,30156 ,13212,13211,13251 ,0,0,0}, {30022,30159,30120 ,13062,13254,13214 ,0,0,0}, + {30119,30118,30157 ,13213,13212,13252 ,0,0,0}, {30159,30158,30121 ,13254,13253,13215 ,0,0,0}, + {30020,30119,30021 ,13060,13213,13061 ,0,0,0}, {30158,30161,30122 ,13253,13256,13216 ,0,0,0}, + {30022,30120,30020 ,13062,13214,13060 ,0,0,0}, {30161,30162,30123 ,13256,13257,13217 ,0,0,0}, + {30159,30121,30120 ,13254,13215,13214 ,0,0,0}, {30162,30163,30124 ,13257,13258,13218 ,0,0,0}, + {30158,30122,30121 ,13253,13216,13215 ,0,0,0}, {30163,30164,30125 ,13258,13259,13219 ,0,0,0}, + {30123,30122,30161 ,13217,13216,13256 ,0,0,0}, {30010,30126,30164 ,13041,13220,13259 ,0,0,0}, + {30124,30123,30162 ,13218,13217,13257 ,0,0,0}, {30010,30009,30127 ,13041,13040,13221 ,0,0,0}, + {30125,30124,30163 ,13219,13218,13258 ,0,0,0}, {30009,30165,30128 ,13040,13260,13222 ,0,0,0}, + {30164,30126,30125 ,13259,13220,13219 ,0,0,0}, {30165,30166,30129 ,13260,13261,13223 ,0,0,0}, + {30010,30127,30126 ,13041,13221,13220 ,0,0,0}, {30166,30167,30130 ,13261,13262,13224 ,0,0,0}, + {30009,30128,30127 ,13040,13222,13221 ,0,0,0}, {30167,30058,30131 ,13262,13126,13225 ,0,0,0}, + {30129,30128,30165 ,13223,13222,13260 ,0,0,0}, {30168,30169,30170 ,13263,13264,13265 ,0,0,0}, + {30130,30129,30166 ,13224,13223,13261 ,0,0,0}, {30059,30171,30132 ,13127,13266,13226 ,0,0,0}, + {30131,30130,30167 ,13225,13224,13262 ,0,0,0}, {30171,30172,30133 ,13266,13267,13227 ,0,0,0}, + {30057,30131,30058 ,13125,13225,13126 ,0,0,0}, {30172,30173,30134 ,13267,13268,13228 ,0,0,0}, + {30059,30132,30057 ,13127,13226,13125 ,0,0,0}, {30173,30174,30135 ,13268,13269,13229 ,0,0,0}, + {30171,30133,30132 ,13266,13227,13226 ,0,0,0}, {30174,30175,30136 ,13269,13270,13230 ,0,0,0}, + {30172,30134,30133 ,13267,13228,13227 ,0,0,0}, {30175,30176,30137 ,13270,13271,13231 ,0,0,0}, + {30135,30134,30173 ,13229,13228,13268 ,0,0,0}, {30176,30067,30138 ,13271,13143,13232 ,0,0,0}, + {30136,30135,30174 ,13230,13229,13269 ,0,0,0}, {30067,30069,30139 ,13143,13145,13233 ,0,0,0}, + {30137,30136,30175 ,13231,13230,13270 ,0,0,0}, {30069,30177,30140 ,13145,13272,13234 ,0,0,0}, + {30176,30138,30137 ,13271,13232,13231 ,0,0,0}, {30177,30178,30141 ,13272,13273,13235 ,0,0,0}, + {30067,30139,30138 ,13143,13233,13232 ,0,0,0}, {30178,30179,30142 ,13273,13274,13236 ,0,0,0}, + {30069,30140,30139 ,13145,13234,13233 ,0,0,0}, {30179,30180,30143 ,13274,13275,13237 ,0,0,0}, + {30177,30141,30140 ,13272,13235,13234 ,0,0,0}, {30180,30181,30080 ,13275,13276,13165 ,0,0,0}, + {30178,30142,30141 ,13273,13236,13235 ,0,0,0}, {30181,30182,30078 ,13276,13277,13163 ,0,0,0}, + {30179,30143,30142 ,13274,13237,13236 ,0,0,0}, {30182,30145,30144 ,13277,13239,13238 ,0,0,0}, + {30180,30080,30143 ,13275,13165,13237 ,0,0,0}, {30145,30102,30088 ,13239,13190,13176 ,0,0,0}, + {30078,30080,30181 ,13163,13165,13276 ,0,0,0}, {30183,30097,30184 ,13278,13185,13279 ,0,0,0}, + {30078,30182,30144 ,13163,13277,13238 ,0,0,0}, {30108,30097,30147 ,13197,13185,13241 ,0,0,0}, + {30096,30184,30097 ,13184,13279,13185 ,0,0,0}, {30090,30089,30107 ,13178,13177,13196 ,0,0,0}, + {30102,30089,30088 ,13190,13177,13176 ,0,0,0}, {30185,30146,30082 ,13280,13240,13169 ,0,0,0}, + {30146,30148,30109 ,13240,13242,13202 ,0,0,0}, {30106,30108,30147 ,13195,13197,13241 ,0,0,0}, + {30146,30147,30183 ,13240,13241,13278 ,0,0,0}, {30185,30148,30146 ,13280,13242,13240 ,0,0,0}, + {30046,30048,30110 ,13101,13104,13204 ,0,0,0}, {29792,30044,29837 ,13107,13098,13105 ,0,0,0}, + {28763,30036,28765 ,13281,13086,13079 ,0,0,0}, {30110,30150,30032 ,13204,13245,13082 ,0,0,0}, + {30150,30044,30186 ,13245,13098,13282 ,0,0,0}, {30038,30187,30151 ,13088,13283,13246 ,0,0,0}, + {30049,30043,30186 ,13110,13096,13282 ,0,0,0}, {30151,30188,30152 ,13246,13284,13247 ,0,0,0}, + {30049,30037,30039 ,13110,13087,13089 ,0,0,0}, {30189,30190,30191 ,13285,13286,13287 ,0,0,0}, + {30037,30187,30038 ,13087,13283,13088 ,0,0,0}, {30153,30152,30192 ,13248,13247,13288 ,0,0,0}, + {30187,30188,30151 ,13283,13284,13246 ,0,0,0}, {30154,30153,30191 ,13249,13248,13287 ,0,0,0}, + {30188,30192,30152 ,13284,13288,13247 ,0,0,0}, {30155,30154,30190 ,13250,13249,13286 ,0,0,0}, + {30192,30191,30153 ,13288,13287,13248 ,0,0,0}, {30156,30155,30193 ,13251,13250,13289 ,0,0,0}, + {30191,30190,30154 ,13287,13286,13249 ,0,0,0}, {30157,30156,30194 ,13252,13251,13290 ,0,0,0}, + {30190,30193,30155 ,13286,13289,13250 ,0,0,0}, {30021,30157,30195 ,13061,13252,13291 ,0,0,0}, + {30193,30194,30156 ,13289,13290,13251 ,0,0,0}, {30022,30021,30196 ,13062,13061,13292 ,0,0,0}, + {30194,30195,30157 ,13290,13291,13252 ,0,0,0}, {30159,30022,30197 ,13254,13062,13293 ,0,0,0}, + {30196,30021,30195 ,13292,13061,13291 ,0,0,0}, {30198,30199,30200 ,13294,13295,13296 ,0,0,0}, + {30197,30022,30196 ,13293,13062,13292 ,0,0,0}, {30161,30158,30201 ,13256,13253,13297 ,0,0,0}, + {30197,30160,30159 ,13293,13255,13254 ,0,0,0}, {30162,30161,30200 ,13257,13256,13296 ,0,0,0}, + {30160,30201,30158 ,13255,13297,13253 ,0,0,0}, {30163,30162,30199 ,13258,13257,13295 ,0,0,0}, + {30201,30200,30161 ,13297,13296,13256 ,0,0,0}, {30164,30163,30202 ,13259,13258,13298 ,0,0,0}, + {30200,30199,30162 ,13296,13295,13257 ,0,0,0}, {30010,30164,30203 ,13041,13259,13299 ,0,0,0}, + {30202,30163,30199 ,13298,13258,13295 ,0,0,0}, {30204,30205,30206 ,13300,13301,13302 ,0,0,0}, + {30203,30164,30202 ,13299,13259,13298 ,0,0,0}, {30165,30009,30207 ,13260,13040,13303 ,0,0,0}, + {30203,30011,30010 ,13299,13042,13041 ,0,0,0}, {30166,30165,30206 ,13261,13260,13302 ,0,0,0}, + {30011,30207,30009 ,13042,13303,13040 ,0,0,0}, {30167,30166,30205 ,13262,13261,13301 ,0,0,0}, + {30207,30206,30165 ,13303,13302,13260 ,0,0,0}, {30058,30167,30208 ,13126,13262,13304 ,0,0,0}, + {30206,30205,30166 ,13302,13301,13261 ,0,0,0}, {30059,30058,30209 ,13127,13126,13305 ,0,0,0}, + {30205,30208,30167 ,13301,13304,13262 ,0,0,0}, {30171,30059,30210 ,13266,13127,13306 ,0,0,0}, + {30209,30058,30208 ,13305,13126,13304 ,0,0,0}, {30172,30171,30211 ,13267,13266,13307 ,0,0,0}, + {30210,30059,30209 ,13306,13127,13305 ,0,0,0}, {30173,30172,30168 ,13268,13267,13263 ,0,0,0}, + {30210,30211,30171 ,13306,13307,13266 ,0,0,0}, {30174,30173,30170 ,13269,13268,13265 ,0,0,0}, + {30211,30168,30172 ,13307,13263,13267 ,0,0,0}, {30175,30174,30212 ,13270,13269,13308 ,0,0,0}, + {30168,30170,30173 ,13263,13265,13268 ,0,0,0}, {30176,30175,30213 ,13271,13270,13309 ,0,0,0}, + {30170,30212,30174 ,13265,13308,13269 ,0,0,0}, {30067,30176,30214 ,13143,13271,13310 ,0,0,0}, + {30213,30175,30212 ,13309,13270,13308 ,0,0,0}, {30215,30216,30217 ,13311,13312,13313 ,0,0,0}, + {30214,30176,30213 ,13310,13271,13309 ,0,0,0}, {30177,30069,30218 ,13272,13145,13314 ,0,0,0}, + {30214,30068,30067 ,13310,13144,13143 ,0,0,0}, {30178,30177,30217 ,13273,13272,13313 ,0,0,0}, + {30068,30218,30069 ,13144,13314,13145 ,0,0,0}, {30179,30178,30216 ,13274,13273,13312 ,0,0,0}, + {30218,30217,30177 ,13314,13313,13272 ,0,0,0}, {30180,30179,30219 ,13275,13274,13315 ,0,0,0}, + {30217,30216,30178 ,13313,13312,13273 ,0,0,0}, {30181,30180,30220 ,13276,13275,13316 ,0,0,0}, + {30216,30219,30179 ,13312,13315,13274 ,0,0,0}, {30182,30181,30221 ,13277,13276,13317 ,0,0,0}, + {30219,30220,30180 ,13315,13316,13275 ,0,0,0}, {30145,30182,30222 ,13239,13277,13318 ,0,0,0}, + {30220,30221,30181 ,13316,13317,13276 ,0,0,0}, {30102,30145,30103 ,13190,13239,13191 ,0,0,0}, + {30221,30222,30182 ,13317,13318,13277 ,0,0,0}, {30098,30102,30101 ,13186,13190,13189 ,0,0,0}, + {30222,30103,30145 ,13318,13191,13239 ,0,0,0}, {30083,30184,30086 ,13170,13279,13174 ,0,0,0}, + {30184,30223,30086 ,13279,13319,13174 ,0,0,0}, {30089,30098,30108 ,13177,13186,13197 ,0,0,0}, + {30101,30096,30098 ,13189,13184,13186 ,0,0,0}, {30224,30082,30084 ,13320,13169,13171 ,0,0,0}, + {30146,30183,30082 ,13240,13278,13169 ,0,0,0}, {30147,30097,30183 ,13241,13185,13278 ,0,0,0}, + {30183,30083,30082 ,13278,13170,13169 ,0,0,0}, {30185,30082,30224 ,13280,13169,13320 ,0,0,0}, + {30044,30150,30048 ,13098,13245,13104 ,0,0,0}, {29930,30041,29931 ,13092,13091,13097 ,0,0,0}, + {30049,30225,30037 ,13110,13321,13087 ,0,0,0}, {30150,30186,30043 ,13245,13282,13096 ,0,0,0}, + {30041,30226,30186 ,13091,13322,13282 ,0,0,0}, {30187,30037,30227 ,13283,13087,13323 ,0,0,0}, + {30226,30225,30049 ,13322,13321,13110 ,0,0,0}, {30188,30187,30228 ,13284,13283,13324 ,0,0,0}, + {30037,30225,30227 ,13087,13321,13323 ,0,0,0}, {30192,30188,30229 ,13288,13284,13325 ,0,0,0}, + {30187,30227,30228 ,13283,13323,13324 ,0,0,0}, {30191,30192,30230 ,13287,13288,13326 ,0,0,0}, + {30228,30229,30188 ,13324,13325,13284 ,0,0,0}, {30231,30193,30190 ,13327,13289,13286 ,0,0,0}, + {30229,30230,30192 ,13325,13326,13288 ,0,0,0}, {30232,30233,30234 ,13328,13329,13330 ,0,0,0}, + {30230,30189,30191 ,13326,13285,13287 ,0,0,0}, {30193,30235,30194 ,13289,13331,13290 ,0,0,0}, + {30189,30231,30190 ,13285,13327,13286 ,0,0,0}, {30194,30233,30195 ,13290,13329,13291 ,0,0,0}, + {30231,30235,30193 ,13327,13331,13289 ,0,0,0}, {30195,30232,30196 ,13291,13328,13292 ,0,0,0}, + {30235,30233,30194 ,13331,13329,13290 ,0,0,0}, {30196,30236,30197 ,13292,13332,13293 ,0,0,0}, + {30233,30232,30195 ,13329,13328,13291 ,0,0,0}, {30197,30237,30160 ,13293,13333,13255 ,0,0,0}, + {30232,30236,30196 ,13328,13332,13292 ,0,0,0}, {30201,30160,30238 ,13297,13255,13334 ,0,0,0}, + {30236,30237,30197 ,13332,13333,13293 ,0,0,0}, {30200,30201,30239 ,13296,13297,13335 ,0,0,0}, + {30237,30238,30160 ,13333,13334,13255 ,0,0,0}, {30240,30241,30242 ,13336,13337,13338 ,0,0,0}, + {30238,30239,30201 ,13334,13335,13297 ,0,0,0}, {30199,30243,30202 ,13295,13339,13298 ,0,0,0}, + {30239,30198,30200 ,13335,13294,13296 ,0,0,0}, {30202,30244,30203 ,13298,13340,13299 ,0,0,0}, + {30198,30243,30199 ,13294,13339,13295 ,0,0,0}, {30203,30245,30011 ,13299,13341,13042 ,0,0,0}, + {30243,30244,30202 ,13339,13340,13298 ,0,0,0}, {30207,30011,30246 ,13303,13042,13342 ,0,0,0}, + {30244,30245,30203 ,13340,13341,13299 ,0,0,0}, {30206,30207,30247 ,13302,13303,13343 ,0,0,0}, + {30245,30246,30011 ,13341,13342,13042 ,0,0,0}, {30248,30249,30250 ,13344,13345,13346 ,0,0,0}, + {30246,30247,30207 ,13342,13343,13303 ,0,0,0}, {30205,30251,30208 ,13301,13347,13304 ,0,0,0}, + {30247,30204,30206 ,13343,13300,13302 ,0,0,0}, {30208,30252,30209 ,13304,13348,13305 ,0,0,0}, + {30204,30251,30205 ,13300,13347,13301 ,0,0,0}, {30209,30253,30210 ,13305,13349,13306 ,0,0,0}, + {30251,30252,30208 ,13347,13348,13304 ,0,0,0}, {30210,30254,30211 ,13306,13350,13307 ,0,0,0}, + {30252,30253,30209 ,13348,13349,13305 ,0,0,0}, {30168,30211,30255 ,13263,13307,13351 ,0,0,0}, + {30253,30254,30210 ,13349,13350,13306 ,0,0,0}, {30256,30257,30258 ,13352,13353,13354 ,0,0,0}, + {30254,30255,30211 ,13350,13351,13307 ,0,0,0}, {30170,30259,30212 ,13265,13355,13308 ,0,0,0}, + {30255,30169,30168 ,13351,13264,13263 ,0,0,0}, {30212,30257,30213 ,13308,13353,13309 ,0,0,0}, + {30169,30259,30170 ,13264,13355,13265 ,0,0,0}, {30213,30256,30214 ,13309,13352,13310 ,0,0,0}, + {30259,30257,30212 ,13355,13353,13308 ,0,0,0}, {30214,30260,30068 ,13310,13356,13144 ,0,0,0}, + {30257,30256,30213 ,13353,13352,13309 ,0,0,0}, {30218,30068,30261 ,13314,13144,13357 ,0,0,0}, + {30256,30260,30214 ,13352,13356,13310 ,0,0,0}, {30217,30218,30262 ,13313,13314,13358 ,0,0,0}, + {30260,30261,30068 ,13356,13357,13144 ,0,0,0}, {30263,30219,30216 ,13359,13315,13312 ,0,0,0}, + {30261,30262,30218 ,13357,13358,13314 ,0,0,0}, {30264,30265,30266 ,13360,13361,13362 ,0,0,0}, + {30262,30215,30217 ,13358,13311,13313 ,0,0,0}, {30219,30267,30220 ,13315,13363,13316 ,0,0,0}, + {30215,30263,30216 ,13311,13359,13312 ,0,0,0}, {30220,30265,30221 ,13316,13361,13317 ,0,0,0}, + {30263,30267,30219 ,13359,13363,13315 ,0,0,0}, {30221,30264,30222 ,13317,13360,13318 ,0,0,0}, + {30267,30265,30220 ,13363,13361,13316 ,0,0,0}, {30222,30268,30103 ,13318,13364,13191 ,0,0,0}, + {30265,30264,30221 ,13361,13360,13317 ,0,0,0}, {30103,30269,30101 ,13191,13365,13189 ,0,0,0}, + {30264,30268,30222 ,13360,13364,13318 ,0,0,0}, {30101,30270,30096 ,13189,13366,13184 ,0,0,0}, + {30268,30269,30103 ,13364,13365,13191 ,0,0,0}, {30096,30223,30184 ,13184,13319,13279 ,0,0,0}, + {30270,30101,30269 ,13366,13189,13365 ,0,0,0}, {30271,30272,30084 ,13367,13368,13171 ,0,0,0}, + {30096,30270,30223 ,13184,13366,13319 ,0,0,0}, {30273,30084,30272 ,13369,13171,13368 ,0,0,0}, + {30274,30224,30084 ,13370,13320,13171 ,0,0,0}, {30183,30184,30083 ,13278,13279,13170 ,0,0,0}, + {30083,30271,30084 ,13170,13367,13171 ,0,0,0}, {30273,30274,30084 ,13369,13370,13171 ,0,0,0}, + {30041,30186,30044 ,13091,13282,13098 ,0,0,0}, {29704,30040,29976 ,13093,13090,13244 ,0,0,0}, + {30225,30275,30227 ,13321,13371,13323 ,0,0,0}, {30186,30226,30049 ,13282,13322,13110 ,0,0,0}, + {30040,30276,30226 ,13090,13372,13322 ,0,0,0}, {30228,30227,30277 ,13324,13323,13373 ,0,0,0}, + {30225,30276,30275 ,13321,13372,13371 ,0,0,0}, {30229,30228,30278 ,13325,13324,13374 ,0,0,0}, + {30227,30275,30277 ,13323,13371,13373 ,0,0,0}, {30230,30229,30279 ,13326,13325,13375 ,0,0,0}, + {30228,30277,30278 ,13324,13373,13374 ,0,0,0}, {30189,30230,30280 ,13285,13326,13376 ,0,0,0}, + {30229,30278,30279 ,13325,13374,13375 ,0,0,0}, {30231,30189,30281 ,13327,13285,13377 ,0,0,0}, + {30230,30279,30280 ,13326,13375,13376 ,0,0,0}, {30235,30231,30282 ,13331,13327,13378 ,0,0,0}, + {30189,30280,30281 ,13285,13376,13377 ,0,0,0}, {30233,30235,30283 ,13329,13331,13379 ,0,0,0}, + {30281,30282,30231 ,13377,13378,13327 ,0,0,0}, {30284,30285,30286 ,13380,13381,13382 ,0,0,0}, + {30282,30283,30235 ,13378,13379,13331 ,0,0,0}, {30232,30287,30236 ,13328,13383,13332 ,0,0,0}, + {30283,30234,30233 ,13379,13330,13329 ,0,0,0}, {30236,30286,30237 ,13332,13382,13333 ,0,0,0}, + {30234,30287,30232 ,13330,13383,13328 ,0,0,0}, {30237,30288,30238 ,13333,13384,13334 ,0,0,0}, + {30287,30286,30236 ,13383,13382,13332 ,0,0,0}, {30239,30238,30289 ,13335,13334,13385 ,0,0,0}, + {30286,30288,30237 ,13382,13384,13333 ,0,0,0}, {30198,30239,30290 ,13294,13335,13386 ,0,0,0}, + {30238,30288,30289 ,13334,13384,13385 ,0,0,0}, {30243,30198,30291 ,13339,13294,13387 ,0,0,0}, + {30239,30289,30290 ,13335,13385,13386 ,0,0,0}, {30244,30243,30292 ,13340,13339,13388 ,0,0,0}, + {30290,30291,30198 ,13386,13387,13294 ,0,0,0}, {30244,30293,30245 ,13340,13389,13341 ,0,0,0}, + {30291,30292,30243 ,13387,13388,13339 ,0,0,0}, {30245,30241,30246 ,13341,13337,13342 ,0,0,0}, + {30292,30293,30244 ,13388,13389,13340 ,0,0,0}, {30247,30246,30294 ,13343,13342,13390 ,0,0,0}, + {30293,30241,30245 ,13389,13337,13341 ,0,0,0}, {30204,30247,30295 ,13300,13343,13391 ,0,0,0}, + {30246,30241,30294 ,13342,13337,13390 ,0,0,0}, {30251,30204,30296 ,13347,13300,13392 ,0,0,0}, + {30247,30294,30295 ,13343,13390,13391 ,0,0,0}, {30252,30251,30297 ,13348,13347,13393 ,0,0,0}, + {30295,30296,30204 ,13391,13392,13300 ,0,0,0}, {30252,30298,30253 ,13348,13394,13349 ,0,0,0}, + {30296,30297,30251 ,13392,13393,13347 ,0,0,0}, {30253,30249,30254 ,13349,13345,13350 ,0,0,0}, + {30297,30298,30252 ,13393,13394,13348 ,0,0,0}, {30255,30254,30299 ,13351,13350,13395 ,0,0,0}, + {30298,30249,30253 ,13394,13345,13349 ,0,0,0}, {30169,30255,30300 ,13264,13351,13396 ,0,0,0}, + {30254,30249,30299 ,13350,13345,13395 ,0,0,0}, {30259,30169,30301 ,13355,13264,13397 ,0,0,0}, + {30255,30299,30300 ,13351,13395,13396 ,0,0,0}, {30257,30259,30302 ,13353,13355,13398 ,0,0,0}, + {30300,30301,30169 ,13396,13397,13264 ,0,0,0}, {30303,30304,30305 ,13399,13400,13401 ,0,0,0}, + {30301,30302,30259 ,13397,13398,13355 ,0,0,0}, {30256,30306,30260 ,13352,13402,13356 ,0,0,0}, + {30302,30258,30257 ,13398,13354,13353 ,0,0,0}, {30260,30305,30261 ,13356,13401,13357 ,0,0,0}, + {30258,30306,30256 ,13354,13402,13352 ,0,0,0}, {30262,30261,30307 ,13358,13357,13403 ,0,0,0}, + {30306,30305,30260 ,13402,13401,13356 ,0,0,0}, {30215,30262,30308 ,13311,13358,13404 ,0,0,0}, + {30261,30305,30307 ,13357,13401,13403 ,0,0,0}, {30263,30215,30309 ,13359,13311,13405 ,0,0,0}, + {30262,30307,30308 ,13358,13403,13404 ,0,0,0}, {30267,30263,30310 ,13363,13359,13406 ,0,0,0}, + {30215,30308,30309 ,13311,13404,13405 ,0,0,0}, {30265,30267,30311 ,13361,13363,13407 ,0,0,0}, + {30309,30310,30263 ,13405,13406,13359 ,0,0,0}, {30312,30268,30264 ,13408,13364,13360 ,0,0,0}, + {30310,30311,30267 ,13406,13407,13363 ,0,0,0}, {30313,30314,30315 ,13409,13410,13411 ,0,0,0}, + {30311,30266,30265 ,13407,13362,13361 ,0,0,0}, {30268,30316,30269 ,13364,13412,13365 ,0,0,0}, + {30266,30312,30264 ,13362,13408,13360 ,0,0,0}, {30269,30315,30270 ,13365,13411,13366 ,0,0,0}, + {30312,30316,30268 ,13408,13412,13364 ,0,0,0}, {30270,30317,30223 ,13366,13413,13319 ,0,0,0}, + {30316,30315,30269 ,13412,13411,13365 ,0,0,0}, {30223,30087,30086 ,13319,13175,13174 ,0,0,0}, + {30315,30317,30270 ,13411,13413,13366 ,0,0,0}, {30086,30085,30271 ,13174,13173,13367 ,0,0,0}, + {30087,30223,30317 ,13175,13319,13413 ,0,0,0}, {30272,30318,30095 ,13368,13414,13183 ,0,0,0}, + {30319,30320,30272 ,13415,13416,13368 ,0,0,0}, {30083,30086,30271 ,13170,13174,13367 ,0,0,0}, + {30271,30318,30272 ,13367,13414,13368 ,0,0,0}, {30273,30272,30320 ,13369,13368,13416 ,0,0,0}, + {30041,30040,30226 ,13091,13090,13322 ,0,0,0}, {29708,30042,29704 ,13417,13094,13093 ,0,0,0}, + {30277,30275,30035 ,13373,13371,13085 ,0,0,0}, {30226,30276,30225 ,13322,13372,13321 ,0,0,0}, + {30042,30321,30276 ,13094,13418,13372 ,0,0,0}, {30278,30277,30322 ,13374,13373,13419 ,0,0,0}, + {30275,30321,30035 ,13371,13418,13085 ,0,0,0}, {30323,30322,30324 ,13420,13419,13421 ,0,0,0}, + {30277,30035,30322 ,13373,13085,13419 ,0,0,0}, {30323,30325,30279 ,13420,13422,13375 ,0,0,0}, + {30279,30278,30323 ,13375,13374,13420 ,0,0,0}, {30325,30326,30280 ,13422,13423,13376 ,0,0,0}, + {30280,30279,30325 ,13376,13375,13422 ,0,0,0}, {30326,30327,30281 ,13423,13424,13377 ,0,0,0}, + {30281,30280,30326 ,13377,13376,13423 ,0,0,0}, {30327,30328,30282 ,13424,13425,13378 ,0,0,0}, + {30282,30281,30327 ,13378,13377,13424 ,0,0,0}, {30328,30329,30283 ,13425,13426,13379 ,0,0,0}, + {30283,30282,30328 ,13379,13378,13425 ,0,0,0}, {30329,30330,30234 ,13426,13427,13330 ,0,0,0}, + {30234,30283,30329 ,13330,13379,13426 ,0,0,0}, {30330,30284,30287 ,13427,13380,13383 ,0,0,0}, + {30234,30330,30287 ,13330,13427,13383 ,0,0,0}, {28751,30331,30332 ,13428,13429,13430 ,0,0,0}, + {30287,30284,30286 ,13383,13380,13382 ,0,0,0}, {30288,30333,30289 ,13384,13431,13385 ,0,0,0}, + {30286,30285,30288 ,13382,13381,13384 ,0,0,0}, {30334,30333,30332 ,13432,13431,13430 ,0,0,0}, + {30285,30333,30288 ,13381,13431,13384 ,0,0,0}, {30334,30335,30290 ,13432,13433,13386 ,0,0,0}, + {30290,30289,30334 ,13386,13385,13432 ,0,0,0}, {30335,30336,30291 ,13433,13434,13387 ,0,0,0}, + {30291,30290,30335 ,13387,13386,13433 ,0,0,0}, {30336,30337,30292 ,13434,13435,13388 ,0,0,0}, + {30292,30291,30336 ,13388,13387,13434 ,0,0,0}, {30337,30242,30293 ,13435,13338,13389 ,0,0,0}, + {30292,30337,30293 ,13388,13435,13389 ,0,0,0}, {30338,30339,30340 ,13436,13437,13438 ,0,0,0}, + {30293,30242,30241 ,13389,13338,13337 ,0,0,0}, {30240,30339,30294 ,13336,13437,13390 ,0,0,0}, + {30241,30240,30294 ,13337,13336,13390 ,0,0,0}, {30339,30341,30295 ,13437,13439,13391 ,0,0,0}, + {30295,30294,30339 ,13391,13390,13437 ,0,0,0}, {30341,30342,30296 ,13439,13440,13392 ,0,0,0}, + {30296,30295,30341 ,13392,13391,13439 ,0,0,0}, {30342,30343,30297 ,13440,13441,13393 ,0,0,0}, + {30297,30296,30342 ,13393,13392,13440 ,0,0,0}, {30343,30250,30298 ,13441,13346,13394 ,0,0,0}, + {30297,30343,30298 ,13393,13441,13394 ,0,0,0}, {30344,28742,30345 ,13442,13443,13444 ,0,0,0}, + {30298,30250,30249 ,13394,13346,13345 ,0,0,0}, {30300,30299,30346 ,13396,13395,13445 ,0,0,0}, + {30249,30248,30299 ,13345,13344,13395 ,0,0,0}, {30347,30346,30344 ,13446,13445,13442 ,0,0,0}, + {30299,30248,30346 ,13395,13344,13445 ,0,0,0}, {30347,30348,30301 ,13446,13447,13397 ,0,0,0}, + {30301,30300,30347 ,13397,13396,13446 ,0,0,0}, {30348,30349,30302 ,13447,13448,13398 ,0,0,0}, + {30302,30301,30348 ,13398,13397,13447 ,0,0,0}, {30349,30350,30258 ,13448,13449,13354 ,0,0,0}, + {30258,30302,30349 ,13354,13398,13448 ,0,0,0}, {30350,30303,30306 ,13449,13399,13402 ,0,0,0}, + {30258,30350,30306 ,13354,13449,13402 ,0,0,0}, {30351,30352,30353 ,13450,13451,13452 ,0,0,0}, + {30306,30303,30305 ,13402,13399,13401 ,0,0,0}, {30304,30352,30307 ,13400,13451,13403 ,0,0,0}, + {30305,30304,30307 ,13401,13400,13403 ,0,0,0}, {30352,30354,30308 ,13451,13453,13404 ,0,0,0}, + {30308,30307,30352 ,13404,13403,13451 ,0,0,0}, {30354,30355,30309 ,13453,13454,13405 ,0,0,0}, + {30309,30308,30354 ,13405,13404,13453 ,0,0,0}, {30355,30356,30310 ,13454,13455,13406 ,0,0,0}, + {30310,30309,30355 ,13406,13405,13454 ,0,0,0}, {30356,30357,30311 ,13455,13456,13407 ,0,0,0}, + {30311,30310,30356 ,13407,13406,13455 ,0,0,0}, {30357,30358,30266 ,13456,13457,13362 ,0,0,0}, + {30266,30311,30357 ,13362,13407,13456 ,0,0,0}, {30358,30359,30312 ,13457,13458,13408 ,0,0,0}, + {30312,30266,30358 ,13408,13362,13457 ,0,0,0}, {30359,30313,30316 ,13458,13409,13412 ,0,0,0}, + {30312,30359,30316 ,13408,13458,13412 ,0,0,0}, {30317,30314,30360 ,13413,13410,13459 ,0,0,0}, + {30316,30313,30315 ,13412,13409,13411 ,0,0,0}, {30092,30085,30087 ,13180,13173,13175 ,0,0,0}, + {30315,30314,30317 ,13411,13410,13413 ,0,0,0}, {30091,30318,30085 ,13179,13414,13173 ,0,0,0}, + {30317,30360,30087 ,13413,13459,13175 ,0,0,0}, {30099,30093,30361 ,13187,13181,13460 ,0,0,0}, + {30360,30092,30087 ,13459,13180,13175 ,0,0,0}, {30091,30362,30363 ,13179,13461,13462 ,0,0,0}, + {30095,30319,30272 ,13183,13415,13368 ,0,0,0}, {30271,30085,30318 ,13367,13173,13414 ,0,0,0}, + {30095,30318,30363 ,13183,13414,13462 ,0,0,0}, {30094,30319,30095 ,13182,13415,13183 ,0,0,0}, + {30040,30042,30276 ,13090,13094,13372 ,0,0,0}, {29708,29710,30031 ,13417,13078,13081 ,0,0,0}, + {30321,30031,30036 ,13418,13081,13086 ,0,0,0}, {30276,30321,30275 ,13372,13418,13371 ,0,0,0}, + {30035,30321,30036 ,13085,13418,13086 ,0,0,0}, {30034,30324,30322 ,13084,13421,13419 ,0,0,0}, + {30322,30035,30034 ,13419,13085,13084 ,0,0,0}, {30324,30364,30323 ,13421,13463,13420 ,0,0,0}, + {30365,30325,30364 ,13464,13422,13463 ,0,0,0}, {30278,30322,30323 ,13374,13419,13420 ,0,0,0}, + {30325,30323,30364 ,13422,13420,13463 ,0,0,0}, {30366,30326,30365 ,13465,13423,13464 ,0,0,0}, + {30326,30325,30365 ,13423,13422,13464 ,0,0,0}, {30367,30327,30366 ,13466,13424,13465 ,0,0,0}, + {30327,30326,30366 ,13424,13423,13465 ,0,0,0}, {30368,30328,30367 ,13467,13425,13466 ,0,0,0}, + {30328,30327,30367 ,13425,13424,13466 ,0,0,0}, {30369,30329,30368 ,13468,13426,13467 ,0,0,0}, + {30329,30328,30368 ,13426,13425,13467 ,0,0,0}, {30370,30330,30369 ,13469,13427,13468 ,0,0,0}, + {30330,30329,30369 ,13427,13426,13468 ,0,0,0}, {30371,30284,30370 ,13470,13380,13469 ,0,0,0}, + {30284,30330,30370 ,13380,13427,13469 ,0,0,0}, {30372,30285,30371 ,13471,13381,13470 ,0,0,0}, + {30285,30284,30371 ,13381,13380,13470 ,0,0,0}, {30332,30333,30372 ,13430,13431,13471 ,0,0,0}, + {30285,30372,30333 ,13381,13471,13431 ,0,0,0}, {30332,30331,30334 ,13430,13429,13432 ,0,0,0}, + {30373,30335,30331 ,13472,13433,13429 ,0,0,0}, {30289,30333,30334 ,13385,13431,13432 ,0,0,0}, + {30335,30334,30331 ,13433,13432,13429 ,0,0,0}, {30374,30336,30373 ,13473,13434,13472 ,0,0,0}, + {30336,30335,30373 ,13434,13433,13472 ,0,0,0}, {30375,30337,30374 ,13474,13435,13473 ,0,0,0}, + {30337,30336,30374 ,13435,13434,13473 ,0,0,0}, {30376,30242,30375 ,13475,13338,13474 ,0,0,0}, + {30242,30337,30375 ,13338,13435,13474 ,0,0,0}, {30340,30240,30376 ,13438,13336,13475 ,0,0,0}, + {30240,30242,30376 ,13336,13338,13475 ,0,0,0}, {30340,28659,30338 ,13438,13476,13436 ,0,0,0}, + {30240,30340,30339 ,13336,13438,13437 ,0,0,0}, {30377,30341,30338 ,13477,13439,13436 ,0,0,0}, + {30341,30339,30338 ,13439,13437,13436 ,0,0,0}, {30378,30342,30377 ,13478,13440,13477 ,0,0,0}, + {30342,30341,30377 ,13440,13439,13477 ,0,0,0}, {30379,30343,30378 ,13479,13441,13478 ,0,0,0}, + {30343,30342,30378 ,13441,13440,13478 ,0,0,0}, {30380,30250,30379 ,13480,13346,13479 ,0,0,0}, + {30250,30343,30379 ,13346,13441,13479 ,0,0,0}, {30381,30248,30380 ,13481,13344,13480 ,0,0,0}, + {30248,30250,30380 ,13344,13346,13480 ,0,0,0}, {30344,30346,30381 ,13442,13445,13481 ,0,0,0}, + {30248,30381,30346 ,13344,13481,13445 ,0,0,0}, {30344,30345,30347 ,13442,13444,13446 ,0,0,0}, + {30382,30348,30345 ,13482,13447,13444 ,0,0,0}, {30300,30346,30347 ,13396,13445,13446 ,0,0,0}, + {30348,30347,30345 ,13447,13446,13444 ,0,0,0}, {30383,30349,30382 ,13483,13448,13482 ,0,0,0}, + {30349,30348,30382 ,13448,13447,13482 ,0,0,0}, {30384,30350,30383 ,13484,13449,13483 ,0,0,0}, + {30350,30349,30383 ,13449,13448,13483 ,0,0,0}, {30385,30303,30384 ,13485,13399,13484 ,0,0,0}, + {30303,30350,30384 ,13399,13449,13484 ,0,0,0}, {30353,30304,30385 ,13452,13400,13485 ,0,0,0}, + {30304,30303,30385 ,13400,13399,13485 ,0,0,0}, {30353,28681,30351 ,13452,13486,13450 ,0,0,0}, + {30304,30353,30352 ,13400,13452,13451 ,0,0,0}, {30386,30354,30351 ,13487,13453,13450 ,0,0,0}, + {30354,30352,30351 ,13453,13451,13450 ,0,0,0}, {30387,30355,30386 ,13488,13454,13487 ,0,0,0}, + {30355,30354,30386 ,13454,13453,13487 ,0,0,0}, {30388,30356,30387 ,13489,13455,13488 ,0,0,0}, + {30356,30355,30387 ,13455,13454,13488 ,0,0,0}, {30389,30357,30388 ,13490,13456,13489 ,0,0,0}, + {30357,30356,30388 ,13456,13455,13489 ,0,0,0}, {30390,30358,30389 ,13491,13457,13490 ,0,0,0}, + {30358,30357,30389 ,13457,13456,13490 ,0,0,0}, {30391,30359,30390 ,13492,13458,13491 ,0,0,0}, + {30359,30358,30390 ,13458,13457,13491 ,0,0,0}, {30392,30313,30391 ,13493,13409,13492 ,0,0,0}, + {30313,30359,30391 ,13409,13458,13492 ,0,0,0}, {30393,30314,30392 ,13494,13410,13493 ,0,0,0}, + {30314,30313,30392 ,13410,13409,13493 ,0,0,0}, {30394,30360,30393 ,13495,13459,13494 ,0,0,0}, + {30360,30314,30393 ,13459,13410,13494 ,0,0,0}, {30395,30092,30394 ,13496,13180,13495 ,0,0,0}, + {30092,30360,30394 ,13180,13459,13495 ,0,0,0}, {30395,30362,30091 ,13496,13461,13179 ,0,0,0}, + {30091,30092,30395 ,13179,13180,13496 ,0,0,0}, {30362,30361,30363 ,13461,13460,13462 ,0,0,0}, + {30095,30363,30093 ,13183,13462,13181 ,0,0,0}, {30318,30091,30363 ,13414,13179,13462 ,0,0,0}, + {30361,30093,30363 ,13460,13181,13462 ,0,0,0}, {30094,30093,30100 ,13182,13181,13188 ,0,0,0}, + {30321,30042,30031 ,13418,13094,13081 ,0,0,0}, {30031,30042,29708 ,13081,13094,13417 ,0,0,0}, + {28763,28759,30036 ,13281,13497,13086 ,0,0,0}, {30036,28759,30034 ,13086,13497,13084 ,0,0,0}, + {28759,28758,30034 ,13497,13498,13084 ,0,0,0}, {30034,28758,30324 ,13084,13498,13421 ,0,0,0}, + {28758,28757,30324 ,13498,13499,13421 ,0,0,0}, {30324,28757,30364 ,13421,13499,13463 ,0,0,0}, + {28757,28620,30364 ,13499,13500,13463 ,0,0,0}, {30364,28620,30365 ,13463,13500,13464 ,0,0,0}, + {28620,28610,30365 ,13500,13501,13464 ,0,0,0}, {30365,28610,30366 ,13464,13501,13465 ,0,0,0}, + {28610,28643,30366 ,13501,13502,13465 ,0,0,0}, {30366,28643,30367 ,13465,13502,13466 ,0,0,0}, + {28643,28640,30367 ,13502,13503,13466 ,0,0,0}, {30367,28640,30368 ,13466,13503,13467 ,0,0,0}, + {28640,28645,30368 ,13503,13504,13467 ,0,0,0}, {28645,28648,30369 ,13504,13505,13468 ,0,0,0}, + {28645,30369,30368 ,13504,13468,13467 ,0,0,0}, {28648,28615,30370 ,13505,13506,13469 ,0,0,0}, + {28648,30370,30369 ,13505,13469,13468 ,0,0,0}, {28615,28614,30371 ,13506,13507,13470 ,0,0,0}, + {28615,30371,30370 ,13506,13470,13469 ,0,0,0}, {28614,28650,30372 ,13507,13508,13471 ,0,0,0}, + {28614,30372,30371 ,13507,13471,13470 ,0,0,0}, {28650,28752,30332 ,13508,13509,13430 ,0,0,0}, + {28650,30332,30372 ,13508,13430,13471 ,0,0,0}, {28751,30332,28752 ,13428,13430,13509 ,0,0,0}, + {28751,28653,30331 ,13428,13510,13429 ,0,0,0}, {30331,28653,30373 ,13429,13510,13472 ,0,0,0}, + {28653,28658,30373 ,13510,13511,13472 ,0,0,0}, {30373,28658,30374 ,13472,13511,13473 ,0,0,0}, + {28658,28656,30374 ,13511,13512,13473 ,0,0,0}, {28656,28655,30375 ,13512,13513,13474 ,0,0,0}, + {28656,30375,30374 ,13512,13474,13473 ,0,0,0}, {28655,28750,30376 ,13513,13514,13475 ,0,0,0}, + {28655,30376,30375 ,13513,13475,13474 ,0,0,0}, {28750,28659,30340 ,13514,13476,13438 ,0,0,0}, + {28750,30340,30376 ,13514,13438,13475 ,0,0,0}, {28659,28749,30338 ,13476,13515,13436 ,0,0,0}, + {28749,28745,30338 ,13515,13516,13436 ,0,0,0}, {30338,28745,30377 ,13436,13516,13477 ,0,0,0}, + {28745,28663,30377 ,13516,13517,13477 ,0,0,0}, {30377,28663,30378 ,13477,13517,13478 ,0,0,0}, + {28663,28665,30378 ,13517,13518,13478 ,0,0,0}, {28665,28670,30379 ,13518,13519,13479 ,0,0,0}, + {28665,30379,30378 ,13518,13479,13478 ,0,0,0}, {28670,28668,30380 ,13519,13520,13480 ,0,0,0}, + {28670,30380,30379 ,13519,13480,13479 ,0,0,0}, {28668,28667,30381 ,13520,13521,13481 ,0,0,0}, + {28668,30381,30380 ,13520,13481,13480 ,0,0,0}, {28667,28743,30344 ,13521,13522,13442 ,0,0,0}, + {28667,30344,30381 ,13521,13442,13481 ,0,0,0}, {28742,30344,28743 ,13443,13442,13522 ,0,0,0}, + {28742,28672,30345 ,13443,13523,13444 ,0,0,0}, {30345,28672,30382 ,13444,13523,13482 ,0,0,0}, + {28672,28679,30382 ,13523,13524,13482 ,0,0,0}, {28679,28678,30383 ,13524,13525,13483 ,0,0,0}, + {28679,30383,30382 ,13524,13483,13482 ,0,0,0}, {28678,28677,30384 ,13525,13526,13484 ,0,0,0}, + {28678,30384,30383 ,13525,13484,13483 ,0,0,0}, {28677,28739,30385 ,13526,13527,13485 ,0,0,0}, + {28677,30385,30384 ,13526,13485,13484 ,0,0,0}, {28739,28681,30353 ,13527,13486,13452 ,0,0,0}, + {28739,30353,30385 ,13527,13452,13485 ,0,0,0}, {28681,28680,30351 ,13486,13528,13450 ,0,0,0}, + {28680,28686,30351 ,13528,13529,13450 ,0,0,0}, {30351,28686,30386 ,13450,13529,13487 ,0,0,0}, + {28686,28685,30386 ,13529,13530,13487 ,0,0,0}, {30386,28685,30387 ,13487,13530,13488 ,0,0,0}, + {28685,28690,30387 ,13530,13531,13488 ,0,0,0}, {30387,28690,30388 ,13488,13531,13489 ,0,0,0}, + {28690,28688,30388 ,13531,13532,13489 ,0,0,0}, {28688,28696,30389 ,13532,13533,13490 ,0,0,0}, + {28688,30389,30388 ,13532,13490,13489 ,0,0,0}, {28696,28692,30390 ,13533,13534,13491 ,0,0,0}, + {28696,30390,30389 ,13533,13491,13490 ,0,0,0}, {28692,28694,30391 ,13534,13535,13492 ,0,0,0}, + {28692,30391,30390 ,13534,13492,13491 ,0,0,0}, {28694,28697,30392 ,13535,13536,13493 ,0,0,0}, + {28694,30392,30391 ,13535,13493,13492 ,0,0,0}, {28697,28699,30393 ,13536,13537,13494 ,0,0,0}, + {28697,30393,30392 ,13536,13494,13493 ,0,0,0}, {28699,28704,30394 ,13537,13538,13495 ,0,0,0}, + {28699,30394,30393 ,13537,13495,13494 ,0,0,0}, {28704,28710,30395 ,13538,13539,13496 ,0,0,0}, + {28704,30395,30394 ,13538,13496,13495 ,0,0,0}, {28710,28711,30362 ,13539,13540,13461 ,0,0,0}, + {28710,30362,30395 ,13539,13461,13496 ,0,0,0}, {28711,28709,30361 ,13540,13541,13460 ,0,0,0}, + {28711,30361,30362 ,13540,13460,13461 ,0,0,0}, {28709,28703,30099 ,13541,13542,13187 ,0,0,0}, + {28709,30099,30361 ,13541,13187,13460 ,0,0,0}, {30099,28703,28702 ,13187,13542,11616 ,0,0,0}, + {29932,29638,29659 ,13543,13543,13543 ,0,0,0}, {29268,29655,29264 ,13543,13543,13543 ,0,0,0}, + {29654,29659,29720 ,13543,13543,13543 ,0,0,0}, {29932,29659,29639 ,13543,13543,13543 ,0,0,0}, + {29654,29720,29797 ,13543,13543,13543 ,0,0,0}, {29639,29654,29269 ,13543,13543,13543 ,0,0,0}, + {29659,29654,29639 ,13543,13543,13543 ,0,0,0}, {29129,29264,29655 ,13543,13543,13543 ,0,0,0}, + {29268,29652,29649 ,13543,13543,13543 ,0,0,0}, {29135,29144,29479 ,13543,13543,13543 ,0,0,0}, + {29270,29129,29655 ,13543,13543,13543 ,0,0,0}, {29271,29270,29135 ,13543,13543,13543 ,0,0,0}, + {29270,29271,29260 ,13543,13543,13543 ,0,0,0}, {29142,29135,29479 ,13543,13543,13543 ,0,0,0}, + {29143,29144,29270 ,13543,13543,13543 ,0,0,0}, {29144,29135,29270 ,13543,13543,13543 ,0,0,0}, + {29657,29270,29655 ,13543,13543,13543 ,0,0,0}, {29657,29143,29270 ,13543,13543,13543 ,0,0,0}, + {29655,29268,29649 ,13543,13543,13543 ,0,0,0}, {29652,29268,29654 ,13543,13543,13543 ,0,0,0}, + {29269,29654,29267 ,13543,13543,13543 ,0,0,0}, {29268,29267,29654 ,13543,13543,13543 ,0,0,0}, + {30319,30094,30100 ,13544,13544,13544 ,0,0,0}, {30148,30185,28898 ,13544,13544,13544 ,0,0,0}, + {30104,30320,30100 ,13544,13544,13544 ,0,0,0}, {30224,30274,28814 ,13544,13544,13544 ,0,0,0}, + {30273,30320,30274 ,13544,13544,13544 ,0,0,0}, {30320,30104,28702 ,13544,13544,13544 ,0,0,0}, + {30319,30100,30320 ,13544,13544,13544 ,0,0,0}, {28814,30274,30320 ,13544,13544,13544 ,0,0,0}, + {30320,28702,28814 ,13544,13544,13544 ,0,0,0}, {28813,30224,28814 ,13544,13544,13544 ,0,0,0}, + {28813,28856,30224 ,13544,13544,13544 ,0,0,0}, {30185,30224,28898 ,13544,13544,13544 ,0,0,0}, + {28856,28898,30224 ,13544,13544,13544 ,0,0,0}, {30149,30148,28898 ,13544,13544,13544 ,0,0,0}, + {28942,28984,28943 ,13544,13544,13544 ,0,0,0}, {28943,30149,28898 ,13544,13544,13544 ,0,0,0}, + {30149,28943,28984 ,13544,13544,13544 ,0,0,0}, {28735,28983,28730 ,13544,13544,13544 ,0,0,0}, + {30149,28984,28736 ,13544,13544,13544 ,0,0,0}, {28984,28735,28734 ,13544,13544,13544 ,0,0,0}, + {28735,28984,28983 ,13544,13544,13544 ,0,0,0}, {28984,28734,28736 ,13544,13544,13544 ,0,0,0} +// M3abstandhalter20mm.prt + , {30396,30397,30398 ,17250,17251,17252 ,0,0,0}, {30398,30399,30400 ,17252,17253,17254 ,0,0,0}, + {30399,30401,30400 ,17253,17255,17254 ,0,0,0}, {30398,30400,30396 ,17252,17254,17250 ,0,0,0}, + {30402,30403,30404 ,17256,17257,17258 ,0,0,0}, {30404,30403,30401 ,17258,17257,17255 ,0,0,0}, + {30402,30405,30406 ,17256,17259,17260 ,0,0,0}, {30406,30403,30402 ,17260,17257,17256 ,0,0,0}, + {30406,30405,30407 ,17260,17259,17261 ,0,0,0}, {30407,30405,30408 ,17261,17259,17262 ,0,0,0}, + {30408,30409,30410 ,17262,17263,17264 ,0,0,0}, {30407,30408,30410 ,17261,17262,17264 ,0,0,0}, + {30401,30399,30404 ,17255,17253,17258 ,0,0,0}, {140,30411,30412 ,17265,82,17266 ,0,0,0}, + {140,30412,30409 ,17265,17266,17263 ,0,0,0}, {30409,30412,30410 ,17263,17266,17264 ,0,0,0}, + {30396,30413,30397 ,17250,17267,17251 ,0,0,0}, {30414,30413,30415 ,17268,17267,17269 ,0,0,0}, + {30413,30414,30397 ,17267,17268,17251 ,0,0,0}, {30416,30417,30415 ,17270,17271,17269 ,0,0,0}, + {30414,30415,30417 ,17268,17269,17271 ,0,0,0}, {30416,30418,30419 ,17270,17272,17273 ,0,0,0}, + {30419,30417,30416 ,17273,17271,17270 ,0,0,0}, {30420,30418,30421 ,17274,17272,17275 ,0,0,0}, + {30418,30420,30419 ,17272,17274,17273 ,0,0,0}, {30422,30423,30421 ,17276,17277,17275 ,0,0,0}, + {30420,30421,30423 ,17274,17275,17277 ,0,0,0}, {30422,30424,30425 ,17276,17278,17279 ,0,0,0}, + {30425,30423,30422 ,17279,17277,17276 ,0,0,0}, {126,30424,30426 ,17280,17278,17281 ,0,0,0}, + {30424,126,30425 ,17278,17280,17279 ,0,0,0}, {30422,30421,30427 ,17282,17283,17284 ,0,0,0}, + {30427,30424,30422 ,17284,17285,17282 ,0,0,0}, {30427,30426,30424 ,17284,17286,17285 ,0,0,0}, + {30427,30418,30416 ,17284,17287,17288 ,0,0,0}, {30421,30418,30427 ,17283,17287,17284 ,0,0,0}, + {30427,30415,30413 ,17284,17289,17290 ,0,0,0}, {30416,30415,30427 ,17288,17289,17284 ,0,0,0}, + {30413,30396,30427 ,17290,17291,17284 ,0,0,0}, {30401,30427,30400 ,17292,17284,17293 ,0,0,0}, + {30427,30396,30400 ,17284,17291,17293 ,0,0,0}, {30406,30427,30403 ,17294,17284,17295 ,0,0,0}, + {30427,30401,30403 ,17284,17292,17295 ,0,0,0}, {30410,30427,30407 ,17296,17284,17297 ,0,0,0}, + {30427,30406,30407 ,17284,17294,17297 ,0,0,0}, {30411,30427,30412 ,17298,17284,17299 ,0,0,0}, + {30427,30410,30412 ,17284,17296,17299 ,0,0,0}, {30428,30429,30430 ,17300,17301,17302 ,0,0,0}, + {30431,30432,30433 ,324,17303,17304 ,0,0,0}, {30434,30429,30435 ,17305,17301,17306 ,0,0,0}, + {30429,30434,30430 ,17301,17305,17302 ,0,0,0}, {30434,30435,30436 ,17305,17306,17307 ,0,0,0}, + {30437,30438,30436 ,17308,17309,17307 ,0,0,0}, {30436,30435,30437 ,17307,17306,17308 ,0,0,0}, + {30439,30438,30437 ,17310,17309,17308 ,0,0,0}, {30439,30440,30438 ,17310,82,17309 ,0,0,0}, + {30441,30428,30430 ,17311,17300,17302 ,0,0,0}, {30442,30443,30441 ,17312,17313,17311 ,0,0,0}, + {30428,30441,30443 ,17300,17311,17313 ,0,0,0}, {30444,30445,30443 ,17314,17315,17313 ,0,0,0}, + {30443,30442,30444 ,17313,17312,17314 ,0,0,0}, {30445,30446,30447 ,17315,17316,17317 ,0,0,0}, + {30446,30445,30444 ,17316,17315,17314 ,0,0,0}, {30431,30447,30448 ,324,17317,17318 ,0,0,0}, + {30446,30448,30447 ,17316,17318,17317 ,0,0,0}, {30449,30450,30451 ,17319,17320,17321 ,0,0,0}, + {30431,30448,30432 ,324,17318,17303 ,0,0,0}, {30452,30453,30454 ,17322,17323,17324 ,0,0,0}, + {30453,30449,30455 ,17323,17319,17325 ,0,0,0}, {30456,30457,30458 ,17326,17327,17328 ,0,0,0}, + {30459,30460,30457 ,17329,17330,17327 ,0,0,0}, {30461,30462,30463 ,17331,17332,17333 ,0,0,0}, + {30456,30463,30462 ,17326,17333,17332 ,0,0,0}, {30461,30464,30465 ,17331,4726,17334 ,0,0,0}, + {30465,30462,30461 ,17334,17332,17331 ,0,0,0}, {30460,30458,30457 ,17330,17328,17327 ,0,0,0}, + {30456,30458,30463 ,17326,17328,17333 ,0,0,0}, {30459,30453,30452 ,17329,17323,17322 ,0,0,0}, + {30459,30452,30460 ,17329,17322,17330 ,0,0,0}, {30449,30451,30455 ,17319,17321,17325 ,0,0,0}, + {30454,30453,30455 ,17324,17323,17325 ,0,0,0}, {30433,30450,30431 ,17304,17320,324 ,0,0,0}, + {30451,30450,30433 ,17321,17320,17304 ,0,0,0}, {30466,30467,30468 ,21,17335,17336 ,0,0,0}, + {30468,30469,30470 ,17336,17337,17338 ,0,0,0}, {30469,30471,30470 ,17337,17339,17338 ,0,0,0}, + {30468,30470,30466 ,17336,17338,21 ,0,0,0}, {30472,30473,30474 ,17340,17341,17342 ,0,0,0}, + {30474,30473,30471 ,17342,17341,17339 ,0,0,0}, {30472,30475,30476 ,17340,17343,17344 ,0,0,0}, + {30476,30473,30472 ,17344,17341,17340 ,0,0,0}, {30476,30475,30477 ,17344,17343,17345 ,0,0,0}, + {30477,30475,30478 ,17345,17343,17346 ,0,0,0}, {30478,30479,30480 ,17346,17347,17348 ,0,0,0}, + {30477,30478,30480 ,17345,17346,17348 ,0,0,0}, {30471,30469,30474 ,17339,17337,17342 ,0,0,0}, + {30481,30482,30483 ,8320,82,17349 ,0,0,0}, {30481,30483,30479 ,8320,17349,17347 ,0,0,0}, + {30479,30483,30480 ,17347,17349,17348 ,0,0,0}, {30466,30484,30467 ,21,17350,17335 ,0,0,0}, + {30485,30484,30486 ,17351,17350,17352 ,0,0,0}, {30484,30485,30467 ,17350,17351,17335 ,0,0,0}, + {30487,30488,30486 ,17353,17354,17352 ,0,0,0}, {30485,30486,30488 ,17351,17352,17354 ,0,0,0}, + {30487,30489,30490 ,17353,17355,17356 ,0,0,0}, {30490,30488,30487 ,17356,17354,17353 ,0,0,0}, + {30491,30489,30492 ,17357,17355,17358 ,0,0,0}, {30489,30491,30490 ,17355,17357,17356 ,0,0,0}, + {30493,30494,30492 ,17359,17360,17358 ,0,0,0}, {30491,30492,30494 ,17357,17358,17360 ,0,0,0}, + {30493,30495,30496 ,17359,17361,17362 ,0,0,0}, {30496,30494,30493 ,17362,17360,17359 ,0,0,0}, + {30497,30495,30498 ,126,17361,17363 ,0,0,0}, {30495,30497,30496 ,17361,126,17362 ,0,0,0}, + {30493,30492,30499 ,17364,17365,17366 ,0,0,0}, {30499,30495,30493 ,17366,17367,17364 ,0,0,0}, + {30499,30498,30495 ,17366,17368,17367 ,0,0,0}, {30499,30489,30487 ,17366,17369,17370 ,0,0,0}, + {30492,30489,30499 ,17365,17369,17366 ,0,0,0}, {30499,30486,30484 ,17366,17371,17372 ,0,0,0}, + {30487,30486,30499 ,17370,17371,17366 ,0,0,0}, {30484,30466,30499 ,17372,17373,17366 ,0,0,0}, + {30471,30499,30470 ,17374,17366,17375 ,0,0,0}, {30499,30466,30470 ,17366,17373,17375 ,0,0,0}, + {30476,30499,30473 ,17376,17366,17377 ,0,0,0}, {30499,30471,30473 ,17366,17374,17377 ,0,0,0}, + {30480,30499,30477 ,17378,17366,17379 ,0,0,0}, {30499,30476,30477 ,17366,17376,17379 ,0,0,0}, + {30482,30499,30483 ,17380,17366,17381 ,0,0,0}, {30499,30480,30483 ,17366,17378,17381 ,0,0,0}, + {30500,30501,30502 ,17382,17383,17384 ,0,0,0}, {30503,30504,30505 ,21,7309,17385 ,0,0,0}, + {30506,30501,30507 ,17386,17383,17387 ,0,0,0}, {30501,30506,30502 ,17383,17386,17384 ,0,0,0}, + {30506,30507,30508 ,17386,17387,17388 ,0,0,0}, {30509,30510,30508 ,17389,17390,17388 ,0,0,0}, + {30508,30507,30509 ,17388,17387,17389 ,0,0,0}, {30511,30510,30509 ,17391,17390,17389 ,0,0,0}, + {30511,30512,30510 ,17391,17392,17390 ,0,0,0}, {30513,30500,30502 ,17393,17382,17384 ,0,0,0}, + {30514,30515,30513 ,17394,17395,17393 ,0,0,0}, {30500,30513,30515 ,17382,17393,17395 ,0,0,0}, + {30516,30517,30515 ,17396,17397,17395 ,0,0,0}, {30515,30514,30516 ,17395,17394,17396 ,0,0,0}, + {30517,30518,30519 ,17397,17398,17399 ,0,0,0}, {30518,30517,30516 ,17398,17397,17396 ,0,0,0}, + {30503,30519,30520 ,21,17399,17400 ,0,0,0}, {30518,30520,30519 ,17398,17400,17399 ,0,0,0}, + {30521,30522,30523 ,17401,17402,17403 ,0,0,0}, {30503,30520,30504 ,21,17400,7309 ,0,0,0}, + {30524,30525,30526 ,17404,17405,17406 ,0,0,0}, {30525,30521,30527 ,17405,17401,17407 ,0,0,0}, + {30528,30529,30530 ,17408,17409,17410 ,0,0,0}, {30531,30532,30529 ,17411,17412,17409 ,0,0,0}, + {30533,30534,30535 ,17413,17414,17415 ,0,0,0}, {30528,30535,30534 ,17408,17415,17414 ,0,0,0}, + {30533,30536,30537 ,17413,126,17416 ,0,0,0}, {30537,30534,30533 ,17416,17414,17413 ,0,0,0}, + {30532,30530,30529 ,17412,17410,17409 ,0,0,0}, {30528,30530,30535 ,17408,17410,17415 ,0,0,0}, + {30531,30525,30524 ,17411,17405,17404 ,0,0,0}, {30531,30524,30532 ,17411,17404,17412 ,0,0,0}, + {30521,30523,30527 ,17401,17403,17407 ,0,0,0}, {30526,30525,30527 ,17406,17405,17407 ,0,0,0}, + {30505,30522,30503 ,17385,17402,21 ,0,0,0}, {30523,30522,30505 ,17403,17402,17385 ,0,0,0}, + {30538,30429,30539 ,17417,17417,17417 ,0,0,0}, {30540,30541,30429 ,17417,17417,17417 ,0,0,0}, + {30429,30541,30539 ,17417,17417,17417 ,0,0,0}, {30538,30539,30542 ,17417,17417,17417 ,0,0,0}, + {30543,30544,30432 ,730,730,730 ,0,0,0}, {30545,30455,30546 ,730,730,730 ,0,0,0}, + {30547,126,30440 ,730,730,730 ,0,0,0}, {30548,30423,30425 ,730,730,730 ,0,0,0}, + {30549,30436,30550 ,730,730,730 ,0,0,0}, {30434,30549,30551 ,730,730,730 ,0,0,0}, + {30551,30430,30434 ,730,730,730 ,0,0,0}, {30552,30441,30551 ,730,730,730 ,0,0,0}, + {30436,30549,30434 ,730,730,730 ,0,0,0}, {30438,126,30550 ,730,730,730 ,0,0,0}, + {30438,30550,30436 ,730,730,730 ,0,0,0}, {30552,30553,30442 ,730,730,730 ,0,0,0}, + {30438,30440,126 ,730,730,730 ,0,0,0}, {30444,30554,30446 ,730,730,730 ,0,0,0}, + {30442,30553,30444 ,730,730,730 ,0,0,0}, {30555,30419,30420 ,730,730,730 ,0,0,0}, + {30417,30419,30556 ,730,730,730 ,0,0,0}, {30432,30544,30433 ,730,730,730 ,0,0,0}, + {30557,30414,30558 ,730,730,730 ,0,0,0}, {30559,30397,30414 ,730,730,730 ,0,0,0}, + {30451,30433,30546 ,730,730,730 ,0,0,0}, {30560,30561,30545 ,730,730,730 ,0,0,0}, + {30398,30562,30399 ,730,730,730 ,0,0,0}, {30397,30563,30398 ,730,730,730 ,0,0,0}, + {30460,30452,30561 ,730,730,730 ,0,0,0}, {30561,30454,30455 ,730,730,730 ,0,0,0}, + {30404,30564,30565 ,730,730,730 ,0,0,0}, {30564,30399,30566 ,730,730,730 ,0,0,0}, + {30567,30458,30568 ,730,730,730 ,0,0,0}, {30569,30405,30402 ,730,730,730 ,0,0,0}, + {30402,30404,30565 ,730,730,730 ,0,0,0}, {30408,30570,30571 ,730,730,730 ,0,0,0}, + {140,30464,30461 ,730,730,730 ,0,0,0}, {30409,30572,140 ,730,730,730 ,0,0,0}, + {30409,30408,30571 ,730,730,730 ,0,0,0}, {30573,30461,30463 ,730,730,730 ,0,0,0}, + {30574,30570,30405 ,730,730,730 ,0,0,0}, {30463,30567,30573 ,730,730,730 ,0,0,0}, + {30554,30543,30448 ,730,730,730 ,0,0,0}, {30420,30423,30575 ,730,730,730 ,0,0,0}, + {30397,30559,30563 ,730,730,730 ,0,0,0}, {30551,30441,30430 ,730,730,730 ,0,0,0}, + {30552,30442,30441 ,730,730,730 ,0,0,0}, {30554,30444,30553 ,730,730,730 ,0,0,0}, + {30554,30448,30446 ,730,730,730 ,0,0,0}, {30543,30432,30448 ,730,730,730 ,0,0,0}, + {30546,30433,30544 ,730,730,730 ,0,0,0}, {30546,30455,30451 ,730,730,730 ,0,0,0}, + {30561,30455,30545 ,730,730,730 ,0,0,0}, {30561,30568,30458 ,730,730,730 ,0,0,0}, + {30458,30460,30561 ,730,730,730 ,0,0,0}, {30567,30463,30458 ,730,730,730 ,0,0,0}, + {140,30461,30573 ,730,730,730 ,0,0,0}, {140,30572,30464 ,730,730,730 ,0,0,0}, + {30409,30571,30572 ,730,730,730 ,0,0,0}, {30405,30570,30408 ,730,730,730 ,0,0,0}, + {30405,30569,30574 ,730,730,730 ,0,0,0}, {30402,30565,30569 ,730,730,730 ,0,0,0}, + {30399,30564,30404 ,730,730,730 ,0,0,0}, {30399,30562,30566 ,730,730,730 ,0,0,0}, + {30398,30563,30562 ,730,730,730 ,0,0,0}, {30557,30559,30414 ,730,730,730 ,0,0,0}, + {30417,30558,30414 ,730,730,730 ,0,0,0}, {30419,30555,30556 ,730,730,730 ,0,0,0}, + {30417,30556,30558 ,730,730,730 ,0,0,0}, {30420,30576,30555 ,730,730,730 ,0,0,0}, + {30575,30423,30548 ,730,730,730 ,0,0,0}, {30576,30420,30575 ,730,730,730 ,0,0,0}, + {30548,30425,30547 ,730,730,730 ,0,0,0}, {126,30547,30425 ,730,730,730 ,0,0,0}, + {30454,30561,30452 ,730,730,730 ,0,0,0}, {30560,30568,30561 ,730,730,730 ,0,0,0}, + {30577,30578,30529 ,17418,17419,17419 ,0,0,0}, {30578,30579,30580 ,17419,2197,2197 ,0,0,0}, + {30580,30529,30578 ,2197,17419,17419 ,0,0,0}, {30529,30581,30577 ,17419,17418,17418 ,0,0,0}, + {30582,30583,30501 ,1398,17420,17420 ,0,0,0}, {30583,30538,30542 ,17420,1398,1398 ,0,0,0}, + {30542,30501,30583 ,1398,17420,17420 ,0,0,0}, {30501,30584,30582 ,17420,1398,1398 ,0,0,0}, + {30503,30579,30585 ,17421,1814,17422 ,0,0,0}, {30582,30584,30585 ,17423,17423,17422 ,0,0,0}, + {30584,30503,30585 ,17423,17421,17422 ,0,0,0}, {30503,30580,30579 ,17421,17424,1814 ,0,0,0}, + {30431,30586,30540 ,17425,17425,17425 ,0,0,0}, {30431,30587,30588 ,17425,17426,17426 ,0,0,0}, + {30431,30588,30586 ,17425,17426,17425 ,0,0,0}, {30586,30541,30540 ,17425,17425,17425 ,0,0,0}, + {30589,30490,30590 ,726,7626,7754 ,0,0,0}, {30591,30479,30592 ,7626,7627,7626 ,0,0,0}, + {30485,30488,30593 ,7625,7627,7755 ,0,0,0}, {30485,30594,30595 ,7625,17427,7249 ,0,0,0}, + {30595,30596,30467 ,7249,17428,7626 ,0,0,0}, {30467,30596,30468 ,7626,17428,7625 ,0,0,0}, + {30488,30490,30589 ,7627,7626,726 ,0,0,0}, {30597,30598,30469 ,7264,17429,7626 ,0,0,0}, + {30469,30468,30599 ,7626,7625,17430 ,0,0,0}, {30600,30474,30598 ,17431,7625,17429 ,0,0,0}, + {30491,30601,30590 ,7626,7754,7754 ,0,0,0}, {30497,30512,30602 ,7626,7626,7626 ,0,0,0}, + {30472,30603,30475 ,7758,7754,7627 ,0,0,0}, {30479,30478,30592 ,7627,7626,7626 ,0,0,0}, + {30604,30510,30497 ,726,7626,7626 ,0,0,0}, {30516,30514,30605 ,7626,726,7626 ,0,0,0}, + {30605,30506,30606 ,7626,726,726 ,0,0,0}, {30607,30505,30608 ,7628,726,726 ,0,0,0}, + {30609,30518,30516 ,7626,7628,7626 ,0,0,0}, {30523,30607,30527 ,7626,7628,726 ,0,0,0}, + {30610,30526,30611 ,7626,7626,726 ,0,0,0}, {30612,30530,30613 ,7626,726,7626 ,0,0,0}, + {30524,30610,30613 ,726,7626,7626 ,0,0,0}, {30608,30504,30614 ,726,7628,7626 ,0,0,0}, + {30612,30615,30535 ,7626,7626,726 ,0,0,0}, {30609,30614,30520 ,7626,7626,7626 ,0,0,0}, + {30536,30481,30591 ,7626,7626,7626 ,0,0,0}, {30481,30536,30533 ,7626,7626,7626 ,0,0,0}, + {30508,30616,30506 ,726,726,726 ,0,0,0}, {30617,30516,30605 ,726,7626,7626 ,0,0,0}, + {30618,30592,30478 ,8135,7626,7626 ,0,0,0}, {30508,30604,30616 ,726,726,726 ,0,0,0}, + {30475,30618,30478 ,7627,8135,7626 ,0,0,0}, {30619,30496,30602 ,7626,7626,7626 ,0,0,0}, + {30505,30504,30608 ,726,7628,726 ,0,0,0}, {30494,30496,30619 ,7626,7626,7626 ,0,0,0}, + {30474,30600,30472 ,7625,17431,7758 ,0,0,0}, {30620,30491,30494 ,7758,7626,7626 ,0,0,0}, + {30479,30591,30481 ,7627,7626,7626 ,0,0,0}, {30502,30605,30513 ,726,7626,726 ,0,0,0}, + {30475,30603,30621 ,7627,7754,7627 ,0,0,0}, {30621,30618,30475 ,7627,8135,7627 ,0,0,0}, + {30472,30600,30603 ,7758,17431,7754 ,0,0,0}, {30469,30598,30474 ,7626,17429,7625 ,0,0,0}, + {30469,30599,30597 ,7626,17430,7264 ,0,0,0}, {30468,30596,30599 ,7625,17428,17430 ,0,0,0}, + {30485,30595,30467 ,7625,7249,7626 ,0,0,0}, {30485,30593,30594 ,7625,7755,17427 ,0,0,0}, + {30488,30589,30593 ,7627,726,7755 ,0,0,0}, {30491,30590,30490 ,7626,7754,7626 ,0,0,0}, + {30491,30620,30601 ,7626,7758,7754 ,0,0,0}, {30494,30619,30620 ,7626,7626,7758 ,0,0,0}, + {30497,30602,30496 ,7626,7626,7626 ,0,0,0}, {30497,30510,30512 ,7626,7626,7626 ,0,0,0}, + {30604,30508,30510 ,726,726,7626 ,0,0,0}, {30606,30506,30616 ,726,726,726 ,0,0,0}, + {30502,30506,30605 ,726,726,7626 ,0,0,0}, {30514,30513,30605 ,726,726,7626 ,0,0,0}, + {30609,30516,30617 ,7626,7626,726 ,0,0,0}, {30609,30520,30518 ,7626,7626,7628 ,0,0,0}, + {30614,30504,30520 ,7626,7628,7626 ,0,0,0}, {30523,30505,30607 ,7626,726,7628 ,0,0,0}, + {30611,30527,30607 ,726,726,7628 ,0,0,0}, {30610,30524,30526 ,7626,726,7626 ,0,0,0}, + {30611,30526,30527 ,726,7626,726 ,0,0,0}, {30613,30532,30524 ,7626,726,726 ,0,0,0}, + {30530,30612,30535 ,726,7626,726 ,0,0,0}, {30532,30613,30530 ,726,7626,726 ,0,0,0}, + {30535,30615,30533 ,726,7626,7626 ,0,0,0}, {30481,30533,30615 ,7626,7626,7626 ,0,0,0}, + {30606,30622,30605 ,726,7626,7626 ,0,0,0}, {30605,30622,30617 ,7626,7626,726 ,0,0,0}, + {30587,30457,30623 ,17432,17433,17433 ,0,0,0}, {30577,30581,30457 ,17434,17434,17433 ,0,0,0}, + {30457,30581,30623 ,17433,17434,17433 ,0,0,0}, {30587,30623,30588 ,17432,17433,17432 ,0,0,0}, + {30602,30511,30624 ,17435,17436,17437 ,0,0,0}, {30590,30601,30625 ,17438,17439,17440 ,0,0,0}, + {30626,30620,30619 ,17441,17442,17443 ,0,0,0}, {30627,30586,30595 ,17444,17445,17446 ,0,0,0}, + {30628,30629,30593 ,17447,17448,17449 ,0,0,0}, {30630,30598,30631 ,17450,17451,17452 ,0,0,0}, + {30597,30599,30632 ,17453,17454,17455 ,0,0,0}, {30603,30630,30633 ,17456,17450,17457 ,0,0,0}, + {30623,30618,30621 ,17458,17459,17460 ,0,0,0}, {30621,30633,30623 ,17460,17457,17458 ,0,0,0}, + {30618,30634,30592 ,17459,17461,17462 ,0,0,0}, {30634,30618,30623 ,17461,17459,17458 ,0,0,0}, + {30634,30635,30592 ,17461,17463,17462 ,0,0,0}, {30537,30591,30635 ,17416,17464,17463 ,0,0,0}, + {30592,30635,30591 ,17462,17463,17464 ,0,0,0}, {30536,30591,30537 ,126,17464,17416 ,0,0,0}, + {30603,30600,30630 ,17456,17465,17450 ,0,0,0}, {30621,30603,30633 ,17460,17456,17457 ,0,0,0}, + {30598,30597,30631 ,17451,17453,17452 ,0,0,0}, {30600,30598,30630 ,17465,17451,17450 ,0,0,0}, + {30632,30599,30586 ,17455,17454,17445 ,0,0,0}, {30631,30597,30632 ,17452,17453,17455 ,0,0,0}, + {30595,30586,30596 ,17446,17445,17466 ,0,0,0}, {30586,30599,30596 ,17445,17454,17466 ,0,0,0}, + {30629,30627,30594 ,17448,17444,17467 ,0,0,0}, {30627,30595,30594 ,17444,17446,17467 ,0,0,0}, + {30589,30628,30593 ,17468,17447,17449 ,0,0,0}, {30593,30629,30594 ,17449,17448,17467 ,0,0,0}, + {30628,30590,30625 ,17447,17438,17440 ,0,0,0}, {30590,30628,30589 ,17438,17447,17468 ,0,0,0}, + {30601,30620,30539 ,17439,17442,17469 ,0,0,0}, {30601,30539,30625 ,17439,17469,17440 ,0,0,0}, + {30626,30619,30624 ,17441,17443,17437 ,0,0,0}, {30539,30620,30626 ,17469,17442,17441 ,0,0,0}, + {30511,30602,30512 ,17436,17435,17392 ,0,0,0}, {30624,30619,30602 ,17437,17443,17435 ,0,0,0}, + {30534,30581,30528 ,726,726,7658 ,0,0,0}, {30581,30529,30528 ,726,7658,7658 ,0,0,0}, + {30537,30581,30534 ,7918,726,726 ,0,0,0}, {30634,30581,30635 ,7661,726,7918 ,0,0,0}, + {30581,30537,30635 ,726,7918,7918 ,0,0,0}, {30623,30581,30634 ,7658,726,7661 ,0,0,0}, + {30628,30541,30629 ,726,17470,17471 ,0,0,0}, {30629,30541,30627 ,17471,17470,17472 ,0,0,0}, + {30541,30586,30627 ,17470,17470,17472 ,0,0,0}, {30541,30625,30539 ,17470,726,726 ,0,0,0}, + {30541,30628,30625 ,17470,726,726 ,0,0,0}, {30500,30584,30501 ,726,726,726 ,0,0,0}, + {30517,30584,30515 ,726,726,726 ,0,0,0}, {30584,30500,30515 ,726,726,726 ,0,0,0}, + {30503,30584,30519 ,726,726,726 ,0,0,0}, {30584,30517,30519 ,726,726,726 ,0,0,0}, + {30580,30522,30521 ,7660,726,17473 ,0,0,0}, {30503,30522,30580 ,726,726,7660 ,0,0,0}, + {30580,30531,30529 ,7660,17474,726 ,0,0,0}, {30580,30525,30531 ,7660,726,17474 ,0,0,0}, + {30521,30525,30580 ,17473,726,7660 ,0,0,0}, {30623,30633,30588 ,726,726,726 ,0,0,0}, + {30631,30588,30630 ,7659,726,7659 ,0,0,0}, {30633,30630,30588 ,726,7659,726 ,0,0,0}, + {30632,30586,30588 ,726,726,726 ,0,0,0}, {30632,30588,30631 ,726,726,7659 ,0,0,0}, + {30626,30542,30539 ,726,726,726 ,0,0,0}, {30542,30626,30624 ,726,726,726 ,0,0,0}, + {30509,30542,30511 ,726,726,726 ,0,0,0}, {30542,30624,30511 ,726,726,726 ,0,0,0}, + {30501,30542,30507 ,726,726,726 ,0,0,0}, {30542,30509,30507 ,726,726,726 ,0,0,0}, + {30636,30637,30499 ,17475,17476,17477 ,0,0,0}, {30499,30638,30636 ,17477,17478,17475 ,0,0,0}, + {30499,30482,30638 ,17477,17479,17478 ,0,0,0}, {30499,30639,30640 ,17477,17480,17481 ,0,0,0}, + {30637,30639,30499 ,17476,17480,17477 ,0,0,0}, {30499,30641,30642 ,17477,17482,17483 ,0,0,0}, + {30640,30641,30499 ,17481,17482,17477 ,0,0,0}, {30642,30643,30499 ,17483,17484,17477 ,0,0,0}, + {30644,30499,30645 ,17485,17477,17486 ,0,0,0}, {30499,30643,30645 ,17477,17484,17486 ,0,0,0}, + {30646,30499,30647 ,17487,17477,17488 ,0,0,0}, {30499,30644,30647 ,17477,17485,17488 ,0,0,0}, + {30648,30499,30649 ,17489,17477,17490 ,0,0,0}, {30499,30646,30649 ,17477,17487,17490 ,0,0,0}, + {30498,30499,30648 ,17491,17477,17489 ,0,0,0}, {30481,30615,30638 ,17492,17493,17494 ,0,0,0}, + {30640,30639,30610 ,17495,17496,17497 ,0,0,0}, {30637,30636,30612 ,17498,17499,17500 ,0,0,0}, + {30642,30608,30643 ,17501,17502,17503 ,0,0,0}, {30611,30607,30641 ,17504,17505,17506 ,0,0,0}, + {30609,30617,30644 ,17507,17508,17509 ,0,0,0}, {30609,30645,30614 ,17507,17510,17511 ,0,0,0}, + {30622,30606,30646 ,17512,17513,17514 ,0,0,0}, {30646,30647,30622 ,17514,17515,17512 ,0,0,0}, + {30649,30606,30616 ,17516,17513,17517 ,0,0,0}, {30606,30649,30646 ,17513,17516,17514 ,0,0,0}, + {30604,30648,30616 ,17518,17519,17517 ,0,0,0}, {30649,30616,30648 ,17516,17517,17519 ,0,0,0}, + {30604,30497,30498 ,17518,17520,17521 ,0,0,0}, {30498,30648,30604 ,17521,17519,17518 ,0,0,0}, + {30608,30642,30607 ,17502,17501,17505 ,0,0,0}, {30617,30647,30644 ,17508,17515,17509 ,0,0,0}, + {30622,30647,30617 ,17512,17515,17508 ,0,0,0}, {30610,30639,30613 ,17497,17496,17522 ,0,0,0}, + {30614,30645,30643 ,17511,17510,17503 ,0,0,0}, {30609,30644,30645 ,17507,17509,17510 ,0,0,0}, + {30608,30614,30643 ,17502,17511,17503 ,0,0,0}, {30641,30607,30642 ,17506,17505,17501 ,0,0,0}, + {30640,30610,30611 ,17495,17497,17504 ,0,0,0}, {30611,30641,30640 ,17504,17506,17495 ,0,0,0}, + {30636,30615,30612 ,17499,17493,17500 ,0,0,0}, {30613,30637,30612 ,17522,17498,17500 ,0,0,0}, + {30639,30637,30613 ,17496,17498,17522 ,0,0,0}, {30481,30638,30482 ,17492,17494,81 ,0,0,0}, + {30615,30636,30638 ,17493,17499,17494 ,0,0,0}, {30547,30439,30650 ,17523,17310,17524 ,0,0,0}, + {30555,30576,30651 ,17525,17526,17527 ,0,0,0}, {30652,30575,30548 ,17528,17529,17530 ,0,0,0}, + {30653,30585,30559 ,17531,17532,17533 ,0,0,0}, {30654,30655,30558 ,17534,17535,17536 ,0,0,0}, + {30656,30564,30657 ,17537,17538,17539 ,0,0,0}, {30566,30562,30658 ,17540,17541,17542 ,0,0,0}, + {30569,30656,30659 ,17543,17537,17544 ,0,0,0}, {30578,30570,30574 ,17545,17546,17547 ,0,0,0}, + {30574,30659,30578 ,17547,17544,17545 ,0,0,0}, {30570,30660,30571 ,17546,17548,17549 ,0,0,0}, + {30660,30570,30578 ,17548,17546,17545 ,0,0,0}, {30660,30661,30571 ,17548,17550,17549 ,0,0,0}, + {30465,30572,30661 ,17551,17552,17550 ,0,0,0}, {30571,30661,30572 ,17549,17550,17552 ,0,0,0}, + {30464,30572,30465 ,17553,17552,17551 ,0,0,0}, {30569,30565,30656 ,17543,17554,17537 ,0,0,0}, + {30574,30569,30659 ,17547,17543,17544 ,0,0,0}, {30564,30566,30657 ,17538,17540,17539 ,0,0,0}, + {30565,30564,30656 ,17554,17538,17537 ,0,0,0}, {30658,30562,30585 ,17542,17541,17532 ,0,0,0}, + {30657,30566,30658 ,17539,17540,17542 ,0,0,0}, {30559,30585,30563 ,17533,17532,17555 ,0,0,0}, + {30585,30562,30563 ,17532,17541,17555 ,0,0,0}, {30655,30653,30557 ,17535,17531,17556 ,0,0,0}, + {30653,30559,30557 ,17531,17533,17556 ,0,0,0}, {30556,30654,30558 ,17557,17534,17536 ,0,0,0}, + {30558,30655,30557 ,17536,17535,17556 ,0,0,0}, {30654,30555,30651 ,17534,17525,17527 ,0,0,0}, + {30555,30654,30556 ,17525,17534,17557 ,0,0,0}, {30576,30575,30583 ,17526,17529,17558 ,0,0,0}, + {30576,30583,30651 ,17526,17558,17527 ,0,0,0}, {30652,30548,30650 ,17528,17530,17524 ,0,0,0}, + {30583,30575,30652 ,17558,17529,17528 ,0,0,0}, {30439,30547,30440 ,17310,17523,82 ,0,0,0}, + {30650,30548,30547 ,17524,17530,17523 ,0,0,0}, {30582,30654,30651 ,730,17559,730 ,0,0,0}, + {30653,30582,30585 ,730,730,730 ,0,0,0}, {30654,30582,30655 ,17559,730,17559 ,0,0,0}, + {30582,30653,30655 ,730,730,17559 ,0,0,0}, {30651,30583,30582 ,730,17560,730 ,0,0,0}, + {30456,30577,30457 ,7433,17559,7433 ,0,0,0}, {30577,30661,30660 ,17559,17559,17560 ,0,0,0}, + {30577,30456,30462 ,17559,7433,730 ,0,0,0}, {30661,30577,30465 ,17559,17559,17561 ,0,0,0}, + {30577,30462,30465 ,17559,730,17561 ,0,0,0}, {30660,30578,30577 ,17560,7433,17559 ,0,0,0}, + {30443,30540,30428 ,7017,730,730 ,0,0,0}, {30540,30429,30428 ,730,11466,730 ,0,0,0}, + {30447,30540,30445 ,7534,730,17562 ,0,0,0}, {30540,30443,30445 ,730,7017,17562 ,0,0,0}, + {30431,30540,30447 ,17563,730,7534 ,0,0,0}, {30657,30579,30656 ,730,17560,17559 ,0,0,0}, + {30659,30656,30579 ,17559,17559,17560 ,0,0,0}, {30578,30659,30579 ,17561,17559,17560 ,0,0,0}, + {30658,30585,30579 ,17564,730,17560 ,0,0,0}, {30658,30579,30657 ,17564,17560,730 ,0,0,0}, + {30450,30449,30587 ,17561,730,17565 ,0,0,0}, {30431,30450,30587 ,17566,17561,17565 ,0,0,0}, + {30453,30459,30587 ,730,730,17565 ,0,0,0}, {30453,30587,30449 ,730,17565,730 ,0,0,0}, + {30457,30587,30459 ,730,17565,730 ,0,0,0}, {30583,30652,30538 ,730,730,730 ,0,0,0}, + {30538,30650,30439 ,730,730,730 ,0,0,0}, {30538,30652,30650 ,730,730,730 ,0,0,0}, + {30439,30437,30538 ,730,730,730 ,0,0,0}, {30538,30435,30429 ,730,730,730 ,0,0,0}, + {30437,30435,30538 ,730,730,730 ,0,0,0}, {30662,30663,30427 ,17567,17568,17569 ,0,0,0}, + {30427,30664,30662 ,17569,17570,17567 ,0,0,0}, {30427,30411,30664 ,17569,17571,17570 ,0,0,0}, + {30427,30665,30666 ,17569,17572,17573 ,0,0,0}, {30663,30665,30427 ,17568,17572,17569 ,0,0,0}, + {30427,30667,30668 ,17569,17574,17575 ,0,0,0}, {30666,30667,30427 ,17573,17574,17569 ,0,0,0}, + {30668,30669,30427 ,17575,17576,17569 ,0,0,0}, {30670,30427,30671 ,17577,17569,17578 ,0,0,0}, + {30427,30669,30671 ,17569,17576,17578 ,0,0,0}, {30672,30427,30673 ,17579,17569,17580 ,0,0,0}, + {30427,30670,30673 ,17569,17577,17580 ,0,0,0}, {30674,30427,30675 ,17581,17569,17582 ,0,0,0}, + {30427,30672,30675 ,17569,17579,17582 ,0,0,0}, {30426,30427,30674 ,17583,17569,17581 ,0,0,0}, + {140,30573,30664 ,2602,17584,17585 ,0,0,0}, {30666,30665,30560 ,17586,17587,17588 ,0,0,0}, + {30663,30662,30567 ,17589,17590,17591 ,0,0,0}, {30668,30544,30669 ,17592,17593,17594 ,0,0,0}, + {30545,30546,30667 ,17595,17596,17597 ,0,0,0}, {30554,30553,30670 ,17598,17599,17600 ,0,0,0}, + {30554,30671,30543 ,17598,17601,17602 ,0,0,0}, {30552,30551,30672 ,17603,17604,17605 ,0,0,0}, + {30672,30673,30552 ,17605,17606,17603 ,0,0,0}, {30675,30551,30549 ,17607,17604,17608 ,0,0,0}, + {30551,30675,30672 ,17604,17607,17605 ,0,0,0}, {30550,30674,30549 ,17609,17610,17608 ,0,0,0}, + {30675,30549,30674 ,17607,17608,17610 ,0,0,0}, {30550,126,30426 ,17609,17611,17612 ,0,0,0}, + {30426,30674,30550 ,17612,17610,17609 ,0,0,0}, {30544,30668,30546 ,17593,17592,17596 ,0,0,0}, + {30553,30673,30670 ,17599,17606,17600 ,0,0,0}, {30552,30673,30553 ,17603,17606,17599 ,0,0,0}, + {30560,30665,30568 ,17588,17587,17613 ,0,0,0}, {30543,30671,30669 ,17602,17601,17594 ,0,0,0}, + {30554,30670,30671 ,17598,17600,17601 ,0,0,0}, {30544,30543,30669 ,17593,17602,17594 ,0,0,0}, + {30667,30546,30668 ,17597,17596,17592 ,0,0,0}, {30666,30560,30545 ,17586,17588,17595 ,0,0,0}, + {30545,30667,30666 ,17595,17597,17586 ,0,0,0}, {30662,30573,30567 ,17590,17584,17591 ,0,0,0}, + {30568,30663,30567 ,17613,17589,17591 ,0,0,0}, {30665,30663,30568 ,17587,17589,17613 ,0,0,0}, + {140,30664,30411 ,2602,17585,82 ,0,0,0}, {30573,30662,30664 ,17584,17590,17585 ,0,0,0} +// M3abstandhalter20mm.prt + , {30676,30677,30678 ,17614,17615,17616 ,0,0,0}, {30678,30679,30680 ,17616,17617,17618 ,0,0,0}, + {30679,30681,30680 ,17617,17619,17618 ,0,0,0}, {30678,30680,30676 ,17616,17618,17614 ,0,0,0}, + {30682,30683,30684 ,17620,17621,17622 ,0,0,0}, {30684,30683,30681 ,17622,17621,17619 ,0,0,0}, + {30682,30685,30686 ,17620,17623,17624 ,0,0,0}, {30686,30683,30682 ,17624,17621,17620 ,0,0,0}, + {30686,30685,30687 ,17624,17623,17625 ,0,0,0}, {30687,30685,30688 ,17625,17623,17626 ,0,0,0}, + {30688,30689,30690 ,17626,17627,17628 ,0,0,0}, {30687,30688,30690 ,17625,17626,17628 ,0,0,0}, + {30681,30679,30684 ,17619,17617,17622 ,0,0,0}, {30691,30692,30693 ,17629,17629,17630 ,0,0,0}, + {30691,30693,30689 ,17629,17630,17627 ,0,0,0}, {30689,30693,30690 ,17627,17630,17628 ,0,0,0}, + {30676,30694,30677 ,17614,17631,17615 ,0,0,0}, {30695,30694,30696 ,17632,17631,17633 ,0,0,0}, + {30694,30695,30677 ,17631,17632,17615 ,0,0,0}, {30697,30698,30696 ,17634,17635,17633 ,0,0,0}, + {30695,30696,30698 ,17632,17633,17635 ,0,0,0}, {30697,30699,30700 ,17634,17636,17637 ,0,0,0}, + {30700,30698,30697 ,17637,17635,17634 ,0,0,0}, {30701,30699,30702 ,17638,17636,17639 ,0,0,0}, + {30699,30701,30700 ,17636,17638,17637 ,0,0,0}, {30703,30704,30702 ,17640,17641,17639 ,0,0,0}, + {30701,30702,30704 ,17638,17639,17641 ,0,0,0}, {30703,30705,30706 ,17640,17642,17643 ,0,0,0}, + {30706,30704,30703 ,17643,17641,17640 ,0,0,0}, {30707,30705,30708 ,17644,17642,17644 ,0,0,0}, + {30705,30707,30706 ,17642,17644,17643 ,0,0,0}, {30703,30702,30709 ,17645,17646,17647 ,0,0,0}, + {30709,30705,30703 ,17647,17648,17645 ,0,0,0}, {30709,30708,30705 ,17647,17649,17648 ,0,0,0}, + {30709,30699,30697 ,17647,17650,17651 ,0,0,0}, {30702,30699,30709 ,17646,17650,17647 ,0,0,0}, + {30709,30696,30694 ,17647,17652,17653 ,0,0,0}, {30697,30696,30709 ,17651,17652,17647 ,0,0,0}, + {30694,30676,30709 ,17653,17654,17647 ,0,0,0}, {30681,30709,30680 ,17655,17647,17656 ,0,0,0}, + {30709,30676,30680 ,17647,17654,17656 ,0,0,0}, {30686,30709,30683 ,17657,17647,17658 ,0,0,0}, + {30709,30681,30683 ,17647,17655,17658 ,0,0,0}, {30690,30709,30687 ,17659,17647,17660 ,0,0,0}, + {30709,30686,30687 ,17647,17657,17660 ,0,0,0}, {30692,30709,30693 ,17647,17647,17661 ,0,0,0}, + {30709,30690,30693 ,17647,17659,17661 ,0,0,0}, {30710,30711,30712 ,17662,17663,17664 ,0,0,0}, + {30713,30714,30715 ,17665,17665,17666 ,0,0,0}, {30716,30711,30717 ,17667,17663,17668 ,0,0,0}, + {30711,30716,30712 ,17663,17667,17664 ,0,0,0}, {30716,30717,30718 ,17667,17668,17669 ,0,0,0}, + {30719,30720,30718 ,17670,17671,17669 ,0,0,0}, {30718,30717,30719 ,17669,17668,17670 ,0,0,0}, + {30721,30720,30719 ,17629,17671,17670 ,0,0,0}, {30721,30722,30720 ,17629,17629,17671 ,0,0,0}, + {30723,30710,30712 ,17672,17662,17664 ,0,0,0}, {30724,30725,30723 ,17673,17674,17672 ,0,0,0}, + {30710,30723,30725 ,17662,17672,17674 ,0,0,0}, {30726,30727,30725 ,17675,17676,17674 ,0,0,0}, + {30725,30724,30726 ,17674,17673,17675 ,0,0,0}, {30727,30728,30729 ,17676,17677,17678 ,0,0,0}, + {30728,30727,30726 ,17677,17676,17675 ,0,0,0}, {30713,30729,30730 ,17665,17678,17679 ,0,0,0}, + {30728,30730,30729 ,17677,17679,17678 ,0,0,0}, {30731,30732,30733 ,17680,17681,17682 ,0,0,0}, + {30713,30730,30714 ,17665,17679,17665 ,0,0,0}, {30734,30735,30736 ,17683,17684,17685 ,0,0,0}, + {30735,30731,30737 ,17684,17680,17686 ,0,0,0}, {30738,30739,30740 ,17687,17688,17689 ,0,0,0}, + {30741,30742,30739 ,17690,17691,17688 ,0,0,0}, {30743,30744,30745 ,17692,17693,17694 ,0,0,0}, + {30738,30745,30744 ,17687,17694,17693 ,0,0,0}, {30743,30746,30747 ,17692,17644,17644 ,0,0,0}, + {30747,30744,30743 ,17644,17693,17692 ,0,0,0}, {30742,30740,30739 ,17691,17689,17688 ,0,0,0}, + {30738,30740,30745 ,17687,17689,17694 ,0,0,0}, {30741,30735,30734 ,17690,17684,17683 ,0,0,0}, + {30741,30734,30742 ,17690,17683,17691 ,0,0,0}, {30731,30733,30737 ,17680,17682,17686 ,0,0,0}, + {30736,30735,30737 ,17685,17684,17686 ,0,0,0}, {30715,30732,30713 ,17666,17681,17665 ,0,0,0}, + {30733,30732,30715 ,17682,17681,17666 ,0,0,0}, {30748,30749,30750 ,17695,17696,17697 ,0,0,0}, + {30750,30751,30752 ,17697,17698,17699 ,0,0,0}, {30751,30753,30752 ,17698,17700,17699 ,0,0,0}, + {30750,30752,30748 ,17697,17699,17695 ,0,0,0}, {30754,30755,30756 ,17701,17702,17703 ,0,0,0}, + {30756,30755,30753 ,17703,17702,17700 ,0,0,0}, {30754,30757,30758 ,17701,17704,17705 ,0,0,0}, + {30758,30755,30754 ,17705,17702,17701 ,0,0,0}, {30758,30757,30759 ,17705,17704,17706 ,0,0,0}, + {30759,30757,30760 ,17706,17704,17707 ,0,0,0}, {30760,30761,30762 ,17707,17708,17709 ,0,0,0}, + {30759,30760,30762 ,17706,17707,17709 ,0,0,0}, {30753,30751,30756 ,17700,17698,17703 ,0,0,0}, + {30763,30764,30765 ,17629,17629,17710 ,0,0,0}, {30763,30765,30761 ,17629,17710,17708 ,0,0,0}, + {30761,30765,30762 ,17708,17710,17709 ,0,0,0}, {30748,30766,30749 ,17695,17711,17696 ,0,0,0}, + {30767,30766,30768 ,17712,17711,17713 ,0,0,0}, {30766,30767,30749 ,17711,17712,17696 ,0,0,0}, + {30769,30770,30768 ,17714,17715,17713 ,0,0,0}, {30767,30768,30770 ,17712,17713,17715 ,0,0,0}, + {30769,30771,30772 ,17714,17716,17717 ,0,0,0}, {30772,30770,30769 ,17717,17715,17714 ,0,0,0}, + {30773,30771,30774 ,17718,17716,17719 ,0,0,0}, {30771,30773,30772 ,17716,17718,17717 ,0,0,0}, + {30775,30776,30774 ,17720,17721,17719 ,0,0,0}, {30773,30774,30776 ,17718,17719,17721 ,0,0,0}, + {30775,30777,30778 ,17720,17722,17723 ,0,0,0}, {30778,30776,30775 ,17723,17721,17720 ,0,0,0}, + {30779,30777,30780 ,17644,17722,17644 ,0,0,0}, {30777,30779,30778 ,17722,17644,17723 ,0,0,0}, + {30775,30774,30781 ,17724,17725,17726 ,0,0,0}, {30781,30777,30775 ,17726,17727,17724 ,0,0,0}, + {30781,30780,30777 ,17726,17728,17727 ,0,0,0}, {30781,30771,30769 ,17726,17729,17730 ,0,0,0}, + {30774,30771,30781 ,17725,17729,17726 ,0,0,0}, {30781,30768,30766 ,17726,17731,17732 ,0,0,0}, + {30769,30768,30781 ,17730,17731,17726 ,0,0,0}, {30766,30748,30781 ,17732,17733,17726 ,0,0,0}, + {30753,30781,30752 ,17734,17726,17735 ,0,0,0}, {30781,30748,30752 ,17726,17733,17735 ,0,0,0}, + {30758,30781,30755 ,17736,17726,17737 ,0,0,0}, {30781,30753,30755 ,17726,17734,17737 ,0,0,0}, + {30762,30781,30759 ,17738,17726,17739 ,0,0,0}, {30781,30758,30759 ,17726,17736,17739 ,0,0,0}, + {30764,30781,30765 ,17726,17726,17740 ,0,0,0}, {30781,30762,30765 ,17726,17738,17740 ,0,0,0}, + {30782,30783,30784 ,17741,17742,17743 ,0,0,0}, {30785,30786,30787 ,17695,17695,17744 ,0,0,0}, + {30788,30783,30789 ,17745,17742,17746 ,0,0,0}, {30783,30788,30784 ,17742,17745,17743 ,0,0,0}, + {30788,30789,30790 ,17745,17746,17747 ,0,0,0}, {30791,30792,30790 ,17748,17749,17747 ,0,0,0}, + {30790,30789,30791 ,17747,17746,17748 ,0,0,0}, {30793,30792,30791 ,17629,17749,17748 ,0,0,0}, + {30793,30794,30792 ,17629,17629,17749 ,0,0,0}, {30795,30782,30784 ,17750,17741,17743 ,0,0,0}, + {30796,30797,30795 ,17751,17752,17750 ,0,0,0}, {30782,30795,30797 ,17741,17750,17752 ,0,0,0}, + {30798,30799,30797 ,17753,17754,17752 ,0,0,0}, {30797,30796,30798 ,17752,17751,17753 ,0,0,0}, + {30799,30800,30801 ,17754,17755,17756 ,0,0,0}, {30800,30799,30798 ,17755,17754,17753 ,0,0,0}, + {30785,30801,30802 ,17695,17756,17757 ,0,0,0}, {30800,30802,30801 ,17755,17757,17756 ,0,0,0}, + {30803,30804,30805 ,17758,17759,17760 ,0,0,0}, {30785,30802,30786 ,17695,17757,17695 ,0,0,0}, + {30806,30807,30808 ,17761,17762,17763 ,0,0,0}, {30807,30803,30809 ,17762,17758,17764 ,0,0,0}, + {30810,30811,30812 ,17765,17766,17767 ,0,0,0}, {30813,30814,30811 ,17768,17769,17766 ,0,0,0}, + {30815,30816,30817 ,17770,17771,17772 ,0,0,0}, {30810,30817,30816 ,17765,17772,17771 ,0,0,0}, + {30815,30818,30819 ,17770,17644,17644 ,0,0,0}, {30819,30816,30815 ,17644,17771,17770 ,0,0,0}, + {30814,30812,30811 ,17769,17767,17766 ,0,0,0}, {30810,30812,30817 ,17765,17767,17772 ,0,0,0}, + {30813,30807,30806 ,17768,17762,17761 ,0,0,0}, {30813,30806,30814 ,17768,17761,17769 ,0,0,0}, + {30803,30805,30809 ,17758,17760,17764 ,0,0,0}, {30808,30807,30809 ,17763,17762,17764 ,0,0,0}, + {30787,30804,30785 ,17744,17759,17695 ,0,0,0}, {30805,30804,30787 ,17760,17759,17744 ,0,0,0}, + {30820,30711,30821 ,17773,17773,17773 ,0,0,0}, {30822,30823,30711 ,17773,17773,17773 ,0,0,0}, + {30711,30823,30821 ,17773,17773,17773 ,0,0,0}, {30820,30821,30824 ,17773,17773,17773 ,0,0,0}, + {30825,30826,30714 ,730,730,730 ,0,0,0}, {30827,30737,30828 ,730,730,730 ,0,0,0}, + {30829,30707,30722 ,730,730,730 ,0,0,0}, {30830,30704,30706 ,730,730,730 ,0,0,0}, + {30831,30718,30832 ,730,730,730 ,0,0,0}, {30716,30831,30833 ,730,730,730 ,0,0,0}, + {30833,30712,30716 ,730,730,730 ,0,0,0}, {30834,30723,30833 ,730,730,730 ,0,0,0}, + {30718,30831,30716 ,730,730,730 ,0,0,0}, {30720,30707,30832 ,730,730,730 ,0,0,0}, + {30720,30832,30718 ,730,730,730 ,0,0,0}, {30834,30835,30724 ,730,730,730 ,0,0,0}, + {30720,30722,30707 ,730,730,730 ,0,0,0}, {30726,30836,30728 ,730,730,730 ,0,0,0}, + {30724,30835,30726 ,730,730,730 ,0,0,0}, {30837,30700,30701 ,730,730,730 ,0,0,0}, + {30698,30700,30838 ,730,730,730 ,0,0,0}, {30714,30826,30715 ,730,730,730 ,0,0,0}, + {30839,30695,30840 ,730,730,730 ,0,0,0}, {30841,30677,30695 ,730,730,730 ,0,0,0}, + {30733,30715,30828 ,730,730,730 ,0,0,0}, {30842,30843,30827 ,730,730,730 ,0,0,0}, + {30678,30844,30679 ,730,730,730 ,0,0,0}, {30677,30845,30678 ,730,730,730 ,0,0,0}, + {30742,30734,30843 ,730,730,730 ,0,0,0}, {30843,30736,30737 ,730,730,730 ,0,0,0}, + {30684,30846,30847 ,730,730,730 ,0,0,0}, {30846,30679,30848 ,730,730,730 ,0,0,0}, + {30849,30740,30850 ,730,730,730 ,0,0,0}, {30851,30685,30682 ,730,730,730 ,0,0,0}, + {30682,30684,30847 ,730,730,730 ,0,0,0}, {30688,30852,30853 ,730,730,730 ,0,0,0}, + {30691,30746,30743 ,730,730,730 ,0,0,0}, {30689,30854,30691 ,730,730,730 ,0,0,0}, + {30689,30688,30853 ,730,730,730 ,0,0,0}, {30855,30743,30745 ,730,730,730 ,0,0,0}, + {30856,30852,30685 ,730,730,730 ,0,0,0}, {30745,30849,30855 ,730,730,730 ,0,0,0}, + {30836,30825,30730 ,730,730,730 ,0,0,0}, {30701,30704,30857 ,730,730,730 ,0,0,0}, + {30677,30841,30845 ,730,730,730 ,0,0,0}, {30833,30723,30712 ,730,730,730 ,0,0,0}, + {30834,30724,30723 ,730,730,730 ,0,0,0}, {30836,30726,30835 ,730,730,730 ,0,0,0}, + {30836,30730,30728 ,730,730,730 ,0,0,0}, {30825,30714,30730 ,730,730,730 ,0,0,0}, + {30828,30715,30826 ,730,730,730 ,0,0,0}, {30828,30737,30733 ,730,730,730 ,0,0,0}, + {30843,30737,30827 ,730,730,730 ,0,0,0}, {30843,30850,30740 ,730,730,730 ,0,0,0}, + {30740,30742,30843 ,730,730,730 ,0,0,0}, {30849,30745,30740 ,730,730,730 ,0,0,0}, + {30691,30743,30855 ,730,730,730 ,0,0,0}, {30691,30854,30746 ,730,730,730 ,0,0,0}, + {30689,30853,30854 ,730,730,730 ,0,0,0}, {30685,30852,30688 ,730,730,730 ,0,0,0}, + {30685,30851,30856 ,730,730,730 ,0,0,0}, {30682,30847,30851 ,730,730,730 ,0,0,0}, + {30679,30846,30684 ,730,730,730 ,0,0,0}, {30679,30844,30848 ,730,730,730 ,0,0,0}, + {30678,30845,30844 ,730,730,730 ,0,0,0}, {30839,30841,30695 ,730,730,730 ,0,0,0}, + {30698,30840,30695 ,730,730,730 ,0,0,0}, {30700,30837,30838 ,730,730,730 ,0,0,0}, + {30698,30838,30840 ,730,730,730 ,0,0,0}, {30701,30858,30837 ,730,730,730 ,0,0,0}, + {30857,30704,30830 ,730,730,730 ,0,0,0}, {30858,30701,30857 ,730,730,730 ,0,0,0}, + {30830,30706,30829 ,730,730,730 ,0,0,0}, {30707,30829,30706 ,730,730,730 ,0,0,0}, + {30736,30843,30734 ,730,730,730 ,0,0,0}, {30842,30850,30843 ,730,730,730 ,0,0,0}, + {30859,30860,30811 ,17774,17775,17775 ,0,0,0}, {30860,30861,30862 ,17775,17776,17776 ,0,0,0}, + {30862,30811,30860 ,17776,17775,17775 ,0,0,0}, {30811,30863,30859 ,17775,17774,17774 ,0,0,0}, + {30864,30865,30783 ,17777,17778,17778 ,0,0,0}, {30865,30820,30824 ,17778,17777,17777 ,0,0,0}, + {30824,30783,30865 ,17777,17778,17778 ,0,0,0}, {30783,30866,30864 ,17778,17777,17777 ,0,0,0}, + {30785,30861,30867 ,17779,17695,17779 ,0,0,0}, {30864,30866,30867 ,17780,17780,17779 ,0,0,0}, + {30866,30785,30867 ,17780,17779,17779 ,0,0,0}, {30785,30862,30861 ,17779,17781,17695 ,0,0,0}, + {30713,30868,30822 ,17782,17782,17782 ,0,0,0}, {30713,30869,30870 ,17782,17665,17665 ,0,0,0}, + {30713,30870,30868 ,17782,17665,17782 ,0,0,0}, {30868,30823,30822 ,17782,17782,17782 ,0,0,0}, + {30871,30772,30872 ,726,17783,17784 ,0,0,0}, {30873,30761,30874 ,17783,17785,17783 ,0,0,0}, + {30767,30770,30875 ,17786,17785,17787 ,0,0,0}, {30767,30876,30877 ,17786,17788,17789 ,0,0,0}, + {30877,30878,30749 ,17789,17790,17783 ,0,0,0}, {30749,30878,30750 ,17783,17790,17786 ,0,0,0}, + {30770,30772,30871 ,17785,17783,726 ,0,0,0}, {30879,30880,30751 ,17791,17792,17783 ,0,0,0}, + {30751,30750,30881 ,17783,17786,17793 ,0,0,0}, {30882,30756,30880 ,17794,17786,17792 ,0,0,0}, + {30773,30883,30872 ,17783,17784,17784 ,0,0,0}, {30779,30794,30884 ,17783,17783,17783 ,0,0,0}, + {30754,30885,30757 ,17795,17784,17785 ,0,0,0}, {30761,30760,30874 ,17785,17783,17783 ,0,0,0}, + {30886,30792,30779 ,726,17783,17783 ,0,0,0}, {30798,30796,30887 ,17783,726,17783 ,0,0,0}, + {30887,30788,30888 ,17783,726,726 ,0,0,0}, {30889,30787,30890 ,17796,726,726 ,0,0,0}, + {30891,30800,30798 ,17783,17796,17783 ,0,0,0}, {30805,30889,30809 ,17783,17796,726 ,0,0,0}, + {30892,30808,30893 ,17783,17783,726 ,0,0,0}, {30894,30812,30895 ,17783,726,17783 ,0,0,0}, + {30806,30892,30895 ,726,17783,17783 ,0,0,0}, {30890,30786,30896 ,726,17796,17783 ,0,0,0}, + {30894,30897,30817 ,17783,17783,726 ,0,0,0}, {30891,30896,30802 ,17783,17783,17783 ,0,0,0}, + {30818,30763,30873 ,17783,17783,17783 ,0,0,0}, {30763,30818,30815 ,17783,17783,17783 ,0,0,0}, + {30790,30898,30788 ,726,726,726 ,0,0,0}, {30899,30798,30887 ,726,17783,17783 ,0,0,0}, + {30900,30874,30760 ,17797,17783,17783 ,0,0,0}, {30790,30886,30898 ,726,726,726 ,0,0,0}, + {30757,30900,30760 ,17785,17797,17783 ,0,0,0}, {30901,30778,30884 ,17783,17783,17783 ,0,0,0}, + {30787,30786,30890 ,726,17796,726 ,0,0,0}, {30776,30778,30901 ,17783,17783,17783 ,0,0,0}, + {30756,30882,30754 ,17786,17794,17795 ,0,0,0}, {30902,30773,30776 ,17795,17783,17783 ,0,0,0}, + {30761,30873,30763 ,17785,17783,17783 ,0,0,0}, {30784,30887,30795 ,726,17783,726 ,0,0,0}, + {30757,30885,30903 ,17785,17784,17785 ,0,0,0}, {30903,30900,30757 ,17785,17797,17785 ,0,0,0}, + {30754,30882,30885 ,17795,17794,17784 ,0,0,0}, {30751,30880,30756 ,17783,17792,17786 ,0,0,0}, + {30751,30881,30879 ,17783,17793,17791 ,0,0,0}, {30750,30878,30881 ,17786,17790,17793 ,0,0,0}, + {30767,30877,30749 ,17786,17789,17783 ,0,0,0}, {30767,30875,30876 ,17786,17787,17788 ,0,0,0}, + {30770,30871,30875 ,17785,726,17787 ,0,0,0}, {30773,30872,30772 ,17783,17784,17783 ,0,0,0}, + {30773,30902,30883 ,17783,17795,17784 ,0,0,0}, {30776,30901,30902 ,17783,17783,17795 ,0,0,0}, + {30779,30884,30778 ,17783,17783,17783 ,0,0,0}, {30779,30792,30794 ,17783,17783,17783 ,0,0,0}, + {30886,30790,30792 ,726,726,17783 ,0,0,0}, {30888,30788,30898 ,726,726,726 ,0,0,0}, + {30784,30788,30887 ,726,726,17783 ,0,0,0}, {30796,30795,30887 ,726,726,17783 ,0,0,0}, + {30891,30798,30899 ,17783,17783,726 ,0,0,0}, {30891,30802,30800 ,17783,17783,17796 ,0,0,0}, + {30896,30786,30802 ,17783,17796,17783 ,0,0,0}, {30805,30787,30889 ,17783,726,17796 ,0,0,0}, + {30893,30809,30889 ,726,726,17796 ,0,0,0}, {30892,30806,30808 ,17783,726,17783 ,0,0,0}, + {30893,30808,30809 ,726,17783,726 ,0,0,0}, {30895,30814,30806 ,17783,726,726 ,0,0,0}, + {30812,30894,30817 ,726,17783,726 ,0,0,0}, {30814,30895,30812 ,726,17783,726 ,0,0,0}, + {30817,30897,30815 ,726,17783,17783 ,0,0,0}, {30763,30815,30897 ,17783,17783,17783 ,0,0,0}, + {30888,30904,30887 ,726,17783,17783 ,0,0,0}, {30887,30904,30899 ,17783,17783,726 ,0,0,0}, + {30869,30739,30905 ,17798,17799,17799 ,0,0,0}, {30859,30863,30739 ,17800,17800,17799 ,0,0,0}, + {30739,30863,30905 ,17799,17800,17799 ,0,0,0}, {30869,30905,30870 ,17798,17799,17798 ,0,0,0}, + {30884,30793,30906 ,17801,17629,17802 ,0,0,0}, {30872,30883,30907 ,17803,17804,17805 ,0,0,0}, + {30908,30902,30901 ,17806,17807,17808 ,0,0,0}, {30909,30868,30877 ,17809,17810,17811 ,0,0,0}, + {30910,30911,30875 ,17812,17813,17814 ,0,0,0}, {30912,30880,30913 ,17815,17816,17817 ,0,0,0}, + {30879,30881,30914 ,17818,17819,17820 ,0,0,0}, {30885,30912,30915 ,17821,17815,17822 ,0,0,0}, + {30905,30900,30903 ,17823,17824,17825 ,0,0,0}, {30903,30915,30905 ,17825,17822,17823 ,0,0,0}, + {30900,30916,30874 ,17824,17826,17827 ,0,0,0}, {30916,30900,30905 ,17826,17824,17823 ,0,0,0}, + {30916,30917,30874 ,17826,17828,17827 ,0,0,0}, {30819,30873,30917 ,17644,17829,17828 ,0,0,0}, + {30874,30917,30873 ,17827,17828,17829 ,0,0,0}, {30818,30873,30819 ,17644,17829,17644 ,0,0,0}, + {30885,30882,30912 ,17821,17830,17815 ,0,0,0}, {30903,30885,30915 ,17825,17821,17822 ,0,0,0}, + {30880,30879,30913 ,17816,17818,17817 ,0,0,0}, {30882,30880,30912 ,17830,17816,17815 ,0,0,0}, + {30914,30881,30868 ,17820,17819,17810 ,0,0,0}, {30913,30879,30914 ,17817,17818,17820 ,0,0,0}, + {30877,30868,30878 ,17811,17810,17665 ,0,0,0}, {30868,30881,30878 ,17810,17819,17665 ,0,0,0}, + {30911,30909,30876 ,17813,17809,17831 ,0,0,0}, {30909,30877,30876 ,17809,17811,17831 ,0,0,0}, + {30871,30910,30875 ,17832,17812,17814 ,0,0,0}, {30875,30911,30876 ,17814,17813,17831 ,0,0,0}, + {30910,30872,30907 ,17812,17803,17805 ,0,0,0}, {30872,30910,30871 ,17803,17812,17832 ,0,0,0}, + {30883,30902,30821 ,17804,17807,17833 ,0,0,0}, {30883,30821,30907 ,17804,17833,17805 ,0,0,0}, + {30908,30901,30906 ,17806,17808,17802 ,0,0,0}, {30821,30902,30908 ,17833,17807,17806 ,0,0,0}, + {30793,30884,30794 ,17629,17801,17629 ,0,0,0}, {30906,30901,30884 ,17802,17808,17801 ,0,0,0}, + {30816,30863,30810 ,726,726,17834 ,0,0,0}, {30863,30811,30810 ,726,17834,17834 ,0,0,0}, + {30819,30863,30816 ,17835,726,726 ,0,0,0}, {30916,30863,30917 ,17836,726,17835 ,0,0,0}, + {30863,30819,30917 ,726,17835,17835 ,0,0,0}, {30905,30863,30916 ,17834,726,17836 ,0,0,0}, + {30910,30823,30911 ,726,17837,17838 ,0,0,0}, {30911,30823,30909 ,17838,17837,17839 ,0,0,0}, + {30823,30868,30909 ,17837,17837,17839 ,0,0,0}, {30823,30907,30821 ,17837,726,726 ,0,0,0}, + {30823,30910,30907 ,17837,726,726 ,0,0,0}, {30782,30866,30783 ,726,726,726 ,0,0,0}, + {30799,30866,30797 ,726,726,726 ,0,0,0}, {30866,30782,30797 ,726,726,726 ,0,0,0}, + {30785,30866,30801 ,726,726,726 ,0,0,0}, {30866,30799,30801 ,726,726,726 ,0,0,0}, + {30862,30804,30803 ,17840,726,17841 ,0,0,0}, {30785,30804,30862 ,726,726,17840 ,0,0,0}, + {30862,30813,30811 ,17840,17842,726 ,0,0,0}, {30862,30807,30813 ,17840,726,17842 ,0,0,0}, + {30803,30807,30862 ,17841,726,17840 ,0,0,0}, {30905,30915,30870 ,726,726,726 ,0,0,0}, + {30913,30870,30912 ,17843,726,17843 ,0,0,0}, {30915,30912,30870 ,726,17843,726 ,0,0,0}, + {30914,30868,30870 ,726,726,726 ,0,0,0}, {30914,30870,30913 ,726,726,17843 ,0,0,0}, + {30908,30824,30821 ,726,726,726 ,0,0,0}, {30824,30908,30906 ,726,726,726 ,0,0,0}, + {30791,30824,30793 ,726,726,726 ,0,0,0}, {30824,30906,30793 ,726,726,726 ,0,0,0}, + {30783,30824,30789 ,726,726,726 ,0,0,0}, {30824,30791,30789 ,726,726,726 ,0,0,0}, + {30918,30919,30781 ,17844,17845,17728 ,0,0,0}, {30781,30920,30918 ,17728,17846,17844 ,0,0,0}, + {30781,30764,30920 ,17728,17726,17846 ,0,0,0}, {30781,30921,30922 ,17728,17847,17848 ,0,0,0}, + {30919,30921,30781 ,17845,17847,17728 ,0,0,0}, {30781,30923,30924 ,17728,17849,17850 ,0,0,0}, + {30922,30923,30781 ,17848,17849,17728 ,0,0,0}, {30924,30925,30781 ,17850,17851,17728 ,0,0,0}, + {30926,30781,30927 ,17852,17728,17853 ,0,0,0}, {30781,30925,30927 ,17728,17851,17853 ,0,0,0}, + {30928,30781,30929 ,17854,17728,17855 ,0,0,0}, {30781,30926,30929 ,17728,17852,17855 ,0,0,0}, + {30930,30781,30931 ,17856,17728,17857 ,0,0,0}, {30781,30928,30931 ,17728,17854,17857 ,0,0,0}, + {30780,30781,30930 ,17728,17728,17856 ,0,0,0}, {30763,30897,30920 ,17629,17858,17859 ,0,0,0}, + {30922,30921,30892 ,17860,17861,17862 ,0,0,0}, {30919,30918,30894 ,17863,17864,17865 ,0,0,0}, + {30924,30890,30925 ,17866,17867,17868 ,0,0,0}, {30893,30889,30923 ,17869,17870,17871 ,0,0,0}, + {30891,30899,30926 ,17872,17873,17874 ,0,0,0}, {30891,30927,30896 ,17872,17875,17876 ,0,0,0}, + {30904,30888,30928 ,17877,17878,17879 ,0,0,0}, {30928,30929,30904 ,17879,17880,17877 ,0,0,0}, + {30931,30888,30898 ,17881,17878,17882 ,0,0,0}, {30888,30931,30928 ,17878,17881,17879 ,0,0,0}, + {30886,30930,30898 ,17883,17884,17882 ,0,0,0}, {30931,30898,30930 ,17881,17882,17884 ,0,0,0}, + {30886,30779,30780 ,17883,17644,17644 ,0,0,0}, {30780,30930,30886 ,17644,17884,17883 ,0,0,0}, + {30890,30924,30889 ,17867,17866,17870 ,0,0,0}, {30899,30929,30926 ,17873,17880,17874 ,0,0,0}, + {30904,30929,30899 ,17877,17880,17873 ,0,0,0}, {30892,30921,30895 ,17862,17861,17885 ,0,0,0}, + {30896,30927,30925 ,17876,17875,17868 ,0,0,0}, {30891,30926,30927 ,17872,17874,17875 ,0,0,0}, + {30890,30896,30925 ,17867,17876,17868 ,0,0,0}, {30923,30889,30924 ,17871,17870,17866 ,0,0,0}, + {30922,30892,30893 ,17860,17862,17869 ,0,0,0}, {30893,30923,30922 ,17869,17871,17860 ,0,0,0}, + {30918,30897,30894 ,17864,17858,17865 ,0,0,0}, {30895,30919,30894 ,17885,17863,17865 ,0,0,0}, + {30921,30919,30895 ,17861,17863,17885 ,0,0,0}, {30763,30920,30764 ,17629,17859,17629 ,0,0,0}, + {30897,30918,30920 ,17858,17864,17859 ,0,0,0}, {30829,30721,30932 ,17886,17629,17887 ,0,0,0}, + {30837,30858,30933 ,17888,17889,17890 ,0,0,0}, {30934,30857,30830 ,17891,17892,17893 ,0,0,0}, + {30935,30867,30841 ,17894,17895,17896 ,0,0,0}, {30936,30937,30840 ,17897,17898,17899 ,0,0,0}, + {30938,30846,30939 ,17900,17901,17902 ,0,0,0}, {30848,30844,30940 ,17903,17904,17905 ,0,0,0}, + {30851,30938,30941 ,17906,17900,17907 ,0,0,0}, {30860,30852,30856 ,17908,17909,17910 ,0,0,0}, + {30856,30941,30860 ,17910,17907,17908 ,0,0,0}, {30852,30942,30853 ,17909,17911,17912 ,0,0,0}, + {30942,30852,30860 ,17911,17909,17908 ,0,0,0}, {30942,30943,30853 ,17911,17913,17912 ,0,0,0}, + {30747,30854,30943 ,17644,17914,17913 ,0,0,0}, {30853,30943,30854 ,17912,17913,17914 ,0,0,0}, + {30746,30854,30747 ,17644,17914,17644 ,0,0,0}, {30851,30847,30938 ,17906,17915,17900 ,0,0,0}, + {30856,30851,30941 ,17910,17906,17907 ,0,0,0}, {30846,30848,30939 ,17901,17903,17902 ,0,0,0}, + {30847,30846,30938 ,17915,17901,17900 ,0,0,0}, {30940,30844,30867 ,17905,17904,17895 ,0,0,0}, + {30939,30848,30940 ,17902,17903,17905 ,0,0,0}, {30841,30867,30845 ,17896,17895,17695 ,0,0,0}, + {30867,30844,30845 ,17895,17904,17695 ,0,0,0}, {30937,30935,30839 ,17898,17894,17916 ,0,0,0}, + {30935,30841,30839 ,17894,17896,17916 ,0,0,0}, {30838,30936,30840 ,17917,17897,17899 ,0,0,0}, + {30840,30937,30839 ,17899,17898,17916 ,0,0,0}, {30936,30837,30933 ,17897,17888,17890 ,0,0,0}, + {30837,30936,30838 ,17888,17897,17917 ,0,0,0}, {30858,30857,30865 ,17889,17892,17918 ,0,0,0}, + {30858,30865,30933 ,17889,17918,17890 ,0,0,0}, {30934,30830,30932 ,17891,17893,17887 ,0,0,0}, + {30865,30857,30934 ,17918,17892,17891 ,0,0,0}, {30721,30829,30722 ,17629,17886,17629 ,0,0,0}, + {30932,30830,30829 ,17887,17893,17886 ,0,0,0}, {30864,30936,30933 ,730,17919,730 ,0,0,0}, + {30935,30864,30867 ,730,730,730 ,0,0,0}, {30936,30864,30937 ,17919,730,17919 ,0,0,0}, + {30864,30935,30937 ,730,730,17919 ,0,0,0}, {30933,30865,30864 ,730,17920,730 ,0,0,0}, + {30738,30859,30739 ,17921,17919,17921 ,0,0,0}, {30859,30943,30942 ,17919,17919,17920 ,0,0,0}, + {30859,30738,30744 ,17919,17921,730 ,0,0,0}, {30943,30859,30747 ,17919,17919,17922 ,0,0,0}, + {30859,30744,30747 ,17919,730,17922 ,0,0,0}, {30942,30860,30859 ,17920,17921,17919 ,0,0,0}, + {30725,30822,30710 ,17923,730,730 ,0,0,0}, {30822,30711,30710 ,730,17924,730 ,0,0,0}, + {30729,30822,30727 ,17925,730,17926 ,0,0,0}, {30822,30725,30727 ,730,17923,17926 ,0,0,0}, + {30713,30822,30729 ,17927,730,17925 ,0,0,0}, {30939,30861,30938 ,730,17920,17919 ,0,0,0}, + {30941,30938,30861 ,17919,17919,17920 ,0,0,0}, {30860,30941,30861 ,17922,17919,17920 ,0,0,0}, + {30940,30867,30861 ,17928,730,17920 ,0,0,0}, {30940,30861,30939 ,17928,17920,730 ,0,0,0}, + {30732,30731,30869 ,17922,730,17929 ,0,0,0}, {30713,30732,30869 ,17930,17922,17929 ,0,0,0}, + {30735,30741,30869 ,730,730,17929 ,0,0,0}, {30735,30869,30731 ,730,17929,730 ,0,0,0}, + {30739,30869,30741 ,730,17929,730 ,0,0,0}, {30865,30934,30820 ,730,730,730 ,0,0,0}, + {30820,30932,30721 ,730,730,730 ,0,0,0}, {30820,30934,30932 ,730,730,730 ,0,0,0}, + {30721,30719,30820 ,730,730,730 ,0,0,0}, {30820,30717,30711 ,730,730,730 ,0,0,0}, + {30719,30717,30820 ,730,730,730 ,0,0,0}, {30944,30945,30709 ,17931,17932,17649 ,0,0,0}, + {30709,30946,30944 ,17649,17933,17931 ,0,0,0}, {30709,30692,30946 ,17649,17647,17933 ,0,0,0}, + {30709,30947,30948 ,17649,17934,17935 ,0,0,0}, {30945,30947,30709 ,17932,17934,17649 ,0,0,0}, + {30709,30949,30950 ,17649,17936,17937 ,0,0,0}, {30948,30949,30709 ,17935,17936,17649 ,0,0,0}, + {30950,30951,30709 ,17937,17938,17649 ,0,0,0}, {30952,30709,30953 ,17939,17649,17940 ,0,0,0}, + {30709,30951,30953 ,17649,17938,17940 ,0,0,0}, {30954,30709,30955 ,17941,17649,17942 ,0,0,0}, + {30709,30952,30955 ,17649,17939,17942 ,0,0,0}, {30956,30709,30957 ,17943,17649,17944 ,0,0,0}, + {30709,30954,30957 ,17649,17941,17944 ,0,0,0}, {30708,30709,30956 ,17649,17649,17943 ,0,0,0}, + {30691,30855,30946 ,17629,17945,17946 ,0,0,0}, {30948,30947,30842 ,17947,17948,17949 ,0,0,0}, + {30945,30944,30849 ,17950,17951,17952 ,0,0,0}, {30950,30826,30951 ,17953,17954,17955 ,0,0,0}, + {30827,30828,30949 ,17956,17957,17958 ,0,0,0}, {30836,30835,30952 ,17959,17960,17961 ,0,0,0}, + {30836,30953,30825 ,17959,17962,17963 ,0,0,0}, {30834,30833,30954 ,17964,17965,17966 ,0,0,0}, + {30954,30955,30834 ,17966,17967,17964 ,0,0,0}, {30957,30833,30831 ,17968,17965,17969 ,0,0,0}, + {30833,30957,30954 ,17965,17968,17966 ,0,0,0}, {30832,30956,30831 ,17970,17971,17969 ,0,0,0}, + {30957,30831,30956 ,17968,17969,17971 ,0,0,0}, {30832,30707,30708 ,17970,17644,17644 ,0,0,0}, + {30708,30956,30832 ,17644,17971,17970 ,0,0,0}, {30826,30950,30828 ,17954,17953,17957 ,0,0,0}, + {30835,30955,30952 ,17960,17967,17961 ,0,0,0}, {30834,30955,30835 ,17964,17967,17960 ,0,0,0}, + {30842,30947,30850 ,17949,17948,17972 ,0,0,0}, {30825,30953,30951 ,17963,17962,17955 ,0,0,0}, + {30836,30952,30953 ,17959,17961,17962 ,0,0,0}, {30826,30825,30951 ,17954,17963,17955 ,0,0,0}, + {30949,30828,30950 ,17958,17957,17953 ,0,0,0}, {30948,30842,30827 ,17947,17949,17956 ,0,0,0}, + {30827,30949,30948 ,17956,17958,17947 ,0,0,0}, {30944,30855,30849 ,17951,17945,17952 ,0,0,0}, + {30850,30945,30849 ,17972,17950,17952 ,0,0,0}, {30947,30945,30850 ,17948,17950,17972 ,0,0,0}, + {30691,30946,30692 ,17629,17946,17629 ,0,0,0}, {30855,30944,30946 ,17945,17951,17946 ,0,0,0} +// M3abstandhalter20mm.prt + , {30958,30959,30960 ,17973,17974,17975 ,0,0,0}, {30960,30961,30962 ,17975,17976,17977 ,0,0,0}, + {30961,30963,30962 ,17976,17978,17977 ,0,0,0}, {30960,30962,30958 ,17975,17977,17973 ,0,0,0}, + {30964,30965,30966 ,17979,17980,17981 ,0,0,0}, {30966,30965,30963 ,17981,17980,17978 ,0,0,0}, + {30964,30967,30968 ,17979,17982,17983 ,0,0,0}, {30968,30965,30964 ,17983,17980,17979 ,0,0,0}, + {30968,30967,30969 ,17983,17982,17984 ,0,0,0}, {30969,30967,30970 ,17984,17982,17985 ,0,0,0}, + {30970,30971,30972 ,17985,17986,17987 ,0,0,0}, {30969,30970,30972 ,17984,17985,17987 ,0,0,0}, + {30963,30961,30966 ,17978,17976,17981 ,0,0,0}, {228,30973,30974 ,7498,126,17988 ,0,0,0}, + {228,30974,30971 ,7498,17988,17986 ,0,0,0}, {30971,30974,30972 ,17986,17988,17987 ,0,0,0}, + {30958,30975,30959 ,17973,17989,17974 ,0,0,0}, {30976,30975,30977 ,17990,17989,17991 ,0,0,0}, + {30975,30976,30959 ,17989,17990,17974 ,0,0,0}, {30978,30979,30977 ,17992,17993,17991 ,0,0,0}, + {30976,30977,30979 ,17990,17991,17993 ,0,0,0}, {30978,30980,30981 ,17992,17994,17995 ,0,0,0}, + {30981,30979,30978 ,17995,17993,17992 ,0,0,0}, {30982,30980,30983 ,17996,17994,17997 ,0,0,0}, + {30980,30982,30981 ,17994,17996,17995 ,0,0,0}, {30984,30985,30983 ,17998,17999,17997 ,0,0,0}, + {30982,30983,30985 ,17996,17997,17999 ,0,0,0}, {30984,30986,30987 ,17998,18000,18001 ,0,0,0}, + {30987,30985,30984 ,18001,17999,17998 ,0,0,0}, {242,30986,30988 ,18002,18000,18003 ,0,0,0}, + {30986,242,30987 ,18000,18002,18001 ,0,0,0}, {30984,30983,30989 ,18004,18005,18006 ,0,0,0}, + {30989,30986,30984 ,18006,18007,18004 ,0,0,0}, {30989,30988,30986 ,18006,18008,18007 ,0,0,0}, + {30989,30980,30978 ,18006,18009,18010 ,0,0,0}, {30983,30980,30989 ,18005,18009,18006 ,0,0,0}, + {30989,30977,30975 ,18006,18011,18012 ,0,0,0}, {30978,30977,30989 ,18010,18011,18006 ,0,0,0}, + {30975,30958,30989 ,18012,18013,18006 ,0,0,0}, {30963,30989,30962 ,18014,18006,18015 ,0,0,0}, + {30989,30958,30962 ,18006,18013,18015 ,0,0,0}, {30968,30989,30965 ,18016,18006,18017 ,0,0,0}, + {30989,30963,30965 ,18006,18014,18017 ,0,0,0}, {30972,30989,30969 ,18018,18006,18019 ,0,0,0}, + {30989,30968,30969 ,18006,18016,18019 ,0,0,0}, {30973,30989,30974 ,18020,18006,18021 ,0,0,0}, + {30989,30972,30974 ,18006,18018,18021 ,0,0,0}, {30990,30991,30992 ,18022,18023,17547 ,0,0,0}, + {30993,30994,30995 ,21,7309,17533 ,0,0,0}, {30996,30991,30997 ,17546,18023,18024 ,0,0,0}, + {30991,30996,30992 ,18023,17546,17547 ,0,0,0}, {30996,30997,30998 ,17546,18024,17549 ,0,0,0}, + {30999,31000,30998 ,18025,17552,17549 ,0,0,0}, {30998,30997,30999 ,17549,18024,18025 ,0,0,0}, + {31001,31000,30999 ,18026,17552,18025 ,0,0,0}, {31001,31002,31000 ,18026,126,17552 ,0,0,0}, + {31003,30990,30992 ,17543,18022,17547 ,0,0,0}, {31004,31005,31003 ,17554,18027,17543 ,0,0,0}, + {30990,31003,31005 ,18022,17543,18027 ,0,0,0}, {31006,31007,31005 ,17538,18028,18027 ,0,0,0}, + {31005,31004,31006 ,18027,17554,17538 ,0,0,0}, {31007,31008,31009 ,18028,17540,18029 ,0,0,0}, + {31008,31007,31006 ,17540,18028,17538 ,0,0,0}, {30993,31009,31010 ,21,18029,17541 ,0,0,0}, + {31008,31010,31009 ,17540,17541,18029 ,0,0,0}, {31011,31012,31013 ,18030,18031,17556 ,0,0,0}, + {30993,31010,30994 ,21,17541,7309 ,0,0,0}, {31014,31015,31016 ,17525,18032,17557 ,0,0,0}, + {31015,31011,31017 ,18032,18030,17536 ,0,0,0}, {31018,31019,31020 ,18033,18034,17529 ,0,0,0}, + {31021,31022,31019 ,18035,17526,18034 ,0,0,0}, {31023,31024,31025 ,17523,18036,17530 ,0,0,0}, + {31018,31025,31024 ,18033,17530,18036 ,0,0,0}, {31023,31026,31027 ,17523,18037,18038 ,0,0,0}, + {31027,31024,31023 ,18038,18036,17523 ,0,0,0}, {31022,31020,31019 ,17526,17529,18034 ,0,0,0}, + {31018,31020,31025 ,18033,17529,17530 ,0,0,0}, {31021,31015,31014 ,18035,18032,17525 ,0,0,0}, + {31021,31014,31022 ,18035,17525,17526 ,0,0,0}, {31011,31013,31017 ,18030,17556,17536 ,0,0,0}, + {31016,31015,31017 ,17557,18032,17536 ,0,0,0}, {30995,31012,30993 ,17533,18031,21 ,0,0,0}, + {31013,31012,30995 ,17556,18031,17533 ,0,0,0}, {31028,31029,31030 ,324,18039,18040 ,0,0,0}, + {31030,31031,31032 ,18040,18041,18042 ,0,0,0}, {31031,31033,31032 ,18041,18043,18042 ,0,0,0}, + {31030,31032,31028 ,18040,18042,324 ,0,0,0}, {31034,31035,31036 ,18044,18045,18046 ,0,0,0}, + {31036,31035,31033 ,18046,18045,18043 ,0,0,0}, {31034,31037,31038 ,18044,18047,18048 ,0,0,0}, + {31038,31035,31034 ,18048,18045,18044 ,0,0,0}, {31038,31037,31039 ,18048,18047,18049 ,0,0,0}, + {31039,31037,31040 ,18049,18047,18050 ,0,0,0}, {31040,31041,31042 ,18050,18051,18052 ,0,0,0}, + {31039,31040,31042 ,18049,18050,18052 ,0,0,0}, {31033,31031,31036 ,18043,18041,18046 ,0,0,0}, + {31043,31044,31045 ,18053,126,18054 ,0,0,0}, {31043,31045,31041 ,18053,18054,18051 ,0,0,0}, + {31041,31045,31042 ,18051,18054,18052 ,0,0,0}, {31028,31046,31029 ,324,18055,18039 ,0,0,0}, + {31047,31046,31048 ,18056,18055,18057 ,0,0,0}, {31046,31047,31029 ,18055,18056,18039 ,0,0,0}, + {31049,31050,31048 ,18058,18059,18057 ,0,0,0}, {31047,31048,31050 ,18056,18057,18059 ,0,0,0}, + {31049,31051,31052 ,18058,18060,18061 ,0,0,0}, {31052,31050,31049 ,18061,18059,18058 ,0,0,0}, + {31053,31051,31054 ,18062,18060,18063 ,0,0,0}, {31051,31053,31052 ,18060,18062,18061 ,0,0,0}, + {31055,31056,31054 ,18064,18065,18063 ,0,0,0}, {31053,31054,31056 ,18062,18063,18065 ,0,0,0}, + {31055,31057,31058 ,18064,18066,18067 ,0,0,0}, {31058,31056,31055 ,18067,18065,18064 ,0,0,0}, + {31059,31057,31060 ,82,18066,18068 ,0,0,0}, {31057,31059,31058 ,18066,82,18067 ,0,0,0}, + {31055,31054,31061 ,18069,18070,18071 ,0,0,0}, {31061,31057,31055 ,18071,18072,18069 ,0,0,0}, + {31061,31060,31057 ,18071,18073,18072 ,0,0,0}, {31061,31051,31049 ,18071,18074,18075 ,0,0,0}, + {31054,31051,31061 ,18070,18074,18071 ,0,0,0}, {31061,31048,31046 ,18071,18076,18077 ,0,0,0}, + {31049,31048,31061 ,18075,18076,18071 ,0,0,0}, {31046,31028,31061 ,18077,18078,18071 ,0,0,0}, + {31033,31061,31032 ,18079,18071,18080 ,0,0,0}, {31061,31028,31032 ,18071,18078,18080 ,0,0,0}, + {31038,31061,31035 ,18081,18071,18082 ,0,0,0}, {31061,31033,31035 ,18071,18079,18082 ,0,0,0}, + {31042,31061,31039 ,18083,18071,18084 ,0,0,0}, {31061,31038,31039 ,18071,18081,18084 ,0,0,0}, + {31044,31061,31045 ,18085,18071,18086 ,0,0,0}, {31061,31042,31045 ,18071,18083,18086 ,0,0,0}, + {31062,31063,31064 ,18087,18088,17460 ,0,0,0}, {31065,31066,31067 ,324,17303,17446 ,0,0,0}, + {31068,31063,31069 ,17459,18088,18089 ,0,0,0}, {31063,31068,31064 ,18088,17459,17460 ,0,0,0}, + {31068,31069,31070 ,17459,18089,17462 ,0,0,0}, {31071,31072,31070 ,18090,17464,17462 ,0,0,0}, + {31070,31069,31071 ,17462,18089,18090 ,0,0,0}, {31073,31072,31071 ,18091,17464,18090 ,0,0,0}, + {31073,31074,31072 ,18091,18092,17464 ,0,0,0}, {31075,31062,31064 ,17456,18087,17460 ,0,0,0}, + {31076,31077,31075 ,17465,18093,17456 ,0,0,0}, {31062,31075,31077 ,18087,17456,18093 ,0,0,0}, + {31078,31079,31077 ,17451,18094,18093 ,0,0,0}, {31077,31076,31078 ,18093,17465,17451 ,0,0,0}, + {31079,31080,31081 ,18094,17453,18095 ,0,0,0}, {31080,31079,31078 ,17453,18094,17451 ,0,0,0}, + {31065,31081,31082 ,324,18095,17454 ,0,0,0}, {31080,31082,31081 ,17453,17454,18095 ,0,0,0}, + {31083,31084,31085 ,18096,18097,17467 ,0,0,0}, {31065,31082,31066 ,324,17454,17303 ,0,0,0}, + {31086,31087,31088 ,17438,18098,17468 ,0,0,0}, {31087,31083,31089 ,18098,18096,17449 ,0,0,0}, + {31090,31091,31092 ,18099,18100,17442 ,0,0,0}, {31093,31094,31091 ,18101,17439,18100 ,0,0,0}, + {31095,31096,31097 ,17435,18102,17443 ,0,0,0}, {31090,31097,31096 ,18099,17443,18102 ,0,0,0}, + {31095,31098,31099 ,17435,82,18103 ,0,0,0}, {31099,31096,31095 ,18103,18102,17435 ,0,0,0}, + {31094,31092,31091 ,17439,17442,18100 ,0,0,0}, {31090,31092,31097 ,18099,17442,17443 ,0,0,0}, + {31093,31087,31086 ,18101,18098,17438 ,0,0,0}, {31093,31086,31094 ,18101,17438,17439 ,0,0,0}, + {31083,31085,31089 ,18096,17467,17449 ,0,0,0}, {31088,31087,31089 ,17468,18098,17449 ,0,0,0}, + {31067,31084,31065 ,17446,18097,324 ,0,0,0}, {31085,31084,31067 ,17467,18097,17446 ,0,0,0}, + {31100,30991,31101 ,18104,18104,18104 ,0,0,0}, {31102,31103,30991 ,18104,18104,18104 ,0,0,0}, + {30991,31103,31101 ,18104,18104,18104 ,0,0,0}, {31100,31101,31104 ,18104,18104,18104 ,0,0,0}, + {31105,31106,30994 ,730,730,730 ,0,0,0}, {31107,31017,31108 ,730,730,730 ,0,0,0}, + {31109,242,31002 ,730,730,730 ,0,0,0}, {31110,30985,30987 ,730,730,730 ,0,0,0}, + {31111,30998,31112 ,730,730,730 ,0,0,0}, {30996,31111,31113 ,730,730,730 ,0,0,0}, + {31113,30992,30996 ,730,730,730 ,0,0,0}, {31114,31003,31113 ,730,730,730 ,0,0,0}, + {30998,31111,30996 ,730,730,730 ,0,0,0}, {31000,242,31112 ,730,730,730 ,0,0,0}, + {31000,31112,30998 ,730,730,730 ,0,0,0}, {31114,31115,31004 ,730,730,730 ,0,0,0}, + {31000,31002,242 ,730,730,730 ,0,0,0}, {31006,31116,31008 ,730,730,730 ,0,0,0}, + {31004,31115,31006 ,730,730,730 ,0,0,0}, {31117,30981,30982 ,730,730,730 ,0,0,0}, + {30979,30981,31118 ,730,730,730 ,0,0,0}, {30994,31106,30995 ,730,730,730 ,0,0,0}, + {31119,30976,31120 ,730,730,730 ,0,0,0}, {31121,30959,30976 ,730,730,730 ,0,0,0}, + {31013,30995,31108 ,730,730,730 ,0,0,0}, {31122,31123,31107 ,730,730,730 ,0,0,0}, + {30960,31124,30961 ,730,730,730 ,0,0,0}, {30959,31125,30960 ,730,730,730 ,0,0,0}, + {31022,31014,31123 ,730,730,730 ,0,0,0}, {31123,31016,31017 ,730,730,730 ,0,0,0}, + {30966,31126,31127 ,730,730,730 ,0,0,0}, {31126,30961,31128 ,730,730,730 ,0,0,0}, + {31129,31020,31130 ,730,730,730 ,0,0,0}, {31131,30967,30964 ,730,730,730 ,0,0,0}, + {30964,30966,31127 ,730,730,730 ,0,0,0}, {30970,31132,31133 ,730,730,730 ,0,0,0}, + {228,31026,31023 ,730,730,730 ,0,0,0}, {30971,31134,228 ,730,730,730 ,0,0,0}, + {30971,30970,31133 ,730,730,730 ,0,0,0}, {31135,31023,31025 ,730,730,730 ,0,0,0}, + {31136,31132,30967 ,730,730,730 ,0,0,0}, {31025,31129,31135 ,730,730,730 ,0,0,0}, + {31116,31105,31010 ,730,730,730 ,0,0,0}, {30982,30985,31137 ,730,730,730 ,0,0,0}, + {30959,31121,31125 ,730,730,730 ,0,0,0}, {31113,31003,30992 ,730,730,730 ,0,0,0}, + {31114,31004,31003 ,730,730,730 ,0,0,0}, {31116,31006,31115 ,730,730,730 ,0,0,0}, + {31116,31010,31008 ,730,730,730 ,0,0,0}, {31105,30994,31010 ,730,730,730 ,0,0,0}, + {31108,30995,31106 ,730,730,730 ,0,0,0}, {31108,31017,31013 ,730,730,730 ,0,0,0}, + {31123,31017,31107 ,730,730,730 ,0,0,0}, {31123,31130,31020 ,730,730,730 ,0,0,0}, + {31020,31022,31123 ,730,730,730 ,0,0,0}, {31129,31025,31020 ,730,730,730 ,0,0,0}, + {228,31023,31135 ,730,730,730 ,0,0,0}, {228,31134,31026 ,730,730,730 ,0,0,0}, + {30971,31133,31134 ,730,730,730 ,0,0,0}, {30967,31132,30970 ,730,730,730 ,0,0,0}, + {30967,31131,31136 ,730,730,730 ,0,0,0}, {30964,31127,31131 ,730,730,730 ,0,0,0}, + {30961,31126,30966 ,730,730,730 ,0,0,0}, {30961,31124,31128 ,730,730,730 ,0,0,0}, + {30960,31125,31124 ,730,730,730 ,0,0,0}, {31119,31121,30976 ,730,730,730 ,0,0,0}, + {30979,31120,30976 ,730,730,730 ,0,0,0}, {30981,31117,31118 ,730,730,730 ,0,0,0}, + {30979,31118,31120 ,730,730,730 ,0,0,0}, {30982,31138,31117 ,730,730,730 ,0,0,0}, + {31137,30985,31110 ,730,730,730 ,0,0,0}, {31138,30982,31137 ,730,730,730 ,0,0,0}, + {31110,30987,31109 ,730,730,730 ,0,0,0}, {242,31109,30987 ,730,730,730 ,0,0,0}, + {31016,31123,31014 ,730,730,730 ,0,0,0}, {31122,31130,31123 ,730,730,730 ,0,0,0}, + {31139,31140,31091 ,18105,18106,18106 ,0,0,0}, {31140,31141,31142 ,18106,1433,1433 ,0,0,0}, + {31142,31091,31140 ,1433,18106,18106 ,0,0,0}, {31091,31143,31139 ,18106,18105,18105 ,0,0,0}, + {31144,31145,31063 ,2162,18107,18107 ,0,0,0}, {31145,31100,31104 ,18107,2162,2162 ,0,0,0}, + {31104,31063,31145 ,2162,18107,18107 ,0,0,0}, {31063,31146,31144 ,18107,2162,2162 ,0,0,0}, + {31065,31141,31147 ,18108,1077,18109 ,0,0,0}, {31144,31146,31147 ,18110,18110,18109 ,0,0,0}, + {31146,31065,31147 ,18110,18108,18109 ,0,0,0}, {31065,31142,31141 ,18108,18111,1077 ,0,0,0}, + {30993,31148,31102 ,18112,18112,18112 ,0,0,0}, {30993,31149,31150 ,18112,18113,18113 ,0,0,0}, + {30993,31150,31148 ,18112,18113,18112 ,0,0,0}, {31148,31103,31102 ,18112,18112,18112 ,0,0,0}, + {31151,31052,31152 ,726,7628,8135 ,0,0,0}, {31153,31041,31154 ,7628,7625,7628 ,0,0,0}, + {31047,31050,31155 ,7627,7625,7761 ,0,0,0}, {31047,31156,31157 ,7627,18114,7253 ,0,0,0}, + {31157,31158,31029 ,7253,18115,7628 ,0,0,0}, {31029,31158,31030 ,7628,18115,7627 ,0,0,0}, + {31050,31052,31151 ,7625,7628,726 ,0,0,0}, {31159,31160,31031 ,8017,18116,7628 ,0,0,0}, + {31031,31030,31161 ,7628,7627,18117 ,0,0,0}, {31162,31036,31160 ,7756,7627,18116 ,0,0,0}, + {31053,31163,31152 ,7628,8135,8135 ,0,0,0}, {31059,31074,31164 ,7628,7628,7628 ,0,0,0}, + {31034,31165,31037 ,7880,8135,7625 ,0,0,0}, {31041,31040,31154 ,7625,7628,7628 ,0,0,0}, + {31166,31072,31059 ,726,7628,7628 ,0,0,0}, {31078,31076,31167 ,7628,726,7628 ,0,0,0}, + {31167,31068,31168 ,7628,726,726 ,0,0,0}, {31169,31067,31170 ,7626,726,726 ,0,0,0}, + {31171,31080,31078 ,7628,7626,7628 ,0,0,0}, {31085,31169,31089 ,7628,7626,726 ,0,0,0}, + {31172,31088,31173 ,7628,7628,726 ,0,0,0}, {31174,31092,31175 ,7628,726,7628 ,0,0,0}, + {31086,31172,31175 ,726,7628,7628 ,0,0,0}, {31170,31066,31176 ,726,7626,7628 ,0,0,0}, + {31174,31177,31097 ,7628,7628,726 ,0,0,0}, {31171,31176,31082 ,7628,7628,7628 ,0,0,0}, + {31098,31043,31153 ,7628,7628,7628 ,0,0,0}, {31043,31098,31095 ,7628,7628,7628 ,0,0,0}, + {31070,31178,31068 ,726,726,726 ,0,0,0}, {31179,31078,31167 ,726,7628,7628 ,0,0,0}, + {31180,31154,31040 ,7754,7628,7628 ,0,0,0}, {31070,31166,31178 ,726,726,726 ,0,0,0}, + {31037,31180,31040 ,7625,7754,7628 ,0,0,0}, {31181,31058,31164 ,7628,7628,7628 ,0,0,0}, + {31067,31066,31170 ,726,7626,726 ,0,0,0}, {31056,31058,31181 ,7628,7628,7628 ,0,0,0}, + {31036,31162,31034 ,7627,7756,7880 ,0,0,0}, {31182,31053,31056 ,7880,7628,7628 ,0,0,0}, + {31041,31153,31043 ,7625,7628,7628 ,0,0,0}, {31064,31167,31075 ,726,7628,726 ,0,0,0}, + {31037,31165,31183 ,7625,8135,7625 ,0,0,0}, {31183,31180,31037 ,7625,7754,7625 ,0,0,0}, + {31034,31162,31165 ,7880,7756,8135 ,0,0,0}, {31031,31160,31036 ,7628,18116,7627 ,0,0,0}, + {31031,31161,31159 ,7628,18117,8017 ,0,0,0}, {31030,31158,31161 ,7627,18115,18117 ,0,0,0}, + {31047,31157,31029 ,7627,7253,7628 ,0,0,0}, {31047,31155,31156 ,7627,7761,18114 ,0,0,0}, + {31050,31151,31155 ,7625,726,7761 ,0,0,0}, {31053,31152,31052 ,7628,8135,7628 ,0,0,0}, + {31053,31182,31163 ,7628,7880,8135 ,0,0,0}, {31056,31181,31182 ,7628,7628,7880 ,0,0,0}, + {31059,31164,31058 ,7628,7628,7628 ,0,0,0}, {31059,31072,31074 ,7628,7628,7628 ,0,0,0}, + {31166,31070,31072 ,726,726,7628 ,0,0,0}, {31168,31068,31178 ,726,726,726 ,0,0,0}, + {31064,31068,31167 ,726,726,7628 ,0,0,0}, {31076,31075,31167 ,726,726,7628 ,0,0,0}, + {31171,31078,31179 ,7628,7628,726 ,0,0,0}, {31171,31082,31080 ,7628,7628,7626 ,0,0,0}, + {31176,31066,31082 ,7628,7626,7628 ,0,0,0}, {31085,31067,31169 ,7628,726,7626 ,0,0,0}, + {31173,31089,31169 ,726,726,7626 ,0,0,0}, {31172,31086,31088 ,7628,726,7628 ,0,0,0}, + {31173,31088,31089 ,726,7628,726 ,0,0,0}, {31175,31094,31086 ,7628,726,726 ,0,0,0}, + {31092,31174,31097 ,726,7628,726 ,0,0,0}, {31094,31175,31092 ,726,7628,726 ,0,0,0}, + {31097,31177,31095 ,726,7628,7628 ,0,0,0}, {31043,31095,31177 ,7628,7628,7628 ,0,0,0}, + {31168,31184,31167 ,726,7628,7628 ,0,0,0}, {31167,31184,31179 ,7628,7628,726 ,0,0,0}, + {31149,31019,31185 ,18118,18119,18119 ,0,0,0}, {31139,31143,31019 ,18120,18120,18119 ,0,0,0}, + {31019,31143,31185 ,18119,18120,18119 ,0,0,0}, {31149,31185,31150 ,18118,18119,18118 ,0,0,0}, + {31164,31073,31186 ,17413,18121,18122 ,0,0,0}, {31152,31163,31187 ,17404,17412,18123 ,0,0,0}, + {31188,31182,31181 ,18124,17410,17415 ,0,0,0}, {31189,31148,31157 ,18125,18126,17385 ,0,0,0}, + {31190,31191,31155 ,18127,18128,17407 ,0,0,0}, {31192,31160,31193 ,18129,17396,18130 ,0,0,0}, + {31159,31161,31194 ,17398,17400,18131 ,0,0,0}, {31165,31192,31195 ,17393,18129,18132 ,0,0,0}, + {31185,31180,31183 ,18133,17386,17384 ,0,0,0}, {31183,31195,31185 ,17384,18132,18133 ,0,0,0}, + {31180,31196,31154 ,17386,18134,17388 ,0,0,0}, {31196,31180,31185 ,18134,17386,18133 ,0,0,0}, + {31196,31197,31154 ,18134,18135,17388 ,0,0,0}, {31099,31153,31197 ,18103,17390,18135 ,0,0,0}, + {31154,31197,31153 ,17388,18135,17390 ,0,0,0}, {31098,31153,31099 ,82,17390,18103 ,0,0,0}, + {31165,31162,31192 ,17393,17394,18129 ,0,0,0}, {31183,31165,31195 ,17384,17393,18132 ,0,0,0}, + {31160,31159,31193 ,17396,17398,18130 ,0,0,0}, {31162,31160,31192 ,17394,17396,18129 ,0,0,0}, + {31194,31161,31148 ,18131,17400,18126 ,0,0,0}, {31193,31159,31194 ,18130,17398,18131 ,0,0,0}, + {31157,31148,31158 ,17385,18126,18136 ,0,0,0}, {31148,31161,31158 ,18126,17400,18136 ,0,0,0}, + {31191,31189,31156 ,18128,18125,17403 ,0,0,0}, {31189,31157,31156 ,18125,17385,17403 ,0,0,0}, + {31151,31190,31155 ,17406,18127,17407 ,0,0,0}, {31155,31191,31156 ,17407,18128,17403 ,0,0,0}, + {31190,31152,31187 ,18127,17404,18123 ,0,0,0}, {31152,31190,31151 ,17404,18127,17406 ,0,0,0}, + {31163,31182,31101 ,17412,17410,18137 ,0,0,0}, {31163,31101,31187 ,17412,18137,18123 ,0,0,0}, + {31188,31181,31186 ,18124,17415,18122 ,0,0,0}, {31101,31182,31188 ,18137,17410,18124 ,0,0,0}, + {31073,31164,31074 ,18121,17413,18092 ,0,0,0}, {31186,31181,31164 ,18122,17415,17413 ,0,0,0}, + {31096,31143,31090 ,726,726,7661 ,0,0,0}, {31143,31091,31090 ,726,7661,7661 ,0,0,0}, + {31099,31143,31096 ,18138,726,726 ,0,0,0}, {31196,31143,31197 ,7658,726,18138 ,0,0,0}, + {31143,31099,31197 ,726,18138,18138 ,0,0,0}, {31185,31143,31196 ,7661,726,7658 ,0,0,0}, + {31190,31103,31191 ,726,17471,17470 ,0,0,0}, {31191,31103,31189 ,17470,17471,18139 ,0,0,0}, + {31103,31148,31189 ,17471,17471,18139 ,0,0,0}, {31103,31187,31101 ,17471,726,726 ,0,0,0}, + {31103,31190,31187 ,17471,726,726 ,0,0,0}, {31062,31146,31063 ,726,726,726 ,0,0,0}, + {31079,31146,31077 ,726,726,726 ,0,0,0}, {31146,31062,31077 ,726,726,726 ,0,0,0}, + {31065,31146,31081 ,726,726,726 ,0,0,0}, {31146,31079,31081 ,726,726,726 ,0,0,0}, + {31142,31084,31083 ,7659,726,18140 ,0,0,0}, {31065,31084,31142 ,726,726,7659 ,0,0,0}, + {31142,31093,31091 ,7659,18141,726 ,0,0,0}, {31142,31087,31093 ,7659,726,18141 ,0,0,0}, + {31083,31087,31142 ,18140,726,7659 ,0,0,0}, {31185,31195,31150 ,726,726,726 ,0,0,0}, + {31193,31150,31192 ,7660,726,7660 ,0,0,0}, {31195,31192,31150 ,726,7660,726 ,0,0,0}, + {31194,31148,31150 ,726,726,726 ,0,0,0}, {31194,31150,31193 ,726,726,7660 ,0,0,0}, + {31188,31104,31101 ,726,726,726 ,0,0,0}, {31104,31188,31186 ,726,726,726 ,0,0,0}, + {31071,31104,31073 ,726,726,726 ,0,0,0}, {31104,31186,31073 ,726,726,726 ,0,0,0}, + {31063,31104,31069 ,726,726,726 ,0,0,0}, {31104,31071,31069 ,726,726,726 ,0,0,0}, + {31198,31199,31061 ,18142,18143,18144 ,0,0,0}, {31061,31200,31198 ,18144,18145,18142 ,0,0,0}, + {31061,31044,31200 ,18144,18146,18145 ,0,0,0}, {31061,31201,31202 ,18144,18147,18148 ,0,0,0}, + {31199,31201,31061 ,18143,18147,18144 ,0,0,0}, {31061,31203,31204 ,18144,18149,18150 ,0,0,0}, + {31202,31203,31061 ,18148,18149,18144 ,0,0,0}, {31204,31205,31061 ,18150,18151,18144 ,0,0,0}, + {31206,31061,31207 ,18152,18144,18153 ,0,0,0}, {31061,31205,31207 ,18144,18151,18153 ,0,0,0}, + {31208,31061,31209 ,18154,18144,18155 ,0,0,0}, {31061,31206,31209 ,18144,18152,18155 ,0,0,0}, + {31210,31061,31211 ,18156,18144,18157 ,0,0,0}, {31061,31208,31211 ,18144,18154,18157 ,0,0,0}, + {31060,31061,31210 ,18158,18144,18156 ,0,0,0}, {31043,31177,31200 ,18159,18160,18161 ,0,0,0}, + {31202,31201,31172 ,18162,18163,18164 ,0,0,0}, {31199,31198,31174 ,18165,18166,18167 ,0,0,0}, + {31204,31170,31205 ,18168,18169,18170 ,0,0,0}, {31173,31169,31203 ,18171,18172,18173 ,0,0,0}, + {31171,31179,31206 ,18174,18175,18176 ,0,0,0}, {31171,31207,31176 ,18174,18177,18178 ,0,0,0}, + {31184,31168,31208 ,18179,18180,18181 ,0,0,0}, {31208,31209,31184 ,18181,18182,18179 ,0,0,0}, + {31211,31168,31178 ,18183,18180,18184 ,0,0,0}, {31168,31211,31208 ,18180,18183,18181 ,0,0,0}, + {31166,31210,31178 ,18185,18186,18184 ,0,0,0}, {31211,31178,31210 ,18183,18184,18186 ,0,0,0}, + {31166,31059,31060 ,18185,18187,18188 ,0,0,0}, {31060,31210,31166 ,18188,18186,18185 ,0,0,0}, + {31170,31204,31169 ,18169,18168,18172 ,0,0,0}, {31179,31209,31206 ,18175,18182,18176 ,0,0,0}, + {31184,31209,31179 ,18179,18182,18175 ,0,0,0}, {31172,31201,31175 ,18164,18163,18189 ,0,0,0}, + {31176,31207,31205 ,18178,18177,18170 ,0,0,0}, {31171,31206,31207 ,18174,18176,18177 ,0,0,0}, + {31170,31176,31205 ,18169,18178,18170 ,0,0,0}, {31203,31169,31204 ,18173,18172,18168 ,0,0,0}, + {31202,31172,31173 ,18162,18164,18171 ,0,0,0}, {31173,31203,31202 ,18171,18173,18162 ,0,0,0}, + {31198,31177,31174 ,18166,18160,18167 ,0,0,0}, {31175,31199,31174 ,18189,18165,18167 ,0,0,0}, + {31201,31199,31175 ,18163,18165,18189 ,0,0,0}, {31043,31200,31044 ,18159,18161,35 ,0,0,0}, + {31177,31198,31200 ,18160,18166,18161 ,0,0,0}, {31109,31001,31212 ,17331,18026,18190 ,0,0,0}, + {31117,31138,31213 ,17322,17330,18191 ,0,0,0}, {31214,31137,31110 ,18192,17328,17333 ,0,0,0}, + {31215,31147,31121 ,18193,18194,17304 ,0,0,0}, {31216,31217,31120 ,18195,18196,17325 ,0,0,0}, + {31218,31126,31219 ,18197,17314,18198 ,0,0,0}, {31128,31124,31220 ,17316,17318,18199 ,0,0,0}, + {31131,31218,31221 ,17311,18197,18200 ,0,0,0}, {31140,31132,31136 ,18201,17305,17302 ,0,0,0}, + {31136,31221,31140 ,17302,18200,18201 ,0,0,0}, {31132,31222,31133 ,17305,18202,17307 ,0,0,0}, + {31222,31132,31140 ,18202,17305,18201 ,0,0,0}, {31222,31223,31133 ,18202,18203,17307 ,0,0,0}, + {31027,31134,31223 ,18204,17309,18203 ,0,0,0}, {31133,31223,31134 ,17307,18203,17309 ,0,0,0}, + {31026,31134,31027 ,18205,17309,18204 ,0,0,0}, {31131,31127,31218 ,17311,17312,18197 ,0,0,0}, + {31136,31131,31221 ,17302,17311,18200 ,0,0,0}, {31126,31128,31219 ,17314,17316,18198 ,0,0,0}, + {31127,31126,31218 ,17312,17314,18197 ,0,0,0}, {31220,31124,31147 ,18199,17318,18194 ,0,0,0}, + {31219,31128,31220 ,18198,17316,18199 ,0,0,0}, {31121,31147,31125 ,17304,18194,10001 ,0,0,0}, + {31147,31124,31125 ,18194,17318,10001 ,0,0,0}, {31217,31215,31119 ,18196,18193,17321 ,0,0,0}, + {31215,31121,31119 ,18193,17304,17321 ,0,0,0}, {31118,31216,31120 ,17324,18195,17325 ,0,0,0}, + {31120,31217,31119 ,17325,18196,17321 ,0,0,0}, {31216,31117,31213 ,18195,17322,18191 ,0,0,0}, + {31117,31216,31118 ,17322,18195,17324 ,0,0,0}, {31138,31137,31145 ,17330,17328,18206 ,0,0,0}, + {31138,31145,31213 ,17330,18206,18191 ,0,0,0}, {31214,31110,31212 ,18192,17333,18190 ,0,0,0}, + {31145,31137,31214 ,18206,17328,18192 ,0,0,0}, {31001,31109,31002 ,18026,17331,126 ,0,0,0}, + {31212,31110,31109 ,18190,17333,17331 ,0,0,0}, {31144,31216,31213 ,730,17561,730 ,0,0,0}, + {31215,31144,31147 ,730,730,730 ,0,0,0}, {31216,31144,31217 ,17561,730,17561 ,0,0,0}, + {31144,31215,31217 ,730,730,17561 ,0,0,0}, {31213,31145,31144 ,730,7433,730 ,0,0,0}, + {31018,31139,31019 ,7376,17561,7376 ,0,0,0}, {31139,31223,31222 ,17561,17561,7433 ,0,0,0}, + {31139,31018,31024 ,17561,7376,730 ,0,0,0}, {31223,31139,31027 ,17561,17561,18207 ,0,0,0}, + {31139,31024,31027 ,17561,730,18207 ,0,0,0}, {31222,31140,31139 ,7433,7376,17561 ,0,0,0}, + {31005,31102,30990 ,7015,730,730 ,0,0,0}, {31102,30991,30990 ,730,11465,730 ,0,0,0}, + {31009,31102,31007 ,7532,730,7016 ,0,0,0}, {31102,31005,31007 ,730,7015,7016 ,0,0,0}, + {30993,31102,31009 ,18208,730,7532 ,0,0,0}, {31219,31141,31218 ,730,7433,17561 ,0,0,0}, + {31221,31218,31141 ,17561,17561,7433 ,0,0,0}, {31140,31221,31141 ,18207,17561,7433 ,0,0,0}, + {31220,31147,31141 ,18209,730,7433 ,0,0,0}, {31220,31141,31219 ,18209,7433,730 ,0,0,0}, + {31012,31011,31149 ,18207,730,9877 ,0,0,0}, {30993,31012,31149 ,18210,18207,9877 ,0,0,0}, + {31015,31021,31149 ,730,730,9877 ,0,0,0}, {31015,31149,31011 ,730,9877,730 ,0,0,0}, + {31019,31149,31021 ,730,9877,730 ,0,0,0}, {31145,31214,31100 ,730,730,730 ,0,0,0}, + {31100,31212,31001 ,730,730,730 ,0,0,0}, {31100,31214,31212 ,730,730,730 ,0,0,0}, + {31001,30999,31100 ,730,730,730 ,0,0,0}, {31100,30997,30991 ,730,730,730 ,0,0,0}, + {30999,30997,31100 ,730,730,730 ,0,0,0}, {31224,31225,30989 ,18211,18212,18213 ,0,0,0}, + {30989,31226,31224 ,18213,18214,18211 ,0,0,0}, {30989,30973,31226 ,18213,18215,18214 ,0,0,0}, + {30989,31227,31228 ,18213,18216,18217 ,0,0,0}, {31225,31227,30989 ,18212,18216,18213 ,0,0,0}, + {30989,31229,31230 ,18213,18218,18219 ,0,0,0}, {31228,31229,30989 ,18217,18218,18213 ,0,0,0}, + {31230,31231,30989 ,18219,18220,18213 ,0,0,0}, {31232,30989,31233 ,18221,18213,18222 ,0,0,0}, + {30989,31231,31233 ,18213,18220,18222 ,0,0,0}, {31234,30989,31235 ,18223,18213,18224 ,0,0,0}, + {30989,31232,31235 ,18213,18221,18224 ,0,0,0}, {31236,30989,31237 ,18225,18213,18226 ,0,0,0}, + {30989,31234,31237 ,18213,18223,18226 ,0,0,0}, {30988,30989,31236 ,18227,18213,18225 ,0,0,0}, + {228,31135,31226 ,3345,18228,18229 ,0,0,0}, {31228,31227,31122 ,18230,18231,18232 ,0,0,0}, + {31225,31224,31129 ,18233,18234,18235 ,0,0,0}, {31230,31106,31231 ,18236,18237,18238 ,0,0,0}, + {31107,31108,31229 ,18239,18240,18241 ,0,0,0}, {31116,31115,31232 ,18242,18243,18244 ,0,0,0}, + {31116,31233,31105 ,18242,18245,18246 ,0,0,0}, {31114,31113,31234 ,18247,18248,18249 ,0,0,0}, + {31234,31235,31114 ,18249,18250,18247 ,0,0,0}, {31237,31113,31111 ,18251,18248,18252 ,0,0,0}, + {31113,31237,31234 ,18248,18251,18249 ,0,0,0}, {31112,31236,31111 ,18253,18254,18252 ,0,0,0}, + {31237,31111,31236 ,18251,18252,18254 ,0,0,0}, {31112,242,30988 ,18253,18255,18256 ,0,0,0}, + {30988,31236,31112 ,18256,18254,18253 ,0,0,0}, {31106,31230,31108 ,18237,18236,18240 ,0,0,0}, + {31115,31235,31232 ,18243,18250,18244 ,0,0,0}, {31114,31235,31115 ,18247,18250,18243 ,0,0,0}, + {31122,31227,31130 ,18232,18231,18257 ,0,0,0}, {31105,31233,31231 ,18246,18245,18238 ,0,0,0}, + {31116,31232,31233 ,18242,18244,18245 ,0,0,0}, {31106,31105,31231 ,18237,18246,18238 ,0,0,0}, + {31229,31108,31230 ,18241,18240,18236 ,0,0,0}, {31228,31122,31107 ,18230,18232,18239 ,0,0,0}, + {31107,31229,31228 ,18239,18241,18230 ,0,0,0}, {31224,31135,31129 ,18234,18228,18235 ,0,0,0}, + {31130,31225,31129 ,18257,18233,18235 ,0,0,0}, {31227,31225,31130 ,18231,18233,18257 ,0,0,0}, + {228,31226,30973 ,3345,18229,126 ,0,0,0}, {31135,31224,31226 ,18228,18234,18229 ,0,0,0} +// M3abstandhalter20mm.prt + , {31238,31239,31240 ,17973,17974,17975 ,0,0,0}, {31240,31241,31242 ,17975,17976,17977 ,0,0,0}, + {31241,31243,31242 ,17976,17978,17977 ,0,0,0}, {31240,31242,31238 ,17975,17977,17973 ,0,0,0}, + {31244,31245,31246 ,17979,17980,17981 ,0,0,0}, {31246,31245,31243 ,17981,17980,17978 ,0,0,0}, + {31244,31247,31248 ,17979,17982,17983 ,0,0,0}, {31248,31245,31244 ,17983,17980,17979 ,0,0,0}, + {31248,31247,31249 ,17983,17982,17984 ,0,0,0}, {31249,31247,31250 ,17984,17982,17985 ,0,0,0}, + {31250,31251,31252 ,17985,17986,17987 ,0,0,0}, {31249,31250,31252 ,17984,17985,17987 ,0,0,0}, + {31243,31241,31246 ,17978,17976,17981 ,0,0,0}, {160,31253,31254 ,7498,126,17988 ,0,0,0}, + {160,31254,31251 ,7498,17988,17986 ,0,0,0}, {31251,31254,31252 ,17986,17988,17987 ,0,0,0}, + {31238,31255,31239 ,17973,17989,17974 ,0,0,0}, {31256,31255,31257 ,17990,17989,17991 ,0,0,0}, + {31255,31256,31239 ,17989,17990,17974 ,0,0,0}, {31258,31259,31257 ,17992,17993,17991 ,0,0,0}, + {31256,31257,31259 ,17990,17991,17993 ,0,0,0}, {31258,31260,31261 ,17992,17994,17995 ,0,0,0}, + {31261,31259,31258 ,17995,17993,17992 ,0,0,0}, {31262,31260,31263 ,17996,17994,17997 ,0,0,0}, + {31260,31262,31261 ,17994,17996,17995 ,0,0,0}, {31264,31265,31263 ,17998,17999,17997 ,0,0,0}, + {31262,31263,31265 ,17996,17997,17999 ,0,0,0}, {31264,31266,31267 ,17998,18000,18001 ,0,0,0}, + {31267,31265,31264 ,18001,17999,17998 ,0,0,0}, {174,31266,31268 ,18002,18000,18003 ,0,0,0}, + {31266,174,31267 ,18000,18002,18001 ,0,0,0}, {31264,31263,31269 ,18004,18005,18006 ,0,0,0}, + {31269,31266,31264 ,18006,18007,18004 ,0,0,0}, {31269,31268,31266 ,18006,18008,18007 ,0,0,0}, + {31269,31260,31258 ,18006,18009,18010 ,0,0,0}, {31263,31260,31269 ,18005,18009,18006 ,0,0,0}, + {31269,31257,31255 ,18006,18011,18012 ,0,0,0}, {31258,31257,31269 ,18010,18011,18006 ,0,0,0}, + {31255,31238,31269 ,18012,18013,18006 ,0,0,0}, {31243,31269,31242 ,18014,18006,18015 ,0,0,0}, + {31269,31238,31242 ,18006,18013,18015 ,0,0,0}, {31248,31269,31245 ,18016,18006,18017 ,0,0,0}, + {31269,31243,31245 ,18006,18014,18017 ,0,0,0}, {31252,31269,31249 ,18018,18006,18019 ,0,0,0}, + {31269,31248,31249 ,18006,18016,18019 ,0,0,0}, {31253,31269,31254 ,18020,18006,18021 ,0,0,0}, + {31269,31252,31254 ,18006,18018,18021 ,0,0,0}, {31270,31271,31272 ,18022,18023,17547 ,0,0,0}, + {31273,31274,31275 ,21,7309,17533 ,0,0,0}, {31276,31271,31277 ,17546,18023,18024 ,0,0,0}, + {31271,31276,31272 ,18023,17546,17547 ,0,0,0}, {31276,31277,31278 ,17546,18024,17549 ,0,0,0}, + {31279,31280,31278 ,18025,17552,17549 ,0,0,0}, {31278,31277,31279 ,17549,18024,18025 ,0,0,0}, + {31281,31280,31279 ,18026,17552,18025 ,0,0,0}, {31281,31282,31280 ,18026,126,17552 ,0,0,0}, + {31283,31270,31272 ,17543,18022,17547 ,0,0,0}, {31284,31285,31283 ,17554,18027,17543 ,0,0,0}, + {31270,31283,31285 ,18022,17543,18027 ,0,0,0}, {31286,31287,31285 ,17538,18028,18027 ,0,0,0}, + {31285,31284,31286 ,18027,17554,17538 ,0,0,0}, {31287,31288,31289 ,18028,17540,18029 ,0,0,0}, + {31288,31287,31286 ,17540,18028,17538 ,0,0,0}, {31273,31289,31290 ,21,18029,17541 ,0,0,0}, + {31288,31290,31289 ,17540,17541,18029 ,0,0,0}, {31291,31292,31293 ,18030,18031,17556 ,0,0,0}, + {31273,31290,31274 ,21,17541,7309 ,0,0,0}, {31294,31295,31296 ,17525,18032,17557 ,0,0,0}, + {31295,31291,31297 ,18032,18030,17536 ,0,0,0}, {31298,31299,31300 ,18033,18034,17529 ,0,0,0}, + {31301,31302,31299 ,18035,17526,18034 ,0,0,0}, {31303,31304,31305 ,17523,18036,17530 ,0,0,0}, + {31298,31305,31304 ,18033,17530,18036 ,0,0,0}, {31303,31306,31307 ,17523,18037,18038 ,0,0,0}, + {31307,31304,31303 ,18038,18036,17523 ,0,0,0}, {31302,31300,31299 ,17526,17529,18034 ,0,0,0}, + {31298,31300,31305 ,18033,17529,17530 ,0,0,0}, {31301,31295,31294 ,18035,18032,17525 ,0,0,0}, + {31301,31294,31302 ,18035,17525,17526 ,0,0,0}, {31291,31293,31297 ,18030,17556,17536 ,0,0,0}, + {31296,31295,31297 ,17557,18032,17536 ,0,0,0}, {31275,31292,31273 ,17533,18031,21 ,0,0,0}, + {31293,31292,31275 ,17556,18031,17533 ,0,0,0}, {31308,31309,31310 ,324,18039,18040 ,0,0,0}, + {31310,31311,31312 ,18040,18041,18042 ,0,0,0}, {31311,31313,31312 ,18041,18043,18042 ,0,0,0}, + {31310,31312,31308 ,18040,18042,324 ,0,0,0}, {31314,31315,31316 ,18044,18045,18046 ,0,0,0}, + {31316,31315,31313 ,18046,18045,18043 ,0,0,0}, {31314,31317,31318 ,18044,18047,18048 ,0,0,0}, + {31318,31315,31314 ,18048,18045,18044 ,0,0,0}, {31318,31317,31319 ,18048,18047,18049 ,0,0,0}, + {31319,31317,31320 ,18049,18047,18050 ,0,0,0}, {31320,31321,31322 ,18050,18051,18052 ,0,0,0}, + {31319,31320,31322 ,18049,18050,18052 ,0,0,0}, {31313,31311,31316 ,18043,18041,18046 ,0,0,0}, + {31323,31324,31325 ,18053,126,18054 ,0,0,0}, {31323,31325,31321 ,18053,18054,18051 ,0,0,0}, + {31321,31325,31322 ,18051,18054,18052 ,0,0,0}, {31308,31326,31309 ,324,18055,18039 ,0,0,0}, + {31327,31326,31328 ,18056,18055,18057 ,0,0,0}, {31326,31327,31309 ,18055,18056,18039 ,0,0,0}, + {31329,31330,31328 ,18058,18059,18057 ,0,0,0}, {31327,31328,31330 ,18056,18057,18059 ,0,0,0}, + {31329,31331,31332 ,18058,18060,18061 ,0,0,0}, {31332,31330,31329 ,18061,18059,18058 ,0,0,0}, + {31333,31331,31334 ,18062,18060,18063 ,0,0,0}, {31331,31333,31332 ,18060,18062,18061 ,0,0,0}, + {31335,31336,31334 ,18064,18065,18063 ,0,0,0}, {31333,31334,31336 ,18062,18063,18065 ,0,0,0}, + {31335,31337,31338 ,18064,18066,18067 ,0,0,0}, {31338,31336,31335 ,18067,18065,18064 ,0,0,0}, + {31339,31337,31340 ,82,18066,18068 ,0,0,0}, {31337,31339,31338 ,18066,82,18067 ,0,0,0}, + {31335,31334,31341 ,18069,18070,18071 ,0,0,0}, {31341,31337,31335 ,18071,18072,18069 ,0,0,0}, + {31341,31340,31337 ,18071,18073,18072 ,0,0,0}, {31341,31331,31329 ,18071,18074,18075 ,0,0,0}, + {31334,31331,31341 ,18070,18074,18071 ,0,0,0}, {31341,31328,31326 ,18071,18076,18077 ,0,0,0}, + {31329,31328,31341 ,18075,18076,18071 ,0,0,0}, {31326,31308,31341 ,18077,18078,18071 ,0,0,0}, + {31313,31341,31312 ,18079,18071,18080 ,0,0,0}, {31341,31308,31312 ,18071,18078,18080 ,0,0,0}, + {31318,31341,31315 ,18081,18071,18082 ,0,0,0}, {31341,31313,31315 ,18071,18079,18082 ,0,0,0}, + {31322,31341,31319 ,18083,18071,18084 ,0,0,0}, {31341,31318,31319 ,18071,18081,18084 ,0,0,0}, + {31324,31341,31325 ,18085,18071,18086 ,0,0,0}, {31341,31322,31325 ,18071,18083,18086 ,0,0,0}, + {31342,31343,31344 ,18087,18088,17460 ,0,0,0}, {31345,31346,31347 ,324,17303,17446 ,0,0,0}, + {31348,31343,31349 ,17459,18088,18089 ,0,0,0}, {31343,31348,31344 ,18088,17459,17460 ,0,0,0}, + {31348,31349,31350 ,17459,18089,17462 ,0,0,0}, {31351,31352,31350 ,18090,17464,17462 ,0,0,0}, + {31350,31349,31351 ,17462,18089,18090 ,0,0,0}, {31353,31352,31351 ,18091,17464,18090 ,0,0,0}, + {31353,31354,31352 ,18091,18092,17464 ,0,0,0}, {31355,31342,31344 ,17456,18087,17460 ,0,0,0}, + {31356,31357,31355 ,17465,18093,17456 ,0,0,0}, {31342,31355,31357 ,18087,17456,18093 ,0,0,0}, + {31358,31359,31357 ,17451,18094,18093 ,0,0,0}, {31357,31356,31358 ,18093,17465,17451 ,0,0,0}, + {31359,31360,31361 ,18094,17453,18095 ,0,0,0}, {31360,31359,31358 ,17453,18094,17451 ,0,0,0}, + {31345,31361,31362 ,324,18095,17454 ,0,0,0}, {31360,31362,31361 ,17453,17454,18095 ,0,0,0}, + {31363,31364,31365 ,18096,18097,17467 ,0,0,0}, {31345,31362,31346 ,324,17454,17303 ,0,0,0}, + {31366,31367,31368 ,17438,18098,17468 ,0,0,0}, {31367,31363,31369 ,18098,18096,17449 ,0,0,0}, + {31370,31371,31372 ,18099,18100,17442 ,0,0,0}, {31373,31374,31371 ,18101,17439,18100 ,0,0,0}, + {31375,31376,31377 ,17435,18102,17443 ,0,0,0}, {31370,31377,31376 ,18099,17443,18102 ,0,0,0}, + {31375,31378,31379 ,17435,82,18103 ,0,0,0}, {31379,31376,31375 ,18103,18102,17435 ,0,0,0}, + {31374,31372,31371 ,17439,17442,18100 ,0,0,0}, {31370,31372,31377 ,18099,17442,17443 ,0,0,0}, + {31373,31367,31366 ,18101,18098,17438 ,0,0,0}, {31373,31366,31374 ,18101,17438,17439 ,0,0,0}, + {31363,31365,31369 ,18096,17467,17449 ,0,0,0}, {31368,31367,31369 ,17468,18098,17449 ,0,0,0}, + {31347,31364,31345 ,17446,18097,324 ,0,0,0}, {31365,31364,31347 ,17467,18097,17446 ,0,0,0}, + {31380,31271,31381 ,18104,18104,18104 ,0,0,0}, {31382,31383,31271 ,18104,18104,18104 ,0,0,0}, + {31271,31383,31381 ,18104,18104,18104 ,0,0,0}, {31380,31381,31384 ,18104,18104,18104 ,0,0,0}, + {31385,31386,31274 ,730,730,730 ,0,0,0}, {31387,31297,31388 ,730,730,730 ,0,0,0}, + {31389,174,31282 ,730,730,730 ,0,0,0}, {31390,31265,31267 ,730,730,730 ,0,0,0}, + {31391,31278,31392 ,730,730,730 ,0,0,0}, {31276,31391,31393 ,730,730,730 ,0,0,0}, + {31393,31272,31276 ,730,730,730 ,0,0,0}, {31394,31283,31393 ,730,730,730 ,0,0,0}, + {31278,31391,31276 ,730,730,730 ,0,0,0}, {31280,174,31392 ,730,730,730 ,0,0,0}, + {31280,31392,31278 ,730,730,730 ,0,0,0}, {31394,31395,31284 ,730,730,730 ,0,0,0}, + {31280,31282,174 ,730,730,730 ,0,0,0}, {31286,31396,31288 ,730,730,730 ,0,0,0}, + {31284,31395,31286 ,730,730,730 ,0,0,0}, {31397,31261,31262 ,730,730,730 ,0,0,0}, + {31259,31261,31398 ,730,730,730 ,0,0,0}, {31274,31386,31275 ,730,730,730 ,0,0,0}, + {31399,31256,31400 ,730,730,730 ,0,0,0}, {31401,31239,31256 ,730,730,730 ,0,0,0}, + {31293,31275,31388 ,730,730,730 ,0,0,0}, {31402,31403,31387 ,730,730,730 ,0,0,0}, + {31240,31404,31241 ,730,730,730 ,0,0,0}, {31239,31405,31240 ,730,730,730 ,0,0,0}, + {31302,31294,31403 ,730,730,730 ,0,0,0}, {31403,31296,31297 ,730,730,730 ,0,0,0}, + {31246,31406,31407 ,730,730,730 ,0,0,0}, {31406,31241,31408 ,730,730,730 ,0,0,0}, + {31409,31300,31410 ,730,730,730 ,0,0,0}, {31411,31247,31244 ,730,730,730 ,0,0,0}, + {31244,31246,31407 ,730,730,730 ,0,0,0}, {31250,31412,31413 ,730,730,730 ,0,0,0}, + {160,31306,31303 ,730,730,730 ,0,0,0}, {31251,31414,160 ,730,730,730 ,0,0,0}, + {31251,31250,31413 ,730,730,730 ,0,0,0}, {31415,31303,31305 ,730,730,730 ,0,0,0}, + {31416,31412,31247 ,730,730,730 ,0,0,0}, {31305,31409,31415 ,730,730,730 ,0,0,0}, + {31396,31385,31290 ,730,730,730 ,0,0,0}, {31262,31265,31417 ,730,730,730 ,0,0,0}, + {31239,31401,31405 ,730,730,730 ,0,0,0}, {31393,31283,31272 ,730,730,730 ,0,0,0}, + {31394,31284,31283 ,730,730,730 ,0,0,0}, {31396,31286,31395 ,730,730,730 ,0,0,0}, + {31396,31290,31288 ,730,730,730 ,0,0,0}, {31385,31274,31290 ,730,730,730 ,0,0,0}, + {31388,31275,31386 ,730,730,730 ,0,0,0}, {31388,31297,31293 ,730,730,730 ,0,0,0}, + {31403,31297,31387 ,730,730,730 ,0,0,0}, {31403,31410,31300 ,730,730,730 ,0,0,0}, + {31300,31302,31403 ,730,730,730 ,0,0,0}, {31409,31305,31300 ,730,730,730 ,0,0,0}, + {160,31303,31415 ,730,730,730 ,0,0,0}, {160,31414,31306 ,730,730,730 ,0,0,0}, + {31251,31413,31414 ,730,730,730 ,0,0,0}, {31247,31412,31250 ,730,730,730 ,0,0,0}, + {31247,31411,31416 ,730,730,730 ,0,0,0}, {31244,31407,31411 ,730,730,730 ,0,0,0}, + {31241,31406,31246 ,730,730,730 ,0,0,0}, {31241,31404,31408 ,730,730,730 ,0,0,0}, + {31240,31405,31404 ,730,730,730 ,0,0,0}, {31399,31401,31256 ,730,730,730 ,0,0,0}, + {31259,31400,31256 ,730,730,730 ,0,0,0}, {31261,31397,31398 ,730,730,730 ,0,0,0}, + {31259,31398,31400 ,730,730,730 ,0,0,0}, {31262,31418,31397 ,730,730,730 ,0,0,0}, + {31417,31265,31390 ,730,730,730 ,0,0,0}, {31418,31262,31417 ,730,730,730 ,0,0,0}, + {31390,31267,31389 ,730,730,730 ,0,0,0}, {174,31389,31267 ,730,730,730 ,0,0,0}, + {31296,31403,31294 ,730,730,730 ,0,0,0}, {31402,31410,31403 ,730,730,730 ,0,0,0}, + {31419,31420,31371 ,18105,18106,18106 ,0,0,0}, {31420,31421,31422 ,18106,1433,1433 ,0,0,0}, + {31422,31371,31420 ,1433,18106,18106 ,0,0,0}, {31371,31423,31419 ,18106,18105,18105 ,0,0,0}, + {31424,31425,31343 ,2162,18107,18107 ,0,0,0}, {31425,31380,31384 ,18107,2162,2162 ,0,0,0}, + {31384,31343,31425 ,2162,18107,18107 ,0,0,0}, {31343,31426,31424 ,18107,2162,2162 ,0,0,0}, + {31345,31421,31427 ,18108,1077,18109 ,0,0,0}, {31424,31426,31427 ,18110,18110,18109 ,0,0,0}, + {31426,31345,31427 ,18110,18108,18109 ,0,0,0}, {31345,31422,31421 ,18108,18111,1077 ,0,0,0}, + {31273,31428,31382 ,18112,18112,18112 ,0,0,0}, {31273,31429,31430 ,18112,18113,18113 ,0,0,0}, + {31273,31430,31428 ,18112,18113,18112 ,0,0,0}, {31428,31383,31382 ,18112,18112,18112 ,0,0,0}, + {31431,31332,31432 ,726,7628,8135 ,0,0,0}, {31433,31321,31434 ,7628,7625,7628 ,0,0,0}, + {31327,31330,31435 ,7627,7625,7761 ,0,0,0}, {31327,31436,31437 ,7627,18114,7253 ,0,0,0}, + {31437,31438,31309 ,7253,18115,7628 ,0,0,0}, {31309,31438,31310 ,7628,18115,7627 ,0,0,0}, + {31330,31332,31431 ,7625,7628,726 ,0,0,0}, {31439,31440,31311 ,8017,18116,7628 ,0,0,0}, + {31311,31310,31441 ,7628,7627,18117 ,0,0,0}, {31442,31316,31440 ,7756,7627,18116 ,0,0,0}, + {31333,31443,31432 ,7628,8135,8135 ,0,0,0}, {31339,31354,31444 ,7628,7628,7628 ,0,0,0}, + {31314,31445,31317 ,7880,8135,7625 ,0,0,0}, {31321,31320,31434 ,7625,7628,7628 ,0,0,0}, + {31446,31352,31339 ,726,7628,7628 ,0,0,0}, {31358,31356,31447 ,7628,726,7628 ,0,0,0}, + {31447,31348,31448 ,7628,726,726 ,0,0,0}, {31449,31347,31450 ,7626,726,726 ,0,0,0}, + {31451,31360,31358 ,7628,7626,7628 ,0,0,0}, {31365,31449,31369 ,7628,7626,726 ,0,0,0}, + {31452,31368,31453 ,7628,7628,726 ,0,0,0}, {31454,31372,31455 ,7628,726,7628 ,0,0,0}, + {31366,31452,31455 ,726,7628,7628 ,0,0,0}, {31450,31346,31456 ,726,7626,7628 ,0,0,0}, + {31454,31457,31377 ,7628,7628,726 ,0,0,0}, {31451,31456,31362 ,7628,7628,7628 ,0,0,0}, + {31378,31323,31433 ,7628,7628,7628 ,0,0,0}, {31323,31378,31375 ,7628,7628,7628 ,0,0,0}, + {31350,31458,31348 ,726,726,726 ,0,0,0}, {31459,31358,31447 ,726,7628,7628 ,0,0,0}, + {31460,31434,31320 ,7754,7628,7628 ,0,0,0}, {31350,31446,31458 ,726,726,726 ,0,0,0}, + {31317,31460,31320 ,7625,7754,7628 ,0,0,0}, {31461,31338,31444 ,7628,7628,7628 ,0,0,0}, + {31347,31346,31450 ,726,7626,726 ,0,0,0}, {31336,31338,31461 ,7628,7628,7628 ,0,0,0}, + {31316,31442,31314 ,7627,7756,7880 ,0,0,0}, {31462,31333,31336 ,7880,7628,7628 ,0,0,0}, + {31321,31433,31323 ,7625,7628,7628 ,0,0,0}, {31344,31447,31355 ,726,7628,726 ,0,0,0}, + {31317,31445,31463 ,7625,8135,7625 ,0,0,0}, {31463,31460,31317 ,7625,7754,7625 ,0,0,0}, + {31314,31442,31445 ,7880,7756,8135 ,0,0,0}, {31311,31440,31316 ,7628,18116,7627 ,0,0,0}, + {31311,31441,31439 ,7628,18117,8017 ,0,0,0}, {31310,31438,31441 ,7627,18115,18117 ,0,0,0}, + {31327,31437,31309 ,7627,7253,7628 ,0,0,0}, {31327,31435,31436 ,7627,7761,18114 ,0,0,0}, + {31330,31431,31435 ,7625,726,7761 ,0,0,0}, {31333,31432,31332 ,7628,8135,7628 ,0,0,0}, + {31333,31462,31443 ,7628,7880,8135 ,0,0,0}, {31336,31461,31462 ,7628,7628,7880 ,0,0,0}, + {31339,31444,31338 ,7628,7628,7628 ,0,0,0}, {31339,31352,31354 ,7628,7628,7628 ,0,0,0}, + {31446,31350,31352 ,726,726,7628 ,0,0,0}, {31448,31348,31458 ,726,726,726 ,0,0,0}, + {31344,31348,31447 ,726,726,7628 ,0,0,0}, {31356,31355,31447 ,726,726,7628 ,0,0,0}, + {31451,31358,31459 ,7628,7628,726 ,0,0,0}, {31451,31362,31360 ,7628,7628,7626 ,0,0,0}, + {31456,31346,31362 ,7628,7626,7628 ,0,0,0}, {31365,31347,31449 ,7628,726,7626 ,0,0,0}, + {31453,31369,31449 ,726,726,7626 ,0,0,0}, {31452,31366,31368 ,7628,726,7628 ,0,0,0}, + {31453,31368,31369 ,726,7628,726 ,0,0,0}, {31455,31374,31366 ,7628,726,726 ,0,0,0}, + {31372,31454,31377 ,726,7628,726 ,0,0,0}, {31374,31455,31372 ,726,7628,726 ,0,0,0}, + {31377,31457,31375 ,726,7628,7628 ,0,0,0}, {31323,31375,31457 ,7628,7628,7628 ,0,0,0}, + {31448,31464,31447 ,726,7628,7628 ,0,0,0}, {31447,31464,31459 ,7628,7628,726 ,0,0,0}, + {31429,31299,31465 ,18118,18119,18119 ,0,0,0}, {31419,31423,31299 ,18120,18120,18119 ,0,0,0}, + {31299,31423,31465 ,18119,18120,18119 ,0,0,0}, {31429,31465,31430 ,18118,18119,18118 ,0,0,0}, + {31444,31353,31466 ,17413,18121,18122 ,0,0,0}, {31432,31443,31467 ,17404,17412,18123 ,0,0,0}, + {31468,31462,31461 ,18124,17410,17415 ,0,0,0}, {31469,31428,31437 ,18125,18126,17385 ,0,0,0}, + {31470,31471,31435 ,18127,18128,17407 ,0,0,0}, {31472,31440,31473 ,18129,17396,18130 ,0,0,0}, + {31439,31441,31474 ,17398,17400,18131 ,0,0,0}, {31445,31472,31475 ,17393,18129,18132 ,0,0,0}, + {31465,31460,31463 ,18133,17386,17384 ,0,0,0}, {31463,31475,31465 ,17384,18132,18133 ,0,0,0}, + {31460,31476,31434 ,17386,18134,17388 ,0,0,0}, {31476,31460,31465 ,18134,17386,18133 ,0,0,0}, + {31476,31477,31434 ,18134,18135,17388 ,0,0,0}, {31379,31433,31477 ,18103,17390,18135 ,0,0,0}, + {31434,31477,31433 ,17388,18135,17390 ,0,0,0}, {31378,31433,31379 ,82,17390,18103 ,0,0,0}, + {31445,31442,31472 ,17393,17394,18129 ,0,0,0}, {31463,31445,31475 ,17384,17393,18132 ,0,0,0}, + {31440,31439,31473 ,17396,17398,18130 ,0,0,0}, {31442,31440,31472 ,17394,17396,18129 ,0,0,0}, + {31474,31441,31428 ,18131,17400,18126 ,0,0,0}, {31473,31439,31474 ,18130,17398,18131 ,0,0,0}, + {31437,31428,31438 ,17385,18126,18136 ,0,0,0}, {31428,31441,31438 ,18126,17400,18136 ,0,0,0}, + {31471,31469,31436 ,18128,18125,17403 ,0,0,0}, {31469,31437,31436 ,18125,17385,17403 ,0,0,0}, + {31431,31470,31435 ,17406,18127,17407 ,0,0,0}, {31435,31471,31436 ,17407,18128,17403 ,0,0,0}, + {31470,31432,31467 ,18127,17404,18123 ,0,0,0}, {31432,31470,31431 ,17404,18127,17406 ,0,0,0}, + {31443,31462,31381 ,17412,17410,18137 ,0,0,0}, {31443,31381,31467 ,17412,18137,18123 ,0,0,0}, + {31468,31461,31466 ,18124,17415,18122 ,0,0,0}, {31381,31462,31468 ,18137,17410,18124 ,0,0,0}, + {31353,31444,31354 ,18121,17413,18092 ,0,0,0}, {31466,31461,31444 ,18122,17415,17413 ,0,0,0}, + {31376,31423,31370 ,726,726,7661 ,0,0,0}, {31423,31371,31370 ,726,7661,7661 ,0,0,0}, + {31379,31423,31376 ,18138,726,726 ,0,0,0}, {31476,31423,31477 ,7658,726,18138 ,0,0,0}, + {31423,31379,31477 ,726,18138,18138 ,0,0,0}, {31465,31423,31476 ,7661,726,7658 ,0,0,0}, + {31470,31383,31471 ,726,17471,17470 ,0,0,0}, {31471,31383,31469 ,17470,17471,18139 ,0,0,0}, + {31383,31428,31469 ,17471,17471,18139 ,0,0,0}, {31383,31467,31381 ,17471,726,726 ,0,0,0}, + {31383,31470,31467 ,17471,726,726 ,0,0,0}, {31342,31426,31343 ,726,726,726 ,0,0,0}, + {31359,31426,31357 ,726,726,726 ,0,0,0}, {31426,31342,31357 ,726,726,726 ,0,0,0}, + {31345,31426,31361 ,726,726,726 ,0,0,0}, {31426,31359,31361 ,726,726,726 ,0,0,0}, + {31422,31364,31363 ,7659,726,18140 ,0,0,0}, {31345,31364,31422 ,726,726,7659 ,0,0,0}, + {31422,31373,31371 ,7659,18141,726 ,0,0,0}, {31422,31367,31373 ,7659,726,18141 ,0,0,0}, + {31363,31367,31422 ,18140,726,7659 ,0,0,0}, {31465,31475,31430 ,726,726,726 ,0,0,0}, + {31473,31430,31472 ,7660,726,7660 ,0,0,0}, {31475,31472,31430 ,726,7660,726 ,0,0,0}, + {31474,31428,31430 ,726,726,726 ,0,0,0}, {31474,31430,31473 ,726,726,7660 ,0,0,0}, + {31468,31384,31381 ,726,726,726 ,0,0,0}, {31384,31468,31466 ,726,726,726 ,0,0,0}, + {31351,31384,31353 ,726,726,726 ,0,0,0}, {31384,31466,31353 ,726,726,726 ,0,0,0}, + {31343,31384,31349 ,726,726,726 ,0,0,0}, {31384,31351,31349 ,726,726,726 ,0,0,0}, + {31478,31479,31341 ,18142,18143,18144 ,0,0,0}, {31341,31480,31478 ,18144,18145,18142 ,0,0,0}, + {31341,31324,31480 ,18144,18146,18145 ,0,0,0}, {31341,31481,31482 ,18144,18147,18148 ,0,0,0}, + {31479,31481,31341 ,18143,18147,18144 ,0,0,0}, {31341,31483,31484 ,18144,18149,18150 ,0,0,0}, + {31482,31483,31341 ,18148,18149,18144 ,0,0,0}, {31484,31485,31341 ,18150,18151,18144 ,0,0,0}, + {31486,31341,31487 ,18152,18144,18153 ,0,0,0}, {31341,31485,31487 ,18144,18151,18153 ,0,0,0}, + {31488,31341,31489 ,18154,18144,18155 ,0,0,0}, {31341,31486,31489 ,18144,18152,18155 ,0,0,0}, + {31490,31341,31491 ,18156,18144,18157 ,0,0,0}, {31341,31488,31491 ,18144,18154,18157 ,0,0,0}, + {31340,31341,31490 ,18158,18144,18156 ,0,0,0}, {31323,31457,31480 ,18159,18160,18161 ,0,0,0}, + {31482,31481,31452 ,18162,18163,18164 ,0,0,0}, {31479,31478,31454 ,18165,18166,18167 ,0,0,0}, + {31484,31450,31485 ,18168,18169,18170 ,0,0,0}, {31453,31449,31483 ,18171,18172,18173 ,0,0,0}, + {31451,31459,31486 ,18174,18175,18176 ,0,0,0}, {31451,31487,31456 ,18174,18177,18178 ,0,0,0}, + {31464,31448,31488 ,18179,18180,18181 ,0,0,0}, {31488,31489,31464 ,18181,18182,18179 ,0,0,0}, + {31491,31448,31458 ,18183,18180,18184 ,0,0,0}, {31448,31491,31488 ,18180,18183,18181 ,0,0,0}, + {31446,31490,31458 ,18185,18186,18184 ,0,0,0}, {31491,31458,31490 ,18183,18184,18186 ,0,0,0}, + {31446,31339,31340 ,18185,18187,18188 ,0,0,0}, {31340,31490,31446 ,18188,18186,18185 ,0,0,0}, + {31450,31484,31449 ,18169,18168,18172 ,0,0,0}, {31459,31489,31486 ,18175,18182,18176 ,0,0,0}, + {31464,31489,31459 ,18179,18182,18175 ,0,0,0}, {31452,31481,31455 ,18164,18163,18189 ,0,0,0}, + {31456,31487,31485 ,18178,18177,18170 ,0,0,0}, {31451,31486,31487 ,18174,18176,18177 ,0,0,0}, + {31450,31456,31485 ,18169,18178,18170 ,0,0,0}, {31483,31449,31484 ,18173,18172,18168 ,0,0,0}, + {31482,31452,31453 ,18162,18164,18171 ,0,0,0}, {31453,31483,31482 ,18171,18173,18162 ,0,0,0}, + {31478,31457,31454 ,18166,18160,18167 ,0,0,0}, {31455,31479,31454 ,18189,18165,18167 ,0,0,0}, + {31481,31479,31455 ,18163,18165,18189 ,0,0,0}, {31323,31480,31324 ,18159,18161,35 ,0,0,0}, + {31457,31478,31480 ,18160,18166,18161 ,0,0,0}, {31389,31281,31492 ,17331,18026,18190 ,0,0,0}, + {31397,31418,31493 ,17322,17330,18191 ,0,0,0}, {31494,31417,31390 ,18192,17328,17333 ,0,0,0}, + {31495,31427,31401 ,18193,18194,17304 ,0,0,0}, {31496,31497,31400 ,18195,18196,17325 ,0,0,0}, + {31498,31406,31499 ,18197,17314,18198 ,0,0,0}, {31408,31404,31500 ,17316,17318,18199 ,0,0,0}, + {31411,31498,31501 ,17311,18197,18200 ,0,0,0}, {31420,31412,31416 ,18201,17305,17302 ,0,0,0}, + {31416,31501,31420 ,17302,18200,18201 ,0,0,0}, {31412,31502,31413 ,17305,18202,17307 ,0,0,0}, + {31502,31412,31420 ,18202,17305,18201 ,0,0,0}, {31502,31503,31413 ,18202,18203,17307 ,0,0,0}, + {31307,31414,31503 ,18204,17309,18203 ,0,0,0}, {31413,31503,31414 ,17307,18203,17309 ,0,0,0}, + {31306,31414,31307 ,18205,17309,18204 ,0,0,0}, {31411,31407,31498 ,17311,17312,18197 ,0,0,0}, + {31416,31411,31501 ,17302,17311,18200 ,0,0,0}, {31406,31408,31499 ,17314,17316,18198 ,0,0,0}, + {31407,31406,31498 ,17312,17314,18197 ,0,0,0}, {31500,31404,31427 ,18199,17318,18194 ,0,0,0}, + {31499,31408,31500 ,18198,17316,18199 ,0,0,0}, {31401,31427,31405 ,17304,18194,10001 ,0,0,0}, + {31427,31404,31405 ,18194,17318,10001 ,0,0,0}, {31497,31495,31399 ,18196,18193,17321 ,0,0,0}, + {31495,31401,31399 ,18193,17304,17321 ,0,0,0}, {31398,31496,31400 ,17324,18195,17325 ,0,0,0}, + {31400,31497,31399 ,17325,18196,17321 ,0,0,0}, {31496,31397,31493 ,18195,17322,18191 ,0,0,0}, + {31397,31496,31398 ,17322,18195,17324 ,0,0,0}, {31418,31417,31425 ,17330,17328,18206 ,0,0,0}, + {31418,31425,31493 ,17330,18206,18191 ,0,0,0}, {31494,31390,31492 ,18192,17333,18190 ,0,0,0}, + {31425,31417,31494 ,18206,17328,18192 ,0,0,0}, {31281,31389,31282 ,18026,17331,126 ,0,0,0}, + {31492,31390,31389 ,18190,17333,17331 ,0,0,0}, {31424,31496,31493 ,730,17561,730 ,0,0,0}, + {31495,31424,31427 ,730,730,730 ,0,0,0}, {31496,31424,31497 ,17561,730,17561 ,0,0,0}, + {31424,31495,31497 ,730,730,17561 ,0,0,0}, {31493,31425,31424 ,730,7433,730 ,0,0,0}, + {31298,31419,31299 ,7376,17561,7376 ,0,0,0}, {31419,31503,31502 ,17561,17561,7433 ,0,0,0}, + {31419,31298,31304 ,17561,7376,730 ,0,0,0}, {31503,31419,31307 ,17561,17561,18207 ,0,0,0}, + {31419,31304,31307 ,17561,730,18207 ,0,0,0}, {31502,31420,31419 ,7433,7376,17561 ,0,0,0}, + {31285,31382,31270 ,7015,730,730 ,0,0,0}, {31382,31271,31270 ,730,11465,730 ,0,0,0}, + {31289,31382,31287 ,7532,730,7016 ,0,0,0}, {31382,31285,31287 ,730,7015,7016 ,0,0,0}, + {31273,31382,31289 ,18208,730,7532 ,0,0,0}, {31499,31421,31498 ,730,7433,17561 ,0,0,0}, + {31501,31498,31421 ,17561,17561,7433 ,0,0,0}, {31420,31501,31421 ,18207,17561,7433 ,0,0,0}, + {31500,31427,31421 ,18209,730,7433 ,0,0,0}, {31500,31421,31499 ,18209,7433,730 ,0,0,0}, + {31292,31291,31429 ,18207,730,9877 ,0,0,0}, {31273,31292,31429 ,18210,18207,9877 ,0,0,0}, + {31295,31301,31429 ,730,730,9877 ,0,0,0}, {31295,31429,31291 ,730,9877,730 ,0,0,0}, + {31299,31429,31301 ,730,9877,730 ,0,0,0}, {31425,31494,31380 ,730,730,730 ,0,0,0}, + {31380,31492,31281 ,730,730,730 ,0,0,0}, {31380,31494,31492 ,730,730,730 ,0,0,0}, + {31281,31279,31380 ,730,730,730 ,0,0,0}, {31380,31277,31271 ,730,730,730 ,0,0,0}, + {31279,31277,31380 ,730,730,730 ,0,0,0}, {31504,31505,31269 ,18211,18212,18213 ,0,0,0}, + {31269,31506,31504 ,18213,18214,18211 ,0,0,0}, {31269,31253,31506 ,18213,18215,18214 ,0,0,0}, + {31269,31507,31508 ,18213,18216,18217 ,0,0,0}, {31505,31507,31269 ,18212,18216,18213 ,0,0,0}, + {31269,31509,31510 ,18213,18218,18219 ,0,0,0}, {31508,31509,31269 ,18217,18218,18213 ,0,0,0}, + {31510,31511,31269 ,18219,18220,18213 ,0,0,0}, {31512,31269,31513 ,18221,18213,18222 ,0,0,0}, + {31269,31511,31513 ,18213,18220,18222 ,0,0,0}, {31514,31269,31515 ,18223,18213,18224 ,0,0,0}, + {31269,31512,31515 ,18213,18221,18224 ,0,0,0}, {31516,31269,31517 ,18225,18213,18226 ,0,0,0}, + {31269,31514,31517 ,18213,18223,18226 ,0,0,0}, {31268,31269,31516 ,18227,18213,18225 ,0,0,0}, + {160,31415,31506 ,3345,18228,18229 ,0,0,0}, {31508,31507,31402 ,18230,18231,18232 ,0,0,0}, + {31505,31504,31409 ,18233,18234,18235 ,0,0,0}, {31510,31386,31511 ,18236,18237,18238 ,0,0,0}, + {31387,31388,31509 ,18239,18240,18241 ,0,0,0}, {31396,31395,31512 ,18242,18243,18244 ,0,0,0}, + {31396,31513,31385 ,18242,18245,18246 ,0,0,0}, {31394,31393,31514 ,18247,18248,18249 ,0,0,0}, + {31514,31515,31394 ,18249,18250,18247 ,0,0,0}, {31517,31393,31391 ,18251,18248,18252 ,0,0,0}, + {31393,31517,31514 ,18248,18251,18249 ,0,0,0}, {31392,31516,31391 ,18253,18254,18252 ,0,0,0}, + {31517,31391,31516 ,18251,18252,18254 ,0,0,0}, {31392,174,31268 ,18253,18255,18256 ,0,0,0}, + {31268,31516,31392 ,18256,18254,18253 ,0,0,0}, {31386,31510,31388 ,18237,18236,18240 ,0,0,0}, + {31395,31515,31512 ,18243,18250,18244 ,0,0,0}, {31394,31515,31395 ,18247,18250,18243 ,0,0,0}, + {31402,31507,31410 ,18232,18231,18257 ,0,0,0}, {31385,31513,31511 ,18246,18245,18238 ,0,0,0}, + {31396,31512,31513 ,18242,18244,18245 ,0,0,0}, {31386,31385,31511 ,18237,18246,18238 ,0,0,0}, + {31509,31388,31510 ,18241,18240,18236 ,0,0,0}, {31508,31402,31387 ,18230,18232,18239 ,0,0,0}, + {31387,31509,31508 ,18239,18241,18230 ,0,0,0}, {31504,31415,31409 ,18234,18228,18235 ,0,0,0}, + {31410,31505,31409 ,18257,18233,18235 ,0,0,0}, {31507,31505,31410 ,18231,18233,18257 ,0,0,0}, + {160,31506,31253 ,3345,18229,126 ,0,0,0}, {31415,31504,31506 ,18228,18234,18229 ,0,0,0} +// Battery3.prt + , {31518,31519,31520 ,0,1,0 ,0,0,0}, {31521,31522,31523 ,2,2,3 ,0,0,0}, + {31521,31520,31522 ,2,0,2 ,0,0,0}, {31523,31522,31524 ,3,2,3 ,0,0,0}, + {31520,31521,31518 ,0,2,0 ,0,0,0}, {31525,31519,31518 ,1,1,0 ,0,0,0}, + {31526,31525,31527 ,4,1,4 ,0,0,0}, {31525,31526,31519 ,1,4,1 ,0,0,0}, + {31528,31529,31530 ,5,6,5 ,0,0,0}, {31531,31532,31533 ,7,7,8 ,0,0,0}, + {31531,31530,31532 ,7,5,7 ,0,0,0}, {31533,31532,31534 ,8,7,8 ,0,0,0}, + {31530,31531,31528 ,5,7,5 ,0,0,0}, {31535,31529,31528 ,9,6,5 ,0,0,0}, + {31536,31535,31537 ,10,9,11 ,0,0,0}, {31535,31536,31529 ,9,10,6 ,0,0,0}, + {31538,31539,31540 ,12,13,12 ,0,0,0}, {31541,31542,31543 ,14,14,15 ,0,0,0}, + {31541,31540,31542 ,14,12,14 ,0,0,0}, {31543,31542,31544 ,15,14,15 ,0,0,0}, + {31540,31541,31538 ,12,14,12 ,0,0,0}, {31545,31539,31538 ,13,13,12 ,0,0,0}, + {31546,31545,31547 ,16,13,16 ,0,0,0}, {31545,31546,31539 ,13,16,13 ,0,0,0}, + {31548,31549,31550 ,17,18,17 ,0,0,0}, {31551,31552,31553 ,19,19,20 ,0,0,0}, + {31551,31550,31552 ,19,17,19 ,0,0,0}, {31553,31552,31554 ,20,19,20 ,0,0,0}, + {31550,31551,31548 ,17,19,17 ,0,0,0}, {31555,31549,31548 ,18,18,17 ,0,0,0}, + {31556,31555,31557 ,21,18,21 ,0,0,0}, {31555,31556,31549 ,18,21,18 ,0,0,0}, + {31558,31559,31560 ,22,23,24 ,0,0,0}, {31561,31562,31563 ,25,26,27 ,0,0,0}, + {31564,31558,31560 ,28,22,24 ,0,0,0}, {31563,31562,31564 ,27,26,28 ,0,0,0}, + {31562,31561,31565 ,26,25,29 ,0,0,0}, {31560,31563,31564 ,24,27,28 ,0,0,0}, + {31566,31567,31568 ,30,31,32 ,0,0,0}, {31567,31569,31568 ,31,33,32 ,0,0,0}, + {31565,31570,31566 ,29,34,30 ,0,0,0}, {31567,31566,31570 ,31,30,34 ,0,0,0}, + {31571,31572,31573 ,35,36,37 ,0,0,0}, {31574,31575,31569 ,38,39,33 ,0,0,0}, + {31572,31575,31574 ,36,39,38 ,0,0,0}, {31572,31574,31573 ,36,38,37 ,0,0,0}, + {31573,31576,31571 ,37,40,35 ,0,0,0}, {31568,31569,31575 ,32,33,39 ,0,0,0}, + {31565,31561,31570 ,29,25,34 ,0,0,0}, {31558,31577,31559 ,22,41,23 ,0,0,0}, + {31578,31577,31579 ,42,41,43 ,0,0,0}, {31577,31578,31559 ,41,42,23 ,0,0,0}, + {31580,31581,31579 ,44,45,43 ,0,0,0}, {31578,31579,31581 ,42,43,45 ,0,0,0}, + {31580,31582,31583 ,44,46,47 ,0,0,0}, {31583,31581,31580 ,47,45,44 ,0,0,0}, + {31584,31582,31585 ,48,46,49 ,0,0,0}, {31582,31584,31583 ,46,48,47 ,0,0,0}, + {31586,31587,31585 ,50,51,49 ,0,0,0}, {31584,31585,31587 ,48,49,51 ,0,0,0}, + {31586,31588,31589 ,50,52,53 ,0,0,0}, {31589,31587,31586 ,53,51,50 ,0,0,0}, + {31590,31588,31591 ,54,52,54 ,0,0,0}, {31588,31590,31589 ,52,54,53 ,0,0,0}, + {31592,31593,31594 ,22,55,24 ,0,0,0}, {31595,31596,31597 ,56,57,58 ,0,0,0}, + {31598,31592,31594 ,59,22,24 ,0,0,0}, {31597,31596,31598 ,58,57,59 ,0,0,0}, + {31596,31595,31599 ,57,56,60 ,0,0,0}, {31594,31597,31598 ,24,58,59 ,0,0,0}, + {31600,31601,31602 ,61,62,63 ,0,0,0}, {31601,31603,31602 ,62,64,63 ,0,0,0}, + {31599,31604,31600 ,60,65,61 ,0,0,0}, {31601,31600,31604 ,62,61,65 ,0,0,0}, + {31605,31606,31607 ,66,67,68 ,0,0,0}, {31608,31609,31603 ,69,70,64 ,0,0,0}, + {31606,31609,31608 ,67,70,69 ,0,0,0}, {31606,31608,31607 ,67,69,68 ,0,0,0}, + {31607,31610,31605 ,68,66,66 ,0,0,0}, {31602,31603,31609 ,63,64,70 ,0,0,0}, + {31599,31595,31604 ,60,56,65 ,0,0,0}, {31592,31611,31593 ,22,71,55 ,0,0,0}, + {31612,31611,31613 ,72,71,43 ,0,0,0}, {31611,31612,31593 ,71,72,55 ,0,0,0}, + {31614,31615,31613 ,73,74,43 ,0,0,0}, {31612,31613,31615 ,72,43,74 ,0,0,0}, + {31614,31616,31617 ,73,46,75 ,0,0,0}, {31617,31615,31614 ,75,74,73 ,0,0,0}, + {31618,31616,31619 ,76,46,77 ,0,0,0}, {31616,31618,31617 ,46,76,75 ,0,0,0}, + {31620,31621,31619 ,50,78,77 ,0,0,0}, {31618,31619,31621 ,76,77,78 ,0,0,0}, + {31620,31622,31623 ,50,79,80 ,0,0,0}, {31623,31621,31620 ,80,78,50 ,0,0,0}, + {31624,31622,31625 ,81,79,82 ,0,0,0}, {31622,31624,31623 ,79,81,80 ,0,0,0}, + {31626,31627,31628 ,83,84,85 ,0,0,0}, {31629,31630,31631 ,86,87,88 ,0,0,0}, + {31632,31626,31628 ,89,83,85 ,0,0,0}, {31631,31630,31632 ,88,87,89 ,0,0,0}, + {31630,31629,31633 ,87,86,90 ,0,0,0}, {31628,31631,31632 ,85,88,89 ,0,0,0}, + {31634,31635,31636 ,91,92,93 ,0,0,0}, {31635,31637,31636 ,92,94,93 ,0,0,0}, + {31633,31638,31634 ,90,95,91 ,0,0,0}, {31635,31634,31638 ,92,91,95 ,0,0,0}, + {30497,31639,31640 ,96,97,98 ,0,0,0}, {31641,31642,31637 ,99,100,94 ,0,0,0}, + {31639,31642,31641 ,97,100,99 ,0,0,0}, {31639,31641,31640 ,97,99,98 ,0,0,0}, + {31640,31643,30497 ,98,101,96 ,0,0,0}, {31636,31637,31642 ,93,94,100 ,0,0,0}, + {31633,31629,31638 ,90,86,95 ,0,0,0}, {31626,31644,31627 ,83,102,84 ,0,0,0}, + {31645,31644,31646 ,103,102,104 ,0,0,0}, {31644,31645,31627 ,102,103,84 ,0,0,0}, + {31647,31648,31646 ,105,106,104 ,0,0,0}, {31645,31646,31648 ,103,104,106 ,0,0,0}, + {31647,31649,31650 ,105,107,108 ,0,0,0}, {31650,31648,31647 ,108,106,105 ,0,0,0}, + {31651,31649,31652 ,109,107,110 ,0,0,0}, {31649,31651,31650 ,107,109,108 ,0,0,0}, + {31653,31654,31652 ,111,112,110 ,0,0,0}, {31651,31652,31654 ,109,110,112 ,0,0,0}, + {31653,31655,31656 ,111,113,114 ,0,0,0}, {31656,31654,31653 ,114,112,111 ,0,0,0}, + {31657,31655,30481 ,54,113,54 ,0,0,0}, {31655,31657,31656 ,113,54,114 ,0,0,0}, + {31658,31659,31660 ,83,115,85 ,0,0,0}, {31661,31662,31663 ,116,117,118 ,0,0,0}, + {31664,31658,31660 ,119,83,85 ,0,0,0}, {31663,31662,31664 ,118,117,119 ,0,0,0}, + {31662,31661,31665 ,117,116,120 ,0,0,0}, {31660,31663,31664 ,85,118,119 ,0,0,0}, + {31666,31667,31668 ,121,122,123 ,0,0,0}, {31667,31669,31668 ,122,124,123 ,0,0,0}, + {31665,31670,31666 ,120,125,121 ,0,0,0}, {31667,31666,31670 ,122,121,125 ,0,0,0}, + {31323,31671,31672 ,126,127,128 ,0,0,0}, {31673,31674,31669 ,129,130,124 ,0,0,0}, + {31671,31674,31673 ,127,130,129 ,0,0,0}, {31671,31673,31672 ,127,129,128 ,0,0,0}, + {31672,31675,31323 ,128,35,126 ,0,0,0}, {31668,31669,31674 ,123,124,130 ,0,0,0}, + {31665,31661,31670 ,120,116,125 ,0,0,0}, {31658,31676,31659 ,83,131,115 ,0,0,0}, + {31677,31676,31678 ,132,131,133 ,0,0,0}, {31676,31677,31659 ,131,132,115 ,0,0,0}, + {31679,31680,31678 ,134,74,133 ,0,0,0}, {31677,31678,31680 ,132,133,74 ,0,0,0}, + {31679,31681,31682 ,134,135,108 ,0,0,0}, {31682,31680,31679 ,108,74,134 ,0,0,0}, + {31683,31681,31684 ,136,135,137 ,0,0,0}, {31681,31683,31682 ,135,136,108 ,0,0,0}, + {31685,31686,31684 ,138,139,137 ,0,0,0}, {31683,31684,31686 ,136,137,139 ,0,0,0}, + {31685,31687,31688 ,138,79,80 ,0,0,0}, {31688,31686,31685 ,80,139,138 ,0,0,0}, + {31689,31687,31339 ,140,79,140 ,0,0,0}, {31687,31689,31688 ,79,140,80 ,0,0,0}, + {31690,31691,31692 ,141,142,143 ,0,0,0}, {31693,31694,31695 ,144,145,146 ,0,0,0}, + {31696,31690,31692 ,147,141,143 ,0,0,0}, {31695,31694,31696 ,146,145,147 ,0,0,0}, + {31694,31693,31697 ,145,144,148 ,0,0,0}, {31692,31695,31696 ,143,146,147 ,0,0,0}, + {31698,31699,31700 ,149,150,151 ,0,0,0}, {31699,31701,31700 ,150,152,151 ,0,0,0}, + {31697,31702,31698 ,148,153,149 ,0,0,0}, {31699,31698,31702 ,150,149,153 ,0,0,0}, + {31703,31704,31705 ,126,154,155 ,0,0,0}, {31706,31707,31701 ,156,157,152 ,0,0,0}, + {31704,31707,31706 ,154,157,156 ,0,0,0}, {31704,31706,31705 ,154,156,155 ,0,0,0}, + {31705,31708,31703 ,155,35,126 ,0,0,0}, {31700,31701,31707 ,151,152,157 ,0,0,0}, + {31697,31693,31702 ,148,144,153 ,0,0,0}, {31690,31709,31691 ,141,158,142 ,0,0,0}, + {31710,31709,31711 ,159,158,160 ,0,0,0}, {31709,31710,31691 ,158,159,142 ,0,0,0}, + {31712,31713,31711 ,161,162,160 ,0,0,0}, {31710,31711,31713 ,159,160,162 ,0,0,0}, + {31712,31714,31715 ,161,163,164 ,0,0,0}, {31715,31713,31712 ,164,162,161 ,0,0,0}, + {31716,31714,31717 ,165,163,166 ,0,0,0}, {31714,31716,31715 ,163,165,164 ,0,0,0}, + {31718,31719,31717 ,167,168,166 ,0,0,0}, {31716,31717,31719 ,165,166,168 ,0,0,0}, + {31718,31720,31721 ,167,169,170 ,0,0,0}, {31721,31719,31718 ,170,168,167 ,0,0,0}, + {31722,31720,31723 ,140,169,140 ,0,0,0}, {31720,31722,31721 ,169,140,170 ,0,0,0}, + {31724,31725,31726 ,171,172,173 ,0,0,0}, {31727,31728,31729 ,174,175,176 ,0,0,0}, + {31730,31724,31726 ,177,171,173 ,0,0,0}, {31729,31728,31730 ,176,175,177 ,0,0,0}, + {31728,31727,31731 ,175,174,178 ,0,0,0}, {31726,31729,31730 ,173,176,177 ,0,0,0}, + {31732,31733,31734 ,179,180,181 ,0,0,0}, {31733,31735,31734 ,180,182,181 ,0,0,0}, + {31731,31736,31732 ,178,183,179 ,0,0,0}, {31733,31732,31736 ,180,179,183 ,0,0,0}, + {31043,31737,31738 ,35,184,185 ,0,0,0}, {31739,31740,31735 ,186,187,182 ,0,0,0}, + {31737,31740,31739 ,184,187,186 ,0,0,0}, {31737,31739,31738 ,184,186,185 ,0,0,0}, + {31738,31741,31043 ,185,40,35 ,0,0,0}, {31734,31735,31740 ,181,182,187 ,0,0,0}, + {31731,31727,31736 ,178,174,183 ,0,0,0}, {31724,31742,31725 ,171,188,172 ,0,0,0}, + {31743,31742,31744 ,189,188,104 ,0,0,0}, {31742,31743,31725 ,188,189,172 ,0,0,0}, + {31745,31746,31744 ,190,45,104 ,0,0,0}, {31743,31744,31746 ,189,104,45 ,0,0,0}, + {31745,31747,31748 ,190,191,192 ,0,0,0}, {31748,31746,31745 ,192,45,190 ,0,0,0}, + {31749,31747,31750 ,193,191,194 ,0,0,0}, {31747,31749,31748 ,191,193,192 ,0,0,0}, + {31751,31752,31750 ,111,195,194 ,0,0,0}, {31749,31750,31752 ,193,194,195 ,0,0,0}, + {31751,31753,31754 ,111,52,53 ,0,0,0}, {31754,31752,31751 ,53,195,111 ,0,0,0}, + {31755,31753,31059 ,54,52,54 ,0,0,0}, {31753,31755,31754 ,52,54,53 ,0,0,0}, + {31756,31757,31758 ,196,197,197 ,0,0,0}, {31759,31760,31761 ,198,196,198 ,0,0,0}, + {31760,31756,31758 ,196,196,197 ,0,0,0}, {31759,31761,31762 ,198,198,199 ,0,0,0}, + {31763,31764,31765 ,200,82,200 ,0,0,0}, {31762,31761,31766 ,199,198,199 ,0,0,0}, + {31766,31765,31762 ,199,200,199 ,0,0,0}, {31765,31766,31763 ,200,199,200 ,0,0,0}, + {31764,31763,31767 ,82,200,201 ,0,0,0}, {31760,31759,31756 ,196,198,196 ,0,0,0}, + {31768,31758,31757 ,202,197,197 ,0,0,0}, {31769,31768,31770 ,203,202,202 ,0,0,0}, + {31757,31770,31768 ,197,202,202 ,0,0,0}, {31771,31772,31769 ,203,204,203 ,0,0,0}, + {31769,31770,31771 ,203,202,203 ,0,0,0}, {31772,31773,31774 ,204,204,205 ,0,0,0}, + {31773,31772,31771 ,204,204,203 ,0,0,0}, {31773,31775,31774 ,204,205,205 ,0,0,0}, + {31776,31777,31778 ,206,207,208 ,0,0,0}, {31779,31776,31780 ,209,206,210 ,0,0,0}, + {31776,31779,31777 ,206,209,207 ,0,0,0}, {31781,31782,31780 ,211,212,210 ,0,0,0}, + {31779,31780,31782 ,209,210,212 ,0,0,0}, {31781,31783,31784 ,211,213,214 ,0,0,0}, + {31784,31782,31781 ,214,212,211 ,0,0,0}, {31785,31783,31786 ,215,213,216 ,0,0,0}, + {31783,31785,31784 ,213,215,214 ,0,0,0}, {31787,31788,31786 ,217,218,216 ,0,0,0}, + {31785,31786,31788 ,215,216,218 ,0,0,0}, {31787,31789,31790 ,217,219,220 ,0,0,0}, + {31790,31788,31787 ,220,218,217 ,0,0,0}, {31791,31790,31789 ,221,220,219 ,0,0,0}, + {31791,31792,31790 ,221,221,220 ,0,0,0}, {31776,31778,31793 ,206,208,222 ,0,0,0}, + {31794,31795,31778 ,223,224,208 ,0,0,0}, {31793,31778,31795 ,222,208,224 ,0,0,0}, + {31794,31796,31797 ,223,225,226 ,0,0,0}, {31797,31795,31794 ,226,224,223 ,0,0,0}, + {31798,31796,31799 ,227,225,228 ,0,0,0}, {31796,31798,31797 ,225,227,226 ,0,0,0}, + {31800,31801,31799 ,229,230,228 ,0,0,0}, {31798,31799,31801 ,227,228,230 ,0,0,0}, + {31800,31802,31803 ,229,231,232 ,0,0,0}, {31803,31801,31800 ,232,230,229 ,0,0,0}, + {31804,31802,31805 ,233,231,234 ,0,0,0}, {31802,31804,31803 ,231,233,232 ,0,0,0}, + {31805,31806,31804 ,234,235,233 ,0,0,0}, {31804,31806,31807 ,233,235,235 ,0,0,0}, + {31808,31809,31810 ,236,237,238 ,0,0,0}, {31811,31812,31808 ,239,240,236 ,0,0,0}, + {31808,31810,31811 ,236,238,239 ,0,0,0}, {31812,31813,31814 ,240,241,242 ,0,0,0}, + {31813,31812,31811 ,241,240,239 ,0,0,0}, {31815,31814,31816 ,243,242,244 ,0,0,0}, + {31813,31816,31814 ,241,244,242 ,0,0,0}, {31817,31818,31815 ,245,246,243 ,0,0,0}, + {31815,31816,31817 ,243,244,245 ,0,0,0}, {31819,31818,31817 ,247,246,245 ,0,0,0}, + {31819,31820,31818 ,247,126,246 ,0,0,0}, {31810,31809,31821 ,238,237,248 ,0,0,0}, + {31821,31822,31823 ,248,249,250 ,0,0,0}, {31822,31821,31809 ,249,248,237 ,0,0,0}, + {31824,31823,31825 ,251,250,252 ,0,0,0}, {31822,31825,31823 ,249,252,250 ,0,0,0}, + {31826,31827,31824 ,253,254,251 ,0,0,0}, {31824,31825,31826 ,251,252,253 ,0,0,0}, + {31827,31828,31829 ,254,255,256 ,0,0,0}, {31828,31827,31826 ,255,254,253 ,0,0,0}, + {31828,31830,31829 ,255,257,256 ,0,0,0}, {31829,31830,31831 ,256,257,257 ,0,0,0}, + {31832,31833,31834 ,258,259,260 ,0,0,0}, {31835,31832,31836 ,261,258,262 ,0,0,0}, + {31832,31835,31833 ,258,261,259 ,0,0,0}, {31837,31838,31836 ,263,264,262 ,0,0,0}, + {31835,31836,31838 ,261,262,264 ,0,0,0}, {31837,31839,31840 ,263,265,266 ,0,0,0}, + {31840,31838,31837 ,266,264,263 ,0,0,0}, {31841,31839,31842 ,267,265,268 ,0,0,0}, + {31839,31841,31840 ,265,267,266 ,0,0,0}, {31843,31844,31842 ,269,270,268 ,0,0,0}, + {31841,31842,31844 ,267,268,270 ,0,0,0}, {31843,31845,31846 ,269,271,272 ,0,0,0}, + {31846,31844,31843 ,272,270,269 ,0,0,0}, {31847,31846,31845 ,273,272,271 ,0,0,0}, + {31847,31848,31846 ,273,273,272 ,0,0,0}, {31832,31834,31849 ,258,260,274 ,0,0,0}, + {31850,31851,31834 ,275,276,260 ,0,0,0}, {31849,31834,31851 ,274,260,276 ,0,0,0}, + {31850,31852,31853 ,275,277,278 ,0,0,0}, {31853,31851,31850 ,278,276,275 ,0,0,0}, + {31854,31852,31855 ,279,277,280 ,0,0,0}, {31852,31854,31853 ,277,279,278 ,0,0,0}, + {31856,31857,31855 ,281,282,280 ,0,0,0}, {31854,31855,31857 ,279,280,282 ,0,0,0}, + {31856,31858,31859 ,281,283,284 ,0,0,0}, {31859,31857,31856 ,284,282,281 ,0,0,0}, + {31860,31858,31861 ,285,283,286 ,0,0,0}, {31858,31860,31859 ,283,285,284 ,0,0,0}, + {31861,31862,31860 ,286,257,285 ,0,0,0}, {31860,31862,31863 ,285,257,257 ,0,0,0}, + {31864,31865,31866 ,287,288,288 ,0,0,0}, {31867,31868,31869 ,289,287,289 ,0,0,0}, + {31868,31864,31866 ,287,287,288 ,0,0,0}, {31867,31869,31870 ,289,289,290 ,0,0,0}, + {31871,31872,31873 ,291,82,291 ,0,0,0}, {31870,31869,31874 ,290,289,290 ,0,0,0}, + {31874,31873,31870 ,290,291,290 ,0,0,0}, {31873,31874,31871 ,291,290,291 ,0,0,0}, + {31872,31871,31875 ,82,291,292 ,0,0,0}, {31868,31867,31864 ,287,289,287 ,0,0,0}, + {31876,31866,31865 ,293,288,288 ,0,0,0}, {31877,31876,31878 ,203,293,293 ,0,0,0}, + {31865,31878,31876 ,288,293,293 ,0,0,0}, {31879,31880,31877 ,203,294,203 ,0,0,0}, + {31877,31878,31879 ,203,293,203 ,0,0,0}, {31880,31881,31882 ,294,294,205 ,0,0,0}, + {31881,31880,31879 ,294,294,203 ,0,0,0}, {31881,31883,31882 ,294,205,205 ,0,0,0}, + {31884,31885,31886 ,295,296,295 ,0,0,0}, {31887,31885,31888 ,296,296,297 ,0,0,0}, + {31885,31887,31886 ,296,296,295 ,0,0,0}, {31889,31890,31888 ,298,297,297 ,0,0,0}, + {31887,31888,31890 ,296,297,297 ,0,0,0}, {31889,31891,31892 ,298,299,298 ,0,0,0}, + {31892,31890,31889 ,298,297,298 ,0,0,0}, {31891,31893,31892 ,299,300,298 ,0,0,0}, + {31894,31884,31886 ,301,295,295 ,0,0,0}, {31895,31896,31894 ,302,301,301 ,0,0,0}, + {31884,31894,31896 ,295,301,301 ,0,0,0}, {31895,31897,31898 ,302,303,302 ,0,0,0}, + {31898,31896,31895 ,302,301,302 ,0,0,0}, {31899,31897,31900 ,303,303,304 ,0,0,0}, + {31897,31899,31898 ,303,303,302 ,0,0,0}, {31899,31900,31901 ,303,304,304 ,0,0,0}, + {31902,31903,31904 ,305,306,305 ,0,0,0}, {31905,31903,31906 ,306,306,307 ,0,0,0}, + {31903,31905,31904 ,306,306,305 ,0,0,0}, {31907,31908,31906 ,308,307,307 ,0,0,0}, + {31905,31906,31908 ,306,307,307 ,0,0,0}, {31907,31909,31910 ,308,309,308 ,0,0,0}, + {31910,31908,31907 ,308,307,308 ,0,0,0}, {31909,31911,31910 ,309,310,308 ,0,0,0}, + {31912,31902,31904 ,311,305,305 ,0,0,0}, {31913,31914,31912 ,312,311,311 ,0,0,0}, + {31902,31912,31914 ,305,311,311 ,0,0,0}, {31913,31915,31916 ,312,313,312 ,0,0,0}, + {31916,31914,31913 ,312,311,312 ,0,0,0}, {31917,31915,31918 ,313,313,314 ,0,0,0}, + {31915,31917,31916 ,313,313,312 ,0,0,0}, {31917,31918,31919 ,313,314,314 ,0,0,0}, + {31920,31911,31909 ,315,309,309 ,0,0,0}, {31921,31922,31923 ,316,317,317 ,0,0,0}, + {31924,31925,31926 ,318,318,315 ,0,0,0}, {31927,31928,31929 ,319,319,320 ,0,0,0}, + {31930,31931,31932 ,316,321,321 ,0,0,0}, {31933,31934,31929 ,322,320,320 ,0,0,0}, + {31927,31929,31934 ,319,320,320 ,0,0,0}, {31935,31934,31933 ,323,320,322 ,0,0,0}, + {31931,31928,31932 ,321,319,321 ,0,0,0}, {31932,31928,31927 ,321,319,319 ,0,0,0}, + {31930,31922,31921 ,316,317,316 ,0,0,0}, {31930,31921,31931 ,316,316,321 ,0,0,0}, + {31923,31925,31924 ,317,318,318 ,0,0,0}, {31922,31925,31923 ,317,318,317 ,0,0,0}, + {31920,31926,31911 ,315,315,309 ,0,0,0}, {31924,31926,31920 ,318,315,315 ,0,0,0}, + {31936,31937,31938 ,324,324,324 ,0,0,0}, {31936,31938,31939 ,324,324,324 ,0,0,0}, + {31940,31941,31942 ,325,326,325 ,0,0,0}, {31943,31944,31940 ,327,327,325 ,0,0,0}, + {31940,31942,31943 ,325,325,327 ,0,0,0}, {31944,31945,31946 ,327,328,329 ,0,0,0}, + {31945,31944,31943 ,328,327,327 ,0,0,0}, {31947,31946,31948 ,330,329,331 ,0,0,0}, + {31945,31948,31946 ,328,331,329 ,0,0,0}, {31949,31950,31947 ,332,332,330 ,0,0,0}, + {31947,31948,31949 ,330,331,332 ,0,0,0}, {31950,31951,31952 ,332,333,334 ,0,0,0}, + {31951,31950,31949 ,333,332,332 ,0,0,0}, {31953,31952,31954 ,335,334,335 ,0,0,0}, + {31951,31954,31952 ,333,335,334 ,0,0,0}, {31955,31956,31953 ,336,336,335 ,0,0,0}, + {31953,31954,31955 ,335,335,336 ,0,0,0}, {31942,31941,31957 ,325,326,337 ,0,0,0}, + {31958,31957,31959 ,338,337,339 ,0,0,0}, {31941,31959,31957 ,326,339,337 ,0,0,0}, + {31960,31961,31958 ,340,341,338 ,0,0,0}, {31958,31959,31960 ,338,339,340 ,0,0,0}, + {31961,31962,31963 ,341,342,343 ,0,0,0}, {31962,31961,31960 ,342,341,340 ,0,0,0}, + {31964,31963,31965 ,344,343,345 ,0,0,0}, {31962,31965,31963 ,342,345,343 ,0,0,0}, + {31966,31967,31964 ,346,347,344 ,0,0,0}, {31964,31965,31966 ,344,345,346 ,0,0,0}, + {31967,31968,31969 ,347,348,349 ,0,0,0}, {31968,31967,31966 ,348,347,346 ,0,0,0}, + {31968,31546,31969 ,348,16,349 ,0,0,0}, {31969,31546,31547 ,349,16,350 ,0,0,0}, + {31970,31893,31891 ,351,299,299 ,0,0,0}, {31971,31972,31973 ,352,353,353 ,0,0,0}, + {31974,31975,31976 ,354,354,351 ,0,0,0}, {31977,31978,31979 ,355,355,356 ,0,0,0}, + {31980,31981,31982 ,352,357,357 ,0,0,0}, {31983,31984,31979 ,358,356,356 ,0,0,0}, + {31977,31979,31984 ,355,356,356 ,0,0,0}, {31985,31984,31983 ,359,356,358 ,0,0,0}, + {31981,31978,31982 ,357,355,357 ,0,0,0}, {31982,31978,31977 ,357,355,355 ,0,0,0}, + {31980,31972,31971 ,352,353,352 ,0,0,0}, {31980,31971,31981 ,352,352,357 ,0,0,0}, + {31973,31975,31974 ,353,354,354 ,0,0,0}, {31972,31975,31973 ,353,354,353 ,0,0,0}, + {31970,31976,31893 ,351,351,299 ,0,0,0}, {31974,31976,31970 ,354,351,351 ,0,0,0}, + {31986,31987,31988 ,360,324,360 ,0,0,0}, {31987,31986,31989 ,324,360,324 ,0,0,0}, + {31990,31991,31992 ,361,362,361 ,0,0,0}, {31993,31994,31990 ,363,363,361 ,0,0,0}, + {31990,31992,31993 ,361,361,363 ,0,0,0}, {31994,31995,31996 ,363,364,365 ,0,0,0}, + {31995,31994,31993 ,364,363,363 ,0,0,0}, {31997,31996,31998 ,366,365,367 ,0,0,0}, + {31995,31998,31996 ,364,367,365 ,0,0,0}, {31999,32000,31997 ,368,369,366 ,0,0,0}, + {31997,31998,31999 ,366,367,368 ,0,0,0}, {32000,32001,32002 ,369,370,370 ,0,0,0}, + {32001,32000,31999 ,370,369,368 ,0,0,0}, {32003,32002,32004 ,371,370,371 ,0,0,0}, + {32001,32004,32002 ,370,371,370 ,0,0,0}, {32005,32006,32003 ,372,372,371 ,0,0,0}, + {32003,32004,32005 ,371,371,372 ,0,0,0}, {31992,31991,32007 ,361,362,373 ,0,0,0}, + {32008,32007,32009 ,374,373,375 ,0,0,0}, {31991,32009,32007 ,362,375,373 ,0,0,0}, + {32010,32011,32008 ,376,377,374 ,0,0,0}, {32008,32009,32010 ,374,375,376 ,0,0,0}, + {32011,32012,32013 ,377,378,379 ,0,0,0}, {32012,32011,32010 ,378,377,376 ,0,0,0}, + {32014,32013,32015 ,380,379,381 ,0,0,0}, {32012,32015,32013 ,378,381,379 ,0,0,0}, + {32016,32017,32014 ,382,383,380 ,0,0,0}, {32014,32015,32016 ,380,381,382 ,0,0,0}, + {32017,32018,32019 ,383,384,385 ,0,0,0}, {32018,32017,32016 ,384,383,382 ,0,0,0}, + {32018,31526,32019 ,384,4,385 ,0,0,0}, {32019,31526,31527 ,385,4,386 ,0,0,0}, + {31875,32020,32021 ,387,388,388 ,0,0,0}, {32022,32023,32024 ,389,389,390 ,0,0,0}, + {32025,32026,32027 ,390,391,391 ,0,0,0}, {32028,32029,32030 ,392,393,392 ,0,0,0}, + {32031,32032,32033 ,394,394,393 ,0,0,0}, {32034,32035,32030 ,395,395,392 ,0,0,0}, + {32028,32030,32035 ,392,392,395 ,0,0,0}, {32034,32036,32037 ,395,396,396 ,0,0,0}, + {32037,32035,32034 ,396,395,395 ,0,0,0}, {32028,32033,32029 ,392,393,393 ,0,0,0}, + {32027,32026,32020 ,391,391,388 ,0,0,0}, {32033,32032,32029 ,393,394,393 ,0,0,0}, + {32031,32022,32032 ,394,389,394 ,0,0,0}, {32023,32025,32024 ,389,390,390 ,0,0,0}, + {32031,32023,32022 ,394,389,389 ,0,0,0}, {32024,32025,32027 ,390,390,391 ,0,0,0}, + {31875,32021,31872 ,387,388,397 ,0,0,0}, {32020,32026,32021 ,388,391,388 ,0,0,0}, + {32038,32039,32040 ,398,399,400 ,0,0,0}, {32041,32040,32042 ,401,400,402 ,0,0,0}, + {32039,32042,32040 ,399,402,400 ,0,0,0}, {32042,32043,32044 ,402,403,404 ,0,0,0}, + {32044,32041,32042 ,404,401,402 ,0,0,0}, {32045,32043,32046 ,405,403,406 ,0,0,0}, + {32043,32045,32044 ,403,405,404 ,0,0,0}, {32047,32048,32046 ,407,408,406 ,0,0,0}, + {32045,32046,32048 ,405,406,408 ,0,0,0}, {32047,32049,32050 ,407,409,410 ,0,0,0}, + {32050,32048,32047 ,410,408,407 ,0,0,0}, {32051,32049,32052 ,411,409,412 ,0,0,0}, + {32049,32051,32050 ,409,411,410 ,0,0,0}, {32053,32051,32054 ,413,411,414 ,0,0,0}, + {32052,32054,32051 ,412,414,411 ,0,0,0}, {32055,32056,32053 ,415,416,413 ,0,0,0}, + {32053,32054,32055 ,413,414,415 ,0,0,0}, {32057,32055,32058 ,417,415,418 ,0,0,0}, + {32055,32057,32056 ,415,417,416 ,0,0,0}, {32059,32060,32058 ,419,420,418 ,0,0,0}, + {32057,32058,32060 ,417,418,420 ,0,0,0}, {32059,32061,32062 ,419,421,422 ,0,0,0}, + {32062,32060,32059 ,422,420,419 ,0,0,0}, {32063,32061,32064 ,423,421,424 ,0,0,0}, + {32061,32063,32062 ,421,423,422 ,0,0,0}, {32065,32066,32064 ,425,426,424 ,0,0,0}, + {32063,32064,32066 ,423,424,426 ,0,0,0}, {32067,32068,32066 ,427,427,426 ,0,0,0}, + {32066,32065,32067 ,426,425,427 ,0,0,0}, {32039,32038,32069 ,399,398,428 ,0,0,0}, + {32069,32070,32071 ,428,429,430 ,0,0,0}, {32070,32069,32038 ,429,428,398 ,0,0,0}, + {32072,32073,32070 ,431,432,429 ,0,0,0}, {32071,32070,32073 ,430,429,432 ,0,0,0}, + {32072,32074,32075 ,431,433,434 ,0,0,0}, {32075,32073,32072 ,434,432,431 ,0,0,0}, + {32076,32074,32077 ,435,433,436 ,0,0,0}, {32074,32076,32075 ,433,435,434 ,0,0,0}, + {32078,32079,32077 ,437,438,436 ,0,0,0}, {32076,32077,32079 ,435,436,438 ,0,0,0}, + {32078,32080,32081 ,437,439,440 ,0,0,0}, {32081,32079,32078 ,440,438,437 ,0,0,0}, + {32081,32082,32083 ,440,441,442 ,0,0,0}, {32082,32081,32080 ,441,440,439 ,0,0,0}, + {32084,32083,32085 ,443,442,444 ,0,0,0}, {32082,32085,32083 ,441,444,442 ,0,0,0}, + {32085,32086,32087 ,444,445,446 ,0,0,0}, {32087,32084,32085 ,446,443,444 ,0,0,0}, + {32088,32086,32089 ,447,445,448 ,0,0,0}, {32086,32088,32087 ,445,447,446 ,0,0,0}, + {32090,32091,32089 ,449,450,448 ,0,0,0}, {32088,32089,32091 ,447,448,450 ,0,0,0}, + {32090,32092,32093 ,449,451,452 ,0,0,0}, {32093,32091,32090 ,452,450,449 ,0,0,0}, + {32094,32092,32095 ,453,451,454 ,0,0,0}, {32092,32094,32093 ,451,453,452 ,0,0,0}, + {32095,32096,32094 ,454,455,453 ,0,0,0}, {32094,32096,32097 ,453,455,456 ,0,0,0}, + {32098,32099,32100 ,457,458,459 ,0,0,0}, {32098,32100,32101 ,457,459,460 ,0,0,0}, + {32102,31848,31847 ,461,273,273 ,0,0,0}, {32103,32104,32105 ,462,463,464 ,0,0,0}, + {32106,32107,32108 ,465,466,467 ,0,0,0}, {32109,32110,32111 ,468,469,470 ,0,0,0}, + {32112,32113,32114 ,471,472,473 ,0,0,0}, {32115,32116,32117 ,474,475,476 ,0,0,0}, + {32118,32119,32120 ,477,478,479 ,0,0,0}, {32121,32122,32123 ,480,481,482 ,0,0,0}, + {32121,32124,32116 ,480,483,475 ,0,0,0}, {32125,32122,32126 ,484,481,485 ,0,0,0}, + {32122,32125,32123 ,481,484,482 ,0,0,0}, {32127,32128,32126 ,486,487,485 ,0,0,0}, + {32125,32126,32128 ,484,485,487 ,0,0,0}, {32129,32130,32128 ,488,488,487 ,0,0,0}, + {32128,32127,32129 ,487,486,488 ,0,0,0}, {32117,32116,32124 ,476,475,483 ,0,0,0}, + {32121,32123,32124 ,480,482,483 ,0,0,0}, {32118,32115,32119 ,477,474,478 ,0,0,0}, + {32115,32117,32119 ,474,476,478 ,0,0,0}, {32111,32118,32109 ,470,477,468 ,0,0,0}, + {32118,32120,32109 ,477,479,468 ,0,0,0}, {32114,32113,32110 ,473,472,469 ,0,0,0}, + {32114,32110,32109 ,473,469,468 ,0,0,0}, {32112,32104,32103 ,471,463,462 ,0,0,0}, + {32112,32103,32113 ,471,462,472 ,0,0,0}, {32105,32107,32106 ,464,466,465 ,0,0,0}, + {32104,32107,32105 ,463,466,464 ,0,0,0}, {32102,32108,32131 ,461,467,489 ,0,0,0}, + {32106,32108,32102 ,465,467,461 ,0,0,0}, {31848,32102,32131 ,273,461,489 ,0,0,0}, + {32132,32133,32134 ,490,491,492 ,0,0,0}, {32135,32136,32133 ,493,494,491 ,0,0,0}, + {32137,32138,32139 ,495,496,497 ,0,0,0}, {32137,32132,32134 ,495,490,492 ,0,0,0}, + {32140,32141,32142 ,498,499,500 ,0,0,0}, {32139,32132,32137 ,497,490,495 ,0,0,0}, + {32138,32142,32141 ,496,500,499 ,0,0,0}, {32143,32140,32142 ,501,498,500 ,0,0,0}, + {32139,32138,32141 ,497,496,499 ,0,0,0}, {32144,32145,32146 ,502,503,504 ,0,0,0}, + {32147,32144,32146 ,505,502,504 ,0,0,0}, {32148,32143,32145 ,506,501,503 ,0,0,0}, + {32145,32144,32148 ,503,502,506 ,0,0,0}, {32146,32149,32147 ,504,507,505 ,0,0,0}, + {32143,32148,32140 ,501,506,498 ,0,0,0}, {32147,32149,32150 ,505,507,508 ,0,0,0}, + {32134,32133,32136 ,492,491,494 ,0,0,0}, {32151,32150,32149 ,508,508,507 ,0,0,0}, + {32135,32152,32153 ,493,509,510 ,0,0,0}, {32153,32136,32135 ,510,494,493 ,0,0,0}, + {32154,32152,32155 ,511,509,512 ,0,0,0}, {32152,32154,32153 ,509,511,510 ,0,0,0}, + {32156,32157,32155 ,513,514,512 ,0,0,0}, {32154,32155,32157 ,511,512,514 ,0,0,0}, + {32156,32158,32159 ,513,515,516 ,0,0,0}, {32159,32157,32156 ,516,514,513 ,0,0,0}, + {32160,32158,32161 ,517,515,518 ,0,0,0}, {32158,32160,32159 ,515,517,516 ,0,0,0}, + {32162,32163,32161 ,519,520,518 ,0,0,0}, {32160,32161,32163 ,517,518,520 ,0,0,0}, + {32162,32164,32165 ,519,521,522 ,0,0,0}, {32165,32163,32162 ,522,520,519 ,0,0,0}, + {32166,32164,32167 ,523,521,524 ,0,0,0}, {32164,32166,32165 ,521,523,522 ,0,0,0}, + {32166,32167,32168 ,523,524,525 ,0,0,0}, {32168,32167,32169 ,525,524,525 ,0,0,0}, + {32170,31820,31819 ,526,527,247 ,0,0,0}, {32171,32172,32173 ,528,529,530 ,0,0,0}, + {32174,32175,32176 ,531,532,533 ,0,0,0}, {32177,32178,32179 ,534,535,536 ,0,0,0}, + {32180,32181,32182 ,537,538,539 ,0,0,0}, {32183,32184,32185 ,540,541,542 ,0,0,0}, + {32186,32183,32179 ,543,540,536 ,0,0,0}, {32187,32185,32188 ,544,542,545 ,0,0,0}, + {32184,32188,32185 ,541,545,542 ,0,0,0}, {32189,32190,32187 ,546,546,544 ,0,0,0}, + {32187,32188,32189 ,544,545,546 ,0,0,0}, {32178,32186,32179 ,535,543,536 ,0,0,0}, + {32186,32184,32183 ,543,541,540 ,0,0,0}, {32182,32181,32177 ,539,538,534 ,0,0,0}, + {32181,32178,32177 ,538,535,534 ,0,0,0}, {32171,32173,32180 ,528,530,537 ,0,0,0}, + {32171,32180,32182 ,528,537,539 ,0,0,0}, {32172,32175,32174 ,529,532,531 ,0,0,0}, + {32172,32174,32173 ,529,531,530 ,0,0,0}, {32176,32191,32170 ,533,547,526 ,0,0,0}, + {32175,32191,32176 ,532,547,533 ,0,0,0}, {31820,32170,32191 ,527,526,547 ,0,0,0}, + {32192,32193,32194 ,548,549,550 ,0,0,0}, {32195,32196,32193 ,551,552,549 ,0,0,0}, + {32197,32198,32199 ,553,554,555 ,0,0,0}, {32197,32192,32194 ,553,548,550 ,0,0,0}, + {32200,32201,32202 ,556,557,558 ,0,0,0}, {32199,32192,32197 ,555,548,553 ,0,0,0}, + {32198,32202,32201 ,554,558,557 ,0,0,0}, {32203,32200,32202 ,559,556,558 ,0,0,0}, + {32199,32198,32201 ,555,554,557 ,0,0,0}, {32204,32205,32206 ,560,561,562 ,0,0,0}, + {32207,32204,32206 ,563,560,562 ,0,0,0}, {32208,32203,32205 ,564,559,561 ,0,0,0}, + {32205,32204,32208 ,561,560,564 ,0,0,0}, {32206,32209,32207 ,562,565,563 ,0,0,0}, + {32203,32208,32200 ,559,564,556 ,0,0,0}, {32207,32209,32210 ,563,565,508 ,0,0,0}, + {32194,32193,32196 ,550,549,552 ,0,0,0}, {32211,32210,32209 ,508,508,565 ,0,0,0}, + {32195,32212,32213 ,551,566,567 ,0,0,0}, {32213,32196,32195 ,567,552,551 ,0,0,0}, + {32214,32212,32215 ,568,566,569 ,0,0,0}, {32212,32214,32213 ,566,568,567 ,0,0,0}, + {32216,32217,32215 ,570,571,569 ,0,0,0}, {32214,32215,32217 ,568,569,571 ,0,0,0}, + {32216,32218,32219 ,570,572,573 ,0,0,0}, {32219,32217,32216 ,573,571,570 ,0,0,0}, + {32220,32218,32221 ,574,572,575 ,0,0,0}, {32218,32220,32219 ,572,574,573 ,0,0,0}, + {32222,32223,32221 ,576,577,575 ,0,0,0}, {32220,32221,32223 ,574,575,577 ,0,0,0}, + {32222,32224,32225 ,576,578,579 ,0,0,0}, {32225,32223,32222 ,579,577,576 ,0,0,0}, + {32226,32224,32227 ,580,578,581 ,0,0,0}, {32224,32226,32225 ,578,580,579 ,0,0,0}, + {32226,32227,32228 ,580,581,525 ,0,0,0}, {32228,32227,32229 ,525,581,525 ,0,0,0}, + {32230,31792,31791 ,582,221,221 ,0,0,0}, {32231,32232,32233 ,583,584,585 ,0,0,0}, + {32234,32235,32236 ,586,587,588 ,0,0,0}, {32237,32238,32239 ,589,590,591 ,0,0,0}, + {32240,32241,32242 ,592,593,594 ,0,0,0}, {32243,32244,32245 ,595,596,597 ,0,0,0}, + {32246,32247,32248 ,598,599,600 ,0,0,0}, {32249,32250,32251 ,601,602,603 ,0,0,0}, + {32249,32252,32244 ,601,604,596 ,0,0,0}, {32253,32250,32254 ,605,602,606 ,0,0,0}, + {32250,32253,32251 ,602,605,603 ,0,0,0}, {32255,32256,32254 ,607,608,606 ,0,0,0}, + {32253,32254,32256 ,605,606,608 ,0,0,0}, {32257,32258,32256 ,546,546,608 ,0,0,0}, + {32256,32255,32257 ,608,607,546 ,0,0,0}, {32245,32244,32252 ,597,596,604 ,0,0,0}, + {32249,32251,32252 ,601,603,604 ,0,0,0}, {32246,32243,32247 ,598,595,599 ,0,0,0}, + {32243,32245,32247 ,595,597,599 ,0,0,0}, {32239,32246,32237 ,591,598,589 ,0,0,0}, + {32246,32248,32237 ,598,600,589 ,0,0,0}, {32242,32241,32238 ,594,593,590 ,0,0,0}, + {32242,32238,32237 ,594,590,589 ,0,0,0}, {32240,32232,32231 ,592,584,583 ,0,0,0}, + {32240,32231,32241 ,592,583,593 ,0,0,0}, {32233,32235,32234 ,585,587,586 ,0,0,0}, + {32232,32235,32233 ,584,587,585 ,0,0,0}, {32230,32236,32259 ,582,588,609 ,0,0,0}, + {32234,32236,32230 ,586,588,582 ,0,0,0}, {31792,32230,32259 ,221,582,609 ,0,0,0}, + {32260,32261,32262 ,610,611,610 ,0,0,0}, {32261,32260,32263 ,611,610,611 ,0,0,0}, + {32264,32265,32266 ,612,613,614 ,0,0,0}, {32267,32266,32268 ,615,614,616 ,0,0,0}, + {32265,32268,32266 ,613,616,614 ,0,0,0}, {32268,32269,32270 ,616,617,618 ,0,0,0}, + {32270,32267,32268 ,618,615,616 ,0,0,0}, {32271,32269,32272 ,619,617,620 ,0,0,0}, + {32269,32271,32270 ,617,619,618 ,0,0,0}, {32273,32274,32272 ,621,622,620 ,0,0,0}, + {32271,32272,32274 ,619,620,622 ,0,0,0}, {32273,32275,32276 ,621,623,624 ,0,0,0}, + {32276,32274,32273 ,624,622,621 ,0,0,0}, {32277,32275,32278 ,625,623,626 ,0,0,0}, + {32275,32277,32276 ,623,625,624 ,0,0,0}, {32279,32277,32280 ,627,625,628 ,0,0,0}, + {32278,32280,32277 ,626,628,625 ,0,0,0}, {32281,32282,32279 ,629,630,627 ,0,0,0}, + {32279,32280,32281 ,627,628,629 ,0,0,0}, {32283,32281,32284 ,631,629,632 ,0,0,0}, + {32281,32283,32282 ,629,631,630 ,0,0,0}, {32285,32286,32284 ,633,634,632 ,0,0,0}, + {32283,32284,32286 ,631,632,634 ,0,0,0}, {32285,32287,32288 ,633,635,636 ,0,0,0}, + {32288,32286,32285 ,636,634,633 ,0,0,0}, {32289,32287,32290 ,637,635,638 ,0,0,0}, + {32287,32289,32288 ,635,637,636 ,0,0,0}, {32291,32292,32290 ,639,640,638 ,0,0,0}, + {32289,32290,32292 ,637,638,640 ,0,0,0}, {32293,32294,32292 ,641,641,640 ,0,0,0}, + {32292,32291,32293 ,640,639,641 ,0,0,0}, {32265,32264,32295 ,613,612,642 ,0,0,0}, + {32295,32296,32297 ,642,643,644 ,0,0,0}, {32296,32295,32264 ,643,642,612 ,0,0,0}, + {32298,32299,32296 ,645,646,643 ,0,0,0}, {32297,32296,32299 ,644,643,646 ,0,0,0}, + {32298,32300,32301 ,645,647,648 ,0,0,0}, {32301,32299,32298 ,648,646,645 ,0,0,0}, + {32302,32300,32303 ,649,647,650 ,0,0,0}, {32300,32302,32301 ,647,649,648 ,0,0,0}, + {32304,32305,32303 ,651,652,650 ,0,0,0}, {32302,32303,32305 ,649,650,652 ,0,0,0}, + {32304,32306,32307 ,651,653,654 ,0,0,0}, {32307,32305,32304 ,654,652,651 ,0,0,0}, + {32307,32308,32309 ,654,655,656 ,0,0,0}, {32308,32307,32306 ,655,654,653 ,0,0,0}, + {32310,32309,32311 ,657,656,658 ,0,0,0}, {32308,32311,32309 ,655,658,656 ,0,0,0}, + {32311,32312,32313 ,658,659,660 ,0,0,0}, {32313,32310,32311 ,660,657,658 ,0,0,0}, + {32314,32312,32315 ,661,659,662 ,0,0,0}, {32312,32314,32313 ,659,661,660 ,0,0,0}, + {32316,32317,32315 ,663,664,662 ,0,0,0}, {32314,32315,32317 ,661,662,664 ,0,0,0}, + {32316,32318,32319 ,663,665,666 ,0,0,0}, {32319,32317,32316 ,666,664,663 ,0,0,0}, + {32320,32318,32321 ,667,665,668 ,0,0,0}, {32318,32320,32319 ,665,667,666 ,0,0,0}, + {32321,32322,32320 ,668,669,667 ,0,0,0}, {32320,32322,32323 ,667,669,670 ,0,0,0}, + {31767,32324,32325 ,671,672,672 ,0,0,0}, {32326,32327,32328 ,673,674,675 ,0,0,0}, + {32329,32330,32331 ,675,676,676 ,0,0,0}, {32332,32333,32334 ,677,678,677 ,0,0,0}, + {32335,32336,32337 ,679,679,678 ,0,0,0}, {32338,32339,32334 ,680,680,677 ,0,0,0}, + {32332,32334,32339 ,677,677,680 ,0,0,0}, {32338,32340,32341 ,680,396,396 ,0,0,0}, + {32341,32339,32338 ,396,680,680 ,0,0,0}, {32332,32337,32333 ,677,678,678 ,0,0,0}, + {32331,32330,32324 ,676,676,672 ,0,0,0}, {32337,32336,32333 ,678,679,678 ,0,0,0}, + {32335,32326,32336 ,679,673,679 ,0,0,0}, {32327,32329,32328 ,674,675,675 ,0,0,0}, + {32335,32327,32326 ,679,674,673 ,0,0,0}, {32328,32329,32331 ,675,675,676 ,0,0,0}, + {31767,32325,31764 ,671,672,681 ,0,0,0}, {32324,32330,32325 ,672,676,672 ,0,0,0}, + {31536,31537,32342 ,21,21,21 ,0,0,0}, {31536,32342,32343 ,21,21,21 ,0,0,0}, + {32344,32345,32346 ,682,683,684 ,0,0,0}, {32347,32348,32346 ,685,686,684 ,0,0,0}, + {32344,32346,32348 ,682,684,686 ,0,0,0}, {32347,32349,32350 ,685,687,688 ,0,0,0}, + {32350,32348,32347 ,688,686,685 ,0,0,0}, {32351,32349,32352 ,689,687,690 ,0,0,0}, + {32349,32351,32350 ,687,689,688 ,0,0,0}, {32353,32354,32352 ,691,692,690 ,0,0,0}, + {32351,32352,32354 ,689,690,692 ,0,0,0}, {32353,32355,32356 ,691,693,694 ,0,0,0}, + {32356,32354,32353 ,694,692,691 ,0,0,0}, {32357,32355,32358 ,695,693,696 ,0,0,0}, + {32355,32357,32356 ,693,695,694 ,0,0,0}, {32359,32360,32358 ,697,698,696 ,0,0,0}, + {32357,32358,32360 ,695,696,698 ,0,0,0}, {32359,32361,32362 ,697,699,700 ,0,0,0}, + {32362,32360,32359 ,700,698,697 ,0,0,0}, {32363,32361,32364 ,701,699,702 ,0,0,0}, + {32361,32363,32362 ,699,701,700 ,0,0,0}, {32365,32366,32364 ,641,703,702 ,0,0,0}, + {32363,32364,32366 ,701,702,703 ,0,0,0}, {32367,32366,32365 ,641,703,641 ,0,0,0}, + {32368,32345,32344 ,704,683,682 ,0,0,0}, {32369,32368,32370 ,705,704,706 ,0,0,0}, + {32368,32369,32345 ,704,705,683 ,0,0,0}, {32371,32372,32370 ,707,708,706 ,0,0,0}, + {32369,32370,32372 ,705,706,708 ,0,0,0}, {32371,32373,32374 ,707,709,710 ,0,0,0}, + {32374,32372,32371 ,710,708,707 ,0,0,0}, {32375,32373,32376 ,711,709,712 ,0,0,0}, + {32373,32375,32374 ,709,711,710 ,0,0,0}, {32377,32378,32376 ,713,714,712 ,0,0,0}, + {32375,32376,32378 ,711,712,714 ,0,0,0}, {32377,32379,32380 ,713,715,716 ,0,0,0}, + {32380,32378,32377 ,716,714,713 ,0,0,0}, {32381,32379,32382 ,717,715,718 ,0,0,0}, + {32379,32381,32380 ,715,717,716 ,0,0,0}, {32383,32384,32382 ,719,720,718 ,0,0,0}, + {32381,32382,32384 ,717,718,720 ,0,0,0}, {32383,32385,32386 ,719,721,722 ,0,0,0}, + {32386,32384,32383 ,722,720,719 ,0,0,0}, {32387,32385,32388 ,723,721,456 ,0,0,0}, + {32385,32387,32386 ,721,723,722 ,0,0,0}, {32387,32388,32389 ,723,456,724 ,0,0,0}, + {31556,31557,32390 ,21,725,725 ,0,0,0}, {31556,32390,32391 ,21,725,21 ,0,0,0}, + {31824,31559,31823 ,726,726,726 ,0,0,0}, {31610,32348,32392 ,727,727,726 ,0,0,0}, + {32184,32186,32393 ,726,726,726 ,0,0,0}, {32368,32344,31610 ,727,727,727 ,0,0,0}, + {31607,32368,31610 ,726,727,727 ,0,0,0}, {31574,32394,32395 ,726,726,726 ,0,0,0}, + {31766,31970,31763 ,726,726,726 ,0,0,0}, {32370,31607,31608 ,726,726,726 ,0,0,0}, + {32373,31603,31601 ,727,726,726 ,0,0,0}, {32396,32392,32350 ,726,726,726 ,0,0,0}, + {32397,32398,32399 ,726,726,726 ,0,0,0}, {32286,32400,32401 ,727,727,727 ,0,0,0}, + {32057,32402,32403 ,726,726,727 ,0,0,0}, {32396,32351,32404 ,726,726,726 ,0,0,0}, + {32405,32277,32406 ,726,726,726 ,0,0,0}, {32276,32405,32407 ,727,726,726 ,0,0,0}, + {32354,32408,32404 ,727,726,726 ,0,0,0}, {31601,31604,32376 ,726,727,726 ,0,0,0}, + {32409,31708,32271 ,726,727,726 ,0,0,0}, {32315,32312,31710 ,726,726,726 ,0,0,0}, + {32410,32408,32356 ,727,726,726 ,0,0,0}, {31595,32377,31604 ,727,726,727 ,0,0,0}, + {32411,32360,32412 ,727,727,727 ,0,0,0}, {32411,32410,32357 ,727,727,727 ,0,0,0}, + {32413,32412,32363 ,726,727,726 ,0,0,0}, {32362,32412,32360 ,726,727,727 ,0,0,0}, + {32414,32367,32415 ,727,726,726 ,0,0,0}, {32414,32413,32366 ,727,726,726 ,0,0,0}, + {32415,32416,32417 ,726,726,726 ,0,0,0}, {32418,32419,31624 ,726,726,727 ,0,0,0}, + {32382,31597,32383 ,726,727,726 ,0,0,0}, {32420,32421,32418 ,727,727,726 ,0,0,0}, + {32422,32416,32423 ,727,726,726 ,0,0,0}, {31617,31618,32424 ,727,726,726 ,0,0,0}, + {32030,31919,32034 ,726,726,726 ,0,0,0}, {32425,32426,32036 ,727,726,726 ,0,0,0}, + {32419,32427,32428 ,726,726,727 ,0,0,0}, {32022,31903,31902 ,726,726,727 ,0,0,0}, + {32429,32110,32430 ,726,726,728 ,0,0,0}, {32020,31875,31909 ,727,726,727 ,0,0,0}, + {32430,32113,32103 ,728,726,726 ,0,0,0}, {31645,31854,31627 ,728,726,726 ,0,0,0}, + {31648,31851,31853 ,726,728,726 ,0,0,0}, {31860,31631,31628 ,726,726,726 ,0,0,0}, + {32431,32432,32116 ,726,726,726 ,0,0,0}, {31631,31863,31629 ,726,726,726 ,0,0,0}, + {31871,31874,31924 ,726,726,727 ,0,0,0}, {32433,31641,31637 ,726,726,726 ,0,0,0}, + {31643,31640,32434 ,726,726,726 ,0,0,0}, {32435,32436,32101 ,727,726,726 ,0,0,0}, + {32164,31953,31956 ,726,726,726 ,0,0,0}, {32437,32096,31677 ,726,726,726 ,0,0,0}, + {32438,32439,32440 ,727,727,726 ,0,0,0}, {31660,32095,32092 ,726,727,726 ,0,0,0}, + {32441,32442,32068 ,727,726,727 ,0,0,0}, {32443,32062,32444 ,726,726,727 ,0,0,0}, + {31670,32085,31667 ,727,726,726 ,0,0,0}, {32445,32045,32048 ,727,726,726 ,0,0,0}, + {32038,32446,32447 ,727,726,726 ,0,0,0}, {31675,31672,32074 ,727,726,726 ,0,0,0}, + {31675,32072,32070 ,727,726,727 ,0,0,0}, {31673,32077,31672 ,726,727,726 ,0,0,0}, + {32078,31673,31669 ,727,726,726 ,0,0,0}, {32447,32070,32038 ,726,727,727 ,0,0,0}, + {32448,32446,32040 ,726,726,726 ,0,0,0}, {31667,32082,32080 ,726,727,726 ,0,0,0}, + {32041,32449,32448 ,727,726,726 ,0,0,0}, {32445,32449,32044 ,727,726,727 ,0,0,0}, + {31661,32086,31670 ,727,726,727 ,0,0,0}, {32050,32450,32451 ,726,727,727 ,0,0,0}, + {32451,32445,32048 ,727,727,726 ,0,0,0}, {32403,32452,32053 ,727,726,727 ,0,0,0}, + {32051,32452,32450 ,726,726,727 ,0,0,0}, {32453,32068,32442 ,727,727,726 ,0,0,0}, + {32063,32454,32444 ,726,726,727 ,0,0,0}, {32066,32068,32454 ,726,727,726 ,0,0,0}, + {32454,32068,32453 ,726,727,727 ,0,0,0}, {32060,32443,32402 ,726,726,726 ,0,0,0}, + {32063,32066,32454 ,726,726,726 ,0,0,0}, {31689,32442,32441 ,727,726,727 ,0,0,0}, + {32439,32455,31683 ,727,726,726 ,0,0,0}, {31689,32441,32456 ,727,727,726 ,0,0,0}, + {31683,31686,32439 ,726,727,727 ,0,0,0}, {32455,31682,31683 ,726,727,726 ,0,0,0}, + {32438,32440,32457 ,727,726,726 ,0,0,0}, {32458,32438,32457 ,726,727,726 ,0,0,0}, + {32459,32460,32101 ,726,726,726 ,0,0,0}, {32101,32458,32457 ,726,726,726 ,0,0,0}, + {32460,31882,32458 ,726,726,726 ,0,0,0}, {32101,32391,32461 ,726,727,726 ,0,0,0}, + {32162,31952,31953 ,726,726,726 ,0,0,0}, {32462,32100,32463 ,726,726,726 ,0,0,0}, + {32167,31956,32464 ,726,726,726 ,0,0,0}, {32105,32465,32103 ,726,726,726 ,0,0,0}, + {32465,32105,32466 ,726,726,726 ,0,0,0}, {31839,31656,31842 ,726,726,726 ,0,0,0}, + {32467,31845,32468 ,726,726,726 ,0,0,0}, {32468,31843,31657 ,726,726,726 ,0,0,0}, + {32469,31847,32467 ,726,726,726 ,0,0,0}, {31847,32469,32102 ,726,726,726 ,0,0,0}, + {31845,31843,32468 ,726,726,726 ,0,0,0}, {32106,32102,32469 ,726,726,726 ,0,0,0}, + {31845,32467,31847 ,726,726,726 ,0,0,0}, {31657,31843,31842 ,726,726,726 ,0,0,0}, + {32106,32469,32466 ,726,726,726 ,0,0,0}, {31654,31656,31837 ,726,726,726 ,0,0,0}, + {32431,32118,32470 ,726,729,726 ,0,0,0}, {31836,31832,31651 ,726,726,726 ,0,0,0}, + {31857,31628,31627 ,726,726,726 ,0,0,0}, {32431,32115,32118 ,726,726,729 ,0,0,0}, + {31629,32471,31638 ,726,728,726 ,0,0,0}, {32432,32472,32121 ,726,726,726 ,0,0,0}, + {32433,32473,31641 ,726,726,726 ,0,0,0}, {32471,32433,31635 ,728,726,726 ,0,0,0}, + {31866,31876,31928 ,727,727,727 ,0,0,0}, {31928,31931,31866 ,727,727,727 ,0,0,0}, + {31868,31866,31931 ,726,727,727 ,0,0,0}, {32474,32176,32170 ,726,726,726 ,0,0,0}, + {31931,31921,31868 ,727,726,726 ,0,0,0}, {32027,32020,31907 ,726,727,726 ,0,0,0}, + {31920,31871,31924 ,727,726,727 ,0,0,0}, {31921,31923,31869 ,726,726,727 ,0,0,0}, + {31933,31877,31880 ,726,726,726 ,0,0,0}, {32126,32122,32475 ,726,726,726 ,0,0,0}, + {31875,31871,31920 ,726,726,727 ,0,0,0}, {31947,32158,32156 ,726,726,726 ,0,0,0}, + {32476,32477,32129 ,726,726,726 ,0,0,0}, {32475,32122,32472 ,726,726,726 ,0,0,0}, + {31923,31874,31869 ,726,726,727 ,0,0,0}, {31869,31868,31921 ,727,726,726 ,0,0,0}, + {31946,31947,32156 ,726,726,726 ,0,0,0}, {32127,32476,32129 ,726,726,726 ,0,0,0}, + {32473,32478,32479 ,726,726,726 ,0,0,0}, {31640,31641,32434 ,726,726,726 ,0,0,0}, + {32480,31554,32169 ,726,726,726 ,0,0,0}, {32478,32462,32463 ,726,726,726 ,0,0,0}, + {32478,32463,32479 ,726,726,726 ,0,0,0}, {32158,31950,32161 ,726,726,726 ,0,0,0}, + {31929,31928,31876 ,726,727,727 ,0,0,0}, {32140,31965,32141 ,726,728,728 ,0,0,0}, + {32141,31962,32139 ,728,728,726 ,0,0,0}, {32027,31906,32024 ,726,726,726 ,0,0,0}, + {31941,32133,31959 ,726,726,728 ,0,0,0}, {32024,31906,31903 ,726,726,726 ,0,0,0}, + {32022,32024,31903 ,726,726,726 ,0,0,0}, {31914,32029,32032 ,727,726,726 ,0,0,0}, + {31902,32032,32022 ,727,726,726 ,0,0,0}, {32006,32481,32227 ,726,726,726 ,0,0,0}, + {32032,31902,31914 ,726,727,727 ,0,0,0}, {32482,32483,31534 ,726,726,726 ,0,0,0}, + {32484,32485,32486 ,726,726,726 ,0,0,0}, {32487,32486,31544 ,726,726,726 ,0,0,0}, + {32488,32188,32489 ,726,726,726 ,0,0,0}, {32485,32484,32490 ,726,726,726 ,0,0,0}, + {31817,31590,31819 ,726,726,726 ,0,0,0}, {31569,32394,31574 ,726,726,726 ,0,0,0}, + {32491,32492,32174 ,726,726,726 ,0,0,0}, {32474,32170,31590 ,726,726,726 ,0,0,0}, + {32174,32176,32491 ,726,726,726 ,0,0,0}, {32474,32491,32176 ,726,726,726 ,0,0,0}, + {32493,32173,32492 ,726,726,726 ,0,0,0}, {32173,32174,32492 ,726,726,726 ,0,0,0}, + {32493,32494,32180 ,726,726,726 ,0,0,0}, {32170,31819,31590 ,726,726,726 ,0,0,0}, + {31589,31816,31587 ,726,726,726 ,0,0,0}, {32494,32495,32181 ,726,728,726 ,0,0,0}, + {31581,31821,31578 ,726,726,728 ,0,0,0}, {31811,31584,31813 ,726,726,726 ,0,0,0}, + {31563,31831,31561 ,726,726,726 ,0,0,0}, {31560,31827,31829 ,726,726,726 ,0,0,0}, + {32241,32496,32497 ,726,726,726 ,0,0,0}, {32394,31567,32498 ,726,726,728 ,0,0,0}, + {32498,31570,31561 ,728,726,726 ,0,0,0}, {32393,32489,32184 ,726,726,726 ,0,0,0}, + {31530,32499,31532 ,726,726,726 ,0,0,0}, {32189,32500,32501 ,726,726,726 ,0,0,0}, + {32502,32503,32504 ,727,727,726 ,0,0,0}, {31997,32218,32216 ,726,726,726 ,0,0,0}, + {31937,32505,31529 ,726,726,726 ,0,0,0}, {32227,32481,32229 ,726,726,726 ,0,0,0}, + {31534,32483,32506 ,726,726,726 ,0,0,0}, {32221,32002,32222 ,726,726,726 ,0,0,0}, + {31774,32507,32508 ,726,726,727 ,0,0,0}, {31758,31971,31760 ,727,727,726 ,0,0,0}, + {31768,31981,31758 ,727,727,727 ,0,0,0}, {31767,31763,31891 ,726,726,727 ,0,0,0}, + {31760,31971,31973 ,726,727,726 ,0,0,0}, {31885,32331,31888 ,726,726,727 ,0,0,0}, + {32193,31991,32195 ,726,726,726 ,0,0,0}, {32326,31884,31896 ,726,726,727 ,0,0,0}, + {31722,32509,32510 ,727,726,726 ,0,0,0}, {32511,32260,32512 ,726,726,726 ,0,0,0}, + {31899,32334,32333 ,726,726,726 ,0,0,0}, {31901,32513,32338 ,726,726,726 ,0,0,0}, + {32397,32399,32514 ,726,726,728 ,0,0,0}, {32515,32516,32263 ,726,726,726 ,0,0,0}, + {32398,32517,32399 ,726,726,726 ,0,0,0}, {32254,32250,32518 ,726,728,726 ,0,0,0}, + {31741,32519,32520 ,726,726,726 ,0,0,0}, {31798,31727,31797 ,726,726,726 ,0,0,0}, + {31807,32519,31738 ,726,726,726 ,0,0,0}, {32521,32520,32517 ,726,726,726 ,0,0,0}, + {31787,31749,31789 ,726,726,726 ,0,0,0}, {31793,31795,31729 ,726,726,726 ,0,0,0}, + {32231,32233,32496 ,726,726,726 ,0,0,0}, {32234,31755,32233 ,726,726,726 ,0,0,0}, + {32522,32238,32497 ,726,728,726 ,0,0,0}, {32241,32497,32238 ,726,726,728 ,0,0,0}, + {32239,32238,32522 ,726,728,726 ,0,0,0}, {32496,32241,32231 ,726,726,726 ,0,0,0}, + {32496,32233,31755 ,726,726,726 ,0,0,0}, {32522,32523,32239 ,726,726,726 ,0,0,0}, + {32524,32243,32523 ,726,726,726 ,0,0,0}, {32523,32246,32239 ,726,726,726 ,0,0,0}, + {32524,32525,32244 ,726,728,726 ,0,0,0}, {32234,32230,31754 ,726,726,726 ,0,0,0}, + {31781,31743,31783 ,726,728,726 ,0,0,0}, {31791,31789,31752 ,726,726,726 ,0,0,0}, + {31726,31776,31793 ,726,726,726 ,0,0,0}, {31743,31780,31725 ,728,726,726 ,0,0,0}, + {31798,31736,31727 ,726,726,726 ,0,0,0}, {31803,31735,31733 ,726,726,726 ,0,0,0}, + {31735,31807,31739 ,726,726,726 ,0,0,0}, {32526,32518,32250 ,726,726,728 ,0,0,0}, + {31801,31733,31736 ,726,726,726 ,0,0,0}, {32527,32255,32518 ,726,726,726 ,0,0,0}, + {32398,32528,32517 ,726,726,726 ,0,0,0}, {32529,32530,32531 ,726,726,726 ,0,0,0}, + {31524,31522,32210 ,726,726,726 ,0,0,0}, {31526,32207,31519 ,726,726,726 ,0,0,0}, + {32311,31692,31691 ,726,726,727 ,0,0,0}, {32532,32294,32533 ,727,726,726 ,0,0,0}, + {31898,32336,31896 ,727,726,727 ,0,0,0}, {32534,32514,32263 ,726,728,726 ,0,0,0}, + {32514,32534,32397 ,728,726,726 ,0,0,0}, {32263,31524,32534 ,726,726,726 ,0,0,0}, + {32292,32535,32289 ,726,726,726 ,0,0,0}, {32303,31702,31693 ,726,727,727 ,0,0,0}, + {32271,31708,32270 ,726,727,726 ,0,0,0}, {32282,32536,32406 ,726,727,726 ,0,0,0}, + {32267,32270,31705 ,726,726,726 ,0,0,0}, {32409,32274,32407 ,726,726,726 ,0,0,0}, + {31705,31706,32266 ,726,726,726 ,0,0,0}, {32296,31701,31699 ,726,726,726 ,0,0,0}, + {31699,32298,32296 ,726,726,726 ,0,0,0}, {32282,32406,32279 ,726,726,726 ,0,0,0}, + {31702,32300,31699 ,727,727,726 ,0,0,0}, {32536,32283,32401 ,727,726,727 ,0,0,0}, + {31693,31695,32304 ,727,727,726 ,0,0,0}, {32400,32288,32535 ,727,726,726 ,0,0,0}, + {32308,32306,31692 ,726,726,726 ,0,0,0}, {32537,32538,32533 ,726,726,726 ,0,0,0}, + {31715,32316,31713 ,727,727,726 ,0,0,0}, {32539,32540,32541 ,726,726,727 ,0,0,0}, + {32542,32537,32540 ,727,726,726 ,0,0,0}, {32543,32541,32544 ,726,727,727 ,0,0,0}, + {32544,32541,32540 ,727,727,726 ,0,0,0}, {32326,31896,32336 ,726,727,726 ,0,0,0}, + {32510,32541,32543 ,726,727,726 ,0,0,0}, {31719,31721,32322 ,727,726,727 ,0,0,0}, + {31898,31899,32333 ,727,726,726 ,0,0,0}, {31722,32510,32545 ,727,726,726 ,0,0,0}, + {32544,32546,32543 ,727,727,726 ,0,0,0}, {32509,32541,32510 ,726,727,726 ,0,0,0}, + {32340,32547,32511 ,726,726,726 ,0,0,0}, {32546,32511,32512 ,727,726,726 ,0,0,0}, + {32546,32512,32543 ,727,726,726 ,0,0,0}, {31898,32333,32336 ,727,726,726 ,0,0,0}, + {31884,32328,31885 ,726,726,726 ,0,0,0}, {32331,31885,32328 ,726,726,726 ,0,0,0}, + {32328,31884,32326 ,726,726,726 ,0,0,0}, {31889,31767,31891 ,727,726,727 ,0,0,0}, + {31888,32324,31889 ,727,727,727 ,0,0,0}, {31763,31970,31891 ,726,726,727 ,0,0,0}, + {32012,32201,32015 ,726,728,726 ,0,0,0}, {31974,31970,31766 ,726,726,726 ,0,0,0}, + {31973,31974,31761 ,726,726,727 ,0,0,0}, {31761,31974,31766 ,727,726,726 ,0,0,0}, + {31973,31761,31760 ,726,727,726 ,0,0,0}, {32503,32502,32548 ,727,727,727 ,0,0,0}, + {31769,31978,31768 ,726,726,727 ,0,0,0}, {31758,31981,31971 ,727,727,727 ,0,0,0}, + {32549,32550,32428 ,727,727,727 ,0,0,0}, {31916,32029,31914 ,726,726,727 ,0,0,0}, + {32030,31917,31919 ,726,726,726 ,0,0,0}, {31916,32030,32029 ,726,726,726 ,0,0,0}, + {31919,32425,32034 ,726,727,726 ,0,0,0}, {32551,32552,32036 ,726,726,726 ,0,0,0}, + {32428,31624,32419 ,727,727,726 ,0,0,0}, {32553,32418,32421 ,727,726,727 ,0,0,0}, + {32418,32553,32419 ,726,727,726 ,0,0,0}, {32423,32421,32420 ,726,727,727 ,0,0,0}, + {31612,32554,32388 ,726,726,726 ,0,0,0}, {32101,32100,31556 ,726,726,726 ,0,0,0}, + {32555,32169,32167 ,726,726,726 ,0,0,0}, {31880,31882,32556 ,726,726,726 ,0,0,0}, + {32101,31556,32391 ,726,726,727 ,0,0,0}, {31880,32557,31933 ,726,726,726 ,0,0,0}, + {32101,32461,32435 ,726,726,727 ,0,0,0}, {32458,32101,32460 ,726,726,726 ,0,0,0}, + {32436,32459,32101 ,726,726,726 ,0,0,0}, {32558,32556,31882 ,726,726,726 ,0,0,0}, + {32460,32558,31882 ,726,726,726 ,0,0,0}, {32556,32557,31880 ,726,726,726 ,0,0,0}, + {31929,31877,31933 ,726,726,726 ,0,0,0}, {31929,31876,31877 ,726,727,726 ,0,0,0}, + {32156,32155,31946 ,726,726,726 ,0,0,0}, {32155,32152,31944 ,726,726,726 ,0,0,0}, + {32152,32135,31940 ,726,726,726 ,0,0,0}, {32135,32133,31941 ,726,726,726 ,0,0,0}, + {32132,31959,32133 ,726,728,726 ,0,0,0}, {31923,31924,31874 ,726,727,726 ,0,0,0}, + {31946,32155,31944 ,726,726,726 ,0,0,0}, {31920,31909,31875 ,727,727,726 ,0,0,0}, + {31940,31944,32152 ,726,726,726 ,0,0,0}, {31960,32132,32139 ,726,726,726 ,0,0,0}, + {31909,31907,32020 ,727,726,727 ,0,0,0}, {31940,32135,31941 ,726,726,726 ,0,0,0}, + {32148,31966,32140 ,726,726,726 ,0,0,0}, {31907,31906,32027 ,726,726,726 ,0,0,0}, + {31959,32132,31960 ,728,726,726 ,0,0,0}, {31546,31968,32144 ,726,726,726 ,0,0,0}, + {31965,31962,32141 ,728,728,728 ,0,0,0}, {32147,32150,31539 ,726,726,726 ,0,0,0}, + {31966,31965,32140 ,726,728,726 ,0,0,0}, {31540,32150,31542 ,726,726,726 ,0,0,0}, + {31968,31966,32148 ,726,726,726 ,0,0,0}, {32419,32553,32559 ,726,727,726 ,0,0,0}, + {31916,31917,32030 ,726,726,726 ,0,0,0}, {32552,32559,32553 ,726,726,727 ,0,0,0}, + {32551,32036,32426 ,726,726,726 ,0,0,0}, {32425,32036,32034 ,727,726,726 ,0,0,0}, + {32552,32551,32559 ,726,726,726 ,0,0,0}, {32560,32548,32427 ,726,727,726 ,0,0,0}, + {32502,32504,32343 ,727,726,727 ,0,0,0}, {32419,32560,32427 ,726,726,726 ,0,0,0}, + {31623,32561,31621 ,726,727,727 ,0,0,0}, {32504,31938,32343 ,726,727,727 ,0,0,0}, + {32562,32563,31774 ,726,726,726 ,0,0,0}, {32000,32221,32218 ,726,726,726 ,0,0,0}, + {32224,32222,32003 ,726,726,728 ,0,0,0}, {31544,32564,32487 ,726,726,726 ,0,0,0}, + {31546,32144,32147 ,726,726,726 ,0,0,0}, {32229,32506,32483 ,726,726,726 ,0,0,0}, + {32490,32484,32565 ,726,726,726 ,0,0,0}, {32564,31544,31542 ,726,726,726 ,0,0,0}, + {32564,31542,32150 ,726,726,726 ,0,0,0}, {31540,31539,32150 ,726,726,726 ,0,0,0}, + {31539,31546,32147 ,726,726,726 ,0,0,0}, {31968,32148,32144 ,726,726,726 ,0,0,0}, + {31962,31960,32139 ,728,726,726 ,0,0,0}, {31950,31952,32161 ,726,726,726 ,0,0,0}, + {31947,31950,32158 ,726,726,726 ,0,0,0}, {32162,31953,32164 ,726,726,726 ,0,0,0}, + {32161,31952,32162 ,726,726,726 ,0,0,0}, {32164,31956,32167 ,726,726,726 ,0,0,0}, + {32464,32555,32167 ,726,726,726 ,0,0,0}, {32555,32480,32169 ,726,726,726 ,0,0,0}, + {32462,32169,31554 ,726,726,726 ,0,0,0}, {31552,32100,31554 ,726,726,726 ,0,0,0}, + {32462,31554,32100 ,726,726,726 ,0,0,0}, {31549,32100,31550 ,726,726,726 ,0,0,0}, + {32100,31552,31550 ,726,726,726 ,0,0,0}, {31556,32100,31549 ,726,726,726 ,0,0,0}, + {31997,32216,31996 ,726,726,726 ,0,0,0}, {31938,31937,31536 ,727,726,726 ,0,0,0}, + {31769,31983,31979 ,726,726,726 ,0,0,0}, {31938,31536,32343 ,727,726,727 ,0,0,0}, + {31983,31772,32563 ,726,726,726 ,0,0,0}, {32503,32548,32560 ,727,727,726 ,0,0,0}, + {31623,32428,32550 ,726,727,727 ,0,0,0}, {32549,32508,32507 ,727,727,726 ,0,0,0}, + {32549,32507,32550 ,727,726,727 ,0,0,0}, {32508,32562,31774 ,727,726,726 ,0,0,0}, + {32563,31772,31774 ,726,726,726 ,0,0,0}, {31983,31769,31772 ,726,726,726 ,0,0,0}, + {31978,31769,31979 ,726,726,726 ,0,0,0}, {31978,31981,31768 ,726,727,727 ,0,0,0}, + {32215,31994,31996 ,726,726,726 ,0,0,0}, {32212,31990,31994 ,726,726,726 ,0,0,0}, + {32195,31991,31990 ,726,726,726 ,0,0,0}, {32193,32009,31991 ,726,729,726 ,0,0,0}, + {32216,32215,31996 ,726,726,726 ,0,0,0}, {32192,32010,32009 ,726,726,729 ,0,0,0}, + {32215,32212,31994 ,726,726,726 ,0,0,0}, {32199,32012,32010 ,726,726,726 ,0,0,0}, + {31889,32324,31767 ,727,727,726 ,0,0,0}, {32212,32195,31990 ,726,726,726 ,0,0,0}, + {32200,32016,32015 ,726,726,726 ,0,0,0}, {31888,32331,32324 ,727,726,727 ,0,0,0}, + {32193,32192,32009 ,726,726,729 ,0,0,0}, {32018,32016,32208 ,726,726,726 ,0,0,0}, + {32192,32199,32010 ,726,726,726 ,0,0,0}, {32207,31526,32204 ,726,726,726 ,0,0,0}, + {32015,32201,32200 ,726,728,726 ,0,0,0}, {31987,32263,32260 ,727,726,726 ,0,0,0}, + {32200,32208,32016 ,726,726,726 ,0,0,0}, {32338,32566,32340 ,726,726,726 ,0,0,0}, + {31901,32334,31899 ,726,726,726 ,0,0,0}, {32513,32567,32338 ,726,727,726 ,0,0,0}, + {32334,31901,32338 ,726,726,726 ,0,0,0}, {32567,32566,32338 ,727,726,726 ,0,0,0}, + {32511,32547,32260 ,726,726,726 ,0,0,0}, {32566,32547,32340 ,726,726,726 ,0,0,0}, + {32568,32260,32569 ,726,726,727 ,0,0,0}, {32260,32547,32569 ,726,726,727 ,0,0,0}, + {32570,32260,32571 ,726,726,726 ,0,0,0}, {32260,32568,32571 ,726,726,726 ,0,0,0}, + {32260,32570,31987 ,726,726,727 ,0,0,0}, {31989,32263,31987 ,726,726,727 ,0,0,0}, + {31520,32207,32210 ,726,726,726 ,0,0,0}, {32263,32572,32515 ,726,726,726 ,0,0,0}, + {32263,31989,32572 ,726,726,726 ,0,0,0}, {31524,32210,32534 ,726,726,726 ,0,0,0}, + {32516,31524,32263 ,726,726,726 ,0,0,0}, {31522,31520,32210 ,726,726,726 ,0,0,0}, + {31520,31519,32207 ,726,726,726 ,0,0,0}, {32018,32204,31526 ,726,726,726 ,0,0,0}, + {32018,32208,32204 ,726,726,726 ,0,0,0}, {32012,32199,32201 ,726,726,728 ,0,0,0}, + {32000,32002,32221 ,726,726,726 ,0,0,0}, {31997,32000,32218 ,726,726,726 ,0,0,0}, + {32002,32003,32222 ,726,728,726 ,0,0,0}, {32003,32006,32224 ,728,726,726 ,0,0,0}, + {32227,32224,32006 ,726,726,726 ,0,0,0}, {32573,32229,32481 ,726,726,726 ,0,0,0}, + {32487,32484,32486 ,726,726,726 ,0,0,0}, {32573,32506,32229 ,726,726,726 ,0,0,0}, + {31576,31532,32574 ,726,726,726 ,0,0,0}, {32499,31530,32505 ,726,726,726 ,0,0,0}, + {32574,31532,32499 ,726,726,726 ,0,0,0}, {31937,31529,31536 ,726,726,726 ,0,0,0}, + {32505,31530,31529 ,726,726,726 ,0,0,0}, {32526,32249,32525 ,726,726,728 ,0,0,0}, + {31748,31786,31746 ,726,726,726 ,0,0,0}, {31729,31795,31727 ,726,726,726 ,0,0,0}, + {32243,32246,32523 ,726,726,726 ,0,0,0}, {32244,32243,32524 ,726,726,726 ,0,0,0}, + {32249,32244,32525 ,726,726,728 ,0,0,0}, {32250,32249,32526 ,728,726,726 ,0,0,0}, + {32257,32255,32527 ,726,726,726 ,0,0,0}, {32255,32254,32518 ,726,726,726 ,0,0,0}, + {32530,32529,32528 ,726,726,726 ,0,0,0}, {32257,32575,32531 ,726,726,726 ,0,0,0}, + {32575,32257,32527 ,726,726,726 ,0,0,0}, {32576,32529,32531 ,726,726,726 ,0,0,0}, + {32575,32576,32531 ,726,726,726 ,0,0,0}, {32528,32398,32530 ,726,726,726 ,0,0,0}, + {32517,32520,32399 ,726,726,726 ,0,0,0}, {31741,32520,32521 ,726,726,726 ,0,0,0}, + {31738,32519,31741 ,726,726,726 ,0,0,0}, {31739,31807,31738 ,726,726,726 ,0,0,0}, + {31803,31804,31735 ,726,726,726 ,0,0,0}, {31807,31735,31804 ,726,726,726 ,0,0,0}, + {31801,31803,31733 ,726,726,726 ,0,0,0}, {31798,31801,31736 ,726,726,726 ,0,0,0}, + {31795,31797,31727 ,726,726,726 ,0,0,0}, {31793,31729,31726 ,726,726,726 ,0,0,0}, + {31776,31726,31725 ,726,726,726 ,0,0,0}, {31781,31780,31743 ,726,726,728 ,0,0,0}, + {31780,31776,31725 ,726,726,726 ,0,0,0}, {31746,31783,31743 ,726,726,728 ,0,0,0}, + {31748,31787,31786 ,726,726,726 ,0,0,0}, {31746,31786,31783 ,726,726,726 ,0,0,0}, + {31749,31752,31789 ,726,726,726 ,0,0,0}, {31748,31749,31787 ,726,726,726 ,0,0,0}, + {31791,31752,32230 ,726,726,726 ,0,0,0}, {32234,31754,31755 ,726,726,726 ,0,0,0}, + {32230,31752,31754 ,726,726,726 ,0,0,0}, {32535,32292,32532 ,726,726,727 ,0,0,0}, + {31716,32318,31715 ,726,727,727 ,0,0,0}, {31692,32306,31695 ,726,726,727 ,0,0,0}, + {32542,32540,32539 ,727,726,726 ,0,0,0}, {32538,32537,32542 ,726,726,727 ,0,0,0}, + {32294,32537,32533 ,726,726,726 ,0,0,0}, {32292,32294,32532 ,726,726,727 ,0,0,0}, + {32288,32289,32535 ,726,726,726 ,0,0,0}, {32286,32288,32400 ,727,726,727 ,0,0,0}, + {32283,32286,32401 ,726,727,727 ,0,0,0}, {32282,32283,32536 ,726,726,727 ,0,0,0}, + {32277,32279,32406 ,726,726,726 ,0,0,0}, {32276,32277,32405 ,727,726,726 ,0,0,0}, + {32274,32276,32407 ,726,727,726 ,0,0,0}, {32271,32274,32409 ,726,726,726 ,0,0,0}, + {32270,31708,31705 ,726,727,726 ,0,0,0}, {32266,32267,31705 ,726,726,726 ,0,0,0}, + {32264,32266,31706 ,727,726,726 ,0,0,0}, {32296,32264,31701 ,726,727,726 ,0,0,0}, + {32264,31706,31701 ,727,726,726 ,0,0,0}, {32300,32298,31699 ,727,726,726 ,0,0,0}, + {32303,32300,31702 ,726,727,727 ,0,0,0}, {32304,32303,31693 ,726,726,727 ,0,0,0}, + {32306,32304,31695 ,726,726,727 ,0,0,0}, {32311,32308,31692 ,726,726,726 ,0,0,0}, + {32312,32311,31691 ,726,726,727 ,0,0,0}, {31713,32315,31710 ,726,726,726 ,0,0,0}, + {31710,32312,31691 ,726,726,727 ,0,0,0}, {31715,32318,32316 ,727,727,727 ,0,0,0}, + {31713,32316,32315 ,726,727,726 ,0,0,0}, {31716,32321,32318 ,726,726,727 ,0,0,0}, + {31719,32322,31716 ,727,727,726 ,0,0,0}, {32321,31716,32322 ,726,726,727 ,0,0,0}, + {32322,31721,32545 ,727,726,726 ,0,0,0}, {31722,32545,31721 ,727,726,726 ,0,0,0}, + {31661,31663,32089 ,727,727,726 ,0,0,0}, {32057,32403,32056 ,726,727,727 ,0,0,0}, + {31660,32090,31663 ,726,727,727 ,0,0,0}, {32062,32063,32444 ,726,726,727 ,0,0,0}, + {32060,32062,32443 ,726,726,726 ,0,0,0}, {32057,32060,32402 ,726,726,726 ,0,0,0}, + {32053,32056,32403 ,727,727,727 ,0,0,0}, {32051,32053,32452 ,726,727,726 ,0,0,0}, + {32050,32051,32450 ,726,726,727 ,0,0,0}, {32048,32050,32451 ,726,726,727 ,0,0,0}, + {32044,32045,32445 ,727,726,727 ,0,0,0}, {32041,32044,32449 ,727,727,726 ,0,0,0}, + {32040,32041,32448 ,726,727,726 ,0,0,0}, {32038,32040,32446 ,727,726,726 ,0,0,0}, + {32070,32447,31675 ,727,726,727 ,0,0,0}, {32074,32072,31675 ,726,726,727 ,0,0,0}, + {32077,32074,31672 ,727,726,726 ,0,0,0}, {32078,32077,31673 ,727,727,726 ,0,0,0}, + {32080,31669,31667 ,726,726,726 ,0,0,0}, {32078,31669,32080 ,727,726,726 ,0,0,0}, + {32085,32082,31667 ,726,727,726 ,0,0,0}, {32086,32085,31670 ,726,726,727 ,0,0,0}, + {32089,32086,31661 ,726,726,727 ,0,0,0}, {32090,32089,31663 ,727,726,727 ,0,0,0}, + {31659,32095,31660 ,727,727,726 ,0,0,0}, {32092,32090,31660 ,726,727,726 ,0,0,0}, + {32096,31659,31677 ,726,727,726 ,0,0,0}, {31659,32096,32095 ,727,726,727 ,0,0,0}, + {31677,31680,32437 ,726,726,726 ,0,0,0}, {32455,32437,31682 ,726,726,727 ,0,0,0}, + {31680,31682,32437 ,726,727,726 ,0,0,0}, {32439,31686,32440 ,727,727,726 ,0,0,0}, + {31688,32456,31686 ,726,726,727 ,0,0,0}, {32440,31686,32456 ,726,727,726 ,0,0,0}, + {31689,32456,31688 ,727,726,726 ,0,0,0}, {32429,32470,32111 ,726,726,726 ,0,0,0}, + {31650,31832,31849 ,726,726,728 ,0,0,0}, {31859,31860,31628 ,728,726,726 ,0,0,0}, + {32105,32106,32466 ,726,726,726 ,0,0,0}, {32103,32465,32430 ,726,726,728 ,0,0,0}, + {32110,32113,32430 ,726,726,728 ,0,0,0}, {32111,32110,32429 ,726,726,726 ,0,0,0}, + {32118,32111,32470 ,729,726,726 ,0,0,0}, {32116,32115,32431 ,726,726,726 ,0,0,0}, + {32121,32116,32432 ,726,726,726 ,0,0,0}, {32122,32121,32472 ,726,726,726 ,0,0,0}, + {32476,32127,32126 ,726,726,726 ,0,0,0}, {32126,32475,32476 ,726,726,726 ,0,0,0}, + {32129,32577,32578 ,726,726,726 ,0,0,0}, {32577,32129,32477 ,726,726,726 ,0,0,0}, + {32578,31643,32434 ,726,726,726 ,0,0,0}, {32577,31643,32578 ,726,726,726 ,0,0,0}, + {31641,32473,32479 ,726,726,726 ,0,0,0}, {31641,32479,32434 ,726,726,726 ,0,0,0}, + {31635,32433,31637 ,726,726,726 ,0,0,0}, {31638,32471,31635 ,726,728,726 ,0,0,0}, + {31863,32471,31629 ,726,728,726 ,0,0,0}, {31860,31863,31631 ,726,726,726 ,0,0,0}, + {31854,31857,31627 ,726,726,726 ,0,0,0}, {31857,31859,31628 ,726,728,726 ,0,0,0}, + {31853,31854,31645 ,726,726,728 ,0,0,0}, {31648,31849,31851 ,726,728,728 ,0,0,0}, + {31648,31853,31645 ,726,726,728 ,0,0,0}, {31650,31651,31832 ,726,726,726 ,0,0,0}, + {31648,31650,31849 ,726,726,728 ,0,0,0}, {31651,31654,31836 ,726,726,726 ,0,0,0}, + {31837,31656,31839 ,726,726,726 ,0,0,0}, {31836,31654,31837 ,726,726,726 ,0,0,0}, + {31842,31656,31657 ,726,726,726 ,0,0,0}, {32385,32383,31594 ,726,726,726 ,0,0,0}, + {32379,31595,32382 ,727,727,726 ,0,0,0}, {32422,32423,32579 ,727,726,726 ,0,0,0}, + {32579,32423,32420 ,726,726,727 ,0,0,0}, {32417,32416,32422 ,726,726,727 ,0,0,0}, + {32367,32416,32415 ,726,726,726 ,0,0,0}, {32366,32367,32414 ,726,726,727 ,0,0,0}, + {32363,32366,32413 ,726,726,726 ,0,0,0}, {32362,32363,32412 ,726,726,727 ,0,0,0}, + {32357,32360,32411 ,727,727,727 ,0,0,0}, {32356,32357,32410 ,726,727,727 ,0,0,0}, + {32354,32356,32408 ,727,726,726 ,0,0,0}, {32351,32354,32404 ,726,727,726 ,0,0,0}, + {32350,32351,32396 ,726,726,726 ,0,0,0}, {32348,32350,32392 ,727,726,726 ,0,0,0}, + {32344,32348,31610 ,727,727,727 ,0,0,0}, {32370,32368,31607 ,726,727,726 ,0,0,0}, + {32371,32370,31608 ,726,726,726 ,0,0,0}, {32373,32371,31603 ,727,726,726 ,0,0,0}, + {32371,31608,31603 ,726,726,726 ,0,0,0}, {32376,32373,31601 ,726,727,726 ,0,0,0}, + {32377,32376,31604 ,726,726,727 ,0,0,0}, {32379,32377,31595 ,727,726,727 ,0,0,0}, + {31597,32382,31595 ,727,726,727 ,0,0,0}, {31593,32385,31594 ,727,726,726 ,0,0,0}, + {31594,32383,31597 ,726,726,727 ,0,0,0}, {32388,31593,31612 ,726,727,726 ,0,0,0}, + {31593,32388,32385 ,727,726,726 ,0,0,0}, {31612,31615,32554 ,726,726,726 ,0,0,0}, + {32424,32554,31617 ,726,726,727 ,0,0,0}, {31615,31617,32554 ,726,727,726 ,0,0,0}, + {32424,31618,32561 ,726,726,727 ,0,0,0}, {32561,31623,32550 ,727,726,727 ,0,0,0}, + {32561,31618,31621 ,727,726,727 ,0,0,0}, {32428,31623,31624 ,727,726,727 ,0,0,0}, + {32495,32186,32178 ,728,726,726 ,0,0,0}, {31583,31810,31581 ,726,726,726 ,0,0,0}, + {31829,31563,31560 ,726,726,726 ,0,0,0}, {32180,32173,32493 ,726,726,726 ,0,0,0}, + {32181,32180,32494 ,726,726,726 ,0,0,0}, {32178,32181,32495 ,726,726,728 ,0,0,0}, + {32393,32186,32495 ,726,726,728 ,0,0,0}, {32188,32184,32489 ,726,726,726 ,0,0,0}, + {32488,32500,32189 ,726,726,726 ,0,0,0}, {32189,32188,32488 ,726,726,726 ,0,0,0}, + {32580,32501,32500 ,726,726,726 ,0,0,0}, {31573,31534,31532 ,726,726,726 ,0,0,0}, + {32501,32581,32565 ,726,726,726 ,0,0,0}, {32581,32501,32580 ,726,726,726 ,0,0,0}, + {31573,31532,31576 ,726,726,726 ,0,0,0}, {32581,32490,32565 ,726,726,726 ,0,0,0}, + {31576,32574,31544 ,726,726,726 ,0,0,0}, {31576,31544,32486 ,726,726,726 ,0,0,0}, + {31573,32482,31534 ,726,726,726 ,0,0,0}, {31573,31574,32395 ,726,726,726 ,0,0,0}, + {31573,32395,32482 ,726,726,726 ,0,0,0}, {31567,32394,31569 ,726,726,726 ,0,0,0}, + {31570,32498,31567 ,726,728,726 ,0,0,0}, {31831,32498,31561 ,726,728,726 ,0,0,0}, + {31829,31831,31563 ,726,726,726 ,0,0,0}, {31827,31560,31559 ,726,726,726 ,0,0,0}, + {31578,31823,31559 ,728,726,726 ,0,0,0}, {31824,31827,31559 ,726,726,726 ,0,0,0}, + {31581,31810,31821 ,726,726,726 ,0,0,0}, {31578,31821,31823 ,728,726,726 ,0,0,0}, + {31583,31811,31810 ,726,726,726 ,0,0,0}, {31584,31587,31813 ,726,726,726 ,0,0,0}, + {31583,31584,31811 ,726,726,726 ,0,0,0}, {31816,31589,31817 ,726,726,726 ,0,0,0}, + {31813,31587,31816 ,726,726,726 ,0,0,0}, {31590,31817,31589 ,726,726,726 ,0,0,0}, + {32582,31883,32583 ,730,730,730 ,0,0,0}, {31779,31744,31742 ,730,730,730 ,0,0,0}, + {31606,32372,31609 ,730,730,730 ,0,0,0}, {32584,32585,32586 ,730,730,730 ,0,0,0}, + {32587,32253,32256 ,730,730,730 ,0,0,0}, {31972,31759,31975 ,730,730,730 ,0,0,0}, + {31995,32214,32217 ,730,730,730 ,0,0,0}, {31775,32588,32589 ,730,730,730 ,0,0,0}, + {32590,32591,32592 ,730,730,730 ,0,0,0}, {32588,31775,32593 ,730,730,730 ,0,0,0}, + {32594,32595,31622 ,730,730,730 ,0,0,0}, {32361,32596,32597 ,730,730,730 ,0,0,0}, + {32594,31620,31619 ,730,730,730 ,0,0,0}, {31602,32374,32375 ,730,730,730 ,0,0,0}, + {31599,31600,32378 ,730,730,730 ,0,0,0}, {32598,32599,32355 ,730,730,730 ,0,0,0}, + {31611,32389,31613 ,730,730,730 ,0,0,0}, {32346,32345,31605 ,730,730,730 ,0,0,0}, + {32347,32600,32349 ,730,730,730 ,0,0,0}, {31592,32386,32387 ,730,730,730 ,0,0,0}, + {32601,32602,31616 ,730,730,730 ,0,0,0}, {31674,31671,32076 ,730,730,730 ,0,0,0}, + {31598,31596,32384 ,730,730,730 ,0,0,0}, {32039,32069,32603 ,730,730,730 ,0,0,0}, + {32387,32389,31611 ,730,730,730 ,0,0,0}, {31599,32380,31596 ,730,730,730 ,0,0,0}, + {31658,32094,31676 ,730,730,730 ,0,0,0}, {32604,32605,32047 ,730,730,730 ,0,0,0}, + {32345,32369,31605 ,730,730,730 ,0,0,0}, {32601,31614,31613 ,730,730,730 ,0,0,0}, + {32605,32606,32049 ,730,730,730 ,0,0,0}, {31666,32081,32083 ,730,730,730 ,0,0,0}, + {32346,31605,32607 ,730,730,730 ,0,0,0}, {32602,32594,31619 ,730,730,730 ,0,0,0}, + {32310,31709,31690 ,730,730,730 ,0,0,0}, {32314,31712,31711 ,730,730,730 ,0,0,0}, + {32352,32349,32608 ,730,730,730 ,0,0,0}, {32349,32600,32608 ,730,730,730 ,0,0,0}, + {32609,32598,32353 ,730,730,730 ,0,0,0}, {32596,32361,32359 ,730,730,730 ,0,0,0}, + {32599,32596,32358 ,730,730,730 ,0,0,0}, {32364,32597,32610 ,730,730,730 ,0,0,0}, + {32611,32612,32613 ,730,730,730 ,0,0,0}, {31775,31773,32593 ,730,730,730 ,0,0,0}, + {32614,32615,32595 ,730,730,730 ,0,0,0}, {31773,31771,31985 ,730,730,730 ,0,0,0}, + {32616,32617,32618 ,730,730,730 ,0,0,0}, {32619,32620,32621 ,730,730,730 ,0,0,0}, + {31756,31759,31972 ,730,730,730 ,0,0,0}, {31893,31976,31765 ,730,730,730 ,0,0,0}, + {32223,32225,32004 ,730,730,730 ,0,0,0}, {32202,32198,32013 ,730,730,730 ,0,0,0}, + {32584,32622,32623 ,730,730,730 ,0,0,0}, {32624,32587,32256 ,730,730,730 ,0,0,0}, + {32625,32626,32252 ,730,730,730 ,0,0,0}, {32627,32240,32242 ,730,730,730 ,0,0,0}, + {32245,32626,32628 ,730,730,730 ,0,0,0}, {31753,31751,32259 ,730,730,730 ,0,0,0}, + {32237,32629,32630 ,730,730,730 ,0,0,0}, {32631,32632,32633 ,730,730,730 ,0,0,0}, + {32634,32635,32636 ,730,730,730 ,0,0,0}, {32019,32206,32205 ,730,730,730 ,0,0,0}, + {32633,32261,32631 ,730,730,730 ,0,0,0}, {32637,32638,32639 ,730,730,730 ,0,0,0}, + {32640,32262,32641 ,730,730,730 ,0,0,0}, {32642,32287,32643 ,730,730,730 ,0,0,0}, + {32291,32644,32293 ,730,730,730 ,0,0,0}, {32645,32646,32281 ,730,730,730 ,0,0,0}, + {31717,32323,31718 ,730,730,730 ,0,0,0}, {32647,32278,32275 ,730,730,730 ,0,0,0}, + {31707,31704,32265 ,730,730,730 ,0,0,0}, {31694,32302,32305 ,730,730,730 ,0,0,0}, + {32648,32637,32639 ,730,730,730 ,0,0,0}, {32647,32275,32649 ,730,730,730 ,0,0,0}, + {32272,31703,32650 ,730,730,730 ,0,0,0}, {31720,32323,32651 ,730,730,730 ,0,0,0}, + {32317,31714,31712 ,730,730,730 ,0,0,0}, {31690,31696,32307 ,730,730,730 ,0,0,0}, + {32299,31698,32297 ,730,730,730 ,0,0,0}, {32301,32302,31697 ,730,730,730 ,0,0,0}, + {31709,32313,31711 ,730,730,730 ,0,0,0}, {31700,32295,32297 ,730,730,730 ,0,0,0}, + {31703,32272,32269 ,730,730,730 ,0,0,0}, {32268,31704,32269 ,730,730,730 ,0,0,0}, + {32320,32323,31717 ,730,730,730 ,0,0,0}, {31717,31714,32319 ,730,730,730 ,0,0,0}, + {31723,32651,32652 ,730,730,730 ,0,0,0}, {32649,32275,32273 ,730,730,730 ,0,0,0}, + {32652,32648,32653 ,730,730,730 ,0,0,0}, {31730,31728,31794 ,730,730,730 ,0,0,0}, + {31709,32310,32313 ,730,730,730 ,0,0,0}, {32647,32645,32278 ,730,730,730 ,0,0,0}, + {32654,32284,32646 ,730,730,730 ,0,0,0}, {32287,32642,32290 ,730,730,730 ,0,0,0}, + {32643,32285,32654 ,730,730,730 ,0,0,0}, {32644,32655,32293 ,730,730,730 ,0,0,0}, + {32648,32639,32656 ,730,730,730 ,0,0,0}, {32657,32656,32658 ,730,730,730 ,0,0,0}, + {32638,32637,32659 ,730,730,730 ,0,0,0}, {32660,32638,32659 ,730,730,730 ,0,0,0}, + {32661,32662,32262 ,730,730,730 ,0,0,0}, {32262,32660,32659 ,730,730,730 ,0,0,0}, + {32662,32341,32660 ,730,730,730 ,0,0,0}, {31900,32339,32663 ,730,730,730 ,0,0,0}, + {32205,32017,32019 ,730,730,730 ,0,0,0}, {31525,32209,31527 ,730,730,730 ,0,0,0}, + {32664,31059,32235 ,730,730,730 ,0,0,0}, {31806,31740,31737 ,730,730,730 ,0,0,0}, + {31745,31784,31785 ,730,730,730 ,0,0,0}, {31750,31747,31788 ,730,730,730 ,0,0,0}, + {31796,31728,31799 ,730,730,730 ,0,0,0}, {31732,31800,31731 ,730,730,730 ,0,0,0}, + {31779,31742,31777 ,730,730,730 ,0,0,0}, {31724,31778,31777 ,730,730,730 ,0,0,0}, + {31784,31744,31782 ,730,730,730 ,0,0,0}, {31751,31792,32259 ,730,730,730 ,0,0,0}, + {31745,31785,31747 ,730,730,730 ,0,0,0}, {32251,32587,32625 ,730,730,730 ,0,0,0}, + {32624,32258,32586 ,730,730,730 ,0,0,0}, {32247,32629,32248 ,730,730,730 ,0,0,0}, + {32628,32247,32245 ,730,730,730 ,0,0,0}, {32240,32664,32232 ,730,730,730 ,0,0,0}, + {32242,32630,32627 ,730,730,730 ,0,0,0}, {31790,31751,31750 ,730,730,730 ,0,0,0}, + {31753,32236,31059 ,730,730,730 ,0,0,0}, {31897,31895,32337 ,730,730,730 ,0,0,0}, + {32197,32008,32011 ,730,730,730 ,0,0,0}, {31998,32217,32219 ,730,730,730 ,0,0,0}, + {31762,31975,31759 ,730,730,730 ,0,0,0}, {31992,32213,31993 ,730,730,730 ,0,0,0}, + {32149,31547,31545 ,730,730,730 ,0,0,0}, {32213,32214,31993 ,730,730,730 ,0,0,0}, + {31992,32196,32213 ,730,730,730 ,0,0,0}, {32194,32008,32197 ,730,730,730 ,0,0,0}, + {32202,32013,32014 ,730,730,730 ,0,0,0}, {32203,32202,32014 ,730,730,730 ,0,0,0}, + {32634,32665,32666 ,730,730,730 ,0,0,0}, {32667,31043,32635 ,730,730,730 ,0,0,0}, + {32634,32666,32635 ,730,730,730 ,0,0,0}, {32203,32017,32205 ,730,730,730 ,0,0,0}, + {32636,32635,31043 ,730,730,730 ,0,0,0}, {32666,32632,32631 ,730,730,730 ,0,0,0}, + {32632,32666,32665 ,730,730,730 ,0,0,0}, {32211,31521,31523 ,730,730,730 ,0,0,0}, + {32014,32017,32203 ,730,730,730 ,0,0,0}, {32198,32011,32013 ,730,730,730 ,0,0,0}, + {32197,32011,32198 ,730,730,730 ,0,0,0}, {32196,32007,32194 ,730,730,730 ,0,0,0}, + {31886,32329,32327 ,730,730,730 ,0,0,0}, {32330,31887,31890 ,730,730,730 ,0,0,0}, + {31765,31976,31762 ,730,730,730 ,0,0,0}, {32668,32228,32669 ,730,730,730 ,0,0,0}, + {32225,32226,32005 ,730,730,730 ,0,0,0}, {31936,31535,32670 ,730,730,730 ,0,0,0}, + {32149,32146,31547 ,730,730,730 ,0,0,0}, {32671,32226,32228 ,730,730,730 ,0,0,0}, + {32151,31545,31538 ,730,730,730 ,0,0,0}, {32672,31543,32673 ,730,730,730 ,0,0,0}, + {31582,31580,31808 ,730,730,730 ,0,0,0}, {31558,31828,31826 ,730,730,730 ,0,0,0}, + {31588,31586,31815 ,730,730,730 ,0,0,0}, {32674,31591,32191 ,730,730,730 ,0,0,0}, + {32675,32182,32676 ,730,730,730 ,0,0,0}, {31825,31577,31826 ,730,730,730 ,0,0,0}, + {32677,32678,32187 ,730,730,730 ,0,0,0}, {32679,32680,32681 ,730,730,730 ,0,0,0}, + {31814,31586,31585 ,730,730,730 ,0,0,0}, {31579,31809,31580 ,730,730,730 ,0,0,0}, + {32172,32682,32683 ,730,730,730 ,0,0,0}, {31820,31591,31818 ,730,730,730 ,0,0,0}, + {32684,32676,32177 ,730,730,730 ,0,0,0}, {32685,32679,32686 ,730,730,730 ,0,0,0}, + {32687,32185,32678 ,730,730,730 ,0,0,0}, {32684,32183,32687 ,730,730,730 ,0,0,0}, + {32190,32681,32677 ,730,730,730 ,0,0,0}, {32183,32684,32179 ,730,730,730 ,0,0,0}, + {32674,32175,32683 ,730,730,730 ,0,0,0}, {32682,32171,32675 ,730,730,730 ,0,0,0}, + {31873,31926,31925 ,730,730,730 ,0,0,0}, {31582,31812,31585 ,730,730,730 ,0,0,0}, + {31591,31588,31818 ,730,730,730 ,0,0,0}, {31822,31579,31577 ,730,730,730 ,0,0,0}, + {32145,32143,31967 ,730,730,730 ,0,0,0}, {32138,32137,31961 ,730,730,730 ,0,0,0}, + {31964,32143,32142 ,730,730,730 ,0,0,0}, {31967,32143,31964 ,730,730,730 ,0,0,0}, + {32145,31969,32146 ,730,730,730 ,0,0,0}, {32688,31830,31562 ,730,730,730 ,0,0,0}, + {32689,32672,32673 ,730,730,730 ,0,0,0}, {31963,31964,32142 ,730,730,730 ,0,0,0}, + {31969,32145,31967 ,730,730,730 ,0,0,0}, {31571,31543,32690 ,730,730,730 ,0,0,0}, + {32691,31566,31568 ,730,730,730 ,0,0,0}, {31545,32151,32149 ,730,730,730 ,0,0,0}, + {31538,31541,32151 ,730,730,730 ,0,0,0}, {31543,31571,32673 ,730,730,730 ,0,0,0}, + {31547,32146,31969 ,730,730,730 ,0,0,0}, {32692,32693,32037 ,730,730,730 ,0,0,0}, + {32142,32138,31963 ,730,730,730 ,0,0,0}, {31963,32138,31961 ,730,730,730 ,0,0,0}, + {32031,31912,31904 ,730,730,730 ,0,0,0}, {31961,32137,31958 ,730,730,730 ,0,0,0}, + {31905,32025,32023 ,730,730,730 ,0,0,0}, {31957,31958,32134 ,730,730,730 ,0,0,0}, + {31943,31942,32153 ,730,730,730 ,0,0,0}, {32136,31942,31957 ,730,730,730 ,0,0,0}, + {32157,31948,31945 ,730,730,730 ,0,0,0}, {31945,31943,32154 ,730,730,730 ,0,0,0}, + {31932,31864,31930 ,730,730,730 ,0,0,0}, {31867,31870,31922 ,730,730,730 ,0,0,0}, + {31878,31934,31879 ,730,730,730 ,0,0,0}, {31935,32694,31881 ,730,730,730 ,0,0,0}, + {32695,31642,32696 ,730,730,730 ,0,0,0}, {32166,32697,31955 ,730,730,730 ,0,0,0}, + {31626,31861,31858 ,730,730,730 ,0,0,0}, {31649,31833,31652 ,730,730,730 ,0,0,0}, + {31626,31856,31644 ,730,730,730 ,0,0,0}, {32125,32128,32698 ,730,730,730 ,0,0,0}, + {32699,32109,32700 ,730,730,730 ,0,0,0}, {32701,32702,32124 ,730,730,730 ,0,0,0}, + {32108,32703,32704 ,730,730,730 ,0,0,0}, {31840,31841,31655 ,730,730,730 ,0,0,0}, + {32128,32130,32698 ,730,730,730 ,0,0,0}, {31652,31835,31653 ,730,730,730 ,0,0,0}, + {32123,32705,32701 ,730,730,730 ,0,0,0}, {32706,31846,32707 ,730,730,730 ,0,0,0}, + {32114,32708,32112 ,730,730,730 ,0,0,0}, {32117,32709,32119 ,730,730,730 ,0,0,0}, + {32700,32120,32709 ,730,730,730 ,0,0,0}, {32708,32114,32699 ,730,730,730 ,0,0,0}, + {32107,32710,32703 ,730,730,730 ,0,0,0}, {32710,32104,32708 ,730,730,730 ,0,0,0}, + {32124,32702,32117 ,730,730,730 ,0,0,0}, {32704,32707,31848 ,730,730,730 ,0,0,0}, + {32108,32704,32131 ,730,730,730 ,0,0,0}, {30481,31655,31841 ,730,730,730 ,0,0,0}, + {32706,30481,31844 ,730,730,730 ,0,0,0}, {32130,32711,32712 ,730,730,730 ,0,0,0}, + {32712,32698,32130 ,730,730,730 ,0,0,0}, {31834,31833,31649 ,730,730,730 ,0,0,0}, + {31653,31838,31655 ,730,730,730 ,0,0,0}, {31647,31646,31852 ,730,730,730 ,0,0,0}, + {31834,31647,31850 ,730,730,730 ,0,0,0}, {30497,32713,32714 ,730,730,730 ,0,0,0}, + {31855,31646,31644 ,730,730,730 ,0,0,0}, {31636,31642,32695 ,730,730,730 ,0,0,0}, + {31862,31630,32715 ,730,730,730 ,0,0,0}, {31878,31927,31934 ,730,730,730 ,0,0,0}, + {31634,31636,32695 ,730,730,730 ,0,0,0}, {32716,32717,32696 ,730,730,730 ,0,0,0}, + {32717,32716,32718 ,730,730,730 ,0,0,0}, {31548,31551,32099 ,730,730,730 ,0,0,0}, + {32099,32719,32718 ,730,730,730 ,0,0,0}, {32717,32718,32719 ,730,730,730 ,0,0,0}, + {32719,32099,31553 ,730,730,730 ,0,0,0}, {32168,31553,32720 ,730,730,730 ,0,0,0}, + {32052,32721,32054 ,730,730,730 ,0,0,0}, {32094,31658,32093 ,730,730,730 ,0,0,0}, + {32722,32058,32723 ,730,730,730 ,0,0,0}, {32054,32723,32055 ,730,730,730 ,0,0,0}, + {32606,32721,32052 ,730,730,730 ,0,0,0}, {32042,32724,32725 ,730,730,730 ,0,0,0}, + {32604,32046,32043 ,730,730,730 ,0,0,0}, {32071,31323,32726 ,730,730,730 ,0,0,0}, + {32603,32724,32039 ,730,730,730 ,0,0,0}, {32727,31679,31678 ,730,730,730 ,0,0,0}, + {32073,32075,31323 ,730,730,730 ,0,0,0}, {32091,31658,31664 ,730,730,730 ,0,0,0}, + {32087,32088,31662 ,730,730,730 ,0,0,0}, {32097,31678,31676 ,730,730,730 ,0,0,0}, + {32087,31665,32084 ,730,730,730 ,0,0,0}, {31681,32727,32728 ,730,730,730 ,0,0,0}, + {32079,31668,31674 ,730,730,730 ,0,0,0}, {31323,32071,32073 ,730,730,730 ,0,0,0}, + {32729,31684,32728 ,730,730,730 ,0,0,0}, {31685,31684,32729 ,730,730,730 ,0,0,0}, + {32042,32039,32724 ,730,730,730 ,0,0,0}, {32064,32061,32730 ,730,730,730 ,0,0,0}, + {32731,32059,32722 ,730,730,730 ,0,0,0}, {32064,32732,32065 ,730,730,730 ,0,0,0}, + {32730,32061,32731 ,730,730,730 ,0,0,0}, {32065,32732,32067 ,730,730,730 ,0,0,0}, + {31687,32733,31339 ,730,730,730 ,0,0,0}, {32729,32734,32735 ,730,730,730 ,0,0,0}, + {31687,31685,32733 ,730,730,730 ,0,0,0}, {32736,32734,32582 ,730,730,730 ,0,0,0}, + {32734,32736,32735 ,730,730,730 ,0,0,0}, {31865,31932,31927 ,730,730,730 ,0,0,0}, + {32736,32582,32098 ,730,730,730 ,0,0,0}, {31932,31865,31864 ,730,730,730 ,0,0,0}, + {31878,31865,31927 ,730,730,730 ,0,0,0}, {31864,31867,31930 ,730,730,730 ,0,0,0}, + {31922,31870,31925 ,730,730,730 ,0,0,0}, {31930,31867,31922 ,730,730,730 ,0,0,0}, + {31948,32159,31949 ,730,730,730 ,0,0,0}, {31942,32136,32153 ,730,730,730 ,0,0,0}, + {31911,31926,32737 ,730,730,730 ,0,0,0}, {31911,32737,31872 ,730,730,730 ,0,0,0}, + {31872,32021,31911 ,730,730,730 ,0,0,0}, {32026,31908,31910 ,730,730,730 ,0,0,0}, + {31951,31949,32160 ,730,730,730 ,0,0,0}, {31925,31870,31873 ,730,730,730 ,0,0,0}, + {32153,32154,31943 ,730,730,730 ,0,0,0}, {31951,32163,31954 ,730,730,730 ,0,0,0}, + {32154,32157,31945 ,730,730,730 ,0,0,0}, {32166,31955,32165 ,730,730,730 ,0,0,0}, + {32157,32159,31948 ,730,730,730 ,0,0,0}, {31557,32098,32390 ,730,730,730 ,0,0,0}, + {32160,32163,31951 ,730,730,730 ,0,0,0}, {31883,32738,32739 ,730,730,730 ,0,0,0}, + {31935,31879,31934 ,730,730,730 ,0,0,0}, {32694,32738,31881 ,730,730,730 ,0,0,0}, + {31879,31935,31881 ,730,730,730 ,0,0,0}, {31881,32738,31883 ,730,730,730 ,0,0,0}, + {32582,32583,32098 ,730,730,730 ,0,0,0}, {32739,32583,31883 ,730,730,730 ,0,0,0}, + {32740,32098,32741 ,730,730,730 ,0,0,0}, {32098,32583,32741 ,730,730,730 ,0,0,0}, + {32742,32098,32743 ,730,730,730 ,0,0,0}, {32098,32740,32743 ,730,730,730 ,0,0,0}, + {32098,32742,32390 ,730,730,730 ,0,0,0}, {32744,32166,32168 ,730,730,730 ,0,0,0}, + {32098,31557,32099 ,730,730,730 ,0,0,0}, {32099,31555,31548 ,730,730,730 ,0,0,0}, + {32099,31557,31555 ,730,730,730 ,0,0,0}, {31553,32168,32719 ,730,730,730 ,0,0,0}, + {31551,31553,32099 ,730,730,730 ,0,0,0}, {32720,32744,32168 ,730,730,730 ,0,0,0}, + {32744,32697,32166 ,730,730,730 ,0,0,0}, {31954,32165,31955 ,730,730,730 ,0,0,0}, + {32165,31954,32163 ,730,730,730 ,0,0,0}, {31949,32159,32160 ,730,730,730 ,0,0,0}, + {31957,32134,32136 ,730,730,730 ,0,0,0}, {31958,32137,32134 ,730,730,730 ,0,0,0}, + {32031,31904,32023 ,730,730,730 ,0,0,0}, {31911,32021,31910 ,730,730,730 ,0,0,0}, + {32033,31913,31912 ,730,730,730 ,0,0,0}, {31908,32026,32025 ,730,730,730 ,0,0,0}, + {31918,31915,32028 ,730,730,730 ,0,0,0}, {32023,31904,31905 ,730,730,730 ,0,0,0}, + {32037,32745,32746 ,730,730,730 ,0,0,0}, {32033,31912,32031 ,730,730,730 ,0,0,0}, + {31533,31572,31531 ,730,730,730 ,0,0,0}, {31913,32033,32028 ,730,730,730 ,0,0,0}, + {32690,31531,31571 ,730,730,730 ,0,0,0}, {32672,32747,31543 ,730,730,730 ,0,0,0}, + {32151,31541,32747 ,730,730,730 ,0,0,0}, {31543,32747,31541 ,730,730,730 ,0,0,0}, + {31535,31528,32670 ,730,730,730 ,0,0,0}, {32748,31531,32690 ,730,730,730 ,0,0,0}, + {32749,31572,31533 ,730,730,730 ,0,0,0}, {31936,31537,31535 ,730,730,730 ,0,0,0}, + {32750,32749,31533 ,730,730,730 ,0,0,0}, {32217,31998,31995 ,730,730,730 ,0,0,0}, + {31757,31982,31770 ,730,730,730 ,0,0,0}, {32751,32752,32613 ,730,730,730 ,0,0,0}, + {31984,31771,31977 ,730,730,730 ,0,0,0}, {31918,32035,32746 ,730,730,730 ,0,0,0}, + {32589,32753,31775 ,730,730,730 ,0,0,0}, {32621,32612,32611 ,730,730,730 ,0,0,0}, + {32752,32693,32692 ,730,730,730 ,0,0,0}, {32752,32692,32613 ,730,730,730 ,0,0,0}, + {32693,32745,32037 ,730,730,730 ,0,0,0}, {32746,32035,32037 ,730,730,730 ,0,0,0}, + {31918,32028,32035 ,730,730,730 ,0,0,0}, {31913,32028,31915 ,730,730,730 ,0,0,0}, + {32025,31905,31908 ,730,730,730 ,0,0,0}, {32021,32026,31910 ,730,730,730 ,0,0,0}, + {31765,31764,31893 ,730,730,730 ,0,0,0}, {31764,32325,31892 ,730,730,730 ,0,0,0}, + {32219,32220,31999 ,730,730,730 ,0,0,0}, {31976,31975,31762 ,730,730,730 ,0,0,0}, + {31995,31993,32214 ,730,730,730 ,0,0,0}, {32001,32220,32223 ,730,730,730 ,0,0,0}, + {31757,31756,31980 ,730,730,730 ,0,0,0}, {31972,31980,31756 ,730,730,730 ,0,0,0}, + {31998,32219,31999 ,730,730,730 ,0,0,0}, {31982,31977,31770 ,730,730,730 ,0,0,0}, + {32001,32223,32004 ,730,730,730 ,0,0,0}, {31984,31985,31771 ,730,730,730 ,0,0,0}, + {31770,31977,31771 ,730,730,730 ,0,0,0}, {31939,32342,31537 ,730,730,730 ,0,0,0}, + {32754,32617,32751 ,730,730,730 ,0,0,0}, {32751,32615,32754 ,730,730,730 ,0,0,0}, + {31985,32593,31773 ,730,730,730 ,0,0,0}, {32621,32611,32619 ,730,730,730 ,0,0,0}, + {32753,32614,32595 ,730,730,730 ,0,0,0}, {32589,32614,32753 ,730,730,730 ,0,0,0}, + {32618,32617,32754 ,730,730,730 ,0,0,0}, {32616,32755,32756 ,730,730,730 ,0,0,0}, + {32755,32616,32618 ,730,730,730 ,0,0,0}, {32756,32342,31939 ,730,730,730 ,0,0,0}, + {32755,32342,32756 ,730,730,730 ,0,0,0}, {31936,31939,31537 ,730,730,730 ,0,0,0}, + {31528,31531,32748 ,730,730,730 ,0,0,0}, {31528,32748,32670 ,730,730,730 ,0,0,0}, + {32757,31572,32749 ,730,730,730 ,0,0,0}, {32750,31533,32669 ,730,730,730 ,0,0,0}, + {32750,32669,32228 ,730,730,730 ,0,0,0}, {32668,32671,32228 ,730,730,730 ,0,0,0}, + {32671,32005,32226 ,730,730,730 ,0,0,0}, {32225,32005,32004 ,730,730,730 ,0,0,0}, + {32001,31999,32220 ,730,730,730 ,0,0,0}, {31992,32007,32196 ,730,730,730 ,0,0,0}, + {32007,32008,32194 ,730,730,730 ,0,0,0}, {32327,31894,31886 ,730,730,730 ,0,0,0}, + {31893,31764,31892 ,730,730,730 ,0,0,0}, {31894,32335,31895 ,730,730,730 ,0,0,0}, + {32325,32330,31890 ,730,730,730 ,0,0,0}, {32332,32339,31900 ,730,730,730 ,0,0,0}, + {31886,31887,32329 ,730,730,730 ,0,0,0}, {32327,32335,31894 ,730,730,730 ,0,0,0}, + {32337,31895,32335 ,730,730,730 ,0,0,0}, {32209,32206,31527 ,730,730,730 ,0,0,0}, + {32206,32019,31527 ,730,730,730 ,0,0,0}, {31518,32211,32209 ,730,730,730 ,0,0,0}, + {31518,32209,31525 ,730,730,730 ,0,0,0}, {31523,32633,32211 ,730,730,730 ,0,0,0}, + {31518,31521,32211 ,730,730,730 ,0,0,0}, {32261,32633,31523 ,730,730,730 ,0,0,0}, + {32758,32261,32759 ,730,730,730 ,0,0,0}, {32261,31523,32759 ,730,730,730 ,0,0,0}, + {32261,32758,32760 ,730,730,730 ,0,0,0}, {32261,31986,31988 ,730,730,730 ,0,0,0}, + {32261,32760,31986 ,730,730,730 ,0,0,0}, {32761,32339,32762 ,730,730,730 ,0,0,0}, + {32261,31988,32262 ,730,730,730 ,0,0,0}, {32262,32763,32641 ,730,730,730 ,0,0,0}, + {32262,31988,32763 ,730,730,730 ,0,0,0}, {32660,32262,32662 ,730,730,730 ,0,0,0}, + {32640,32661,32262 ,730,730,730 ,0,0,0}, {32341,32762,32339 ,730,730,730 ,0,0,0}, + {32662,32762,32341 ,730,730,730 ,0,0,0}, {32761,32663,32339 ,730,730,730 ,0,0,0}, + {31897,32332,31900 ,730,730,730 ,0,0,0}, {31897,32337,32332 ,730,730,730 ,0,0,0}, + {31887,32330,32329 ,730,730,730 ,0,0,0}, {31890,31892,32325 ,730,730,730 ,0,0,0}, + {32665,32634,32764 ,730,730,730 ,0,0,0}, {31802,31732,31734 ,730,730,730 ,0,0,0}, + {32623,32622,32764 ,730,730,730 ,0,0,0}, {32622,32665,32764 ,730,730,730 ,0,0,0}, + {32585,32584,32623 ,730,730,730 ,0,0,0}, {32258,32584,32586 ,730,730,730 ,0,0,0}, + {32256,32258,32624 ,730,730,730 ,0,0,0}, {32251,32253,32587 ,730,730,730 ,0,0,0}, + {32252,32251,32625 ,730,730,730 ,0,0,0}, {32245,32252,32626 ,730,730,730 ,0,0,0}, + {32247,32628,32629 ,730,730,730 ,0,0,0}, {32237,32248,32629 ,730,730,730 ,0,0,0}, + {32242,32237,32630 ,730,730,730 ,0,0,0}, {32240,32627,32664 ,730,730,730 ,0,0,0}, + {32235,32232,32664 ,730,730,730 ,0,0,0}, {32236,32235,31059 ,730,730,730 ,0,0,0}, + {32259,32236,31753 ,730,730,730 ,0,0,0}, {31790,31792,31751 ,730,730,730 ,0,0,0}, + {31788,31790,31750 ,730,730,730 ,0,0,0}, {31785,31788,31747 ,730,730,730 ,0,0,0}, + {31784,31745,31744 ,730,730,730 ,0,0,0}, {31779,31782,31744 ,730,730,730 ,0,0,0}, + {31777,31742,31724 ,730,730,730 ,0,0,0}, {31778,31724,31730 ,730,730,730 ,0,0,0}, + {31796,31794,31728 ,730,730,730 ,0,0,0}, {31794,31778,31730 ,730,730,730 ,0,0,0}, + {31731,31799,31728 ,730,730,730 ,0,0,0}, {31732,31802,31800 ,730,730,730 ,0,0,0}, + {31731,31800,31799 ,730,730,730 ,0,0,0}, {31734,31805,31802 ,730,730,730 ,0,0,0}, + {31740,31806,31734 ,730,730,730 ,0,0,0}, {31805,31734,31806 ,730,730,730 ,0,0,0}, + {31806,31737,32667 ,730,730,730 ,0,0,0}, {31043,32667,31737 ,730,730,730 ,0,0,0}, + {32650,32649,32273 ,730,730,730 ,0,0,0}, {32273,32272,32650 ,730,730,730 ,0,0,0}, + {32281,32280,32645 ,730,730,730 ,0,0,0}, {32278,32645,32280 ,730,730,730 ,0,0,0}, + {32284,32281,32646 ,730,730,730 ,0,0,0}, {32285,32284,32654 ,730,730,730 ,0,0,0}, + {32287,32285,32643 ,730,730,730 ,0,0,0}, {32642,32644,32291 ,730,730,730 ,0,0,0}, + {32291,32290,32642 ,730,730,730 ,0,0,0}, {32656,32765,32658 ,730,730,730 ,0,0,0}, + {32765,32655,32766 ,730,730,730 ,0,0,0}, {32655,32765,32293 ,730,730,730 ,0,0,0}, + {32766,32658,32765 ,730,730,730 ,0,0,0}, {32656,32657,32648 ,730,730,730 ,0,0,0}, + {32648,32652,32637 ,730,730,730 ,0,0,0}, {31723,32652,32653 ,730,730,730 ,0,0,0}, + {31720,32651,31723 ,730,730,730 ,0,0,0}, {31718,32323,31720 ,730,730,730 ,0,0,0}, + {32319,32320,31717 ,730,730,730 ,0,0,0}, {32317,32319,31714 ,730,730,730 ,0,0,0}, + {32314,32317,31712 ,730,730,730 ,0,0,0}, {32313,32314,31711 ,730,730,730 ,0,0,0}, + {32310,31690,32309 ,730,730,730 ,0,0,0}, {32305,32307,31696 ,730,730,730 ,0,0,0}, + {32307,32309,31690 ,730,730,730 ,0,0,0}, {31697,32302,31694 ,730,730,730 ,0,0,0}, + {31694,32305,31696 ,730,730,730 ,0,0,0}, {31698,32301,31697 ,730,730,730 ,0,0,0}, + {31698,31700,32297 ,730,730,730 ,0,0,0}, {31698,32299,32301 ,730,730,730 ,0,0,0}, + {31700,31707,32295 ,730,730,730 ,0,0,0}, {32265,31704,32268 ,730,730,730 ,0,0,0}, + {32295,31707,32265 ,730,730,730 ,0,0,0}, {32269,31704,31703 ,730,730,730 ,0,0,0}, + {32726,32603,32069 ,730,730,730 ,0,0,0}, {32726,32069,32071 ,730,730,730 ,0,0,0}, + {32043,32725,32604 ,730,730,730 ,0,0,0}, {32042,32725,32043 ,730,730,730 ,0,0,0}, + {32047,32046,32604 ,730,730,730 ,0,0,0}, {32049,32047,32605 ,730,730,730 ,0,0,0}, + {32052,32049,32606 ,730,730,730 ,0,0,0}, {32054,32721,32723 ,730,730,730 ,0,0,0}, + {32058,32055,32723 ,730,730,730 ,0,0,0}, {32059,32058,32722 ,730,730,730 ,0,0,0}, + {32061,32059,32731 ,730,730,730 ,0,0,0}, {32733,31685,32735 ,730,730,730 ,0,0,0}, + {32064,32730,32732 ,730,730,730 ,0,0,0}, {32767,32067,32732 ,730,730,730 ,0,0,0}, + {32067,32768,32769 ,730,730,730 ,0,0,0}, {32768,32067,32767 ,730,730,730 ,0,0,0}, + {32769,31339,32733 ,730,730,730 ,0,0,0}, {32768,31339,32769 ,730,730,730 ,0,0,0}, + {31685,32729,32735 ,730,730,730 ,0,0,0}, {31681,32728,31684 ,730,730,730 ,0,0,0}, + {31679,32727,31681 ,730,730,730 ,0,0,0}, {32097,32727,31678 ,730,730,730 ,0,0,0}, + {32094,32097,31676 ,730,730,730 ,0,0,0}, {32091,32093,31658 ,730,730,730 ,0,0,0}, + {32088,32091,31664 ,730,730,730 ,0,0,0}, {31665,32087,31662 ,730,730,730 ,0,0,0}, + {31662,32088,31664 ,730,730,730 ,0,0,0}, {31666,32084,31665 ,730,730,730 ,0,0,0}, + {31666,31668,32081 ,730,730,730 ,0,0,0}, {31666,32083,32084 ,730,730,730 ,0,0,0}, + {32079,31674,32076 ,730,730,730 ,0,0,0}, {32081,31668,32079 ,730,730,730 ,0,0,0}, + {32076,31671,32075 ,730,730,730 ,0,0,0}, {31323,32075,31671 ,730,730,730 ,0,0,0}, + {32713,32711,32130 ,730,730,730 ,0,0,0}, {30497,32711,32713 ,730,730,730 ,0,0,0}, + {32123,32125,32705 ,730,730,730 ,0,0,0}, {32125,32698,32705 ,730,730,730 ,0,0,0}, + {32124,32123,32701 ,730,730,730 ,0,0,0}, {32117,32702,32709 ,730,730,730 ,0,0,0}, + {32120,32119,32709 ,730,730,730 ,0,0,0}, {32109,32120,32700 ,730,730,730 ,0,0,0}, + {32114,32109,32699 ,730,730,730 ,0,0,0}, {32104,32112,32708 ,730,730,730 ,0,0,0}, + {32107,32104,32710 ,730,730,730 ,0,0,0}, {32108,32107,32703 ,730,730,730 ,0,0,0}, + {31848,32131,32704 ,730,730,730 ,0,0,0}, {31846,31848,32707 ,730,730,730 ,0,0,0}, + {31844,31846,32706 ,730,730,730 ,0,0,0}, {31841,31844,30481 ,730,730,730 ,0,0,0}, + {31838,31840,31655 ,730,730,730 ,0,0,0}, {31835,31838,31653 ,730,730,730 ,0,0,0}, + {31833,31835,31652 ,730,730,730 ,0,0,0}, {31834,31649,31647 ,730,730,730 ,0,0,0}, + {31852,31850,31647 ,730,730,730 ,0,0,0}, {31855,31852,31646 ,730,730,730 ,0,0,0}, + {31856,31855,31644 ,730,730,730 ,0,0,0}, {31632,31861,31626 ,730,730,730 ,0,0,0}, + {31858,31856,31626 ,730,730,730 ,0,0,0}, {31862,31632,31630 ,730,730,730 ,0,0,0}, + {31632,31862,31861 ,730,730,730 ,0,0,0}, {31630,31633,32715 ,730,730,730 ,0,0,0}, + {32695,32715,31634 ,730,730,730 ,0,0,0}, {31633,31634,32715 ,730,730,730 ,0,0,0}, + {32696,31642,32716 ,730,730,730 ,0,0,0}, {31639,32714,31642 ,730,730,730 ,0,0,0}, + {32716,31642,32714 ,730,730,730 ,0,0,0}, {30497,32714,31639 ,730,730,730 ,0,0,0}, + {32607,32600,32347 ,730,730,730 ,0,0,0}, {32607,32347,32346 ,730,730,730 ,0,0,0}, + {32353,32352,32609 ,730,730,730 ,0,0,0}, {32352,32608,32609 ,730,730,730 ,0,0,0}, + {32355,32353,32598 ,730,730,730 ,0,0,0}, {32358,32355,32599 ,730,730,730 ,0,0,0}, + {32359,32358,32596 ,730,730,730 ,0,0,0}, {32364,32361,32597 ,730,730,730 ,0,0,0}, + {32610,32591,32365 ,730,730,730 ,0,0,0}, {32365,32364,32610 ,730,730,730 ,0,0,0}, + {31622,32615,31625 ,730,730,730 ,0,0,0}, {32770,32590,32592 ,730,730,730 ,0,0,0}, + {32591,32590,32365 ,730,730,730 ,0,0,0}, {32619,32770,32620 ,730,730,730 ,0,0,0}, + {32770,32619,32590 ,730,730,730 ,0,0,0}, {32615,32751,31625 ,730,730,730 ,0,0,0}, + {32612,31625,32751 ,730,730,730 ,0,0,0}, {32612,32751,32613 ,730,730,730 ,0,0,0}, + {31622,32595,32615 ,730,730,730 ,0,0,0}, {31622,31620,32594 ,730,730,730 ,0,0,0}, + {31616,32602,31619 ,730,730,730 ,0,0,0}, {31614,32601,31616 ,730,730,730 ,0,0,0}, + {32389,32601,31613 ,730,730,730 ,0,0,0}, {32387,31611,31592 ,730,730,730 ,0,0,0}, + {32386,31592,31598 ,730,730,730 ,0,0,0}, {32381,32384,31596 ,730,730,730 ,0,0,0}, + {32384,32386,31598 ,730,730,730 ,0,0,0}, {31599,32378,32380 ,730,730,730 ,0,0,0}, + {31596,32380,32381 ,730,730,730 ,0,0,0}, {31600,32375,32378 ,730,730,730 ,0,0,0}, + {31602,31609,32374 ,730,730,730 ,0,0,0}, {31600,31602,32375 ,730,730,730 ,0,0,0}, + {32372,31606,32369 ,730,730,730 ,0,0,0}, {32374,31609,32372 ,730,730,730 ,0,0,0}, + {31605,32369,31606 ,730,730,730 ,0,0,0}, {32771,32689,32772 ,730,730,730 ,0,0,0}, + {32689,32673,32772 ,730,730,730 ,0,0,0}, {32685,32686,32771 ,730,730,730 ,0,0,0}, + {32686,32689,32771 ,730,730,730 ,0,0,0}, {32680,32679,32685 ,730,730,730 ,0,0,0}, + {32190,32679,32681 ,730,730,730 ,0,0,0}, {32187,32190,32677 ,730,730,730 ,0,0,0}, + {32185,32187,32678 ,730,730,730 ,0,0,0}, {32183,32185,32687 ,730,730,730 ,0,0,0}, + {32177,32179,32684 ,730,730,730 ,0,0,0}, {32182,32177,32676 ,730,730,730 ,0,0,0}, + {32171,32182,32675 ,730,730,730 ,0,0,0}, {32172,32171,32682 ,730,730,730 ,0,0,0}, + {32175,32172,32683 ,730,730,730 ,0,0,0}, {32191,32175,32674 ,730,730,730 ,0,0,0}, + {31820,32191,31591 ,730,730,730 ,0,0,0}, {31815,31818,31588 ,730,730,730 ,0,0,0}, + {31814,31815,31586 ,730,730,730 ,0,0,0}, {31812,31814,31585 ,730,730,730 ,0,0,0}, + {31808,31812,31582 ,730,730,730 ,0,0,0}, {31809,31808,31580 ,730,730,730 ,0,0,0}, + {31822,31809,31579 ,730,730,730 ,0,0,0}, {31825,31822,31577 ,730,730,730 ,0,0,0}, + {31564,31828,31558 ,730,730,730 ,0,0,0}, {31558,31826,31577 ,730,730,730 ,0,0,0}, + {31830,31564,31562 ,730,730,730 ,0,0,0}, {31564,31830,31828 ,730,730,730 ,0,0,0}, + {31562,31565,32688 ,730,730,730 ,0,0,0}, {32691,32688,31566 ,730,730,730 ,0,0,0}, + {31565,31566,32688 ,730,730,730 ,0,0,0}, {31568,31575,32691 ,730,730,730 ,0,0,0}, + {31572,32757,31575 ,730,730,730 ,0,0,0}, {32691,31575,32757 ,730,730,730 ,0,0,0}, + {31571,31531,31572 ,730,730,730 ,0,0,0}, {31980,31982,31757 ,730,730,730 ,0,0,0}, + {31926,31873,32737 ,730,730,730 ,0,0,0}, {31873,31872,32737 ,730,730,730 ,0,0,0}, + {31741,32521,32636 ,731,732,733 ,0,0,0}, {32529,32623,32528 ,734,735,736 ,0,0,0}, + {32764,32634,32517 ,737,738,739 ,0,0,0}, {32624,32527,32587 ,740,741,742 ,0,0,0}, + {32576,32575,32586 ,743,744,745 ,0,0,0}, {32525,32628,32626 ,746,747,748 ,0,0,0}, + {32526,32625,32518 ,749,750,751 ,0,0,0}, {32523,32630,32629 ,752,753,754 ,0,0,0}, + {32629,32628,32524 ,754,747,755 ,0,0,0}, {32630,32522,32627 ,753,756,757 ,0,0,0}, + {32522,32630,32523 ,756,753,752 ,0,0,0}, {32664,32627,32497 ,758,757,759 ,0,0,0}, + {32522,32497,32627 ,756,759,757 ,0,0,0}, {32496,31059,32664 ,760,761,758 ,0,0,0}, + {32664,32497,32496 ,758,759,760 ,0,0,0}, {31755,31059,32496 ,761,761,760 ,0,0,0}, + {32526,32525,32626 ,749,746,748 ,0,0,0}, {32628,32525,32524 ,747,746,755 ,0,0,0}, + {32523,32629,32524 ,752,754,755 ,0,0,0}, {32526,32626,32625 ,749,748,750 ,0,0,0}, + {32518,32625,32587 ,751,750,742 ,0,0,0}, {32527,32624,32575 ,741,740,744 ,0,0,0}, + {32527,32518,32587 ,741,751,742 ,0,0,0}, {32576,32586,32585 ,743,745,762 ,0,0,0}, + {32586,32575,32624 ,745,744,740 ,0,0,0}, {32585,32623,32529 ,762,735,734 ,0,0,0}, + {32585,32529,32576 ,762,734,743 ,0,0,0}, {32517,32528,32764 ,739,736,737 ,0,0,0}, + {32623,32764,32528 ,735,737,736 ,0,0,0}, {32634,32521,32517 ,738,732,739 ,0,0,0}, + {31741,32636,31043 ,731,733,35 ,0,0,0}, {32521,32634,32636 ,732,738,733 ,0,0,0}, + {31708,32409,32650 ,763,764,765 ,0,0,0}, {32406,32645,32405 ,766,767,768 ,0,0,0}, + {32647,32649,32407 ,769,770,771 ,0,0,0}, {32643,32400,32642 ,772,773,774 ,0,0,0}, + {32536,32401,32654 ,775,776,777 ,0,0,0}, {32533,32766,32655 ,778,779,780 ,0,0,0}, + {32532,32644,32535 ,781,782,783 ,0,0,0}, {32542,32657,32658 ,784,785,786 ,0,0,0}, + {32658,32766,32538 ,786,779,787 ,0,0,0}, {32657,32539,32648 ,785,788,789 ,0,0,0}, + {32539,32657,32542 ,788,785,784 ,0,0,0}, {32653,32648,32541 ,790,789,791 ,0,0,0}, + {32539,32541,32648 ,788,791,789 ,0,0,0}, {32509,31723,32653 ,792,793,790 ,0,0,0}, + {32653,32541,32509 ,790,791,792 ,0,0,0}, {31722,31723,32509 ,793,793,792 ,0,0,0}, + {32532,32533,32655 ,781,778,780 ,0,0,0}, {32766,32533,32538 ,779,778,787 ,0,0,0}, + {32542,32658,32538 ,784,786,787 ,0,0,0}, {32532,32655,32644 ,781,780,782 ,0,0,0}, + {32535,32644,32642 ,783,782,774 ,0,0,0}, {32400,32643,32401 ,773,772,776 ,0,0,0}, + {32400,32535,32642 ,773,783,774 ,0,0,0}, {32536,32654,32646 ,775,777,794 ,0,0,0}, + {32654,32401,32643 ,777,776,772 ,0,0,0}, {32646,32645,32406 ,794,767,766 ,0,0,0}, + {32646,32406,32536 ,794,766,775 ,0,0,0}, {32407,32405,32647 ,771,768,769 ,0,0,0}, + {32645,32647,32405 ,767,769,768 ,0,0,0}, {32649,32409,32407 ,770,764,771 ,0,0,0}, + {31708,32650,31703 ,763,765,126 ,0,0,0}, {32409,32649,32650 ,764,770,765 ,0,0,0}, + {31675,32447,32726 ,763,795,796 ,0,0,0}, {32449,32725,32448 ,797,798,799 ,0,0,0}, + {32724,32603,32446 ,800,801,802 ,0,0,0}, {32606,32450,32721 ,803,804,805 ,0,0,0}, + {32445,32451,32605 ,806,807,808 ,0,0,0}, {32402,32731,32722 ,809,810,811 ,0,0,0}, + {32403,32723,32452 ,812,813,814 ,0,0,0}, {32444,32732,32730 ,815,816,817 ,0,0,0}, + {32730,32731,32443 ,817,810,818 ,0,0,0}, {32732,32454,32767 ,816,819,820 ,0,0,0}, + {32454,32732,32444 ,819,816,815 ,0,0,0}, {32768,32767,32453 ,821,820,822 ,0,0,0}, + {32454,32453,32767 ,819,822,820 ,0,0,0}, {32442,31339,32768 ,823,793,821 ,0,0,0}, + {32768,32453,32442 ,821,822,823 ,0,0,0}, {31689,31339,32442 ,793,793,823 ,0,0,0}, + {32403,32402,32722 ,812,809,811 ,0,0,0}, {32731,32402,32443 ,810,809,818 ,0,0,0}, + {32444,32730,32443 ,815,817,818 ,0,0,0}, {32403,32722,32723 ,812,811,813 ,0,0,0}, + {32452,32723,32721 ,814,813,805 ,0,0,0}, {32450,32606,32451 ,804,803,807 ,0,0,0}, + {32450,32452,32721 ,804,814,805 ,0,0,0}, {32445,32605,32604 ,806,808,824 ,0,0,0}, + {32605,32451,32606 ,808,807,803 ,0,0,0}, {32604,32725,32449 ,824,798,797 ,0,0,0}, + {32604,32449,32445 ,824,797,806 ,0,0,0}, {32446,32448,32724 ,802,799,800 ,0,0,0}, + {32725,32724,32448 ,798,800,799 ,0,0,0}, {32603,32447,32446 ,801,795,802 ,0,0,0}, + {31675,32726,31323 ,763,796,126 ,0,0,0}, {32447,32603,32726 ,795,801,796 ,0,0,0}, + {31643,32577,32711 ,731,795,796 ,0,0,0}, {32475,32705,32476 ,825,826,799 ,0,0,0}, + {32698,32712,32477 ,827,828,829 ,0,0,0}, {32709,32431,32700 ,830,831,805 ,0,0,0}, + {32472,32432,32702 ,832,833,834 ,0,0,0}, {32430,32710,32708 ,835,836,837 ,0,0,0}, + {32429,32699,32470 ,838,839,814 ,0,0,0}, {32466,32704,32703 ,840,841,842 ,0,0,0}, + {32703,32710,32465 ,842,836,843 ,0,0,0}, {32704,32469,32707 ,841,844,845 ,0,0,0}, + {32469,32704,32466 ,844,841,840 ,0,0,0}, {32706,32707,32467 ,846,845,847 ,0,0,0}, + {32469,32467,32707 ,844,847,845 ,0,0,0}, {32468,30481,32706 ,848,761,846 ,0,0,0}, + {32706,32467,32468 ,846,847,848 ,0,0,0}, {31657,30481,32468 ,761,761,848 ,0,0,0}, + {32429,32430,32708 ,838,835,837 ,0,0,0}, {32710,32430,32465 ,836,835,843 ,0,0,0}, + {32466,32703,32465 ,840,842,843 ,0,0,0}, {32429,32708,32699 ,838,837,839 ,0,0,0}, + {32470,32699,32700 ,814,839,805 ,0,0,0}, {32431,32709,32432 ,831,830,833 ,0,0,0}, + {32431,32470,32700 ,831,814,805 ,0,0,0}, {32472,32702,32701 ,832,834,849 ,0,0,0}, + {32702,32432,32709 ,834,833,830 ,0,0,0}, {32701,32705,32475 ,849,826,825 ,0,0,0}, + {32701,32475,32472 ,849,825,832 ,0,0,0}, {32477,32476,32698 ,829,799,827 ,0,0,0}, + {32705,32698,32476 ,826,827,799 ,0,0,0}, {32712,32577,32477 ,828,795,829 ,0,0,0}, + {31643,32711,30497 ,731,796,35 ,0,0,0}, {32577,32712,32711 ,795,828,796 ,0,0,0}, + {31610,32392,32607 ,850,851,852 ,0,0,0}, {32408,32609,32404 ,853,854,855 ,0,0,0}, + {32608,32600,32396 ,856,801,857 ,0,0,0}, {32596,32412,32597 ,830,858,859 ,0,0,0}, + {32410,32411,32599 ,860,861,862 ,0,0,0}, {32415,32592,32591 ,863,864,865 ,0,0,0}, + {32414,32610,32413 ,866,867,868 ,0,0,0}, {32422,32620,32770 ,869,870,871 ,0,0,0}, + {32770,32592,32417 ,871,864,872 ,0,0,0}, {32620,32579,32621 ,870,873,874 ,0,0,0}, + {32579,32620,32422 ,873,870,869 ,0,0,0}, {32612,32621,32420 ,875,874,876 ,0,0,0}, + {32579,32420,32621 ,873,876,874 ,0,0,0}, {32418,31625,32612 ,877,82,875 ,0,0,0}, + {32612,32420,32418 ,875,876,877 ,0,0,0}, {31624,31625,32418 ,878,82,877 ,0,0,0}, + {32414,32415,32591 ,866,863,865 ,0,0,0}, {32592,32415,32417 ,864,863,872 ,0,0,0}, + {32422,32770,32417 ,869,871,872 ,0,0,0}, {32414,32591,32610 ,866,865,867 ,0,0,0}, + {32413,32610,32597 ,868,867,859 ,0,0,0}, {32412,32596,32411 ,858,830,861 ,0,0,0}, + {32412,32413,32597 ,858,868,859 ,0,0,0}, {32410,32599,32598 ,860,862,879 ,0,0,0}, + {32599,32411,32596 ,862,861,830 ,0,0,0}, {32598,32609,32408 ,879,854,853 ,0,0,0}, + {32598,32408,32410 ,879,853,860 ,0,0,0}, {32396,32404,32608 ,857,855,856 ,0,0,0}, + {32609,32608,32404 ,854,856,855 ,0,0,0}, {32600,32392,32396 ,801,851,857 ,0,0,0}, + {31610,32607,31605 ,850,852,850 ,0,0,0}, {32392,32600,32607 ,851,801,852 ,0,0,0}, + {31576,32486,32673 ,731,851,880 ,0,0,0}, {32581,32685,32490 ,881,882,855 ,0,0,0}, + {32771,32772,32485 ,856,801,857 ,0,0,0}, {32677,32488,32678 ,883,884,859 ,0,0,0}, + {32580,32500,32681 ,860,885,834 ,0,0,0}, {32495,32676,32684 ,886,887,888 ,0,0,0}, + {32393,32687,32489 ,889,890,868 ,0,0,0}, {32493,32682,32675 ,891,892,893 ,0,0,0}, + {32675,32676,32494 ,893,887,894 ,0,0,0}, {32682,32492,32683 ,892,895,896 ,0,0,0}, + {32492,32682,32493 ,895,892,891 ,0,0,0}, {32674,32683,32491 ,897,896,898 ,0,0,0}, + {32492,32491,32683 ,895,898,896 ,0,0,0}, {32474,31591,32674 ,899,761,897 ,0,0,0}, + {32674,32491,32474 ,897,898,899 ,0,0,0}, {31590,31591,32474 ,761,761,899 ,0,0,0}, + {32393,32495,32684 ,889,886,888 ,0,0,0}, {32676,32495,32494 ,887,886,894 ,0,0,0}, + {32493,32675,32494 ,891,893,894 ,0,0,0}, {32393,32684,32687 ,889,888,890 ,0,0,0}, + {32489,32687,32678 ,868,890,859 ,0,0,0}, {32488,32677,32500 ,884,883,885 ,0,0,0}, + {32488,32489,32678 ,884,868,859 ,0,0,0}, {32580,32681,32680 ,860,834,849 ,0,0,0}, + {32681,32500,32677 ,834,885,883 ,0,0,0}, {32680,32685,32581 ,849,882,881 ,0,0,0}, + {32680,32581,32580 ,849,881,860 ,0,0,0}, {32485,32490,32771 ,857,855,856 ,0,0,0}, + {32685,32771,32490 ,882,856,855 ,0,0,0}, {32772,32486,32485 ,801,851,857 ,0,0,0}, + {31576,32673,31571 ,731,880,35 ,0,0,0}, {32486,32772,32673 ,851,801,880 ,0,0,0}, + {31554,32480,32720 ,20,900,900 ,0,0,0}, {32464,31955,32697 ,901,336,901 ,0,0,0}, + {32697,32744,32555 ,901,902,902 ,0,0,0}, {31956,31955,32464 ,336,336,901 ,0,0,0}, + {32480,32744,32720 ,900,902,900 ,0,0,0}, {32744,32480,32555 ,902,900,902 ,0,0,0}, + {32464,32697,32555 ,901,901,902 ,0,0,0}, {32720,31553,31554 ,900,20,20 ,0,0,0}, + {32741,32583,32460 ,903,904,905 ,0,0,0}, {32459,32436,32740 ,906,907,908 ,0,0,0}, + {32459,32740,32741 ,906,908,903 ,0,0,0}, {32459,32741,32460 ,906,903,905 ,0,0,0}, + {32742,32743,32435 ,909,910,911 ,0,0,0}, {32743,32436,32435 ,910,907,911 ,0,0,0}, + {32740,32436,32743 ,908,907,910 ,0,0,0}, {32461,32391,32390 ,912,21,21 ,0,0,0}, + {32461,32390,32742 ,912,21,909 ,0,0,0}, {32435,32461,32742 ,911,912,909 ,0,0,0}, + {32460,32583,32558 ,905,904,913 ,0,0,0}, {32556,32558,32739 ,914,913,915 ,0,0,0}, + {32583,32739,32558 ,904,915,913 ,0,0,0}, {32738,32557,32556 ,916,917,914 ,0,0,0}, + {32556,32739,32738 ,914,915,916 ,0,0,0}, {32557,32694,31933 ,917,918,322 ,0,0,0}, + {32694,32557,32738 ,918,917,916 ,0,0,0}, {32694,31935,31933 ,918,322,322 ,0,0,0}, + {31544,32574,32690 ,15,919,920 ,0,0,0}, {32505,31936,32670 ,921,922,921 ,0,0,0}, + {32670,32748,32499 ,921,923,923 ,0,0,0}, {31937,31936,32505 ,924,922,921 ,0,0,0}, + {32574,32748,32690 ,919,923,920 ,0,0,0}, {32748,32574,32499 ,923,919,923 ,0,0,0}, + {32505,32670,32499 ,921,921,923 ,0,0,0}, {32690,31543,31544 ,920,15,15 ,0,0,0}, + {31534,32506,32669 ,8,925,925 ,0,0,0}, {32481,32005,32671 ,926,372,926 ,0,0,0}, + {32671,32668,32573 ,926,927,927 ,0,0,0}, {32006,32005,32481 ,372,372,926 ,0,0,0}, + {32506,32668,32669 ,925,927,925 ,0,0,0}, {32668,32506,32573 ,927,925,927 ,0,0,0}, + {32481,32671,32573 ,926,926,927 ,0,0,0}, {32669,31533,31534 ,925,8,8 ,0,0,0}, + {32752,32751,32419 ,928,929,930 ,0,0,0}, {32752,32559,32693 ,928,931,932 ,0,0,0}, + {32559,32752,32419 ,931,928,930 ,0,0,0}, {32426,32745,32551 ,933,934,935 ,0,0,0}, + {32551,32745,32693 ,935,934,932 ,0,0,0}, {31918,32746,32425 ,314,936,937 ,0,0,0}, + {32425,31919,31918 ,937,314,314 ,0,0,0}, {32425,32746,32426 ,937,936,933 ,0,0,0}, + {32426,32746,32745 ,933,936,934 ,0,0,0}, {32693,32559,32551 ,932,931,935 ,0,0,0}, + {32419,32751,32560 ,930,929,938 ,0,0,0}, {32503,32560,32617 ,939,938,940 ,0,0,0}, + {32751,32617,32560 ,929,940,938 ,0,0,0}, {32616,32504,32503 ,941,942,939 ,0,0,0}, + {32503,32617,32616 ,939,940,941 ,0,0,0}, {32504,32756,31938 ,942,943,944 ,0,0,0}, + {32756,32504,32616 ,943,942,941 ,0,0,0}, {32756,31939,31938 ,943,324,944 ,0,0,0}, + {32615,32614,32549 ,945,946,947 ,0,0,0}, {32615,32428,32754 ,945,948,949 ,0,0,0}, + {32428,32615,32549 ,948,945,947 ,0,0,0}, {32548,32618,32427 ,950,951,952 ,0,0,0}, + {32427,32618,32754 ,952,951,949 ,0,0,0}, {32342,32755,32502 ,953,954,955 ,0,0,0}, + {32502,32343,32342 ,955,21,953 ,0,0,0}, {32502,32755,32548 ,955,954,950 ,0,0,0}, + {32548,32755,32618 ,950,954,951 ,0,0,0}, {32754,32428,32427 ,949,948,952 ,0,0,0}, + {32549,32614,32508 ,947,946,956 ,0,0,0}, {32562,32508,32589 ,957,956,958 ,0,0,0}, + {32614,32589,32508 ,946,958,956 ,0,0,0}, {32588,32563,32562 ,959,960,957 ,0,0,0}, + {32562,32589,32588 ,957,958,959 ,0,0,0}, {32563,32593,31983 ,960,961,358 ,0,0,0}, + {32593,32563,32588 ,961,960,959 ,0,0,0}, {32593,31985,31983 ,961,358,358 ,0,0,0}, + {32662,32661,32569 ,962,963,964 ,0,0,0}, {32547,32566,32762 ,965,966,967 ,0,0,0}, + {32547,32762,32662 ,965,967,962 ,0,0,0}, {32547,32662,32569 ,965,962,964 ,0,0,0}, + {32663,32761,32567 ,968,969,970 ,0,0,0}, {32761,32566,32567 ,969,966,970 ,0,0,0}, + {32762,32566,32761 ,967,966,969 ,0,0,0}, {32513,31901,31900 ,971,304,304 ,0,0,0}, + {32513,31900,32663 ,971,304,968 ,0,0,0}, {32567,32513,32663 ,970,971,968 ,0,0,0}, + {32569,32661,32568 ,964,963,972 ,0,0,0}, {32571,32568,32640 ,973,972,974 ,0,0,0}, + {32661,32640,32568 ,963,974,972 ,0,0,0}, {32641,32570,32571 ,975,976,973 ,0,0,0}, + {32571,32640,32641 ,973,974,975 ,0,0,0}, {32570,32763,31987 ,976,977,324 ,0,0,0}, + {32763,32570,32641 ,977,976,975 ,0,0,0}, {32763,31988,31987 ,977,978,324 ,0,0,0}, + {31524,32516,32759 ,3,979,979 ,0,0,0}, {32572,31986,32760 ,980,324,980 ,0,0,0}, + {32760,32758,32515 ,980,981,981 ,0,0,0}, {31989,31986,32572 ,982,324,980 ,0,0,0}, + {32516,32758,32759 ,979,981,979 ,0,0,0}, {32758,32516,32515 ,981,979,981 ,0,0,0}, + {32572,32760,32515 ,980,980,981 ,0,0,0}, {32759,31523,31524 ,979,3,3 ,0,0,0}, + {32666,32399,32635 ,983,983,984 ,0,0,0}, {32520,32519,32667 ,984,985,986 ,0,0,0}, + {32635,32520,32667 ,984,984,986 ,0,0,0}, {32519,31807,31806 ,985,235,235 ,0,0,0}, + {32667,32519,31806 ,986,985,235 ,0,0,0}, {32635,32399,32520 ,984,983,984 ,0,0,0}, + {32514,32399,32666 ,987,983,983 ,0,0,0}, {32514,32631,32263 ,987,987,988 ,0,0,0}, + {32631,32514,32666 ,987,987,983 ,0,0,0}, {32631,32261,32263 ,987,988,988 ,0,0,0}, + {32530,32398,32665 ,989,990,990 ,0,0,0}, {32397,32633,32632 ,991,992,991 ,0,0,0}, + {32665,32398,32632 ,990,990,991 ,0,0,0}, {32210,32211,32534 ,508,508,992 ,0,0,0}, + {32633,32397,32534 ,992,991,992 ,0,0,0}, {32534,32211,32633 ,992,508,992 ,0,0,0}, + {32397,32632,32398 ,991,991,990 ,0,0,0}, {32665,32622,32530 ,990,989,989 ,0,0,0}, + {32622,32584,32531 ,989,993,994 ,0,0,0}, {32531,32530,32622 ,994,989,989 ,0,0,0}, + {32257,32584,32258 ,546,993,546 ,0,0,0}, {32584,32257,32531 ,993,546,994 ,0,0,0}, + {32482,32395,32757 ,995,996,996 ,0,0,0}, {32394,32688,32691 ,997,998,997 ,0,0,0}, + {32757,32395,32691 ,996,996,997 ,0,0,0}, {31831,31830,32498 ,257,257,998 ,0,0,0}, + {32688,32394,32498 ,998,997,998 ,0,0,0}, {32498,31830,32688 ,998,257,998 ,0,0,0}, + {32394,32691,32395 ,997,997,996 ,0,0,0}, {32757,32749,32482 ,996,995,995 ,0,0,0}, + {32749,32750,32483 ,995,999,999 ,0,0,0}, {32483,32482,32749 ,999,995,995 ,0,0,0}, + {32229,32750,32228 ,525,999,525 ,0,0,0}, {32750,32229,32483 ,999,525,999 ,0,0,0}, + {32565,32484,32689 ,1000,1001,1001 ,0,0,0}, {32487,32747,32672 ,1002,1003,1004 ,0,0,0}, + {32689,32484,32672 ,1001,1001,1004 ,0,0,0}, {32150,32151,32564 ,508,508,1003 ,0,0,0}, + {32747,32487,32564 ,1003,1002,1003 ,0,0,0}, {32564,32151,32747 ,1003,508,1003 ,0,0,0}, + {32487,32672,32484 ,1002,1004,1001 ,0,0,0}, {32689,32686,32565 ,1001,1000,1000 ,0,0,0}, + {32686,32679,32501 ,1000,1005,1005 ,0,0,0}, {32501,32565,32686 ,1005,1000,1000 ,0,0,0}, + {32189,32679,32190 ,546,1005,546 ,0,0,0}, {32679,32189,32501 ,1005,546,1005 ,0,0,0}, + {32478,32473,32696 ,1006,1007,1007 ,0,0,0}, {32433,32715,32695 ,1008,1009,1008 ,0,0,0}, + {32696,32473,32695 ,1007,1007,1008 ,0,0,0}, {31863,31862,32471 ,257,257,1009 ,0,0,0}, + {32715,32433,32471 ,1009,1008,1009 ,0,0,0}, {32471,31862,32715 ,1009,257,1009 ,0,0,0}, + {32433,32695,32473 ,1008,1008,1007 ,0,0,0}, {32696,32717,32478 ,1007,1006,1006 ,0,0,0}, + {32717,32719,32462 ,1006,1010,1010 ,0,0,0}, {32462,32478,32717 ,1010,1006,1006 ,0,0,0}, + {32169,32719,32168 ,525,1010,525 ,0,0,0}, {32719,32169,32462 ,1010,525,1010 ,0,0,0}, + {32714,32434,32716 ,1011,1011,1012 ,0,0,0}, {32479,32463,32718 ,1012,1013,1013 ,0,0,0}, + {32716,32479,32718 ,1012,1012,1013 ,0,0,0}, {32463,32100,32099 ,1013,324,324 ,0,0,0}, + {32718,32463,32099 ,1013,1013,324 ,0,0,0}, {32716,32434,32479 ,1012,1011,1012 ,0,0,0}, + {32578,32434,32714 ,1014,1011,1011 ,0,0,0}, {32578,32713,32129 ,1014,1014,488 ,0,0,0}, + {32713,32578,32714 ,1014,1014,1011 ,0,0,0}, {32713,32130,32129 ,1014,488,488 ,0,0,0}, + {32735,32440,32733 ,1015,1015,1016 ,0,0,0}, {32456,32441,32769 ,1016,1017,1017 ,0,0,0}, + {32733,32456,32769 ,1016,1016,1017 ,0,0,0}, {32441,32068,32067 ,1017,427,427 ,0,0,0}, + {32769,32441,32067 ,1017,1017,427 ,0,0,0}, {32733,32440,32456 ,1016,1015,1016 ,0,0,0}, + {32457,32440,32735 ,1018,1015,1015 ,0,0,0}, {32457,32736,32101 ,1018,1018,1019 ,0,0,0}, + {32736,32457,32735 ,1018,1018,1015 ,0,0,0}, {32736,32098,32101 ,1018,324,1019 ,0,0,0}, + {32455,32439,32729 ,1020,1021,1021 ,0,0,0}, {32438,32582,32734 ,1022,1023,1022 ,0,0,0}, + {32729,32439,32734 ,1021,1021,1022 ,0,0,0}, {31882,31883,32458 ,205,205,1023 ,0,0,0}, + {32582,32438,32458 ,1023,1022,1023 ,0,0,0}, {32458,31883,32582 ,1023,205,1023 ,0,0,0}, + {32438,32734,32439 ,1022,1022,1021 ,0,0,0}, {32729,32728,32455 ,1021,1020,1020 ,0,0,0}, + {32728,32727,32437 ,1020,1024,1024 ,0,0,0}, {32437,32455,32728 ,1024,1020,1020 ,0,0,0}, + {32096,32727,32097 ,456,1024,456 ,0,0,0}, {32727,32096,32437 ,1024,456,1024 ,0,0,0}, + {32553,32421,32611 ,1025,1026,1026 ,0,0,0}, {32423,32590,32619 ,1027,1028,1027 ,0,0,0}, + {32611,32421,32619 ,1026,1026,1027 ,0,0,0}, {32367,32365,32416 ,641,641,1028 ,0,0,0}, + {32590,32423,32416 ,1028,1027,1028 ,0,0,0}, {32416,32365,32590 ,1028,641,1028 ,0,0,0}, + {32423,32619,32421 ,1027,1027,1026 ,0,0,0}, {32611,32613,32553 ,1026,1025,1025 ,0,0,0}, + {32613,32692,32552 ,1025,1029,1029 ,0,0,0}, {32552,32553,32613 ,1029,1025,1025 ,0,0,0}, + {32036,32692,32037 ,396,1029,396 ,0,0,0}, {32692,32036,32552 ,1029,396,1029 ,0,0,0}, + {32424,32561,32594 ,1030,1031,1031 ,0,0,0}, {32550,32753,32595 ,1032,1033,1032 ,0,0,0}, + {32594,32561,32595 ,1031,1031,1032 ,0,0,0}, {31774,31775,32507 ,205,205,1033 ,0,0,0}, + {32753,32550,32507 ,1033,1032,1033 ,0,0,0}, {32507,31775,32753 ,1033,205,1033 ,0,0,0}, + {32550,32595,32561 ,1032,1032,1031 ,0,0,0}, {32594,32602,32424 ,1031,1030,1030 ,0,0,0}, + {32602,32601,32554 ,1030,1034,1034 ,0,0,0}, {32554,32424,32602 ,1034,1030,1030 ,0,0,0}, + {32388,32601,32389 ,456,1034,456 ,0,0,0}, {32601,32388,32554 ,1034,456,1034 ,0,0,0}, + {32546,32544,32639 ,1035,1036,1036 ,0,0,0}, {32540,32765,32656 ,1037,1038,1037 ,0,0,0}, + {32639,32544,32656 ,1036,1036,1037 ,0,0,0}, {32294,32293,32537 ,641,641,1038 ,0,0,0}, + {32765,32540,32537 ,1038,1037,1038 ,0,0,0}, {32537,32293,32765 ,1038,641,1038 ,0,0,0}, + {32540,32656,32544 ,1037,1037,1036 ,0,0,0}, {32639,32638,32546 ,1036,1035,1035 ,0,0,0}, + {32638,32660,32511 ,1035,1039,1040 ,0,0,0}, {32511,32546,32638 ,1040,1035,1035 ,0,0,0}, + {32340,32660,32341 ,396,1039,396 ,0,0,0}, {32660,32340,32511 ,1039,396,1040 ,0,0,0}, + {32652,32510,32637 ,1041,1041,1042 ,0,0,0}, {32543,32512,32659 ,1042,1043,1044 ,0,0,0}, + {32637,32543,32659 ,1042,1042,1044 ,0,0,0}, {32512,32260,32262 ,1043,1045,1045 ,0,0,0}, + {32659,32512,32262 ,1044,1043,1045 ,0,0,0}, {32637,32510,32543 ,1042,1041,1042 ,0,0,0}, + {32545,32510,32652 ,1046,1041,1041 ,0,0,0}, {32545,32651,32322 ,1046,1046,670 ,0,0,0}, + {32651,32545,32652 ,1046,1046,1041 ,0,0,0}, {32651,32323,32322 ,1046,670,670 ,0,0,0} +// M3abstandhalter10mm.prt + , {32773,32452,32774 ,18258,18259,18260 ,0,0,0}, {32775,32776,32777 ,18261,18262,18263 ,0,0,0}, + {32774,32452,32777 ,18260,18259,18263 ,0,0,0}, {32776,32775,32778 ,18262,18261,18264 ,0,0,0}, + {32778,32779,32776 ,18264,18265,18262 ,0,0,0}, {32779,32780,32781 ,18265,18266,18267 ,0,0,0}, + {32778,32780,32779 ,18264,18266,18265 ,0,0,0}, {32775,32777,32452 ,18261,18263,18259 ,0,0,0}, + {32782,32783,32784 ,18268,18269,18270 ,0,0,0}, {32783,32781,32784 ,18269,18267,18270 ,0,0,0}, + {32782,32785,32786 ,18268,18271,18272 ,0,0,0}, {32786,32783,32782 ,18272,18269,18268 ,0,0,0}, + {32785,32787,32788 ,18271,18273,18274 ,0,0,0}, {32785,32788,32786 ,18271,18274,18272 ,0,0,0}, + {32780,32784,32781 ,18266,18270,18267 ,0,0,0}, {32789,32788,32787 ,18275,18274,18273 ,0,0,0}, + {32790,31675,32791 ,18276,18277,126 ,0,0,0}, {32790,32791,32789 ,18276,126,18275 ,0,0,0}, + {32787,32790,32789 ,18273,18276,18275 ,0,0,0}, {32773,32774,32792 ,18258,18260,18278 ,0,0,0}, + {32792,32793,32794 ,18278,18279,18280 ,0,0,0}, {32794,32773,32792 ,18280,18258,18278 ,0,0,0}, + {32795,32793,32796 ,18281,18279,18282 ,0,0,0}, {32793,32795,32794 ,18279,18281,18280 ,0,0,0}, + {32797,32798,32796 ,18283,18284,18282 ,0,0,0}, {32795,32796,32798 ,18281,18282,18284 ,0,0,0}, + {32797,32799,32800 ,18283,18285,18286 ,0,0,0}, {32800,32798,32797 ,18286,18284,18283 ,0,0,0}, + {32801,32799,32802 ,18287,18285,18288 ,0,0,0}, {32799,32801,32800 ,18285,18287,18286 ,0,0,0}, + {32803,32804,32802 ,18289,18290,18288 ,0,0,0}, {32801,32802,32804 ,18287,18288,18290 ,0,0,0}, + {32803,32805,32806 ,18289,18291,18292 ,0,0,0}, {32806,32804,32803 ,18292,18290,18289 ,0,0,0}, + {31689,32805,32807 ,18293,18291,18003 ,0,0,0}, {32805,31689,32806 ,18291,18293,18292 ,0,0,0}, + {32808,32809,32810 ,18294,18295,18296 ,0,0,0}, {32811,32812,32813 ,18297,21,18298 ,0,0,0}, + {32814,32808,32815 ,18299,18294,18300 ,0,0,0}, {32808,32814,32809 ,18294,18299,18295 ,0,0,0}, + {32814,32815,32816 ,18299,18300,18301 ,0,0,0}, {32817,32818,32816 ,18302,18303,18301 ,0,0,0}, + {32816,32815,32817 ,18301,18300,18302 ,0,0,0}, {32818,32819,32820 ,18303,18304,126 ,0,0,0}, + {32819,32818,32817 ,18304,18303,18302 ,0,0,0}, {32819,32821,32820 ,18304,3135,126 ,0,0,0}, + {32808,32810,32822 ,18294,18296,18305 ,0,0,0}, {32823,32822,32824 ,18306,18305,18307 ,0,0,0}, + {32810,32824,32822 ,18296,18307,18305 ,0,0,0}, {32825,32823,32826 ,18308,18306,18309 ,0,0,0}, + {32823,32824,32826 ,18306,18307,18309 ,0,0,0}, {32825,32827,32828 ,18308,18310,18311 ,0,0,0}, + {32828,32823,32825 ,18311,18306,18308 ,0,0,0}, {32829,32827,32830 ,18312,18310,18313 ,0,0,0}, + {32827,32829,32828 ,18310,18312,18311 ,0,0,0}, {32812,32829,32813 ,21,18312,18298 ,0,0,0}, + {32830,32813,32829 ,18313,18298,18312 ,0,0,0}, {32831,32832,32833 ,18314,18315,18316 ,0,0,0}, + {32811,32834,32833 ,18297,18317,18316 ,0,0,0}, {32835,32836,32837 ,18318,18319,18320 ,0,0,0}, + {32836,32832,32838 ,18319,18315,18321 ,0,0,0}, {32839,32840,32841 ,18322,18323,18324 ,0,0,0}, + {32842,32843,32839 ,18325,18326,18322 ,0,0,0}, {32844,32845,32846 ,18327,18328,18329 ,0,0,0}, + {32845,32844,32847 ,18328,18327,18330 ,0,0,0}, {32848,32849,32846 ,18037,18331,18329 ,0,0,0}, + {32844,32846,32849 ,18327,18329,18331 ,0,0,0}, {32850,32849,32848 ,18038,18331,18037 ,0,0,0}, + {32841,32847,32839 ,18324,18330,18322 ,0,0,0}, {32841,32845,32847 ,18324,18328,18330 ,0,0,0}, + {32836,32835,32842 ,18319,18318,18325 ,0,0,0}, {32839,32843,32840 ,18322,18326,18323 ,0,0,0}, + {32842,32835,32843 ,18325,18318,18326 ,0,0,0}, {32832,32831,32838 ,18315,18314,18321 ,0,0,0}, + {32837,32836,32838 ,18320,18319,18321 ,0,0,0}, {32833,32812,32811 ,18316,21,18297 ,0,0,0}, + {32831,32833,32834 ,18314,18316,18317 ,0,0,0}, {32851,32852,32853 ,18332,1077,18332 ,0,0,0}, + {32854,32855,32853 ,18333,18333,18332 ,0,0,0}, {32855,32851,32853 ,18333,18332,18332 ,0,0,0}, + {32851,32856,32852 ,18332,18334,1077 ,0,0,0}, {32857,32858,32859 ,18335,18336,324 ,0,0,0}, + {32860,32861,32862 ,18337,18338,18339 ,0,0,0}, {32859,32858,32862 ,324,18336,18339 ,0,0,0}, + {32861,32860,32863 ,18338,18337,18340 ,0,0,0}, {32863,32864,32861 ,18340,18341,18338 ,0,0,0}, + {32864,32865,32866 ,18341,18342,18343 ,0,0,0}, {32863,32865,32864 ,18340,18342,18341 ,0,0,0}, + {32860,32862,32858 ,18337,18339,18336 ,0,0,0}, {32867,32868,32869 ,18344,18345,18346 ,0,0,0}, + {32868,32866,32869 ,18345,18343,18346 ,0,0,0}, {32867,32870,32871 ,18344,18347,18348 ,0,0,0}, + {32871,32868,32867 ,18348,18345,18344 ,0,0,0}, {32870,32872,32873 ,18347,18349,18350 ,0,0,0}, + {32870,32873,32871 ,18347,18350,18348 ,0,0,0}, {32865,32869,32866 ,18342,18346,18343 ,0,0,0}, + {32874,32873,32872 ,18351,18350,18349 ,0,0,0}, {32875,32876,32877 ,18352,18353,126 ,0,0,0}, + {32875,32877,32874 ,18352,126,18351 ,0,0,0}, {32872,32875,32874 ,18349,18352,18351 ,0,0,0}, + {32857,32859,32878 ,18335,324,18354 ,0,0,0}, {32878,32879,32880 ,18354,18355,18356 ,0,0,0}, + {32880,32857,32878 ,18356,18335,18354 ,0,0,0}, {32881,32879,32882 ,18357,18355,18358 ,0,0,0}, + {32879,32881,32880 ,18355,18357,18356 ,0,0,0}, {32883,32884,32882 ,18359,18360,18358 ,0,0,0}, + {32881,32882,32884 ,18357,18358,18360 ,0,0,0}, {32883,32885,32886 ,18359,18361,18362 ,0,0,0}, + {32886,32884,32883 ,18362,18360,18359 ,0,0,0}, {32887,32885,32888 ,18363,18361,18364 ,0,0,0}, + {32885,32887,32886 ,18361,18363,18362 ,0,0,0}, {32889,32890,32888 ,18365,18366,18364 ,0,0,0}, + {32887,32888,32890 ,18363,18364,18366 ,0,0,0}, {32889,32891,32892 ,18365,18367,18368 ,0,0,0}, + {32892,32890,32889 ,18368,18366,18365 ,0,0,0}, {32893,32891,32894 ,18369,18367,18188 ,0,0,0}, + {32891,32893,32892 ,18367,18369,18368 ,0,0,0}, {32895,32896,32897 ,18370,18371,18372 ,0,0,0}, + {32898,32851,32899 ,18373,324,18374 ,0,0,0}, {32900,32895,32901 ,18375,18370,18376 ,0,0,0}, + {32895,32900,32896 ,18370,18375,18371 ,0,0,0}, {32900,32901,32902 ,18375,18376,18377 ,0,0,0}, + {32903,32904,32902 ,18378,18379,18377 ,0,0,0}, {32902,32901,32903 ,18377,18376,18378 ,0,0,0}, + {32904,32905,32906 ,18379,18380,18092 ,0,0,0}, {32905,32904,32903 ,18380,18379,18378 ,0,0,0}, + {32905,32907,32906 ,18380,18381,18092 ,0,0,0}, {32895,32897,32908 ,18370,18372,18382 ,0,0,0}, + {32909,32908,32910 ,18383,18382,18384 ,0,0,0}, {32897,32910,32908 ,18372,18384,18382 ,0,0,0}, + {32911,32909,32912 ,18385,18383,18386 ,0,0,0}, {32909,32910,32912 ,18383,18384,18386 ,0,0,0}, + {32911,32913,32914 ,18385,18387,18388 ,0,0,0}, {32914,32909,32911 ,18388,18383,18385 ,0,0,0}, + {32915,32913,32916 ,18389,18387,18390 ,0,0,0}, {32913,32915,32914 ,18387,18389,18388 ,0,0,0}, + {32851,32915,32899 ,324,18389,18374 ,0,0,0}, {32916,32899,32915 ,18390,18374,18389 ,0,0,0}, + {32917,32918,32919 ,18391,18392,18393 ,0,0,0}, {32898,32920,32919 ,18373,18394,18393 ,0,0,0}, + {32921,32922,32923 ,18395,18396,18397 ,0,0,0}, {32922,32918,32924 ,18396,18392,18398 ,0,0,0}, + {32925,32926,32927 ,18399,18400,18401 ,0,0,0}, {32928,32929,32925 ,18402,18403,18399 ,0,0,0}, + {32930,32931,32932 ,18404,18405,18406 ,0,0,0}, {32931,32930,32933 ,18405,18404,18407 ,0,0,0}, + {32934,32935,32932 ,82,18408,18406 ,0,0,0}, {32930,32932,32935 ,18404,18406,18408 ,0,0,0}, + {32936,32935,32934 ,18103,18408,82 ,0,0,0}, {32927,32933,32925 ,18401,18407,18399 ,0,0,0}, + {32927,32931,32933 ,18401,18405,18407 ,0,0,0}, {32922,32921,32928 ,18396,18395,18402 ,0,0,0}, + {32925,32929,32926 ,18399,18403,18400 ,0,0,0}, {32928,32921,32929 ,18402,18395,18403 ,0,0,0}, + {32918,32917,32924 ,18392,18391,18398 ,0,0,0}, {32923,32922,32924 ,18397,18396,18398 ,0,0,0}, + {32919,32851,32898 ,18393,324,18373 ,0,0,0}, {32917,32919,32920 ,18391,18393,18394 ,0,0,0}, + {32937,32808,32938 ,2197,2197,2197 ,0,0,0}, {32939,32940,32808 ,2197,2197,2197 ,0,0,0}, + {32940,32938,32808 ,2197,2197,2197 ,0,0,0}, {32938,32941,32937 ,2197,2197,2197 ,0,0,0}, + {32942,32943,32845 ,730,730,730 ,0,0,0}, {32798,32944,32945 ,730,730,730 ,0,0,0}, + {32946,32947,32835 ,730,730,730 ,0,0,0}, {32843,32947,32840 ,730,730,730 ,0,0,0}, + {32811,32948,32834 ,730,730,730 ,0,0,0}, {32834,32949,32831 ,730,730,730 ,0,0,0}, + {32950,32837,32838 ,730,730,730 ,0,0,0}, {32830,32951,32813 ,730,730,730 ,0,0,0}, + {32827,32952,32830 ,730,730,730 ,0,0,0}, {32953,32952,32825 ,730,730,730 ,0,0,0}, + {32825,32826,32953 ,730,730,730 ,0,0,0}, {32814,32816,32954 ,730,730,730 ,0,0,0}, + {32955,32826,32824 ,730,730,730 ,0,0,0}, {32809,32956,32957 ,730,730,730 ,0,0,0}, + {32958,32816,32818 ,730,730,730 ,0,0,0}, {31689,32818,32820 ,730,730,730 ,0,0,0}, + {31689,32959,32806 ,730,730,730 ,0,0,0}, {32960,32801,32961 ,730,730,730 ,0,0,0}, + {32804,32806,32962 ,730,730,730 ,0,0,0}, {32804,32962,32961 ,730,730,730 ,0,0,0}, + {32960,32963,32800 ,730,730,730 ,0,0,0}, {32798,32800,32944 ,730,730,730 ,0,0,0}, + {32810,32957,32824 ,730,730,730 ,0,0,0}, {32795,32945,32964 ,730,730,730 ,0,0,0}, + {32773,32794,32965 ,730,730,730 ,0,0,0}, {32773,32966,32452 ,730,730,730 ,0,0,0}, + {32966,32967,32452 ,730,730,730 ,0,0,0}, {32794,32964,32968 ,730,730,730 ,0,0,0}, + {32969,32775,32967 ,730,730,730 ,0,0,0}, {32778,32969,32970 ,730,730,730 ,0,0,0}, + {32971,32780,32972 ,730,730,730 ,0,0,0}, {32780,32778,32972 ,730,730,730 ,0,0,0}, + {32784,32971,32973 ,730,730,730 ,0,0,0}, {32974,32787,32785 ,730,730,730 ,0,0,0}, + {32975,32782,32973 ,730,730,730 ,0,0,0}, {32974,32785,32976 ,730,730,730 ,0,0,0}, + {32948,32811,31660 ,730,730,730 ,0,0,0}, {32790,32787,32977 ,730,730,730 ,0,0,0}, + {32974,32977,32787 ,730,730,730 ,0,0,0}, {32790,32978,31675 ,730,730,730 ,0,0,0}, + {32978,32790,32977 ,730,730,730 ,0,0,0}, {31675,32848,32846 ,730,730,730 ,0,0,0}, + {32978,32848,31675 ,730,730,730 ,0,0,0}, {32979,32942,32841 ,730,730,730 ,0,0,0}, + {31660,32811,32813 ,730,730,730 ,0,0,0}, {32975,32976,32782 ,730,730,730 ,0,0,0}, + {32976,32785,32782 ,730,730,730 ,0,0,0}, {32784,32973,32782 ,730,730,730 ,0,0,0}, + {32780,32971,32784 ,730,730,730 ,0,0,0}, {32970,32972,32778 ,730,730,730 ,0,0,0}, + {32775,32969,32778 ,730,730,730 ,0,0,0}, {32452,32967,32775 ,730,730,730 ,0,0,0}, + {32965,32966,32773 ,730,730,730 ,0,0,0}, {32968,32965,32794 ,730,730,730 ,0,0,0}, + {32795,32964,32794 ,730,730,730 ,0,0,0}, {32798,32945,32795 ,730,730,730 ,0,0,0}, + {32963,32944,32800 ,730,730,730 ,0,0,0}, {32801,32960,32800 ,730,730,730 ,0,0,0}, + {32804,32961,32801 ,730,730,730 ,0,0,0}, {32959,32962,32806 ,730,730,730 ,0,0,0}, + {32820,32959,31689 ,730,730,730 ,0,0,0}, {32958,32818,31689 ,730,730,730 ,0,0,0}, + {32954,32816,32958 ,730,730,730 ,0,0,0}, {32809,32814,32956 ,730,730,730 ,0,0,0}, + {32814,32954,32956 ,730,730,730 ,0,0,0}, {32810,32809,32957 ,730,730,730 ,0,0,0}, + {32955,32824,32957 ,730,730,730 ,0,0,0}, {32953,32826,32955 ,730,730,730 ,0,0,0}, + {32827,32825,32952 ,730,730,730 ,0,0,0}, {32951,32830,32952 ,730,730,730 ,0,0,0}, + {31660,32813,32951 ,730,730,730 ,0,0,0}, {32834,32948,32949 ,730,730,730 ,0,0,0}, + {32838,32831,32949 ,730,730,730 ,0,0,0}, {32946,32837,32950 ,730,730,730 ,0,0,0}, + {32950,32838,32949 ,730,730,730 ,0,0,0}, {32947,32843,32835 ,730,730,730 ,0,0,0}, + {32946,32835,32837 ,730,730,730 ,0,0,0}, {32947,32979,32840 ,730,730,730 ,0,0,0}, + {32841,32942,32845 ,730,730,730 ,0,0,0}, {32840,32979,32841 ,730,730,730 ,0,0,0}, + {32845,32943,32846 ,730,730,730 ,0,0,0}, {31675,32846,32943 ,730,730,730 ,0,0,0}, + {32980,32981,32925 ,18409,18410,18410 ,0,0,0}, {32981,32852,32856 ,18410,1433,1433 ,0,0,0}, + {32925,32981,32856 ,18410,18410,1433 ,0,0,0}, {32925,32982,32980 ,18410,18409,18409 ,0,0,0}, + {32854,32983,32895 ,2162,18411,18411 ,0,0,0}, {32983,32937,32941 ,18411,2162,2162 ,0,0,0}, + {32895,32983,32941 ,18411,18411,2162 ,0,0,0}, {32895,32855,32854 ,18411,2162,2162 ,0,0,0}, + {31675,32943,32984 ,18353,18412,18413 ,0,0,0}, {32947,32985,32979 ,18414,18415,18416 ,0,0,0}, + {32986,32987,32942 ,18417,18418,18419 ,0,0,0}, {32988,32949,32989 ,18420,18421,18422 ,0,0,0}, + {32946,32950,32990 ,18423,18239,18424 ,0,0,0}, {32951,32991,32992 ,18425,18426,18427 ,0,0,0}, + {32992,32993,31660 ,18427,324,18428 ,0,0,0}, {32955,32994,32953 ,18429,18430,18431 ,0,0,0}, + {32995,32952,32953 ,18432,18433,18431 ,0,0,0}, {32957,32996,32997 ,18434,18435,18436 ,0,0,0}, + {32997,32955,32957 ,18436,18429,18434 ,0,0,0}, {32996,32956,32998 ,18435,18437,18438 ,0,0,0}, + {32956,32996,32957 ,18437,18435,18434 ,0,0,0}, {32999,32998,32954 ,18439,18438,18440 ,0,0,0}, + {32956,32954,32998 ,18437,18440,18438 ,0,0,0}, {32958,32807,32999 ,18441,18256,18439 ,0,0,0}, + {32999,32954,32958 ,18439,18440,18441 ,0,0,0}, {31689,32807,32958 ,18002,18256,18441 ,0,0,0}, + {32997,32994,32955 ,18436,18430,18429 ,0,0,0}, {32995,32953,32994 ,18432,18431,18430 ,0,0,0}, + {32995,32991,32952 ,18432,18426,18433 ,0,0,0}, {32989,32948,32993 ,18422,18442,324 ,0,0,0}, + {32951,32992,31660 ,18425,18427,18428 ,0,0,0}, {32952,32991,32951 ,18433,18426,18425 ,0,0,0}, + {32993,32948,31660 ,324,18442,18428 ,0,0,0}, {32948,32989,32949 ,18442,18422,18421 ,0,0,0}, + {32990,32950,32988 ,18424,18239,18420 ,0,0,0}, {32950,32949,32988 ,18239,18421,18420 ,0,0,0}, + {32946,33000,32947 ,18423,18443,18414 ,0,0,0}, {33000,32946,32990 ,18443,18423,18424 ,0,0,0}, + {32986,32979,32985 ,18417,18416,18415 ,0,0,0}, {33000,32985,32947 ,18443,18415,18414 ,0,0,0}, + {32942,32987,32943 ,18419,18418,18412 ,0,0,0}, {32979,32986,32942 ,18416,18417,18419 ,0,0,0}, + {31675,32984,32791 ,18353,18413,3345 ,0,0,0}, {32943,32987,32984 ,18412,18418,18413 ,0,0,0}, + {32812,33001,32939 ,18444,18444,18113 ,0,0,0}, {32812,33002,33003 ,18444,18113,18113 ,0,0,0}, + {32812,33003,33001 ,18444,18113,18444 ,0,0,0}, {33001,32940,32939 ,18444,18113,18113 ,0,0,0}, + {32890,32892,33004 ,7758,7880,7627 ,0,0,0}, {32898,32899,33005 ,726,726,7627 ,0,0,0}, + {32884,33006,33007 ,726,18445,7755 ,0,0,0}, {33008,32886,33009 ,8017,7627,7627 ,0,0,0}, + {33010,32857,33011 ,18446,7758,18447 ,0,0,0}, {33011,32880,33012 ,18447,7264,7249 ,0,0,0}, + {33013,32863,33014 ,18448,7627,18449 ,0,0,0}, {33007,33015,32881 ,7755,8018,7755 ,0,0,0}, + {32860,33016,33014 ,7761,18450,18449 ,0,0,0}, {33017,32865,32863 ,18451,726,7627 ,0,0,0}, + {32865,33017,33018 ,726,18451,726 ,0,0,0}, {32858,33010,33016 ,7755,18446,18450 ,0,0,0}, + {33019,32869,33018 ,7264,7627,726 ,0,0,0}, {32867,33020,32870 ,7758,7264,7880 ,0,0,0}, + {33021,33022,32872 ,726,7880,7627 ,0,0,0}, {33023,32900,33024 ,726,7627,726 ,0,0,0}, + {33025,32911,32912 ,726,7627,7627 ,0,0,0}, {33022,33026,32875 ,7880,7627,7880 ,0,0,0}, + {32876,32932,33027 ,7627,7627,726 ,0,0,0}, {32931,33028,33027 ,7627,7627,726 ,0,0,0}, + {32929,33029,32926 ,7625,7627,7627 ,0,0,0}, {32927,32926,33030 ,726,7627,726 ,0,0,0}, + {32910,33031,32912 ,7627,726,7627 ,0,0,0}, {33028,32931,32927 ,7627,7627,726 ,0,0,0}, + {33032,32923,32924 ,7627,726,726 ,0,0,0}, {32921,32923,33033 ,7627,726,7627 ,0,0,0}, + {32898,33005,33034 ,726,7627,726 ,0,0,0}, {33034,33035,32920 ,726,7627,7627 ,0,0,0}, + {33036,32916,32913 ,7627,726,726 ,0,0,0}, {33035,32924,32917 ,7627,726,726 ,0,0,0}, + {33036,32911,33025 ,7627,7627,726 ,0,0,0}, {32916,33037,32899 ,726,726,726 ,0,0,0}, + {33029,32921,33033 ,7627,7627,7627 ,0,0,0}, {32910,32897,33038 ,7627,7625,726 ,0,0,0}, + {33023,32896,32900 ,726,726,7627 ,0,0,0}, {33024,32900,32902 ,726,7627,726 ,0,0,0}, + {32896,33023,33038 ,726,726,726 ,0,0,0}, {33026,32934,32876 ,7627,7627,7627 ,0,0,0}, + {33039,32902,32904 ,726,726,7627 ,0,0,0}, {32902,33039,33024 ,726,726,726 ,0,0,0}, + {32893,32904,32906 ,7627,7627,7627 ,0,0,0}, {32893,33039,32904 ,7627,726,7627 ,0,0,0}, + {32906,33040,32893 ,7627,7758,7627 ,0,0,0}, {33041,33009,32887 ,7758,7627,7758 ,0,0,0}, + {33019,33042,32867 ,7264,7761,7758 ,0,0,0}, {33010,32858,32857 ,18446,7755,7758 ,0,0,0}, + {32897,32896,33038 ,7625,726,726 ,0,0,0}, {33031,32910,33038 ,726,7627,726 ,0,0,0}, + {33025,32912,33031 ,726,7627,726 ,0,0,0}, {32913,32911,33036 ,726,7627,7627 ,0,0,0}, + {33037,32916,33036 ,726,726,7627 ,0,0,0}, {33005,32899,33037 ,7627,726,726 ,0,0,0}, + {32920,32898,33034 ,7627,726,726 ,0,0,0}, {32917,32920,33035 ,726,7627,7627 ,0,0,0}, + {33032,32924,33035 ,7627,726,7627 ,0,0,0}, {33033,32923,33032 ,7627,726,7627 ,0,0,0}, + {32929,32921,33029 ,7625,7627,7627 ,0,0,0}, {33030,32926,33029 ,726,7627,7627 ,0,0,0}, + {33028,32927,33030 ,7627,726,726 ,0,0,0}, {32932,32931,33027 ,7627,7627,726 ,0,0,0}, + {32934,32932,32876 ,7627,7627,7627 ,0,0,0}, {32875,33026,32876 ,7880,7627,7627 ,0,0,0}, + {32872,33022,32875 ,7627,7880,7880 ,0,0,0}, {33020,33021,32870 ,7264,726,7880 ,0,0,0}, + {33021,32872,32870 ,726,7627,7880 ,0,0,0}, {33042,33020,32867 ,7761,7264,7758 ,0,0,0}, + {32869,33019,32867 ,7627,7264,7758 ,0,0,0}, {32865,33018,32869 ,726,726,7627 ,0,0,0}, + {33013,33017,32863 ,18448,18451,7627 ,0,0,0}, {32860,33014,32863 ,7761,18449,7627 ,0,0,0}, + {32858,33016,32860 ,7755,18450,7761 ,0,0,0}, {33011,32857,32880 ,18447,7758,7264 ,0,0,0}, + {33015,33012,32880 ,8018,7249,7264 ,0,0,0}, {32884,33007,32881 ,726,7755,7755 ,0,0,0}, + {32881,33015,32880 ,7755,8018,7264 ,0,0,0}, {32886,33006,32884 ,7627,18445,726 ,0,0,0}, + {32886,32887,33009 ,7627,7758,7627 ,0,0,0}, {32886,33008,33006 ,7627,8017,18445 ,0,0,0}, + {32887,32890,33041 ,7758,7758,7758 ,0,0,0}, {33004,32892,33040 ,7627,7880,7758 ,0,0,0}, + {33041,32890,33004 ,7758,7758,7627 ,0,0,0}, {32893,33040,32892 ,7627,7758,7880 ,0,0,0}, + {33002,32839,33043 ,1398,18452,18452 ,0,0,0}, {32980,32982,32839 ,18453,18453,18452 ,0,0,0}, + {32982,33043,32839 ,18453,18452,18452 ,0,0,0}, {33043,33003,33002 ,18452,1398,1398 ,0,0,0}, + {33044,32906,32907 ,18454,18092,18121 ,0,0,0}, {33009,33041,32938 ,18455,18456,18457 ,0,0,0}, + {33045,33004,33046 ,18458,18459,18460 ,0,0,0}, {33008,33047,33006 ,18461,18462,18463 ,0,0,0}, + {33048,33001,33010 ,18464,7309,18465 ,0,0,0}, {33049,33012,33015 ,18466,18467,18468 ,0,0,0}, + {33018,33017,33050 ,18469,18470,18471 ,0,0,0}, {33013,33014,33051 ,18472,18473,18474 ,0,0,0}, + {33019,33052,33042 ,18475,18476,18477 ,0,0,0}, {33043,33021,33020 ,18478,18479,18480 ,0,0,0}, + {33042,33043,33020 ,18477,18478,18480 ,0,0,0}, {33021,33053,33022 ,18479,18481,18482 ,0,0,0}, + {33053,33021,33043 ,18481,18479,18478 ,0,0,0}, {33053,33054,33022 ,18481,18483,18482 ,0,0,0}, + {33055,33026,33054 ,18484,18485,18483 ,0,0,0}, {33022,33054,33026 ,18482,18483,18485 ,0,0,0}, + {33055,32936,32934 ,18484,18486,82 ,0,0,0}, {32934,33026,33055 ,82,18485,18484 ,0,0,0}, + {33050,33052,33019 ,18471,18476,18475 ,0,0,0}, {33042,33052,33043 ,18477,18476,18478 ,0,0,0}, + {33017,33056,33050 ,18470,18487,18471 ,0,0,0}, {33019,33018,33050 ,18475,18469,18471 ,0,0,0}, + {33051,33056,33013 ,18474,18487,18472 ,0,0,0}, {33017,33013,33056 ,18470,18472,18487 ,0,0,0}, + {33051,33016,33001 ,18474,18488,7309 ,0,0,0}, {33014,33016,33051 ,18473,18488,18474 ,0,0,0}, + {33048,33010,33011 ,18464,18465,18489 ,0,0,0}, {33001,33016,33010 ,7309,18488,18465 ,0,0,0}, + {33012,33049,33048 ,18467,18466,18464 ,0,0,0}, {33048,33011,33012 ,18464,18489,18467 ,0,0,0}, + {33007,33057,33015 ,18490,18491,18468 ,0,0,0}, {33057,33049,33015 ,18491,18466,18468 ,0,0,0}, + {33057,33006,33047 ,18491,18463,18462 ,0,0,0}, {33006,33057,33007 ,18463,18491,18490 ,0,0,0}, + {33008,33009,32938 ,18461,18455,18457 ,0,0,0}, {33008,32938,33047 ,18461,18457,18462 ,0,0,0}, + {33041,33004,33045 ,18456,18459,18458 ,0,0,0}, {33041,33045,32938 ,18456,18458,18457 ,0,0,0}, + {33046,33040,33044 ,18460,18492,18454 ,0,0,0}, {33004,33040,33046 ,18459,18492,18460 ,0,0,0}, + {32906,33044,33040 ,18092,18454,18492 ,0,0,0}, {32930,32982,32933 ,7792,726,7658 ,0,0,0}, + {32982,32925,32933 ,726,726,7658 ,0,0,0}, {32936,32982,32935 ,7664,726,7662 ,0,0,0}, + {32982,32930,32935 ,726,7792,7662 ,0,0,0}, {33054,32982,33055 ,7662,726,5488 ,0,0,0}, + {32982,32936,33055 ,726,7664,5488 ,0,0,0}, {33043,32982,33053 ,726,726,726 ,0,0,0}, + {32982,33054,33053 ,726,7662,726 ,0,0,0}, {33057,32940,33049 ,726,726,17470 ,0,0,0}, + {33049,32940,33048 ,17470,726,7628 ,0,0,0}, {32940,33001,33048 ,726,726,7628 ,0,0,0}, + {32940,33047,32938 ,726,726,726 ,0,0,0}, {32940,33057,33047 ,726,726,726 ,0,0,0}, + {32908,32855,32895 ,726,726,726 ,0,0,0}, {32914,32855,32909 ,7661,726,7659 ,0,0,0}, + {32855,32908,32909 ,726,726,7659 ,0,0,0}, {32851,32855,32915 ,7661,726,7661 ,0,0,0}, + {32855,32914,32915 ,726,7661,7661 ,0,0,0}, {32856,32919,32918 ,7660,7660,7660 ,0,0,0}, + {32851,32919,32856 ,726,7660,7660 ,0,0,0}, {32856,32928,32925 ,7660,726,726 ,0,0,0}, + {32856,32922,32928 ,7660,7658,726 ,0,0,0}, {32918,32922,32856 ,7660,7658,7660 ,0,0,0}, + {33043,33052,33003 ,726,726,726 ,0,0,0}, {33056,33003,33050 ,726,726,7661 ,0,0,0}, + {33052,33050,33003 ,726,7661,726 ,0,0,0}, {33051,33001,33003 ,726,726,726 ,0,0,0}, + {33051,33003,33056 ,726,726,726 ,0,0,0}, {33045,32941,32938 ,726,726,726 ,0,0,0}, + {33044,32941,33046 ,726,726,726 ,0,0,0}, {32941,33045,33046 ,726,726,726 ,0,0,0}, + {32905,32941,32907 ,726,726,726 ,0,0,0}, {32941,33044,32907 ,726,726,726 ,0,0,0}, + {32901,32941,32903 ,726,726,7660 ,0,0,0}, {32941,32905,32903 ,726,726,7660 ,0,0,0}, + {32895,32941,32901 ,726,726,726 ,0,0,0}, {32891,32889,33058 ,726,726,7583 ,0,0,0}, + {33059,33060,33061 ,726,726,726 ,0,0,0}, {33062,33059,32894 ,726,726,726 ,0,0,0}, + {33058,33063,32891 ,7583,7583,726 ,0,0,0}, {33064,33065,33061 ,726,726,726 ,0,0,0}, + {33066,33067,33060 ,726,726,726 ,0,0,0}, {33064,33061,33067 ,726,726,726 ,0,0,0}, + {33060,33067,33061 ,726,726,726 ,0,0,0}, {33061,33068,33059 ,726,726,726 ,0,0,0}, + {32891,33062,32894 ,726,726,726 ,0,0,0}, {32894,33059,33068 ,726,726,726 ,0,0,0}, + {33058,32889,32888 ,7583,726,726 ,0,0,0}, {32891,33063,33062 ,726,7583,726 ,0,0,0}, + {33069,32888,32885 ,7583,726,726 ,0,0,0}, {32888,33069,33058 ,726,7583,7583 ,0,0,0}, + {32885,33070,33071 ,726,726,726 ,0,0,0}, {33069,32885,33071 ,7583,726,726 ,0,0,0}, + {32883,33070,32885 ,726,726,726 ,0,0,0}, {33070,32882,33072 ,726,726,726 ,0,0,0}, + {32882,33070,32883 ,726,726,726 ,0,0,0}, {32882,32879,33072 ,726,726,726 ,0,0,0}, + {33073,32879,33074 ,726,726,5489 ,0,0,0}, {33073,33072,32879 ,726,726,726 ,0,0,0}, + {33074,32878,32859 ,5489,7583,726 ,0,0,0}, {32879,32878,33074 ,726,7583,5489 ,0,0,0}, + {32862,32877,32859 ,7583,7583,726 ,0,0,0}, {33074,32859,32877 ,5489,726,7583 ,0,0,0}, + {32866,32873,32861 ,7583,7583,726 ,0,0,0}, {32861,32864,32866 ,726,726,7583 ,0,0,0}, + {32873,32868,32871 ,7583,7583,726 ,0,0,0}, {32873,32862,32861 ,7583,7583,726 ,0,0,0}, + {32873,32874,32862 ,7583,5489,7583 ,0,0,0}, {32873,32866,32868 ,7583,7583,7583 ,0,0,0}, + {32862,32874,32877 ,7583,5489,7583 ,0,0,0}, {32876,33027,33074 ,35,18493,18494 ,0,0,0}, + {33029,33070,33030 ,18495,18496,18497 ,0,0,0}, {33072,33073,33028 ,18498,18499,18500 ,0,0,0}, + {33058,33035,33063 ,18501,18502,18503 ,0,0,0}, {33033,33032,33069 ,18504,18505,18506 ,0,0,0}, + {33037,33060,33059 ,18507,18508,18509 ,0,0,0}, {33059,33062,33005 ,18509,18510,18511 ,0,0,0}, + {33031,33067,33025 ,18512,18513,18514 ,0,0,0}, {33066,33036,33025 ,18515,18516,18514 ,0,0,0}, + {33038,33065,33064 ,18517,18518,18519 ,0,0,0}, {33064,33031,33038 ,18519,18512,18517 ,0,0,0}, + {33065,33023,33061 ,18518,18520,18521 ,0,0,0}, {33023,33065,33038 ,18520,18518,18517 ,0,0,0}, + {33068,33061,33024 ,18522,18521,18523 ,0,0,0}, {33023,33024,33061 ,18520,18523,18521 ,0,0,0}, + {33039,32894,33068 ,18524,18188,18522 ,0,0,0}, {33068,33024,33039 ,18522,18523,18524 ,0,0,0}, + {32893,32894,33039 ,18188,18188,18524 ,0,0,0}, {33064,33067,33031 ,18519,18513,18512 ,0,0,0}, + {33066,33025,33067 ,18515,18514,18513 ,0,0,0}, {33066,33060,33036 ,18515,18508,18516 ,0,0,0}, + {33063,33034,33062 ,18503,18525,18510 ,0,0,0}, {33037,33059,33005 ,18507,18509,18511 ,0,0,0}, + {33036,33060,33037 ,18516,18508,18507 ,0,0,0}, {33062,33034,33005 ,18510,18525,18511 ,0,0,0}, + {33034,33063,33035 ,18525,18503,18502 ,0,0,0}, {33069,33032,33058 ,18506,18505,18501 ,0,0,0}, + {33032,33035,33058 ,18505,18502,18501 ,0,0,0}, {33033,33071,33029 ,18504,18526,18495 ,0,0,0}, + {33071,33033,33069 ,18526,18504,18506 ,0,0,0}, {33072,33030,33070 ,18498,18497,18496 ,0,0,0}, + {33071,33070,33029 ,18526,18496,18495 ,0,0,0}, {33028,33073,33027 ,18500,18499,18493 ,0,0,0}, + {33030,33072,33028 ,18497,18498,18500 ,0,0,0}, {32876,33074,32877 ,35,18494,763 ,0,0,0}, + {33027,33073,33074 ,18493,18499,18494 ,0,0,0}, {33075,32820,32821 ,18527,126,18026 ,0,0,0}, + {32960,32961,32983 ,18528,18529,18530 ,0,0,0}, {33076,32962,33077 ,18531,18532,18533 ,0,0,0}, + {32963,33078,32944 ,18534,18535,18536 ,0,0,0}, {33079,32853,32966 ,18537,10001,18538 ,0,0,0}, + {33080,32968,32964 ,18539,18540,18541 ,0,0,0}, {32971,32972,33081 ,18542,18543,18544 ,0,0,0}, + {32970,32969,33082 ,18545,18546,18547 ,0,0,0}, {32973,33083,32975 ,18548,18549,18550 ,0,0,0}, + {32981,32974,32976 ,18551,18552,18553 ,0,0,0}, {32975,32981,32976 ,18550,18551,18553 ,0,0,0}, + {32974,33084,32977 ,18552,18554,18555 ,0,0,0}, {33084,32974,32981 ,18554,18552,18551 ,0,0,0}, + {33084,33085,32977 ,18554,18556,18555 ,0,0,0}, {33086,32978,33085 ,18557,18558,18556 ,0,0,0}, + {32977,33085,32978 ,18555,18556,18558 ,0,0,0}, {33086,32850,32848 ,18557,5000,18205 ,0,0,0}, + {32848,32978,33086 ,18205,18558,18557 ,0,0,0}, {33081,33083,32973 ,18544,18549,18548 ,0,0,0}, + {32975,33083,32981 ,18550,18549,18551 ,0,0,0}, {32972,33087,33081 ,18543,18559,18544 ,0,0,0}, + {32973,32971,33081 ,18548,18542,18544 ,0,0,0}, {33082,33087,32970 ,18547,18559,18545 ,0,0,0}, + {32972,32970,33087 ,18543,18545,18559 ,0,0,0}, {33082,32967,32853 ,18547,18560,10001 ,0,0,0}, + {32969,32967,33082 ,18546,18560,18547 ,0,0,0}, {33079,32966,32965 ,18537,18538,18561 ,0,0,0}, + {32853,32967,32966 ,10001,18560,18538 ,0,0,0}, {32968,33080,33079 ,18540,18539,18537 ,0,0,0}, + {33079,32965,32968 ,18537,18561,18540 ,0,0,0}, {32945,33088,32964 ,18562,18563,18541 ,0,0,0}, + {33088,33080,32964 ,18563,18539,18541 ,0,0,0}, {33088,32944,33078 ,18563,18536,18535 ,0,0,0}, + {32944,33088,32945 ,18536,18563,18562 ,0,0,0}, {32963,32960,32983 ,18534,18528,18530 ,0,0,0}, + {32963,32983,33078 ,18534,18530,18535 ,0,0,0}, {32961,32962,33076 ,18529,18532,18531 ,0,0,0}, + {32961,33076,32983 ,18529,18531,18530 ,0,0,0}, {33077,32959,33075 ,18533,18564,18527 ,0,0,0}, + {32962,32959,33077 ,18532,18564,18533 ,0,0,0}, {32820,33075,32959 ,126,18527,18564 ,0,0,0}, + {32854,33088,33078 ,17561,17561,730 ,0,0,0}, {33079,32854,32853 ,730,17561,730 ,0,0,0}, + {33088,32854,33080 ,17561,17561,730 ,0,0,0}, {32854,33079,33080 ,17561,730,730 ,0,0,0}, + {33078,32983,32854 ,730,7376,17561 ,0,0,0}, {32847,32980,32839 ,18207,730,730 ,0,0,0}, + {32980,33086,33085 ,730,730,730 ,0,0,0}, {32849,32980,32844 ,17561,730,7433 ,0,0,0}, + {32980,32847,32844 ,730,18207,7433 ,0,0,0}, {33086,32980,32850 ,730,730,17561 ,0,0,0}, + {32980,32849,32850 ,730,17561,17561 ,0,0,0}, {33085,33084,32980 ,730,7433,730 ,0,0,0}, + {33084,32981,32980 ,7433,730,730 ,0,0,0}, {32823,32939,32822 ,7017,730,730 ,0,0,0}, + {32939,32808,32822 ,730,11465,730 ,0,0,0}, {32829,32939,32828 ,18565,730,730 ,0,0,0}, + {32939,32823,32828 ,730,7017,730 ,0,0,0}, {32812,32939,32829 ,18566,730,18565 ,0,0,0}, + {33087,32852,33081 ,730,7376,17561 ,0,0,0}, {33083,33081,32852 ,730,17561,7376 ,0,0,0}, + {32981,33083,32852 ,730,730,7376 ,0,0,0}, {33082,32853,32852 ,7376,730,7376 ,0,0,0}, + {33082,32852,33087 ,7376,7376,730 ,0,0,0}, {32833,32832,33002 ,18207,18207,9877 ,0,0,0}, + {32812,32833,33002 ,18567,18207,9877 ,0,0,0}, {32836,32842,33002 ,730,9878,9877 ,0,0,0}, + {32836,33002,32832 ,730,9877,18207 ,0,0,0}, {32839,33002,32842 ,730,9877,9878 ,0,0,0}, + {32983,33076,32937 ,730,730,730 ,0,0,0}, {32937,33075,32821 ,730,730,9877 ,0,0,0}, + {33075,32937,33077 ,730,730,730 ,0,0,0}, {32937,33076,33077 ,730,730,730 ,0,0,0}, + {32821,32819,32937 ,9877,730,730 ,0,0,0}, {32937,32817,32815 ,730,9878,730 ,0,0,0}, + {32819,32817,32937 ,730,9878,730 ,0,0,0}, {32815,32808,32937 ,730,730,730 ,0,0,0}, + {32984,32987,32793 ,730,730,9878 ,0,0,0}, {32777,32776,32788 ,730,730,730 ,0,0,0}, + {32774,32777,32791 ,9875,730,730 ,0,0,0}, {32793,32792,32984 ,9878,730,730 ,0,0,0}, + {32783,32786,32788 ,730,730,730 ,0,0,0}, {32779,32781,32776 ,730,730,730 ,0,0,0}, + {32783,32788,32781 ,730,730,730 ,0,0,0}, {32776,32781,32788 ,730,730,730 ,0,0,0}, + {32788,32789,32777 ,730,730,730 ,0,0,0}, {32984,32774,32791 ,730,9875,730 ,0,0,0}, + {32791,32777,32789 ,730,730,730 ,0,0,0}, {32793,32987,32986 ,9878,730,730 ,0,0,0}, + {32984,32792,32774 ,730,730,9875 ,0,0,0}, {32796,32986,32985 ,9878,730,730 ,0,0,0}, + {32986,32796,32793 ,730,9878,9878 ,0,0,0}, {32985,32799,32797 ,730,730,730 ,0,0,0}, + {32796,32985,32797 ,9878,730,730 ,0,0,0}, {33000,32799,32985 ,730,730,730 ,0,0,0}, + {32799,32990,32802 ,730,9875,9878 ,0,0,0}, {32990,32799,33000 ,9875,730,730 ,0,0,0}, + {32990,32988,32802 ,9875,730,9878 ,0,0,0}, {32803,32988,32805 ,9878,730,730 ,0,0,0}, + {32803,32802,32988 ,9878,9878,730 ,0,0,0}, {32805,32989,32993 ,730,9875,9875 ,0,0,0}, + {32988,32989,32805 ,730,9875,730 ,0,0,0}, {32992,32807,32993 ,730,9878,9875 ,0,0,0}, + {32805,32993,32807 ,730,9875,9878 ,0,0,0}, {32994,32998,32991 ,9878,9878,730 ,0,0,0}, + {32991,32995,32994 ,730,9878,9878 ,0,0,0}, {32998,32997,32996 ,9878,9878,9877 ,0,0,0}, + {32998,32992,32991 ,9878,730,730 ,0,0,0}, {32998,32999,32992 ,9878,730,730 ,0,0,0}, + {32998,32994,32997 ,9878,9878,9878 ,0,0,0}, {32992,32999,32807 ,730,730,9878 ,0,0,0} +// M3abstandhalter10mm.prt + , {33089,32518,33090 ,18258,18259,18260 ,0,0,0}, {33091,33092,33093 ,18261,18262,18263 ,0,0,0}, + {33090,32518,33093 ,18260,18259,18263 ,0,0,0}, {33092,33091,33094 ,18262,18261,18264 ,0,0,0}, + {33094,33095,33092 ,18264,18265,18262 ,0,0,0}, {33095,33096,33097 ,18265,18266,18267 ,0,0,0}, + {33094,33096,33095 ,18264,18266,18265 ,0,0,0}, {33091,33093,32518 ,18261,18263,18259 ,0,0,0}, + {33098,33099,33100 ,18268,18269,18270 ,0,0,0}, {33099,33097,33100 ,18269,18267,18270 ,0,0,0}, + {33098,33101,33102 ,18268,18271,18272 ,0,0,0}, {33102,33099,33098 ,18272,18269,18268 ,0,0,0}, + {33101,33103,33104 ,18271,18273,18274 ,0,0,0}, {33101,33104,33102 ,18271,18274,18272 ,0,0,0}, + {33096,33100,33097 ,18266,18270,18267 ,0,0,0}, {33105,33104,33103 ,18275,18274,18273 ,0,0,0}, + {33106,31741,33107 ,18276,18277,126 ,0,0,0}, {33106,33107,33105 ,18276,126,18275 ,0,0,0}, + {33103,33106,33105 ,18273,18276,18275 ,0,0,0}, {33089,33090,33108 ,18258,18260,18278 ,0,0,0}, + {33108,33109,33110 ,18278,18279,18280 ,0,0,0}, {33110,33089,33108 ,18280,18258,18278 ,0,0,0}, + {33111,33109,33112 ,18281,18279,18282 ,0,0,0}, {33109,33111,33110 ,18279,18281,18280 ,0,0,0}, + {33113,33114,33112 ,18283,18284,18282 ,0,0,0}, {33111,33112,33114 ,18281,18282,18284 ,0,0,0}, + {33113,33115,33116 ,18283,18285,18286 ,0,0,0}, {33116,33114,33113 ,18286,18284,18283 ,0,0,0}, + {33117,33115,33118 ,18287,18285,18288 ,0,0,0}, {33115,33117,33116 ,18285,18287,18286 ,0,0,0}, + {33119,33120,33118 ,18289,18290,18288 ,0,0,0}, {33117,33118,33120 ,18287,18288,18290 ,0,0,0}, + {33119,33121,33122 ,18289,18291,18292 ,0,0,0}, {33122,33120,33119 ,18292,18290,18289 ,0,0,0}, + {31755,33121,33123 ,18293,18291,18003 ,0,0,0}, {33121,31755,33122 ,18291,18293,18292 ,0,0,0}, + {33124,33125,33126 ,18294,18295,18296 ,0,0,0}, {33127,33128,33129 ,18297,21,18298 ,0,0,0}, + {33130,33124,33131 ,18299,18294,18300 ,0,0,0}, {33124,33130,33125 ,18294,18299,18295 ,0,0,0}, + {33130,33131,33132 ,18299,18300,18301 ,0,0,0}, {33133,33134,33132 ,18302,18303,18301 ,0,0,0}, + {33132,33131,33133 ,18301,18300,18302 ,0,0,0}, {33134,33135,33136 ,18303,18304,126 ,0,0,0}, + {33135,33134,33133 ,18304,18303,18302 ,0,0,0}, {33135,33137,33136 ,18304,3135,126 ,0,0,0}, + {33124,33126,33138 ,18294,18296,18305 ,0,0,0}, {33139,33138,33140 ,18306,18305,18307 ,0,0,0}, + {33126,33140,33138 ,18296,18307,18305 ,0,0,0}, {33141,33139,33142 ,18308,18306,18309 ,0,0,0}, + {33139,33140,33142 ,18306,18307,18309 ,0,0,0}, {33141,33143,33144 ,18308,18310,18311 ,0,0,0}, + {33144,33139,33141 ,18311,18306,18308 ,0,0,0}, {33145,33143,33146 ,18312,18310,18313 ,0,0,0}, + {33143,33145,33144 ,18310,18312,18311 ,0,0,0}, {33128,33145,33129 ,21,18312,18298 ,0,0,0}, + {33146,33129,33145 ,18313,18298,18312 ,0,0,0}, {33147,33148,33149 ,18314,18315,18316 ,0,0,0}, + {33127,33150,33149 ,18297,18317,18316 ,0,0,0}, {33151,33152,33153 ,18318,18319,18320 ,0,0,0}, + {33152,33148,33154 ,18319,18315,18321 ,0,0,0}, {33155,33156,33157 ,18322,18323,18324 ,0,0,0}, + {33158,33159,33155 ,18325,18326,18322 ,0,0,0}, {33160,33161,33162 ,18327,18328,18329 ,0,0,0}, + {33161,33160,33163 ,18328,18327,18330 ,0,0,0}, {33164,33165,33162 ,18037,18331,18329 ,0,0,0}, + {33160,33162,33165 ,18327,18329,18331 ,0,0,0}, {33166,33165,33164 ,18038,18331,18037 ,0,0,0}, + {33157,33163,33155 ,18324,18330,18322 ,0,0,0}, {33157,33161,33163 ,18324,18328,18330 ,0,0,0}, + {33152,33151,33158 ,18319,18318,18325 ,0,0,0}, {33155,33159,33156 ,18322,18326,18323 ,0,0,0}, + {33158,33151,33159 ,18325,18318,18326 ,0,0,0}, {33148,33147,33154 ,18315,18314,18321 ,0,0,0}, + {33153,33152,33154 ,18320,18319,18321 ,0,0,0}, {33149,33128,33127 ,18316,21,18297 ,0,0,0}, + {33147,33149,33150 ,18314,18316,18317 ,0,0,0}, {33167,33168,33169 ,18332,1077,18332 ,0,0,0}, + {33170,33171,33169 ,18333,18333,18332 ,0,0,0}, {33171,33167,33169 ,18333,18332,18332 ,0,0,0}, + {33167,33172,33168 ,18332,18334,1077 ,0,0,0}, {33173,33174,33175 ,18335,18336,324 ,0,0,0}, + {33176,33177,33178 ,18337,18338,18339 ,0,0,0}, {33175,33174,33178 ,324,18336,18339 ,0,0,0}, + {33177,33176,33179 ,18338,18337,18340 ,0,0,0}, {33179,33180,33177 ,18340,18341,18338 ,0,0,0}, + {33180,33181,33182 ,18341,18342,18343 ,0,0,0}, {33179,33181,33180 ,18340,18342,18341 ,0,0,0}, + {33176,33178,33174 ,18337,18339,18336 ,0,0,0}, {33183,33184,33185 ,18344,18345,18346 ,0,0,0}, + {33184,33182,33185 ,18345,18343,18346 ,0,0,0}, {33183,33186,33187 ,18344,18347,18348 ,0,0,0}, + {33187,33184,33183 ,18348,18345,18344 ,0,0,0}, {33186,33188,33189 ,18347,18349,18350 ,0,0,0}, + {33186,33189,33187 ,18347,18350,18348 ,0,0,0}, {33181,33185,33182 ,18342,18346,18343 ,0,0,0}, + {33190,33189,33188 ,18351,18350,18349 ,0,0,0}, {33191,33192,33193 ,18352,18353,126 ,0,0,0}, + {33191,33193,33190 ,18352,126,18351 ,0,0,0}, {33188,33191,33190 ,18349,18352,18351 ,0,0,0}, + {33173,33175,33194 ,18335,324,18354 ,0,0,0}, {33194,33195,33196 ,18354,18355,18356 ,0,0,0}, + {33196,33173,33194 ,18356,18335,18354 ,0,0,0}, {33197,33195,33198 ,18357,18355,18358 ,0,0,0}, + {33195,33197,33196 ,18355,18357,18356 ,0,0,0}, {33199,33200,33198 ,18359,18360,18358 ,0,0,0}, + {33197,33198,33200 ,18357,18358,18360 ,0,0,0}, {33199,33201,33202 ,18359,18361,18362 ,0,0,0}, + {33202,33200,33199 ,18362,18360,18359 ,0,0,0}, {33203,33201,33204 ,18363,18361,18364 ,0,0,0}, + {33201,33203,33202 ,18361,18363,18362 ,0,0,0}, {33205,33206,33204 ,18365,18366,18364 ,0,0,0}, + {33203,33204,33206 ,18363,18364,18366 ,0,0,0}, {33205,33207,33208 ,18365,18367,18368 ,0,0,0}, + {33208,33206,33205 ,18368,18366,18365 ,0,0,0}, {33209,33207,33210 ,18369,18367,18188 ,0,0,0}, + {33207,33209,33208 ,18367,18369,18368 ,0,0,0}, {33211,33212,33213 ,18370,18371,18372 ,0,0,0}, + {33214,33167,33215 ,18373,324,18374 ,0,0,0}, {33216,33211,33217 ,18375,18370,18376 ,0,0,0}, + {33211,33216,33212 ,18370,18375,18371 ,0,0,0}, {33216,33217,33218 ,18375,18376,18377 ,0,0,0}, + {33219,33220,33218 ,18378,18379,18377 ,0,0,0}, {33218,33217,33219 ,18377,18376,18378 ,0,0,0}, + {33220,33221,33222 ,18379,18380,18092 ,0,0,0}, {33221,33220,33219 ,18380,18379,18378 ,0,0,0}, + {33221,33223,33222 ,18380,18381,18092 ,0,0,0}, {33211,33213,33224 ,18370,18372,18382 ,0,0,0}, + {33225,33224,33226 ,18383,18382,18384 ,0,0,0}, {33213,33226,33224 ,18372,18384,18382 ,0,0,0}, + {33227,33225,33228 ,18385,18383,18386 ,0,0,0}, {33225,33226,33228 ,18383,18384,18386 ,0,0,0}, + {33227,33229,33230 ,18385,18387,18388 ,0,0,0}, {33230,33225,33227 ,18388,18383,18385 ,0,0,0}, + {33231,33229,33232 ,18389,18387,18390 ,0,0,0}, {33229,33231,33230 ,18387,18389,18388 ,0,0,0}, + {33167,33231,33215 ,324,18389,18374 ,0,0,0}, {33232,33215,33231 ,18390,18374,18389 ,0,0,0}, + {33233,33234,33235 ,18391,18392,18393 ,0,0,0}, {33214,33236,33235 ,18373,18394,18393 ,0,0,0}, + {33237,33238,33239 ,18395,18396,18397 ,0,0,0}, {33238,33234,33240 ,18396,18392,18398 ,0,0,0}, + {33241,33242,33243 ,18399,18400,18401 ,0,0,0}, {33244,33245,33241 ,18402,18403,18399 ,0,0,0}, + {33246,33247,33248 ,18404,18405,18406 ,0,0,0}, {33247,33246,33249 ,18405,18404,18407 ,0,0,0}, + {33250,33251,33248 ,82,18408,18406 ,0,0,0}, {33246,33248,33251 ,18404,18406,18408 ,0,0,0}, + {33252,33251,33250 ,18103,18408,82 ,0,0,0}, {33243,33249,33241 ,18401,18407,18399 ,0,0,0}, + {33243,33247,33249 ,18401,18405,18407 ,0,0,0}, {33238,33237,33244 ,18396,18395,18402 ,0,0,0}, + {33241,33245,33242 ,18399,18403,18400 ,0,0,0}, {33244,33237,33245 ,18402,18395,18403 ,0,0,0}, + {33234,33233,33240 ,18392,18391,18398 ,0,0,0}, {33239,33238,33240 ,18397,18396,18398 ,0,0,0}, + {33235,33167,33214 ,18393,324,18373 ,0,0,0}, {33233,33235,33236 ,18391,18393,18394 ,0,0,0}, + {33253,33124,33254 ,2197,2197,2197 ,0,0,0}, {33255,33256,33124 ,2197,2197,2197 ,0,0,0}, + {33256,33254,33124 ,2197,2197,2197 ,0,0,0}, {33254,33257,33253 ,2197,2197,2197 ,0,0,0}, + {33258,33259,33161 ,730,730,730 ,0,0,0}, {33114,33260,33261 ,730,730,730 ,0,0,0}, + {33262,33263,33151 ,730,730,730 ,0,0,0}, {33159,33263,33156 ,730,730,730 ,0,0,0}, + {33127,33264,33150 ,730,730,730 ,0,0,0}, {33150,33265,33147 ,730,730,730 ,0,0,0}, + {33266,33153,33154 ,730,730,730 ,0,0,0}, {33146,33267,33129 ,730,730,730 ,0,0,0}, + {33143,33268,33146 ,730,730,730 ,0,0,0}, {33269,33268,33141 ,730,730,730 ,0,0,0}, + {33141,33142,33269 ,730,730,730 ,0,0,0}, {33130,33132,33270 ,730,730,730 ,0,0,0}, + {33271,33142,33140 ,730,730,730 ,0,0,0}, {33125,33272,33273 ,730,730,730 ,0,0,0}, + {33274,33132,33134 ,730,730,730 ,0,0,0}, {31755,33134,33136 ,730,730,730 ,0,0,0}, + {31755,33275,33122 ,730,730,730 ,0,0,0}, {33276,33117,33277 ,730,730,730 ,0,0,0}, + {33120,33122,33278 ,730,730,730 ,0,0,0}, {33120,33278,33277 ,730,730,730 ,0,0,0}, + {33276,33279,33116 ,730,730,730 ,0,0,0}, {33114,33116,33260 ,730,730,730 ,0,0,0}, + {33126,33273,33140 ,730,730,730 ,0,0,0}, {33111,33261,33280 ,730,730,730 ,0,0,0}, + {33089,33110,33281 ,730,730,730 ,0,0,0}, {33089,33282,32518 ,730,730,730 ,0,0,0}, + {33282,33283,32518 ,730,730,730 ,0,0,0}, {33110,33280,33284 ,730,730,730 ,0,0,0}, + {33285,33091,33283 ,730,730,730 ,0,0,0}, {33094,33285,33286 ,730,730,730 ,0,0,0}, + {33287,33096,33288 ,730,730,730 ,0,0,0}, {33096,33094,33288 ,730,730,730 ,0,0,0}, + {33100,33287,33289 ,730,730,730 ,0,0,0}, {33290,33103,33101 ,730,730,730 ,0,0,0}, + {33291,33098,33289 ,730,730,730 ,0,0,0}, {33290,33101,33292 ,730,730,730 ,0,0,0}, + {33264,33127,31726 ,730,730,730 ,0,0,0}, {33106,33103,33293 ,730,730,730 ,0,0,0}, + {33290,33293,33103 ,730,730,730 ,0,0,0}, {33106,33294,31741 ,730,730,730 ,0,0,0}, + {33294,33106,33293 ,730,730,730 ,0,0,0}, {31741,33164,33162 ,730,730,730 ,0,0,0}, + {33294,33164,31741 ,730,730,730 ,0,0,0}, {33295,33258,33157 ,730,730,730 ,0,0,0}, + {31726,33127,33129 ,730,730,730 ,0,0,0}, {33291,33292,33098 ,730,730,730 ,0,0,0}, + {33292,33101,33098 ,730,730,730 ,0,0,0}, {33100,33289,33098 ,730,730,730 ,0,0,0}, + {33096,33287,33100 ,730,730,730 ,0,0,0}, {33286,33288,33094 ,730,730,730 ,0,0,0}, + {33091,33285,33094 ,730,730,730 ,0,0,0}, {32518,33283,33091 ,730,730,730 ,0,0,0}, + {33281,33282,33089 ,730,730,730 ,0,0,0}, {33284,33281,33110 ,730,730,730 ,0,0,0}, + {33111,33280,33110 ,730,730,730 ,0,0,0}, {33114,33261,33111 ,730,730,730 ,0,0,0}, + {33279,33260,33116 ,730,730,730 ,0,0,0}, {33117,33276,33116 ,730,730,730 ,0,0,0}, + {33120,33277,33117 ,730,730,730 ,0,0,0}, {33275,33278,33122 ,730,730,730 ,0,0,0}, + {33136,33275,31755 ,730,730,730 ,0,0,0}, {33274,33134,31755 ,730,730,730 ,0,0,0}, + {33270,33132,33274 ,730,730,730 ,0,0,0}, {33125,33130,33272 ,730,730,730 ,0,0,0}, + {33130,33270,33272 ,730,730,730 ,0,0,0}, {33126,33125,33273 ,730,730,730 ,0,0,0}, + {33271,33140,33273 ,730,730,730 ,0,0,0}, {33269,33142,33271 ,730,730,730 ,0,0,0}, + {33143,33141,33268 ,730,730,730 ,0,0,0}, {33267,33146,33268 ,730,730,730 ,0,0,0}, + {31726,33129,33267 ,730,730,730 ,0,0,0}, {33150,33264,33265 ,730,730,730 ,0,0,0}, + {33154,33147,33265 ,730,730,730 ,0,0,0}, {33262,33153,33266 ,730,730,730 ,0,0,0}, + {33266,33154,33265 ,730,730,730 ,0,0,0}, {33263,33159,33151 ,730,730,730 ,0,0,0}, + {33262,33151,33153 ,730,730,730 ,0,0,0}, {33263,33295,33156 ,730,730,730 ,0,0,0}, + {33157,33258,33161 ,730,730,730 ,0,0,0}, {33156,33295,33157 ,730,730,730 ,0,0,0}, + {33161,33259,33162 ,730,730,730 ,0,0,0}, {31741,33162,33259 ,730,730,730 ,0,0,0}, + {33296,33297,33241 ,18409,18410,18410 ,0,0,0}, {33297,33168,33172 ,18410,1433,1433 ,0,0,0}, + {33241,33297,33172 ,18410,18410,1433 ,0,0,0}, {33241,33298,33296 ,18410,18409,18409 ,0,0,0}, + {33170,33299,33211 ,2162,18411,18411 ,0,0,0}, {33299,33253,33257 ,18411,2162,2162 ,0,0,0}, + {33211,33299,33257 ,18411,18411,2162 ,0,0,0}, {33211,33171,33170 ,18411,2162,2162 ,0,0,0}, + {31741,33259,33300 ,18353,18412,18413 ,0,0,0}, {33263,33301,33295 ,18414,18415,18416 ,0,0,0}, + {33302,33303,33258 ,18417,18418,18419 ,0,0,0}, {33304,33265,33305 ,18420,18421,18422 ,0,0,0}, + {33262,33266,33306 ,18423,18239,18424 ,0,0,0}, {33267,33307,33308 ,18425,18426,18427 ,0,0,0}, + {33308,33309,31726 ,18427,324,18428 ,0,0,0}, {33271,33310,33269 ,18429,18430,18431 ,0,0,0}, + {33311,33268,33269 ,18432,18433,18431 ,0,0,0}, {33273,33312,33313 ,18434,18435,18436 ,0,0,0}, + {33313,33271,33273 ,18436,18429,18434 ,0,0,0}, {33312,33272,33314 ,18435,18437,18438 ,0,0,0}, + {33272,33312,33273 ,18437,18435,18434 ,0,0,0}, {33315,33314,33270 ,18439,18438,18440 ,0,0,0}, + {33272,33270,33314 ,18437,18440,18438 ,0,0,0}, {33274,33123,33315 ,18441,18256,18439 ,0,0,0}, + {33315,33270,33274 ,18439,18440,18441 ,0,0,0}, {31755,33123,33274 ,18002,18256,18441 ,0,0,0}, + {33313,33310,33271 ,18436,18430,18429 ,0,0,0}, {33311,33269,33310 ,18432,18431,18430 ,0,0,0}, + {33311,33307,33268 ,18432,18426,18433 ,0,0,0}, {33305,33264,33309 ,18422,18442,324 ,0,0,0}, + {33267,33308,31726 ,18425,18427,18428 ,0,0,0}, {33268,33307,33267 ,18433,18426,18425 ,0,0,0}, + {33309,33264,31726 ,324,18442,18428 ,0,0,0}, {33264,33305,33265 ,18442,18422,18421 ,0,0,0}, + {33306,33266,33304 ,18424,18239,18420 ,0,0,0}, {33266,33265,33304 ,18239,18421,18420 ,0,0,0}, + {33262,33316,33263 ,18423,18443,18414 ,0,0,0}, {33316,33262,33306 ,18443,18423,18424 ,0,0,0}, + {33302,33295,33301 ,18417,18416,18415 ,0,0,0}, {33316,33301,33263 ,18443,18415,18414 ,0,0,0}, + {33258,33303,33259 ,18419,18418,18412 ,0,0,0}, {33295,33302,33258 ,18416,18417,18419 ,0,0,0}, + {31741,33300,33107 ,18353,18413,3345 ,0,0,0}, {33259,33303,33300 ,18412,18418,18413 ,0,0,0}, + {33128,33317,33255 ,18444,18444,18113 ,0,0,0}, {33128,33318,33319 ,18444,18113,18113 ,0,0,0}, + {33128,33319,33317 ,18444,18113,18444 ,0,0,0}, {33317,33256,33255 ,18444,18113,18113 ,0,0,0}, + {33206,33208,33320 ,7758,7880,7627 ,0,0,0}, {33214,33215,33321 ,726,726,7627 ,0,0,0}, + {33200,33322,33323 ,726,18445,7755 ,0,0,0}, {33324,33202,33325 ,8017,7627,7627 ,0,0,0}, + {33326,33173,33327 ,18446,7758,18447 ,0,0,0}, {33327,33196,33328 ,18447,7264,7249 ,0,0,0}, + {33329,33179,33330 ,18448,7627,18449 ,0,0,0}, {33323,33331,33197 ,7755,8018,7755 ,0,0,0}, + {33176,33332,33330 ,7761,18450,18449 ,0,0,0}, {33333,33181,33179 ,18451,726,7627 ,0,0,0}, + {33181,33333,33334 ,726,18451,726 ,0,0,0}, {33174,33326,33332 ,7755,18446,18450 ,0,0,0}, + {33335,33185,33334 ,7264,7627,726 ,0,0,0}, {33183,33336,33186 ,7758,7264,7880 ,0,0,0}, + {33337,33338,33188 ,726,7880,7627 ,0,0,0}, {33339,33216,33340 ,726,7627,726 ,0,0,0}, + {33341,33227,33228 ,726,7627,7627 ,0,0,0}, {33338,33342,33191 ,7880,7627,7880 ,0,0,0}, + {33192,33248,33343 ,7627,7627,726 ,0,0,0}, {33247,33344,33343 ,7627,7627,726 ,0,0,0}, + {33245,33345,33242 ,7625,7627,7627 ,0,0,0}, {33243,33242,33346 ,726,7627,726 ,0,0,0}, + {33226,33347,33228 ,7627,726,7627 ,0,0,0}, {33344,33247,33243 ,7627,7627,726 ,0,0,0}, + {33348,33239,33240 ,7627,726,726 ,0,0,0}, {33237,33239,33349 ,7627,726,7627 ,0,0,0}, + {33214,33321,33350 ,726,7627,726 ,0,0,0}, {33350,33351,33236 ,726,7627,7627 ,0,0,0}, + {33352,33232,33229 ,7627,726,726 ,0,0,0}, {33351,33240,33233 ,7627,726,726 ,0,0,0}, + {33352,33227,33341 ,7627,7627,726 ,0,0,0}, {33232,33353,33215 ,726,726,726 ,0,0,0}, + {33345,33237,33349 ,7627,7627,7627 ,0,0,0}, {33226,33213,33354 ,7627,7625,726 ,0,0,0}, + {33339,33212,33216 ,726,726,7627 ,0,0,0}, {33340,33216,33218 ,726,7627,726 ,0,0,0}, + {33212,33339,33354 ,726,726,726 ,0,0,0}, {33342,33250,33192 ,7627,7627,7627 ,0,0,0}, + {33355,33218,33220 ,726,726,7627 ,0,0,0}, {33218,33355,33340 ,726,726,726 ,0,0,0}, + {33209,33220,33222 ,7627,7627,7627 ,0,0,0}, {33209,33355,33220 ,7627,726,7627 ,0,0,0}, + {33222,33356,33209 ,7627,7758,7627 ,0,0,0}, {33357,33325,33203 ,7758,7627,7758 ,0,0,0}, + {33335,33358,33183 ,7264,7761,7758 ,0,0,0}, {33326,33174,33173 ,18446,7755,7758 ,0,0,0}, + {33213,33212,33354 ,7625,726,726 ,0,0,0}, {33347,33226,33354 ,726,7627,726 ,0,0,0}, + {33341,33228,33347 ,726,7627,726 ,0,0,0}, {33229,33227,33352 ,726,7627,7627 ,0,0,0}, + {33353,33232,33352 ,726,726,7627 ,0,0,0}, {33321,33215,33353 ,7627,726,726 ,0,0,0}, + {33236,33214,33350 ,7627,726,726 ,0,0,0}, {33233,33236,33351 ,726,7627,7627 ,0,0,0}, + {33348,33240,33351 ,7627,726,7627 ,0,0,0}, {33349,33239,33348 ,7627,726,7627 ,0,0,0}, + {33245,33237,33345 ,7625,7627,7627 ,0,0,0}, {33346,33242,33345 ,726,7627,7627 ,0,0,0}, + {33344,33243,33346 ,7627,726,726 ,0,0,0}, {33248,33247,33343 ,7627,7627,726 ,0,0,0}, + {33250,33248,33192 ,7627,7627,7627 ,0,0,0}, {33191,33342,33192 ,7880,7627,7627 ,0,0,0}, + {33188,33338,33191 ,7627,7880,7880 ,0,0,0}, {33336,33337,33186 ,7264,726,7880 ,0,0,0}, + {33337,33188,33186 ,726,7627,7880 ,0,0,0}, {33358,33336,33183 ,7761,7264,7758 ,0,0,0}, + {33185,33335,33183 ,7627,7264,7758 ,0,0,0}, {33181,33334,33185 ,726,726,7627 ,0,0,0}, + {33329,33333,33179 ,18448,18451,7627 ,0,0,0}, {33176,33330,33179 ,7761,18449,7627 ,0,0,0}, + {33174,33332,33176 ,7755,18450,7761 ,0,0,0}, {33327,33173,33196 ,18447,7758,7264 ,0,0,0}, + {33331,33328,33196 ,8018,7249,7264 ,0,0,0}, {33200,33323,33197 ,726,7755,7755 ,0,0,0}, + {33197,33331,33196 ,7755,8018,7264 ,0,0,0}, {33202,33322,33200 ,7627,18445,726 ,0,0,0}, + {33202,33203,33325 ,7627,7758,7627 ,0,0,0}, {33202,33324,33322 ,7627,8017,18445 ,0,0,0}, + {33203,33206,33357 ,7758,7758,7758 ,0,0,0}, {33320,33208,33356 ,7627,7880,7758 ,0,0,0}, + {33357,33206,33320 ,7758,7758,7627 ,0,0,0}, {33209,33356,33208 ,7627,7758,7880 ,0,0,0}, + {33318,33155,33359 ,1398,18452,18452 ,0,0,0}, {33296,33298,33155 ,18453,18453,18452 ,0,0,0}, + {33298,33359,33155 ,18453,18452,18452 ,0,0,0}, {33359,33319,33318 ,18452,1398,1398 ,0,0,0}, + {33360,33222,33223 ,18454,18092,18121 ,0,0,0}, {33325,33357,33254 ,18455,18456,18457 ,0,0,0}, + {33361,33320,33362 ,18458,18459,18460 ,0,0,0}, {33324,33363,33322 ,18461,18462,18463 ,0,0,0}, + {33364,33317,33326 ,18464,7309,18465 ,0,0,0}, {33365,33328,33331 ,18466,18467,18468 ,0,0,0}, + {33334,33333,33366 ,18469,18470,18471 ,0,0,0}, {33329,33330,33367 ,18472,18473,18474 ,0,0,0}, + {33335,33368,33358 ,18475,18476,18477 ,0,0,0}, {33359,33337,33336 ,18478,18479,18480 ,0,0,0}, + {33358,33359,33336 ,18477,18478,18480 ,0,0,0}, {33337,33369,33338 ,18479,18481,18482 ,0,0,0}, + {33369,33337,33359 ,18481,18479,18478 ,0,0,0}, {33369,33370,33338 ,18481,18483,18482 ,0,0,0}, + {33371,33342,33370 ,18484,18485,18483 ,0,0,0}, {33338,33370,33342 ,18482,18483,18485 ,0,0,0}, + {33371,33252,33250 ,18484,18486,82 ,0,0,0}, {33250,33342,33371 ,82,18485,18484 ,0,0,0}, + {33366,33368,33335 ,18471,18476,18475 ,0,0,0}, {33358,33368,33359 ,18477,18476,18478 ,0,0,0}, + {33333,33372,33366 ,18470,18487,18471 ,0,0,0}, {33335,33334,33366 ,18475,18469,18471 ,0,0,0}, + {33367,33372,33329 ,18474,18487,18472 ,0,0,0}, {33333,33329,33372 ,18470,18472,18487 ,0,0,0}, + {33367,33332,33317 ,18474,18488,7309 ,0,0,0}, {33330,33332,33367 ,18473,18488,18474 ,0,0,0}, + {33364,33326,33327 ,18464,18465,18489 ,0,0,0}, {33317,33332,33326 ,7309,18488,18465 ,0,0,0}, + {33328,33365,33364 ,18467,18466,18464 ,0,0,0}, {33364,33327,33328 ,18464,18489,18467 ,0,0,0}, + {33323,33373,33331 ,18490,18491,18468 ,0,0,0}, {33373,33365,33331 ,18491,18466,18468 ,0,0,0}, + {33373,33322,33363 ,18491,18463,18462 ,0,0,0}, {33322,33373,33323 ,18463,18491,18490 ,0,0,0}, + {33324,33325,33254 ,18461,18455,18457 ,0,0,0}, {33324,33254,33363 ,18461,18457,18462 ,0,0,0}, + {33357,33320,33361 ,18456,18459,18458 ,0,0,0}, {33357,33361,33254 ,18456,18458,18457 ,0,0,0}, + {33362,33356,33360 ,18460,18492,18454 ,0,0,0}, {33320,33356,33362 ,18459,18492,18460 ,0,0,0}, + {33222,33360,33356 ,18092,18454,18492 ,0,0,0}, {33246,33298,33249 ,7792,726,7658 ,0,0,0}, + {33298,33241,33249 ,726,726,7658 ,0,0,0}, {33252,33298,33251 ,7664,726,7662 ,0,0,0}, + {33298,33246,33251 ,726,7792,7662 ,0,0,0}, {33370,33298,33371 ,7662,726,5488 ,0,0,0}, + {33298,33252,33371 ,726,7664,5488 ,0,0,0}, {33359,33298,33369 ,726,726,726 ,0,0,0}, + {33298,33370,33369 ,726,7662,726 ,0,0,0}, {33373,33256,33365 ,726,726,17470 ,0,0,0}, + {33365,33256,33364 ,17470,726,7628 ,0,0,0}, {33256,33317,33364 ,726,726,7628 ,0,0,0}, + {33256,33363,33254 ,726,726,726 ,0,0,0}, {33256,33373,33363 ,726,726,726 ,0,0,0}, + {33224,33171,33211 ,726,726,726 ,0,0,0}, {33230,33171,33225 ,7661,726,7659 ,0,0,0}, + {33171,33224,33225 ,726,726,7659 ,0,0,0}, {33167,33171,33231 ,7661,726,7661 ,0,0,0}, + {33171,33230,33231 ,726,7661,7661 ,0,0,0}, {33172,33235,33234 ,7660,7660,7660 ,0,0,0}, + {33167,33235,33172 ,726,7660,7660 ,0,0,0}, {33172,33244,33241 ,7660,726,726 ,0,0,0}, + {33172,33238,33244 ,7660,7658,726 ,0,0,0}, {33234,33238,33172 ,7660,7658,7660 ,0,0,0}, + {33359,33368,33319 ,726,726,726 ,0,0,0}, {33372,33319,33366 ,726,726,7661 ,0,0,0}, + {33368,33366,33319 ,726,7661,726 ,0,0,0}, {33367,33317,33319 ,726,726,726 ,0,0,0}, + {33367,33319,33372 ,726,726,726 ,0,0,0}, {33361,33257,33254 ,726,726,726 ,0,0,0}, + {33360,33257,33362 ,726,726,726 ,0,0,0}, {33257,33361,33362 ,726,726,726 ,0,0,0}, + {33221,33257,33223 ,726,726,726 ,0,0,0}, {33257,33360,33223 ,726,726,726 ,0,0,0}, + {33217,33257,33219 ,726,726,7660 ,0,0,0}, {33257,33221,33219 ,726,726,7660 ,0,0,0}, + {33211,33257,33217 ,726,726,726 ,0,0,0}, {33207,33205,33374 ,726,726,7583 ,0,0,0}, + {33375,33376,33377 ,726,726,726 ,0,0,0}, {33378,33375,33210 ,726,726,726 ,0,0,0}, + {33374,33379,33207 ,7583,7583,726 ,0,0,0}, {33380,33381,33377 ,726,726,726 ,0,0,0}, + {33382,33383,33376 ,726,726,726 ,0,0,0}, {33380,33377,33383 ,726,726,726 ,0,0,0}, + {33376,33383,33377 ,726,726,726 ,0,0,0}, {33377,33384,33375 ,726,726,726 ,0,0,0}, + {33207,33378,33210 ,726,726,726 ,0,0,0}, {33210,33375,33384 ,726,726,726 ,0,0,0}, + {33374,33205,33204 ,7583,726,726 ,0,0,0}, {33207,33379,33378 ,726,7583,726 ,0,0,0}, + {33385,33204,33201 ,7583,726,726 ,0,0,0}, {33204,33385,33374 ,726,7583,7583 ,0,0,0}, + {33201,33386,33387 ,726,726,726 ,0,0,0}, {33385,33201,33387 ,7583,726,726 ,0,0,0}, + {33199,33386,33201 ,726,726,726 ,0,0,0}, {33386,33198,33388 ,726,726,726 ,0,0,0}, + {33198,33386,33199 ,726,726,726 ,0,0,0}, {33198,33195,33388 ,726,726,726 ,0,0,0}, + {33389,33195,33390 ,726,726,5489 ,0,0,0}, {33389,33388,33195 ,726,726,726 ,0,0,0}, + {33390,33194,33175 ,5489,7583,726 ,0,0,0}, {33195,33194,33390 ,726,7583,5489 ,0,0,0}, + {33178,33193,33175 ,7583,7583,726 ,0,0,0}, {33390,33175,33193 ,5489,726,7583 ,0,0,0}, + {33182,33189,33177 ,7583,7583,726 ,0,0,0}, {33177,33180,33182 ,726,726,7583 ,0,0,0}, + {33189,33184,33187 ,7583,7583,726 ,0,0,0}, {33189,33178,33177 ,7583,7583,726 ,0,0,0}, + {33189,33190,33178 ,7583,5489,7583 ,0,0,0}, {33189,33182,33184 ,7583,7583,7583 ,0,0,0}, + {33178,33190,33193 ,7583,5489,7583 ,0,0,0}, {33192,33343,33390 ,35,18493,18494 ,0,0,0}, + {33345,33386,33346 ,18495,18496,18497 ,0,0,0}, {33388,33389,33344 ,18498,18499,18500 ,0,0,0}, + {33374,33351,33379 ,18501,18502,18503 ,0,0,0}, {33349,33348,33385 ,18504,18505,18506 ,0,0,0}, + {33353,33376,33375 ,18507,18508,18509 ,0,0,0}, {33375,33378,33321 ,18509,18510,18511 ,0,0,0}, + {33347,33383,33341 ,18512,18513,18514 ,0,0,0}, {33382,33352,33341 ,18515,18516,18514 ,0,0,0}, + {33354,33381,33380 ,18517,18518,18519 ,0,0,0}, {33380,33347,33354 ,18519,18512,18517 ,0,0,0}, + {33381,33339,33377 ,18518,18520,18521 ,0,0,0}, {33339,33381,33354 ,18520,18518,18517 ,0,0,0}, + {33384,33377,33340 ,18522,18521,18523 ,0,0,0}, {33339,33340,33377 ,18520,18523,18521 ,0,0,0}, + {33355,33210,33384 ,18524,18188,18522 ,0,0,0}, {33384,33340,33355 ,18522,18523,18524 ,0,0,0}, + {33209,33210,33355 ,18188,18188,18524 ,0,0,0}, {33380,33383,33347 ,18519,18513,18512 ,0,0,0}, + {33382,33341,33383 ,18515,18514,18513 ,0,0,0}, {33382,33376,33352 ,18515,18508,18516 ,0,0,0}, + {33379,33350,33378 ,18503,18525,18510 ,0,0,0}, {33353,33375,33321 ,18507,18509,18511 ,0,0,0}, + {33352,33376,33353 ,18516,18508,18507 ,0,0,0}, {33378,33350,33321 ,18510,18525,18511 ,0,0,0}, + {33350,33379,33351 ,18525,18503,18502 ,0,0,0}, {33385,33348,33374 ,18506,18505,18501 ,0,0,0}, + {33348,33351,33374 ,18505,18502,18501 ,0,0,0}, {33349,33387,33345 ,18504,18526,18495 ,0,0,0}, + {33387,33349,33385 ,18526,18504,18506 ,0,0,0}, {33388,33346,33386 ,18498,18497,18496 ,0,0,0}, + {33387,33386,33345 ,18526,18496,18495 ,0,0,0}, {33344,33389,33343 ,18500,18499,18493 ,0,0,0}, + {33346,33388,33344 ,18497,18498,18500 ,0,0,0}, {33192,33390,33193 ,35,18494,763 ,0,0,0}, + {33343,33389,33390 ,18493,18499,18494 ,0,0,0}, {33391,33136,33137 ,18527,126,18026 ,0,0,0}, + {33276,33277,33299 ,18528,18529,18530 ,0,0,0}, {33392,33278,33393 ,18531,18532,18533 ,0,0,0}, + {33279,33394,33260 ,18534,18535,18536 ,0,0,0}, {33395,33169,33282 ,18537,10001,18538 ,0,0,0}, + {33396,33284,33280 ,18539,18540,18541 ,0,0,0}, {33287,33288,33397 ,18542,18543,18544 ,0,0,0}, + {33286,33285,33398 ,18545,18546,18547 ,0,0,0}, {33289,33399,33291 ,18548,18549,18550 ,0,0,0}, + {33297,33290,33292 ,18551,18552,18553 ,0,0,0}, {33291,33297,33292 ,18550,18551,18553 ,0,0,0}, + {33290,33400,33293 ,18552,18554,18555 ,0,0,0}, {33400,33290,33297 ,18554,18552,18551 ,0,0,0}, + {33400,33401,33293 ,18554,18556,18555 ,0,0,0}, {33402,33294,33401 ,18557,18558,18556 ,0,0,0}, + {33293,33401,33294 ,18555,18556,18558 ,0,0,0}, {33402,33166,33164 ,18557,5000,18205 ,0,0,0}, + {33164,33294,33402 ,18205,18558,18557 ,0,0,0}, {33397,33399,33289 ,18544,18549,18548 ,0,0,0}, + {33291,33399,33297 ,18550,18549,18551 ,0,0,0}, {33288,33403,33397 ,18543,18559,18544 ,0,0,0}, + {33289,33287,33397 ,18548,18542,18544 ,0,0,0}, {33398,33403,33286 ,18547,18559,18545 ,0,0,0}, + {33288,33286,33403 ,18543,18545,18559 ,0,0,0}, {33398,33283,33169 ,18547,18560,10001 ,0,0,0}, + {33285,33283,33398 ,18546,18560,18547 ,0,0,0}, {33395,33282,33281 ,18537,18538,18561 ,0,0,0}, + {33169,33283,33282 ,10001,18560,18538 ,0,0,0}, {33284,33396,33395 ,18540,18539,18537 ,0,0,0}, + {33395,33281,33284 ,18537,18561,18540 ,0,0,0}, {33261,33404,33280 ,18562,18563,18541 ,0,0,0}, + {33404,33396,33280 ,18563,18539,18541 ,0,0,0}, {33404,33260,33394 ,18563,18536,18535 ,0,0,0}, + {33260,33404,33261 ,18536,18563,18562 ,0,0,0}, {33279,33276,33299 ,18534,18528,18530 ,0,0,0}, + {33279,33299,33394 ,18534,18530,18535 ,0,0,0}, {33277,33278,33392 ,18529,18532,18531 ,0,0,0}, + {33277,33392,33299 ,18529,18531,18530 ,0,0,0}, {33393,33275,33391 ,18533,18564,18527 ,0,0,0}, + {33278,33275,33393 ,18532,18564,18533 ,0,0,0}, {33136,33391,33275 ,126,18527,18564 ,0,0,0}, + {33170,33404,33394 ,17561,17561,730 ,0,0,0}, {33395,33170,33169 ,730,17561,730 ,0,0,0}, + {33404,33170,33396 ,17561,17561,730 ,0,0,0}, {33170,33395,33396 ,17561,730,730 ,0,0,0}, + {33394,33299,33170 ,730,7376,17561 ,0,0,0}, {33163,33296,33155 ,18207,730,730 ,0,0,0}, + {33296,33402,33401 ,730,730,730 ,0,0,0}, {33165,33296,33160 ,17561,730,7433 ,0,0,0}, + {33296,33163,33160 ,730,18207,7433 ,0,0,0}, {33402,33296,33166 ,730,730,17561 ,0,0,0}, + {33296,33165,33166 ,730,17561,17561 ,0,0,0}, {33401,33400,33296 ,730,7433,730 ,0,0,0}, + {33400,33297,33296 ,7433,730,730 ,0,0,0}, {33139,33255,33138 ,7017,730,730 ,0,0,0}, + {33255,33124,33138 ,730,11465,730 ,0,0,0}, {33145,33255,33144 ,18565,730,730 ,0,0,0}, + {33255,33139,33144 ,730,7017,730 ,0,0,0}, {33128,33255,33145 ,18566,730,18565 ,0,0,0}, + {33403,33168,33397 ,730,7376,17561 ,0,0,0}, {33399,33397,33168 ,730,17561,7376 ,0,0,0}, + {33297,33399,33168 ,730,730,7376 ,0,0,0}, {33398,33169,33168 ,7376,730,7376 ,0,0,0}, + {33398,33168,33403 ,7376,7376,730 ,0,0,0}, {33149,33148,33318 ,18207,18207,9877 ,0,0,0}, + {33128,33149,33318 ,18567,18207,9877 ,0,0,0}, {33152,33158,33318 ,730,9878,9877 ,0,0,0}, + {33152,33318,33148 ,730,9877,18207 ,0,0,0}, {33155,33318,33158 ,730,9877,9878 ,0,0,0}, + {33299,33392,33253 ,730,730,730 ,0,0,0}, {33253,33391,33137 ,730,730,9877 ,0,0,0}, + {33391,33253,33393 ,730,730,730 ,0,0,0}, {33253,33392,33393 ,730,730,730 ,0,0,0}, + {33137,33135,33253 ,9877,730,730 ,0,0,0}, {33253,33133,33131 ,730,9878,730 ,0,0,0}, + {33135,33133,33253 ,730,9878,730 ,0,0,0}, {33131,33124,33253 ,730,730,730 ,0,0,0}, + {33300,33303,33109 ,730,730,9878 ,0,0,0}, {33093,33092,33104 ,730,730,730 ,0,0,0}, + {33090,33093,33107 ,9875,730,730 ,0,0,0}, {33109,33108,33300 ,9878,730,730 ,0,0,0}, + {33099,33102,33104 ,730,730,730 ,0,0,0}, {33095,33097,33092 ,730,730,730 ,0,0,0}, + {33099,33104,33097 ,730,730,730 ,0,0,0}, {33092,33097,33104 ,730,730,730 ,0,0,0}, + {33104,33105,33093 ,730,730,730 ,0,0,0}, {33300,33090,33107 ,730,9875,730 ,0,0,0}, + {33107,33093,33105 ,730,730,730 ,0,0,0}, {33109,33303,33302 ,9878,730,730 ,0,0,0}, + {33300,33108,33090 ,730,730,9875 ,0,0,0}, {33112,33302,33301 ,9878,730,730 ,0,0,0}, + {33302,33112,33109 ,730,9878,9878 ,0,0,0}, {33301,33115,33113 ,730,730,730 ,0,0,0}, + {33112,33301,33113 ,9878,730,730 ,0,0,0}, {33316,33115,33301 ,730,730,730 ,0,0,0}, + {33115,33306,33118 ,730,9875,9878 ,0,0,0}, {33306,33115,33316 ,9875,730,730 ,0,0,0}, + {33306,33304,33118 ,9875,730,9878 ,0,0,0}, {33119,33304,33121 ,9878,730,730 ,0,0,0}, + {33119,33118,33304 ,9878,9878,730 ,0,0,0}, {33121,33305,33309 ,730,9875,9875 ,0,0,0}, + {33304,33305,33121 ,730,9875,730 ,0,0,0}, {33308,33123,33309 ,730,9878,9875 ,0,0,0}, + {33121,33309,33123 ,730,9875,9878 ,0,0,0}, {33310,33314,33307 ,9878,9878,730 ,0,0,0}, + {33307,33311,33310 ,730,9878,9878 ,0,0,0}, {33314,33313,33312 ,9878,9878,9877 ,0,0,0}, + {33314,33308,33307 ,9878,730,730 ,0,0,0}, {33314,33315,33308 ,9878,730,730 ,0,0,0}, + {33314,33310,33313 ,9878,9878,9878 ,0,0,0}, {33308,33315,33123 ,730,730,9878 ,0,0,0} +// M3abstandhalter10mm.prt + , {33405,32470,33406 ,18258,18259,18260 ,0,0,0}, {33407,33408,33409 ,18261,18262,18263 ,0,0,0}, + {33406,32470,33409 ,18260,18259,18263 ,0,0,0}, {33408,33407,33410 ,18262,18261,18264 ,0,0,0}, + {33410,33411,33408 ,18264,18265,18262 ,0,0,0}, {33411,33412,33413 ,18265,18266,18267 ,0,0,0}, + {33410,33412,33411 ,18264,18266,18265 ,0,0,0}, {33407,33409,32470 ,18261,18263,18259 ,0,0,0}, + {33414,33415,33416 ,18268,18269,18270 ,0,0,0}, {33415,33413,33416 ,18269,18267,18270 ,0,0,0}, + {33414,33417,33418 ,18268,18271,18272 ,0,0,0}, {33418,33415,33414 ,18272,18269,18268 ,0,0,0}, + {33417,33419,33420 ,18271,18273,18274 ,0,0,0}, {33417,33420,33418 ,18271,18274,18272 ,0,0,0}, + {33412,33416,33413 ,18266,18270,18267 ,0,0,0}, {33421,33420,33419 ,18275,18274,18273 ,0,0,0}, + {33422,31643,33423 ,18276,18277,126 ,0,0,0}, {33422,33423,33421 ,18276,126,18275 ,0,0,0}, + {33419,33422,33421 ,18273,18276,18275 ,0,0,0}, {33405,33406,33424 ,18258,18260,18278 ,0,0,0}, + {33424,33425,33426 ,18278,18279,18280 ,0,0,0}, {33426,33405,33424 ,18280,18258,18278 ,0,0,0}, + {33427,33425,33428 ,18281,18279,18282 ,0,0,0}, {33425,33427,33426 ,18279,18281,18280 ,0,0,0}, + {33429,33430,33428 ,18283,18284,18282 ,0,0,0}, {33427,33428,33430 ,18281,18282,18284 ,0,0,0}, + {33429,33431,33432 ,18283,18285,18286 ,0,0,0}, {33432,33430,33429 ,18286,18284,18283 ,0,0,0}, + {33433,33431,33434 ,18287,18285,18288 ,0,0,0}, {33431,33433,33432 ,18285,18287,18286 ,0,0,0}, + {33435,33436,33434 ,18289,18290,18288 ,0,0,0}, {33433,33434,33436 ,18287,18288,18290 ,0,0,0}, + {33435,33437,33438 ,18289,18291,18292 ,0,0,0}, {33438,33436,33435 ,18292,18290,18289 ,0,0,0}, + {31657,33437,33439 ,18293,18291,18003 ,0,0,0}, {33437,31657,33438 ,18291,18293,18292 ,0,0,0}, + {33440,33441,33442 ,18294,18295,18296 ,0,0,0}, {33443,33444,33445 ,18297,21,18298 ,0,0,0}, + {33446,33440,33447 ,18299,18294,18300 ,0,0,0}, {33440,33446,33441 ,18294,18299,18295 ,0,0,0}, + {33446,33447,33448 ,18299,18300,18301 ,0,0,0}, {33449,33450,33448 ,18302,18303,18301 ,0,0,0}, + {33448,33447,33449 ,18301,18300,18302 ,0,0,0}, {33450,33451,33452 ,18303,18304,126 ,0,0,0}, + {33451,33450,33449 ,18304,18303,18302 ,0,0,0}, {33451,33453,33452 ,18304,3135,126 ,0,0,0}, + {33440,33442,33454 ,18294,18296,18305 ,0,0,0}, {33455,33454,33456 ,18306,18305,18307 ,0,0,0}, + {33442,33456,33454 ,18296,18307,18305 ,0,0,0}, {33457,33455,33458 ,18308,18306,18309 ,0,0,0}, + {33455,33456,33458 ,18306,18307,18309 ,0,0,0}, {33457,33459,33460 ,18308,18310,18311 ,0,0,0}, + {33460,33455,33457 ,18311,18306,18308 ,0,0,0}, {33461,33459,33462 ,18312,18310,18313 ,0,0,0}, + {33459,33461,33460 ,18310,18312,18311 ,0,0,0}, {33444,33461,33445 ,21,18312,18298 ,0,0,0}, + {33462,33445,33461 ,18313,18298,18312 ,0,0,0}, {33463,33464,33465 ,18314,18315,18316 ,0,0,0}, + {33443,33466,33465 ,18297,18317,18316 ,0,0,0}, {33467,33468,33469 ,18318,18319,18320 ,0,0,0}, + {33468,33464,33470 ,18319,18315,18321 ,0,0,0}, {33471,33472,33473 ,18322,18323,18324 ,0,0,0}, + {33474,33475,33471 ,18325,18326,18322 ,0,0,0}, {33476,33477,33478 ,18327,18328,18329 ,0,0,0}, + {33477,33476,33479 ,18328,18327,18330 ,0,0,0}, {33480,33481,33478 ,18037,18331,18329 ,0,0,0}, + {33476,33478,33481 ,18327,18329,18331 ,0,0,0}, {33482,33481,33480 ,18038,18331,18037 ,0,0,0}, + {33473,33479,33471 ,18324,18330,18322 ,0,0,0}, {33473,33477,33479 ,18324,18328,18330 ,0,0,0}, + {33468,33467,33474 ,18319,18318,18325 ,0,0,0}, {33471,33475,33472 ,18322,18326,18323 ,0,0,0}, + {33474,33467,33475 ,18325,18318,18326 ,0,0,0}, {33464,33463,33470 ,18315,18314,18321 ,0,0,0}, + {33469,33468,33470 ,18320,18319,18321 ,0,0,0}, {33465,33444,33443 ,18316,21,18297 ,0,0,0}, + {33463,33465,33466 ,18314,18316,18317 ,0,0,0}, {33483,33484,33485 ,18332,1077,18332 ,0,0,0}, + {33486,33487,33485 ,18333,18333,18332 ,0,0,0}, {33487,33483,33485 ,18333,18332,18332 ,0,0,0}, + {33483,33488,33484 ,18332,18334,1077 ,0,0,0}, {33489,33490,33491 ,18335,18336,324 ,0,0,0}, + {33492,33493,33494 ,18337,18338,18339 ,0,0,0}, {33491,33490,33494 ,324,18336,18339 ,0,0,0}, + {33493,33492,33495 ,18338,18337,18340 ,0,0,0}, {33495,33496,33493 ,18340,18341,18338 ,0,0,0}, + {33496,33497,33498 ,18341,18342,18343 ,0,0,0}, {33495,33497,33496 ,18340,18342,18341 ,0,0,0}, + {33492,33494,33490 ,18337,18339,18336 ,0,0,0}, {33499,33500,33501 ,18344,18345,18346 ,0,0,0}, + {33500,33498,33501 ,18345,18343,18346 ,0,0,0}, {33499,33502,33503 ,18344,18347,18348 ,0,0,0}, + {33503,33500,33499 ,18348,18345,18344 ,0,0,0}, {33502,33504,33505 ,18347,18349,18350 ,0,0,0}, + {33502,33505,33503 ,18347,18350,18348 ,0,0,0}, {33497,33501,33498 ,18342,18346,18343 ,0,0,0}, + {33506,33505,33504 ,18351,18350,18349 ,0,0,0}, {33507,33508,33509 ,18352,18353,126 ,0,0,0}, + {33507,33509,33506 ,18352,126,18351 ,0,0,0}, {33504,33507,33506 ,18349,18352,18351 ,0,0,0}, + {33489,33491,33510 ,18335,324,18354 ,0,0,0}, {33510,33511,33512 ,18354,18355,18356 ,0,0,0}, + {33512,33489,33510 ,18356,18335,18354 ,0,0,0}, {33513,33511,33514 ,18357,18355,18358 ,0,0,0}, + {33511,33513,33512 ,18355,18357,18356 ,0,0,0}, {33515,33516,33514 ,18359,18360,18358 ,0,0,0}, + {33513,33514,33516 ,18357,18358,18360 ,0,0,0}, {33515,33517,33518 ,18359,18361,18362 ,0,0,0}, + {33518,33516,33515 ,18362,18360,18359 ,0,0,0}, {33519,33517,33520 ,18363,18361,18364 ,0,0,0}, + {33517,33519,33518 ,18361,18363,18362 ,0,0,0}, {33521,33522,33520 ,18365,18366,18364 ,0,0,0}, + {33519,33520,33522 ,18363,18364,18366 ,0,0,0}, {33521,33523,33524 ,18365,18367,18368 ,0,0,0}, + {33524,33522,33521 ,18368,18366,18365 ,0,0,0}, {33525,33523,33526 ,18369,18367,18188 ,0,0,0}, + {33523,33525,33524 ,18367,18369,18368 ,0,0,0}, {33527,33528,33529 ,18370,18371,18372 ,0,0,0}, + {33530,33483,33531 ,18373,324,18374 ,0,0,0}, {33532,33527,33533 ,18375,18370,18376 ,0,0,0}, + {33527,33532,33528 ,18370,18375,18371 ,0,0,0}, {33532,33533,33534 ,18375,18376,18377 ,0,0,0}, + {33535,33536,33534 ,18378,18379,18377 ,0,0,0}, {33534,33533,33535 ,18377,18376,18378 ,0,0,0}, + {33536,33537,33538 ,18379,18380,18092 ,0,0,0}, {33537,33536,33535 ,18380,18379,18378 ,0,0,0}, + {33537,33539,33538 ,18380,18381,18092 ,0,0,0}, {33527,33529,33540 ,18370,18372,18382 ,0,0,0}, + {33541,33540,33542 ,18383,18382,18384 ,0,0,0}, {33529,33542,33540 ,18372,18384,18382 ,0,0,0}, + {33543,33541,33544 ,18385,18383,18386 ,0,0,0}, {33541,33542,33544 ,18383,18384,18386 ,0,0,0}, + {33543,33545,33546 ,18385,18387,18388 ,0,0,0}, {33546,33541,33543 ,18388,18383,18385 ,0,0,0}, + {33547,33545,33548 ,18389,18387,18390 ,0,0,0}, {33545,33547,33546 ,18387,18389,18388 ,0,0,0}, + {33483,33547,33531 ,324,18389,18374 ,0,0,0}, {33548,33531,33547 ,18390,18374,18389 ,0,0,0}, + {33549,33550,33551 ,18391,18392,18393 ,0,0,0}, {33530,33552,33551 ,18373,18394,18393 ,0,0,0}, + {33553,33554,33555 ,18395,18396,18397 ,0,0,0}, {33554,33550,33556 ,18396,18392,18398 ,0,0,0}, + {33557,33558,33559 ,18399,18400,18401 ,0,0,0}, {33560,33561,33557 ,18402,18403,18399 ,0,0,0}, + {33562,33563,33564 ,18404,18405,18406 ,0,0,0}, {33563,33562,33565 ,18405,18404,18407 ,0,0,0}, + {33566,33567,33564 ,82,18408,18406 ,0,0,0}, {33562,33564,33567 ,18404,18406,18408 ,0,0,0}, + {33568,33567,33566 ,18103,18408,82 ,0,0,0}, {33559,33565,33557 ,18401,18407,18399 ,0,0,0}, + {33559,33563,33565 ,18401,18405,18407 ,0,0,0}, {33554,33553,33560 ,18396,18395,18402 ,0,0,0}, + {33557,33561,33558 ,18399,18403,18400 ,0,0,0}, {33560,33553,33561 ,18402,18395,18403 ,0,0,0}, + {33550,33549,33556 ,18392,18391,18398 ,0,0,0}, {33555,33554,33556 ,18397,18396,18398 ,0,0,0}, + {33551,33483,33530 ,18393,324,18373 ,0,0,0}, {33549,33551,33552 ,18391,18393,18394 ,0,0,0}, + {33569,33440,33570 ,2197,2197,2197 ,0,0,0}, {33571,33572,33440 ,2197,2197,2197 ,0,0,0}, + {33572,33570,33440 ,2197,2197,2197 ,0,0,0}, {33570,33573,33569 ,2197,2197,2197 ,0,0,0}, + {33574,33575,33477 ,730,730,730 ,0,0,0}, {33430,33576,33577 ,730,730,730 ,0,0,0}, + {33578,33579,33467 ,730,730,730 ,0,0,0}, {33475,33579,33472 ,730,730,730 ,0,0,0}, + {33443,33580,33466 ,730,730,730 ,0,0,0}, {33466,33581,33463 ,730,730,730 ,0,0,0}, + {33582,33469,33470 ,730,730,730 ,0,0,0}, {33462,33583,33445 ,730,730,730 ,0,0,0}, + {33459,33584,33462 ,730,730,730 ,0,0,0}, {33585,33584,33457 ,730,730,730 ,0,0,0}, + {33457,33458,33585 ,730,730,730 ,0,0,0}, {33446,33448,33586 ,730,730,730 ,0,0,0}, + {33587,33458,33456 ,730,730,730 ,0,0,0}, {33441,33588,33589 ,730,730,730 ,0,0,0}, + {33590,33448,33450 ,730,730,730 ,0,0,0}, {31657,33450,33452 ,730,730,730 ,0,0,0}, + {31657,33591,33438 ,730,730,730 ,0,0,0}, {33592,33433,33593 ,730,730,730 ,0,0,0}, + {33436,33438,33594 ,730,730,730 ,0,0,0}, {33436,33594,33593 ,730,730,730 ,0,0,0}, + {33592,33595,33432 ,730,730,730 ,0,0,0}, {33430,33432,33576 ,730,730,730 ,0,0,0}, + {33442,33589,33456 ,730,730,730 ,0,0,0}, {33427,33577,33596 ,730,730,730 ,0,0,0}, + {33405,33426,33597 ,730,730,730 ,0,0,0}, {33405,33598,32470 ,730,730,730 ,0,0,0}, + {33598,33599,32470 ,730,730,730 ,0,0,0}, {33426,33596,33600 ,730,730,730 ,0,0,0}, + {33601,33407,33599 ,730,730,730 ,0,0,0}, {33410,33601,33602 ,730,730,730 ,0,0,0}, + {33603,33412,33604 ,730,730,730 ,0,0,0}, {33412,33410,33604 ,730,730,730 ,0,0,0}, + {33416,33603,33605 ,730,730,730 ,0,0,0}, {33606,33419,33417 ,730,730,730 ,0,0,0}, + {33607,33414,33605 ,730,730,730 ,0,0,0}, {33606,33417,33608 ,730,730,730 ,0,0,0}, + {33580,33443,31628 ,730,730,730 ,0,0,0}, {33422,33419,33609 ,730,730,730 ,0,0,0}, + {33606,33609,33419 ,730,730,730 ,0,0,0}, {33422,33610,31643 ,730,730,730 ,0,0,0}, + {33610,33422,33609 ,730,730,730 ,0,0,0}, {31643,33480,33478 ,730,730,730 ,0,0,0}, + {33610,33480,31643 ,730,730,730 ,0,0,0}, {33611,33574,33473 ,730,730,730 ,0,0,0}, + {31628,33443,33445 ,730,730,730 ,0,0,0}, {33607,33608,33414 ,730,730,730 ,0,0,0}, + {33608,33417,33414 ,730,730,730 ,0,0,0}, {33416,33605,33414 ,730,730,730 ,0,0,0}, + {33412,33603,33416 ,730,730,730 ,0,0,0}, {33602,33604,33410 ,730,730,730 ,0,0,0}, + {33407,33601,33410 ,730,730,730 ,0,0,0}, {32470,33599,33407 ,730,730,730 ,0,0,0}, + {33597,33598,33405 ,730,730,730 ,0,0,0}, {33600,33597,33426 ,730,730,730 ,0,0,0}, + {33427,33596,33426 ,730,730,730 ,0,0,0}, {33430,33577,33427 ,730,730,730 ,0,0,0}, + {33595,33576,33432 ,730,730,730 ,0,0,0}, {33433,33592,33432 ,730,730,730 ,0,0,0}, + {33436,33593,33433 ,730,730,730 ,0,0,0}, {33591,33594,33438 ,730,730,730 ,0,0,0}, + {33452,33591,31657 ,730,730,730 ,0,0,0}, {33590,33450,31657 ,730,730,730 ,0,0,0}, + {33586,33448,33590 ,730,730,730 ,0,0,0}, {33441,33446,33588 ,730,730,730 ,0,0,0}, + {33446,33586,33588 ,730,730,730 ,0,0,0}, {33442,33441,33589 ,730,730,730 ,0,0,0}, + {33587,33456,33589 ,730,730,730 ,0,0,0}, {33585,33458,33587 ,730,730,730 ,0,0,0}, + {33459,33457,33584 ,730,730,730 ,0,0,0}, {33583,33462,33584 ,730,730,730 ,0,0,0}, + {31628,33445,33583 ,730,730,730 ,0,0,0}, {33466,33580,33581 ,730,730,730 ,0,0,0}, + {33470,33463,33581 ,730,730,730 ,0,0,0}, {33578,33469,33582 ,730,730,730 ,0,0,0}, + {33582,33470,33581 ,730,730,730 ,0,0,0}, {33579,33475,33467 ,730,730,730 ,0,0,0}, + {33578,33467,33469 ,730,730,730 ,0,0,0}, {33579,33611,33472 ,730,730,730 ,0,0,0}, + {33473,33574,33477 ,730,730,730 ,0,0,0}, {33472,33611,33473 ,730,730,730 ,0,0,0}, + {33477,33575,33478 ,730,730,730 ,0,0,0}, {31643,33478,33575 ,730,730,730 ,0,0,0}, + {33612,33613,33557 ,18409,18410,18410 ,0,0,0}, {33613,33484,33488 ,18410,1433,1433 ,0,0,0}, + {33557,33613,33488 ,18410,18410,1433 ,0,0,0}, {33557,33614,33612 ,18410,18409,18409 ,0,0,0}, + {33486,33615,33527 ,2162,18411,18411 ,0,0,0}, {33615,33569,33573 ,18411,2162,2162 ,0,0,0}, + {33527,33615,33573 ,18411,18411,2162 ,0,0,0}, {33527,33487,33486 ,18411,2162,2162 ,0,0,0}, + {31643,33575,33616 ,18353,18412,18413 ,0,0,0}, {33579,33617,33611 ,18414,18415,18416 ,0,0,0}, + {33618,33619,33574 ,18417,18418,18419 ,0,0,0}, {33620,33581,33621 ,18420,18421,18422 ,0,0,0}, + {33578,33582,33622 ,18423,18239,18424 ,0,0,0}, {33583,33623,33624 ,18425,18426,18427 ,0,0,0}, + {33624,33625,31628 ,18427,324,18428 ,0,0,0}, {33587,33626,33585 ,18429,18430,18431 ,0,0,0}, + {33627,33584,33585 ,18432,18433,18431 ,0,0,0}, {33589,33628,33629 ,18434,18435,18436 ,0,0,0}, + {33629,33587,33589 ,18436,18429,18434 ,0,0,0}, {33628,33588,33630 ,18435,18437,18438 ,0,0,0}, + {33588,33628,33589 ,18437,18435,18434 ,0,0,0}, {33631,33630,33586 ,18439,18438,18440 ,0,0,0}, + {33588,33586,33630 ,18437,18440,18438 ,0,0,0}, {33590,33439,33631 ,18441,18256,18439 ,0,0,0}, + {33631,33586,33590 ,18439,18440,18441 ,0,0,0}, {31657,33439,33590 ,18002,18256,18441 ,0,0,0}, + {33629,33626,33587 ,18436,18430,18429 ,0,0,0}, {33627,33585,33626 ,18432,18431,18430 ,0,0,0}, + {33627,33623,33584 ,18432,18426,18433 ,0,0,0}, {33621,33580,33625 ,18422,18442,324 ,0,0,0}, + {33583,33624,31628 ,18425,18427,18428 ,0,0,0}, {33584,33623,33583 ,18433,18426,18425 ,0,0,0}, + {33625,33580,31628 ,324,18442,18428 ,0,0,0}, {33580,33621,33581 ,18442,18422,18421 ,0,0,0}, + {33622,33582,33620 ,18424,18239,18420 ,0,0,0}, {33582,33581,33620 ,18239,18421,18420 ,0,0,0}, + {33578,33632,33579 ,18423,18443,18414 ,0,0,0}, {33632,33578,33622 ,18443,18423,18424 ,0,0,0}, + {33618,33611,33617 ,18417,18416,18415 ,0,0,0}, {33632,33617,33579 ,18443,18415,18414 ,0,0,0}, + {33574,33619,33575 ,18419,18418,18412 ,0,0,0}, {33611,33618,33574 ,18416,18417,18419 ,0,0,0}, + {31643,33616,33423 ,18353,18413,3345 ,0,0,0}, {33575,33619,33616 ,18412,18418,18413 ,0,0,0}, + {33444,33633,33571 ,18444,18444,18113 ,0,0,0}, {33444,33634,33635 ,18444,18113,18113 ,0,0,0}, + {33444,33635,33633 ,18444,18113,18444 ,0,0,0}, {33633,33572,33571 ,18444,18113,18113 ,0,0,0}, + {33522,33524,33636 ,7758,7880,7627 ,0,0,0}, {33530,33531,33637 ,726,726,7627 ,0,0,0}, + {33516,33638,33639 ,726,18445,7755 ,0,0,0}, {33640,33518,33641 ,8017,7627,7627 ,0,0,0}, + {33642,33489,33643 ,18446,7758,18447 ,0,0,0}, {33643,33512,33644 ,18447,7264,7249 ,0,0,0}, + {33645,33495,33646 ,18448,7627,18449 ,0,0,0}, {33639,33647,33513 ,7755,8018,7755 ,0,0,0}, + {33492,33648,33646 ,7761,18450,18449 ,0,0,0}, {33649,33497,33495 ,18451,726,7627 ,0,0,0}, + {33497,33649,33650 ,726,18451,726 ,0,0,0}, {33490,33642,33648 ,7755,18446,18450 ,0,0,0}, + {33651,33501,33650 ,7264,7627,726 ,0,0,0}, {33499,33652,33502 ,7758,7264,7880 ,0,0,0}, + {33653,33654,33504 ,726,7880,7627 ,0,0,0}, {33655,33532,33656 ,726,7627,726 ,0,0,0}, + {33657,33543,33544 ,726,7627,7627 ,0,0,0}, {33654,33658,33507 ,7880,7627,7880 ,0,0,0}, + {33508,33564,33659 ,7627,7627,726 ,0,0,0}, {33563,33660,33659 ,7627,7627,726 ,0,0,0}, + {33561,33661,33558 ,7625,7627,7627 ,0,0,0}, {33559,33558,33662 ,726,7627,726 ,0,0,0}, + {33542,33663,33544 ,7627,726,7627 ,0,0,0}, {33660,33563,33559 ,7627,7627,726 ,0,0,0}, + {33664,33555,33556 ,7627,726,726 ,0,0,0}, {33553,33555,33665 ,7627,726,7627 ,0,0,0}, + {33530,33637,33666 ,726,7627,726 ,0,0,0}, {33666,33667,33552 ,726,7627,7627 ,0,0,0}, + {33668,33548,33545 ,7627,726,726 ,0,0,0}, {33667,33556,33549 ,7627,726,726 ,0,0,0}, + {33668,33543,33657 ,7627,7627,726 ,0,0,0}, {33548,33669,33531 ,726,726,726 ,0,0,0}, + {33661,33553,33665 ,7627,7627,7627 ,0,0,0}, {33542,33529,33670 ,7627,7625,726 ,0,0,0}, + {33655,33528,33532 ,726,726,7627 ,0,0,0}, {33656,33532,33534 ,726,7627,726 ,0,0,0}, + {33528,33655,33670 ,726,726,726 ,0,0,0}, {33658,33566,33508 ,7627,7627,7627 ,0,0,0}, + {33671,33534,33536 ,726,726,7627 ,0,0,0}, {33534,33671,33656 ,726,726,726 ,0,0,0}, + {33525,33536,33538 ,7627,7627,7627 ,0,0,0}, {33525,33671,33536 ,7627,726,7627 ,0,0,0}, + {33538,33672,33525 ,7627,7758,7627 ,0,0,0}, {33673,33641,33519 ,7758,7627,7758 ,0,0,0}, + {33651,33674,33499 ,7264,7761,7758 ,0,0,0}, {33642,33490,33489 ,18446,7755,7758 ,0,0,0}, + {33529,33528,33670 ,7625,726,726 ,0,0,0}, {33663,33542,33670 ,726,7627,726 ,0,0,0}, + {33657,33544,33663 ,726,7627,726 ,0,0,0}, {33545,33543,33668 ,726,7627,7627 ,0,0,0}, + {33669,33548,33668 ,726,726,7627 ,0,0,0}, {33637,33531,33669 ,7627,726,726 ,0,0,0}, + {33552,33530,33666 ,7627,726,726 ,0,0,0}, {33549,33552,33667 ,726,7627,7627 ,0,0,0}, + {33664,33556,33667 ,7627,726,7627 ,0,0,0}, {33665,33555,33664 ,7627,726,7627 ,0,0,0}, + {33561,33553,33661 ,7625,7627,7627 ,0,0,0}, {33662,33558,33661 ,726,7627,7627 ,0,0,0}, + {33660,33559,33662 ,7627,726,726 ,0,0,0}, {33564,33563,33659 ,7627,7627,726 ,0,0,0}, + {33566,33564,33508 ,7627,7627,7627 ,0,0,0}, {33507,33658,33508 ,7880,7627,7627 ,0,0,0}, + {33504,33654,33507 ,7627,7880,7880 ,0,0,0}, {33652,33653,33502 ,7264,726,7880 ,0,0,0}, + {33653,33504,33502 ,726,7627,7880 ,0,0,0}, {33674,33652,33499 ,7761,7264,7758 ,0,0,0}, + {33501,33651,33499 ,7627,7264,7758 ,0,0,0}, {33497,33650,33501 ,726,726,7627 ,0,0,0}, + {33645,33649,33495 ,18448,18451,7627 ,0,0,0}, {33492,33646,33495 ,7761,18449,7627 ,0,0,0}, + {33490,33648,33492 ,7755,18450,7761 ,0,0,0}, {33643,33489,33512 ,18447,7758,7264 ,0,0,0}, + {33647,33644,33512 ,8018,7249,7264 ,0,0,0}, {33516,33639,33513 ,726,7755,7755 ,0,0,0}, + {33513,33647,33512 ,7755,8018,7264 ,0,0,0}, {33518,33638,33516 ,7627,18445,726 ,0,0,0}, + {33518,33519,33641 ,7627,7758,7627 ,0,0,0}, {33518,33640,33638 ,7627,8017,18445 ,0,0,0}, + {33519,33522,33673 ,7758,7758,7758 ,0,0,0}, {33636,33524,33672 ,7627,7880,7758 ,0,0,0}, + {33673,33522,33636 ,7758,7758,7627 ,0,0,0}, {33525,33672,33524 ,7627,7758,7880 ,0,0,0}, + {33634,33471,33675 ,1398,18452,18452 ,0,0,0}, {33612,33614,33471 ,18453,18453,18452 ,0,0,0}, + {33614,33675,33471 ,18453,18452,18452 ,0,0,0}, {33675,33635,33634 ,18452,1398,1398 ,0,0,0}, + {33676,33538,33539 ,18454,18092,18121 ,0,0,0}, {33641,33673,33570 ,18455,18456,18457 ,0,0,0}, + {33677,33636,33678 ,18458,18459,18460 ,0,0,0}, {33640,33679,33638 ,18461,18462,18463 ,0,0,0}, + {33680,33633,33642 ,18464,7309,18465 ,0,0,0}, {33681,33644,33647 ,18466,18467,18468 ,0,0,0}, + {33650,33649,33682 ,18469,18470,18471 ,0,0,0}, {33645,33646,33683 ,18472,18473,18474 ,0,0,0}, + {33651,33684,33674 ,18475,18476,18477 ,0,0,0}, {33675,33653,33652 ,18478,18479,18480 ,0,0,0}, + {33674,33675,33652 ,18477,18478,18480 ,0,0,0}, {33653,33685,33654 ,18479,18481,18482 ,0,0,0}, + {33685,33653,33675 ,18481,18479,18478 ,0,0,0}, {33685,33686,33654 ,18481,18483,18482 ,0,0,0}, + {33687,33658,33686 ,18484,18485,18483 ,0,0,0}, {33654,33686,33658 ,18482,18483,18485 ,0,0,0}, + {33687,33568,33566 ,18484,18486,82 ,0,0,0}, {33566,33658,33687 ,82,18485,18484 ,0,0,0}, + {33682,33684,33651 ,18471,18476,18475 ,0,0,0}, {33674,33684,33675 ,18477,18476,18478 ,0,0,0}, + {33649,33688,33682 ,18470,18487,18471 ,0,0,0}, {33651,33650,33682 ,18475,18469,18471 ,0,0,0}, + {33683,33688,33645 ,18474,18487,18472 ,0,0,0}, {33649,33645,33688 ,18470,18472,18487 ,0,0,0}, + {33683,33648,33633 ,18474,18488,7309 ,0,0,0}, {33646,33648,33683 ,18473,18488,18474 ,0,0,0}, + {33680,33642,33643 ,18464,18465,18489 ,0,0,0}, {33633,33648,33642 ,7309,18488,18465 ,0,0,0}, + {33644,33681,33680 ,18467,18466,18464 ,0,0,0}, {33680,33643,33644 ,18464,18489,18467 ,0,0,0}, + {33639,33689,33647 ,18490,18491,18468 ,0,0,0}, {33689,33681,33647 ,18491,18466,18468 ,0,0,0}, + {33689,33638,33679 ,18491,18463,18462 ,0,0,0}, {33638,33689,33639 ,18463,18491,18490 ,0,0,0}, + {33640,33641,33570 ,18461,18455,18457 ,0,0,0}, {33640,33570,33679 ,18461,18457,18462 ,0,0,0}, + {33673,33636,33677 ,18456,18459,18458 ,0,0,0}, {33673,33677,33570 ,18456,18458,18457 ,0,0,0}, + {33678,33672,33676 ,18460,18492,18454 ,0,0,0}, {33636,33672,33678 ,18459,18492,18460 ,0,0,0}, + {33538,33676,33672 ,18092,18454,18492 ,0,0,0}, {33562,33614,33565 ,7792,726,7658 ,0,0,0}, + {33614,33557,33565 ,726,726,7658 ,0,0,0}, {33568,33614,33567 ,7664,726,7662 ,0,0,0}, + {33614,33562,33567 ,726,7792,7662 ,0,0,0}, {33686,33614,33687 ,7662,726,5488 ,0,0,0}, + {33614,33568,33687 ,726,7664,5488 ,0,0,0}, {33675,33614,33685 ,726,726,726 ,0,0,0}, + {33614,33686,33685 ,726,7662,726 ,0,0,0}, {33689,33572,33681 ,726,726,17470 ,0,0,0}, + {33681,33572,33680 ,17470,726,7628 ,0,0,0}, {33572,33633,33680 ,726,726,7628 ,0,0,0}, + {33572,33679,33570 ,726,726,726 ,0,0,0}, {33572,33689,33679 ,726,726,726 ,0,0,0}, + {33540,33487,33527 ,726,726,726 ,0,0,0}, {33546,33487,33541 ,7661,726,7659 ,0,0,0}, + {33487,33540,33541 ,726,726,7659 ,0,0,0}, {33483,33487,33547 ,7661,726,7661 ,0,0,0}, + {33487,33546,33547 ,726,7661,7661 ,0,0,0}, {33488,33551,33550 ,7660,7660,7660 ,0,0,0}, + {33483,33551,33488 ,726,7660,7660 ,0,0,0}, {33488,33560,33557 ,7660,726,726 ,0,0,0}, + {33488,33554,33560 ,7660,7658,726 ,0,0,0}, {33550,33554,33488 ,7660,7658,7660 ,0,0,0}, + {33675,33684,33635 ,726,726,726 ,0,0,0}, {33688,33635,33682 ,726,726,7661 ,0,0,0}, + {33684,33682,33635 ,726,7661,726 ,0,0,0}, {33683,33633,33635 ,726,726,726 ,0,0,0}, + {33683,33635,33688 ,726,726,726 ,0,0,0}, {33677,33573,33570 ,726,726,726 ,0,0,0}, + {33676,33573,33678 ,726,726,726 ,0,0,0}, {33573,33677,33678 ,726,726,726 ,0,0,0}, + {33537,33573,33539 ,726,726,726 ,0,0,0}, {33573,33676,33539 ,726,726,726 ,0,0,0}, + {33533,33573,33535 ,726,726,7660 ,0,0,0}, {33573,33537,33535 ,726,726,7660 ,0,0,0}, + {33527,33573,33533 ,726,726,726 ,0,0,0}, {33523,33521,33690 ,726,726,7583 ,0,0,0}, + {33691,33692,33693 ,726,726,726 ,0,0,0}, {33694,33691,33526 ,726,726,726 ,0,0,0}, + {33690,33695,33523 ,7583,7583,726 ,0,0,0}, {33696,33697,33693 ,726,726,726 ,0,0,0}, + {33698,33699,33692 ,726,726,726 ,0,0,0}, {33696,33693,33699 ,726,726,726 ,0,0,0}, + {33692,33699,33693 ,726,726,726 ,0,0,0}, {33693,33700,33691 ,726,726,726 ,0,0,0}, + {33523,33694,33526 ,726,726,726 ,0,0,0}, {33526,33691,33700 ,726,726,726 ,0,0,0}, + {33690,33521,33520 ,7583,726,726 ,0,0,0}, {33523,33695,33694 ,726,7583,726 ,0,0,0}, + {33701,33520,33517 ,7583,726,726 ,0,0,0}, {33520,33701,33690 ,726,7583,7583 ,0,0,0}, + {33517,33702,33703 ,726,726,726 ,0,0,0}, {33701,33517,33703 ,7583,726,726 ,0,0,0}, + {33515,33702,33517 ,726,726,726 ,0,0,0}, {33702,33514,33704 ,726,726,726 ,0,0,0}, + {33514,33702,33515 ,726,726,726 ,0,0,0}, {33514,33511,33704 ,726,726,726 ,0,0,0}, + {33705,33511,33706 ,726,726,5489 ,0,0,0}, {33705,33704,33511 ,726,726,726 ,0,0,0}, + {33706,33510,33491 ,5489,7583,726 ,0,0,0}, {33511,33510,33706 ,726,7583,5489 ,0,0,0}, + {33494,33509,33491 ,7583,7583,726 ,0,0,0}, {33706,33491,33509 ,5489,726,7583 ,0,0,0}, + {33498,33505,33493 ,7583,7583,726 ,0,0,0}, {33493,33496,33498 ,726,726,7583 ,0,0,0}, + {33505,33500,33503 ,7583,7583,726 ,0,0,0}, {33505,33494,33493 ,7583,7583,726 ,0,0,0}, + {33505,33506,33494 ,7583,5489,7583 ,0,0,0}, {33505,33498,33500 ,7583,7583,7583 ,0,0,0}, + {33494,33506,33509 ,7583,5489,7583 ,0,0,0}, {33508,33659,33706 ,35,18493,18494 ,0,0,0}, + {33661,33702,33662 ,18495,18496,18497 ,0,0,0}, {33704,33705,33660 ,18498,18499,18500 ,0,0,0}, + {33690,33667,33695 ,18501,18502,18503 ,0,0,0}, {33665,33664,33701 ,18504,18505,18506 ,0,0,0}, + {33669,33692,33691 ,18507,18508,18509 ,0,0,0}, {33691,33694,33637 ,18509,18510,18511 ,0,0,0}, + {33663,33699,33657 ,18512,18513,18514 ,0,0,0}, {33698,33668,33657 ,18515,18516,18514 ,0,0,0}, + {33670,33697,33696 ,18517,18518,18519 ,0,0,0}, {33696,33663,33670 ,18519,18512,18517 ,0,0,0}, + {33697,33655,33693 ,18518,18520,18521 ,0,0,0}, {33655,33697,33670 ,18520,18518,18517 ,0,0,0}, + {33700,33693,33656 ,18522,18521,18523 ,0,0,0}, {33655,33656,33693 ,18520,18523,18521 ,0,0,0}, + {33671,33526,33700 ,18524,18188,18522 ,0,0,0}, {33700,33656,33671 ,18522,18523,18524 ,0,0,0}, + {33525,33526,33671 ,18188,18188,18524 ,0,0,0}, {33696,33699,33663 ,18519,18513,18512 ,0,0,0}, + {33698,33657,33699 ,18515,18514,18513 ,0,0,0}, {33698,33692,33668 ,18515,18508,18516 ,0,0,0}, + {33695,33666,33694 ,18503,18525,18510 ,0,0,0}, {33669,33691,33637 ,18507,18509,18511 ,0,0,0}, + {33668,33692,33669 ,18516,18508,18507 ,0,0,0}, {33694,33666,33637 ,18510,18525,18511 ,0,0,0}, + {33666,33695,33667 ,18525,18503,18502 ,0,0,0}, {33701,33664,33690 ,18506,18505,18501 ,0,0,0}, + {33664,33667,33690 ,18505,18502,18501 ,0,0,0}, {33665,33703,33661 ,18504,18526,18495 ,0,0,0}, + {33703,33665,33701 ,18526,18504,18506 ,0,0,0}, {33704,33662,33702 ,18498,18497,18496 ,0,0,0}, + {33703,33702,33661 ,18526,18496,18495 ,0,0,0}, {33660,33705,33659 ,18500,18499,18493 ,0,0,0}, + {33662,33704,33660 ,18497,18498,18500 ,0,0,0}, {33508,33706,33509 ,35,18494,763 ,0,0,0}, + {33659,33705,33706 ,18493,18499,18494 ,0,0,0}, {33707,33452,33453 ,18527,126,18026 ,0,0,0}, + {33592,33593,33615 ,18528,18529,18530 ,0,0,0}, {33708,33594,33709 ,18531,18532,18533 ,0,0,0}, + {33595,33710,33576 ,18534,18535,18536 ,0,0,0}, {33711,33485,33598 ,18537,10001,18538 ,0,0,0}, + {33712,33600,33596 ,18539,18540,18541 ,0,0,0}, {33603,33604,33713 ,18542,18543,18544 ,0,0,0}, + {33602,33601,33714 ,18545,18546,18547 ,0,0,0}, {33605,33715,33607 ,18548,18549,18550 ,0,0,0}, + {33613,33606,33608 ,18551,18552,18553 ,0,0,0}, {33607,33613,33608 ,18550,18551,18553 ,0,0,0}, + {33606,33716,33609 ,18552,18554,18555 ,0,0,0}, {33716,33606,33613 ,18554,18552,18551 ,0,0,0}, + {33716,33717,33609 ,18554,18556,18555 ,0,0,0}, {33718,33610,33717 ,18557,18558,18556 ,0,0,0}, + {33609,33717,33610 ,18555,18556,18558 ,0,0,0}, {33718,33482,33480 ,18557,5000,18205 ,0,0,0}, + {33480,33610,33718 ,18205,18558,18557 ,0,0,0}, {33713,33715,33605 ,18544,18549,18548 ,0,0,0}, + {33607,33715,33613 ,18550,18549,18551 ,0,0,0}, {33604,33719,33713 ,18543,18559,18544 ,0,0,0}, + {33605,33603,33713 ,18548,18542,18544 ,0,0,0}, {33714,33719,33602 ,18547,18559,18545 ,0,0,0}, + {33604,33602,33719 ,18543,18545,18559 ,0,0,0}, {33714,33599,33485 ,18547,18560,10001 ,0,0,0}, + {33601,33599,33714 ,18546,18560,18547 ,0,0,0}, {33711,33598,33597 ,18537,18538,18561 ,0,0,0}, + {33485,33599,33598 ,10001,18560,18538 ,0,0,0}, {33600,33712,33711 ,18540,18539,18537 ,0,0,0}, + {33711,33597,33600 ,18537,18561,18540 ,0,0,0}, {33577,33720,33596 ,18562,18563,18541 ,0,0,0}, + {33720,33712,33596 ,18563,18539,18541 ,0,0,0}, {33720,33576,33710 ,18563,18536,18535 ,0,0,0}, + {33576,33720,33577 ,18536,18563,18562 ,0,0,0}, {33595,33592,33615 ,18534,18528,18530 ,0,0,0}, + {33595,33615,33710 ,18534,18530,18535 ,0,0,0}, {33593,33594,33708 ,18529,18532,18531 ,0,0,0}, + {33593,33708,33615 ,18529,18531,18530 ,0,0,0}, {33709,33591,33707 ,18533,18564,18527 ,0,0,0}, + {33594,33591,33709 ,18532,18564,18533 ,0,0,0}, {33452,33707,33591 ,126,18527,18564 ,0,0,0}, + {33486,33720,33710 ,17561,17561,730 ,0,0,0}, {33711,33486,33485 ,730,17561,730 ,0,0,0}, + {33720,33486,33712 ,17561,17561,730 ,0,0,0}, {33486,33711,33712 ,17561,730,730 ,0,0,0}, + {33710,33615,33486 ,730,7376,17561 ,0,0,0}, {33479,33612,33471 ,18207,730,730 ,0,0,0}, + {33612,33718,33717 ,730,730,730 ,0,0,0}, {33481,33612,33476 ,17561,730,7433 ,0,0,0}, + {33612,33479,33476 ,730,18207,7433 ,0,0,0}, {33718,33612,33482 ,730,730,17561 ,0,0,0}, + {33612,33481,33482 ,730,17561,17561 ,0,0,0}, {33717,33716,33612 ,730,7433,730 ,0,0,0}, + {33716,33613,33612 ,7433,730,730 ,0,0,0}, {33455,33571,33454 ,7017,730,730 ,0,0,0}, + {33571,33440,33454 ,730,11465,730 ,0,0,0}, {33461,33571,33460 ,18565,730,730 ,0,0,0}, + {33571,33455,33460 ,730,7017,730 ,0,0,0}, {33444,33571,33461 ,18566,730,18565 ,0,0,0}, + {33719,33484,33713 ,730,7376,17561 ,0,0,0}, {33715,33713,33484 ,730,17561,7376 ,0,0,0}, + {33613,33715,33484 ,730,730,7376 ,0,0,0}, {33714,33485,33484 ,7376,730,7376 ,0,0,0}, + {33714,33484,33719 ,7376,7376,730 ,0,0,0}, {33465,33464,33634 ,18207,18207,9877 ,0,0,0}, + {33444,33465,33634 ,18567,18207,9877 ,0,0,0}, {33468,33474,33634 ,730,9878,9877 ,0,0,0}, + {33468,33634,33464 ,730,9877,18207 ,0,0,0}, {33471,33634,33474 ,730,9877,9878 ,0,0,0}, + {33615,33708,33569 ,730,730,730 ,0,0,0}, {33569,33707,33453 ,730,730,9877 ,0,0,0}, + {33707,33569,33709 ,730,730,730 ,0,0,0}, {33569,33708,33709 ,730,730,730 ,0,0,0}, + {33453,33451,33569 ,9877,730,730 ,0,0,0}, {33569,33449,33447 ,730,9878,730 ,0,0,0}, + {33451,33449,33569 ,730,9878,730 ,0,0,0}, {33447,33440,33569 ,730,730,730 ,0,0,0}, + {33616,33619,33425 ,730,730,9878 ,0,0,0}, {33409,33408,33420 ,730,730,730 ,0,0,0}, + {33406,33409,33423 ,9875,730,730 ,0,0,0}, {33425,33424,33616 ,9878,730,730 ,0,0,0}, + {33415,33418,33420 ,730,730,730 ,0,0,0}, {33411,33413,33408 ,730,730,730 ,0,0,0}, + {33415,33420,33413 ,730,730,730 ,0,0,0}, {33408,33413,33420 ,730,730,730 ,0,0,0}, + {33420,33421,33409 ,730,730,730 ,0,0,0}, {33616,33406,33423 ,730,9875,730 ,0,0,0}, + {33423,33409,33421 ,730,730,730 ,0,0,0}, {33425,33619,33618 ,9878,730,730 ,0,0,0}, + {33616,33424,33406 ,730,730,9875 ,0,0,0}, {33428,33618,33617 ,9878,730,730 ,0,0,0}, + {33618,33428,33425 ,730,9878,9878 ,0,0,0}, {33617,33431,33429 ,730,730,730 ,0,0,0}, + {33428,33617,33429 ,9878,730,730 ,0,0,0}, {33632,33431,33617 ,730,730,730 ,0,0,0}, + {33431,33622,33434 ,730,9875,9878 ,0,0,0}, {33622,33431,33632 ,9875,730,730 ,0,0,0}, + {33622,33620,33434 ,9875,730,9878 ,0,0,0}, {33435,33620,33437 ,9878,730,730 ,0,0,0}, + {33435,33434,33620 ,9878,9878,730 ,0,0,0}, {33437,33621,33625 ,730,9875,9875 ,0,0,0}, + {33620,33621,33437 ,730,9875,730 ,0,0,0}, {33624,33439,33625 ,730,9878,9875 ,0,0,0}, + {33437,33625,33439 ,730,9875,9878 ,0,0,0}, {33626,33630,33623 ,9878,9878,730 ,0,0,0}, + {33623,33627,33626 ,730,9878,9878 ,0,0,0}, {33630,33629,33628 ,9878,9878,9877 ,0,0,0}, + {33630,33624,33623 ,9878,730,730 ,0,0,0}, {33630,33631,33624 ,9878,730,730 ,0,0,0}, + {33630,33626,33629 ,9878,9878,9878 ,0,0,0}, {33624,33631,33439 ,730,730,9878 ,0,0,0} +// M3abstandhalter10mm.prt + , {33721,32535,33722 ,18258,18259,18260 ,0,0,0}, {33723,33724,33725 ,18261,18262,18263 ,0,0,0}, + {33722,32535,33725 ,18260,18259,18263 ,0,0,0}, {33724,33723,33726 ,18262,18261,18264 ,0,0,0}, + {33726,33727,33724 ,18264,18265,18262 ,0,0,0}, {33727,33728,33729 ,18265,18266,18267 ,0,0,0}, + {33726,33728,33727 ,18264,18266,18265 ,0,0,0}, {33723,33725,32535 ,18261,18263,18259 ,0,0,0}, + {33730,33731,33732 ,18268,18269,18270 ,0,0,0}, {33731,33729,33732 ,18269,18267,18270 ,0,0,0}, + {33730,33733,33734 ,18268,18271,18272 ,0,0,0}, {33734,33731,33730 ,18272,18269,18268 ,0,0,0}, + {33733,33735,33736 ,18271,18273,18274 ,0,0,0}, {33733,33736,33734 ,18271,18274,18272 ,0,0,0}, + {33728,33732,33729 ,18266,18270,18267 ,0,0,0}, {33737,33736,33735 ,18275,18274,18273 ,0,0,0}, + {33738,31708,33739 ,18276,18277,126 ,0,0,0}, {33738,33739,33737 ,18276,126,18275 ,0,0,0}, + {33735,33738,33737 ,18273,18276,18275 ,0,0,0}, {33721,33722,33740 ,18258,18260,18278 ,0,0,0}, + {33740,33741,33742 ,18278,18279,18280 ,0,0,0}, {33742,33721,33740 ,18280,18258,18278 ,0,0,0}, + {33743,33741,33744 ,18281,18279,18282 ,0,0,0}, {33741,33743,33742 ,18279,18281,18280 ,0,0,0}, + {33745,33746,33744 ,18283,18284,18282 ,0,0,0}, {33743,33744,33746 ,18281,18282,18284 ,0,0,0}, + {33745,33747,33748 ,18283,18285,18286 ,0,0,0}, {33748,33746,33745 ,18286,18284,18283 ,0,0,0}, + {33749,33747,33750 ,18287,18285,18288 ,0,0,0}, {33747,33749,33748 ,18285,18287,18286 ,0,0,0}, + {33751,33752,33750 ,18289,18290,18288 ,0,0,0}, {33749,33750,33752 ,18287,18288,18290 ,0,0,0}, + {33751,33753,33754 ,18289,18291,18292 ,0,0,0}, {33754,33752,33751 ,18292,18290,18289 ,0,0,0}, + {31722,33753,33755 ,18293,18291,18003 ,0,0,0}, {33753,31722,33754 ,18291,18293,18292 ,0,0,0}, + {33756,33757,33758 ,18294,18295,18296 ,0,0,0}, {33759,33760,33761 ,18297,21,18298 ,0,0,0}, + {33762,33756,33763 ,18299,18294,18300 ,0,0,0}, {33756,33762,33757 ,18294,18299,18295 ,0,0,0}, + {33762,33763,33764 ,18299,18300,18301 ,0,0,0}, {33765,33766,33764 ,18302,18303,18301 ,0,0,0}, + {33764,33763,33765 ,18301,18300,18302 ,0,0,0}, {33766,33767,33768 ,18303,18304,126 ,0,0,0}, + {33767,33766,33765 ,18304,18303,18302 ,0,0,0}, {33767,33769,33768 ,18304,3135,126 ,0,0,0}, + {33756,33758,33770 ,18294,18296,18305 ,0,0,0}, {33771,33770,33772 ,18306,18305,18307 ,0,0,0}, + {33758,33772,33770 ,18296,18307,18305 ,0,0,0}, {33773,33771,33774 ,18308,18306,18309 ,0,0,0}, + {33771,33772,33774 ,18306,18307,18309 ,0,0,0}, {33773,33775,33776 ,18308,18310,18311 ,0,0,0}, + {33776,33771,33773 ,18311,18306,18308 ,0,0,0}, {33777,33775,33778 ,18312,18310,18313 ,0,0,0}, + {33775,33777,33776 ,18310,18312,18311 ,0,0,0}, {33760,33777,33761 ,21,18312,18298 ,0,0,0}, + {33778,33761,33777 ,18313,18298,18312 ,0,0,0}, {33779,33780,33781 ,18314,18315,18316 ,0,0,0}, + {33759,33782,33781 ,18297,18317,18316 ,0,0,0}, {33783,33784,33785 ,18318,18319,18320 ,0,0,0}, + {33784,33780,33786 ,18319,18315,18321 ,0,0,0}, {33787,33788,33789 ,18322,18323,18324 ,0,0,0}, + {33790,33791,33787 ,18325,18326,18322 ,0,0,0}, {33792,33793,33794 ,18327,18328,18329 ,0,0,0}, + {33793,33792,33795 ,18328,18327,18330 ,0,0,0}, {33796,33797,33794 ,18037,18331,18329 ,0,0,0}, + {33792,33794,33797 ,18327,18329,18331 ,0,0,0}, {33798,33797,33796 ,18038,18331,18037 ,0,0,0}, + {33789,33795,33787 ,18324,18330,18322 ,0,0,0}, {33789,33793,33795 ,18324,18328,18330 ,0,0,0}, + {33784,33783,33790 ,18319,18318,18325 ,0,0,0}, {33787,33791,33788 ,18322,18326,18323 ,0,0,0}, + {33790,33783,33791 ,18325,18318,18326 ,0,0,0}, {33780,33779,33786 ,18315,18314,18321 ,0,0,0}, + {33785,33784,33786 ,18320,18319,18321 ,0,0,0}, {33781,33760,33759 ,18316,21,18297 ,0,0,0}, + {33779,33781,33782 ,18314,18316,18317 ,0,0,0}, {33799,33800,33801 ,18332,1077,18332 ,0,0,0}, + {33802,33803,33801 ,18333,18333,18332 ,0,0,0}, {33803,33799,33801 ,18333,18332,18332 ,0,0,0}, + {33799,33804,33800 ,18332,18334,1077 ,0,0,0}, {33805,33806,33807 ,18335,18336,324 ,0,0,0}, + {33808,33809,33810 ,18337,18338,18339 ,0,0,0}, {33807,33806,33810 ,324,18336,18339 ,0,0,0}, + {33809,33808,33811 ,18338,18337,18340 ,0,0,0}, {33811,33812,33809 ,18340,18341,18338 ,0,0,0}, + {33812,33813,33814 ,18341,18342,18343 ,0,0,0}, {33811,33813,33812 ,18340,18342,18341 ,0,0,0}, + {33808,33810,33806 ,18337,18339,18336 ,0,0,0}, {33815,33816,33817 ,18344,18345,18346 ,0,0,0}, + {33816,33814,33817 ,18345,18343,18346 ,0,0,0}, {33815,33818,33819 ,18344,18347,18348 ,0,0,0}, + {33819,33816,33815 ,18348,18345,18344 ,0,0,0}, {33818,33820,33821 ,18347,18349,18350 ,0,0,0}, + {33818,33821,33819 ,18347,18350,18348 ,0,0,0}, {33813,33817,33814 ,18342,18346,18343 ,0,0,0}, + {33822,33821,33820 ,18351,18350,18349 ,0,0,0}, {33823,33824,33825 ,18352,18353,126 ,0,0,0}, + {33823,33825,33822 ,18352,126,18351 ,0,0,0}, {33820,33823,33822 ,18349,18352,18351 ,0,0,0}, + {33805,33807,33826 ,18335,324,18354 ,0,0,0}, {33826,33827,33828 ,18354,18355,18356 ,0,0,0}, + {33828,33805,33826 ,18356,18335,18354 ,0,0,0}, {33829,33827,33830 ,18357,18355,18358 ,0,0,0}, + {33827,33829,33828 ,18355,18357,18356 ,0,0,0}, {33831,33832,33830 ,18359,18360,18358 ,0,0,0}, + {33829,33830,33832 ,18357,18358,18360 ,0,0,0}, {33831,33833,33834 ,18359,18361,18362 ,0,0,0}, + {33834,33832,33831 ,18362,18360,18359 ,0,0,0}, {33835,33833,33836 ,18363,18361,18364 ,0,0,0}, + {33833,33835,33834 ,18361,18363,18362 ,0,0,0}, {33837,33838,33836 ,18365,18366,18364 ,0,0,0}, + {33835,33836,33838 ,18363,18364,18366 ,0,0,0}, {33837,33839,33840 ,18365,18367,18368 ,0,0,0}, + {33840,33838,33837 ,18368,18366,18365 ,0,0,0}, {33841,33839,33842 ,18369,18367,18188 ,0,0,0}, + {33839,33841,33840 ,18367,18369,18368 ,0,0,0}, {33843,33844,33845 ,18370,18371,18372 ,0,0,0}, + {33846,33799,33847 ,18373,324,18374 ,0,0,0}, {33848,33843,33849 ,18375,18370,18376 ,0,0,0}, + {33843,33848,33844 ,18370,18375,18371 ,0,0,0}, {33848,33849,33850 ,18375,18376,18377 ,0,0,0}, + {33851,33852,33850 ,18378,18379,18377 ,0,0,0}, {33850,33849,33851 ,18377,18376,18378 ,0,0,0}, + {33852,33853,33854 ,18379,18380,18092 ,0,0,0}, {33853,33852,33851 ,18380,18379,18378 ,0,0,0}, + {33853,33855,33854 ,18380,18381,18092 ,0,0,0}, {33843,33845,33856 ,18370,18372,18382 ,0,0,0}, + {33857,33856,33858 ,18383,18382,18384 ,0,0,0}, {33845,33858,33856 ,18372,18384,18382 ,0,0,0}, + {33859,33857,33860 ,18385,18383,18386 ,0,0,0}, {33857,33858,33860 ,18383,18384,18386 ,0,0,0}, + {33859,33861,33862 ,18385,18387,18388 ,0,0,0}, {33862,33857,33859 ,18388,18383,18385 ,0,0,0}, + {33863,33861,33864 ,18389,18387,18390 ,0,0,0}, {33861,33863,33862 ,18387,18389,18388 ,0,0,0}, + {33799,33863,33847 ,324,18389,18374 ,0,0,0}, {33864,33847,33863 ,18390,18374,18389 ,0,0,0}, + {33865,33866,33867 ,18391,18392,18393 ,0,0,0}, {33846,33868,33867 ,18373,18394,18393 ,0,0,0}, + {33869,33870,33871 ,18395,18396,18397 ,0,0,0}, {33870,33866,33872 ,18396,18392,18398 ,0,0,0}, + {33873,33874,33875 ,18399,18400,18401 ,0,0,0}, {33876,33877,33873 ,18402,18403,18399 ,0,0,0}, + {33878,33879,33880 ,18404,18405,18406 ,0,0,0}, {33879,33878,33881 ,18405,18404,18407 ,0,0,0}, + {33882,33883,33880 ,82,18408,18406 ,0,0,0}, {33878,33880,33883 ,18404,18406,18408 ,0,0,0}, + {33884,33883,33882 ,18103,18408,82 ,0,0,0}, {33875,33881,33873 ,18401,18407,18399 ,0,0,0}, + {33875,33879,33881 ,18401,18405,18407 ,0,0,0}, {33870,33869,33876 ,18396,18395,18402 ,0,0,0}, + {33873,33877,33874 ,18399,18403,18400 ,0,0,0}, {33876,33869,33877 ,18402,18395,18403 ,0,0,0}, + {33866,33865,33872 ,18392,18391,18398 ,0,0,0}, {33871,33870,33872 ,18397,18396,18398 ,0,0,0}, + {33867,33799,33846 ,18393,324,18373 ,0,0,0}, {33865,33867,33868 ,18391,18393,18394 ,0,0,0}, + {33885,33756,33886 ,2197,2197,2197 ,0,0,0}, {33887,33888,33756 ,2197,2197,2197 ,0,0,0}, + {33888,33886,33756 ,2197,2197,2197 ,0,0,0}, {33886,33889,33885 ,2197,2197,2197 ,0,0,0}, + {33890,33891,33793 ,730,730,730 ,0,0,0}, {33746,33892,33893 ,730,730,730 ,0,0,0}, + {33894,33895,33783 ,730,730,730 ,0,0,0}, {33791,33895,33788 ,730,730,730 ,0,0,0}, + {33759,33896,33782 ,730,730,730 ,0,0,0}, {33782,33897,33779 ,730,730,730 ,0,0,0}, + {33898,33785,33786 ,730,730,730 ,0,0,0}, {33778,33899,33761 ,730,730,730 ,0,0,0}, + {33775,33900,33778 ,730,730,730 ,0,0,0}, {33901,33900,33773 ,730,730,730 ,0,0,0}, + {33773,33774,33901 ,730,730,730 ,0,0,0}, {33762,33764,33902 ,730,730,730 ,0,0,0}, + {33903,33774,33772 ,730,730,730 ,0,0,0}, {33757,33904,33905 ,730,730,730 ,0,0,0}, + {33906,33764,33766 ,730,730,730 ,0,0,0}, {31722,33766,33768 ,730,730,730 ,0,0,0}, + {31722,33907,33754 ,730,730,730 ,0,0,0}, {33908,33749,33909 ,730,730,730 ,0,0,0}, + {33752,33754,33910 ,730,730,730 ,0,0,0}, {33752,33910,33909 ,730,730,730 ,0,0,0}, + {33908,33911,33748 ,730,730,730 ,0,0,0}, {33746,33748,33892 ,730,730,730 ,0,0,0}, + {33758,33905,33772 ,730,730,730 ,0,0,0}, {33743,33893,33912 ,730,730,730 ,0,0,0}, + {33721,33742,33913 ,730,730,730 ,0,0,0}, {33721,33914,32535 ,730,730,730 ,0,0,0}, + {33914,33915,32535 ,730,730,730 ,0,0,0}, {33742,33912,33916 ,730,730,730 ,0,0,0}, + {33917,33723,33915 ,730,730,730 ,0,0,0}, {33726,33917,33918 ,730,730,730 ,0,0,0}, + {33919,33728,33920 ,730,730,730 ,0,0,0}, {33728,33726,33920 ,730,730,730 ,0,0,0}, + {33732,33919,33921 ,730,730,730 ,0,0,0}, {33922,33735,33733 ,730,730,730 ,0,0,0}, + {33923,33730,33921 ,730,730,730 ,0,0,0}, {33922,33733,33924 ,730,730,730 ,0,0,0}, + {33896,33759,31692 ,730,730,730 ,0,0,0}, {33738,33735,33925 ,730,730,730 ,0,0,0}, + {33922,33925,33735 ,730,730,730 ,0,0,0}, {33738,33926,31708 ,730,730,730 ,0,0,0}, + {33926,33738,33925 ,730,730,730 ,0,0,0}, {31708,33796,33794 ,730,730,730 ,0,0,0}, + {33926,33796,31708 ,730,730,730 ,0,0,0}, {33927,33890,33789 ,730,730,730 ,0,0,0}, + {31692,33759,33761 ,730,730,730 ,0,0,0}, {33923,33924,33730 ,730,730,730 ,0,0,0}, + {33924,33733,33730 ,730,730,730 ,0,0,0}, {33732,33921,33730 ,730,730,730 ,0,0,0}, + {33728,33919,33732 ,730,730,730 ,0,0,0}, {33918,33920,33726 ,730,730,730 ,0,0,0}, + {33723,33917,33726 ,730,730,730 ,0,0,0}, {32535,33915,33723 ,730,730,730 ,0,0,0}, + {33913,33914,33721 ,730,730,730 ,0,0,0}, {33916,33913,33742 ,730,730,730 ,0,0,0}, + {33743,33912,33742 ,730,730,730 ,0,0,0}, {33746,33893,33743 ,730,730,730 ,0,0,0}, + {33911,33892,33748 ,730,730,730 ,0,0,0}, {33749,33908,33748 ,730,730,730 ,0,0,0}, + {33752,33909,33749 ,730,730,730 ,0,0,0}, {33907,33910,33754 ,730,730,730 ,0,0,0}, + {33768,33907,31722 ,730,730,730 ,0,0,0}, {33906,33766,31722 ,730,730,730 ,0,0,0}, + {33902,33764,33906 ,730,730,730 ,0,0,0}, {33757,33762,33904 ,730,730,730 ,0,0,0}, + {33762,33902,33904 ,730,730,730 ,0,0,0}, {33758,33757,33905 ,730,730,730 ,0,0,0}, + {33903,33772,33905 ,730,730,730 ,0,0,0}, {33901,33774,33903 ,730,730,730 ,0,0,0}, + {33775,33773,33900 ,730,730,730 ,0,0,0}, {33899,33778,33900 ,730,730,730 ,0,0,0}, + {31692,33761,33899 ,730,730,730 ,0,0,0}, {33782,33896,33897 ,730,730,730 ,0,0,0}, + {33786,33779,33897 ,730,730,730 ,0,0,0}, {33894,33785,33898 ,730,730,730 ,0,0,0}, + {33898,33786,33897 ,730,730,730 ,0,0,0}, {33895,33791,33783 ,730,730,730 ,0,0,0}, + {33894,33783,33785 ,730,730,730 ,0,0,0}, {33895,33927,33788 ,730,730,730 ,0,0,0}, + {33789,33890,33793 ,730,730,730 ,0,0,0}, {33788,33927,33789 ,730,730,730 ,0,0,0}, + {33793,33891,33794 ,730,730,730 ,0,0,0}, {31708,33794,33891 ,730,730,730 ,0,0,0}, + {33928,33929,33873 ,18409,18410,18410 ,0,0,0}, {33929,33800,33804 ,18410,1433,1433 ,0,0,0}, + {33873,33929,33804 ,18410,18410,1433 ,0,0,0}, {33873,33930,33928 ,18410,18409,18409 ,0,0,0}, + {33802,33931,33843 ,2162,18411,18411 ,0,0,0}, {33931,33885,33889 ,18411,2162,2162 ,0,0,0}, + {33843,33931,33889 ,18411,18411,2162 ,0,0,0}, {33843,33803,33802 ,18411,2162,2162 ,0,0,0}, + {31708,33891,33932 ,18353,18412,18413 ,0,0,0}, {33895,33933,33927 ,18414,18415,18416 ,0,0,0}, + {33934,33935,33890 ,18417,18418,18419 ,0,0,0}, {33936,33897,33937 ,18420,18421,18422 ,0,0,0}, + {33894,33898,33938 ,18423,18239,18424 ,0,0,0}, {33899,33939,33940 ,18425,18426,18427 ,0,0,0}, + {33940,33941,31692 ,18427,324,18428 ,0,0,0}, {33903,33942,33901 ,18429,18430,18431 ,0,0,0}, + {33943,33900,33901 ,18432,18433,18431 ,0,0,0}, {33905,33944,33945 ,18434,18435,18436 ,0,0,0}, + {33945,33903,33905 ,18436,18429,18434 ,0,0,0}, {33944,33904,33946 ,18435,18437,18438 ,0,0,0}, + {33904,33944,33905 ,18437,18435,18434 ,0,0,0}, {33947,33946,33902 ,18439,18438,18440 ,0,0,0}, + {33904,33902,33946 ,18437,18440,18438 ,0,0,0}, {33906,33755,33947 ,18441,18256,18439 ,0,0,0}, + {33947,33902,33906 ,18439,18440,18441 ,0,0,0}, {31722,33755,33906 ,18002,18256,18441 ,0,0,0}, + {33945,33942,33903 ,18436,18430,18429 ,0,0,0}, {33943,33901,33942 ,18432,18431,18430 ,0,0,0}, + {33943,33939,33900 ,18432,18426,18433 ,0,0,0}, {33937,33896,33941 ,18422,18442,324 ,0,0,0}, + {33899,33940,31692 ,18425,18427,18428 ,0,0,0}, {33900,33939,33899 ,18433,18426,18425 ,0,0,0}, + {33941,33896,31692 ,324,18442,18428 ,0,0,0}, {33896,33937,33897 ,18442,18422,18421 ,0,0,0}, + {33938,33898,33936 ,18424,18239,18420 ,0,0,0}, {33898,33897,33936 ,18239,18421,18420 ,0,0,0}, + {33894,33948,33895 ,18423,18443,18414 ,0,0,0}, {33948,33894,33938 ,18443,18423,18424 ,0,0,0}, + {33934,33927,33933 ,18417,18416,18415 ,0,0,0}, {33948,33933,33895 ,18443,18415,18414 ,0,0,0}, + {33890,33935,33891 ,18419,18418,18412 ,0,0,0}, {33927,33934,33890 ,18416,18417,18419 ,0,0,0}, + {31708,33932,33739 ,18353,18413,3345 ,0,0,0}, {33891,33935,33932 ,18412,18418,18413 ,0,0,0}, + {33760,33949,33887 ,18444,18444,18113 ,0,0,0}, {33760,33950,33951 ,18444,18113,18113 ,0,0,0}, + {33760,33951,33949 ,18444,18113,18444 ,0,0,0}, {33949,33888,33887 ,18444,18113,18113 ,0,0,0}, + {33838,33840,33952 ,7758,7880,7627 ,0,0,0}, {33846,33847,33953 ,726,726,7627 ,0,0,0}, + {33832,33954,33955 ,726,18445,7755 ,0,0,0}, {33956,33834,33957 ,8017,7627,7627 ,0,0,0}, + {33958,33805,33959 ,18446,7758,18447 ,0,0,0}, {33959,33828,33960 ,18447,7264,7249 ,0,0,0}, + {33961,33811,33962 ,18448,7627,18449 ,0,0,0}, {33955,33963,33829 ,7755,8018,7755 ,0,0,0}, + {33808,33964,33962 ,7761,18450,18449 ,0,0,0}, {33965,33813,33811 ,18451,726,7627 ,0,0,0}, + {33813,33965,33966 ,726,18451,726 ,0,0,0}, {33806,33958,33964 ,7755,18446,18450 ,0,0,0}, + {33967,33817,33966 ,7264,7627,726 ,0,0,0}, {33815,33968,33818 ,7758,7264,7880 ,0,0,0}, + {33969,33970,33820 ,726,7880,7627 ,0,0,0}, {33971,33848,33972 ,726,7627,726 ,0,0,0}, + {33973,33859,33860 ,726,7627,7627 ,0,0,0}, {33970,33974,33823 ,7880,7627,7880 ,0,0,0}, + {33824,33880,33975 ,7627,7627,726 ,0,0,0}, {33879,33976,33975 ,7627,7627,726 ,0,0,0}, + {33877,33977,33874 ,7625,7627,7627 ,0,0,0}, {33875,33874,33978 ,726,7627,726 ,0,0,0}, + {33858,33979,33860 ,7627,726,7627 ,0,0,0}, {33976,33879,33875 ,7627,7627,726 ,0,0,0}, + {33980,33871,33872 ,7627,726,726 ,0,0,0}, {33869,33871,33981 ,7627,726,7627 ,0,0,0}, + {33846,33953,33982 ,726,7627,726 ,0,0,0}, {33982,33983,33868 ,726,7627,7627 ,0,0,0}, + {33984,33864,33861 ,7627,726,726 ,0,0,0}, {33983,33872,33865 ,7627,726,726 ,0,0,0}, + {33984,33859,33973 ,7627,7627,726 ,0,0,0}, {33864,33985,33847 ,726,726,726 ,0,0,0}, + {33977,33869,33981 ,7627,7627,7627 ,0,0,0}, {33858,33845,33986 ,7627,7625,726 ,0,0,0}, + {33971,33844,33848 ,726,726,7627 ,0,0,0}, {33972,33848,33850 ,726,7627,726 ,0,0,0}, + {33844,33971,33986 ,726,726,726 ,0,0,0}, {33974,33882,33824 ,7627,7627,7627 ,0,0,0}, + {33987,33850,33852 ,726,726,7627 ,0,0,0}, {33850,33987,33972 ,726,726,726 ,0,0,0}, + {33841,33852,33854 ,7627,7627,7627 ,0,0,0}, {33841,33987,33852 ,7627,726,7627 ,0,0,0}, + {33854,33988,33841 ,7627,7758,7627 ,0,0,0}, {33989,33957,33835 ,7758,7627,7758 ,0,0,0}, + {33967,33990,33815 ,7264,7761,7758 ,0,0,0}, {33958,33806,33805 ,18446,7755,7758 ,0,0,0}, + {33845,33844,33986 ,7625,726,726 ,0,0,0}, {33979,33858,33986 ,726,7627,726 ,0,0,0}, + {33973,33860,33979 ,726,7627,726 ,0,0,0}, {33861,33859,33984 ,726,7627,7627 ,0,0,0}, + {33985,33864,33984 ,726,726,7627 ,0,0,0}, {33953,33847,33985 ,7627,726,726 ,0,0,0}, + {33868,33846,33982 ,7627,726,726 ,0,0,0}, {33865,33868,33983 ,726,7627,7627 ,0,0,0}, + {33980,33872,33983 ,7627,726,7627 ,0,0,0}, {33981,33871,33980 ,7627,726,7627 ,0,0,0}, + {33877,33869,33977 ,7625,7627,7627 ,0,0,0}, {33978,33874,33977 ,726,7627,7627 ,0,0,0}, + {33976,33875,33978 ,7627,726,726 ,0,0,0}, {33880,33879,33975 ,7627,7627,726 ,0,0,0}, + {33882,33880,33824 ,7627,7627,7627 ,0,0,0}, {33823,33974,33824 ,7880,7627,7627 ,0,0,0}, + {33820,33970,33823 ,7627,7880,7880 ,0,0,0}, {33968,33969,33818 ,7264,726,7880 ,0,0,0}, + {33969,33820,33818 ,726,7627,7880 ,0,0,0}, {33990,33968,33815 ,7761,7264,7758 ,0,0,0}, + {33817,33967,33815 ,7627,7264,7758 ,0,0,0}, {33813,33966,33817 ,726,726,7627 ,0,0,0}, + {33961,33965,33811 ,18448,18451,7627 ,0,0,0}, {33808,33962,33811 ,7761,18449,7627 ,0,0,0}, + {33806,33964,33808 ,7755,18450,7761 ,0,0,0}, {33959,33805,33828 ,18447,7758,7264 ,0,0,0}, + {33963,33960,33828 ,8018,7249,7264 ,0,0,0}, {33832,33955,33829 ,726,7755,7755 ,0,0,0}, + {33829,33963,33828 ,7755,8018,7264 ,0,0,0}, {33834,33954,33832 ,7627,18445,726 ,0,0,0}, + {33834,33835,33957 ,7627,7758,7627 ,0,0,0}, {33834,33956,33954 ,7627,8017,18445 ,0,0,0}, + {33835,33838,33989 ,7758,7758,7758 ,0,0,0}, {33952,33840,33988 ,7627,7880,7758 ,0,0,0}, + {33989,33838,33952 ,7758,7758,7627 ,0,0,0}, {33841,33988,33840 ,7627,7758,7880 ,0,0,0}, + {33950,33787,33991 ,1398,18452,18452 ,0,0,0}, {33928,33930,33787 ,18453,18453,18452 ,0,0,0}, + {33930,33991,33787 ,18453,18452,18452 ,0,0,0}, {33991,33951,33950 ,18452,1398,1398 ,0,0,0}, + {33992,33854,33855 ,18454,18092,18121 ,0,0,0}, {33957,33989,33886 ,18455,18456,18457 ,0,0,0}, + {33993,33952,33994 ,18458,18459,18460 ,0,0,0}, {33956,33995,33954 ,18461,18462,18463 ,0,0,0}, + {33996,33949,33958 ,18464,7309,18465 ,0,0,0}, {33997,33960,33963 ,18466,18467,18468 ,0,0,0}, + {33966,33965,33998 ,18469,18470,18471 ,0,0,0}, {33961,33962,33999 ,18472,18473,18474 ,0,0,0}, + {33967,34000,33990 ,18475,18476,18477 ,0,0,0}, {33991,33969,33968 ,18478,18479,18480 ,0,0,0}, + {33990,33991,33968 ,18477,18478,18480 ,0,0,0}, {33969,34001,33970 ,18479,18481,18482 ,0,0,0}, + {34001,33969,33991 ,18481,18479,18478 ,0,0,0}, {34001,34002,33970 ,18481,18483,18482 ,0,0,0}, + {34003,33974,34002 ,18484,18485,18483 ,0,0,0}, {33970,34002,33974 ,18482,18483,18485 ,0,0,0}, + {34003,33884,33882 ,18484,18486,82 ,0,0,0}, {33882,33974,34003 ,82,18485,18484 ,0,0,0}, + {33998,34000,33967 ,18471,18476,18475 ,0,0,0}, {33990,34000,33991 ,18477,18476,18478 ,0,0,0}, + {33965,34004,33998 ,18470,18487,18471 ,0,0,0}, {33967,33966,33998 ,18475,18469,18471 ,0,0,0}, + {33999,34004,33961 ,18474,18487,18472 ,0,0,0}, {33965,33961,34004 ,18470,18472,18487 ,0,0,0}, + {33999,33964,33949 ,18474,18488,7309 ,0,0,0}, {33962,33964,33999 ,18473,18488,18474 ,0,0,0}, + {33996,33958,33959 ,18464,18465,18489 ,0,0,0}, {33949,33964,33958 ,7309,18488,18465 ,0,0,0}, + {33960,33997,33996 ,18467,18466,18464 ,0,0,0}, {33996,33959,33960 ,18464,18489,18467 ,0,0,0}, + {33955,34005,33963 ,18490,18491,18468 ,0,0,0}, {34005,33997,33963 ,18491,18466,18468 ,0,0,0}, + {34005,33954,33995 ,18491,18463,18462 ,0,0,0}, {33954,34005,33955 ,18463,18491,18490 ,0,0,0}, + {33956,33957,33886 ,18461,18455,18457 ,0,0,0}, {33956,33886,33995 ,18461,18457,18462 ,0,0,0}, + {33989,33952,33993 ,18456,18459,18458 ,0,0,0}, {33989,33993,33886 ,18456,18458,18457 ,0,0,0}, + {33994,33988,33992 ,18460,18492,18454 ,0,0,0}, {33952,33988,33994 ,18459,18492,18460 ,0,0,0}, + {33854,33992,33988 ,18092,18454,18492 ,0,0,0}, {33878,33930,33881 ,7792,726,7658 ,0,0,0}, + {33930,33873,33881 ,726,726,7658 ,0,0,0}, {33884,33930,33883 ,7664,726,7662 ,0,0,0}, + {33930,33878,33883 ,726,7792,7662 ,0,0,0}, {34002,33930,34003 ,7662,726,5488 ,0,0,0}, + {33930,33884,34003 ,726,7664,5488 ,0,0,0}, {33991,33930,34001 ,726,726,726 ,0,0,0}, + {33930,34002,34001 ,726,7662,726 ,0,0,0}, {34005,33888,33997 ,726,726,17470 ,0,0,0}, + {33997,33888,33996 ,17470,726,7628 ,0,0,0}, {33888,33949,33996 ,726,726,7628 ,0,0,0}, + {33888,33995,33886 ,726,726,726 ,0,0,0}, {33888,34005,33995 ,726,726,726 ,0,0,0}, + {33856,33803,33843 ,726,726,726 ,0,0,0}, {33862,33803,33857 ,7661,726,7659 ,0,0,0}, + {33803,33856,33857 ,726,726,7659 ,0,0,0}, {33799,33803,33863 ,7661,726,7661 ,0,0,0}, + {33803,33862,33863 ,726,7661,7661 ,0,0,0}, {33804,33867,33866 ,7660,7660,7660 ,0,0,0}, + {33799,33867,33804 ,726,7660,7660 ,0,0,0}, {33804,33876,33873 ,7660,726,726 ,0,0,0}, + {33804,33870,33876 ,7660,7658,726 ,0,0,0}, {33866,33870,33804 ,7660,7658,7660 ,0,0,0}, + {33991,34000,33951 ,726,726,726 ,0,0,0}, {34004,33951,33998 ,726,726,7661 ,0,0,0}, + {34000,33998,33951 ,726,7661,726 ,0,0,0}, {33999,33949,33951 ,726,726,726 ,0,0,0}, + {33999,33951,34004 ,726,726,726 ,0,0,0}, {33993,33889,33886 ,726,726,726 ,0,0,0}, + {33992,33889,33994 ,726,726,726 ,0,0,0}, {33889,33993,33994 ,726,726,726 ,0,0,0}, + {33853,33889,33855 ,726,726,726 ,0,0,0}, {33889,33992,33855 ,726,726,726 ,0,0,0}, + {33849,33889,33851 ,726,726,7660 ,0,0,0}, {33889,33853,33851 ,726,726,7660 ,0,0,0}, + {33843,33889,33849 ,726,726,726 ,0,0,0}, {33839,33837,34006 ,726,726,7583 ,0,0,0}, + {34007,34008,34009 ,726,726,726 ,0,0,0}, {34010,34007,33842 ,726,726,726 ,0,0,0}, + {34006,34011,33839 ,7583,7583,726 ,0,0,0}, {34012,34013,34009 ,726,726,726 ,0,0,0}, + {34014,34015,34008 ,726,726,726 ,0,0,0}, {34012,34009,34015 ,726,726,726 ,0,0,0}, + {34008,34015,34009 ,726,726,726 ,0,0,0}, {34009,34016,34007 ,726,726,726 ,0,0,0}, + {33839,34010,33842 ,726,726,726 ,0,0,0}, {33842,34007,34016 ,726,726,726 ,0,0,0}, + {34006,33837,33836 ,7583,726,726 ,0,0,0}, {33839,34011,34010 ,726,7583,726 ,0,0,0}, + {34017,33836,33833 ,7583,726,726 ,0,0,0}, {33836,34017,34006 ,726,7583,7583 ,0,0,0}, + {33833,34018,34019 ,726,726,726 ,0,0,0}, {34017,33833,34019 ,7583,726,726 ,0,0,0}, + {33831,34018,33833 ,726,726,726 ,0,0,0}, {34018,33830,34020 ,726,726,726 ,0,0,0}, + {33830,34018,33831 ,726,726,726 ,0,0,0}, {33830,33827,34020 ,726,726,726 ,0,0,0}, + {34021,33827,34022 ,726,726,5489 ,0,0,0}, {34021,34020,33827 ,726,726,726 ,0,0,0}, + {34022,33826,33807 ,5489,7583,726 ,0,0,0}, {33827,33826,34022 ,726,7583,5489 ,0,0,0}, + {33810,33825,33807 ,7583,7583,726 ,0,0,0}, {34022,33807,33825 ,5489,726,7583 ,0,0,0}, + {33814,33821,33809 ,7583,7583,726 ,0,0,0}, {33809,33812,33814 ,726,726,7583 ,0,0,0}, + {33821,33816,33819 ,7583,7583,726 ,0,0,0}, {33821,33810,33809 ,7583,7583,726 ,0,0,0}, + {33821,33822,33810 ,7583,5489,7583 ,0,0,0}, {33821,33814,33816 ,7583,7583,7583 ,0,0,0}, + {33810,33822,33825 ,7583,5489,7583 ,0,0,0}, {33824,33975,34022 ,35,18493,18494 ,0,0,0}, + {33977,34018,33978 ,18495,18496,18497 ,0,0,0}, {34020,34021,33976 ,18498,18499,18500 ,0,0,0}, + {34006,33983,34011 ,18501,18502,18503 ,0,0,0}, {33981,33980,34017 ,18504,18505,18506 ,0,0,0}, + {33985,34008,34007 ,18507,18508,18509 ,0,0,0}, {34007,34010,33953 ,18509,18510,18511 ,0,0,0}, + {33979,34015,33973 ,18512,18513,18514 ,0,0,0}, {34014,33984,33973 ,18515,18516,18514 ,0,0,0}, + {33986,34013,34012 ,18517,18518,18519 ,0,0,0}, {34012,33979,33986 ,18519,18512,18517 ,0,0,0}, + {34013,33971,34009 ,18518,18520,18521 ,0,0,0}, {33971,34013,33986 ,18520,18518,18517 ,0,0,0}, + {34016,34009,33972 ,18522,18521,18523 ,0,0,0}, {33971,33972,34009 ,18520,18523,18521 ,0,0,0}, + {33987,33842,34016 ,18524,18188,18522 ,0,0,0}, {34016,33972,33987 ,18522,18523,18524 ,0,0,0}, + {33841,33842,33987 ,18188,18188,18524 ,0,0,0}, {34012,34015,33979 ,18519,18513,18512 ,0,0,0}, + {34014,33973,34015 ,18515,18514,18513 ,0,0,0}, {34014,34008,33984 ,18515,18508,18516 ,0,0,0}, + {34011,33982,34010 ,18503,18525,18510 ,0,0,0}, {33985,34007,33953 ,18507,18509,18511 ,0,0,0}, + {33984,34008,33985 ,18516,18508,18507 ,0,0,0}, {34010,33982,33953 ,18510,18525,18511 ,0,0,0}, + {33982,34011,33983 ,18525,18503,18502 ,0,0,0}, {34017,33980,34006 ,18506,18505,18501 ,0,0,0}, + {33980,33983,34006 ,18505,18502,18501 ,0,0,0}, {33981,34019,33977 ,18504,18526,18495 ,0,0,0}, + {34019,33981,34017 ,18526,18504,18506 ,0,0,0}, {34020,33978,34018 ,18498,18497,18496 ,0,0,0}, + {34019,34018,33977 ,18526,18496,18495 ,0,0,0}, {33976,34021,33975 ,18500,18499,18493 ,0,0,0}, + {33978,34020,33976 ,18497,18498,18500 ,0,0,0}, {33824,34022,33825 ,35,18494,763 ,0,0,0}, + {33975,34021,34022 ,18493,18499,18494 ,0,0,0}, {34023,33768,33769 ,18527,126,18026 ,0,0,0}, + {33908,33909,33931 ,18528,18529,18530 ,0,0,0}, {34024,33910,34025 ,18531,18532,18533 ,0,0,0}, + {33911,34026,33892 ,18534,18535,18536 ,0,0,0}, {34027,33801,33914 ,18537,10001,18538 ,0,0,0}, + {34028,33916,33912 ,18539,18540,18541 ,0,0,0}, {33919,33920,34029 ,18542,18543,18544 ,0,0,0}, + {33918,33917,34030 ,18545,18546,18547 ,0,0,0}, {33921,34031,33923 ,18548,18549,18550 ,0,0,0}, + {33929,33922,33924 ,18551,18552,18553 ,0,0,0}, {33923,33929,33924 ,18550,18551,18553 ,0,0,0}, + {33922,34032,33925 ,18552,18554,18555 ,0,0,0}, {34032,33922,33929 ,18554,18552,18551 ,0,0,0}, + {34032,34033,33925 ,18554,18556,18555 ,0,0,0}, {34034,33926,34033 ,18557,18558,18556 ,0,0,0}, + {33925,34033,33926 ,18555,18556,18558 ,0,0,0}, {34034,33798,33796 ,18557,5000,18205 ,0,0,0}, + {33796,33926,34034 ,18205,18558,18557 ,0,0,0}, {34029,34031,33921 ,18544,18549,18548 ,0,0,0}, + {33923,34031,33929 ,18550,18549,18551 ,0,0,0}, {33920,34035,34029 ,18543,18559,18544 ,0,0,0}, + {33921,33919,34029 ,18548,18542,18544 ,0,0,0}, {34030,34035,33918 ,18547,18559,18545 ,0,0,0}, + {33920,33918,34035 ,18543,18545,18559 ,0,0,0}, {34030,33915,33801 ,18547,18560,10001 ,0,0,0}, + {33917,33915,34030 ,18546,18560,18547 ,0,0,0}, {34027,33914,33913 ,18537,18538,18561 ,0,0,0}, + {33801,33915,33914 ,10001,18560,18538 ,0,0,0}, {33916,34028,34027 ,18540,18539,18537 ,0,0,0}, + {34027,33913,33916 ,18537,18561,18540 ,0,0,0}, {33893,34036,33912 ,18562,18563,18541 ,0,0,0}, + {34036,34028,33912 ,18563,18539,18541 ,0,0,0}, {34036,33892,34026 ,18563,18536,18535 ,0,0,0}, + {33892,34036,33893 ,18536,18563,18562 ,0,0,0}, {33911,33908,33931 ,18534,18528,18530 ,0,0,0}, + {33911,33931,34026 ,18534,18530,18535 ,0,0,0}, {33909,33910,34024 ,18529,18532,18531 ,0,0,0}, + {33909,34024,33931 ,18529,18531,18530 ,0,0,0}, {34025,33907,34023 ,18533,18564,18527 ,0,0,0}, + {33910,33907,34025 ,18532,18564,18533 ,0,0,0}, {33768,34023,33907 ,126,18527,18564 ,0,0,0}, + {33802,34036,34026 ,17561,17561,730 ,0,0,0}, {34027,33802,33801 ,730,17561,730 ,0,0,0}, + {34036,33802,34028 ,17561,17561,730 ,0,0,0}, {33802,34027,34028 ,17561,730,730 ,0,0,0}, + {34026,33931,33802 ,730,7376,17561 ,0,0,0}, {33795,33928,33787 ,18207,730,730 ,0,0,0}, + {33928,34034,34033 ,730,730,730 ,0,0,0}, {33797,33928,33792 ,17561,730,7433 ,0,0,0}, + {33928,33795,33792 ,730,18207,7433 ,0,0,0}, {34034,33928,33798 ,730,730,17561 ,0,0,0}, + {33928,33797,33798 ,730,17561,17561 ,0,0,0}, {34033,34032,33928 ,730,7433,730 ,0,0,0}, + {34032,33929,33928 ,7433,730,730 ,0,0,0}, {33771,33887,33770 ,7017,730,730 ,0,0,0}, + {33887,33756,33770 ,730,11465,730 ,0,0,0}, {33777,33887,33776 ,18565,730,730 ,0,0,0}, + {33887,33771,33776 ,730,7017,730 ,0,0,0}, {33760,33887,33777 ,18566,730,18565 ,0,0,0}, + {34035,33800,34029 ,730,7376,17561 ,0,0,0}, {34031,34029,33800 ,730,17561,7376 ,0,0,0}, + {33929,34031,33800 ,730,730,7376 ,0,0,0}, {34030,33801,33800 ,7376,730,7376 ,0,0,0}, + {34030,33800,34035 ,7376,7376,730 ,0,0,0}, {33781,33780,33950 ,18207,18207,9877 ,0,0,0}, + {33760,33781,33950 ,18567,18207,9877 ,0,0,0}, {33784,33790,33950 ,730,9878,9877 ,0,0,0}, + {33784,33950,33780 ,730,9877,18207 ,0,0,0}, {33787,33950,33790 ,730,9877,9878 ,0,0,0}, + {33931,34024,33885 ,730,730,730 ,0,0,0}, {33885,34023,33769 ,730,730,9877 ,0,0,0}, + {34023,33885,34025 ,730,730,730 ,0,0,0}, {33885,34024,34025 ,730,730,730 ,0,0,0}, + {33769,33767,33885 ,9877,730,730 ,0,0,0}, {33885,33765,33763 ,730,9878,730 ,0,0,0}, + {33767,33765,33885 ,730,9878,730 ,0,0,0}, {33763,33756,33885 ,730,730,730 ,0,0,0}, + {33932,33935,33741 ,730,730,9878 ,0,0,0}, {33725,33724,33736 ,730,730,730 ,0,0,0}, + {33722,33725,33739 ,9875,730,730 ,0,0,0}, {33741,33740,33932 ,9878,730,730 ,0,0,0}, + {33731,33734,33736 ,730,730,730 ,0,0,0}, {33727,33729,33724 ,730,730,730 ,0,0,0}, + {33731,33736,33729 ,730,730,730 ,0,0,0}, {33724,33729,33736 ,730,730,730 ,0,0,0}, + {33736,33737,33725 ,730,730,730 ,0,0,0}, {33932,33722,33739 ,730,9875,730 ,0,0,0}, + {33739,33725,33737 ,730,730,730 ,0,0,0}, {33741,33935,33934 ,9878,730,730 ,0,0,0}, + {33932,33740,33722 ,730,730,9875 ,0,0,0}, {33744,33934,33933 ,9878,730,730 ,0,0,0}, + {33934,33744,33741 ,730,9878,9878 ,0,0,0}, {33933,33747,33745 ,730,730,730 ,0,0,0}, + {33744,33933,33745 ,9878,730,730 ,0,0,0}, {33948,33747,33933 ,730,730,730 ,0,0,0}, + {33747,33938,33750 ,730,9875,9878 ,0,0,0}, {33938,33747,33948 ,9875,730,730 ,0,0,0}, + {33938,33936,33750 ,9875,730,9878 ,0,0,0}, {33751,33936,33753 ,9878,730,730 ,0,0,0}, + {33751,33750,33936 ,9878,9878,730 ,0,0,0}, {33753,33937,33941 ,730,9875,9875 ,0,0,0}, + {33936,33937,33753 ,730,9875,730 ,0,0,0}, {33940,33755,33941 ,730,9878,9875 ,0,0,0}, + {33753,33941,33755 ,730,9875,9878 ,0,0,0}, {33942,33946,33939 ,9878,9878,730 ,0,0,0}, + {33939,33943,33942 ,730,9878,9878 ,0,0,0}, {33946,33945,33944 ,9878,9878,9877 ,0,0,0}, + {33946,33940,33939 ,9878,730,730 ,0,0,0}, {33946,33947,33940 ,9878,730,730 ,0,0,0}, + {33946,33942,33945 ,9878,9878,9878 ,0,0,0}, {33940,33947,33755 ,730,730,9878 ,0,0,0} +// Airframe2.prt + , {34037,34038,34039 ,18568,18569,18569 ,0,0,0}, {34040,34041,34042 ,18570,18571,18572 ,0,0,0}, + {34039,34038,34042 ,18569,18569,18572 ,0,0,0}, {34043,34044,34045 ,18573,18573,18571 ,0,0,0}, + {34041,34040,34045 ,18571,18570,18571 ,0,0,0}, {34045,34044,34041 ,18571,18573,18571 ,0,0,0}, + {34040,34042,34038 ,18570,18572,18569 ,0,0,0}, {34039,34046,34037 ,18569,18568,18568 ,0,0,0}, + {34046,34047,34048 ,18568,18574,18574 ,0,0,0}, {34048,34037,34046 ,18574,18568,18568 ,0,0,0}, + {34049,34047,34050 ,18575,18574,18575 ,0,0,0}, {34047,34049,34048 ,18574,18575,18574 ,0,0,0}, + {34051,34052,34053 ,18576,18577,18577 ,0,0,0}, {34054,34055,34056 ,18578,18579,18580 ,0,0,0}, + {34053,34052,34056 ,18577,18577,18580 ,0,0,0}, {34057,34058,34059 ,18581,18581,18579 ,0,0,0}, + {34055,34054,34059 ,18579,18578,18579 ,0,0,0}, {34059,34058,34055 ,18579,18581,18579 ,0,0,0}, + {34054,34056,34052 ,18578,18580,18577 ,0,0,0}, {34053,34060,34051 ,18577,18576,18576 ,0,0,0}, + {34060,34061,34062 ,18576,18582,18582 ,0,0,0}, {34062,34051,34060 ,18582,18576,18576 ,0,0,0}, + {34063,34061,34064 ,18583,18582,18583 ,0,0,0}, {34061,34063,34062 ,18582,18583,18582 ,0,0,0}, + {34065,34066,34067 ,18584,18585,18585 ,0,0,0}, {34068,34069,34070 ,18586,18587,18586 ,0,0,0}, + {34067,34066,34070 ,18585,18585,18586 ,0,0,0}, {34071,34072,34073 ,18588,18588,18587 ,0,0,0}, + {34069,34068,34073 ,18587,18586,18587 ,0,0,0}, {34073,34072,34069 ,18587,18588,18587 ,0,0,0}, + {34068,34070,34066 ,18586,18586,18585 ,0,0,0}, {34067,34074,34065 ,18585,18584,18584 ,0,0,0}, + {34074,34075,34076 ,18584,18589,18589 ,0,0,0}, {34076,34065,34074 ,18589,18584,18584 ,0,0,0}, + {34077,34075,34078 ,18573,18589,18573 ,0,0,0}, {34075,34077,34076 ,18589,18573,18589 ,0,0,0}, + {34079,34080,34081 ,18590,18591,18591 ,0,0,0}, {34082,34083,34084 ,18592,18593,18592 ,0,0,0}, + {34081,34080,34084 ,18591,18591,18592 ,0,0,0}, {34085,34086,34087 ,18594,18594,18593 ,0,0,0}, + {34083,34082,34087 ,18593,18592,18593 ,0,0,0}, {34087,34086,34083 ,18593,18594,18593 ,0,0,0}, + {34082,34084,34080 ,18592,18592,18591 ,0,0,0}, {34081,34088,34079 ,18591,18590,18590 ,0,0,0}, + {34088,34089,34090 ,18590,18595,18595 ,0,0,0}, {34090,34079,34088 ,18595,18590,18590 ,0,0,0}, + {34091,34089,34092 ,18581,18595,18581 ,0,0,0}, {34089,34091,34090 ,18595,18581,18595 ,0,0,0}, + {34093,34094,34095 ,18596,18597,18597 ,0,0,0}, {34096,34097,34098 ,18598,18599,18600 ,0,0,0}, + {34095,34094,34098 ,18597,18597,18600 ,0,0,0}, {34099,34100,34101 ,18601,18601,18599 ,0,0,0}, + {34097,34096,34101 ,18599,18598,18599 ,0,0,0}, {34101,34100,34097 ,18599,18601,18599 ,0,0,0}, + {34096,34098,34094 ,18598,18600,18597 ,0,0,0}, {34095,34102,34093 ,18597,18596,18596 ,0,0,0}, + {34102,34103,34104 ,18596,18602,18602 ,0,0,0}, {34104,34093,34102 ,18602,18596,18596 ,0,0,0}, + {34105,34103,34106 ,18588,18602,18588 ,0,0,0}, {34103,34105,34104 ,18602,18588,18602 ,0,0,0}, + {34107,34108,34109 ,18603,18604,18605 ,0,0,0}, {34110,34111,34112 ,18606,18607,18608 ,0,0,0}, + {34109,34108,34112 ,18605,18604,18608 ,0,0,0}, {34113,34114,34115 ,18609,18609,18607 ,0,0,0}, + {34111,34110,34115 ,18607,18606,18607 ,0,0,0}, {34115,34114,34111 ,18607,18609,18607 ,0,0,0}, + {34110,34112,34108 ,18606,18608,18604 ,0,0,0}, {34109,34116,34107 ,18605,18603,18603 ,0,0,0}, + {34116,34117,34118 ,18603,18610,18610 ,0,0,0}, {34118,34107,34116 ,18610,18603,18603 ,0,0,0}, + {34119,34117,34120 ,18594,18610,18594 ,0,0,0}, {34117,34119,34118 ,18610,18594,18610 ,0,0,0}, + {34121,34122,34123 ,18611,18612,18612 ,0,0,0}, {34124,34125,34126 ,18613,18614,18613 ,0,0,0}, + {34123,34122,34126 ,18612,18612,18613 ,0,0,0}, {34127,34128,34129 ,18588,18588,18614 ,0,0,0}, + {34125,34124,34129 ,18614,18613,18614 ,0,0,0}, {34129,34128,34125 ,18614,18588,18614 ,0,0,0}, + {34124,34126,34122 ,18613,18613,18612 ,0,0,0}, {34123,34130,34121 ,18612,18611,18611 ,0,0,0}, + {34130,34131,34132 ,18611,18615,18615 ,0,0,0}, {34132,34121,34130 ,18615,18611,18611 ,0,0,0}, + {34133,34131,34134 ,18573,18615,18573 ,0,0,0}, {34131,34133,34132 ,18615,18573,18615 ,0,0,0}, + {34135,34136,34137 ,18616,18617,18617 ,0,0,0}, {34138,34139,34140 ,18618,18619,18618 ,0,0,0}, + {34137,34136,34140 ,18617,18617,18618 ,0,0,0}, {34141,34142,34143 ,18594,18594,18619 ,0,0,0}, + {34139,34138,34143 ,18619,18618,18619 ,0,0,0}, {34143,34142,34139 ,18619,18594,18619 ,0,0,0}, + {34138,34140,34136 ,18618,18618,18617 ,0,0,0}, {34137,34144,34135 ,18617,18616,18616 ,0,0,0}, + {34144,34145,34146 ,18616,18620,18620 ,0,0,0}, {34146,34135,34144 ,18620,18616,18616 ,0,0,0}, + {34147,34145,34148 ,18581,18620,18581 ,0,0,0}, {34145,34147,34146 ,18620,18581,18620 ,0,0,0}, + {34149,34150,34151 ,18621,18622,18622 ,0,0,0}, {34152,34153,34154 ,18623,18624,18623 ,0,0,0}, + {34151,34150,34154 ,18622,18622,18623 ,0,0,0}, {34155,34156,34157 ,18601,18601,18624 ,0,0,0}, + {34153,34152,34157 ,18624,18623,18624 ,0,0,0}, {34157,34156,34153 ,18624,18601,18624 ,0,0,0}, + {34152,34154,34150 ,18623,18623,18622 ,0,0,0}, {34151,34158,34149 ,18622,18621,18621 ,0,0,0}, + {34158,34159,34160 ,18621,18625,18625 ,0,0,0}, {34160,34149,34158 ,18625,18621,18621 ,0,0,0}, + {34161,34159,34162 ,18588,18625,18588 ,0,0,0}, {34159,34161,34160 ,18625,18588,18625 ,0,0,0}, + {34163,34164,34165 ,18626,18627,18627 ,0,0,0}, {34166,34167,34168 ,18628,18629,18628 ,0,0,0}, + {34165,34164,34168 ,18627,18627,18628 ,0,0,0}, {34169,34170,34171 ,18609,18609,18629 ,0,0,0}, + {34167,34166,34171 ,18629,18628,18629 ,0,0,0}, {34171,34170,34167 ,18629,18609,18629 ,0,0,0}, + {34166,34168,34164 ,18628,18628,18627 ,0,0,0}, {34165,34172,34163 ,18627,18626,18626 ,0,0,0}, + {34172,34173,34174 ,18626,18630,18630 ,0,0,0}, {34174,34163,34172 ,18630,18626,18626 ,0,0,0}, + {34175,34173,34176 ,18594,18630,18594 ,0,0,0}, {34173,34175,34174 ,18630,18594,18630 ,0,0,0}, + {34177,34178,34179 ,18631,18632,18632 ,0,0,0}, {34180,34181,34182 ,18633,18634,18633 ,0,0,0}, + {34179,34178,34182 ,18632,18632,18633 ,0,0,0}, {34183,34184,34185 ,18575,18575,18634 ,0,0,0}, + {34181,34180,34185 ,18634,18633,18634 ,0,0,0}, {34185,34184,34181 ,18634,18575,18634 ,0,0,0}, + {34180,34182,34178 ,18633,18633,18632 ,0,0,0}, {34179,34186,34177 ,18632,18631,18631 ,0,0,0}, + {34186,34187,34188 ,18631,18635,18635 ,0,0,0}, {34188,34177,34186 ,18635,18631,18631 ,0,0,0}, + {34189,34187,34190 ,18601,18635,18601 ,0,0,0}, {34187,34189,34188 ,18635,18601,18635 ,0,0,0}, + {34191,34192,34193 ,18636,18637,18637 ,0,0,0}, {34194,34195,34196 ,18638,18639,18638 ,0,0,0}, + {34193,34192,34196 ,18637,18637,18638 ,0,0,0}, {34197,34198,34199 ,18583,18583,18639 ,0,0,0}, + {34195,34194,34199 ,18639,18638,18639 ,0,0,0}, {34199,34198,34195 ,18639,18583,18639 ,0,0,0}, + {34194,34196,34192 ,18638,18638,18637 ,0,0,0}, {34193,34200,34191 ,18637,18636,18636 ,0,0,0}, + {34200,34201,34202 ,18636,18640,18640 ,0,0,0}, {34202,34191,34200 ,18640,18636,18636 ,0,0,0}, + {34203,34201,34204 ,18609,18640,18609 ,0,0,0}, {34201,34203,34202 ,18640,18609,18640 ,0,0,0}, + {34205,34206,34207 ,18641,18642,18642 ,0,0,0}, {34208,34209,34210 ,18643,18644,18645 ,0,0,0}, + {34207,34206,34210 ,18642,18642,18645 ,0,0,0}, {34211,34212,34213 ,18601,18601,18644 ,0,0,0}, + {34209,34208,34213 ,18644,18643,18644 ,0,0,0}, {34213,34212,34209 ,18644,18601,18644 ,0,0,0}, + {34208,34210,34206 ,18643,18645,18642 ,0,0,0}, {34207,34214,34205 ,18642,18641,18641 ,0,0,0}, + {34214,34215,34216 ,18641,18646,18646 ,0,0,0}, {34216,34205,34214 ,18646,18641,18641 ,0,0,0}, + {34217,34215,34218 ,18588,18646,18588 ,0,0,0}, {34215,34217,34216 ,18646,18588,18646 ,0,0,0}, + {34219,34220,34221 ,18647,18648,18649 ,0,0,0}, {34222,34223,34224 ,18650,18651,18652 ,0,0,0}, + {34221,34220,34224 ,18649,18648,18652 ,0,0,0}, {34225,34226,34227 ,18609,18609,18651 ,0,0,0}, + {34223,34222,34227 ,18651,18650,18651 ,0,0,0}, {34227,34226,34223 ,18651,18609,18651 ,0,0,0}, + {34222,34224,34220 ,18650,18652,18648 ,0,0,0}, {34221,34228,34219 ,18649,18647,18647 ,0,0,0}, + {34228,34229,34230 ,18647,18653,18653 ,0,0,0}, {34230,34219,34228 ,18653,18647,18647 ,0,0,0}, + {34231,34229,34232 ,18594,18653,18594 ,0,0,0}, {34229,34231,34230 ,18653,18594,18653 ,0,0,0}, + {34233,34234,34235 ,18654,18655,18655 ,0,0,0}, {34236,34237,34238 ,18656,18657,18658 ,0,0,0}, + {34235,34234,34238 ,18655,18655,18658 ,0,0,0}, {34239,34240,34241 ,18575,18575,18657 ,0,0,0}, + {34237,34236,34241 ,18657,18656,18657 ,0,0,0}, {34241,34240,34237 ,18657,18575,18657 ,0,0,0}, + {34236,34238,34234 ,18656,18658,18655 ,0,0,0}, {34235,34242,34233 ,18655,18654,18654 ,0,0,0}, + {34242,34243,34244 ,18654,18659,18659 ,0,0,0}, {34244,34233,34242 ,18659,18654,18654 ,0,0,0}, + {34245,34243,34246 ,18601,18659,18601 ,0,0,0}, {34243,34245,34244 ,18659,18601,18659 ,0,0,0}, + {34247,34248,34249 ,18660,18661,18661 ,0,0,0}, {34250,34251,34252 ,18662,18663,18662 ,0,0,0}, + {34249,34248,34252 ,18661,18661,18662 ,0,0,0}, {34253,34254,34255 ,18583,18583,18663 ,0,0,0}, + {34251,34250,34255 ,18663,18662,18663 ,0,0,0}, {34255,34254,34251 ,18663,18583,18663 ,0,0,0}, + {34250,34252,34248 ,18662,18662,18661 ,0,0,0}, {34249,34256,34247 ,18661,18660,18660 ,0,0,0}, + {34256,34257,34258 ,18660,18664,18664 ,0,0,0}, {34258,34247,34256 ,18664,18660,18660 ,0,0,0}, + {34259,34257,34260 ,18609,18664,18609 ,0,0,0}, {34257,34259,34258 ,18664,18609,18664 ,0,0,0}, + {34261,34262,34263 ,18665,18666,18666 ,0,0,0}, {34264,34265,34266 ,18667,18668,18667 ,0,0,0}, + {34263,34262,34266 ,18666,18666,18667 ,0,0,0}, {34267,34268,34269 ,18573,18573,18668 ,0,0,0}, + {34265,34264,34269 ,18668,18667,18668 ,0,0,0}, {34269,34268,34265 ,18668,18573,18668 ,0,0,0}, + {34264,34266,34262 ,18667,18667,18666 ,0,0,0}, {34263,34270,34261 ,18666,18665,18665 ,0,0,0}, + {34270,34271,34272 ,18665,18669,18669 ,0,0,0}, {34272,34261,34270 ,18669,18665,18665 ,0,0,0}, + {34273,34271,34274 ,18575,18669,18575 ,0,0,0}, {34271,34273,34272 ,18669,18575,18669 ,0,0,0}, + {34275,34276,34277 ,18670,18671,18671 ,0,0,0}, {34278,34279,34280 ,18672,18673,18672 ,0,0,0}, + {34277,34276,34280 ,18671,18671,18672 ,0,0,0}, {34281,34282,34283 ,18581,18581,18673 ,0,0,0}, + {34279,34278,34283 ,18673,18672,18673 ,0,0,0}, {34283,34282,34279 ,18673,18581,18673 ,0,0,0}, + {34278,34280,34276 ,18672,18672,18671 ,0,0,0}, {34277,34284,34275 ,18671,18670,18670 ,0,0,0}, + {34284,34285,34286 ,18670,18582,18582 ,0,0,0}, {34286,34275,34284 ,18582,18670,18670 ,0,0,0}, + {34287,34285,34288 ,18583,18582,18583 ,0,0,0}, {34285,34287,34286 ,18582,18583,18582 ,0,0,0}, + {34289,34290,34291 ,18674,18675,18675 ,0,0,0}, {34292,34293,34294 ,18676,18677,18676 ,0,0,0}, + {34291,34290,34294 ,18675,18675,18676 ,0,0,0}, {34295,34296,34297 ,18575,18575,18677 ,0,0,0}, + {34293,34292,34297 ,18677,18676,18677 ,0,0,0}, {34297,34296,34293 ,18677,18575,18677 ,0,0,0}, + {34292,34294,34290 ,18676,18676,18675 ,0,0,0}, {34291,34298,34289 ,18675,18674,18674 ,0,0,0}, + {34298,34299,34300 ,18674,18678,18678 ,0,0,0}, {34300,34289,34298 ,18678,18674,18674 ,0,0,0}, + {34301,34299,34302 ,18601,18678,18601 ,0,0,0}, {34299,34301,34300 ,18678,18601,18678 ,0,0,0}, + {34303,34304,34305 ,18679,18680,18680 ,0,0,0}, {34306,34307,34308 ,18681,18682,18681 ,0,0,0}, + {34305,34304,34308 ,18680,18680,18681 ,0,0,0}, {34309,34310,34311 ,18583,18583,18682 ,0,0,0}, + {34307,34306,34311 ,18682,18681,18682 ,0,0,0}, {34311,34310,34307 ,18682,18583,18682 ,0,0,0}, + {34306,34308,34304 ,18681,18681,18680 ,0,0,0}, {34305,34312,34303 ,18680,18679,18679 ,0,0,0}, + {34312,34313,34314 ,18679,18683,18683 ,0,0,0}, {34314,34303,34312 ,18683,18679,18679 ,0,0,0}, + {34315,34313,34316 ,18609,18683,18609 ,0,0,0}, {34313,34315,34314 ,18683,18609,18683 ,0,0,0}, + {34317,34318,34319 ,18684,18685,18685 ,0,0,0}, {34320,34321,34322 ,18686,18687,18686 ,0,0,0}, + {34319,34318,34322 ,18685,18685,18686 ,0,0,0}, {34323,34324,34325 ,18573,18573,18687 ,0,0,0}, + {34321,34320,34325 ,18687,18686,18687 ,0,0,0}, {34325,34324,34321 ,18687,18573,18687 ,0,0,0}, + {34320,34322,34318 ,18686,18686,18685 ,0,0,0}, {34319,34326,34317 ,18685,18684,18684 ,0,0,0}, + {34326,34327,34328 ,18684,18688,18688 ,0,0,0}, {34328,34317,34326 ,18688,18684,18684 ,0,0,0}, + {34329,34327,34330 ,18575,18688,18575 ,0,0,0}, {34327,34329,34328 ,18688,18575,18688 ,0,0,0}, + {34331,34332,34333 ,18689,18690,18690 ,0,0,0}, {34334,34335,34336 ,18691,18692,18691 ,0,0,0}, + {34333,34332,34336 ,18690,18690,18691 ,0,0,0}, {34337,34338,34339 ,18581,18581,18692 ,0,0,0}, + {34335,34334,34339 ,18692,18691,18692 ,0,0,0}, {34339,34338,34335 ,18692,18581,18692 ,0,0,0}, + {34334,34336,34332 ,18691,18691,18690 ,0,0,0}, {34333,34340,34331 ,18690,18689,18689 ,0,0,0}, + {34340,34341,34342 ,18689,18693,18693 ,0,0,0}, {34342,34331,34340 ,18693,18689,18689 ,0,0,0}, + {34343,34341,34344 ,18583,18693,18583 ,0,0,0}, {34341,34343,34342 ,18693,18583,18693 ,0,0,0}, + {34345,34346,34347 ,18694,18695,18695 ,0,0,0}, {34348,34349,34350 ,18696,18697,18696 ,0,0,0}, + {34347,34346,34350 ,18695,18695,18696 ,0,0,0}, {34351,34352,34353 ,18588,18588,18697 ,0,0,0}, + {34349,34348,34353 ,18697,18696,18697 ,0,0,0}, {34353,34352,34349 ,18697,18588,18697 ,0,0,0}, + {34348,34350,34346 ,18696,18696,18695 ,0,0,0}, {34347,34354,34345 ,18695,18694,18694 ,0,0,0}, + {34354,34355,34356 ,18694,18615,18615 ,0,0,0}, {34356,34345,34354 ,18615,18694,18694 ,0,0,0}, + {34357,34355,34358 ,18573,18615,18573 ,0,0,0}, {34355,34357,34356 ,18615,18573,18615 ,0,0,0}, + {34359,34360,34361 ,18698,18699,18699 ,0,0,0}, {34362,34363,34364 ,18700,18701,18700 ,0,0,0}, + {34361,34360,34364 ,18699,18699,18700 ,0,0,0}, {34365,34366,34367 ,18594,18594,18701 ,0,0,0}, + {34363,34362,34367 ,18701,18700,18701 ,0,0,0}, {34367,34366,34363 ,18701,18594,18701 ,0,0,0}, + {34362,34364,34360 ,18700,18700,18699 ,0,0,0}, {34361,34368,34359 ,18699,18698,18698 ,0,0,0}, + {34368,34369,34370 ,18698,18702,18702 ,0,0,0}, {34370,34359,34368 ,18702,18698,18698 ,0,0,0}, + {34371,34369,34372 ,18581,18702,18581 ,0,0,0}, {34369,34371,34370 ,18702,18581,18702 ,0,0,0}, + {34373,34374,34375 ,18703,18704,18704 ,0,0,0}, {34376,34377,34378 ,18705,18706,18707 ,0,0,0}, + {34375,34374,34378 ,18704,18704,18707 ,0,0,0}, {34379,34380,34381 ,18575,18575,18706 ,0,0,0}, + {34377,34376,34381 ,18706,18705,18706 ,0,0,0}, {34381,34380,34377 ,18706,18575,18706 ,0,0,0}, + {34376,34378,34374 ,18705,18707,18704 ,0,0,0}, {34375,34382,34373 ,18704,18703,18703 ,0,0,0}, + {34382,34383,34384 ,18703,18708,18708 ,0,0,0}, {34384,34373,34382 ,18708,18703,18703 ,0,0,0}, + {34385,34383,34386 ,18601,18708,18601 ,0,0,0}, {34383,34385,34384 ,18708,18601,18708 ,0,0,0}, + {34387,34388,34389 ,18709,18710,18710 ,0,0,0}, {34390,34391,34392 ,18711,18712,18711 ,0,0,0}, + {34389,34388,34392 ,18710,18710,18711 ,0,0,0}, {34393,34394,34395 ,18583,18583,18712 ,0,0,0}, + {34391,34390,34395 ,18712,18711,18712 ,0,0,0}, {34395,34394,34391 ,18712,18583,18712 ,0,0,0}, + {34390,34392,34388 ,18711,18711,18710 ,0,0,0}, {34389,34396,34387 ,18710,18709,18709 ,0,0,0}, + {34396,34397,34398 ,18709,18713,18713 ,0,0,0}, {34398,34387,34396 ,18713,18709,18709 ,0,0,0}, + {34399,34397,34400 ,18609,18713,18609 ,0,0,0}, {34397,34399,34398 ,18713,18609,18713 ,0,0,0}, + {34401,34402,34403 ,18714,18715,18715 ,0,0,0}, {34404,34405,34406 ,18716,18717,18716 ,0,0,0}, + {34403,34402,34406 ,18715,18715,18716 ,0,0,0}, {34407,34408,34409 ,18573,18573,18717 ,0,0,0}, + {34405,34404,34409 ,18717,18716,18717 ,0,0,0}, {34409,34408,34405 ,18717,18573,18717 ,0,0,0}, + {34404,34406,34402 ,18716,18716,18715 ,0,0,0}, {34403,34410,34401 ,18715,18714,18714 ,0,0,0}, + {34410,34411,34412 ,18714,18718,18718 ,0,0,0}, {34412,34401,34410 ,18718,18714,18714 ,0,0,0}, + {34413,34411,34414 ,18575,18718,18575 ,0,0,0}, {34411,34413,34412 ,18718,18575,18718 ,0,0,0}, + {34415,34416,34417 ,18719,18720,18720 ,0,0,0}, {34418,34419,34420 ,18721,18722,18721 ,0,0,0}, + {34417,34416,34420 ,18720,18720,18721 ,0,0,0}, {34421,34422,34423 ,18581,18581,18722 ,0,0,0}, + {34419,34418,34423 ,18722,18721,18722 ,0,0,0}, {34423,34422,34419 ,18722,18581,18722 ,0,0,0}, + {34418,34420,34416 ,18721,18721,18720 ,0,0,0}, {34417,34424,34415 ,18720,18719,18719 ,0,0,0}, + {34424,34425,34426 ,18719,18723,18723 ,0,0,0}, {34426,34415,34424 ,18723,18719,18719 ,0,0,0}, + {34427,34425,34428 ,18583,18723,18583 ,0,0,0}, {34425,34427,34426 ,18723,18583,18723 ,0,0,0}, + {34429,34430,34431 ,18724,18725,18725 ,0,0,0}, {34432,34433,34434 ,18726,18727,18726 ,0,0,0}, + {34431,34430,34434 ,18725,18725,18726 ,0,0,0}, {34435,34436,34437 ,18588,18588,18727 ,0,0,0}, + {34433,34432,34437 ,18727,18726,18727 ,0,0,0}, {34437,34436,34433 ,18727,18588,18727 ,0,0,0}, + {34432,34434,34430 ,18726,18726,18725 ,0,0,0}, {34431,34438,34429 ,18725,18724,18724 ,0,0,0}, + {34438,34439,34440 ,18724,18728,18728 ,0,0,0}, {34440,34429,34438 ,18728,18724,18724 ,0,0,0}, + {34441,34439,34442 ,18573,18728,18573 ,0,0,0}, {34439,34441,34440 ,18728,18573,18728 ,0,0,0}, + {34443,34444,34445 ,18729,18730,18731 ,0,0,0}, {34446,34447,34448 ,18732,18733,18734 ,0,0,0}, + {34445,34444,34448 ,18731,18730,18734 ,0,0,0}, {34449,34450,34451 ,18594,18594,18733 ,0,0,0}, + {34447,34446,34451 ,18733,18732,18733 ,0,0,0}, {34451,34450,34447 ,18733,18594,18733 ,0,0,0}, + {34446,34448,34444 ,18732,18734,18730 ,0,0,0}, {34445,34452,34443 ,18731,18729,18729 ,0,0,0}, + {34452,34453,34454 ,18729,18595,18595 ,0,0,0}, {34454,34443,34452 ,18595,18729,18729 ,0,0,0}, + {34455,34453,34456 ,18581,18595,18581 ,0,0,0}, {34453,34455,34454 ,18595,18581,18595 ,0,0,0}, + {34457,34458,34459 ,18735,18736,18737 ,0,0,0}, {34457,34460,34461 ,18735,18738,18739 ,0,0,0}, + {34460,34462,34461 ,18738,18740,18739 ,0,0,0}, {34459,34460,34457 ,18737,18738,18735 ,0,0,0}, + {34463,34464,34465 ,18741,18742,18743 ,0,0,0}, {34462,34463,34465 ,18740,18741,18743 ,0,0,0}, + {34464,34466,34467 ,18742,18744,18745 ,0,0,0}, {34466,34464,34463 ,18744,18742,18741 ,0,0,0}, + {34467,34466,34468 ,18745,18744,18746 ,0,0,0}, {34469,34467,34468 ,18747,18745,18746 ,0,0,0}, + {34469,34470,34471 ,18747,18748,18749 ,0,0,0}, {34469,34468,34470 ,18747,18746,18748 ,0,0,0}, + {34465,34461,34462 ,18743,18739,18740 ,0,0,0}, {34472,34473,34474 ,18750,18751,126 ,0,0,0}, + {34472,34474,34471 ,18750,126,18749 ,0,0,0}, {34470,34472,34471 ,18748,18750,18749 ,0,0,0}, + {34459,34458,34475 ,18737,18736,18752 ,0,0,0}, {34476,34475,34477 ,18753,18752,18754 ,0,0,0}, + {34458,34477,34475 ,18736,18754,18752 ,0,0,0}, {34478,34479,34476 ,18755,18756,18753 ,0,0,0}, + {34476,34477,34478 ,18753,18754,18755 ,0,0,0}, {34479,34480,34481 ,18756,18757,18758 ,0,0,0}, + {34480,34479,34478 ,18757,18756,18755 ,0,0,0}, {34482,34481,34483 ,18759,18758,18760 ,0,0,0}, + {34480,34483,34481 ,18757,18760,18758 ,0,0,0}, {34484,34485,34482 ,18761,18067,18759 ,0,0,0}, + {34482,34483,34484 ,18759,18760,18761 ,0,0,0}, {34485,34486,34487 ,18067,18762,18763 ,0,0,0}, + {34486,34485,34484 ,18762,18067,18761 ,0,0,0}, {34486,34488,34487 ,18762,82,18763 ,0,0,0}, + {34489,34490,34491 ,18764,18765,18766 ,0,0,0}, {34489,34492,34493 ,18764,18767,18768 ,0,0,0}, + {34492,34494,34493 ,18767,18769,18768 ,0,0,0}, {34491,34492,34489 ,18766,18767,18764 ,0,0,0}, + {34495,34496,34497 ,18770,18771,18239 ,0,0,0}, {34494,34495,34497 ,18769,18770,18239 ,0,0,0}, + {34496,34498,34499 ,18771,18772,18773 ,0,0,0}, {34498,34496,34495 ,18772,18771,18770 ,0,0,0}, + {34499,34498,34500 ,18773,18772,18774 ,0,0,0}, {34501,34499,34500 ,18775,18773,18774 ,0,0,0}, + {34501,34502,34503 ,18775,18776,18777 ,0,0,0}, {34501,34500,34502 ,18775,18774,18776 ,0,0,0}, + {34497,34493,34494 ,18239,18768,18769 ,0,0,0}, {34504,34505,1297 ,18778,18751,126 ,0,0,0}, + {34504,1297,34503 ,18778,126,18777 ,0,0,0}, {34502,34504,34503 ,18776,18778,18777 ,0,0,0}, + {34491,34490,34506 ,18766,18765,18779 ,0,0,0}, {34507,34506,34508 ,18780,18779,18781 ,0,0,0}, + {34490,34508,34506 ,18765,18781,18779 ,0,0,0}, {34509,34510,34507 ,18782,18756,18780 ,0,0,0}, + {34507,34508,34509 ,18780,18781,18782 ,0,0,0}, {34510,34511,34512 ,18756,18783,18758 ,0,0,0}, + {34511,34510,34509 ,18783,18756,18782 ,0,0,0}, {34513,34512,34514 ,18784,18758,18785 ,0,0,0}, + {34511,34514,34512 ,18783,18785,18758 ,0,0,0}, {34515,34516,34513 ,18761,18786,18784 ,0,0,0}, + {34513,34514,34515 ,18784,18785,18761 ,0,0,0}, {34516,34517,34518 ,18786,18787,18763 ,0,0,0}, + {34517,34516,34515 ,18787,18786,18761 ,0,0,0}, {34517,2073,34518 ,18787,82,18763 ,0,0,0}, + {34519,34520,34521 ,18788,18789,18790 ,0,0,0}, {34519,34522,34523 ,18788,18791,18792 ,0,0,0}, + {34522,34524,34523 ,18791,18793,18792 ,0,0,0}, {34521,34522,34519 ,18790,18791,18788 ,0,0,0}, + {34525,34526,34527 ,18794,18795,18796 ,0,0,0}, {34524,34525,34527 ,18793,18794,18796 ,0,0,0}, + {34526,34528,34529 ,18795,18797,18798 ,0,0,0}, {34528,34526,34525 ,18797,18795,18794 ,0,0,0}, + {34529,34528,34530 ,18798,18797,18799 ,0,0,0}, {34531,34529,34530 ,18800,18798,18799 ,0,0,0}, + {34531,34532,34533 ,18800,18801,18802 ,0,0,0}, {34531,34530,34532 ,18800,18799,18801 ,0,0,0}, + {34527,34523,34524 ,18796,18792,18793 ,0,0,0}, {34534,34535,34536 ,18803,18804,126 ,0,0,0}, + {34534,34536,34533 ,18803,126,18802 ,0,0,0}, {34532,34534,34533 ,18801,18803,18802 ,0,0,0}, + {34521,34520,34537 ,18790,18789,18805 ,0,0,0}, {34538,34537,34539 ,18806,18805,18781 ,0,0,0}, + {34520,34539,34537 ,18789,18781,18805 ,0,0,0}, {34540,34541,34538 ,18807,18808,18806 ,0,0,0}, + {34538,34539,34540 ,18806,18781,18807 ,0,0,0}, {34541,34542,34543 ,18808,18809,18758 ,0,0,0}, + {34542,34541,34540 ,18809,18808,18807 ,0,0,0}, {34544,34543,34545 ,18810,18758,18811 ,0,0,0}, + {34542,34545,34543 ,18809,18811,18758 ,0,0,0}, {34546,34547,34544 ,18812,18813,18810 ,0,0,0}, + {34544,34545,34546 ,18810,18811,18812 ,0,0,0}, {34547,34548,34549 ,18813,18814,18763 ,0,0,0}, + {34548,34547,34546 ,18814,18813,18812 ,0,0,0}, {34548,34550,34549 ,18814,82,18763 ,0,0,0}, + {34551,34552,34553 ,18815,18816,18817 ,0,0,0}, {34551,34554,34555 ,18815,18818,18819 ,0,0,0}, + {34554,34556,34555 ,18818,18820,18819 ,0,0,0}, {34553,34554,34551 ,18817,18818,18815 ,0,0,0}, + {34557,34558,34559 ,18821,18822,18823 ,0,0,0}, {34556,34557,34559 ,18820,18821,18823 ,0,0,0}, + {34558,34560,34561 ,18822,18824,18825 ,0,0,0}, {34560,34558,34557 ,18824,18822,18821 ,0,0,0}, + {34561,34560,34562 ,18825,18824,18826 ,0,0,0}, {34563,34561,34562 ,18827,18825,18826 ,0,0,0}, + {34563,34564,34565 ,18827,18828,18829 ,0,0,0}, {34563,34562,34564 ,18827,18826,18828 ,0,0,0}, + {34559,34555,34556 ,18823,18819,18820 ,0,0,0}, {34566,34567,1263 ,18830,18804,126 ,0,0,0}, + {34566,1263,34565 ,18830,126,18829 ,0,0,0}, {34564,34566,34565 ,18828,18830,18829 ,0,0,0}, + {34553,34552,34568 ,18817,18816,18831 ,0,0,0}, {34569,34568,34570 ,18832,18831,18754 ,0,0,0}, + {34552,34570,34568 ,18816,18754,18831 ,0,0,0}, {34571,34572,34569 ,18833,18808,18832 ,0,0,0}, + {34569,34570,34571 ,18832,18754,18833 ,0,0,0}, {34572,34573,34574 ,18808,18834,18758 ,0,0,0}, + {34573,34572,34571 ,18834,18808,18833 ,0,0,0}, {34575,34574,34576 ,18835,18758,18836 ,0,0,0}, + {34573,34576,34574 ,18834,18836,18758 ,0,0,0}, {34577,34578,34575 ,18812,18837,18835 ,0,0,0}, + {34575,34576,34577 ,18835,18836,18812 ,0,0,0}, {34578,34579,34580 ,18837,18838,18763 ,0,0,0}, + {34579,34578,34577 ,18838,18837,18812 ,0,0,0}, {34579,2082,34580 ,18838,82,18763 ,0,0,0}, + {34581,34582,34583 ,18839,18840,18841 ,0,0,0}, {34581,34584,34585 ,18839,18842,18843 ,0,0,0}, + {34584,34586,34585 ,18842,18844,18843 ,0,0,0}, {34583,34584,34581 ,18841,18842,18839 ,0,0,0}, + {34587,34588,34589 ,18845,18846,18847 ,0,0,0}, {34586,34587,34589 ,18844,18845,18847 ,0,0,0}, + {34588,34590,34591 ,18846,18848,18849 ,0,0,0}, {34590,34588,34587 ,18848,18846,18845 ,0,0,0}, + {34591,34590,34592 ,18849,18848,18850 ,0,0,0}, {34593,34591,34592 ,18851,18849,18850 ,0,0,0}, + {34593,34594,34595 ,18851,18852,18853 ,0,0,0}, {34593,34592,34594 ,18851,18850,18852 ,0,0,0}, + {34589,34585,34586 ,18847,18843,18844 ,0,0,0}, {34596,34597,3049 ,18854,3316,126 ,0,0,0}, + {34596,3049,34595 ,18854,126,18853 ,0,0,0}, {34594,34596,34595 ,18852,18854,18853 ,0,0,0}, + {34583,34582,34598 ,18841,18840,18855 ,0,0,0}, {34599,34598,34600 ,18856,18855,18857 ,0,0,0}, + {34582,34600,34598 ,18840,18857,18855 ,0,0,0}, {34601,34602,34599 ,18858,18859,18856 ,0,0,0}, + {34599,34600,34601 ,18856,18857,18858 ,0,0,0}, {34602,34603,34604 ,18859,18860,18861 ,0,0,0}, + {34603,34602,34601 ,18860,18859,18858 ,0,0,0}, {34605,34604,34606 ,18784,18861,18862 ,0,0,0}, + {34603,34606,34604 ,18860,18862,18861 ,0,0,0}, {34607,34608,34605 ,18863,18864,18784 ,0,0,0}, + {34605,34606,34607 ,18784,18862,18863 ,0,0,0}, {34608,34609,34610 ,18864,18865,3343 ,0,0,0}, + {34609,34608,34607 ,18865,18864,18863 ,0,0,0}, {34609,3063,34610 ,18865,3370,3343 ,0,0,0}, + {34611,34612,34613 ,18866,18867,18868 ,0,0,0}, {34611,34614,34615 ,18866,18869,18870 ,0,0,0}, + {34614,34616,34615 ,18869,18871,18870 ,0,0,0}, {34613,34614,34611 ,18868,18869,18866 ,0,0,0}, + {34617,34618,34619 ,18872,18873,18874 ,0,0,0}, {34616,34617,34619 ,18871,18872,18874 ,0,0,0}, + {34618,34620,34621 ,18873,18875,18876 ,0,0,0}, {34620,34618,34617 ,18875,18873,18872 ,0,0,0}, + {34621,34620,34622 ,18876,18875,18877 ,0,0,0}, {34623,34621,34622 ,18878,18876,18877 ,0,0,0}, + {34623,34624,34625 ,18878,18879,18880 ,0,0,0}, {34623,34622,34624 ,18878,18877,18879 ,0,0,0}, + {34619,34615,34616 ,18874,18870,18871 ,0,0,0}, {34626,34627,34628 ,18881,18882,2619 ,0,0,0}, + {34626,34628,34625 ,18881,2619,18880 ,0,0,0}, {34624,34626,34625 ,18879,18881,18880 ,0,0,0}, + {34613,34612,34629 ,18868,18867,18883 ,0,0,0}, {34630,34629,34631 ,18884,18883,18885 ,0,0,0}, + {34612,34631,34629 ,18867,18885,18883 ,0,0,0}, {34632,34633,34630 ,18886,18887,18884 ,0,0,0}, + {34630,34631,34632 ,18884,18885,18886 ,0,0,0}, {34633,34634,34635 ,18887,18888,18889 ,0,0,0}, + {34634,34633,34632 ,18888,18887,18886 ,0,0,0}, {34636,34635,34637 ,18784,18889,18862 ,0,0,0}, + {34634,34637,34635 ,18888,18862,18889 ,0,0,0}, {34638,34639,34636 ,18890,18067,18784 ,0,0,0}, + {34636,34637,34638 ,18784,18862,18890 ,0,0,0}, {34639,34640,34641 ,18067,18891,2602 ,0,0,0}, + {34640,34639,34638 ,18891,18067,18890 ,0,0,0}, {34640,34642,34641 ,18891,82,2602 ,0,0,0}, + {34643,34644,34645 ,18839,18892,18893 ,0,0,0}, {34643,34646,34647 ,18839,18842,18843 ,0,0,0}, + {34646,34648,34647 ,18842,18894,18843 ,0,0,0}, {34645,34646,34643 ,18893,18842,18839 ,0,0,0}, + {34649,34650,34651 ,18895,18896,18897 ,0,0,0}, {34648,34649,34651 ,18894,18895,18897 ,0,0,0}, + {34650,34652,34653 ,18896,18898,18899 ,0,0,0}, {34652,34650,34649 ,18898,18896,18895 ,0,0,0}, + {34653,34652,34654 ,18899,18898,18900 ,0,0,0}, {34655,34653,34654 ,18901,18899,18900 ,0,0,0}, + {34655,34656,34657 ,18901,18902,18903 ,0,0,0}, {34655,34654,34656 ,18901,18900,18902 ,0,0,0}, + {34651,34647,34648 ,18897,18843,18894 ,0,0,0}, {34658,34659,34660 ,18904,2589,126 ,0,0,0}, + {34658,34660,34657 ,18904,126,18903 ,0,0,0}, {34656,34658,34657 ,18902,18904,18903 ,0,0,0}, + {34645,34644,34661 ,18893,18892,18905 ,0,0,0}, {34662,34661,34663 ,18906,18905,18907 ,0,0,0}, + {34644,34663,34661 ,18892,18907,18905 ,0,0,0}, {34664,34665,34662 ,18908,18909,18906 ,0,0,0}, + {34662,34663,34664 ,18906,18907,18908 ,0,0,0}, {34665,34666,34667 ,18909,18910,18911 ,0,0,0}, + {34666,34665,34664 ,18910,18909,18908 ,0,0,0}, {34668,34667,34669 ,18784,18911,18912 ,0,0,0}, + {34666,34669,34667 ,18910,18912,18911 ,0,0,0}, {34670,34671,34668 ,18913,18914,18784 ,0,0,0}, + {34668,34669,34670 ,18784,18912,18913 ,0,0,0}, {34671,34672,34673 ,18914,18891,3371 ,0,0,0}, + {34672,34671,34670 ,18891,18914,18913 ,0,0,0}, {34672,34674,34673 ,18891,82,3371 ,0,0,0}, + {34675,34676,34677 ,18866,18915,18916 ,0,0,0}, {34675,34678,34679 ,18866,18917,18843 ,0,0,0}, + {34678,34680,34679 ,18917,18918,18843 ,0,0,0}, {34677,34678,34675 ,18916,18917,18866 ,0,0,0}, + {34681,34682,34683 ,18919,18920,18921 ,0,0,0}, {34680,34681,34683 ,18918,18919,18921 ,0,0,0}, + {34682,34684,34685 ,18920,18922,18923 ,0,0,0}, {34684,34682,34681 ,18922,18920,18919 ,0,0,0}, + {34685,34684,34686 ,18923,18922,18924 ,0,0,0}, {34687,34685,34686 ,18925,18923,18924 ,0,0,0}, + {34687,34688,34689 ,18925,18926,18927 ,0,0,0}, {34687,34686,34688 ,18925,18924,18926 ,0,0,0}, + {34683,34679,34680 ,18921,18843,18918 ,0,0,0}, {34690,34691,3015 ,18928,18929,126 ,0,0,0}, + {34690,3015,34689 ,18928,126,18927 ,0,0,0}, {34688,34690,34689 ,18926,18928,18927 ,0,0,0}, + {34677,34676,34692 ,18916,18915,18930 ,0,0,0}, {34693,34692,34694 ,18931,18930,18932 ,0,0,0}, + {34676,34694,34692 ,18915,18932,18930 ,0,0,0}, {34695,34696,34693 ,18933,18934,18931 ,0,0,0}, + {34693,34694,34695 ,18931,18932,18933 ,0,0,0}, {34696,34697,34698 ,18934,18935,18936 ,0,0,0}, + {34697,34696,34695 ,18935,18934,18933 ,0,0,0}, {34699,34698,34700 ,18937,18936,18811 ,0,0,0}, + {34697,34700,34698 ,18935,18811,18936 ,0,0,0}, {34701,34702,34699 ,18761,18938,18937 ,0,0,0}, + {34699,34700,34701 ,18937,18811,18761 ,0,0,0}, {34702,34703,34704 ,18938,18865,3371 ,0,0,0}, + {34703,34702,34701 ,18865,18938,18761 ,0,0,0}, {34703,3029,34704 ,18865,82,3371 ,0,0,0}, + {34705,34706,34707 ,18939,18765,18940 ,0,0,0}, {34705,34708,34709 ,18939,18941,18942 ,0,0,0}, + {34708,34710,34709 ,18941,18943,18942 ,0,0,0}, {34707,34708,34705 ,18940,18941,18939 ,0,0,0}, + {34711,34712,34713 ,18944,18945,18946 ,0,0,0}, {34710,34711,34713 ,18943,18944,18946 ,0,0,0}, + {34712,34714,34715 ,18945,18797,18947 ,0,0,0}, {34714,34712,34711 ,18797,18945,18944 ,0,0,0}, + {34715,34714,34716 ,18947,18797,18948 ,0,0,0}, {34717,34715,34716 ,18949,18947,18948 ,0,0,0}, + {34717,34718,34719 ,18949,18950,18951 ,0,0,0}, {34717,34716,34718 ,18949,18948,18950 ,0,0,0}, + {34713,34709,34710 ,18946,18942,18943 ,0,0,0}, {34720,34721,34722 ,18952,8371,126 ,0,0,0}, + {34720,34722,34719 ,18952,126,18951 ,0,0,0}, {34718,34720,34719 ,18950,18952,18951 ,0,0,0}, + {34707,34706,34723 ,18940,18765,18953 ,0,0,0}, {34724,34723,34725 ,18954,18953,18955 ,0,0,0}, + {34706,34725,34723 ,18765,18955,18953 ,0,0,0}, {34726,34727,34724 ,18956,18957,18954 ,0,0,0}, + {34724,34725,34726 ,18954,18955,18956 ,0,0,0}, {34727,34728,34729 ,18957,18958,18959 ,0,0,0}, + {34728,34727,34726 ,18958,18957,18956 ,0,0,0}, {34730,34729,34731 ,18784,18959,18811 ,0,0,0}, + {34728,34731,34729 ,18958,18811,18959 ,0,0,0}, {34732,34733,34730 ,18960,18786,18784 ,0,0,0}, + {34730,34731,34732 ,18784,18811,18960 ,0,0,0}, {34733,34734,34735 ,18786,18814,18961 ,0,0,0}, + {34734,34733,34732 ,18814,18786,18960 ,0,0,0}, {34734,34736,34735 ,18814,82,18961 ,0,0,0}, + {34737,34738,34739 ,18962,18765,18940 ,0,0,0}, {34737,34740,34741 ,18962,18791,18963 ,0,0,0}, + {34740,34742,34741 ,18791,18943,18963 ,0,0,0}, {34739,34740,34737 ,18940,18791,18962 ,0,0,0}, + {34743,34744,34745 ,18964,18965,18239 ,0,0,0}, {34742,34743,34745 ,18943,18964,18239 ,0,0,0}, + {34744,34746,34747 ,18965,18966,18967 ,0,0,0}, {34746,34744,34743 ,18966,18965,18964 ,0,0,0}, + {34747,34746,34748 ,18967,18966,18968 ,0,0,0}, {34749,34747,34748 ,18969,18967,18968 ,0,0,0}, + {34749,34750,34751 ,18969,18970,18971 ,0,0,0}, {34749,34748,34750 ,18969,18968,18970 ,0,0,0}, + {34745,34741,34742 ,18239,18963,18943 ,0,0,0}, {34752,34753,2950 ,18972,18973,126 ,0,0,0}, + {34752,2950,34751 ,18972,126,18971 ,0,0,0}, {34750,34752,34751 ,18970,18972,18971 ,0,0,0}, + {34739,34738,34754 ,18940,18765,18805 ,0,0,0}, {34755,34754,34756 ,18954,18805,18974 ,0,0,0}, + {34738,34756,34754 ,18765,18974,18805 ,0,0,0}, {34757,34758,34755 ,18956,18957,18954 ,0,0,0}, + {34755,34756,34757 ,18954,18974,18956 ,0,0,0}, {34758,34759,34760 ,18957,18958,18975 ,0,0,0}, + {34759,34758,34757 ,18958,18957,18956 ,0,0,0}, {34761,34760,34762 ,18976,18975,18811 ,0,0,0}, + {34759,34762,34760 ,18958,18811,18975 ,0,0,0}, {34763,34764,34761 ,18812,18786,18976 ,0,0,0}, + {34761,34762,34763 ,18976,18811,18812 ,0,0,0}, {34764,34765,34766 ,18786,18814,18961 ,0,0,0}, + {34765,34764,34763 ,18814,18786,18812 ,0,0,0}, {34765,2131,34766 ,18814,82,18961 ,0,0,0}, + {34767,34768,34769 ,18977,18736,18978 ,0,0,0}, {34767,34770,34771 ,18977,18818,18979 ,0,0,0}, + {34770,34772,34771 ,18818,18980,18979 ,0,0,0}, {34769,34770,34767 ,18978,18818,18977 ,0,0,0}, + {34773,34774,34775 ,18981,18982,18743 ,0,0,0}, {34772,34773,34775 ,18980,18981,18743 ,0,0,0}, + {34774,34776,34777 ,18982,18983,18984 ,0,0,0}, {34776,34774,34773 ,18983,18982,18981 ,0,0,0}, + {34777,34776,34778 ,18984,18983,18985 ,0,0,0}, {34779,34777,34778 ,18986,18984,18985 ,0,0,0}, + {34779,34780,34781 ,18986,18987,18988 ,0,0,0}, {34779,34778,34780 ,18986,18985,18987 ,0,0,0}, + {34775,34771,34772 ,18743,18979,18980 ,0,0,0}, {34782,34783,34784 ,18989,18973,126 ,0,0,0}, + {34782,34784,34781 ,18989,126,18988 ,0,0,0}, {34780,34782,34781 ,18987,18989,18988 ,0,0,0}, + {34769,34768,34785 ,18978,18736,18831 ,0,0,0}, {34786,34785,34787 ,18990,18831,18991 ,0,0,0}, + {34768,34787,34785 ,18736,18991,18831 ,0,0,0}, {34788,34789,34786 ,18992,18957,18990 ,0,0,0}, + {34786,34787,34788 ,18990,18991,18992 ,0,0,0}, {34789,34790,34791 ,18957,18993,18975 ,0,0,0}, + {34790,34789,34788 ,18993,18957,18992 ,0,0,0}, {34792,34791,34793 ,18994,18975,18836 ,0,0,0}, + {34790,34793,34791 ,18993,18836,18975 ,0,0,0}, {34794,34795,34792 ,18812,18067,18994 ,0,0,0}, + {34792,34793,34794 ,18994,18836,18812 ,0,0,0}, {34795,34796,34797 ,18067,18838,18961 ,0,0,0}, + {34796,34795,34794 ,18838,18067,18812 ,0,0,0}, {34796,34798,34797 ,18838,82,18961 ,0,0,0}, + {34799,34800,34801 ,18995,18736,18978 ,0,0,0}, {34799,34802,34803 ,18995,18996,18997 ,0,0,0}, + {34802,34804,34803 ,18996,18980,18997 ,0,0,0}, {34801,34802,34799 ,18978,18996,18995 ,0,0,0}, + {34805,34806,34807 ,18998,18999,19000 ,0,0,0}, {34804,34805,34807 ,18980,18998,19000 ,0,0,0}, + {34806,34808,34809 ,18999,18824,19001 ,0,0,0}, {34808,34806,34805 ,18824,18999,18998 ,0,0,0}, + {34809,34808,34810 ,19001,18824,19002 ,0,0,0}, {34811,34809,34810 ,19003,19001,19002 ,0,0,0}, + {34811,34812,34813 ,19003,19004,19005 ,0,0,0}, {34811,34810,34812 ,19003,19002,19004 ,0,0,0}, + {34807,34803,34804 ,19000,18997,18980 ,0,0,0}, {34814,34815,2941 ,19006,8371,126 ,0,0,0}, + {34814,2941,34813 ,19006,126,19005 ,0,0,0}, {34812,34814,34813 ,19004,19006,19005 ,0,0,0}, + {34801,34800,34816 ,18978,18736,19007 ,0,0,0}, {34817,34816,34818 ,18990,19007,19008 ,0,0,0}, + {34800,34818,34816 ,18736,19008,19007 ,0,0,0}, {34819,34820,34817 ,18992,18957,18990 ,0,0,0}, + {34817,34818,34819 ,18990,19008,18992 ,0,0,0}, {34820,34821,34822 ,18957,18993,18959 ,0,0,0}, + {34821,34820,34819 ,18993,18957,18992 ,0,0,0}, {34823,34822,34824 ,18759,18959,18836 ,0,0,0}, + {34821,34824,34822 ,18993,18836,18959 ,0,0,0}, {34825,34826,34823 ,18960,18067,18759 ,0,0,0}, + {34823,34824,34825 ,18759,18836,18960 ,0,0,0}, {34826,34827,34828 ,18067,18838,18961 ,0,0,0}, + {34827,34826,34825 ,18838,18067,18960 ,0,0,0}, {34827,2165,34828 ,18838,82,18961 ,0,0,0}, + {34829,34830,34831 ,19009,19010,19011 ,0,0,0}, {34829,34832,34833 ,19009,19012,19013 ,0,0,0}, + {34832,34834,34833 ,19012,18844,19013 ,0,0,0}, {34831,34832,34829 ,19011,19012,19009 ,0,0,0}, + {34835,34836,34837 ,19014,19015,19016 ,0,0,0}, {34834,34835,34837 ,18844,19014,19016 ,0,0,0}, + {34836,34838,34839 ,19015,19017,19018 ,0,0,0}, {34838,34836,34835 ,19017,19015,19014 ,0,0,0}, + {34839,34838,34840 ,19018,19017,19019 ,0,0,0}, {34841,34839,34840 ,19020,19018,19019 ,0,0,0}, + {34841,34842,34843 ,19020,19021,19022 ,0,0,0}, {34841,34840,34842 ,19020,19019,19021 ,0,0,0}, + {34837,34833,34834 ,19016,19013,18844 ,0,0,0}, {34844,34845,3931 ,19023,2589,126 ,0,0,0}, + {34844,3931,34843 ,19023,126,19022 ,0,0,0}, {34842,34844,34843 ,19021,19023,19022 ,0,0,0}, + {34831,34830,34846 ,19011,19010,19024 ,0,0,0}, {34847,34846,34848 ,19025,19024,19026 ,0,0,0}, + {34830,34848,34846 ,19010,19026,19024 ,0,0,0}, {34849,34850,34847 ,19027,18756,19025 ,0,0,0}, + {34847,34848,34849 ,19025,19026,19027 ,0,0,0}, {34850,34851,34852 ,18756,18910,19028 ,0,0,0}, + {34851,34850,34849 ,18910,18756,19027 ,0,0,0}, {34853,34852,34854 ,18937,19028,19029 ,0,0,0}, + {34851,34854,34852 ,18910,19029,19028 ,0,0,0}, {34855,34856,34853 ,19030,18864,18937 ,0,0,0}, + {34853,34854,34855 ,18937,19029,19030 ,0,0,0}, {34856,34857,34858 ,18864,19031,3371 ,0,0,0}, + {34857,34856,34855 ,19031,18864,19030 ,0,0,0}, {34857,3917,34858 ,19031,82,3371 ,0,0,0}, + {34859,34860,34861 ,19032,19033,19034 ,0,0,0}, {34859,34862,34863 ,19032,19035,19036 ,0,0,0}, + {34862,34864,34863 ,19035,19037,19036 ,0,0,0}, {34861,34862,34859 ,19034,19035,19032 ,0,0,0}, + {34865,34866,34867 ,19038,19039,19040 ,0,0,0}, {34864,34865,34867 ,19037,19038,19040 ,0,0,0}, + {34866,34868,34869 ,19039,19041,19042 ,0,0,0}, {34868,34866,34865 ,19041,19039,19038 ,0,0,0}, + {34869,34868,34870 ,19042,19041,19043 ,0,0,0}, {34871,34869,34870 ,19044,19042,19043 ,0,0,0}, + {34871,34872,34873 ,19044,19045,19046 ,0,0,0}, {34871,34870,34872 ,19044,19043,19045 ,0,0,0}, + {34867,34863,34864 ,19040,19036,19037 ,0,0,0}, {34874,34875,34876 ,19047,18929,126 ,0,0,0}, + {34874,34876,34873 ,19047,126,19046 ,0,0,0}, {34872,34874,34873 ,19045,19047,19046 ,0,0,0}, + {34861,34860,34877 ,19034,19033,19048 ,0,0,0}, {34878,34877,34879 ,19049,19048,19050 ,0,0,0}, + {34860,34879,34877 ,19033,19050,19048 ,0,0,0}, {34880,34881,34878 ,19051,19052,19049 ,0,0,0}, + {34878,34879,34880 ,19049,19050,19051 ,0,0,0}, {34881,34882,34883 ,19052,19053,19054 ,0,0,0}, + {34882,34881,34880 ,19053,19052,19051 ,0,0,0}, {34884,34883,34885 ,19055,19054,18811 ,0,0,0}, + {34882,34885,34883 ,19053,18811,19054 ,0,0,0}, {34886,34887,34884 ,19056,18938,19055 ,0,0,0}, + {34884,34885,34886 ,19055,18811,19056 ,0,0,0}, {34887,34888,34889 ,18938,19057,3371 ,0,0,0}, + {34888,34887,34886 ,19057,18938,19056 ,0,0,0}, {34888,34890,34889 ,19057,82,3371 ,0,0,0}, + {34891,34892,34893 ,19058,19059,19060 ,0,0,0}, {34891,34894,34895 ,19058,19061,19062 ,0,0,0}, + {34894,34896,34895 ,19061,19063,19062 ,0,0,0}, {34893,34894,34891 ,19060,19061,19058 ,0,0,0}, + {34897,34898,34899 ,19064,19065,19066 ,0,0,0}, {34896,34897,34899 ,19063,19064,19066 ,0,0,0}, + {34898,34900,34901 ,19065,19067,19068 ,0,0,0}, {34900,34898,34897 ,19067,19065,19064 ,0,0,0}, + {34901,34900,34902 ,19068,19067,19069 ,0,0,0}, {34903,34901,34902 ,19070,19068,19069 ,0,0,0}, + {34903,34904,34905 ,19070,19071,19072 ,0,0,0}, {34903,34902,34904 ,19070,19069,19071 ,0,0,0}, + {34899,34895,34896 ,19066,19062,19063 ,0,0,0}, {34906,34907,3897 ,19073,3316,126 ,0,0,0}, + {34906,3897,34905 ,19073,126,19072 ,0,0,0}, {34904,34906,34905 ,19071,19073,19072 ,0,0,0}, + {34893,34892,34908 ,19060,19059,19074 ,0,0,0}, {34909,34908,34910 ,19075,19074,19076 ,0,0,0}, + {34892,34910,34908 ,19059,19076,19074 ,0,0,0}, {34911,34912,34909 ,18933,19077,19075 ,0,0,0}, + {34909,34910,34911 ,19075,19076,18933 ,0,0,0}, {34912,34913,34914 ,19077,19078,19079 ,0,0,0}, + {34913,34912,34911 ,19078,19077,18933 ,0,0,0}, {34915,34914,34916 ,19080,19079,18811 ,0,0,0}, + {34913,34916,34914 ,19078,18811,19079 ,0,0,0}, {34917,34918,34915 ,19081,18067,19080 ,0,0,0}, + {34915,34916,34917 ,19080,18811,19081 ,0,0,0}, {34918,34919,34920 ,18067,18838,2602 ,0,0,0}, + {34919,34918,34917 ,18838,18067,19081 ,0,0,0}, {34919,3883,34920 ,18838,82,2602 ,0,0,0}, + {34921,34922,34923 ,19009,19082,19083 ,0,0,0}, {34921,34924,34925 ,19009,19084,19085 ,0,0,0}, + {34924,34926,34925 ,19084,19086,19085 ,0,0,0}, {34923,34924,34921 ,19083,19084,19009 ,0,0,0}, + {34927,34928,34929 ,19087,19088,19089 ,0,0,0}, {34926,34927,34929 ,19086,19087,19089 ,0,0,0}, + {34928,34930,34931 ,19088,19090,19091 ,0,0,0}, {34930,34928,34927 ,19090,19088,19087 ,0,0,0}, + {34931,34930,34932 ,19091,19090,19092 ,0,0,0}, {34933,34931,34932 ,19093,19091,19092 ,0,0,0}, + {34933,34934,34935 ,19093,19094,19095 ,0,0,0}, {34933,34932,34934 ,19093,19092,19094 ,0,0,0}, + {34929,34925,34926 ,19089,19085,19086 ,0,0,0}, {34936,34937,34938 ,19096,3316,126 ,0,0,0}, + {34936,34938,34935 ,19096,126,19095 ,0,0,0}, {34934,34936,34935 ,19094,19096,19095 ,0,0,0}, + {34923,34922,34939 ,19083,19082,19097 ,0,0,0}, {34940,34939,34941 ,18906,19097,19098 ,0,0,0}, + {34922,34941,34939 ,19082,19098,19097 ,0,0,0}, {34942,34943,34940 ,19099,19100,18906 ,0,0,0}, + {34940,34941,34942 ,18906,19098,19099 ,0,0,0}, {34943,34944,34945 ,19100,19101,19102 ,0,0,0}, + {34944,34943,34942 ,19101,19100,19099 ,0,0,0}, {34946,34945,34947 ,18784,19102,19103 ,0,0,0}, + {34944,34947,34945 ,19101,19103,19102 ,0,0,0}, {34948,34949,34946 ,18761,19104,18784 ,0,0,0}, + {34946,34947,34948 ,18784,19103,18761 ,0,0,0}, {34949,34950,34951 ,19104,19105,3343 ,0,0,0}, + {34950,34949,34948 ,19105,19104,18761 ,0,0,0}, {34950,34952,34951 ,19105,3370,3343 ,0,0,0}, + {34953,34954,34955 ,19106,19107,19108 ,0,0,0}, {34956,34957,34958 ,19109,19110,19111 ,0,0,0}, + {34959,34953,34955 ,19112,19106,19108 ,0,0,0}, {34956,34958,34960 ,19109,19111,19113 ,0,0,0}, + {34957,34956,34959 ,19110,19109,19112 ,0,0,0}, {34957,34959,34955 ,19110,19112,19108 ,0,0,0}, + {34961,34962,34963 ,19114,126,19115 ,0,0,0}, {34963,34960,34964 ,19115,19113,19116 ,0,0,0}, + {34961,34963,34964 ,19114,19115,19116 ,0,0,0}, {34962,34961,34965 ,126,19114,18751 ,0,0,0}, + {34964,34960,34958 ,19116,19113,19111 ,0,0,0}, {34953,34966,34954 ,19106,19117,19107 ,0,0,0}, + {34967,34966,34968 ,19118,19117,19119 ,0,0,0}, {34966,34967,34954 ,19117,19118,19107 ,0,0,0}, + {34969,34970,34968 ,19120,19121,19119 ,0,0,0}, {34967,34968,34970 ,19118,19119,19121 ,0,0,0}, + {34969,34971,34972 ,19120,19122,19123 ,0,0,0}, {34972,34970,34969 ,19123,19121,19120 ,0,0,0}, + {34973,34971,34974 ,793,19122,18961 ,0,0,0}, {34971,34973,34972 ,19122,793,19123 ,0,0,0}, + {34975,34976,34977 ,19124,19125,19126 ,0,0,0}, {34978,34979,34980 ,19127,19128,19129 ,0,0,0}, + {34981,34975,34977 ,19130,19124,19126 ,0,0,0}, {34978,34980,34982 ,19127,19129,19131 ,0,0,0}, + {34979,34978,34981 ,19128,19127,19130 ,0,0,0}, {34979,34981,34977 ,19128,19130,19126 ,0,0,0}, + {34983,34984,34985 ,19132,126,19133 ,0,0,0}, {34985,34982,34986 ,19133,19131,19134 ,0,0,0}, + {34983,34985,34986 ,19132,19133,19134 ,0,0,0}, {34984,34983,34987 ,126,19132,8371 ,0,0,0}, + {34986,34982,34980 ,19134,19131,19129 ,0,0,0}, {34975,34988,34976 ,19124,19135,19125 ,0,0,0}, + {34989,34988,34990 ,19136,19135,19137 ,0,0,0}, {34988,34989,34976 ,19135,19136,19125 ,0,0,0}, + {34991,34992,34990 ,19138,19139,19137 ,0,0,0}, {34989,34990,34992 ,19136,19137,19139 ,0,0,0}, + {34991,34993,34994 ,19138,19140,19141 ,0,0,0}, {34994,34992,34991 ,19141,19139,19138 ,0,0,0}, + {34995,34993,34996 ,19142,19140,18961 ,0,0,0}, {34993,34995,34994 ,19140,19142,19141 ,0,0,0}, + {34997,34998,34999 ,19143,19144,19145 ,0,0,0}, {35000,35001,35002 ,19146,19147,19148 ,0,0,0}, + {35003,34997,34999 ,19149,19143,19145 ,0,0,0}, {35000,35002,35004 ,19146,19148,19150 ,0,0,0}, + {35001,35000,35003 ,19147,19146,19149 ,0,0,0}, {35001,35003,34999 ,19147,19149,19145 ,0,0,0}, + {35005,35006,35007 ,19151,35,19152 ,0,0,0}, {35007,35004,35008 ,19152,19150,19153 ,0,0,0}, + {35005,35007,35008 ,19151,19152,19153 ,0,0,0}, {35006,35005,35009 ,35,19151,40 ,0,0,0}, + {35008,35004,35002 ,19153,19150,19148 ,0,0,0}, {34997,35010,34998 ,19143,19154,19144 ,0,0,0}, + {35011,35010,35012 ,19155,19154,19156 ,0,0,0}, {35010,35011,34998 ,19154,19155,19144 ,0,0,0}, + {35013,35014,35012 ,19157,19158,19156 ,0,0,0}, {35011,35012,35014 ,19155,19156,19158 ,0,0,0}, + {35013,35015,35016 ,19157,19159,19160 ,0,0,0}, {35016,35014,35013 ,19160,19158,19157 ,0,0,0}, + {35017,35015,35018 ,19161,19159,82 ,0,0,0}, {35015,35017,35016 ,19159,19161,19160 ,0,0,0}, + {35019,35020,35021 ,19162,19163,19164 ,0,0,0}, {35022,35023,35024 ,19165,19166,19167 ,0,0,0}, + {35025,35019,35021 ,19168,19162,19164 ,0,0,0}, {35022,35024,35026 ,19165,19167,19169 ,0,0,0}, + {35023,35022,35025 ,19166,19165,19168 ,0,0,0}, {35023,35025,35021 ,19166,19168,19164 ,0,0,0}, + {35027,35028,35029 ,19170,35,19171 ,0,0,0}, {35029,35026,35030 ,19171,19169,19172 ,0,0,0}, + {35027,35029,35030 ,19170,19171,19172 ,0,0,0}, {35028,35027,35031 ,35,19170,40 ,0,0,0}, + {35030,35026,35024 ,19172,19169,19167 ,0,0,0}, {35019,35032,35020 ,19162,19154,19163 ,0,0,0}, + {35033,35032,35034 ,19173,19154,19174 ,0,0,0}, {35032,35033,35020 ,19154,19173,19163 ,0,0,0}, + {35035,35036,35034 ,19175,19176,19174 ,0,0,0}, {35033,35034,35036 ,19173,19174,19176 ,0,0,0}, + {35035,35037,35038 ,19175,19159,19177 ,0,0,0}, {35038,35036,35035 ,19177,19176,19175 ,0,0,0}, + {35039,35037,35040 ,19161,19159,82 ,0,0,0}, {35037,35039,35038 ,19159,19161,19177 ,0,0,0}, + {35041,35042,35043 ,19106,19178,19108 ,0,0,0}, {35044,35045,35046 ,19179,19180,19181 ,0,0,0}, + {35047,35041,35043 ,19112,19106,19108 ,0,0,0}, {35044,35046,35048 ,19179,19181,19182 ,0,0,0}, + {35045,35044,35047 ,19180,19179,19112 ,0,0,0}, {35045,35047,35043 ,19180,19112,19108 ,0,0,0}, + {35049,35050,35051 ,19183,19184,19185 ,0,0,0}, {35051,35048,35052 ,19185,19182,19186 ,0,0,0}, + {35049,35051,35052 ,19183,19185,19186 ,0,0,0}, {35050,35049,35053 ,19184,19183,19187 ,0,0,0}, + {35052,35048,35046 ,19186,19182,19181 ,0,0,0}, {35041,35054,35042 ,19106,19188,19178 ,0,0,0}, + {35055,35054,35056 ,19189,19188,19190 ,0,0,0}, {35054,35055,35042 ,19188,19189,19178 ,0,0,0}, + {35057,35058,35056 ,19120,19191,19190 ,0,0,0}, {35055,35056,35058 ,19189,19190,19191 ,0,0,0}, + {35057,35059,35060 ,19120,19192,19193 ,0,0,0}, {35060,35058,35057 ,19193,19191,19120 ,0,0,0}, + {35061,35059,35062 ,19142,19192,18961 ,0,0,0}, {35059,35061,35060 ,19192,19142,19193 ,0,0,0}, + {35063,35064,35065 ,19194,19195,19196 ,0,0,0}, {35066,35067,35068 ,19197,19198,19199 ,0,0,0}, + {35069,35063,35065 ,19200,19194,19196 ,0,0,0}, {35066,35068,35070 ,19197,19199,19201 ,0,0,0}, + {35067,35066,35069 ,19198,19197,19200 ,0,0,0}, {35067,35069,35065 ,19198,19200,19196 ,0,0,0}, + {35071,35072,35073 ,19202,35,19203 ,0,0,0}, {35073,35070,35074 ,19203,19201,19204 ,0,0,0}, + {35071,35073,35074 ,19202,19203,19204 ,0,0,0}, {35072,35071,35075 ,35,19202,40 ,0,0,0}, + {35074,35070,35068 ,19204,19201,19199 ,0,0,0}, {35063,35076,35064 ,19194,19205,19195 ,0,0,0}, + {35077,35076,35078 ,19206,19205,19207 ,0,0,0}, {35076,35077,35064 ,19205,19206,19195 ,0,0,0}, + {35079,35080,35078 ,19157,19176,19207 ,0,0,0}, {35077,35078,35080 ,19206,19207,19176 ,0,0,0}, + {35079,35081,35082 ,19157,19159,8359 ,0,0,0}, {35082,35080,35079 ,8359,19176,19157 ,0,0,0}, + {35083,35081,35084 ,19161,19159,82 ,0,0,0}, {35081,35083,35082 ,19159,19161,8359 ,0,0,0}, + {35085,35086,35087 ,19208,19209,19210 ,0,0,0}, {35088,35089,35090 ,19197,19166,19211 ,0,0,0}, + {35091,35085,35087 ,19212,19208,19210 ,0,0,0}, {35088,35090,35092 ,19197,19211,19213 ,0,0,0}, + {35089,35088,35091 ,19166,19197,19212 ,0,0,0}, {35089,35091,35087 ,19166,19212,19210 ,0,0,0}, + {35093,35094,35095 ,19214,35,19215 ,0,0,0}, {35095,35092,35096 ,19215,19213,19216 ,0,0,0}, + {35093,35095,35096 ,19214,19215,19216 ,0,0,0}, {35094,35093,35097 ,35,19214,40 ,0,0,0}, + {35096,35092,35090 ,19216,19213,19211 ,0,0,0}, {35085,35098,35086 ,19208,19217,19209 ,0,0,0}, + {35099,35098,35100 ,19206,19217,19218 ,0,0,0}, {35098,35099,35086 ,19217,19206,19209 ,0,0,0}, + {35101,35102,35100 ,19157,8360,19218 ,0,0,0}, {35099,35100,35102 ,19206,19218,8360 ,0,0,0}, + {35101,35103,35104 ,19157,19159,19160 ,0,0,0}, {35104,35102,35101 ,19160,8360,19157 ,0,0,0}, + {35105,35103,35106 ,19161,19159,82 ,0,0,0}, {35103,35105,35104 ,19159,19161,19160 ,0,0,0}, + {35107,35108,35109 ,19124,19219,19126 ,0,0,0}, {35110,35111,35112 ,19220,19221,19222 ,0,0,0}, + {35113,35107,35109 ,19223,19124,19126 ,0,0,0}, {35110,35112,35114 ,19220,19222,19224 ,0,0,0}, + {35111,35110,35113 ,19221,19220,19223 ,0,0,0}, {35111,35113,35109 ,19221,19223,19126 ,0,0,0}, + {35115,35116,35117 ,19225,126,19226 ,0,0,0}, {35117,35114,35118 ,19226,19224,19227 ,0,0,0}, + {35115,35117,35118 ,19225,19226,19227 ,0,0,0}, {35116,35115,35119 ,126,19225,18751 ,0,0,0}, + {35118,35114,35112 ,19227,19224,19222 ,0,0,0}, {35107,35120,35108 ,19124,19228,19219 ,0,0,0}, + {35121,35120,35122 ,19229,19228,19230 ,0,0,0}, {35120,35121,35108 ,19228,19229,19219 ,0,0,0}, + {35123,35124,35122 ,19231,19232,19230 ,0,0,0}, {35121,35122,35124 ,19229,19230,19232 ,0,0,0}, + {35123,35125,35126 ,19231,19140,19233 ,0,0,0}, {35126,35124,35123 ,19233,19232,19231 ,0,0,0}, + {35127,35125,35128 ,19234,19140,18763 ,0,0,0}, {35125,35127,35126 ,19140,19234,19233 ,0,0,0}, + {35129,35130,35131 ,19235,19236,19237 ,0,0,0}, {35132,35133,35134 ,19238,19239,19240 ,0,0,0}, + {35135,35133,35136 ,19241,19239,19242 ,0,0,0}, {35132,35136,35133 ,19238,19242,19239 ,0,0,0}, + {35137,35132,35134 ,19243,19238,19240 ,0,0,0}, {35137,35138,35139 ,19243,19244,19245 ,0,0,0}, + {35138,35140,35139 ,19244,19246,19245 ,0,0,0}, {35139,35140,35141 ,19245,19246,19247 ,0,0,0}, + {35141,35142,35143 ,19247,19248,19249 ,0,0,0}, {35141,35140,35142 ,19247,19246,19248 ,0,0,0}, + {35144,35145,35146 ,19250,19251,19252 ,0,0,0}, {35147,35143,35142 ,19253,19249,19248 ,0,0,0}, + {35145,35148,35146 ,19251,19254,19252 ,0,0,0}, {35147,35148,35149 ,19253,19254,19255 ,0,0,0}, + {35143,35147,35149 ,19249,19253,19255 ,0,0,0}, {35149,35148,35145 ,19255,19254,19251 ,0,0,0}, + {35150,35151,35152 ,19256,19257,19258 ,0,0,0}, {35146,35151,35144 ,19252,19257,19250 ,0,0,0}, + {35150,35152,35153 ,19256,19258,19259 ,0,0,0}, {35151,35150,35144 ,19257,19256,19250 ,0,0,0}, + {35138,35137,35134 ,19244,19243,19240 ,0,0,0}, {35154,35155,35156 ,19260,19261,19262 ,0,0,0}, + {35155,35153,35156 ,19261,19259,19262 ,0,0,0}, {35157,35158,35159 ,19263,19264,19265 ,0,0,0}, + {35157,35155,35154 ,19263,19261,19260 ,0,0,0}, {35160,35159,35158 ,19266,19265,19264 ,0,0,0}, + {35154,35158,35157 ,19260,19264,19263 ,0,0,0}, {35161,35162,35160 ,19267,19268,19266 ,0,0,0}, + {35162,35159,35160 ,19268,19265,19266 ,0,0,0}, {35163,35164,35165 ,19269,19270,19271 ,0,0,0}, + {35166,35167,35168 ,19272,19273,19274 ,0,0,0}, {35169,35161,35170 ,19275,19267,19276 ,0,0,0}, + {35171,35167,35166 ,19277,19273,19272 ,0,0,0}, {35168,35170,35166 ,19274,19276,19272 ,0,0,0}, + {35171,35172,35167 ,19277,19278,19273 ,0,0,0}, {35169,35170,35168 ,19275,19276,19274 ,0,0,0}, + {35171,35173,35172 ,19277,19279,19278 ,0,0,0}, {35174,35173,35175 ,19280,19279,19281 ,0,0,0}, + {35174,35175,35176 ,19280,19281,19282 ,0,0,0}, {35164,35163,35176 ,19270,19269,19282 ,0,0,0}, + {35173,35174,35172 ,19279,19280,19278 ,0,0,0}, {35164,35176,35175 ,19270,19282,19281 ,0,0,0}, + {35177,35178,35179 ,19283,19284,19285 ,0,0,0}, {35180,35165,35177 ,19286,19271,19283 ,0,0,0}, + {35163,35165,35180 ,19269,19271,19286 ,0,0,0}, {35162,35161,35169 ,19268,19267,19275 ,0,0,0}, + {35180,35177,35179 ,19286,19283,19285 ,0,0,0}, {35179,35178,35181 ,19285,19284,82 ,0,0,0}, + {35178,35182,35181 ,19284,19287,82 ,0,0,0}, {35152,35156,35153 ,19258,19262,19259 ,0,0,0}, + {35183,35135,35136 ,19288,19241,19242 ,0,0,0}, {35183,35184,35185 ,19288,19289,19290 ,0,0,0}, + {35185,35135,35183 ,19290,19241,19288 ,0,0,0}, {35186,35184,35187 ,19291,19289,19292 ,0,0,0}, + {35184,35186,35185 ,19289,19291,19290 ,0,0,0}, {35188,35189,35187 ,19293,19294,19292 ,0,0,0}, + {35186,35187,35189 ,19291,19292,19294 ,0,0,0}, {35188,35190,35191 ,19293,19295,19296 ,0,0,0}, + {35191,35189,35188 ,19296,19294,19293 ,0,0,0}, {35192,35190,35193 ,19297,19295,19298 ,0,0,0}, + {35190,35192,35191 ,19295,19297,19296 ,0,0,0}, {35194,35195,35193 ,19299,19300,19298 ,0,0,0}, + {35192,35193,35195 ,19297,19298,19300 ,0,0,0}, {35194,35196,35197 ,19299,19301,19302 ,0,0,0}, + {35197,35195,35194 ,19302,19300,19299 ,0,0,0}, {35198,35196,35199 ,19303,19301,19304 ,0,0,0}, + {35196,35198,35197 ,19301,19303,19302 ,0,0,0}, {35200,35201,35199 ,19305,19306,19304 ,0,0,0}, + {35198,35199,35201 ,19303,19304,19306 ,0,0,0}, {35200,35202,35203 ,19305,19307,19308 ,0,0,0}, + {35203,35201,35200 ,19308,19306,19305 ,0,0,0}, {35204,35202,35205 ,19309,19307,19310 ,0,0,0}, + {35202,35204,35203 ,19307,19309,19308 ,0,0,0}, {35131,35130,35205 ,19237,19236,19310 ,0,0,0}, + {35204,35205,35130 ,19309,19310,19236 ,0,0,0}, {35129,35131,35206 ,19235,19237,19311 ,0,0,0}, + {35206,35207,35208 ,19311,19312,19313 ,0,0,0}, {35208,35129,35206 ,19313,19235,19311 ,0,0,0}, + {35209,35207,35210 ,19314,19312,19315 ,0,0,0}, {35207,35209,35208 ,19312,19314,19313 ,0,0,0}, + {35211,35212,35210 ,19316,19317,19315 ,0,0,0}, {35209,35210,35212 ,19314,19315,19317 ,0,0,0}, + {35211,35213,35214 ,19316,19318,19319 ,0,0,0}, {35214,35212,35211 ,19319,19317,19316 ,0,0,0}, + {35215,35213,35216 ,19320,19318,19321 ,0,0,0}, {35213,35215,35214 ,19318,19320,19319 ,0,0,0}, + {35217,35218,35216 ,19322,19323,19321 ,0,0,0}, {35215,35216,35218 ,19320,19321,19323 ,0,0,0}, + {35217,35219,35220 ,19322,19324,19325 ,0,0,0}, {35220,35218,35217 ,19325,19323,19322 ,0,0,0}, + {35221,35219,35222 ,19326,19324,19327 ,0,0,0}, {35219,35221,35220 ,19324,19326,19325 ,0,0,0}, + {35223,35224,35222 ,19328,19329,19327 ,0,0,0}, {35221,35222,35224 ,19326,19327,19329 ,0,0,0}, + {35223,35225,35226 ,19328,19330,19331 ,0,0,0}, {35226,35224,35223 ,19331,19329,19328 ,0,0,0}, + {35227,35225,35228 ,19332,19330,19332 ,0,0,0}, {35225,35227,35226 ,19330,19332,19331 ,0,0,0}, + {35229,35230,35231 ,19333,19334,19335 ,0,0,0}, {35232,35233,35234 ,19336,19337,19338 ,0,0,0}, + {35235,35233,35236 ,19339,19337,19340 ,0,0,0}, {35232,35236,35233 ,19336,19340,19337 ,0,0,0}, + {35237,35232,35234 ,19341,19336,19338 ,0,0,0}, {35237,35238,35239 ,19341,19342,19343 ,0,0,0}, + {35238,35240,35239 ,19342,19344,19343 ,0,0,0}, {35239,35240,35241 ,19343,19344,19345 ,0,0,0}, + {35241,35242,35243 ,19345,19346,19347 ,0,0,0}, {35241,35240,35242 ,19345,19344,19346 ,0,0,0}, + {35244,35245,35246 ,19348,19349,19350 ,0,0,0}, {35247,35243,35242 ,19351,19347,19346 ,0,0,0}, + {35245,35248,35246 ,19349,19352,19350 ,0,0,0}, {35247,35248,35249 ,19351,19352,19353 ,0,0,0}, + {35243,35247,35249 ,19347,19351,19353 ,0,0,0}, {35249,35248,35245 ,19353,19352,19349 ,0,0,0}, + {35250,35251,35252 ,19354,19355,19356 ,0,0,0}, {35246,35251,35244 ,19350,19355,19348 ,0,0,0}, + {35250,35252,35253 ,19354,19356,19357 ,0,0,0}, {35251,35250,35244 ,19355,19354,19348 ,0,0,0}, + {35238,35237,35234 ,19342,19341,19338 ,0,0,0}, {35254,35255,35256 ,19358,19359,19360 ,0,0,0}, + {35255,35253,35256 ,19359,19357,19360 ,0,0,0}, {35257,35258,35259 ,19361,19362,19363 ,0,0,0}, + {35257,35255,35254 ,19361,19359,19358 ,0,0,0}, {35260,35259,35258 ,19364,19363,19362 ,0,0,0}, + {35254,35258,35257 ,19358,19362,19361 ,0,0,0}, {35261,35262,35260 ,19365,19366,19364 ,0,0,0}, + {35262,35259,35260 ,19366,19363,19364 ,0,0,0}, {35263,35264,35265 ,19367,19368,19369 ,0,0,0}, + {35266,35267,35268 ,19370,19371,19372 ,0,0,0}, {35269,35261,35270 ,19373,19365,19374 ,0,0,0}, + {35271,35267,35266 ,19375,19371,19370 ,0,0,0}, {35268,35270,35266 ,19372,19374,19370 ,0,0,0}, + {35271,35272,35267 ,19375,19376,19371 ,0,0,0}, {35269,35270,35268 ,19373,19374,19372 ,0,0,0}, + {35271,35273,35272 ,19375,19377,19376 ,0,0,0}, {35274,35273,35275 ,19378,19377,19379 ,0,0,0}, + {35274,35275,35276 ,19378,19379,19380 ,0,0,0}, {35264,35263,35276 ,19368,19367,19380 ,0,0,0}, + {35273,35274,35272 ,19377,19378,19376 ,0,0,0}, {35264,35276,35275 ,19368,19380,19379 ,0,0,0}, + {35277,35278,35279 ,19381,19382,19383 ,0,0,0}, {35280,35265,35277 ,19384,19369,19381 ,0,0,0}, + {35263,35265,35280 ,19367,19369,19384 ,0,0,0}, {35262,35261,35269 ,19366,19365,19373 ,0,0,0}, + {35280,35277,35279 ,19384,19381,19383 ,0,0,0}, {35279,35278,35281 ,19383,19382,82 ,0,0,0}, + {35278,35282,35281 ,19382,19287,82 ,0,0,0}, {35252,35256,35253 ,19356,19360,19357 ,0,0,0}, + {35283,35235,35236 ,19385,19339,19340 ,0,0,0}, {35283,35284,35285 ,19385,19386,19387 ,0,0,0}, + {35285,35235,35283 ,19387,19339,19385 ,0,0,0}, {35286,35284,35287 ,19388,19386,19389 ,0,0,0}, + {35284,35286,35285 ,19386,19388,19387 ,0,0,0}, {35288,35289,35287 ,19390,19391,19389 ,0,0,0}, + {35286,35287,35289 ,19388,19389,19391 ,0,0,0}, {35288,35290,35291 ,19390,19392,19393 ,0,0,0}, + {35291,35289,35288 ,19393,19391,19390 ,0,0,0}, {35292,35290,35293 ,19394,19392,19395 ,0,0,0}, + {35290,35292,35291 ,19392,19394,19393 ,0,0,0}, {35294,35295,35293 ,19396,19397,19395 ,0,0,0}, + {35292,35293,35295 ,19394,19395,19397 ,0,0,0}, {35294,35296,35297 ,19396,19398,19399 ,0,0,0}, + {35297,35295,35294 ,19399,19397,19396 ,0,0,0}, {35298,35296,35299 ,19400,19398,19401 ,0,0,0}, + {35296,35298,35297 ,19398,19400,19399 ,0,0,0}, {35300,35301,35299 ,19402,19403,19401 ,0,0,0}, + {35298,35299,35301 ,19400,19401,19403 ,0,0,0}, {35300,35302,35303 ,19402,19404,19405 ,0,0,0}, + {35303,35301,35300 ,19405,19403,19402 ,0,0,0}, {35304,35302,35305 ,19406,19404,19407 ,0,0,0}, + {35302,35304,35303 ,19404,19406,19405 ,0,0,0}, {35231,35230,35305 ,19335,19334,19407 ,0,0,0}, + {35304,35305,35230 ,19406,19407,19334 ,0,0,0}, {35229,35231,35306 ,19333,19335,19408 ,0,0,0}, + {35306,35307,35308 ,19408,19409,19410 ,0,0,0}, {35308,35229,35306 ,19410,19333,19408 ,0,0,0}, + {35309,35307,35310 ,19411,19409,19412 ,0,0,0}, {35307,35309,35308 ,19409,19411,19410 ,0,0,0}, + {35311,35312,35310 ,19413,19317,19412 ,0,0,0}, {35309,35310,35312 ,19411,19412,19317 ,0,0,0}, + {35311,35313,35314 ,19413,19414,19415 ,0,0,0}, {35314,35312,35311 ,19415,19317,19413 ,0,0,0}, + {35315,35313,35316 ,19416,19414,19417 ,0,0,0}, {35313,35315,35314 ,19414,19416,19415 ,0,0,0}, + {35317,35318,35316 ,19418,19419,19417 ,0,0,0}, {35315,35316,35318 ,19416,19417,19419 ,0,0,0}, + {35317,35319,35320 ,19418,19420,19421 ,0,0,0}, {35320,35318,35317 ,19421,19419,19418 ,0,0,0}, + {35321,35319,35322 ,19422,19420,19423 ,0,0,0}, {35319,35321,35320 ,19420,19422,19421 ,0,0,0}, + {35323,35324,35322 ,19328,19424,19423 ,0,0,0}, {35321,35322,35324 ,19422,19423,19424 ,0,0,0}, + {35323,35325,35326 ,19328,19330,19425 ,0,0,0}, {35326,35324,35323 ,19425,19424,19328 ,0,0,0}, + {35327,35325,35328 ,19332,19330,19332 ,0,0,0}, {35325,35327,35326 ,19330,19332,19425 ,0,0,0}, + {35329,35330,35331 ,19426,19427,19428 ,0,0,0}, {35332,35333,35334 ,19429,19430,19240 ,0,0,0}, + {35335,35333,35336 ,19431,19430,19432 ,0,0,0}, {35332,35336,35333 ,19429,19432,19430 ,0,0,0}, + {35337,35332,35334 ,19433,19429,19240 ,0,0,0}, {35337,35338,35339 ,19433,19434,19435 ,0,0,0}, + {35338,35340,35339 ,19434,19436,19435 ,0,0,0}, {35339,35340,35341 ,19435,19436,19437 ,0,0,0}, + {35341,35342,35343 ,19437,19438,19439 ,0,0,0}, {35341,35340,35342 ,19437,19436,19438 ,0,0,0}, + {35344,35345,35346 ,19440,19441,19442 ,0,0,0}, {35347,35343,35342 ,19443,19439,19438 ,0,0,0}, + {35345,35348,35346 ,19441,19444,19442 ,0,0,0}, {35347,35348,35349 ,19443,19444,19445 ,0,0,0}, + {35343,35347,35349 ,19439,19443,19445 ,0,0,0}, {35349,35348,35345 ,19445,19444,19441 ,0,0,0}, + {35350,35351,35352 ,19446,19447,19448 ,0,0,0}, {35346,35351,35344 ,19442,19447,19440 ,0,0,0}, + {35350,35352,35353 ,19446,19448,19449 ,0,0,0}, {35351,35350,35344 ,19447,19446,19440 ,0,0,0}, + {35338,35337,35334 ,19434,19433,19240 ,0,0,0}, {35354,35355,35356 ,19450,19451,19452 ,0,0,0}, + {35355,35353,35356 ,19451,19449,19452 ,0,0,0}, {35357,35358,35359 ,19453,19454,19455 ,0,0,0}, + {35357,35355,35354 ,19453,19451,19450 ,0,0,0}, {35360,35359,35358 ,19456,19455,19454 ,0,0,0}, + {35354,35358,35357 ,19450,19454,19453 ,0,0,0}, {35361,35362,35360 ,19457,19458,19456 ,0,0,0}, + {35362,35359,35360 ,19458,19455,19456 ,0,0,0}, {35363,35364,35365 ,19459,19460,19461 ,0,0,0}, + {35366,35367,35368 ,19462,19463,19464 ,0,0,0}, {35369,35361,35370 ,19465,19457,19466 ,0,0,0}, + {35371,35367,35366 ,19467,19463,19462 ,0,0,0}, {35368,35370,35366 ,19464,19466,19462 ,0,0,0}, + {35371,35372,35367 ,19467,19468,19463 ,0,0,0}, {35369,35370,35368 ,19465,19466,19464 ,0,0,0}, + {35371,35373,35372 ,19467,19469,19468 ,0,0,0}, {35374,35373,35375 ,19470,19469,19471 ,0,0,0}, + {35374,35375,35376 ,19470,19471,19472 ,0,0,0}, {35364,35363,35376 ,19460,19459,19472 ,0,0,0}, + {35373,35374,35372 ,19469,19470,19468 ,0,0,0}, {35364,35376,35375 ,19460,19472,19471 ,0,0,0}, + {35377,35378,35379 ,19473,19474,19475 ,0,0,0}, {35380,35365,35377 ,19476,19461,19473 ,0,0,0}, + {35363,35365,35380 ,19459,19461,19476 ,0,0,0}, {35362,35361,35369 ,19458,19457,19465 ,0,0,0}, + {35380,35377,35379 ,19476,19473,19475 ,0,0,0}, {35379,35378,35381 ,19475,19474,19477 ,0,0,0}, + {35378,35382,35381 ,19474,19478,19477 ,0,0,0}, {35352,35356,35353 ,19448,19452,19449 ,0,0,0}, + {35383,35335,35336 ,19479,19431,19432 ,0,0,0}, {35383,35384,35385 ,19479,19480,19481 ,0,0,0}, + {35385,35335,35383 ,19481,19431,19479 ,0,0,0}, {35386,35384,35387 ,19482,19480,19483 ,0,0,0}, + {35384,35386,35385 ,19480,19482,19481 ,0,0,0}, {35388,35389,35387 ,19484,19485,19483 ,0,0,0}, + {35386,35387,35389 ,19482,19483,19485 ,0,0,0}, {35388,35390,35391 ,19484,19486,19487 ,0,0,0}, + {35391,35389,35388 ,19487,19485,19484 ,0,0,0}, {35392,35390,35393 ,19488,19486,19489 ,0,0,0}, + {35390,35392,35391 ,19486,19488,19487 ,0,0,0}, {35394,35395,35393 ,19490,19491,19489 ,0,0,0}, + {35392,35393,35395 ,19488,19489,19491 ,0,0,0}, {35394,35396,35397 ,19490,19492,19493 ,0,0,0}, + {35397,35395,35394 ,19493,19491,19490 ,0,0,0}, {35398,35396,35399 ,19494,19492,19495 ,0,0,0}, + {35396,35398,35397 ,19492,19494,19493 ,0,0,0}, {35400,35401,35399 ,19496,19497,19495 ,0,0,0}, + {35398,35399,35401 ,19494,19495,19497 ,0,0,0}, {35400,35402,35403 ,19496,19498,19499 ,0,0,0}, + {35403,35401,35400 ,19499,19497,19496 ,0,0,0}, {35404,35402,35405 ,19500,19498,19501 ,0,0,0}, + {35402,35404,35403 ,19498,19500,19499 ,0,0,0}, {35331,35330,35405 ,19428,19427,19501 ,0,0,0}, + {35404,35405,35330 ,19500,19501,19427 ,0,0,0}, {35329,35331,35406 ,19426,19428,19502 ,0,0,0}, + {35406,35407,35408 ,19502,19503,19504 ,0,0,0}, {35408,35329,35406 ,19504,19426,19502 ,0,0,0}, + {35409,35407,35410 ,19505,19503,19506 ,0,0,0}, {35407,35409,35408 ,19503,19505,19504 ,0,0,0}, + {35411,35412,35410 ,19507,19508,19506 ,0,0,0}, {35409,35410,35412 ,19505,19506,19508 ,0,0,0}, + {35411,35413,35414 ,19507,19509,19510 ,0,0,0}, {35414,35412,35411 ,19510,19508,19507 ,0,0,0}, + {35415,35413,35416 ,19511,19509,19321 ,0,0,0}, {35413,35415,35414 ,19509,19511,19510 ,0,0,0}, + {35417,35418,35416 ,19512,19513,19321 ,0,0,0}, {35415,35416,35418 ,19511,19321,19513 ,0,0,0}, + {35417,35419,35420 ,19512,19324,19325 ,0,0,0}, {35420,35418,35417 ,19325,19513,19512 ,0,0,0}, + {35421,35419,35422 ,19326,19324,19514 ,0,0,0}, {35419,35421,35420 ,19324,19326,19325 ,0,0,0}, + {35423,35424,35422 ,19515,19329,19514 ,0,0,0}, {35421,35422,35424 ,19326,19514,19329 ,0,0,0}, + {35423,35425,35426 ,19515,19516,19517 ,0,0,0}, {35426,35424,35423 ,19517,19329,19515 ,0,0,0}, + {35427,35425,35428 ,19518,19516,126 ,0,0,0}, {35425,35427,35426 ,19516,19518,19517 ,0,0,0}, + {35429,35430,35431 ,19519,19520,19521 ,0,0,0}, {35432,35433,35434 ,19522,19523,19524 ,0,0,0}, + {35435,35433,35436 ,19525,19523,19526 ,0,0,0}, {35432,35436,35433 ,19522,19526,19523 ,0,0,0}, + {35437,35432,35434 ,19527,19522,19524 ,0,0,0}, {35437,35438,35439 ,19527,19528,19529 ,0,0,0}, + {35438,35440,35439 ,19528,19530,19529 ,0,0,0}, {35439,35440,35441 ,19529,19530,19531 ,0,0,0}, + {35441,35442,35443 ,19531,19532,19533 ,0,0,0}, {35441,35440,35442 ,19531,19530,19532 ,0,0,0}, + {35444,35445,35446 ,19534,19535,19536 ,0,0,0}, {35447,35443,35442 ,19537,19533,19532 ,0,0,0}, + {35445,35448,35446 ,19535,19538,19536 ,0,0,0}, {35447,35448,35449 ,19537,19538,19539 ,0,0,0}, + {35443,35447,35449 ,19533,19537,19539 ,0,0,0}, {35449,35448,35445 ,19539,19538,19535 ,0,0,0}, + {35450,35451,35452 ,19540,19541,19542 ,0,0,0}, {35446,35451,35444 ,19536,19541,19534 ,0,0,0}, + {35450,35452,35453 ,19540,19542,19543 ,0,0,0}, {35451,35450,35444 ,19541,19540,19534 ,0,0,0}, + {35438,35437,35434 ,19528,19527,19524 ,0,0,0}, {35454,35455,35456 ,19544,19545,19546 ,0,0,0}, + {35455,35453,35456 ,19545,19543,19546 ,0,0,0}, {35457,35458,35459 ,19547,19548,19549 ,0,0,0}, + {35457,35455,35454 ,19547,19545,19544 ,0,0,0}, {35460,35459,35458 ,19550,19549,19548 ,0,0,0}, + {35454,35458,35457 ,19544,19548,19547 ,0,0,0}, {35461,35462,35460 ,19551,19552,19550 ,0,0,0}, + {35462,35459,35460 ,19552,19549,19550 ,0,0,0}, {35463,35464,35465 ,19553,19554,19555 ,0,0,0}, + {35466,35467,35468 ,19556,19557,19558 ,0,0,0}, {35469,35461,35470 ,19559,19551,19560 ,0,0,0}, + {35471,35467,35466 ,19561,19557,19556 ,0,0,0}, {35468,35470,35466 ,19558,19560,19556 ,0,0,0}, + {35471,35472,35467 ,19561,19562,19557 ,0,0,0}, {35469,35470,35468 ,19559,19560,19558 ,0,0,0}, + {35471,35473,35472 ,19561,19563,19562 ,0,0,0}, {35474,35473,35475 ,19564,19563,19565 ,0,0,0}, + {35474,35475,35476 ,19564,19565,19566 ,0,0,0}, {35464,35463,35476 ,19554,19553,19566 ,0,0,0}, + {35473,35474,35472 ,19563,19564,19562 ,0,0,0}, {35464,35476,35475 ,19554,19566,19565 ,0,0,0}, + {35477,35478,35479 ,19567,19568,19569 ,0,0,0}, {35480,35465,35477 ,19570,19555,19567 ,0,0,0}, + {35463,35465,35480 ,19553,19555,19570 ,0,0,0}, {35462,35461,35469 ,19552,19551,19559 ,0,0,0}, + {35480,35477,35479 ,19570,19567,19569 ,0,0,0}, {35479,35478,35481 ,19569,19568,878 ,0,0,0}, + {35478,35482,35481 ,19568,19571,878 ,0,0,0}, {35452,35456,35453 ,19542,19546,19543 ,0,0,0}, + {35483,35435,35436 ,19572,19525,19526 ,0,0,0}, {35483,35484,35485 ,19572,19573,19387 ,0,0,0}, + {35485,35435,35483 ,19387,19525,19572 ,0,0,0}, {35486,35484,35487 ,19574,19573,19575 ,0,0,0}, + {35484,35486,35485 ,19573,19574,19387 ,0,0,0}, {35488,35489,35487 ,19576,19577,19575 ,0,0,0}, + {35486,35487,35489 ,19574,19575,19577 ,0,0,0}, {35488,35490,35491 ,19576,19578,19579 ,0,0,0}, + {35491,35489,35488 ,19579,19577,19576 ,0,0,0}, {35492,35490,35493 ,19580,19578,19581 ,0,0,0}, + {35490,35492,35491 ,19578,19580,19579 ,0,0,0}, {35494,35495,35493 ,19299,19582,19581 ,0,0,0}, + {35492,35493,35495 ,19580,19581,19582 ,0,0,0}, {35494,35496,35497 ,19299,19492,19583 ,0,0,0}, + {35497,35495,35494 ,19583,19582,19299 ,0,0,0}, {35498,35496,35499 ,19584,19492,19585 ,0,0,0}, + {35496,35498,35497 ,19492,19584,19583 ,0,0,0}, {35500,35501,35499 ,19586,19497,19585 ,0,0,0}, + {35498,35499,35501 ,19584,19585,19497 ,0,0,0}, {35500,35502,35503 ,19586,19587,19308 ,0,0,0}, + {35503,35501,35500 ,19308,19497,19586 ,0,0,0}, {35504,35502,35505 ,19588,19587,19589 ,0,0,0}, + {35502,35504,35503 ,19587,19588,19308 ,0,0,0}, {35431,35430,35505 ,19521,19520,19589 ,0,0,0}, + {35504,35505,35430 ,19588,19589,19520 ,0,0,0}, {35429,35431,35506 ,19519,19521,19590 ,0,0,0}, + {35506,35507,35508 ,19590,19591,19592 ,0,0,0}, {35508,35429,35506 ,19592,19519,19590 ,0,0,0}, + {35509,35507,35510 ,19593,19591,19506 ,0,0,0}, {35507,35509,35508 ,19591,19593,19592 ,0,0,0}, + {35511,35512,35510 ,19594,19595,19506 ,0,0,0}, {35509,35510,35512 ,19593,19506,19595 ,0,0,0}, + {35511,35513,35514 ,19594,19596,19597 ,0,0,0}, {35514,35512,35511 ,19597,19595,19594 ,0,0,0}, + {35515,35513,35516 ,19598,19596,19599 ,0,0,0}, {35513,35515,35514 ,19596,19598,19597 ,0,0,0}, + {35517,35518,35516 ,19600,19513,19599 ,0,0,0}, {35515,35516,35518 ,19598,19599,19513 ,0,0,0}, + {35517,35519,35520 ,19600,19601,19602 ,0,0,0}, {35520,35518,35517 ,19602,19513,19600 ,0,0,0}, + {35521,35519,35522 ,19326,19601,19603 ,0,0,0}, {35519,35521,35520 ,19601,19326,19602 ,0,0,0}, + {35523,35524,35522 ,19604,19605,19603 ,0,0,0}, {35521,35522,35524 ,19326,19603,19605 ,0,0,0}, + {35523,35525,35526 ,19604,19330,19517 ,0,0,0}, {35526,35524,35523 ,19517,19605,19604 ,0,0,0}, + {35527,35525,35528 ,19606,19330,126 ,0,0,0}, {35525,35527,35526 ,19330,19606,19517 ,0,0,0}, + {35529,35530,35531 ,19607,19608,19609 ,0,0,0}, {35529,35532,35533 ,19607,19610,19611 ,0,0,0}, + {35532,35534,35533 ,19610,19612,19611 ,0,0,0}, {35531,35532,35529 ,19609,19610,19607 ,0,0,0}, + {35535,35536,35537 ,19613,19614,19615 ,0,0,0}, {35534,35535,35537 ,19612,19613,19615 ,0,0,0}, + {35536,35538,35539 ,19614,19616,19617 ,0,0,0}, {35538,35536,35535 ,19616,19614,19613 ,0,0,0}, + {35539,35538,35540 ,19617,19616,19618 ,0,0,0}, {35541,35539,35540 ,19619,19617,19618 ,0,0,0}, + {35541,35542,35543 ,19619,19620,19621 ,0,0,0}, {35541,35540,35542 ,19619,19618,19620 ,0,0,0}, + {35537,35533,35534 ,19615,19611,19612 ,0,0,0}, {35544,35545,33824 ,19622,19623,126 ,0,0,0}, + {35544,33824,35543 ,19622,126,19621 ,0,0,0}, {35542,35544,35543 ,19620,19622,19621 ,0,0,0}, + {35531,35530,35546 ,19609,19608,18805 ,0,0,0}, {35547,35546,35548 ,19624,18805,19625 ,0,0,0}, + {35530,35548,35546 ,19608,19625,18805 ,0,0,0}, {35549,35550,35547 ,19626,19627,19624 ,0,0,0}, + {35547,35548,35549 ,19624,19625,19626 ,0,0,0}, {35550,35551,35552 ,19627,19628,19629 ,0,0,0}, + {35551,35550,35549 ,19628,19627,19626 ,0,0,0}, {35553,35552,35554 ,19630,19629,19631 ,0,0,0}, + {35551,35554,35552 ,19628,19631,19629 ,0,0,0}, {35555,35556,35553 ,19632,18067,19630 ,0,0,0}, + {35553,35554,35555 ,19630,19631,19632 ,0,0,0}, {35556,35557,35558 ,18067,18838,19633 ,0,0,0}, + {35557,35556,35555 ,18838,18067,19632 ,0,0,0}, {35557,33841,35558 ,18838,82,19633 ,0,0,0}, + {35559,35560,35561 ,19634,19635,19636 ,0,0,0}, {35559,35562,35563 ,19634,19637,19638 ,0,0,0}, + {35562,35564,35563 ,19637,19639,19638 ,0,0,0}, {35561,35562,35559 ,19636,19637,19634 ,0,0,0}, + {35565,35566,35567 ,19640,19614,19641 ,0,0,0}, {35564,35565,35567 ,19639,19640,19641 ,0,0,0}, + {35566,35568,35569 ,19614,19642,19643 ,0,0,0}, {35568,35566,35565 ,19642,19614,19640 ,0,0,0}, + {35569,35568,35570 ,19643,19642,19644 ,0,0,0}, {35571,35569,35570 ,19645,19643,19644 ,0,0,0}, + {35571,35572,35573 ,19645,19646,19647 ,0,0,0}, {35571,35570,35572 ,19645,19644,19646 ,0,0,0}, + {35567,35563,35564 ,19641,19638,19639 ,0,0,0}, {35574,35575,33192 ,19648,19649,126 ,0,0,0}, + {35574,33192,35573 ,19648,126,19647 ,0,0,0}, {35572,35574,35573 ,19646,19648,19647 ,0,0,0}, + {35561,35560,35576 ,19636,19635,19650 ,0,0,0}, {35577,35576,35578 ,19624,19650,19651 ,0,0,0}, + {35560,35578,35576 ,19635,19651,19650 ,0,0,0}, {35579,35580,35577 ,19626,19627,19624 ,0,0,0}, + {35577,35578,35579 ,19624,19651,19626 ,0,0,0}, {35580,35581,35582 ,19627,19628,19629 ,0,0,0}, + {35581,35580,35579 ,19628,19627,19626 ,0,0,0}, {35583,35582,35584 ,19630,19629,19652 ,0,0,0}, + {35581,35584,35582 ,19628,19652,19629 ,0,0,0}, {35585,35586,35583 ,19653,18067,19630 ,0,0,0}, + {35583,35584,35585 ,19630,19652,19653 ,0,0,0}, {35586,35587,35588 ,18067,19654,19655 ,0,0,0}, + {35587,35586,35585 ,19654,18067,19653 ,0,0,0}, {35587,33209,35588 ,19654,82,19655 ,0,0,0}, + {35589,35590,35591 ,19656,19657,19658 ,0,0,0}, {35589,35592,35593 ,19656,19659,19660 ,0,0,0}, + {35592,35594,35593 ,19659,19612,19660 ,0,0,0}, {35591,35592,35589 ,19658,19659,19656 ,0,0,0}, + {35595,35596,35597 ,19661,19662,19663 ,0,0,0}, {35594,35595,35597 ,19612,19661,19663 ,0,0,0}, + {35596,35598,35599 ,19662,19664,19665 ,0,0,0}, {35598,35596,35595 ,19664,19662,19661 ,0,0,0}, + {35599,35598,35600 ,19665,19664,19666 ,0,0,0}, {35601,35599,35600 ,19667,19665,19666 ,0,0,0}, + {35601,35602,35603 ,19667,19668,19669 ,0,0,0}, {35601,35600,35602 ,19667,19666,19668 ,0,0,0}, + {35597,35593,35594 ,19663,19660,19612 ,0,0,0}, {35604,35605,32876 ,19670,19623,126 ,0,0,0}, + {35604,32876,35603 ,19670,126,19669 ,0,0,0}, {35602,35604,35603 ,19668,19670,19669 ,0,0,0}, + {35591,35590,35606 ,19658,19657,19671 ,0,0,0}, {35607,35606,35608 ,19672,19671,19673 ,0,0,0}, + {35590,35608,35606 ,19657,19673,19671 ,0,0,0}, {35609,35610,35607 ,19626,19674,19672 ,0,0,0}, + {35607,35608,35609 ,19672,19673,19626 ,0,0,0}, {35610,35611,35612 ,19674,19675,19629 ,0,0,0}, + {35611,35610,35609 ,19675,19674,19626 ,0,0,0}, {35613,35612,35614 ,19676,19629,19677 ,0,0,0}, + {35611,35614,35612 ,19675,19677,19629 ,0,0,0}, {35615,35616,35613 ,19632,18067,19676 ,0,0,0}, + {35613,35614,35615 ,19676,19677,19632 ,0,0,0}, {35616,35617,35618 ,18067,18838,19633 ,0,0,0}, + {35617,35616,35615 ,18838,18067,19632 ,0,0,0}, {35617,32893,35618 ,18838,82,19633 ,0,0,0}, + {35619,35620,35621 ,19678,19679,19680 ,0,0,0}, {35619,35622,35623 ,19678,19681,19682 ,0,0,0}, + {35622,35624,35623 ,19681,19639,19682 ,0,0,0}, {35621,35622,35619 ,19680,19681,19678 ,0,0,0}, + {35625,35626,35627 ,19683,19662,19684 ,0,0,0}, {35624,35625,35627 ,19639,19683,19684 ,0,0,0}, + {35626,35628,35629 ,19662,19685,19686 ,0,0,0}, {35628,35626,35625 ,19685,19662,19683 ,0,0,0}, + {35629,35628,35630 ,19686,19685,19687 ,0,0,0}, {35631,35629,35630 ,19688,19686,19687 ,0,0,0}, + {35631,35632,35633 ,19688,19689,19690 ,0,0,0}, {35631,35630,35632 ,19688,19687,19689 ,0,0,0}, + {35627,35623,35624 ,19684,19682,19639 ,0,0,0}, {35634,35635,33508 ,19691,19649,126 ,0,0,0}, + {35634,33508,35633 ,19691,126,19690 ,0,0,0}, {35632,35634,35633 ,19689,19691,19690 ,0,0,0}, + {35621,35620,35636 ,19680,19679,19692 ,0,0,0}, {35637,35636,35638 ,19672,19692,19693 ,0,0,0}, + {35620,35638,35636 ,19679,19693,19692 ,0,0,0}, {35639,35640,35637 ,19626,19674,19672 ,0,0,0}, + {35637,35638,35639 ,19672,19693,19626 ,0,0,0}, {35640,35641,35642 ,19674,19675,19629 ,0,0,0}, + {35641,35640,35639 ,19675,19674,19626 ,0,0,0}, {35643,35642,35644 ,19676,19629,19694 ,0,0,0}, + {35641,35644,35642 ,19675,19694,19629 ,0,0,0}, {35645,35646,35643 ,19653,18067,19676 ,0,0,0}, + {35643,35644,35645 ,19676,19694,19653 ,0,0,0}, {35646,35647,35648 ,18067,19654,19655 ,0,0,0}, + {35647,35646,35645 ,19654,18067,19653 ,0,0,0}, {35647,33525,35648 ,19654,82,19655 ,0,0,0}, + {35649,35650,35651 ,19695,19696,19697 ,0,0,0}, {35649,35652,35653 ,19695,19698,19699 ,0,0,0}, + {35652,35654,35653 ,19698,19700,19699 ,0,0,0}, {35651,35652,35649 ,19697,19698,19695 ,0,0,0}, + {35655,35656,35657 ,19701,19702,19703 ,0,0,0}, {35654,35655,35657 ,19700,19701,19703 ,0,0,0}, + {35656,35658,35659 ,19702,19704,19705 ,0,0,0}, {35658,35656,35655 ,19704,19702,19701 ,0,0,0}, + {35659,35658,35660 ,19705,19704,19706 ,0,0,0}, {35661,35659,35660 ,19707,19705,19706 ,0,0,0}, + {35661,35662,35663 ,19707,19708,19709 ,0,0,0}, {35661,35660,35662 ,19707,19706,19708 ,0,0,0}, + {35657,35653,35654 ,19703,19699,19700 ,0,0,0}, {35664,35665,35666 ,19710,19711,126 ,0,0,0}, + {35664,35666,35663 ,19710,126,19709 ,0,0,0}, {35662,35664,35663 ,19708,19710,19709 ,0,0,0}, + {35651,35650,35667 ,19697,19696,19712 ,0,0,0}, {35668,35667,35669 ,19672,19712,19673 ,0,0,0}, + {35650,35669,35667 ,19696,19673,19712 ,0,0,0}, {35670,35671,35668 ,19713,19674,19672 ,0,0,0}, + {35668,35669,35670 ,19672,19673,19713 ,0,0,0}, {35671,35672,35673 ,19674,19714,19715 ,0,0,0}, + {35672,35671,35670 ,19714,19674,19713 ,0,0,0}, {35674,35673,35675 ,19676,19715,19694 ,0,0,0}, + {35672,35675,35673 ,19714,19694,19715 ,0,0,0}, {35676,35677,35674 ,18761,18067,19676 ,0,0,0}, + {35674,35675,35676 ,19676,19694,18761 ,0,0,0}, {35677,35678,35679 ,18067,19716,140 ,0,0,0}, + {35678,35677,35676 ,19716,18067,18761 ,0,0,0}, {35678,35680,35679 ,19716,82,140 ,0,0,0}, + {35681,35682,35683 ,19656,19657,19717 ,0,0,0}, {35681,35684,35685 ,19656,19698,19718 ,0,0,0}, + {35684,35686,35685 ,19698,19719,19718 ,0,0,0}, {35683,35684,35681 ,19717,19698,19656 ,0,0,0}, + {35687,35688,35689 ,19720,19721,19722 ,0,0,0}, {35686,35687,35689 ,19719,19720,19722 ,0,0,0}, + {35688,35690,35691 ,19721,19723,19724 ,0,0,0}, {35690,35688,35687 ,19723,19721,19720 ,0,0,0}, + {35691,35690,35692 ,19724,19723,19725 ,0,0,0}, {35693,35691,35692 ,19726,19724,19725 ,0,0,0}, + {35693,35694,35695 ,19726,19727,19728 ,0,0,0}, {35693,35692,35694 ,19726,19725,19727 ,0,0,0}, + {35689,35685,35686 ,19722,19718,19719 ,0,0,0}, {35696,35697,35698 ,19729,19730,126 ,0,0,0}, + {35696,35698,35695 ,19729,126,19728 ,0,0,0}, {35694,35696,35695 ,19727,19729,19728 ,0,0,0}, + {35683,35682,35699 ,19717,19657,19671 ,0,0,0}, {35700,35699,35701 ,19731,19671,19732 ,0,0,0}, + {35682,35701,35699 ,19657,19732,19671 ,0,0,0}, {35702,35703,35700 ,19733,19674,19731 ,0,0,0}, + {35700,35701,35702 ,19731,19732,19733 ,0,0,0}, {35703,35704,35705 ,19674,19734,19715 ,0,0,0}, + {35704,35703,35702 ,19734,19674,19733 ,0,0,0}, {35706,35705,35707 ,19676,19715,19735 ,0,0,0}, + {35704,35707,35705 ,19734,19735,19715 ,0,0,0}, {35708,35709,35706 ,18761,18067,19676 ,0,0,0}, + {35706,35707,35708 ,19676,19735,18761 ,0,0,0}, {35709,35710,35711 ,18067,18838,793 ,0,0,0}, + {35710,35709,35708 ,18838,18067,18761 ,0,0,0}, {35710,35712,35711 ,18838,82,793 ,0,0,0}, + {35713,35714,35715 ,19607,19608,19736 ,0,0,0}, {35713,35716,35717 ,19607,19737,19738 ,0,0,0}, + {35716,35718,35717 ,19737,19719,19738 ,0,0,0}, {35715,35716,35713 ,19736,19737,19607 ,0,0,0}, + {35719,35720,35721 ,19739,19740,19741 ,0,0,0}, {35718,35719,35721 ,19719,19739,19741 ,0,0,0}, + {35720,35722,35723 ,19740,19742,19743 ,0,0,0}, {35722,35720,35719 ,19742,19740,19739 ,0,0,0}, + {35723,35722,35724 ,19743,19742,19744 ,0,0,0}, {35725,35723,35724 ,19745,19743,19744 ,0,0,0}, + {35725,35726,35727 ,19745,19746,19747 ,0,0,0}, {35725,35724,35726 ,19745,19744,19746 ,0,0,0}, + {35721,35717,35718 ,19741,19738,19719 ,0,0,0}, {35728,35729,35730 ,19748,19730,126 ,0,0,0}, + {35728,35730,35727 ,19748,126,19747 ,0,0,0}, {35726,35728,35727 ,19746,19748,19747 ,0,0,0}, + {35715,35714,35731 ,19736,19608,18805 ,0,0,0}, {35732,35731,35733 ,19749,18805,19750 ,0,0,0}, + {35714,35733,35731 ,19608,19750,18805 ,0,0,0}, {35734,35735,35732 ,19733,19627,19749 ,0,0,0}, + {35732,35733,35734 ,19749,19750,19733 ,0,0,0}, {35735,35736,35737 ,19627,19751,19715 ,0,0,0}, + {35736,35735,35734 ,19751,19627,19733 ,0,0,0}, {35738,35737,35739 ,19630,19715,19752 ,0,0,0}, + {35736,35739,35737 ,19751,19752,19715 ,0,0,0}, {35740,35741,35738 ,18761,18067,19630 ,0,0,0}, + {35738,35739,35740 ,19630,19752,18761 ,0,0,0}, {35741,35742,35743 ,18067,18838,793 ,0,0,0}, + {35742,35741,35740 ,18838,18067,18761 ,0,0,0}, {35742,35744,35743 ,18838,82,793 ,0,0,0}, + {35745,35746,35747 ,19634,19753,19754 ,0,0,0}, {35745,35748,35749 ,19634,19610,19755 ,0,0,0}, + {35748,35750,35749 ,19610,19756,19755 ,0,0,0}, {35747,35748,35745 ,19754,19610,19634 ,0,0,0}, + {35751,35752,35753 ,19757,19758,19759 ,0,0,0}, {35750,35751,35753 ,19756,19757,19759 ,0,0,0}, + {35752,35754,35755 ,19758,19760,19761 ,0,0,0}, {35754,35752,35751 ,19760,19758,19757 ,0,0,0}, + {35755,35754,35756 ,19761,19760,19762 ,0,0,0}, {35757,35755,35756 ,19763,19761,19762 ,0,0,0}, + {35757,35758,35759 ,19763,19764,19765 ,0,0,0}, {35757,35756,35758 ,19763,19762,19764 ,0,0,0}, + {35753,35749,35750 ,19759,19755,19756 ,0,0,0}, {35760,35761,35762 ,19766,19767,18751 ,0,0,0}, + {35760,35762,35759 ,19766,18751,19765 ,0,0,0}, {35758,35760,35759 ,19764,19766,19765 ,0,0,0}, + {35747,35746,35763 ,19754,19753,19768 ,0,0,0}, {35764,35763,35765 ,19749,19768,19769 ,0,0,0}, + {35746,35765,35763 ,19753,19769,19768 ,0,0,0}, {35766,35767,35764 ,19713,19770,19749 ,0,0,0}, + {35764,35765,35766 ,19749,19769,19713 ,0,0,0}, {35767,35768,35769 ,19770,19771,19772 ,0,0,0}, + {35768,35767,35766 ,19771,19770,19713 ,0,0,0}, {35770,35769,35771 ,19773,19772,19774 ,0,0,0}, + {35768,35771,35769 ,19771,19774,19772 ,0,0,0}, {35772,35773,35770 ,19653,19775,19773 ,0,0,0}, + {35770,35771,35772 ,19773,19774,19653 ,0,0,0}, {35773,35774,35775 ,19775,19654,140 ,0,0,0}, + {35774,35773,35772 ,19654,19775,19653 ,0,0,0}, {35774,35776,35775 ,19654,82,140 ,0,0,0}, + {35777,35778,35779 ,19776,19777,19777 ,0,0,0}, {35780,35781,35782 ,19778,19779,19778 ,0,0,0}, + {35779,35778,35782 ,19777,19777,19778 ,0,0,0}, {35783,35784,35785 ,18601,18601,19779 ,0,0,0}, + {35781,35780,35785 ,19779,19778,19779 ,0,0,0}, {35785,35784,35781 ,19779,18601,19779 ,0,0,0}, + {35780,35782,35778 ,19778,19778,19777 ,0,0,0}, {35779,35786,35777 ,19777,19776,19776 ,0,0,0}, + {35786,35787,35788 ,19776,19780,19780 ,0,0,0}, {35788,35777,35786 ,19780,19776,19776 ,0,0,0}, + {35789,35787,35790 ,18588,19780,18588 ,0,0,0}, {35787,35789,35788 ,19780,18588,19780 ,0,0,0}, + {35791,35792,35793 ,19781,19782,19782 ,0,0,0}, {35794,35795,35796 ,19783,19784,19783 ,0,0,0}, + {35793,35792,35796 ,19782,19782,19783 ,0,0,0}, {35797,35798,35799 ,18609,18609,19784 ,0,0,0}, + {35795,35794,35799 ,19784,19783,19784 ,0,0,0}, {35799,35798,35795 ,19784,18609,19784 ,0,0,0}, + {35794,35796,35792 ,19783,19783,19782 ,0,0,0}, {35793,35800,35791 ,19782,19781,19781 ,0,0,0}, + {35800,35801,35802 ,19781,19785,19785 ,0,0,0}, {35802,35791,35800 ,19785,19781,19781 ,0,0,0}, + {35803,35801,35804 ,18594,19785,18594 ,0,0,0}, {35801,35803,35802 ,19785,18594,19785 ,0,0,0}, + {35805,35806,35807 ,19786,19787,19788 ,0,0,0}, {35808,35809,35810 ,19789,19790,19791 ,0,0,0}, + {35809,35805,35807 ,19790,19786,19788 ,0,0,0}, {35811,35808,35810 ,19792,19789,19791 ,0,0,0}, + {35809,35808,35805 ,19790,19789,19786 ,0,0,0}, {35811,35810,35812 ,19792,19791,19793 ,0,0,0}, + {35812,35813,35814 ,19793,19794,19795 ,0,0,0}, {35815,35814,35813 ,19796,19795,19794 ,0,0,0}, + {35816,35817,35818 ,19797,19798,19799 ,0,0,0}, {35813,35819,35815 ,19794,19800,19796 ,0,0,0}, + {35818,35820,35821 ,19799,19801,19802 ,0,0,0}, {35820,35819,35821 ,19801,19800,19802 ,0,0,0}, + {35815,35819,35820 ,19796,19800,19801 ,0,0,0}, {35818,35821,35816 ,19799,19802,19797 ,0,0,0}, + {35817,35816,35822 ,19798,19797,19803 ,0,0,0}, {35817,35822,35823 ,19798,19803,19804 ,0,0,0}, + {35824,35823,35822 ,19805,19804,19803 ,0,0,0}, {35825,35826,35827 ,19806,82,19807 ,0,0,0}, + {35827,35823,35824 ,19807,19804,19805 ,0,0,0}, {35825,35827,35824 ,19806,19807,19805 ,0,0,0}, + {35825,35828,35826 ,19806,3370,82 ,0,0,0}, {35811,35812,35814 ,19792,19793,19795 ,0,0,0}, + {35807,35806,35829 ,19788,19787,19808 ,0,0,0}, {35830,35829,35831 ,19809,19808,19810 ,0,0,0}, + {35806,35831,35829 ,19787,19810,19808 ,0,0,0}, {35832,35833,35830 ,19811,19812,19809 ,0,0,0}, + {35830,35831,35832 ,19809,19810,19811 ,0,0,0}, {35833,35834,35835 ,19812,19813,19814 ,0,0,0}, + {35834,35833,35832 ,19813,19812,19811 ,0,0,0}, {35836,35835,35837 ,19815,19814,19816 ,0,0,0}, + {35834,35837,35835 ,19813,19816,19814 ,0,0,0}, {35838,35839,35836 ,19817,19818,19815 ,0,0,0}, + {35836,35837,35838 ,19815,19816,19817 ,0,0,0}, {35839,35840,35841 ,19818,19819,19820 ,0,0,0}, + {35840,35839,35838 ,19819,19818,19817 ,0,0,0}, {35842,35841,35843 ,19821,19820,19822 ,0,0,0}, + {35840,35843,35841 ,19819,19822,19820 ,0,0,0}, {35844,35845,35842 ,19823,19824,19821 ,0,0,0}, + {35842,35843,35844 ,19821,19822,19823 ,0,0,0}, {35845,35846,35847 ,19824,19825,2614 ,0,0,0}, + {35846,35845,35844 ,19825,19824,19823 ,0,0,0}, {35846,35848,35847 ,19825,126,2614 ,0,0,0}, + {35849,35850,35851 ,19826,19827,19828 ,0,0,0}, {35852,35853,35854 ,19829,19830,19831 ,0,0,0}, + {35853,35849,35851 ,19830,19826,19828 ,0,0,0}, {35855,35852,35854 ,19832,19829,19831 ,0,0,0}, + {35853,35852,35849 ,19830,19829,19826 ,0,0,0}, {35855,35854,35856 ,19832,19831,19833 ,0,0,0}, + {35856,35857,35858 ,19833,19834,19835 ,0,0,0}, {35859,35858,35857 ,19836,19835,19834 ,0,0,0}, + {35860,35861,35862 ,19837,19838,19839 ,0,0,0}, {35857,35863,35859 ,19834,19840,19836 ,0,0,0}, + {35862,35864,35865 ,19839,19841,19842 ,0,0,0}, {35864,35863,35865 ,19841,19840,19842 ,0,0,0}, + {35859,35863,35864 ,19836,19840,19841 ,0,0,0}, {35862,35865,35860 ,19839,19842,19837 ,0,0,0}, + {35861,35860,35866 ,19838,19837,19843 ,0,0,0}, {35861,35866,35867 ,19838,19843,19844 ,0,0,0}, + {35868,35867,35866 ,19845,19844,19843 ,0,0,0}, {35869,35870,35871 ,19846,9510,19847 ,0,0,0}, + {35871,35867,35868 ,19847,19844,19845 ,0,0,0}, {35869,35871,35868 ,19846,19847,19845 ,0,0,0}, + {35869,35872,35870 ,19846,8396,9510 ,0,0,0}, {35855,35856,35858 ,19832,19833,19835 ,0,0,0}, + {35851,35850,35873 ,19828,19827,19848 ,0,0,0}, {35874,35873,35875 ,19849,19848,19850 ,0,0,0}, + {35850,35875,35873 ,19827,19850,19848 ,0,0,0}, {35876,35877,35874 ,19851,19852,19849 ,0,0,0}, + {35874,35875,35876 ,19849,19850,19851 ,0,0,0}, {35877,35878,35879 ,19852,4543,19853 ,0,0,0}, + {35878,35877,35876 ,4543,19852,19851 ,0,0,0}, {35880,35879,35881 ,19854,19853,19855 ,0,0,0}, + {35878,35881,35879 ,4543,19855,19853 ,0,0,0}, {35882,35883,35880 ,19856,19857,19854 ,0,0,0}, + {35880,35881,35882 ,19854,19855,19856 ,0,0,0}, {35883,35884,35885 ,19857,19858,19859 ,0,0,0}, + {35884,35883,35882 ,19858,19857,19856 ,0,0,0}, {35886,35885,35887 ,19860,19859,19861 ,0,0,0}, + {35884,35887,35885 ,19858,19861,19859 ,0,0,0}, {35888,35889,35886 ,19862,19863,19860 ,0,0,0}, + {35886,35887,35888 ,19860,19861,19862 ,0,0,0}, {35889,35890,35891 ,19863,19864,96 ,0,0,0}, + {35890,35889,35888 ,19864,19863,19862 ,0,0,0}, {35890,35892,35891 ,19864,126,96 ,0,0,0}, + {35893,35894,35895 ,19865,19866,19867 ,0,0,0}, {35896,35897,35898 ,19868,19869,19870 ,0,0,0}, + {35897,35893,35895 ,19869,19865,19867 ,0,0,0}, {35899,35896,35898 ,19871,19868,19870 ,0,0,0}, + {35897,35896,35893 ,19869,19868,19865 ,0,0,0}, {35899,35898,35900 ,19871,19870,19872 ,0,0,0}, + {35900,35901,35902 ,19872,19873,19874 ,0,0,0}, {35903,35902,35901 ,19875,19874,19873 ,0,0,0}, + {35904,35905,35906 ,19876,19877,19878 ,0,0,0}, {35901,35907,35903 ,19873,19879,19875 ,0,0,0}, + {35906,35908,35909 ,19878,19880,19881 ,0,0,0}, {35908,35907,35909 ,19880,19879,19881 ,0,0,0}, + {35903,35907,35908 ,19875,19879,19880 ,0,0,0}, {35906,35909,35904 ,19878,19881,19876 ,0,0,0}, + {35905,35904,35910 ,19877,19876,19882 ,0,0,0}, {35905,35910,35911 ,19877,19882,19883 ,0,0,0}, + {35912,35911,35910 ,19884,19883,19882 ,0,0,0}, {35913,35914,35915 ,19885,82,19886 ,0,0,0}, + {35915,35911,35912 ,19886,19883,19884 ,0,0,0}, {35913,35915,35912 ,19885,19886,19884 ,0,0,0}, + {35913,35916,35914 ,19885,2602,82 ,0,0,0}, {35899,35900,35902 ,19871,19872,19874 ,0,0,0}, + {35895,35894,35917 ,19867,19866,19887 ,0,0,0}, {35918,35917,35919 ,19809,19887,19888 ,0,0,0}, + {35894,35919,35917 ,19866,19888,19887 ,0,0,0}, {35920,35921,35918 ,19811,19812,19809 ,0,0,0}, + {35918,35919,35920 ,19809,19888,19811 ,0,0,0}, {35921,35922,35923 ,19812,19889,19890 ,0,0,0}, + {35922,35921,35920 ,19889,19812,19811 ,0,0,0}, {35924,35923,35925 ,19891,19890,19892 ,0,0,0}, + {35922,35925,35923 ,19889,19892,19890 ,0,0,0}, {35926,35927,35924 ,19893,19894,19891 ,0,0,0}, + {35924,35925,35926 ,19891,19892,19893 ,0,0,0}, {35927,35928,35929 ,19894,19895,19820 ,0,0,0}, + {35928,35927,35926 ,19895,19894,19893 ,0,0,0}, {35930,35929,35931 ,19896,19820,19822 ,0,0,0}, + {35928,35931,35929 ,19895,19822,19820 ,0,0,0}, {35932,35933,35930 ,19897,19824,19896 ,0,0,0}, + {35930,35931,35932 ,19896,19822,19897 ,0,0,0}, {35933,35934,35935 ,19824,19825,3345 ,0,0,0}, + {35934,35933,35932 ,19825,19824,19897 ,0,0,0}, {35934,35936,35935 ,19825,126,3345 ,0,0,0}, + {35937,35938,35939 ,19898,19899,19900 ,0,0,0}, {35940,35941,35942 ,19901,19902,19903 ,0,0,0}, + {35941,35937,35939 ,19902,19898,19900 ,0,0,0}, {35943,35940,35942 ,19904,19901,19903 ,0,0,0}, + {35941,35940,35937 ,19902,19901,19898 ,0,0,0}, {35943,35942,35944 ,19904,19903,19905 ,0,0,0}, + {35944,35945,35946 ,19905,19906,19907 ,0,0,0}, {35947,35946,35945 ,19908,19907,19906 ,0,0,0}, + {35948,35949,35950 ,19909,19910,19911 ,0,0,0}, {35945,35951,35947 ,19906,19912,19908 ,0,0,0}, + {35950,35952,35953 ,19911,19913,19914 ,0,0,0}, {35952,35951,35953 ,19913,19912,19914 ,0,0,0}, + {35947,35951,35952 ,19908,19912,19913 ,0,0,0}, {35950,35953,35948 ,19911,19914,19909 ,0,0,0}, + {35949,35948,35954 ,19910,19909,19915 ,0,0,0}, {35949,35954,35955 ,19910,19915,19916 ,0,0,0}, + {35956,35955,35954 ,19917,19916,19915 ,0,0,0}, {35957,35958,35959 ,19918,9510,19919 ,0,0,0}, + {35959,35955,35956 ,19919,19916,19917 ,0,0,0}, {35957,35959,35956 ,19918,19919,19917 ,0,0,0}, + {35957,35960,35958 ,19918,8396,9510 ,0,0,0}, {35943,35944,35946 ,19904,19905,19907 ,0,0,0}, + {35939,35938,35961 ,19900,19899,19920 ,0,0,0}, {35962,35961,35963 ,19921,19920,19922 ,0,0,0}, + {35938,35963,35961 ,19899,19922,19920 ,0,0,0}, {35964,35965,35962 ,19923,19852,19921 ,0,0,0}, + {35962,35963,35964 ,19921,19922,19923 ,0,0,0}, {35965,35966,35967 ,19852,19924,19925 ,0,0,0}, + {35966,35965,35964 ,19924,19852,19923 ,0,0,0}, {35968,35967,35969 ,19926,19925,19927 ,0,0,0}, + {35966,35969,35967 ,19924,19927,19925 ,0,0,0}, {35970,35971,35968 ,19928,19929,19926 ,0,0,0}, + {35968,35969,35970 ,19926,19927,19928 ,0,0,0}, {35971,35972,35973 ,19929,19930,19931 ,0,0,0}, + {35972,35971,35970 ,19930,19929,19928 ,0,0,0}, {35974,35973,35975 ,19932,19931,4552 ,0,0,0}, + {35972,35975,35973 ,19930,4552,19931 ,0,0,0}, {35976,35977,35974 ,19933,19934,19932 ,0,0,0}, + {35974,35975,35976 ,19932,4552,19933 ,0,0,0}, {35977,35978,35979 ,19934,19935,18053 ,0,0,0}, + {35978,35977,35976 ,19935,19934,19933 ,0,0,0}, {35978,35980,35979 ,19935,96,18053 ,0,0,0}, + {35981,35982,35983 ,19936,19937,19938 ,0,0,0}, {35984,35983,35985 ,19939,19938,19940 ,0,0,0}, + {35982,35985,35983 ,19937,19940,19938 ,0,0,0}, {35986,35987,35984 ,19941,19942,19939 ,0,0,0}, + {35984,35985,35986 ,19939,19940,19941 ,0,0,0}, {35987,35988,35989 ,19942,19943,19944 ,0,0,0}, + {35988,35987,35986 ,19943,19942,19941 ,0,0,0}, {35990,35989,35991 ,19945,19944,19946 ,0,0,0}, + {35988,35991,35989 ,19943,19946,19944 ,0,0,0}, {35992,35993,35990 ,19947,19948,19945 ,0,0,0}, + {35990,35991,35992 ,19945,19946,19947 ,0,0,0}, {35993,35994,35995 ,19948,19949,19950 ,0,0,0}, + {35994,35993,35992 ,19949,19948,19947 ,0,0,0}, {35996,35995,35997 ,19951,19950,19952 ,0,0,0}, + {35994,35997,35995 ,19949,19952,19950 ,0,0,0}, {35998,35999,35996 ,19953,19954,19951 ,0,0,0}, + {35996,35997,35998 ,19951,19952,19953 ,0,0,0}, {35999,36000,36001 ,19954,19955,19956 ,0,0,0}, + {36000,35999,35998 ,19955,19954,19953 ,0,0,0}, {36002,36001,36003 ,19957,19956,19958 ,0,0,0}, + {36000,36003,36001 ,19955,19958,19956 ,0,0,0}, {36004,36005,36002 ,19959,19960,19957 ,0,0,0}, + {36002,36003,36004 ,19957,19958,19959 ,0,0,0}, {36005,36006,36007 ,19960,19961,19962 ,0,0,0}, + {36006,36005,36004 ,19961,19960,19959 ,0,0,0}, {36008,36007,36009 ,19963,19962,19964 ,0,0,0}, + {36006,36009,36007 ,19961,19964,19962 ,0,0,0}, {36010,36011,36008 ,19965,19966,19963 ,0,0,0}, + {36008,36009,36010 ,19963,19964,19965 ,0,0,0}, {36012,36011,36010 ,19967,19966,19965 ,0,0,0}, + {36012,36013,36011 ,19967,19968,19966 ,0,0,0}, {35982,35981,36014 ,19937,19936,19969 ,0,0,0}, + {36015,36016,36014 ,19970,19971,19969 ,0,0,0}, {36014,35981,36015 ,19969,19936,19970 ,0,0,0}, + {36016,36017,36018 ,19971,19972,19973 ,0,0,0}, {36017,36016,36015 ,19972,19971,19970 ,0,0,0}, + {36019,36018,36020 ,19974,19973,19975 ,0,0,0}, {36017,36020,36018 ,19972,19975,19973 ,0,0,0}, + {36021,36022,36019 ,19976,19977,19974 ,0,0,0}, {36019,36020,36021 ,19974,19975,19976 ,0,0,0}, + {36022,36023,36024 ,19977,19978,19979 ,0,0,0}, {36023,36022,36021 ,19978,19977,19976 ,0,0,0}, + {36025,36024,36026 ,19980,19979,19981 ,0,0,0}, {36023,36026,36024 ,19978,19981,19979 ,0,0,0}, + {36027,36028,36025 ,19982,19983,19980 ,0,0,0}, {36025,36026,36027 ,19980,19981,19982 ,0,0,0}, + {36028,36029,36030 ,19983,19984,19985 ,0,0,0}, {36029,36028,36027 ,19984,19983,19982 ,0,0,0}, + {36031,36030,36032 ,19986,19985,19987 ,0,0,0}, {36029,36032,36030 ,19984,19987,19985 ,0,0,0}, + {36033,36034,36031 ,19988,19989,19986 ,0,0,0}, {36031,36032,36033 ,19986,19987,19988 ,0,0,0}, + {36034,36035,36036 ,19989,19990,19991 ,0,0,0}, {36035,36034,36033 ,19990,19989,19988 ,0,0,0}, + {36037,36036,36038 ,19992,19991,19993 ,0,0,0}, {36035,36038,36036 ,19990,19993,19991 ,0,0,0}, + {36039,36040,36037 ,19994,19995,19992 ,0,0,0}, {36037,36038,36039 ,19992,19993,19994 ,0,0,0}, + {36040,36041,36042 ,19995,19996,19997 ,0,0,0}, {36041,36040,36039 ,19996,19995,19994 ,0,0,0}, + {36041,36043,36042 ,19996,19998,19997 ,0,0,0}, {36042,36043,36044 ,19997,19998,19998 ,0,0,0}, + {36045,36046,36047 ,19999,20000,20001 ,0,0,0}, {36048,36047,36049 ,20002,20001,20003 ,0,0,0}, + {36046,36049,36047 ,20000,20003,20001 ,0,0,0}, {36050,36051,36048 ,20004,20005,20002 ,0,0,0}, + {36048,36049,36050 ,20002,20003,20004 ,0,0,0}, {36051,36052,36053 ,20005,20006,20007 ,0,0,0}, + {36052,36051,36050 ,20006,20005,20004 ,0,0,0}, {36054,36053,36055 ,20008,20007,20009 ,0,0,0}, + {36052,36055,36053 ,20006,20009,20007 ,0,0,0}, {36056,36057,36054 ,20010,20011,20008 ,0,0,0}, + {36054,36055,36056 ,20008,20009,20010 ,0,0,0}, {36057,36058,36059 ,20011,20012,20013 ,0,0,0}, + {36058,36057,36056 ,20012,20011,20010 ,0,0,0}, {36060,36059,36061 ,20014,20013,20015 ,0,0,0}, + {36058,36061,36059 ,20012,20015,20013 ,0,0,0}, {36062,36063,36060 ,20016,20017,20014 ,0,0,0}, + {36060,36061,36062 ,20014,20015,20016 ,0,0,0}, {36063,36064,36065 ,20017,20018,20019 ,0,0,0}, + {36064,36063,36062 ,20018,20017,20016 ,0,0,0}, {36066,36065,36067 ,20020,20019,20021 ,0,0,0}, + {36064,36067,36065 ,20018,20021,20019 ,0,0,0}, {36068,36069,36066 ,20022,20023,20020 ,0,0,0}, + {36066,36067,36068 ,20020,20021,20022 ,0,0,0}, {36069,36070,36071 ,20023,20024,20025 ,0,0,0}, + {36070,36069,36068 ,20024,20023,20022 ,0,0,0}, {36072,36071,36073 ,20026,20025,20027 ,0,0,0}, + {36070,36073,36071 ,20024,20027,20025 ,0,0,0}, {36074,36075,36072 ,20028,20029,20026 ,0,0,0}, + {36072,36073,36074 ,20026,20027,20028 ,0,0,0}, {36076,36075,36074 ,20030,20029,20028 ,0,0,0}, + {36076,36077,36075 ,20030,126,20029 ,0,0,0}, {36046,36045,36078 ,20000,19999,20031 ,0,0,0}, + {36079,36080,36078 ,20032,20033,20031 ,0,0,0}, {36078,36045,36079 ,20031,19999,20032 ,0,0,0}, + {36080,36081,36082 ,20033,20034,20035 ,0,0,0}, {36081,36080,36079 ,20034,20033,20032 ,0,0,0}, + {36083,36082,36084 ,20036,20035,20037 ,0,0,0}, {36081,36084,36082 ,20034,20037,20035 ,0,0,0}, + {36085,36086,36083 ,20038,20039,20036 ,0,0,0}, {36083,36084,36085 ,20036,20037,20038 ,0,0,0}, + {36086,36087,36088 ,20039,20040,20041 ,0,0,0}, {36087,36086,36085 ,20040,20039,20038 ,0,0,0}, + {36089,36088,36090 ,20042,20041,20043 ,0,0,0}, {36087,36090,36088 ,20040,20043,20041 ,0,0,0}, + {36091,36092,36089 ,20044,20045,20042 ,0,0,0}, {36089,36090,36091 ,20042,20043,20044 ,0,0,0}, + {36092,36093,36094 ,20045,20046,20047 ,0,0,0}, {36093,36092,36091 ,20046,20045,20044 ,0,0,0}, + {36095,36094,36096 ,20048,20047,20049 ,0,0,0}, {36093,36096,36094 ,20046,20049,20047 ,0,0,0}, + {36097,36098,36095 ,20050,20051,20048 ,0,0,0}, {36095,36096,36097 ,20048,20049,20050 ,0,0,0}, + {36098,36099,36100 ,20051,20052,20053 ,0,0,0}, {36099,36098,36097 ,20052,20051,20050 ,0,0,0}, + {36101,36100,36102 ,20054,20053,20055 ,0,0,0}, {36099,36102,36100 ,20052,20055,20053 ,0,0,0}, + {36103,36104,36101 ,20056,20057,20054 ,0,0,0}, {36101,36102,36103 ,20054,20055,20056 ,0,0,0}, + {36104,36105,36106 ,20057,20058,20059 ,0,0,0}, {36105,36104,36103 ,20058,20057,20056 ,0,0,0}, + {36105,36107,36106 ,20058,20060,20059 ,0,0,0}, {36106,36107,36108 ,20059,20060,20060 ,0,0,0}, + {36109,36110,36111 ,20061,20062,20063 ,0,0,0}, {36112,36111,36113 ,20064,20063,20065 ,0,0,0}, + {36110,36113,36111 ,20062,20065,20063 ,0,0,0}, {36114,36115,36112 ,20066,20067,20064 ,0,0,0}, + {36112,36113,36114 ,20064,20065,20066 ,0,0,0}, {36115,36116,36117 ,20067,20068,20069 ,0,0,0}, + {36116,36115,36114 ,20068,20067,20066 ,0,0,0}, {36118,36117,36119 ,20070,20069,20071 ,0,0,0}, + {36116,36119,36117 ,20068,20071,20069 ,0,0,0}, {36120,36121,36118 ,20072,20073,20070 ,0,0,0}, + {36118,36119,36120 ,20070,20071,20072 ,0,0,0}, {36121,36122,36123 ,20073,20074,20075 ,0,0,0}, + {36122,36121,36120 ,20074,20073,20072 ,0,0,0}, {36124,36123,36125 ,20076,20075,20077 ,0,0,0}, + {36122,36125,36123 ,20074,20077,20075 ,0,0,0}, {36126,36127,36124 ,20078,20079,20076 ,0,0,0}, + {36124,36125,36126 ,20076,20077,20078 ,0,0,0}, {36127,36128,36129 ,20079,20080,20081 ,0,0,0}, + {36128,36127,36126 ,20080,20079,20078 ,0,0,0}, {36130,36129,36131 ,20082,20081,20083 ,0,0,0}, + {36128,36131,36129 ,20080,20083,20081 ,0,0,0}, {36132,36133,36130 ,20084,20085,20082 ,0,0,0}, + {36130,36131,36132 ,20082,20083,20084 ,0,0,0}, {36133,36134,36135 ,20085,20086,20087 ,0,0,0}, + {36134,36133,36132 ,20086,20085,20084 ,0,0,0}, {36136,36135,36137 ,20088,20087,20089 ,0,0,0}, + {36134,36137,36135 ,20086,20089,20087 ,0,0,0}, {36138,36139,36136 ,20090,20091,20088 ,0,0,0}, + {36136,36137,36138 ,20088,20089,20090 ,0,0,0}, {36140,36139,36138 ,20092,20091,20090 ,0,0,0}, + {36140,36141,36139 ,20092,20093,20091 ,0,0,0}, {36110,36109,36142 ,20062,20061,20094 ,0,0,0}, + {36143,36144,36142 ,20095,20096,20094 ,0,0,0}, {36142,36109,36143 ,20094,20061,20095 ,0,0,0}, + {36144,36145,36146 ,20096,20097,20098 ,0,0,0}, {36145,36144,36143 ,20097,20096,20095 ,0,0,0}, + {36147,36146,36148 ,20099,20098,20100 ,0,0,0}, {36145,36148,36146 ,20097,20100,20098 ,0,0,0}, + {36149,36150,36147 ,20101,20102,20099 ,0,0,0}, {36147,36148,36149 ,20099,20100,20101 ,0,0,0}, + {36150,36151,36152 ,20102,20103,20104 ,0,0,0}, {36151,36150,36149 ,20103,20102,20101 ,0,0,0}, + {36153,36152,36154 ,20105,20104,20106 ,0,0,0}, {36151,36154,36152 ,20103,20106,20104 ,0,0,0}, + {36155,36156,36153 ,20107,20108,20105 ,0,0,0}, {36153,36154,36155 ,20105,20106,20107 ,0,0,0}, + {36156,36157,36158 ,20108,20109,20110 ,0,0,0}, {36157,36156,36155 ,20109,20108,20107 ,0,0,0}, + {36159,36158,36160 ,20111,20110,20112 ,0,0,0}, {36157,36160,36158 ,20109,20112,20110 ,0,0,0}, + {36161,36162,36159 ,20113,20114,20111 ,0,0,0}, {36159,36160,36161 ,20111,20112,20113 ,0,0,0}, + {36162,36163,36164 ,20114,20115,20116 ,0,0,0}, {36163,36162,36161 ,20115,20114,20113 ,0,0,0}, + {36165,36164,36166 ,20117,20116,20118 ,0,0,0}, {36163,36166,36164 ,20115,20118,20116 ,0,0,0}, + {36167,36168,36165 ,20119,20120,20117 ,0,0,0}, {36165,36166,36167 ,20117,20118,20119 ,0,0,0}, + {36168,36169,36170 ,20120,20121,20122 ,0,0,0}, {36169,36168,36167 ,20121,20120,20119 ,0,0,0}, + {36169,36171,36170 ,20121,20123,20122 ,0,0,0}, {36170,36171,36172 ,20122,20123,20123 ,0,0,0}, + {36173,35775,36174 ,726,726,20124 ,0,0,0}, {36175,36176,36177 ,727,726,20124 ,0,0,0}, + {36178,36179,36180 ,726,726,726 ,0,0,0}, {36181,35773,35775 ,726,20124,726 ,0,0,0}, + {36182,36183,36184 ,726,726,20124 ,0,0,0}, {35769,36181,35767 ,20124,726,726 ,0,0,0}, + {36181,35770,35773 ,726,726,20124 ,0,0,0}, {36185,36186,36187 ,726,726,726 ,0,0,0}, + {35750,35748,36181 ,726,20124,726 ,0,0,0}, {35764,35767,36181 ,726,726,726 ,0,0,0}, + {34562,36108,36188 ,726,726,726 ,0,0,0}, {36189,36190,34340 ,726,726,726 ,0,0,0}, + {36191,36192,36193 ,726,726,726 ,0,0,0}, {36194,36195,36196 ,726,726,726 ,0,0,0}, + {34084,34580,36197 ,728,726,726 ,0,0,0}, {35814,35815,36198 ,728,726,726 ,0,0,0}, + {35750,36181,36199 ,726,726,20124 ,0,0,0}, {36200,36201,36202 ,20124,20124,726 ,0,0,0}, + {35159,36194,35157 ,20124,726,726 ,0,0,0}, {36181,35748,35747 ,726,20124,726 ,0,0,0}, + {36203,35193,36204 ,726,20124,726 ,0,0,0}, {36205,36206,35131 ,20124,20124,20124 ,0,0,0}, + {36207,35300,36208 ,726,20124,20124 ,0,0,0}, {36209,35357,36210 ,726,727,726 ,0,0,0}, + {36211,36212,36210 ,20124,727,726 ,0,0,0}, {36213,35741,35743 ,726,1793,726 ,0,0,0}, + {36214,36215,36216 ,726,726,727 ,0,0,0}, {36216,36217,36214 ,727,727,726 ,0,0,0}, + {36216,36212,36217 ,727,727,727 ,0,0,0}, {36215,36192,36191 ,726,726,726 ,0,0,0}, + {36214,36192,36215 ,726,726,726 ,0,0,0}, {36191,36193,36218 ,726,726,727 ,0,0,0}, + {36219,36220,35940 ,20124,727,20124 ,0,0,0}, {36221,35946,35947 ,20124,20124,726 ,0,0,0}, + {36153,36156,36222 ,727,727,727 ,0,0,0}, {34936,36113,34937 ,727,727,726 ,0,0,0}, + {36110,34039,36113 ,726,726,727 ,0,0,0}, {34904,36223,34906 ,727,727,727 ,0,0,0}, + {36224,36225,36226 ,727,727,727 ,0,0,0}, {34221,36227,36228 ,726,726,20124 ,0,0,0}, + {36229,36134,36230 ,20124,727,726 ,0,0,0}, {34878,34212,36231 ,727,20124,20124 ,0,0,0}, + {34209,34212,34883 ,726,20124,726 ,0,0,0}, {36232,34868,34865 ,726,20124,20124 ,0,0,0}, + {34865,34864,36233 ,20124,726,20124 ,0,0,0}, {34856,36234,36235 ,20124,20124,20124 ,0,0,0}, + {36235,36236,34853 ,20124,727,20124 ,0,0,0}, {34877,36231,34861 ,727,20124,726 ,0,0,0}, + {36237,34850,34852 ,726,726,726 ,0,0,0}, {36238,36239,36240 ,20124,726,726 ,0,0,0}, + {35947,35952,36241 ,726,727,726 ,0,0,0}, {34846,36242,36243 ,727,20124,727 ,0,0,0}, + {36244,34568,34569 ,726,726,726 ,0,0,0}, {34543,36245,34541 ,726,726,729 ,0,0,0}, + {34945,34946,34139 ,20124,726,726 ,0,0,0}, {36246,36088,36247 ,726,726,728 ,0,0,0}, + {36248,34840,34128 ,20124,20124,726 ,0,0,0}, {34923,34939,36249 ,20124,726,726 ,0,0,0}, + {36250,36251,36252 ,726,726,726 ,0,0,0}, {35827,34176,34173 ,728,726,728 ,0,0,0}, + {34932,34930,36119 ,726,727,727 ,0,0,0}, {34044,36253,36254 ,726,727,727 ,0,0,0}, + {36255,36256,34260 ,726,726,726 ,0,0,0}, {36257,36258,34165 ,726,726,726 ,0,0,0}, + {36259,36260,35972 ,726,726,726 ,0,0,0}, {34934,34932,36116 ,727,726,727 ,0,0,0}, + {36261,36262,36256 ,726,726,726 ,0,0,0}, {36186,36185,36263 ,726,726,726 ,0,0,0}, + {34047,34046,36144 ,727,726,726 ,0,0,0}, {36113,34936,36114 ,727,727,727 ,0,0,0}, + {36061,36058,34482 ,726,726,726 ,0,0,0}, {34481,36056,34479 ,726,726,726 ,0,0,0}, + {36100,36101,34554 ,726,726,726 ,0,0,0}, {36259,35970,35969 ,726,726,20124 ,0,0,0}, + {34145,35963,34148 ,20124,726,726 ,0,0,0}, {35937,36264,35938 ,20124,20124,726 ,0,0,0}, + {36153,36222,36265 ,727,727,727 ,0,0,0}, {34058,36266,34902 ,726,726,726 ,0,0,0}, + {36114,34934,36116 ,727,727,727 ,0,0,0}, {36116,34932,36119 ,727,726,727 ,0,0,0}, + {36267,34907,36223 ,726,726,727 ,0,0,0}, {35978,35976,36268 ,726,726,726 ,0,0,0}, + {34838,34128,34840 ,20124,726,20124 ,0,0,0}, {36122,36120,34927 ,727,20124,726 ,0,0,0}, + {34044,36254,36269 ,726,727,727 ,0,0,0}, {34906,36223,34907 ,727,727,726 ,0,0,0}, + {34041,34044,36269 ,726,726,727 ,0,0,0}, {36270,34923,36249 ,20124,20124,726 ,0,0,0}, + {36126,36125,34926 ,727,726,20124 ,0,0,0}, {36170,36172,36271 ,727,727,727 ,0,0,0}, + {34053,34908,34909 ,726,726,726 ,0,0,0}, {36128,36270,36131 ,726,20124,726 ,0,0,0}, + {34923,36270,34924 ,20124,20124,20124 ,0,0,0}, {34912,34914,36272 ,726,20124,20124 ,0,0,0}, + {36273,36274,34060 ,727,727,726 ,0,0,0}, {35345,36275,35349 ,726,727,727 ,0,0,0}, + {36221,36276,36277 ,20124,727,726 ,0,0,0}, {36278,34130,36279 ,726,20124,20124 ,0,0,0}, + {36138,36280,36281 ,20124,727,20124 ,0,0,0}, {36239,36238,36282 ,726,20124,727 ,0,0,0}, + {34229,35959,34232 ,726,20124,726 ,0,0,0}, {36283,36284,34868 ,726,726,20124 ,0,0,0}, + {36285,36286,34847 ,20124,20124,727 ,0,0,0}, {36287,36282,36238 ,20124,727,20124 ,0,0,0}, + {34308,34875,34874 ,726,727,726 ,0,0,0}, {35105,36288,36289 ,727,727,727 ,0,0,0}, + {34316,36290,36291 ,20124,726,726 ,0,0,0}, {36218,36292,36293 ,727,727,727 ,0,0,0}, + {36284,34870,34868 ,726,20124,20124 ,0,0,0}, {35071,36294,36295 ,20124,727,727 ,0,0,0}, + {36296,36297,36298 ,726,727,20124 ,0,0,0}, {36299,36300,36301 ,727,20124,726 ,0,0,0}, + {36302,36303,34296 ,726,726,726 ,0,0,0}, {35075,36304,36305 ,726,727,20124 ,0,0,0}, + {36306,36307,36308 ,727,726,726 ,0,0,0}, {36309,36310,36308 ,20124,20124,726 ,0,0,0}, + {36311,35083,36299 ,727,727,727 ,0,0,0}, {36306,36312,36307 ,727,20124,726 ,0,0,0}, + {36301,36311,36299 ,726,727,727 ,0,0,0}, {36289,36313,36312 ,727,726,20124 ,0,0,0}, + {36304,36310,36305 ,727,20124,20124 ,0,0,0}, {36289,36288,36292 ,727,727,727 ,0,0,0}, + {36193,36292,36218 ,726,727,727 ,0,0,0}, {36210,36206,36211 ,726,20124,20124 ,0,0,0}, + {36212,36211,36217 ,727,20124,727 ,0,0,0}, {35339,35341,36314 ,727,726,726 ,0,0,0}, + {36315,35716,36316 ,1793,1793,1793 ,0,0,0}, {36213,36317,35735 ,726,1793,1793 ,0,0,0}, + {35394,36213,35743 ,726,726,726 ,0,0,0}, {36318,36319,36320 ,1792,1793,727 ,0,0,0}, + {35379,35223,35380 ,726,20124,726 ,0,0,0}, {35216,35372,35374 ,726,20124,727 ,0,0,0}, + {36321,36322,35728 ,1793,1793,1793 ,0,0,0}, {35729,35728,36322 ,726,1793,1793 ,0,0,0}, + {36322,36323,35729 ,1793,1793,726 ,0,0,0}, {35726,36321,35728 ,1793,1793,1793 ,0,0,0}, + {36324,36325,36326 ,1793,1793,1792 ,0,0,0}, {35724,36321,35726 ,726,1793,1793 ,0,0,0}, + {36327,36328,36329 ,726,727,1793 ,0,0,0}, {36321,35724,36330 ,1793,726,1793 ,0,0,0}, + {36331,36332,36333 ,1793,1793,726 ,0,0,0}, {36330,35722,35719 ,1793,1793,1793 ,0,0,0}, + {36334,36327,36335 ,1793,726,726 ,0,0,0}, {35718,36336,35719 ,727,726,1793 ,0,0,0}, + {35425,36337,35428 ,726,726,1793 ,0,0,0}, {35425,35423,36337 ,726,1793,726 ,0,0,0}, + {36338,36339,36340 ,20124,727,727 ,0,0,0}, {35210,35207,35369 ,726,726,726 ,0,0,0}, + {36341,35519,35517 ,726,726,726 ,0,0,0}, {36342,36343,36344 ,726,1792,727 ,0,0,0}, + {36345,36346,36347 ,727,1792,727 ,0,0,0}, {36332,36331,36343 ,1793,1793,1792 ,0,0,0}, + {36332,36343,36342 ,1793,1792,726 ,0,0,0}, {36348,36333,36349 ,1793,726,1793 ,0,0,0}, + {36333,36348,36331 ,726,1793,1793 ,0,0,0}, {36350,36351,34394 ,20125,20126,1792 ,0,0,0}, + {36348,36349,36352 ,1793,1793,1792 ,0,0,0}, {36353,36354,36355 ,20127,20128,20129 ,0,0,0}, + {34424,36356,36357 ,20130,20131,20132 ,0,0,0}, {34718,36358,34720 ,20133,20134,20135 ,0,0,0}, + {34417,34723,34724 ,1793,20136,1793 ,0,0,0}, {35934,35932,36359 ,20137,1793,20136 ,0,0,0}, + {34408,36360,36361 ,20126,20138,20128 ,0,0,0}, {35896,36362,36363 ,20137,20139,20140 ,0,0,0}, + {36364,36365,36366 ,20141,20142,20143 ,0,0,0}, {35926,35925,36367 ,20137,1792,20133 ,0,0,0}, + {36368,34814,34812 ,20144,20135,20133 ,0,0,0}, {34410,36369,34411 ,1793,20145,20146 ,0,0,0}, + {35919,34456,34453 ,20147,20148,20137 ,0,0,0}, {34410,34403,36370 ,1793,20143,20149 ,0,0,0}, + {34815,34814,36371 ,20127,20135,20150 ,0,0,0}, {36372,36373,36374 ,20131,20151,20152 ,0,0,0}, + {34456,35919,35894 ,20148,20147,726 ,0,0,0}, {34814,36375,36371 ,20135,20153,20150 ,0,0,0}, + {36376,36377,36378 ,20154,20155,20156 ,0,0,0}, {36379,36380,36381 ,20157,20158,20159 ,0,0,0}, + {35928,36367,36382 ,727,20133,20136 ,0,0,0}, {34812,36383,36368 ,20133,20160,20144 ,0,0,0}, + {34812,34810,36383 ,20133,20127,20160 ,0,0,0}, {34721,36366,36365 ,20127,20143,20142 ,0,0,0}, + {36384,36385,36386 ,1793,1792,20161 ,0,0,0}, {36383,34810,36387 ,20160,20127,20148 ,0,0,0}, + {36387,34808,36388 ,20148,20126,20162 ,0,0,0}, {34436,34778,34776 ,1792,20137,20126 ,0,0,0}, + {35903,36389,35902 ,20162,20137,726 ,0,0,0}, {36390,36360,34408 ,20137,20138,20126 ,0,0,0}, + {36361,34405,34408 ,20128,20131,20126 ,0,0,0}, {36391,34805,34804 ,20163,20135,20164 ,0,0,0}, + {34436,36392,34778 ,1792,20124,20137 ,0,0,0}, {34720,36358,34721 ,20135,20134,20127 ,0,0,0}, + {36393,36394,34802 ,20124,20133,1792 ,0,0,0}, {34817,36395,34816 ,1793,20140,20136 ,0,0,0}, + {36396,34802,34801 ,20165,1792,726 ,0,0,0}, {36397,36398,36399 ,20132,20137,20166 ,0,0,0}, + {36400,36401,36402 ,20167,20137,20138 ,0,0,0}, {36403,36404,34386 ,20134,20165,20161 ,0,0,0}, + {36405,36406,36407 ,20167,20167,20126 ,0,0,0}, {34822,34823,34447 ,20131,20139,20134 ,0,0,0}, + {36408,34377,36409 ,20136,20136,20133 ,0,0,0}, {36356,34724,34727 ,20131,1793,1792 ,0,0,0}, + {36410,36411,36412 ,20168,1792,20139 ,0,0,0}, {34733,36413,36414 ,20165,1792,20133 ,0,0,0}, + {36415,36416,36417 ,20169,20128,20168 ,0,0,0}, {36418,36419,36420 ,20137,20167,20137 ,0,0,0}, + {36421,36422,36423 ,20147,20170,20139 ,0,0,0}, {34742,34740,36424 ,20124,1792,20137 ,0,0,0}, + {35779,36425,35786 ,1793,20139,1793 ,0,0,0}, {34740,36426,36424 ,1792,20162,20137 ,0,0,0}, + {34748,34746,36427 ,20137,20126,20139 ,0,0,0}, {36428,36429,36430 ,20140,726,1793 ,0,0,0}, + {36431,36427,34746 ,1793,20139,20126 ,0,0,0}, {36432,36433,36434 ,20137,20140,20139 ,0,0,0}, + {34397,36435,34400 ,20168,20125,20140 ,0,0,0}, {35782,34764,34766 ,20137,20137,20170 ,0,0,0}, + {34764,35782,34761 ,20137,20137,727 ,0,0,0}, {34769,36436,36437 ,726,1793,20130 ,0,0,0}, + {36438,36439,35914 ,20125,20125,20167 ,0,0,0}, {36440,36441,36442 ,20124,20147,1793 ,0,0,0}, + {36443,36352,36349 ,1792,1792,1793 ,0,0,0}, {36443,34995,36352 ,1792,20130,1792 ,0,0,0}, + {36444,35903,35908 ,20126,20162,20139 ,0,0,0}, {36445,34797,36446 ,20170,20170,1793 ,0,0,0}, + {34789,34791,36447 ,20125,20147,20130 ,0,0,0}, {36448,36449,35061 ,20140,20140,726 ,0,0,0}, + {36450,35790,35053 ,20140,20147,20140 ,0,0,0}, {36432,36451,36452 ,20137,20168,1793 ,0,0,0}, + {34792,34795,36453 ,727,20137,20124 ,0,0,0}, {36454,35046,36455 ,20167,1792,727 ,0,0,0}, + {36456,35049,36457 ,20147,1793,726 ,0,0,0}, {36448,36458,36459 ,20140,20130,20124 ,0,0,0}, + {36448,36459,36460 ,20140,20124,1792 ,0,0,0}, {35061,36458,36448 ,726,20130,20140 ,0,0,0}, + {35043,36461,36455 ,1793,726,727 ,0,0,0}, {36462,35055,35058 ,20167,1792,20140 ,0,0,0}, + {36463,36448,36464 ,1793,20140,20148 ,0,0,0}, {36344,36346,36465 ,727,1792,1793 ,0,0,0}, + {36344,36465,36342 ,727,1793,726 ,0,0,0}, {35517,36466,36341 ,726,1793,726 ,0,0,0}, + {36346,36345,36465 ,1792,727,1793 ,0,0,0}, {36467,35605,36468 ,20124,726,1793 ,0,0,0}, + {35522,35519,36341 ,1793,726,726 ,0,0,0}, {36469,36470,36471 ,726,726,1793 ,0,0,0}, + {36472,36473,36474 ,726,726,726 ,0,0,0}, {35207,35206,35362 ,726,726,727 ,0,0,0}, + {36475,36476,36477 ,727,726,726 ,0,0,0}, {36475,36478,36476 ,727,727,726 ,0,0,0}, + {35496,36479,35499 ,1793,726,1793 ,0,0,0}, {36480,36478,36481 ,727,727,726 ,0,0,0}, + {36482,36483,36484 ,1792,726,1793 ,0,0,0}, {35696,36485,36486 ,1793,1793,1793 ,0,0,0}, + {36487,35697,36486 ,727,726,1793 ,0,0,0}, {35696,36486,35697 ,1793,1793,726 ,0,0,0}, + {36488,36489,36490 ,1793,727,1793 ,0,0,0}, {36491,36492,36493 ,727,1793,1792 ,0,0,0}, + {36494,36495,36496 ,726,726,726 ,0,0,0}, {36497,36469,36498 ,726,726,726 ,0,0,0}, + {36499,36489,36500 ,1792,727,727 ,0,0,0}, {36497,36501,36502 ,726,727,727 ,0,0,0}, + {35694,36485,35696 ,1793,1793,1793 ,0,0,0}, {36503,36504,36505 ,727,726,727 ,0,0,0}, + {35692,36506,35694 ,726,1793,1793 ,0,0,0}, {35490,36507,36508 ,1793,726,1792 ,0,0,0}, + {35630,35628,36509 ,726,726,20124 ,0,0,0}, {36510,36511,35634 ,726,726,726 ,0,0,0}, + {36512,36513,36514 ,20124,726,726 ,0,0,0}, {36515,36516,36517 ,727,726,726 ,0,0,0}, + {36518,36519,36520 ,727,726,726 ,0,0,0}, {36521,36522,36523 ,726,727,726 ,0,0,0}, + {36523,36516,36521 ,726,726,726 ,0,0,0}, {36524,36522,36525 ,726,727,727 ,0,0,0}, + {36522,36524,36523 ,727,726,726 ,0,0,0}, {36526,36527,36525 ,727,726,727 ,0,0,0}, + {36524,36525,36527 ,726,727,726 ,0,0,0}, {36528,36527,36526 ,727,726,727 ,0,0,0}, + {36529,34686,34352 ,20124,20124,726 ,0,0,0}, {34649,34648,36530 ,20124,726,20124 ,0,0,0}, + {34114,36531,36532 ,20124,726,727 ,0,0,0}, {36533,36534,34200 ,726,726,726 ,0,0,0}, + {34692,36535,34677 ,727,727,726 ,0,0,0}, {34201,36536,34204 ,726,726,20124 ,0,0,0}, + {36537,36010,36538 ,20124,726,727 ,0,0,0}, {35888,36539,35890 ,726,726,726 ,0,0,0}, + {36540,36541,34268 ,727,727,726 ,0,0,0}, {35882,35881,36542 ,726,20124,726 ,0,0,0}, + {36543,36544,36545 ,727,726,727 ,0,0,0}, {36546,35884,36542 ,726,726,726 ,0,0,0}, + {34627,34266,36547 ,726,727,727 ,0,0,0}, {36548,36549,36550 ,727,727,727 ,0,0,0}, + {34597,36551,36552 ,726,726,726 ,0,0,0}, {34594,36553,36554 ,727,727,727 ,0,0,0}, + {36555,36552,36551 ,727,726,726 ,0,0,0}, {34182,36556,36557 ,20124,20124,727 ,0,0,0}, + {36558,36559,36560 ,727,727,727 ,0,0,0}, {36561,36003,36000 ,726,727,20124 ,0,0,0}, + {36562,34622,34620 ,727,726,727 ,0,0,0}, {36563,35991,35988 ,726,726,726 ,0,0,0}, + {36561,36564,36565 ,726,20124,726 ,0,0,0}, {36040,34702,36037 ,727,20124,726 ,0,0,0}, + {36530,34646,36566 ,20124,726,20124 ,0,0,0}, {36028,36567,36025 ,20124,20124,726 ,0,0,0}, + {36568,36024,36025 ,726,727,726 ,0,0,0}, {34652,36569,36533 ,20124,726,726 ,0,0,0}, + {34654,34652,36533 ,20124,20124,726 ,0,0,0}, {34097,34667,34668 ,726,726,20124 ,0,0,0}, + {36570,36571,36572 ,726,20124,726 ,0,0,0}, {36572,36571,34704 ,726,20124,726 ,0,0,0}, + {36019,34103,36018 ,20124,726,20124 ,0,0,0}, {36573,34200,36534 ,726,726,726 ,0,0,0}, + {35985,34673,36574 ,726,726,726 ,0,0,0}, {34699,36042,34698 ,20124,20124,726 ,0,0,0}, + {34696,36044,36575 ,726,20124,20124 ,0,0,0}, {36576,36577,36578 ,20124,726,20124 ,0,0,0}, + {36536,36577,34204 ,726,726,20124 ,0,0,0}, {36579,34109,36580 ,20124,726,726 ,0,0,0}, + {36581,36582,36583 ,20124,727,726 ,0,0,0}, {36584,35998,36585 ,727,20124,726 ,0,0,0}, + {36586,34610,36587 ,727,726,726 ,0,0,0}, {34117,35871,34120 ,726,20124,726 ,0,0,0}, + {36588,36589,36590 ,726,20124,727 ,0,0,0}, {36561,36000,36584 ,726,20124,727 ,0,0,0}, + {36591,36592,36593 ,20124,727,20124 ,0,0,0}, {36594,36595,36596 ,726,726,726 ,0,0,0}, + {34195,36597,34196 ,20124,726,726 ,0,0,0}, {34495,36598,34498 ,728,726,726 ,0,0,0}, + {34190,36599,36600 ,727,726,726 ,0,0,0}, {36601,36602,34284 ,727,727,726 ,0,0,0}, + {34599,34277,34598 ,726,726,726 ,0,0,0}, {36603,34288,34285 ,726,20124,726 ,0,0,0}, + {36541,34265,34268 ,727,726,726 ,0,0,0}, {36554,34596,34594 ,727,727,727 ,0,0,0}, + {36604,36540,34268 ,727,727,726 ,0,0,0}, {34641,36605,34364 ,726,726,20124 ,0,0,0}, + {36606,34270,36607 ,726,726,20124 ,0,0,0}, {35875,34372,34369 ,726,726,20124 ,0,0,0}, + {36608,35005,36609 ,726,20124,727 ,0,0,0}, {34627,36610,36611 ,726,726,727 ,0,0,0}, + {34684,34349,34352 ,20124,726,726 ,0,0,0}, {35249,35245,36612 ,726,726,20124 ,0,0,0}, + {36610,34627,34626 ,726,726,727 ,0,0,0}, {36613,36610,34626 ,727,726,727 ,0,0,0}, + {35481,35328,35325 ,727,727,726 ,0,0,0}, {35009,36608,36614 ,726,726,20124 ,0,0,0}, + {36615,36616,36596 ,727,20124,726 ,0,0,0}, {36615,36596,36617 ,727,726,726 ,0,0,0}, + {36617,35017,36615 ,726,727,727 ,0,0,0}, {36589,35858,35859 ,20124,20124,726 ,0,0,0}, + {34998,35011,36618 ,727,726,726 ,0,0,0}, {34635,34366,34633 ,20124,726,726 ,0,0,0}, + {36619,35001,34999 ,727,726,20124 ,0,0,0}, {36620,36592,36591 ,727,727,20124 ,0,0,0}, + {36621,36609,35008 ,727,727,726 ,0,0,0}, {36614,36620,36622 ,20124,727,20124 ,0,0,0}, + {36623,36624,36625 ,727,726,726 ,0,0,0}, {36521,36516,36515 ,726,726,727 ,0,0,0}, + {36515,36517,36626 ,727,726,20124 ,0,0,0}, {36627,36628,36626 ,20124,726,20124 ,0,0,0}, + {36626,36517,36627 ,20124,726,20124 ,0,0,0}, {36629,35628,35625 ,726,726,20124 ,0,0,0}, + {35630,36630,35632 ,726,726,726 ,0,0,0}, {35479,35481,35325 ,726,727,726 ,0,0,0}, + {35296,35294,36631 ,726,20124,726 ,0,0,0}, {36632,35293,36633 ,726,20124,20124 ,0,0,0}, + {36634,36635,36636 ,20124,726,20124 ,0,0,0}, {35243,36637,36638 ,726,727,726 ,0,0,0}, + {36639,36640,36641 ,20124,726,726 ,0,0,0}, {36642,36643,35677 ,726,727,20124 ,0,0,0}, + {36643,36644,35674 ,727,726,726 ,0,0,0}, {36644,36645,35673 ,726,726,726 ,0,0,0}, + {36646,35679,36647 ,726,726,726 ,0,0,0}, {36645,35668,35671 ,726,726,20124 ,0,0,0}, + {36648,36647,36649 ,726,726,726 ,0,0,0}, {36650,36651,36652 ,726,20124,726 ,0,0,0}, + {36645,35651,35667 ,726,726,726 ,0,0,0}, {36653,36654,35276 ,726,20124,726 ,0,0,0}, + {36655,36656,36657 ,726,20124,726 ,0,0,0}, {36658,36659,36653 ,726,20124,726 ,0,0,0}, + {36660,36661,36662 ,726,727,726 ,0,0,0}, {36663,35250,36664 ,726,726,726 ,0,0,0}, + {36182,36195,35176 ,726,726,726 ,0,0,0}, {35181,36182,35179 ,20124,726,20124 ,0,0,0}, + {36665,36666,36513 ,20124,726,726 ,0,0,0}, {36636,36667,36668 ,20124,20124,726 ,0,0,0}, + {36669,36670,36671 ,20124,727,726 ,0,0,0}, {36672,36673,36670 ,726,20124,727 ,0,0,0}, + {36179,36674,36180 ,726,727,726 ,0,0,0}, {36675,36179,36178 ,20124,726,726 ,0,0,0}, + {36676,36677,36674 ,20124,20124,727 ,0,0,0}, {36180,36674,36677 ,726,727,20124 ,0,0,0}, + {36678,36679,36680 ,729,726,726 ,0,0,0}, {35806,34092,35831 ,728,726,726 ,0,0,0}, + {34964,34958,36681 ,726,729,20124 ,0,0,0}, {34156,34512,34153 ,726,726,726 ,0,0,0}, + {34506,36682,34491 ,726,726,726 ,0,0,0}, {34507,34510,34156 ,726,726,726 ,0,0,0}, + {36683,36073,36684 ,726,726,726 ,0,0,0}, {36685,36064,34487 ,726,726,728 ,0,0,0}, + {36686,34498,36687 ,726,726,726 ,0,0,0}, {34498,36686,34500 ,726,726,726 ,0,0,0}, + {36062,36061,34485 ,726,726,726 ,0,0,0}, {34256,36686,36688 ,726,726,726 ,0,0,0}, + {36689,34158,36690 ,726,726,729 ,0,0,0}, {36688,36691,34256 ,726,726,726 ,0,0,0}, + {34257,36691,36255 ,726,726,726 ,0,0,0}, {34260,34257,36255 ,726,726,726 ,0,0,0}, + {36055,36052,34476 ,726,726,726 ,0,0,0}, {36692,36693,36694 ,729,726,726 ,0,0,0}, + {36695,36696,36697 ,726,726,728 ,0,0,0}, {36698,36699,36700 ,726,729,728 ,0,0,0}, + {36049,36046,34067 ,726,726,728 ,0,0,0}, {35820,36701,35815 ,726,726,726 ,0,0,0}, + {35818,36258,36702 ,726,726,726 ,0,0,0}, {36703,36704,36198 ,726,726,726 ,0,0,0}, + {34070,34462,34460 ,726,726,726 ,0,0,0}, {36705,36706,36707 ,726,726,726 ,0,0,0}, + {36708,34238,36709 ,726,726,726 ,0,0,0}, {34556,36104,34557 ,726,726,726 ,0,0,0}, + {34463,34069,34466 ,728,726,726 ,0,0,0}, {36108,34560,36106 ,726,728,726 ,0,0,0}, + {36710,34468,34072 ,726,726,726 ,0,0,0}, {34566,36188,36711 ,726,726,726 ,0,0,0}, + {34562,36188,34564 ,726,726,726 ,0,0,0}, {35838,35837,36712 ,726,726,726 ,0,0,0}, + {36713,34327,36714 ,726,726,726 ,0,0,0}, {36715,35808,36716 ,726,728,726 ,0,0,0}, + {34566,36711,34567 ,726,726,726 ,0,0,0}, {34072,34468,34466 ,726,726,726 ,0,0,0}, + {36188,34566,34564 ,726,726,726 ,0,0,0}, {36717,35848,34344 ,726,726,726 ,0,0,0}, + {35840,36712,36718 ,726,726,726 ,0,0,0}, {34341,36719,36717 ,726,726,726 ,0,0,0}, + {36720,36721,36722 ,726,726,728 ,0,0,0}, {34338,34530,34528 ,726,726,728 ,0,0,0}, + {34532,36723,36724 ,726,726,726 ,0,0,0}, {36725,36726,34324 ,726,726,726 ,0,0,0}, + {36727,36728,36729 ,726,726,726 ,0,0,0}, {36730,34535,36731 ,726,726,726 ,0,0,0}, + {36724,34535,34534 ,726,726,726 ,0,0,0}, {34970,36732,34967 ,726,726,726 ,0,0,0}, + {36733,36720,36734 ,726,726,726 ,0,0,0}, {36735,36678,36736 ,726,729,728 ,0,0,0}, + {36678,36737,36736 ,729,726,728 ,0,0,0}, {34965,36738,36739 ,726,20124,726 ,0,0,0}, + {36676,36740,36741 ,20124,726,20124 ,0,0,0}, {36738,36740,36676 ,20124,726,20124 ,0,0,0}, + {36675,36178,36669 ,20124,726,20124 ,0,0,0}, {36670,36673,36671 ,727,20124,726 ,0,0,0}, + {36669,36671,36675 ,20124,726,20124 ,0,0,0}, {36672,36742,36673 ,726,727,20124 ,0,0,0}, + {36665,36743,36744 ,20124,726,726 ,0,0,0}, {36672,36745,36742 ,726,727,727 ,0,0,0}, + {36746,36668,36667 ,20124,726,20124 ,0,0,0}, {36747,35237,36748 ,726,726,727 ,0,0,0}, + {36182,35181,36749 ,726,20124,20124 ,0,0,0}, {35350,35353,36750 ,727,726,727 ,0,0,0}, + {35754,35580,35582 ,726,20124,20124 ,0,0,0}, {36202,36751,36752 ,726,726,726 ,0,0,0}, + {35169,36195,35162 ,727,726,726 ,0,0,0}, {35345,35344,36753 ,726,726,726 ,0,0,0}, + {36195,35169,35168 ,726,727,20124 ,0,0,0}, {35332,35337,36754 ,726,726,726 ,0,0,0}, + {36755,35384,35383 ,726,726,726 ,0,0,0}, {35552,35553,36756 ,726,726,727 ,0,0,0}, + {36209,36750,35353 ,726,727,726 ,0,0,0}, {35131,36206,35206 ,20124,20124,726 ,0,0,0}, + {35205,35202,36205 ,726,20124,20124 ,0,0,0}, {35205,36205,35131 ,726,20124,20124 ,0,0,0}, + {36757,35202,35200 ,20124,20124,20124 ,0,0,0}, {35202,36757,36205 ,20124,20124,20124 ,0,0,0}, + {35199,36758,35200 ,726,726,20124 ,0,0,0}, {36757,35200,36758 ,20124,20124,726 ,0,0,0}, + {35575,36758,35196 ,727,726,726 ,0,0,0}, {36758,35199,35196 ,726,726,726 ,0,0,0}, + {36758,35575,36759 ,726,727,726 ,0,0,0}, {35196,35194,36760 ,726,20124,726 ,0,0,0}, + {35575,35574,36759 ,727,726,726 ,0,0,0}, {35188,36761,35190 ,726,726,726 ,0,0,0}, + {36762,35184,36763 ,20124,20124,726 ,0,0,0}, {35187,36764,36765 ,726,726,20124 ,0,0,0}, + {35132,35137,36766 ,726,726,20124 ,0,0,0}, {36767,36768,35136 ,726,20124,726 ,0,0,0}, + {36769,35139,36770 ,726,20124,20124 ,0,0,0}, {36770,35139,36771 ,20124,20124,726 ,0,0,0}, + {35582,35583,35756 ,20124,20124,726 ,0,0,0}, {36772,35149,36773 ,20124,726,726 ,0,0,0}, + {35141,35143,36774 ,726,726,726 ,0,0,0}, {35150,36775,36776 ,726,20124,727 ,0,0,0}, + {35145,36777,36778 ,726,726,20124 ,0,0,0}, {36779,36780,35155 ,726,726,726 ,0,0,0}, + {35155,36780,35153 ,726,726,20124 ,0,0,0}, {36181,35763,35764 ,726,726,726 ,0,0,0}, + {35157,36194,36779 ,726,726,726 ,0,0,0}, {36202,36781,35775 ,726,726,726 ,0,0,0}, + {36174,35775,36781 ,20124,726,726 ,0,0,0}, {36201,36782,36202 ,20124,20124,726 ,0,0,0}, + {35159,35162,36195 ,20124,726,726 ,0,0,0}, {35172,36195,35167 ,20124,726,727 ,0,0,0}, + {36195,35168,35167 ,726,20124,727 ,0,0,0}, {35176,36195,35174 ,726,726,727 ,0,0,0}, + {36195,35172,35174 ,726,20124,727 ,0,0,0}, {36182,35176,35163 ,726,726,726 ,0,0,0}, + {35179,36182,35180 ,20124,726,726 ,0,0,0}, {36182,35163,35180 ,726,726,726 ,0,0,0}, + {36182,36749,36183 ,726,20124,726 ,0,0,0}, {36182,36184,36783 ,726,20124,20124 ,0,0,0}, + {36746,36667,36182 ,20124,20124,726 ,0,0,0}, {36182,36783,36746 ,726,20124,20124 ,0,0,0}, + {36636,36635,36743 ,20124,726,726 ,0,0,0}, {36634,36636,36668 ,20124,20124,726 ,0,0,0}, + {36665,36744,36666 ,20124,726,726 ,0,0,0}, {36743,36635,36744 ,726,726,726 ,0,0,0}, + {36514,36784,36512 ,726,726,20124 ,0,0,0}, {36513,36512,36665 ,726,20124,20124 ,0,0,0}, + {36784,36664,35253 ,726,726,20124 ,0,0,0}, {36512,36784,36745 ,20124,726,727 ,0,0,0}, + {35244,36663,36785 ,726,726,726 ,0,0,0}, {36786,36748,35239 ,726,727,20124 ,0,0,0}, + {35243,36638,35241 ,726,726,726 ,0,0,0}, {35232,35237,36747 ,726,726,726 ,0,0,0}, + {35236,36787,35283 ,726,20124,20124 ,0,0,0}, {36788,36633,35290 ,726,20124,726 ,0,0,0}, + {35284,36789,35287 ,20124,726,726 ,0,0,0}, {36631,35294,36632 ,726,20124,726 ,0,0,0}, + {35255,36784,35253 ,726,726,20124 ,0,0,0}, {35307,35462,35469 ,726,727,726 ,0,0,0}, + {35443,35449,36790 ,726,727,726 ,0,0,0}, {36791,35654,35652 ,726,726,726 ,0,0,0}, + {36792,36793,36794 ,20124,20124,726 ,0,0,0}, {36795,36790,35449 ,727,726,727 ,0,0,0}, + {36796,35616,36797 ,726,727,727 ,0,0,0}, {36798,36799,36800 ,726,726,726 ,0,0,0}, + {35437,36801,35432 ,726,727,726 ,0,0,0}, {36802,36803,35635 ,726,726,727 ,0,0,0}, + {36790,36804,35443 ,726,727,726 ,0,0,0}, {36805,35450,35453 ,726,727,726 ,0,0,0}, + {35449,35445,36795 ,727,726,727 ,0,0,0}, {36478,36475,36481 ,727,727,726 ,0,0,0}, + {36476,36806,36477 ,726,727,726 ,0,0,0}, {36177,36807,36808 ,20124,726,727 ,0,0,0}, + {36480,36176,36175 ,727,726,727 ,0,0,0}, {36807,36809,36810 ,726,726,726 ,0,0,0}, + {36809,36811,36810 ,726,727,726 ,0,0,0}, {35225,35381,35228 ,726,727,727 ,0,0,0}, + {36812,36813,36814 ,727,726,20124 ,0,0,0}, {35516,36815,36466 ,726,1792,1793 ,0,0,0}, + {35632,36510,35634 ,726,726,726 ,0,0,0}, {35374,35217,35216 ,727,726,726 ,0,0,0}, + {35363,35219,35376 ,726,726,20124 ,0,0,0}, {35213,35372,35216 ,726,20124,726 ,0,0,0}, + {36816,35507,35506 ,1793,1793,1792 ,0,0,0}, {35211,35367,35213 ,726,727,726 ,0,0,0}, + {36817,36818,36819 ,1793,1793,727 ,0,0,0}, {35368,35367,35211 ,726,727,726 ,0,0,0}, + {35369,35368,35210 ,726,726,726 ,0,0,0}, {35422,36337,35423 ,1793,726,1793 ,0,0,0}, + {35217,35376,35219 ,726,20124,726 ,0,0,0}, {36337,35419,36327 ,726,726,726 ,0,0,0}, + {35419,36337,35422 ,726,726,1793 ,0,0,0}, {36327,35417,35416 ,726,726,726 ,0,0,0}, + {35419,35417,36327 ,726,726,726 ,0,0,0}, {36820,35410,35407 ,727,1793,1793 ,0,0,0}, + {35416,35413,36327 ,726,727,726 ,0,0,0}, {36821,35402,36822 ,727,1793,727 ,0,0,0}, + {36823,35331,35405 ,1793,726,1793 ,0,0,0}, {35399,36824,35400 ,1793,726,1793 ,0,0,0}, + {36824,36822,35400 ,726,727,1793 ,0,0,0}, {35394,35743,35396 ,726,726,1793 ,0,0,0}, + {35359,35362,35206 ,726,727,726 ,0,0,0}, {35732,36825,35731 ,726,1792,1792 ,0,0,0}, + {35393,35545,35544 ,726,726,727 ,0,0,0}, {35390,35388,36826 ,1793,726,20124 ,0,0,0}, + {35393,35390,35545 ,726,1793,726 ,0,0,0}, {36210,35359,36206 ,726,726,20124 ,0,0,0}, + {35387,36827,36828 ,1793,727,727 ,0,0,0}, {35355,35357,36209 ,726,727,726 ,0,0,0}, + {36829,36830,35336 ,726,727,20124 ,0,0,0}, {35343,36831,36832 ,726,726,726 ,0,0,0}, + {35341,35343,36832 ,726,726,726 ,0,0,0}, {35355,36209,35353 ,726,726,726 ,0,0,0}, + {35535,36213,35538 ,726,726,727 ,0,0,0}, {35349,36275,36831 ,727,727,726 ,0,0,0}, + {35350,36753,35344 ,727,726,726 ,0,0,0}, {35531,35546,36833 ,727,726,726 ,0,0,0}, + {36833,35535,35534 ,726,726,726 ,0,0,0}, {35556,36834,36756 ,727,727,727 ,0,0,0}, + {35350,36750,36753 ,727,727,726 ,0,0,0}, {35359,36210,35357 ,726,726,727 ,0,0,0}, + {36206,35359,35206 ,20124,726,726 ,0,0,0}, {35362,35369,35207 ,727,726,726 ,0,0,0}, + {35368,35211,35210 ,726,726,726 ,0,0,0}, {35372,35213,35367 ,20124,726,727 ,0,0,0}, + {35217,35374,35376 ,726,727,20124 ,0,0,0}, {35219,35363,35222 ,726,726,726 ,0,0,0}, + {35380,35223,35222 ,726,20124,726 ,0,0,0}, {35222,35363,35380 ,726,726,726 ,0,0,0}, + {35225,35223,35379 ,726,20124,726 ,0,0,0}, {36812,35228,35381 ,727,727,727 ,0,0,0}, + {35381,35225,35379 ,727,726,726 ,0,0,0}, {36813,36338,36814 ,726,20124,20124 ,0,0,0}, + {36812,36814,35228 ,727,20124,727 ,0,0,0}, {35511,36835,36815 ,727,727,1792 ,0,0,0}, + {36339,36811,36340 ,727,727,727 ,0,0,0}, {36813,36339,36338 ,726,727,20124 ,0,0,0}, + {36836,35612,35613 ,727,726,726 ,0,0,0}, {36340,36811,36809 ,727,727,726 ,0,0,0}, + {36807,36810,36808 ,726,726,727 ,0,0,0}, {35302,36837,35305 ,20124,726,726 ,0,0,0}, + {36177,36808,36175 ,20124,727,727 ,0,0,0}, {36176,36480,36481 ,726,727,726 ,0,0,0}, + {36838,36806,36839 ,726,727,727 ,0,0,0}, {36477,36806,36838 ,726,727,726 ,0,0,0}, + {36805,35453,36840 ,726,726,726 ,0,0,0}, {36838,36839,36841 ,726,727,727 ,0,0,0}, + {36804,35441,35443 ,727,726,726 ,0,0,0}, {36795,35445,36842 ,727,726,726 ,0,0,0}, + {36843,35437,35439 ,20124,726,727 ,0,0,0}, {36801,35437,36843 ,727,726,20124 ,0,0,0}, + {36844,36845,35436 ,726,727,20124 ,0,0,0}, {36845,35483,35436 ,727,726,20124 ,0,0,0}, + {36846,35640,35642 ,727,20124,20124 ,0,0,0}, {36845,36847,35483 ,727,726,726 ,0,0,0}, + {36469,36848,36849 ,726,726,726 ,0,0,0}, {36850,35607,36851 ,727,726,20124 ,0,0,0}, + {36852,36853,35598 ,726,727,727 ,0,0,0}, {36854,35592,35591 ,726,726,727 ,0,0,0}, + {35502,35500,36855 ,1793,1793,1792 ,0,0,0}, {36856,36852,35594 ,727,726,726 ,0,0,0}, + {36857,35505,35502 ,1792,1793,1793 ,0,0,0}, {36341,35528,35525 ,726,1793,726 ,0,0,0}, + {35523,36341,35525 ,1793,726,726 ,0,0,0}, {36857,36858,35505 ,1792,726,1793 ,0,0,0}, + {35431,36859,35506 ,726,726,1792 ,0,0,0}, {35505,36859,35431 ,1793,726,726 ,0,0,0}, + {36341,35523,35522 ,726,1793,1793 ,0,0,0}, {35511,36815,35513 ,727,1792,727 ,0,0,0}, + {35505,36347,36859 ,1793,727,726 ,0,0,0}, {35507,36816,35510 ,1793,1793,1793 ,0,0,0}, + {36345,36858,36860 ,727,726,727 ,0,0,0}, {36858,36345,36347 ,726,727,727 ,0,0,0}, + {36817,36861,36860 ,1793,1792,727 ,0,0,0}, {36345,36860,36861 ,727,727,1792 ,0,0,0}, + {36819,36818,36862 ,727,1793,1793 ,0,0,0}, {36819,36861,36817 ,727,1792,1793 ,0,0,0}, + {36862,36319,36863 ,1793,1793,726 ,0,0,0}, {36863,36819,36862 ,726,727,1793 ,0,0,0}, + {36864,36318,36320 ,726,1792,727 ,0,0,0}, {36319,36318,36863 ,1793,1792,726 ,0,0,0}, + {36865,36864,36866 ,1793,726,1793 ,0,0,0}, {36864,36865,36318 ,726,1793,1792 ,0,0,0}, + {36337,36865,36867 ,726,1793,726 ,0,0,0}, {36866,36867,36865 ,1793,726,1793 ,0,0,0}, + {36868,36337,36869 ,727,726,1792 ,0,0,0}, {36337,36867,36869 ,726,726,1792 ,0,0,0}, + {35428,36337,36870 ,1793,726,1793 ,0,0,0}, {36337,36868,36870 ,726,727,1793 ,0,0,0}, + {34951,36871,34140 ,726,726,20124 ,0,0,0}, {36872,34302,35065 ,20124,727,20124 ,0,0,0}, + {36873,36874,36875 ,20124,726,20124 ,0,0,0}, {34930,36120,36119 ,727,20124,727 ,0,0,0}, + {34927,36120,34930 ,726,20124,727 ,0,0,0}, {36125,34927,34926 ,726,726,20124 ,0,0,0}, + {34924,36128,36126 ,20124,726,727 ,0,0,0}, {36876,34940,34943 ,727,726,726 ,0,0,0}, + {34125,34128,34838 ,726,726,20124 ,0,0,0}, {34832,34126,34834 ,726,726,726 ,0,0,0}, + {36138,36137,36280 ,20124,20124,727 ,0,0,0}, {36877,35950,36228 ,727,20124,20124 ,0,0,0}, + {34831,36243,36878 ,726,727,726 ,0,0,0}, {36286,36242,34846 ,20124,20124,727 ,0,0,0}, + {34850,36237,36285 ,726,726,20124 ,0,0,0}, {36236,34852,34853 ,727,726,20124 ,0,0,0}, + {36879,36880,36881 ,20124,726,20124 ,0,0,0}, {34862,36882,36233 ,726,20124,20124 ,0,0,0}, + {36232,36283,34868 ,726,726,20124 ,0,0,0}, {34887,34889,34210 ,20124,726,726 ,0,0,0}, + {36883,36884,36885 ,726,726,726 ,0,0,0}, {36284,36886,34312 ,726,726,726 ,0,0,0}, + {36887,36888,34215 ,20124,726,726 ,0,0,0}, {36886,36889,34312 ,726,726,726 ,0,0,0}, + {36890,36891,34214 ,20124,20124,726 ,0,0,0}, {34316,34313,36290 ,20124,726,726 ,0,0,0}, + {36291,36892,36893 ,726,20124,20124 ,0,0,0}, {36894,36895,36896 ,726,726,726 ,0,0,0}, + {36897,36898,36899 ,726,726,726 ,0,0,0}, {36294,35074,35068 ,727,726,726 ,0,0,0}, + {36294,35068,36900 ,727,726,727 ,0,0,0}, {36901,36902,36903 ,727,726,726 ,0,0,0}, + {36904,35077,36905 ,726,726,726 ,0,0,0}, {36273,34909,34912 ,727,726,726 ,0,0,0}, + {34064,36906,35980 ,20124,726,726 ,0,0,0}, {36906,34064,34061 ,726,20124,726 ,0,0,0}, + {36907,36172,36908 ,727,727,726 ,0,0,0}, {36909,36910,36168 ,727,727,727 ,0,0,0}, + {36164,36165,34907 ,726,726,726 ,0,0,0}, {36911,36268,35975 ,20124,726,20124 ,0,0,0}, + {36266,36223,34904 ,726,727,727 ,0,0,0}, {36164,36267,36162 ,726,726,20124 ,0,0,0}, + {34428,34425,36912 ,20138,20130,20137 ,0,0,0}, {36913,36410,36412 ,20130,20168,20139 ,0,0,0}, + {34810,34808,36387 ,20127,20126,20148 ,0,0,0}, {34808,34805,36388 ,20126,20135,20162 ,0,0,0}, + {36394,36391,34804 ,20133,20163,20164 ,0,0,0}, {36396,34801,36914 ,20165,726,20130 ,0,0,0}, + {36396,36393,34802 ,20165,20124,1792 ,0,0,0}, {34826,34448,34447 ,20165,20165,20134 ,0,0,0}, + {34770,34434,34772 ,1792,1792,20124 ,0,0,0}, {36915,36916,36389 ,20126,20126,20137 ,0,0,0}, + {36917,34442,36918 ,20137,20167,20124 ,0,0,0}, {36919,35795,36920 ,20126,20126,1793 ,0,0,0}, + {35793,36921,36922 ,20170,20137,20137 ,0,0,0}, {34438,36923,36924 ,20162,1793,727 ,0,0,0}, + {35906,35905,35800 ,20125,20148,20167 ,0,0,0}, {36925,34431,36437 ,20147,20168,20130 ,0,0,0}, + {35911,35801,35905 ,20168,20170,20148 ,0,0,0}, {35804,35915,35914 ,1792,20168,20167 ,0,0,0}, + {36433,36432,36452 ,20140,20137,1793 ,0,0,0}, {36926,36927,36928 ,20148,1792,20140 ,0,0,0}, + {36929,36930,36931 ,727,20148,727 ,0,0,0}, {36932,35787,35786 ,20124,20167,1793 ,0,0,0}, + {34755,35784,36933 ,20168,20167,20137 ,0,0,0}, {36425,35779,34766 ,20139,1793,20170 ,0,0,0}, + {36934,36935,36936 ,20126,20162,20126 ,0,0,0}, {36413,34735,36937 ,1792,20169,20164 ,0,0,0}, + {36938,36411,36410 ,20147,1792,20168 ,0,0,0}, {36939,36938,36410 ,20168,20147,20168 ,0,0,0}, + {36940,36941,36942 ,20135,20168,20133 ,0,0,0}, {36943,36944,36945 ,20126,20139,20148 ,0,0,0}, + {36414,36941,34730 ,20133,20168,20139 ,0,0,0}, {34378,36946,36947 ,20132,1792,1792 ,0,0,0}, + {12820,36948,36406 ,20140,1792,20167 ,0,0,0}, {36912,35936,34428 ,20137,20169,20138 ,0,0,0}, + {36949,36950,34382 ,20131,20162,20135 ,0,0,0}, {34375,36951,36952 ,20165,20148,20132 ,0,0,0}, + {36912,34425,36953 ,20137,20130,20165 ,0,0,0}, {36954,36955,36956 ,20169,20168,20171 ,0,0,0}, + {36957,36955,36365 ,20172,20168,20142 ,0,0,0}, {36958,36359,35931 ,20132,20136,20148 ,0,0,0}, + {36959,36358,34718 ,20135,20134,20133 ,0,0,0}, {34716,36959,34718 ,20127,20135,20133 ,0,0,0}, + {34366,36960,34633 ,726,727,726 ,0,0,0}, {36961,36962,36963 ,727,726,727 ,0,0,0}, + {36964,36965,36966 ,726,726,726 ,0,0,0}, {36967,35852,36968 ,727,20124,20124 ,0,0,0}, + {36613,34626,34624 ,727,727,727 ,0,0,0}, {36589,36968,35855 ,20124,20124,726 ,0,0,0}, + {36969,36613,34624 ,726,727,727 ,0,0,0}, {36969,34624,34622 ,726,727,726 ,0,0,0}, + {34363,34635,34636 ,726,20124,726 ,0,0,0}, {36616,36594,36596 ,20124,726,726 ,0,0,0}, + {36579,36970,35862 ,20124,727,20124 ,0,0,0}, {36575,34692,34693 ,20124,727,727 ,0,0,0}, + {36044,34696,34698 ,20124,726,726 ,0,0,0}, {34699,36040,36042 ,20124,727,20124 ,0,0,0}, + {34702,34704,36037 ,20124,726,726 ,0,0,0}, {36571,36971,34704 ,20124,727,726 ,0,0,0}, + {34648,34646,36530 ,726,726,20124 ,0,0,0}, {34671,34098,34668 ,20124,726,20124 ,0,0,0}, + {36028,36972,36567 ,20124,20124,20124 ,0,0,0}, {34095,36014,34102 ,727,726,726 ,0,0,0}, + {34201,36573,36536 ,726,726,726 ,0,0,0}, {35992,35991,36973 ,20124,726,727 ,0,0,0}, + {36974,35997,35994 ,726,726,20124 ,0,0,0}, {36975,36976,36977 ,726,726,20124 ,0,0,0}, + {36564,36561,36584 ,20124,726,727 ,0,0,0}, {34608,36586,36978 ,726,727,726 ,0,0,0}, + {34198,36979,36980 ,726,727,726 ,0,0,0}, {36981,34605,36978 ,726,726,726 ,0,0,0}, + {34602,36601,34599 ,726,727,726 ,0,0,0}, {36982,36983,36006 ,726,726,726 ,0,0,0}, + {36009,36538,36010 ,726,727,726 ,0,0,0}, {36603,35892,34288 ,726,726,20124 ,0,0,0}, + {34186,36984,36985 ,726,726,726 ,0,0,0}, {36963,36986,36987 ,727,726,726 ,0,0,0}, + {35887,36539,35888 ,20124,726,726 ,0,0,0}, {36988,36989,36552 ,727,727,726 ,0,0,0}, + {34597,36554,36551 ,726,727,726 ,0,0,0}, {36990,36539,35887 ,20124,726,20124 ,0,0,0}, + {34596,36554,34597 ,727,727,726 ,0,0,0}, {36991,36992,36993 ,727,726,727 ,0,0,0}, + {34554,34553,36994 ,726,726,726 ,0,0,0}, {34569,34572,36244 ,726,729,726 ,0,0,0}, + {36995,36996,36997 ,729,726,726 ,0,0,0}, {34562,34560,36108 ,726,728,726 ,0,0,0}, + {34560,34557,36106 ,728,726,726 ,0,0,0}, {36101,36104,34556 ,726,726,726 ,0,0,0}, + {36994,34553,36998 ,726,726,726 ,0,0,0}, {36098,36100,36994 ,726,726,726 ,0,0,0}, + {34574,34575,34083 ,726,726,726 ,0,0,0}, {36999,36094,37000 ,726,726,726 ,0,0,0}, + {36089,36092,36247 ,726,726,728 ,0,0,0}, {36080,34075,34074 ,726,726,726 ,0,0,0}, + {36050,34459,34475 ,726,726,726 ,0,0,0}, {36052,36050,34475 ,726,726,726 ,0,0,0}, + {36056,36055,34479 ,726,726,726 ,0,0,0}, {36058,34481,34482 ,726,726,726 ,0,0,0}, + {37001,37002,34170 ,726,726,726 ,0,0,0}, {36598,36687,34498 ,726,726,726 ,0,0,0}, + {37003,37004,37001 ,726,729,726 ,0,0,0}, {36074,36073,36683 ,726,726,726 ,0,0,0}, + {36076,36074,37005 ,728,726,726 ,0,0,0}, {37006,37007,34159 ,728,726,726 ,0,0,0}, + {34518,37008,37009 ,728,726,726 ,0,0,0}, {37010,37011,37012 ,726,726,726 ,0,0,0}, + {36697,37013,36692 ,728,726,729 ,0,0,0}, {36705,37014,34254 ,726,726,726 ,0,0,0}, + {34240,37015,37016 ,726,726,726 ,0,0,0}, {37017,34547,34549 ,726,726,726 ,0,0,0}, + {36245,34543,36250 ,726,726,726 ,0,0,0}, {37018,36997,36996 ,726,726,726 ,0,0,0}, + {34541,36189,34538 ,729,726,726 ,0,0,0}, {37019,37020,37021 ,726,726,726 ,0,0,0}, + {37022,37023,37024 ,726,726,729 ,0,0,0}, {37025,37023,34246 ,726,726,728 ,0,0,0}, + {37026,37025,34246 ,726,726,728 ,0,0,0}, {34344,34341,36717 ,726,726,726 ,0,0,0}, + {37027,37028,34242 ,726,726,726 ,0,0,0}, {37029,37030,37031 ,726,726,726 ,0,0,0}, + {37032,37033,37034 ,726,726,726 ,0,0,0}, {37035,37036,35843 ,726,729,726 ,0,0,0}, + {37037,37038,37039 ,729,726,726 ,0,0,0}, {37040,34322,37041 ,726,726,726 ,0,0,0}, + {36927,37042,36928 ,1792,1793,20140 ,0,0,0}, {34785,37043,36436 ,1793,20168,1793 ,0,0,0}, + {36446,37044,37045 ,1793,20139,20162 ,0,0,0}, {37045,36445,36446 ,20162,20170,1793 ,0,0,0}, + {36457,37046,37045 ,726,20130,20162 ,0,0,0}, {36457,37045,37044 ,726,20162,20139 ,0,0,0}, + {37042,35787,36928 ,1793,20167,20140 ,0,0,0}, {36429,36930,37047 ,726,20148,1793 ,0,0,0}, + {34397,37048,36435 ,20168,20139,20125 ,0,0,0}, {36425,36932,35786 ,20139,20124,1793 ,0,0,0}, + {36932,36928,35787 ,20124,20140,20167 ,0,0,0}, {37049,37050,37051 ,1793,20168,20140 ,0,0,0}, + {35781,34761,35782 ,20139,727,20137 ,0,0,0}, {34746,34743,37052 ,20126,20137,20125 ,0,0,0}, + {36423,36422,36425 ,20139,20170,20139 ,0,0,0}, {37053,37054,36936 ,20147,1793,20126 ,0,0,0}, + {37055,37056,37057 ,20130,1793,20139 ,0,0,0}, {36933,36426,34739 ,20137,20162,726 ,0,0,0}, + {36434,36433,37052 ,20139,20140,20125 ,0,0,0}, {36451,36438,35914 ,20168,20125,20167 ,0,0,0}, + {36438,36451,36432 ,20125,20168,20137 ,0,0,0}, {35801,35915,35804 ,20170,20168,1792 ,0,0,0}, + {35804,35914,36439 ,1792,20167,20125 ,0,0,0}, {35801,35800,35905 ,20170,20167,20148 ,0,0,0}, + {35801,35911,35915 ,20170,20168,20168 ,0,0,0}, {37058,36921,35793 ,20139,20137,20170 ,0,0,0}, + {35793,35796,37058 ,20170,20125,20139 ,0,0,0}, {37059,35906,36922 ,20125,20125,20137 ,0,0,0}, + {37060,37061,12921 ,20137,20132,20140 ,0,0,0}, {37062,34797,37063 ,20167,20170,20139 ,0,0,0}, + {35580,35754,35751 ,20124,726,726 ,0,0,0}, {37064,36770,35761 ,726,20124,726 ,0,0,0}, + {35150,35153,36775 ,726,20124,20124 ,0,0,0}, {35136,35132,37065 ,726,726,20124 ,0,0,0}, + {35577,35580,35751 ,20124,20124,726 ,0,0,0}, {36199,35562,35561 ,20124,726,727 ,0,0,0}, + {35570,35568,36199 ,726,726,20124 ,0,0,0}, {36199,35751,35750 ,20124,726,726 ,0,0,0}, + {35763,36181,35747 ,726,726,726 ,0,0,0}, {35770,36181,35769 ,726,726,20124 ,0,0,0}, + {36181,35775,36173 ,726,726,726 ,0,0,0}, {36781,36202,36782 ,726,726,20124 ,0,0,0}, + {37066,36196,36195 ,20124,726,726 ,0,0,0}, {36752,36200,36202 ,726,20124,726 ,0,0,0}, + {36196,37067,36202 ,726,726,726 ,0,0,0}, {36751,36202,37067 ,726,726,726 ,0,0,0}, + {36196,37066,37068 ,726,20124,20124 ,0,0,0}, {37068,37067,36196 ,20124,726,726 ,0,0,0}, + {36194,35159,36195 ,726,20124,726 ,0,0,0}, {36779,35155,35157 ,726,726,726 ,0,0,0}, + {36775,35153,36780 ,20124,20124,726 ,0,0,0}, {35144,35150,36776 ,726,726,727 ,0,0,0}, + {35144,36777,35145 ,726,726,726 ,0,0,0}, {36777,35144,36776 ,726,726,727 ,0,0,0}, + {36773,35145,36778 ,726,726,20124 ,0,0,0}, {36772,35143,35149 ,20124,726,726 ,0,0,0}, + {36773,35149,35145 ,726,726,726 ,0,0,0}, {36774,36771,35141 ,726,726,726 ,0,0,0}, + {36772,36774,35143 ,20124,726,726 ,0,0,0}, {35588,35760,35586 ,726,726,726 ,0,0,0}, + {35141,36771,35139 ,726,726,20124 ,0,0,0}, {35754,35582,35756 ,726,20124,726 ,0,0,0}, + {35743,36824,35399 ,726,726,1793 ,0,0,0}, {35716,36315,35718 ,1793,1793,727 ,0,0,0}, + {35402,35400,36822 ,1793,1793,727 ,0,0,0}, {35722,36330,35724 ,1793,1793,726 ,0,0,0}, + {36336,36330,35719 ,726,1793,1793 ,0,0,0}, {36315,36336,35718 ,1793,726,727 ,0,0,0}, + {35731,36316,35715 ,1792,1793,727 ,0,0,0}, {36316,35716,35715 ,1793,1793,727 ,0,0,0}, + {35738,35741,36213 ,727,1793,726 ,0,0,0}, {36825,36316,35731 ,1792,1793,1792 ,0,0,0}, + {36317,35732,35735 ,1793,726,1793 ,0,0,0}, {35732,36317,36825 ,726,1793,1792 ,0,0,0}, + {35735,35737,36213 ,1793,1793,726 ,0,0,0}, {35737,35738,36213 ,1793,727,726 ,0,0,0}, + {35399,35396,35743 ,1793,1793,726 ,0,0,0}, {36821,35405,35402 ,727,1793,1793 ,0,0,0}, + {37069,36335,35413 ,727,726,727 ,0,0,0}, {36821,36823,35405 ,727,1793,1793 ,0,0,0}, + {37070,35406,36823 ,727,1792,1793 ,0,0,0}, {35331,36823,35406 ,726,1793,1792 ,0,0,0}, + {37070,36820,35407 ,727,727,1793 ,0,0,0}, {35407,35406,37070 ,1793,1792,727 ,0,0,0}, + {37069,35410,36820 ,727,1793,727 ,0,0,0}, {35411,37069,35413 ,727,727,727 ,0,0,0}, + {37069,35411,35410 ,727,727,1793 ,0,0,0}, {36334,37071,36327 ,1793,1792,726 ,0,0,0}, + {35413,36335,36327 ,727,726,726 ,0,0,0}, {36329,37072,36327 ,1793,1792,726 ,0,0,0}, + {37071,36328,36327 ,1792,727,726 ,0,0,0}, {36324,37072,36325 ,1793,1792,1793 ,0,0,0}, + {36329,36325,37072 ,1793,1793,1792 ,0,0,0}, {36324,36326,36323 ,1793,1792,1793 ,0,0,0}, + {35729,36323,36326 ,726,1793,1792 ,0,0,0}, {36852,35598,35595 ,726,727,726 ,0,0,0}, + {35694,36506,36485 ,1793,1793,1793 ,0,0,0}, {36500,36503,37073 ,727,727,1793 ,0,0,0}, + {36506,35690,36849 ,1793,1793,726 ,0,0,0}, {35690,36506,35692 ,1793,1793,726 ,0,0,0}, + {36849,35687,35686 ,726,1793,727 ,0,0,0}, {35690,35687,36849 ,1793,1793,726 ,0,0,0}, + {35700,36469,35699 ,726,726,1792 ,0,0,0}, {35686,35684,36849 ,727,1793,726 ,0,0,0}, + {37074,37075,36469 ,1793,1793,726 ,0,0,0}, {37076,37077,36469 ,1793,1793,726 ,0,0,0}, + {35706,35709,36469 ,727,1793,726 ,0,0,0}, {36853,37078,35600 ,727,1793,727 ,0,0,0}, + {35602,35600,37078 ,727,727,1793 ,0,0,0}, {35602,37078,37079 ,727,1793,726 ,0,0,0}, + {35602,37079,35604 ,727,726,727 ,0,0,0}, {35604,37080,35605 ,727,1792,726 ,0,0,0}, + {36498,36501,36497 ,726,727,726 ,0,0,0}, {36488,36490,36497 ,1793,1793,726 ,0,0,0}, + {36488,36497,36502 ,1793,726,727 ,0,0,0}, {36489,36499,36490 ,727,1792,1793 ,0,0,0}, + {36500,37073,36499 ,727,1793,1792 ,0,0,0}, {37081,36505,36504 ,1793,727,726 ,0,0,0}, + {36503,36505,37073 ,727,727,1793 ,0,0,0}, {37082,37081,36493 ,1792,1793,1792 ,0,0,0}, + {37081,37082,36505 ,1793,1792,727 ,0,0,0}, {36491,37083,36492 ,727,1793,1793 ,0,0,0}, + {37082,36493,36492 ,1792,1792,1793 ,0,0,0}, {36484,36483,37083 ,1793,726,1793 ,0,0,0}, + {36492,37083,36483 ,1793,1793,726 ,0,0,0}, {36483,36482,36487 ,726,1792,727 ,0,0,0}, + {35697,36487,36482 ,726,727,1792 ,0,0,0}, {37084,36645,36653 ,20124,726,726 ,0,0,0}, + {37085,36645,37084 ,20124,726,20124 ,0,0,0}, {36648,37086,36639 ,726,20124,20124 ,0,0,0}, + {37087,36658,36653 ,20124,726,726 ,0,0,0}, {37088,37089,35648 ,726,726,726 ,0,0,0}, + {35257,37090,36742 ,726,20124,727 ,0,0,0}, {37091,35646,35648 ,726,726,726 ,0,0,0}, + {36654,37092,35272 ,20124,20124,20124 ,0,0,0}, {36653,35281,37087 ,726,20124,20124 ,0,0,0}, + {35667,35668,36645 ,726,726,726 ,0,0,0}, {35673,36645,35671 ,726,726,20124 ,0,0,0}, + {35674,36644,35673 ,726,726,726 ,0,0,0}, {35677,36643,35674 ,20124,727,726 ,0,0,0}, + {35679,36646,36642 ,726,726,726 ,0,0,0}, {35679,36642,35677 ,726,726,20124 ,0,0,0}, + {36647,36648,36646 ,726,726,726 ,0,0,0}, {37086,36648,36649 ,20124,726,726 ,0,0,0}, + {36652,36639,36641 ,726,20124,726 ,0,0,0}, {36640,36639,37086 ,726,20124,20124 ,0,0,0}, + {36656,36651,36650 ,20124,20124,726 ,0,0,0}, {36650,36652,36641 ,726,726,726 ,0,0,0}, + {36662,36655,36657 ,726,726,726 ,0,0,0}, {36656,36655,36651 ,20124,726,20124 ,0,0,0}, + {36660,37093,36661 ,726,726,727 ,0,0,0}, {36662,36661,36655 ,726,727,726 ,0,0,0}, + {37094,37093,37095 ,726,726,20124 ,0,0,0}, {36660,37095,37093 ,726,20124,726 ,0,0,0}, + {37096,37094,37097 ,726,726,20124 ,0,0,0}, {37094,37095,37097 ,726,20124,20124 ,0,0,0}, + {35665,37094,37098 ,726,726,20124 ,0,0,0}, {37094,37096,37098 ,726,726,20124 ,0,0,0}, + {35453,35455,36840 ,726,726,726 ,0,0,0}, {37099,37100,37094 ,20124,726,726 ,0,0,0}, + {35322,35319,35463 ,726,726,726 ,0,0,0}, {35323,35479,35325 ,20124,726,726 ,0,0,0}, + {35457,35231,36841 ,727,20124,727 ,0,0,0}, {35296,37101,35299 ,726,726,726 ,0,0,0}, + {35299,37101,36208 ,726,726,20124 ,0,0,0}, {37091,35648,37089 ,726,726,726 ,0,0,0}, + {35255,36742,36745 ,726,727,727 ,0,0,0}, {37102,35658,37103 ,726,726,726 ,0,0,0}, + {37104,35658,37102 ,726,726,726 ,0,0,0}, {35660,37105,35662 ,20124,726,726 ,0,0,0}, + {37105,37106,35662 ,726,726,726 ,0,0,0}, {35665,35664,37107 ,726,727,726 ,0,0,0}, + {37108,37094,37088 ,726,726,726 ,0,0,0}, {35665,37109,37110 ,726,20124,727 ,0,0,0}, + {37094,37111,37099 ,726,20124,20124 ,0,0,0}, {37094,37108,37111 ,726,726,20124 ,0,0,0}, + {37112,36792,37100 ,20124,20124,726 ,0,0,0}, {37094,37100,36792 ,726,726,20124 ,0,0,0}, + {37113,36792,37114 ,20124,20124,726 ,0,0,0}, {36792,37112,37114 ,20124,20124,726 ,0,0,0}, + {36793,36792,37115 ,20124,20124,726 ,0,0,0}, {36792,37113,37115 ,20124,20124,726 ,0,0,0}, + {36794,37116,36792 ,726,726,20124 ,0,0,0}, {36798,36800,37116 ,726,726,726 ,0,0,0}, + {36792,37116,36800 ,20124,726,726 ,0,0,0}, {36800,36799,36803 ,726,726,726 ,0,0,0}, + {35635,36803,36799 ,727,726,726 ,0,0,0}, {37117,35618,37118 ,726,726,726 ,0,0,0}, + {35594,36852,35595 ,726,726,726 ,0,0,0}, {37119,37118,37120 ,726,726,727 ,0,0,0}, + {35499,36479,37121 ,1793,726,1793 ,0,0,0}, {35618,36797,35616 ,726,727,727 ,0,0,0}, + {37122,35496,35494 ,727,1793,726 ,0,0,0}, {35493,36508,37123 ,726,1792,1793 ,0,0,0}, + {35494,37123,37122 ,726,1793,727 ,0,0,0}, {35490,35488,36507 ,1793,726,726 ,0,0,0}, + {35490,36508,35493 ,1793,1792,726 ,0,0,0}, {35484,37124,35487 ,726,727,1793 ,0,0,0}, + {35306,35459,35462 ,726,726,727 ,0,0,0}, {37125,37117,37126 ,726,726,726 ,0,0,0}, + {36841,35231,37127 ,727,20124,726 ,0,0,0}, {35480,35323,35322 ,726,20124,726 ,0,0,0}, + {37128,37125,37126 ,726,726,726 ,0,0,0}, {35618,37120,37118 ,726,727,726 ,0,0,0}, + {37119,37129,37130 ,726,726,726 ,0,0,0}, {37120,37129,37119 ,727,726,726 ,0,0,0}, + {37131,36494,37130 ,726,726,726 ,0,0,0}, {37119,37130,36494 ,726,726,726 ,0,0,0}, + {37132,36494,37133 ,726,726,727 ,0,0,0}, {36494,37131,37133 ,726,726,727 ,0,0,0}, + {36496,37134,36494 ,726,727,726 ,0,0,0}, {36494,37132,36495 ,726,726,726 ,0,0,0}, + {36497,36494,37135 ,726,726,726 ,0,0,0}, {37134,37135,36494 ,727,726,726 ,0,0,0}, + {37136,36497,37137 ,727,726,726 ,0,0,0}, {36497,37135,37137 ,726,726,726 ,0,0,0}, + {36467,36497,37138 ,20124,726,727 ,0,0,0}, {36497,37136,37138 ,726,727,727 ,0,0,0}, + {36468,35605,37080 ,1793,726,1792 ,0,0,0}, {35137,36769,36766 ,726,726,20124 ,0,0,0}, + {35574,37139,36759 ,726,726,726 ,0,0,0}, {37139,35572,35570 ,726,726,726 ,0,0,0}, + {35574,35572,37139 ,726,726,726 ,0,0,0}, {35577,35751,36199 ,20124,726,20124 ,0,0,0}, + {37139,35570,36199 ,726,726,20124 ,0,0,0}, {35564,36199,35565 ,726,20124,20124 ,0,0,0}, + {36199,35568,35565 ,20124,726,20124 ,0,0,0}, {36199,35576,35577 ,20124,726,20124 ,0,0,0}, + {36199,35564,35562 ,20124,726,726 ,0,0,0}, {36199,35561,35576 ,20124,727,726 ,0,0,0}, + {35586,35758,35583 ,726,726,20124 ,0,0,0}, {35756,35583,35758 ,726,20124,726 ,0,0,0}, + {35588,37064,35761 ,726,726,726 ,0,0,0}, {35760,35758,35586 ,726,726,726 ,0,0,0}, + {35588,35761,35760 ,726,726,726 ,0,0,0}, {36769,36770,37064 ,726,20124,726 ,0,0,0}, + {36769,35137,35139 ,726,726,20124 ,0,0,0}, {37065,35132,36766 ,20124,726,20124 ,0,0,0}, + {35183,35136,36768 ,20124,726,20124 ,0,0,0}, {36767,35136,37065 ,726,726,20124 ,0,0,0}, + {35183,36763,35184 ,20124,726,20124 ,0,0,0}, {36763,35183,36768 ,726,20124,20124 ,0,0,0}, + {36762,35187,35184 ,20124,726,20124 ,0,0,0}, {36765,35188,35187 ,20124,726,726 ,0,0,0}, + {36762,36764,35187 ,20124,726,726 ,0,0,0}, {36761,36204,35190 ,726,726,726 ,0,0,0}, + {36765,36761,35188 ,20124,726,726 ,0,0,0}, {35193,36203,35194 ,20124,726,20124 ,0,0,0}, + {35190,36204,35193 ,726,726,20124 ,0,0,0}, {35196,36760,35575 ,726,726,727 ,0,0,0}, + {35194,36203,36760 ,20124,726,726 ,0,0,0}, {36213,35394,35544 ,726,726,727 ,0,0,0}, + {35393,35544,35394 ,726,727,726 ,0,0,0}, {35337,35339,37140 ,726,727,727 ,0,0,0}, + {35540,36213,35542 ,727,726,727 ,0,0,0}, {36213,35544,35542 ,726,727,727 ,0,0,0}, + {36213,35540,35538 ,726,727,727 ,0,0,0}, {36213,35535,36833 ,726,726,726 ,0,0,0}, + {36833,35532,35531 ,726,726,727 ,0,0,0}, {35534,35532,36833 ,726,726,726 ,0,0,0}, + {35547,36833,35546 ,726,726,726 ,0,0,0}, {36753,35558,35345 ,726,726,726 ,0,0,0}, + {35550,35552,36833 ,726,726,726 ,0,0,0}, {35550,36833,35547 ,726,726,726 ,0,0,0}, + {35558,36753,36834 ,726,726,727 ,0,0,0}, {35552,36756,36833 ,726,727,726 ,0,0,0}, + {35558,36834,35556 ,726,727,727 ,0,0,0}, {35553,35556,36756 ,726,727,727 ,0,0,0}, + {35558,36275,35345 ,726,727,726 ,0,0,0}, {36831,35343,35349 ,726,726,727 ,0,0,0}, + {36314,35341,36832 ,726,726,726 ,0,0,0}, {37140,35339,36314 ,727,727,726 ,0,0,0}, + {37141,36754,35337 ,726,726,726 ,0,0,0}, {37141,35337,37140 ,726,726,727 ,0,0,0}, + {36829,35332,36754 ,726,726,726 ,0,0,0}, {36830,35383,35336 ,727,726,20124 ,0,0,0}, + {36829,35336,35332 ,726,20124,726 ,0,0,0}, {35383,37142,36755 ,726,726,726 ,0,0,0}, + {36830,37142,35383 ,727,726,726 ,0,0,0}, {36755,36827,35384 ,726,727,726 ,0,0,0}, + {35387,36828,35388 ,1793,727,726 ,0,0,0}, {35384,36827,35387 ,726,727,1793 ,0,0,0}, + {35390,36826,35545 ,1793,20124,726 ,0,0,0}, {35388,36828,36826 ,726,727,20124 ,0,0,0}, + {35616,36796,35613 ,727,726,726 ,0,0,0}, {37121,36855,35500 ,1793,1792,1793 ,0,0,0}, + {35612,36836,37143 ,726,727,20124 ,0,0,0}, {35510,36816,36835 ,1793,1793,727 ,0,0,0}, + {35510,36835,35511 ,1793,727,727 ,0,0,0}, {36466,35517,35516 ,1793,726,726 ,0,0,0}, + {35513,36815,35516 ,727,1792,726 ,0,0,0}, {35506,36859,36816 ,1792,726,1793 ,0,0,0}, + {35505,36858,36347 ,1793,726,727 ,0,0,0}, {36857,35502,36855 ,1792,1793,1792 ,0,0,0}, + {35500,35499,37121 ,1793,1793,1793 ,0,0,0}, {35496,37122,36479 ,1793,727,726 ,0,0,0}, + {35493,37123,35494 ,726,1793,726 ,0,0,0}, {36507,35488,37144 ,726,726,1793 ,0,0,0}, + {35487,37124,37144 ,1793,727,1793 ,0,0,0}, {37144,35488,35487 ,1793,726,1793 ,0,0,0}, + {36847,37124,35484 ,726,727,726 ,0,0,0}, {36797,37117,37145 ,727,726,726 ,0,0,0}, + {37117,37125,37145 ,726,726,726 ,0,0,0}, {35483,36847,35484 ,726,726,726 ,0,0,0}, + {36844,35432,36801 ,726,726,727 ,0,0,0}, {35436,35432,36844 ,20124,726,726 ,0,0,0}, + {35439,35441,37146 ,727,726,20124 ,0,0,0}, {36843,35439,37146 ,20124,727,20124 ,0,0,0}, + {35307,35306,35462 ,726,726,727 ,0,0,0}, {35441,36804,37146 ,726,727,20124 ,0,0,0}, + {35444,37147,36842 ,726,726,726 ,0,0,0}, {35445,35444,36842 ,726,726,726 ,0,0,0}, + {37147,35450,36805 ,726,727,726 ,0,0,0}, {35450,37147,35444 ,727,726,726 ,0,0,0}, + {36839,36840,35455 ,727,726,726 ,0,0,0}, {36839,35457,36841 ,727,727,727 ,0,0,0}, + {35457,36839,35455 ,727,727,726 ,0,0,0}, {35468,35310,35469 ,726,726,726 ,0,0,0}, + {35231,35459,35306 ,20124,726,726 ,0,0,0}, {35319,35476,35463 ,726,20124,726 ,0,0,0}, + {35467,35472,35313 ,727,20124,726 ,0,0,0}, {35468,35467,35311 ,726,727,726 ,0,0,0}, + {35476,35319,35317 ,20124,726,726 ,0,0,0}, {35472,35474,35316 ,20124,727,726 ,0,0,0}, + {35476,35317,35474 ,20124,726,727 ,0,0,0}, {35463,35480,35322 ,726,726,726 ,0,0,0}, + {35480,35479,35323 ,726,726,20124 ,0,0,0}, {37128,37148,37149 ,726,727,726 ,0,0,0}, + {37127,35305,36837 ,726,726,726 ,0,0,0}, {36802,35635,36511 ,726,727,726 ,0,0,0}, + {37150,37151,37152 ,20124,20124,726 ,0,0,0}, {35481,37153,35328 ,727,727,727 ,0,0,0}, + {37154,37155,37156 ,727,727,727 ,0,0,0}, {37157,35636,37158 ,726,726,20124 ,0,0,0}, + {35622,35621,37159 ,726,727,726 ,0,0,0}, {37160,37161,37162 ,726,727,726 ,0,0,0}, + {37163,37164,37165 ,726,20124,727 ,0,0,0}, {35624,37166,35625 ,726,726,20124 ,0,0,0}, + {37167,37168,37169 ,727,727,726 ,0,0,0}, {37170,37171,37172 ,727,726,726 ,0,0,0}, + {36509,36630,35630 ,20124,726,726 ,0,0,0}, {36511,37173,36802 ,726,20124,726 ,0,0,0}, + {35634,36511,35635 ,726,726,727 ,0,0,0}, {36472,36519,36473 ,726,726,726 ,0,0,0}, + {37174,36628,37170 ,727,726,727 ,0,0,0}, {36627,36519,36518 ,20124,726,727 ,0,0,0}, + {37149,37148,37174 ,726,727,727 ,0,0,0}, {37148,36628,37174 ,727,726,727 ,0,0,0}, + {37126,37148,37128 ,726,727,726 ,0,0,0}, {36797,35618,37117 ,727,726,726 ,0,0,0}, + {36836,35613,36796 ,727,726,726 ,0,0,0}, {37143,36851,35610 ,20124,20124,726 ,0,0,0}, + {35610,35612,37143 ,726,726,20124 ,0,0,0}, {36850,35606,35607 ,727,726,726 ,0,0,0}, + {36851,35607,35610 ,20124,726,726 ,0,0,0}, {36854,35591,36850 ,726,727,727 ,0,0,0}, + {35606,36850,35591 ,726,727,727 ,0,0,0}, {35592,36854,36856 ,726,726,727 ,0,0,0}, + {35600,35598,36853 ,727,727,727 ,0,0,0}, {35594,35592,36856 ,726,726,727 ,0,0,0}, + {36467,36468,37175 ,20124,1793,727 ,0,0,0}, {37079,37080,35604 ,726,1792,727 ,0,0,0}, + {36469,36497,36467 ,726,726,20124 ,0,0,0}, {36467,37175,36469 ,20124,727,726 ,0,0,0}, + {35711,36498,36469 ,726,726,726 ,0,0,0}, {36470,36469,37175 ,726,726,727 ,0,0,0}, + {36469,35709,35711 ,726,1793,726 ,0,0,0}, {37176,36469,36471 ,1792,726,1793 ,0,0,0}, + {37177,37178,36469 ,1792,726,726 ,0,0,0}, {37176,37177,36469 ,1792,1792,726 ,0,0,0}, + {37179,37074,36469 ,727,1793,726 ,0,0,0}, {36469,35705,35706 ,726,1793,727 ,0,0,0}, + {35703,36469,35700 ,1793,726,726 ,0,0,0}, {36469,35683,35699 ,726,727,1792 ,0,0,0}, + {37075,37076,36469 ,1793,1793,726 ,0,0,0}, {37180,36848,36469 ,727,726,726 ,0,0,0}, + {36469,37077,37180 ,726,1793,727 ,0,0,0}, {35684,36469,36849 ,1793,726,726 ,0,0,0}, + {35684,35683,36469 ,1793,727,726 ,0,0,0}, {36848,37181,36849 ,726,1793,726 ,0,0,0}, + {36341,36849,37182 ,726,726,726 ,0,0,0}, {37181,37182,36849 ,1793,726,726 ,0,0,0}, + {37183,36341,37184 ,727,726,1792 ,0,0,0}, {36341,37182,37184 ,726,726,1792 ,0,0,0}, + {35528,36341,37185 ,1793,726,1793 ,0,0,0}, {36341,37183,37185 ,726,727,1793 ,0,0,0}, + {35643,35646,37186 ,20124,726,727 ,0,0,0}, {36207,35302,35300 ,726,20124,20124 ,0,0,0}, + {35643,37186,37187 ,20124,727,726 ,0,0,0}, {35310,35468,35311 ,726,726,726 ,0,0,0}, + {35316,35313,35472 ,726,726,20124 ,0,0,0}, {35317,35316,35474 ,726,726,727 ,0,0,0}, + {35311,35467,35313 ,726,727,726 ,0,0,0}, {35469,35310,35307 ,726,726,726 ,0,0,0}, + {35231,35457,35459 ,20124,727,726 ,0,0,0}, {37127,35231,35305 ,726,20124,726 ,0,0,0}, + {36837,35302,36207 ,726,20124,726 ,0,0,0}, {35300,35299,36208 ,20124,726,20124 ,0,0,0}, + {35296,36631,37101 ,726,726,726 ,0,0,0}, {35293,36632,35294 ,20124,726,20124 ,0,0,0}, + {35288,36788,35290 ,726,726,726 ,0,0,0}, {35290,36633,35293 ,726,20124,20124 ,0,0,0}, + {37188,35288,35287 ,726,726,726 ,0,0,0}, {35288,37188,36788 ,726,726,726 ,0,0,0}, + {36789,35284,37189 ,726,20124,726 ,0,0,0}, {37188,35287,36789 ,726,726,726 ,0,0,0}, + {35250,36663,35244 ,726,726,726 ,0,0,0}, {35283,36787,37189 ,20124,20124,726 ,0,0,0}, + {37189,35284,35283 ,726,20124,20124 ,0,0,0}, {37190,36787,35236 ,727,20124,726 ,0,0,0}, + {37190,35232,36747 ,727,726,726 ,0,0,0}, {35232,37190,35236 ,726,727,726 ,0,0,0}, + {36785,36612,35245 ,726,20124,726 ,0,0,0}, {35239,35241,36786 ,20124,726,726 ,0,0,0}, + {35237,35239,36748 ,726,20124,727 ,0,0,0}, {36612,36637,35249 ,20124,727,726 ,0,0,0}, + {36786,35241,36638 ,726,726,726 ,0,0,0}, {35243,35249,36637 ,726,726,727 ,0,0,0}, + {35245,35244,36785 ,726,726,726 ,0,0,0}, {36664,35250,35253 ,726,726,20124 ,0,0,0}, + {36745,36784,35255 ,727,726,726 ,0,0,0}, {35257,36742,35255 ,726,727,726 ,0,0,0}, + {37090,35259,37191 ,20124,20124,20124 ,0,0,0}, {35259,37090,35257 ,20124,20124,726 ,0,0,0}, + {37191,35262,35269 ,20124,726,727 ,0,0,0}, {35259,35262,37191 ,20124,726,20124 ,0,0,0}, + {35279,35281,36653 ,20124,20124,726 ,0,0,0}, {35268,37192,35269 ,20124,726,727 ,0,0,0}, + {37191,35269,37192 ,20124,727,726 ,0,0,0}, {35268,35267,37092 ,20124,727,20124 ,0,0,0}, + {37092,37192,35268 ,20124,726,20124 ,0,0,0}, {35280,35279,36653 ,726,20124,726 ,0,0,0}, + {35272,37092,35267 ,20124,20124,727 ,0,0,0}, {36654,35274,35276 ,20124,727,726 ,0,0,0}, + {35272,35274,36654 ,20124,727,20124 ,0,0,0}, {35276,35263,36653 ,726,726,726 ,0,0,0}, + {35263,35280,36653 ,726,726,726 ,0,0,0}, {37110,37088,37094 ,727,726,726 ,0,0,0}, + {36653,36659,37084 ,726,20124,20124 ,0,0,0}, {36645,37085,37193 ,726,20124,726 ,0,0,0}, + {37194,35651,36645 ,20124,726,726 ,0,0,0}, {36645,37193,37194 ,726,726,20124 ,0,0,0}, + {35652,37194,37195 ,726,20124,726 ,0,0,0}, {37194,35652,35651 ,20124,726,726 ,0,0,0}, + {35665,37110,37094 ,726,727,726 ,0,0,0}, {36791,37196,35654 ,726,726,726 ,0,0,0}, + {37195,36791,35652 ,726,726,726 ,0,0,0}, {37103,35655,37196 ,726,726,726 ,0,0,0}, + {35654,37196,35655 ,726,726,726 ,0,0,0}, {35665,37107,37109 ,726,726,20124 ,0,0,0}, + {35658,35655,37103 ,726,726,726 ,0,0,0}, {37104,37105,35660 ,726,726,20124 ,0,0,0}, + {35660,35658,37104 ,20124,726,726 ,0,0,0}, {35664,35662,37106 ,727,726,726 ,0,0,0}, + {37107,35664,37106 ,726,727,726 ,0,0,0}, {37110,37089,37088 ,727,726,726 ,0,0,0}, + {37186,35646,37091 ,727,726,726 ,0,0,0}, {37187,36846,35642 ,726,727,20124 ,0,0,0}, + {35642,35643,37187 ,20124,20124,726 ,0,0,0}, {37158,35640,36846 ,20124,20124,727 ,0,0,0}, + {35636,35637,37158 ,726,20124,20124 ,0,0,0}, {37158,35637,35640 ,20124,20124,20124 ,0,0,0}, + {35636,37157,35621 ,726,726,727 ,0,0,0}, {35622,37159,37166 ,726,726,726 ,0,0,0}, + {35621,37157,37159 ,727,726,726 ,0,0,0}, {36629,35625,37166 ,726,20124,726 ,0,0,0}, + {35624,35622,37166 ,726,726,726 ,0,0,0}, {36509,35628,36629 ,20124,726,726 ,0,0,0}, + {36630,36510,35632 ,726,726,726 ,0,0,0}, {36802,37173,36474 ,726,20124,726 ,0,0,0}, + {36519,36472,36520 ,726,726,726 ,0,0,0}, {36474,36473,36802 ,726,726,726 ,0,0,0}, + {36518,37171,36627 ,727,726,20124 ,0,0,0}, {36628,37171,37170 ,726,726,727 ,0,0,0}, + {36628,36627,37171 ,726,20124,726 ,0,0,0}, {37172,37197,37170 ,726,726,727 ,0,0,0}, + {37167,37197,37168 ,727,726,727 ,0,0,0}, {37172,37168,37197 ,726,727,726 ,0,0,0}, + {37167,37169,37198 ,727,726,727 ,0,0,0}, {37163,37165,37198 ,726,727,727 ,0,0,0}, + {37198,37169,37163 ,727,726,726 ,0,0,0}, {37161,37165,37164 ,727,727,20124 ,0,0,0}, + {37199,37160,37162 ,726,726,726 ,0,0,0}, {37162,37161,37164 ,726,727,20124 ,0,0,0}, + {37155,37199,37156 ,727,726,727 ,0,0,0}, {37199,37155,37160 ,726,727,726 ,0,0,0}, + {37156,37150,37154 ,727,20124,727 ,0,0,0}, {37152,37151,37153 ,726,20124,727 ,0,0,0}, + {37154,37150,37152 ,727,20124,726 ,0,0,0}, {35328,37153,37151 ,727,727,20124 ,0,0,0}, + {36738,37200,35127 ,20124,20124,726 ,0,0,0}, {37201,36738,37202 ,727,20124,726 ,0,0,0}, + {36738,35127,37202 ,20124,726,726 ,0,0,0}, {37203,36738,37204 ,726,20124,727 ,0,0,0}, + {36738,37201,37204 ,20124,727,727 ,0,0,0}, {36738,37205,36740 ,20124,726,726 ,0,0,0}, + {36738,37203,37205 ,20124,726,726 ,0,0,0}, {36676,37206,37207 ,20124,726,727 ,0,0,0}, + {36741,37206,36676 ,20124,726,20124 ,0,0,0}, {37200,35111,35109 ,20124,726,726 ,0,0,0}, + {37207,35119,36676 ,727,727,20124 ,0,0,0}, {35115,36677,35119 ,727,20124,727 ,0,0,0}, + {36676,35119,36677 ,20124,727,20124 ,0,0,0}, {35112,36677,35118 ,726,20124,726 ,0,0,0}, + {36677,35115,35118 ,20124,727,726 ,0,0,0}, {37200,36677,35111 ,20124,20124,726 ,0,0,0}, + {36677,35112,35111 ,20124,726,726 ,0,0,0}, {35121,37200,35108 ,726,20124,20124 ,0,0,0}, + {37200,35109,35108 ,20124,726,20124 ,0,0,0}, {35126,37200,35124 ,726,20124,726 ,0,0,0}, + {37200,35121,35124 ,20124,726,726 ,0,0,0}, {35127,37200,35126 ,726,20124,726 ,0,0,0}, + {36306,35097,35093 ,727,726,20124 ,0,0,0}, {36288,37208,36292 ,727,20124,727 ,0,0,0}, + {36292,37209,37210 ,727,726,726 ,0,0,0}, {37208,37209,36292 ,20124,726,727 ,0,0,0}, + {36293,36292,37211 ,727,727,20124 ,0,0,0}, {37210,37211,36292 ,726,20124,727 ,0,0,0}, + {37212,36293,37213 ,20124,727,726 ,0,0,0}, {36293,37211,37213 ,727,20124,726 ,0,0,0}, + {37214,36293,37215 ,20124,727,20124 ,0,0,0}, {36293,37212,37215 ,727,20124,20124 ,0,0,0}, + {36306,36293,37214 ,727,727,20124 ,0,0,0}, {36306,35090,35089 ,727,726,726 ,0,0,0}, + {36306,37214,35097 ,727,20124,726 ,0,0,0}, {36306,35096,35090 ,727,726,726 ,0,0,0}, + {36306,35093,35096 ,727,20124,726 ,0,0,0}, {36289,36306,35087 ,727,727,20124 ,0,0,0}, + {35089,35087,36306 ,726,20124,727 ,0,0,0}, {35099,36289,35086 ,726,727,727 ,0,0,0}, + {36289,35087,35086 ,727,20124,727 ,0,0,0}, {35104,36289,35102 ,727,727,726 ,0,0,0}, + {36289,35099,35102 ,727,726,726 ,0,0,0}, {35105,36289,35104 ,727,727,727 ,0,0,0}, + {35080,35082,37216 ,726,727,726 ,0,0,0}, {37217,37218,37219 ,726,727,20124 ,0,0,0}, + {37220,36300,37221 ,727,20124,726 ,0,0,0}, {36300,37220,36301 ,20124,727,726 ,0,0,0}, + {37220,36313,36289 ,727,726,727 ,0,0,0}, {37221,36313,37220 ,726,726,727 ,0,0,0}, + {36289,36312,36306 ,727,20124,727 ,0,0,0}, {36307,36309,36308 ,726,20124,726 ,0,0,0}, + {36310,36304,36308 ,20124,727,726 ,0,0,0}, {36295,36304,35075 ,727,727,726 ,0,0,0}, + {35071,36295,35075 ,20124,727,726 ,0,0,0}, {34302,35067,35065 ,727,726,20124 ,0,0,0}, + {35074,36294,35071 ,726,727,20124 ,0,0,0}, {37222,34296,36303 ,726,726,726 ,0,0,0}, + {37223,36883,36885 ,726,726,726 ,0,0,0}, {37224,35065,35064 ,727,20124,727 ,0,0,0}, + {36898,34915,37225 ,726,726,726 ,0,0,0}, {37226,36904,37227 ,726,726,20124 ,0,0,0}, + {35080,37216,35077 ,726,726,726 ,0,0,0}, {36905,35077,37216 ,726,726,726 ,0,0,0}, + {37216,35082,36311 ,726,727,727 ,0,0,0}, {35083,36311,35082 ,727,727,727 ,0,0,0}, + {35052,36454,37046 ,20148,20167,20130 ,0,0,0}, {36931,36930,36460 ,727,20148,1792 ,0,0,0}, + {36931,36460,36459 ,727,1792,20124 ,0,0,0}, {37047,36930,36929 ,1793,20148,727 ,0,0,0}, + {36428,36927,36926 ,20140,1792,20148 ,0,0,0}, {36430,36429,37047 ,1793,726,1793 ,0,0,0}, + {36428,36926,36429 ,20140,20148,726 ,0,0,0}, {37042,35053,35790 ,1793,20140,20147 ,0,0,0}, + {35790,35787,37042 ,20147,20167,1793 ,0,0,0}, {35053,36456,36450 ,20140,20147,20140 ,0,0,0}, + {35053,35049,36456 ,20140,1793,20147 ,0,0,0}, {35049,35052,37046 ,1793,20148,20130 ,0,0,0}, + {35049,37046,36457 ,1793,20130,726 ,0,0,0}, {35052,35046,36454 ,20148,1792,20167 ,0,0,0}, + {36455,35045,35043 ,727,726,1793 ,0,0,0}, {35046,35045,36455 ,1792,726,727 ,0,0,0}, + {35043,35042,36461 ,1793,20130,726 ,0,0,0}, {36462,36461,35055 ,20167,726,1792 ,0,0,0}, + {35042,35055,36461 ,20130,1792,726 ,0,0,0}, {36462,35058,36449 ,20167,20140,20140 ,0,0,0}, + {35061,36449,35060 ,726,20140,20130 ,0,0,0}, {36449,35058,35060 ,20140,20140,20130 ,0,0,0}, + {36528,35036,35038 ,727,726,727 ,0,0,0}, {36526,36619,35027 ,727,727,20124 ,0,0,0}, + {37228,36623,37229 ,20124,727,727 ,0,0,0}, {36623,35039,37229 ,727,727,727 ,0,0,0}, + {36623,37228,36624 ,727,20124,726 ,0,0,0}, {36526,35027,35030 ,727,20124,726 ,0,0,0}, + {36619,36623,37230 ,727,727,20124 ,0,0,0}, {36625,37230,36623 ,726,20124,727 ,0,0,0}, + {37231,36619,37232 ,20124,727,726 ,0,0,0}, {36619,37230,37232 ,727,20124,726 ,0,0,0}, + {37233,36619,37234 ,20124,727,20124 ,0,0,0}, {36619,37231,37234 ,727,20124,20124 ,0,0,0}, + {36619,35031,35027 ,727,726,20124 ,0,0,0}, {36619,37233,35031 ,727,20124,726 ,0,0,0}, + {36526,35024,35023 ,727,726,726 ,0,0,0}, {35030,35024,36526 ,726,726,727 ,0,0,0}, + {36528,36526,35021 ,727,727,20124 ,0,0,0}, {35023,35021,36526 ,726,20124,727 ,0,0,0}, + {35033,36528,35020 ,726,727,727 ,0,0,0}, {36528,35021,35020 ,727,20124,727 ,0,0,0}, + {35038,35039,36623 ,727,727,727 ,0,0,0}, {36528,35033,35036 ,727,726,726 ,0,0,0}, + {36623,36528,35038 ,727,727,727 ,0,0,0}, {37235,35017,36617 ,727,727,726 ,0,0,0}, + {37236,37237,36593 ,726,726,20124 ,0,0,0}, {37238,37239,37240 ,726,727,20124 ,0,0,0}, + {37240,34358,37241 ,20124,727,726 ,0,0,0}, {34614,37242,37243 ,20124,20124,726 ,0,0,0}, + {36562,36969,34622 ,727,726,726 ,0,0,0}, {34686,34684,34352 ,20124,20124,726 ,0,0,0}, + {37242,34614,34613 ,20124,20124,20124 ,0,0,0}, {36591,36622,36620 ,20124,20124,727 ,0,0,0}, + {36614,36608,36620 ,20124,726,727 ,0,0,0}, {35005,36608,35009 ,20124,726,726 ,0,0,0}, + {36623,34999,34998 ,727,20124,727 ,0,0,0}, {35008,36609,35005 ,726,727,20124 ,0,0,0}, + {36621,35002,35001 ,727,726,726 ,0,0,0}, {35008,35002,36621 ,726,726,727 ,0,0,0}, + {36621,35001,36619 ,727,726,727 ,0,0,0}, {36619,34999,36623 ,727,20124,727 ,0,0,0}, + {35011,35014,36618 ,726,726,726 ,0,0,0}, {36623,34998,36618 ,727,727,726 ,0,0,0}, + {35016,37235,35014 ,727,727,726 ,0,0,0}, {36618,35014,37235 ,726,726,727 ,0,0,0}, + {35017,37235,35016 ,727,727,727 ,0,0,0}, {36449,34986,34980 ,20140,20130,1793 ,0,0,0}, + {36448,37244,37245 ,20140,1792,20167 ,0,0,0}, {37246,36352,37247 ,20140,1792,727 ,0,0,0}, + {36352,34995,37247 ,1792,20130,727 ,0,0,0}, {37244,36352,37248 ,1792,1792,20140 ,0,0,0}, + {36352,37246,37248 ,1792,20140,20140 ,0,0,0}, {36448,36352,37244 ,20140,1792,1792 ,0,0,0}, + {37249,36448,37250 ,1792,20140,1793 ,0,0,0}, {36448,37245,37250 ,20140,20167,1793 ,0,0,0}, + {36448,37249,36464 ,20140,1792,20148 ,0,0,0}, {36463,34987,36448 ,1793,20140,20140 ,0,0,0}, + {34983,36449,34987 ,1793,20140,20140 ,0,0,0}, {36448,34987,36449 ,20140,20140,20140 ,0,0,0}, + {36449,34983,34986 ,20140,1793,20130 ,0,0,0}, {34976,36443,36449 ,20167,1792,20140 ,0,0,0}, + {34977,36449,34979 ,20167,20140,726 ,0,0,0}, {36449,34980,34979 ,20140,1793,726 ,0,0,0}, + {36449,34977,34976 ,20140,20167,20167 ,0,0,0}, {34992,36443,34989 ,726,1792,726 ,0,0,0}, + {36443,34976,34989 ,1792,20167,726 ,0,0,0}, {34995,36443,34994 ,20130,1792,727 ,0,0,0}, + {36443,34992,34994 ,1792,726,727 ,0,0,0}, {34955,37251,37252 ,728,726,726 ,0,0,0}, + {34964,36681,37200 ,726,20124,20124 ,0,0,0}, {36733,36680,36679 ,726,726,726 ,0,0,0}, + {36733,36679,36720 ,726,726,726 ,0,0,0}, {36680,36737,36678 ,726,726,729 ,0,0,0}, + {37253,37254,36735 ,726,726,726 ,0,0,0}, {37253,36735,36736 ,726,726,728 ,0,0,0}, + {37255,37254,37256 ,20124,726,726 ,0,0,0}, {37254,37255,36735 ,726,20124,726 ,0,0,0}, + {36738,37256,36739 ,20124,726,726 ,0,0,0}, {37255,37256,36738 ,20124,726,20124 ,0,0,0}, + {36738,34965,37200 ,20124,726,20124 ,0,0,0}, {34961,34964,37200 ,726,726,20124 ,0,0,0}, + {34965,34961,37200 ,726,726,20124 ,0,0,0}, {37252,34958,34957 ,726,729,726 ,0,0,0}, + {34958,37252,36681 ,729,726,20124 ,0,0,0}, {34955,34954,37251 ,728,726,726 ,0,0,0}, + {34957,34955,37252 ,726,728,726 ,0,0,0}, {36732,37251,34967 ,726,726,726 ,0,0,0}, + {34954,34967,37251 ,726,726,726 ,0,0,0}, {36732,34970,36713 ,726,726,726 ,0,0,0}, + {34535,36724,36731 ,726,726,726 ,0,0,0}, {36713,34970,34972 ,726,726,726 ,0,0,0}, + {34148,35963,35938 ,726,726,726 ,0,0,0}, {34936,34934,36114 ,727,727,727 ,0,0,0}, + {34144,35966,35964 ,20124,726,726 ,0,0,0}, {36122,34927,36125 ,727,726,726 ,0,0,0}, + {34926,34924,36126 ,20124,20124,727 ,0,0,0}, {34939,34940,36876 ,726,726,727 ,0,0,0}, + {36219,35943,36221 ,20124,726,20124 ,0,0,0}, {36876,36249,34939 ,727,726,726 ,0,0,0}, + {36128,34924,36270 ,726,20124,20124 ,0,0,0}, {36131,36270,36230 ,726,20124,726 ,0,0,0}, + {34943,34142,36876 ,726,726,727 ,0,0,0}, {34140,34139,34949 ,20124,726,726 ,0,0,0}, + {34142,34943,34945 ,726,726,20124 ,0,0,0}, {34125,34838,34835 ,726,20124,20124 ,0,0,0}, + {34144,37257,37258 ,20124,726,726 ,0,0,0}, {34145,35964,35963 ,20124,726,726 ,0,0,0}, + {34144,35969,35966 ,20124,20124,726 ,0,0,0}, {35972,35970,36259 ,726,726,726 ,0,0,0}, + {35969,37258,36259 ,20124,726,726 ,0,0,0}, {37259,36224,36260 ,20124,727,726 ,0,0,0}, + {36225,37260,36226 ,727,726,727 ,0,0,0}, {37259,36225,36224 ,20124,727,727 ,0,0,0}, + {34044,37261,36253 ,726,726,727 ,0,0,0}, {34900,34058,34902 ,727,726,726 ,0,0,0}, + {34907,36267,36164 ,726,726,726 ,0,0,0}, {34902,36266,34904 ,726,726,727 ,0,0,0}, + {36158,37262,37263 ,726,727,727 ,0,0,0}, {36222,36156,37263 ,727,727,727 ,0,0,0}, + {36152,36153,36265 ,20124,727,727 ,0,0,0}, {36147,34047,36146 ,727,727,726 ,0,0,0}, + {36265,34050,36150 ,727,727,726 ,0,0,0}, {34061,37264,36906 ,726,20124,726 ,0,0,0}, + {35976,35975,36268 ,726,20124,726 ,0,0,0}, {36272,36273,34912 ,20124,727,726 ,0,0,0}, + {36269,37265,34041 ,727,727,726 ,0,0,0}, {36159,37262,36158 ,726,727,726 ,0,0,0}, + {34897,34896,34055 ,726,20124,727 ,0,0,0}, {34893,34056,34894 ,20124,727,20124 ,0,0,0}, + {35980,37266,37267 ,726,20124,20124 ,0,0,0}, {34060,36274,34061 ,726,727,726 ,0,0,0}, + {34914,36897,36272 ,20124,726,20124 ,0,0,0}, {34299,36900,35068 ,726,727,726 ,0,0,0}, + {37225,34918,37268 ,726,726,727 ,0,0,0}, {36898,34914,34915 ,726,20124,726 ,0,0,0}, + {34920,37269,37268 ,726,726,727 ,0,0,0}, {34920,37268,34918 ,726,727,726 ,0,0,0}, + {37270,37271,34307 ,726,727,20124 ,0,0,0}, {37269,36302,37268 ,726,726,727 ,0,0,0}, + {34293,34296,37222 ,20124,726,726 ,0,0,0}, {37272,37273,37274 ,726,726,726 ,0,0,0}, + {37275,37276,37218 ,726,726,727 ,0,0,0}, {36905,37227,36904 ,726,20124,726 ,0,0,0}, + {37277,37278,37279 ,727,727,726 ,0,0,0}, {36900,34299,37280 ,727,726,727 ,0,0,0}, + {36908,37277,37281 ,726,727,727 ,0,0,0}, {37277,36908,37278 ,727,726,727 ,0,0,0}, + {36907,36271,36172 ,727,727,727 ,0,0,0}, {37281,36907,36908 ,727,727,726 ,0,0,0}, + {36271,36909,36170 ,727,727,727 ,0,0,0}, {36168,36910,36165 ,727,727,726 ,0,0,0}, + {36170,36909,36168 ,727,727,727 ,0,0,0}, {34907,36165,36910 ,726,726,727 ,0,0,0}, + {37282,34889,37283 ,20124,726,726 ,0,0,0}, {36889,36290,34313 ,726,726,726 ,0,0,0}, + {36896,37283,36894 ,726,726,726 ,0,0,0}, {34858,36234,34856 ,726,20124,20124 ,0,0,0}, + {34881,34883,34212 ,726,726,20124 ,0,0,0}, {34862,36233,34864 ,726,20124,726 ,0,0,0}, + {34878,34881,34212 ,727,726,20124 ,0,0,0}, {34862,34861,36882 ,726,726,20124 ,0,0,0}, + {34226,37284,37285 ,20124,726,727 ,0,0,0}, {37286,37287,37288 ,726,20124,20124 ,0,0,0}, + {36874,37289,36875 ,726,20124,20124 ,0,0,0}, {36873,36296,36298 ,20124,726,20124 ,0,0,0}, + {36888,37290,34218 ,726,726,20124 ,0,0,0}, {36890,34214,34207 ,20124,726,727 ,0,0,0}, + {37282,37291,34889 ,20124,20124,726 ,0,0,0}, {36896,37282,37283 ,726,20124,726 ,0,0,0}, + {36895,36894,37292 ,726,726,726 ,0,0,0}, {37292,36901,37293 ,726,727,20124 ,0,0,0}, + {37293,36895,37292 ,20124,726,726 ,0,0,0}, {37276,36903,36902 ,726,726,726 ,0,0,0}, + {36901,36903,37293 ,727,726,20124 ,0,0,0}, {37219,37272,37274 ,20124,726,726 ,0,0,0}, + {37276,37275,36903 ,726,726,726 ,0,0,0}, {37272,37294,37273 ,726,20124,726 ,0,0,0}, + {34310,37273,37295 ,726,726,727 ,0,0,0}, {37273,37294,37295 ,726,20124,727 ,0,0,0}, + {37274,37217,37219 ,726,726,20124 ,0,0,0}, {34293,37296,34294 ,20124,20124,20124 ,0,0,0}, + {37275,37226,37227 ,726,726,20124 ,0,0,0}, {34293,37222,37297 ,20124,726,726 ,0,0,0}, + {37298,34308,34307 ,726,726,20124 ,0,0,0}, {37223,36898,36883 ,726,726,726 ,0,0,0}, + {34312,34872,34870 ,726,726,20124 ,0,0,0}, {36279,34130,37299 ,20124,20124,726 ,0,0,0}, + {35955,35959,34229 ,726,20124,726 ,0,0,0}, {36137,36229,36280 ,20124,20124,727 ,0,0,0}, + {37300,36281,34134 ,726,20124,727 ,0,0,0}, {36278,37301,34131 ,726,20124,726 ,0,0,0}, + {36878,37299,34123 ,726,726,726 ,0,0,0}, {36243,34831,34846 ,727,726,727 ,0,0,0}, + {36286,34846,34847 ,20124,727,727 ,0,0,0}, {36285,34847,34850 ,20124,727,726 ,0,0,0}, + {36237,34852,36236 ,726,726,727 ,0,0,0}, {34853,34856,36235 ,20124,20124,20124 ,0,0,0}, + {37286,37288,37302 ,726,20124,726 ,0,0,0}, {37303,34858,37288 ,727,726,20124 ,0,0,0}, + {37288,34858,37302 ,20124,726,726 ,0,0,0}, {37303,37304,36234 ,727,726,20124 ,0,0,0}, + {37287,37284,34226 ,20124,726,20124 ,0,0,0}, {37284,37287,37286 ,726,20124,726 ,0,0,0}, + {36234,34858,37303 ,20124,726,727 ,0,0,0}, {34883,34884,34209 ,726,20124,726 ,0,0,0}, + {34887,34210,34884 ,20124,726,20124 ,0,0,0}, {37305,37306,34223 ,726,726,727 ,0,0,0}, + {37307,34224,37308 ,20124,726,727 ,0,0,0}, {35959,35958,34232 ,20124,727,726 ,0,0,0}, + {35958,37309,37310 ,727,726,726 ,0,0,0}, {34228,35949,34229 ,726,726,726 ,0,0,0}, + {35950,35949,34228 ,20124,726,726 ,0,0,0}, {36877,35952,35950 ,727,727,20124 ,0,0,0}, + {36221,36241,36276 ,20124,726,727 ,0,0,0}, {36877,36241,35952 ,727,726,727 ,0,0,0}, + {36277,37311,37312 ,726,726,726 ,0,0,0}, {36248,37312,34844 ,20124,726,726 ,0,0,0}, + {34845,37312,37311 ,727,726,726 ,0,0,0}, {35893,37313,35894 ,20130,20140,726 ,0,0,0}, + {36375,34814,36368 ,20153,20135,20144 ,0,0,0}, {35922,35920,34452 ,20137,20169,20140 ,0,0,0}, + {36388,34805,36391 ,20162,20135,20163 ,0,0,0}, {34804,34802,36394 ,20164,1792,20133 ,0,0,0}, + {34801,34816,36914 ,726,20136,20130 ,0,0,0}, {34816,36395,36914 ,20136,20140,20130 ,0,0,0}, + {36362,35899,36389 ,20139,20124,20137 ,0,0,0}, {36396,37314,36393 ,20165,20124,20124 ,0,0,0}, + {36395,34817,34820 ,20140,1793,1792 ,0,0,0}, {36354,37314,36396 ,20128,20124,20165 ,0,0,0}, + {34820,34450,36395 ,1792,20133,20140 ,0,0,0}, {34450,34820,34822 ,20133,1792,20131 ,0,0,0}, + {34776,34433,34436 ,20126,20137,1792 ,0,0,0}, {34433,34776,34773 ,20137,20126,20137 ,0,0,0}, + {34828,37315,34448 ,20169,20164,20165 ,0,0,0}, {34452,37316,37317 ,20140,20131,1793 ,0,0,0}, + {34453,35920,35919 ,20137,20169,20147 ,0,0,0}, {34452,35925,35922 ,20140,1792,20137 ,0,0,0}, + {35928,35926,36367 ,727,20137,20133 ,0,0,0}, {35925,37317,36367 ,1792,1793,20133 ,0,0,0}, + {37318,36384,36382 ,1792,1793,20136 ,0,0,0}, {36385,37319,36386 ,1792,20139,20161 ,0,0,0}, + {37318,36385,36384 ,1792,1792,1793 ,0,0,0}, {34408,37320,36390 ,20126,20136,20137 ,0,0,0}, + {34714,34422,34716 ,20126,20126,20127 ,0,0,0}, {34721,36358,36366 ,20127,20134,20143 ,0,0,0}, + {34716,34422,36959 ,20127,20126,20135 ,0,0,0}, {34815,34406,37321 ,20127,20130,20168 ,0,0,0}, + {36372,36374,36380 ,20131,20152,20158 ,0,0,0}, {36380,36379,36378 ,20158,20157,20156 ,0,0,0}, + {34414,34411,37322 ,20158,20146,20173 ,0,0,0}, {37063,36441,37062 ,20139,20147,20167 ,0,0,0}, + {37323,37324,37325 ,20131,20140,20136 ,0,0,0}, {37326,35798,36442 ,20139,20167,1793 ,0,0,0}, + {37327,37325,37324 ,20161,20136,20140 ,0,0,0}, {37327,12921,37061 ,20161,20140,20132 ,0,0,0}, + {36924,36918,34439 ,727,20124,1793 ,0,0,0}, {34438,36925,36923 ,20162,20147,1793 ,0,0,0}, + {36436,34769,34785 ,1793,726,1793 ,0,0,0}, {34786,37328,37043 ,20168,20168,20168 ,0,0,0}, + {37043,34785,34786 ,20168,1793,20168 ,0,0,0}, {37328,34789,36447 ,20168,20125,20130 ,0,0,0}, + {34789,37328,34786 ,20125,20168,20168 ,0,0,0}, {34791,36453,36447 ,20147,20124,20130 ,0,0,0}, + {36445,34795,34797 ,20170,20137,20170 ,0,0,0}, {34791,34792,36453 ,20147,727,20124 ,0,0,0}, + {36453,34795,36445 ,20124,20137,20170 ,0,0,0}, {36446,34797,37062 ,1793,20170,20167 ,0,0,0}, + {36441,36440,37062 ,20147,20124,20167 ,0,0,0}, {36442,35798,36440 ,1793,20167,20124 ,0,0,0}, + {35798,36920,35795 ,20167,1793,20126 ,0,0,0}, {36920,35798,37326 ,1793,20167,20139 ,0,0,0}, + {37329,35795,36919 ,1792,20126,20126 ,0,0,0}, {35796,37329,37058 ,20125,1792,20139 ,0,0,0}, + {37329,35796,35795 ,1792,20125,20126 ,0,0,0}, {35793,36922,35800 ,20170,20137,20167 ,0,0,0}, + {37059,35908,35906 ,20125,20139,20125 ,0,0,0}, {36922,35906,35800 ,20137,20125,20167 ,0,0,0}, + {36389,36444,36915 ,20137,20126,20126 ,0,0,0}, {37059,36444,35908 ,20125,20126,20139 ,0,0,0}, + {36916,37330,37331 ,20126,20168,20125 ,0,0,0}, {36392,37331,34782 ,20124,20125,726 ,0,0,0}, + {34783,37331,37330 ,20137,20125,20168 ,0,0,0}, {34743,36424,36434 ,20137,20137,20139 ,0,0,0}, + {34400,36435,37049 ,20140,20125,1793 ,0,0,0}, {34396,36427,37332 ,20148,20139,1793 ,0,0,0}, + {34396,37332,37048 ,20148,1793,20139 ,0,0,0}, {37052,36431,34746 ,20125,1793,20126 ,0,0,0}, + {34743,36434,37052 ,20137,20139,20125 ,0,0,0}, {34743,34742,36424 ,20137,20124,20137 ,0,0,0}, + {34739,36426,34740 ,726,20162,1792 ,0,0,0}, {36422,37056,37055 ,20170,1793,20130 ,0,0,0}, + {34754,34755,36933 ,1793,20168,20137 ,0,0,0}, {34754,36933,34739 ,1793,20137,726 ,0,0,0}, + {34758,35784,34755 ,20125,20167,20168 ,0,0,0}, {35784,34760,35781 ,20167,20147,20139 ,0,0,0}, + {34760,35784,34758 ,20147,20167,20125 ,0,0,0}, {34760,34761,35781 ,20147,727,20139 ,0,0,0}, + {35779,35782,34766 ,1793,20137,20170 ,0,0,0}, {36423,36425,34766 ,20139,20139,20170 ,0,0,0}, + {36422,36421,37056 ,20170,20147,1793 ,0,0,0}, {37055,37057,37053 ,20130,20139,20147 ,0,0,0}, + {36936,37054,36934 ,20126,1793,20126 ,0,0,0}, {37053,37057,37054 ,20147,20139,1793 ,0,0,0}, + {36935,36934,36411 ,20162,20126,1792 ,0,0,0}, {36420,36913,36412 ,20137,20130,20139 ,0,0,0}, + {36938,36935,36411 ,20147,20162,1792 ,0,0,0}, {36913,36420,36419 ,20130,20137,20167 ,0,0,0}, + {36418,36350,36419 ,20137,20125,20167 ,0,0,0}, {36419,36350,34394 ,20167,20125,1792 ,0,0,0}, + {36417,37333,36415 ,20168,20135,20169 ,0,0,0}, {37334,34392,34391 ,20168,20168,1793 ,0,0,0}, + {36940,37335,34729 ,20135,726,20131 ,0,0,0}, {37336,36409,34380 ,1793,20133,20133 ,0,0,0}, + {34727,34729,37335 ,1792,20131,726 ,0,0,0}, {34396,34750,34748 ,20148,20140,20137 ,0,0,0}, + {36359,35932,35931 ,20136,1793,20148 ,0,0,0}, {37337,37338,37339 ,20128,1793,20167 ,0,0,0}, + {37335,36356,34727 ,726,20131,1792 ,0,0,0}, {36361,37340,34405 ,20128,20169,20131 ,0,0,0}, + {37341,36377,36376 ,20174,20155,20154 ,0,0,0}, {34711,34710,34419 ,20135,20164,20133 ,0,0,0}, + {34707,34420,34708 ,726,20138,1792 ,0,0,0}, {35936,37342,37343 ,20169,727,727 ,0,0,0}, + {34424,36357,34425 ,20130,20132,20130 ,0,0,0}, {34383,36403,34386 ,20127,20134,20161 ,0,0,0}, + {36941,34729,34730 ,20168,20131,20139 ,0,0,0}, {36413,36937,37344 ,1792,20164,726 ,0,0,0}, + {36413,34733,34735 ,1792,20165,20169 ,0,0,0}, {34392,34753,34752 ,20168,20137,726 ,0,0,0}, + {34380,37344,37336 ,20133,726,1793 ,0,0,0}, {34377,34380,36409 ,20136,20133,20133 ,0,0,0}, + {37333,36941,36415 ,20135,20168,20169 ,0,0,0}, {37345,36943,36945 ,20130,20126,20148 ,0,0,0}, + {36405,36944,36406 ,20167,20139,20167 ,0,0,0}, {36948,12820,36404 ,1792,20140,20165 ,0,0,0}, + {36950,34383,34382 ,20162,20127,20135 ,0,0,0}, {36397,36951,37346 ,20132,20148,20139 ,0,0,0}, + {34375,36952,36949 ,20165,20132,20131 ,0,0,0}, {36401,36399,36398 ,20137,20166,20137 ,0,0,0}, + {36398,36397,37346 ,20137,20132,20139 ,0,0,0}, {36402,37339,36400 ,20138,20167,20167 ,0,0,0}, + {36401,36400,36399 ,20137,20167,20166 ,0,0,0}, {37337,36954,37338 ,20128,20169,1793 ,0,0,0}, + {36402,37337,37339 ,20138,20128,20167 ,0,0,0}, {36956,36955,36957 ,20171,20168,20172 ,0,0,0}, + {37338,36954,36956 ,1793,20169,20171 ,0,0,0}, {36365,36955,34721 ,20142,20168,20127 ,0,0,0}, + {37347,34358,37240 ,20124,727,20124 ,0,0,0}, {37348,35859,35864 ,726,726,727 ,0,0,0}, + {34117,35867,35871 ,726,726,20124 ,0,0,0}, {37243,37349,34616 ,726,20124,20124 ,0,0,0}, + {34616,37349,34617 ,20124,20124,726 ,0,0,0}, {36592,37236,36593 ,727,726,20124 ,0,0,0}, + {36595,34355,37350 ,726,726,726 ,0,0,0}, {36575,36535,34692 ,20124,727,727 ,0,0,0}, + {36575,34693,34696 ,20124,727,726 ,0,0,0}, {36044,34698,36042 ,20124,726,20124 ,0,0,0}, + {34699,34702,36040 ,20124,20124,727 ,0,0,0}, {34704,36036,36037 ,726,726,726 ,0,0,0}, + {36570,37351,36571 ,726,20124,20124 ,0,0,0}, {34114,37351,36531 ,20124,20124,726 ,0,0,0}, + {37351,36570,36531 ,20124,726,726 ,0,0,0}, {36036,34704,36971 ,726,726,727 ,0,0,0}, + {36582,36581,37352 ,727,20124,20124 ,0,0,0}, {36036,36971,36034 ,726,727,726 ,0,0,0}, + {34100,34662,34665 ,20124,727,726 ,0,0,0}, {34112,37353,37354 ,726,727,20124 ,0,0,0}, + {37355,36569,34652 ,726,726,20124 ,0,0,0}, {35871,35870,34120 ,20124,727,726 ,0,0,0}, + {35870,37356,37357 ,727,726,726 ,0,0,0}, {34116,35861,34117 ,726,726,726 ,0,0,0}, + {35862,35861,34116 ,20124,726,726 ,0,0,0}, {36970,35864,35862 ,727,727,20124 ,0,0,0}, + {36589,37348,36590 ,20124,726,727 ,0,0,0}, {36970,37348,35864 ,727,726,727 ,0,0,0}, + {36588,37358,37359 ,726,726,726 ,0,0,0}, {36529,37359,34690 ,20124,726,726 ,0,0,0}, + {34691,37359,37358 ,727,726,726 ,0,0,0}, {37360,35988,35986 ,726,726,20124 ,0,0,0}, + {35985,36574,35986 ,726,726,20124 ,0,0,0}, {35991,36563,36973 ,726,726,727 ,0,0,0}, + {37355,34652,34649 ,726,20124,20124 ,0,0,0}, {34667,34097,34100 ,726,726,20124 ,0,0,0}, + {34661,37361,34645 ,727,20124,726 ,0,0,0}, {34646,34645,36566 ,726,726,20124 ,0,0,0}, + {34667,34100,34665 ,726,20124,726 ,0,0,0}, {37361,34662,34100 ,20124,727,20124 ,0,0,0}, + {36583,37362,36581 ,726,726,20124 ,0,0,0}, {37363,37364,34111 ,726,726,727 ,0,0,0}, + {37365,36972,36030 ,20124,20124,726 ,0,0,0}, {36567,36568,36025 ,20124,726,726 ,0,0,0}, + {36022,36568,34106 ,726,726,20124 ,0,0,0}, {34102,36016,34103 ,726,726,726 ,0,0,0}, + {35982,34095,35985 ,726,727,726 ,0,0,0}, {35986,36574,37360 ,20124,726,726 ,0,0,0}, + {35988,37360,36563 ,726,726,726 ,0,0,0}, {36973,36974,35992 ,727,726,20124 ,0,0,0}, + {35997,36974,36585 ,726,726,726 ,0,0,0}, {35992,36974,35994 ,20124,726,20124 ,0,0,0}, + {36000,35998,36584 ,20124,20124,727 ,0,0,0}, {35998,35997,36585 ,20124,726,726 ,0,0,0}, + {36976,36565,36564 ,726,726,20124 ,0,0,0}, {36565,36976,36975 ,726,726,726 ,0,0,0}, + {36977,36979,36975 ,20124,727,726 ,0,0,0}, {36975,36979,34198 ,726,727,726 ,0,0,0}, + {36964,37366,36965 ,726,726,726 ,0,0,0}, {34659,34658,34196 ,727,726,726 ,0,0,0}, + {34604,37367,37368 ,20124,726,20124 ,0,0,0}, {37369,37367,36981 ,726,726,726 ,0,0,0}, + {34602,34604,37368 ,726,20124,20124 ,0,0,0}, {34200,34656,34654 ,726,726,20124 ,0,0,0}, + {35850,35849,37370 ,726,20124,20124 ,0,0,0}, {34372,35875,35850 ,726,726,726 ,0,0,0}, + {35876,34368,35878 ,726,20124,726 ,0,0,0}, {34617,37349,34620 ,726,20124,727 ,0,0,0}, + {37349,36562,34620 ,20124,727,727 ,0,0,0}, {34613,34629,37371 ,20124,726,726 ,0,0,0}, + {37243,34616,34614 ,726,20124,20124 ,0,0,0}, {36960,34629,34630 ,727,726,726 ,0,0,0}, + {36960,37371,34629 ,727,726,726 ,0,0,0}, {36960,34630,34633 ,727,726,726 ,0,0,0}, + {37371,37242,34613 ,726,20124,20124 ,0,0,0}, {34680,34350,34349 ,726,726,726 ,0,0,0}, + {34681,34349,34684 ,20124,726,20124 ,0,0,0}, {34364,34363,34639 ,20124,726,726 ,0,0,0}, + {34368,37372,37373 ,20124,726,726 ,0,0,0}, {34369,35876,35875 ,20124,726,726 ,0,0,0}, + {34368,35881,35878 ,20124,20124,726 ,0,0,0}, {35884,35882,36542 ,726,726,726 ,0,0,0}, + {35881,37373,36542 ,20124,726,726 ,0,0,0}, {37374,36550,36546 ,20124,727,726 ,0,0,0}, + {36548,37375,36549 ,727,726,727 ,0,0,0}, {37374,36548,36550 ,20124,727,727 ,0,0,0}, + {34268,37376,36604 ,726,726,727 ,0,0,0}, {34592,34590,34282 ,726,727,726 ,0,0,0}, + {34594,34592,36553 ,727,726,727 ,0,0,0}, {34592,34282,36553 ,726,726,727 ,0,0,0}, + {37377,37378,37379 ,726,726,727 ,0,0,0}, {37378,37377,37380 ,726,726,727 ,0,0,0}, + {37381,34274,37382 ,726,727,727 ,0,0,0}, {36545,36544,37380 ,727,726,727 ,0,0,0}, + {37382,34271,37383 ,727,727,726 ,0,0,0}, {34263,36607,34270 ,726,20124,726 ,0,0,0}, + {37384,36603,34285 ,20124,726,726 ,0,0,0}, {37385,37386,37387 ,727,726,20124 ,0,0,0}, + {37368,36601,34602 ,20124,727,726 ,0,0,0}, {36541,37388,34265 ,727,727,726 ,0,0,0}, + {36992,36991,37377 ,726,727,726 ,0,0,0}, {34587,34586,34279 ,726,20124,727 ,0,0,0}, + {34583,34280,34584 ,20124,727,20124 ,0,0,0}, {35892,37389,37390 ,726,20124,20124 ,0,0,0}, + {34284,36602,34285 ,726,727,726 ,0,0,0}, {37391,36984,34186 ,727,726,726 ,0,0,0}, + {36981,34604,34605 ,726,20124,726 ,0,0,0}, {36586,36587,37392 ,727,726,726 ,0,0,0}, + {36586,34608,34610 ,727,726,726 ,0,0,0}, {37393,37394,34181 ,726,726,20124 ,0,0,0}, + {37395,37393,34184 ,726,726,726 ,0,0,0}, {34184,37392,37395 ,726,726,726 ,0,0,0}, + {34181,34184,37393 ,20124,726,726 ,0,0,0}, {36981,36965,37366 ,726,726,726 ,0,0,0}, + {36006,36004,36982 ,726,726,726 ,0,0,0}, {36009,36983,36538 ,726,726,727 ,0,0,0}, + {36600,36537,34190 ,726,20124,727 ,0,0,0}, {36985,36599,34187 ,726,726,726 ,0,0,0}, + {37396,37391,34179 ,727,727,20124 ,0,0,0}, {37397,36986,36963 ,727,726,727 ,0,0,0}, + {36986,37396,36987 ,726,727,726 ,0,0,0}, {36961,37387,36962 ,727,20124,726 ,0,0,0}, + {36963,36962,37397 ,727,726,727 ,0,0,0}, {37385,36560,37386 ,727,727,726 ,0,0,0}, + {36961,37385,37387 ,727,727,20124 ,0,0,0}, {36559,36558,36988 ,727,727,727 ,0,0,0}, + {37386,36560,36559 ,726,727,727 ,0,0,0}, {36552,36989,34597 ,726,727,726 ,0,0,0}, + {36988,36558,36989 ,727,727,727 ,0,0,0}, {34092,34089,35831 ,726,726,726 ,0,0,0}, + {35805,37398,35806 ,726,726,728 ,0,0,0}, {34088,35834,35832 ,726,726,726 ,0,0,0}, + {36106,34557,36104 ,726,726,726 ,0,0,0}, {34556,34554,36101 ,726,726,726 ,0,0,0}, + {34553,34568,36998 ,726,726,726 ,0,0,0}, {36716,35811,36198 ,726,726,726 ,0,0,0}, + {36244,36998,34568 ,726,726,726 ,0,0,0}, {36244,34572,34086 ,726,729,726 ,0,0,0}, + {36100,34554,36994 ,726,726,726 ,0,0,0}, {36098,36994,37000 ,726,726,726 ,0,0,0}, + {34084,34083,34578 ,728,726,726 ,0,0,0}, {34086,34572,34574 ,726,729,726 ,0,0,0}, + {34072,34466,34069 ,726,726,726 ,0,0,0}, {34088,37399,37400 ,726,726,726 ,0,0,0}, + {34089,35832,35831 ,726,726,726 ,0,0,0}, {34088,35837,35834 ,726,726,726 ,0,0,0}, + {35840,35838,36712 ,726,726,726 ,0,0,0}, {35837,37400,36712 ,726,726,726 ,0,0,0}, + {37401,36728,36718 ,726,726,726 ,0,0,0}, {36729,37402,36727 ,726,726,726 ,0,0,0}, + {37401,36729,36728 ,726,726,726 ,0,0,0}, {34324,37403,36725 ,726,726,726 ,0,0,0}, + {36726,37404,34324 ,726,729,726 ,0,0,0}, {34530,34338,36723 ,726,726,726 ,0,0,0}, + {34321,34324,37404 ,726,726,729 ,0,0,0}, {34532,34530,36723 ,726,726,726 ,0,0,0}, + {34532,36724,34534 ,726,726,726 ,0,0,0}, {36722,36721,37405 ,728,726,726 ,0,0,0}, + {34973,37406,34330 ,729,726,726 ,0,0,0}, {37407,37406,34973 ,726,726,729 ,0,0,0}, + {34326,36714,34327 ,726,726,726 ,0,0,0}, {35844,35843,37036 ,726,726,729 ,0,0,0}, + {34537,34538,34333 ,726,726,726 ,0,0,0}, {36245,36189,34541 ,726,726,729 ,0,0,0}, + {37404,37041,34321 ,729,726,726 ,0,0,0}, {34528,34525,34338 ,728,726,726 ,0,0,0}, + {34525,34524,34335 ,726,726,726 ,0,0,0}, {34521,34336,34522 ,726,726,726 ,0,0,0}, + {35848,37408,37409 ,726,726,726 ,0,0,0}, {34340,36190,34341 ,726,726,726 ,0,0,0}, + {36251,34544,37410 ,726,726,726 ,0,0,0}, {36251,34543,34544 ,726,726,726 ,0,0,0}, + {34237,34240,37016 ,726,726,726 ,0,0,0}, {37411,37017,34549 ,726,726,726 ,0,0,0}, + {37017,37410,34547 ,726,726,726 ,0,0,0}, {34505,34504,34252 ,726,729,726 ,0,0,0}, + {37412,37015,34240 ,726,726,726 ,0,0,0}, {37411,37412,37017 ,726,726,726 ,0,0,0}, + {37413,36707,36706 ,726,726,726 ,0,0,0}, {37414,36696,36700 ,726,726,728 ,0,0,0}, + {37415,37019,37021 ,726,726,726 ,0,0,0}, {37415,37023,37022 ,726,726,726 ,0,0,0}, + {37416,37026,34243 ,726,726,728 ,0,0,0}, {37417,37027,34235 ,729,726,726 ,0,0,0}, + {37418,37032,37034 ,726,726,726 ,0,0,0}, {37032,37417,37033 ,726,729,726 ,0,0,0}, + {37418,37419,37031 ,726,726,726 ,0,0,0}, {37419,37418,37034 ,726,726,726 ,0,0,0}, + {37029,37420,37030 ,726,729,726 ,0,0,0}, {37419,37029,37031 ,726,726,726 ,0,0,0}, + {37038,37037,37420 ,726,729,729 ,0,0,0}, {37030,37420,37037 ,726,729,729 ,0,0,0}, + {37037,37039,36730 ,729,726,726 ,0,0,0}, {34535,36730,37039 ,726,726,726 ,0,0,0}, + {37421,37011,37422 ,729,726,726 ,0,0,0}, {37009,37008,37422 ,726,726,726 ,0,0,0}, + {36694,37010,37012 ,726,726,726 ,0,0,0}, {37423,34495,34494 ,726,728,726 ,0,0,0}, + {34485,34487,36062 ,726,728,726 ,0,0,0}, {34492,37424,37423 ,726,726,726 ,0,0,0}, + {34492,37423,34494 ,726,726,726 ,0,0,0}, {34510,34512,34156 ,726,726,726 ,0,0,0}, + {36682,34507,34156 ,726,726,726 ,0,0,0}, {34492,34491,37424 ,726,726,726 ,0,0,0}, + {36186,37425,36187 ,726,728,726 ,0,0,0}, {37426,37004,37427 ,726,729,726 ,0,0,0}, + {37428,36684,36070 ,726,726,726 ,0,0,0}, {36683,37005,36074 ,726,726,726 ,0,0,0}, + {37429,37005,34162 ,726,726,726 ,0,0,0}, {36690,34158,34151 ,729,726,726 ,0,0,0}, + {37009,37430,34518 ,726,726,728 ,0,0,0}, {37422,37008,37421 ,726,726,729 ,0,0,0}, + {37011,37421,37012 ,726,729,726 ,0,0,0}, {36693,36692,37013 ,726,729,726 ,0,0,0}, + {37010,36694,36693 ,726,726,726 ,0,0,0}, {37013,36697,37431 ,726,728,726 ,0,0,0}, + {36696,36695,36700 ,726,726,728 ,0,0,0}, {36696,37431,36697 ,726,726,728 ,0,0,0}, + {37413,36699,36698 ,726,729,726 ,0,0,0}, {36699,37413,36706 ,729,726,726 ,0,0,0}, + {36698,36700,36695 ,726,728,726 ,0,0,0}, {36706,36705,34254 ,726,726,726 ,0,0,0}, + {37432,37433,37434 ,726,726,726 ,0,0,0}, {37434,37433,37021 ,726,726,726 ,0,0,0}, + {34237,37016,37435 ,726,726,726 ,0,0,0}, {37436,34252,34251 ,729,726,726 ,0,0,0}, + {37018,36251,36997 ,726,726,726 ,0,0,0}, {34256,34502,34500 ,726,726,726 ,0,0,0}, + {36080,34074,36078 ,726,726,729 ,0,0,0}, {35823,35827,34173 ,729,728,728 ,0,0,0}, + {36092,36999,36247 ,726,726,728 ,0,0,0}, {36086,36246,34078 ,729,726,726 ,0,0,0}, + {36082,36083,34075 ,726,726,726 ,0,0,0}, {36046,36078,34067 ,726,729,728 ,0,0,0}, + {36050,36049,34459 ,726,726,726 ,0,0,0}, {36052,34475,34476 ,726,726,726 ,0,0,0}, + {36055,34476,34479 ,726,726,726 ,0,0,0}, {36056,34481,36058 ,726,726,726 ,0,0,0}, + {34482,34485,36061 ,726,726,726 ,0,0,0}, {37426,37427,34487 ,726,726,728 ,0,0,0}, + {34487,36064,36062 ,728,726,726 ,0,0,0}, {36685,36067,36064 ,726,726,726 ,0,0,0}, + {37427,37004,37003 ,726,729,726 ,0,0,0}, {37003,37001,34170 ,726,726,726 ,0,0,0}, + {36685,34487,37427 ,726,728,726 ,0,0,0}, {34512,34513,34153 ,726,726,726 ,0,0,0}, + {34516,34154,34513 ,726,726,726 ,0,0,0}, {37437,37438,34167 ,729,728,726 ,0,0,0}, + {37439,34168,37440 ,726,726,726 ,0,0,0}, {35827,35826,34176 ,728,726,726 ,0,0,0}, + {35826,37441,37442 ,726,726,726 ,0,0,0}, {34172,35817,34173 ,726,726,728 ,0,0,0}, + {35818,35817,34172 ,726,726,726 ,0,0,0}, {36702,35820,35818 ,726,726,726 ,0,0,0}, + {36198,36701,36703 ,726,726,726 ,0,0,0}, {36702,36701,35820 ,726,726,726 ,0,0,0}, + {36704,37443,37444 ,726,729,726 ,0,0,0}, {36710,37444,34472 ,726,726,729 ,0,0,0}, + {34473,37444,37443 ,726,726,729 ,0,0,0}, {34772,34434,34433 ,20124,1792,20137 ,0,0,0}, + {37324,36353,36355 ,20140,20127,20129 ,0,0,0}, {35896,35899,36362 ,20137,20124,20139 ,0,0,0}, + {36355,36354,36396 ,20129,20128,20165 ,0,0,0}, {37323,36353,37324 ,20131,20127,20140 ,0,0,0}, + {37061,37325,37327 ,20132,20136,20161 ,0,0,0}, {34431,34434,34770 ,20168,1792,1792 ,0,0,0}, + {37060,12921,34442 ,20137,20140,20167 ,0,0,0}, {34439,36918,34442 ,1793,20124,20167 ,0,0,0}, + {36917,37060,34442 ,20137,20137,20167 ,0,0,0}, {34769,34431,34770 ,726,20168,1792 ,0,0,0}, + {34438,36924,34439 ,20162,727,1793 ,0,0,0}, {34438,34431,36925 ,20162,20168,20147 ,0,0,0}, + {34431,34769,36437 ,20168,726,20130 ,0,0,0}, {34433,34773,34772 ,20137,20137,20124 ,0,0,0}, + {36389,35903,36444 ,20137,20162,20126 ,0,0,0}, {34780,34778,36392 ,20140,20137,20124 ,0,0,0}, + {36392,34782,34780 ,20124,726,20140 ,0,0,0}, {37330,36916,36915 ,20168,20126,20126 ,0,0,0}, + {37331,34783,34782 ,20125,20137,726 ,0,0,0}, {36389,35899,35902 ,20137,20124,726 ,0,0,0}, + {35893,35896,36363 ,20130,20137,20140 ,0,0,0}, {34456,35894,37313 ,20148,726,20140 ,0,0,0}, + {37313,35893,36363 ,20140,20130,20140 ,0,0,0}, {35920,34453,34452 ,20169,20137,20140 ,0,0,0}, + {37316,34445,37315 ,20131,20135,20164 ,0,0,0}, {35925,34452,37317 ,1792,20140,1793 ,0,0,0}, + {34452,34445,37316 ,20140,20135,20131 ,0,0,0}, {34828,34448,34826 ,20169,20165,20165 ,0,0,0}, + {34445,34448,37315 ,20135,20165,20164 ,0,0,0}, {34826,34447,34823 ,20165,20134,20139 ,0,0,0}, + {34822,34447,34450 ,20131,20134,20133 ,0,0,0}, {34422,34714,34711 ,20126,20126,20135 ,0,0,0}, + {37321,34406,37340 ,20168,20130,20169 ,0,0,0}, {37341,36364,36377 ,20174,20141,20155 ,0,0,0}, + {36364,36366,36377 ,20141,20143,20155 ,0,0,0}, {36379,36376,36378 ,20157,20154,20156 ,0,0,0}, + {36374,36381,36380 ,20152,20159,20158 ,0,0,0}, {36373,36372,34414 ,20151,20131,20158 ,0,0,0}, + {37445,37322,34411 ,20175,20173,20146 ,0,0,0}, {37322,36373,34414 ,20173,20151,20158 ,0,0,0}, + {34406,34815,34403 ,20130,20127,20143 ,0,0,0}, {34410,37446,36369 ,1793,20139,20145 ,0,0,0}, + {34411,36369,37445 ,20146,20145,20175 ,0,0,0}, {34815,36371,34403 ,20127,20150,20143 ,0,0,0}, + {34403,36371,36370 ,20143,20150,20149 ,0,0,0}, {37446,34410,36370 ,20139,1793,20149 ,0,0,0}, + {34406,34405,37340 ,20130,20131,20169 ,0,0,0}, {37447,36390,37320 ,20137,20137,20136 ,0,0,0}, + {36958,35928,36382 ,20132,727,20136 ,0,0,0}, {37319,37320,36386 ,20139,20136,20161 ,0,0,0}, + {37320,37319,37447 ,20136,20139,20137 ,0,0,0}, {36382,36384,36958 ,20136,1793,20132 ,0,0,0}, + {36958,35931,35928 ,20132,20148,727 ,0,0,0}, {35934,37342,35936 ,20137,727,20169 ,0,0,0}, + {37342,35934,36359 ,727,20137,20136 ,0,0,0}, {34428,35936,37343 ,20138,20169,727 ,0,0,0}, + {34417,34724,34424 ,1793,1793,20130 ,0,0,0}, {34425,36357,36953 ,20130,20132,20165 ,0,0,0}, + {34724,36356,34424 ,1793,20131,20130 ,0,0,0}, {34417,34707,34723 ,1793,726,20136 ,0,0,0}, + {34420,34419,34708 ,20138,20133,1792 ,0,0,0}, {34417,34420,34707 ,1793,20138,726 ,0,0,0}, + {34711,34419,34422 ,20135,20133,20126 ,0,0,0}, {34708,34419,34710 ,1792,20133,20164 ,0,0,0}, + {34391,36351,37448 ,1793,20126,20126 ,0,0,0}, {34378,34377,36946 ,20132,20136,1792 ,0,0,0}, + {37345,36939,36943 ,20130,20168,20126 ,0,0,0}, {36939,36410,36943 ,20168,20168,20126 ,0,0,0}, + {36405,36945,36944 ,20167,20148,20139 ,0,0,0}, {36948,36407,36406 ,1792,20126,20167 ,0,0,0}, + {36404,12820,34386 ,20165,20140,20161 ,0,0,0}, {34375,34378,36947 ,20165,20132,1792 ,0,0,0}, + {37449,36403,34383 ,20170,20134,20127 ,0,0,0}, {37449,34383,36950 ,20170,20127,20162 ,0,0,0}, + {37346,34375,36947 ,20139,20165,1792 ,0,0,0}, {37346,36951,34375 ,20139,20148,20165 ,0,0,0}, + {34382,34375,36949 ,20135,20165,20131 ,0,0,0}, {34377,36408,36946 ,20136,20136,1792 ,0,0,0}, + {37450,37336,37344 ,20131,1793,726 ,0,0,0}, {36941,36940,34729 ,20168,20135,20131 ,0,0,0}, + {37344,36937,37450 ,726,20164,20131 ,0,0,0}, {34733,36414,34730 ,20165,20133,20139 ,0,0,0}, + {36941,37333,36942 ,20168,20135,20133 ,0,0,0}, {37050,36417,36416 ,20168,20168,20128 ,0,0,0}, + {37051,37050,36416 ,20140,20168,20128 ,0,0,0}, {34400,37049,37051 ,20140,1793,20140 ,0,0,0}, + {34750,34389,34752 ,20140,20124,726 ,0,0,0}, {36427,34396,34748 ,20139,20148,20137 ,0,0,0}, + {34396,37048,34397 ,20148,20139,20168 ,0,0,0}, {34396,34389,34750 ,20148,20124,20140 ,0,0,0}, + {34753,34392,37334 ,20137,20168,20168 ,0,0,0}, {34389,34392,34752 ,20124,20168,726 ,0,0,0}, + {37334,34391,37448 ,20168,1793,20126 ,0,0,0}, {36351,34391,34394 ,20126,1793,1792 ,0,0,0}, + {34678,34350,34680 ,726,726,726 ,0,0,0}, {37236,37243,37237 ,726,726,726 ,0,0,0}, + {36968,35852,35855 ,20124,20124,726 ,0,0,0}, {37237,37243,37242 ,726,726,20124 ,0,0,0}, + {34347,34350,34678 ,726,726,726 ,0,0,0}, {36593,37239,37238 ,20124,727,726 ,0,0,0}, + {37238,36591,36593 ,726,20124,20124 ,0,0,0}, {37240,37239,37347 ,20124,727,20124 ,0,0,0}, + {34355,36594,37241 ,726,726,726 ,0,0,0}, {34358,34355,37241 ,727,726,726 ,0,0,0}, + {34347,34678,34677 ,726,726,726 ,0,0,0}, {34355,34354,37350 ,726,20124,726 ,0,0,0}, + {34355,36595,36594 ,726,726,726 ,0,0,0}, {34677,36535,34347 ,726,727,726 ,0,0,0}, + {37350,34347,36535 ,726,726,727 ,0,0,0}, {34354,34347,37350 ,20124,726,726 ,0,0,0}, + {34349,34681,34680 ,726,20124,726 ,0,0,0}, {36589,35859,37348 ,20124,726,726 ,0,0,0}, + {34688,34686,36529 ,726,20124,20124 ,0,0,0}, {36529,34690,34688 ,20124,726,726 ,0,0,0}, + {37358,36588,36590 ,726,726,727 ,0,0,0}, {37359,34691,34690 ,726,727,726 ,0,0,0}, + {36589,35855,35858 ,20124,726,20124 ,0,0,0}, {35849,35852,36967 ,20124,20124,727 ,0,0,0}, + {34372,35850,37370 ,726,726,20124 ,0,0,0}, {37370,35849,36967 ,20124,20124,727 ,0,0,0}, + {35876,34369,34368 ,726,20124,20124 ,0,0,0}, {37372,34361,36605 ,726,726,726 ,0,0,0}, + {35881,34368,37373 ,20124,20124,726 ,0,0,0}, {34368,34361,37372 ,20124,726,726 ,0,0,0}, + {34641,34364,34639 ,726,20124,726 ,0,0,0}, {34361,34364,36605 ,726,20124,726 ,0,0,0}, + {34639,34363,34636 ,726,726,726 ,0,0,0}, {34635,34363,34366 ,20124,726,726 ,0,0,0}, + {34567,34322,37040 ,726,726,726 ,0,0,0}, {36731,37405,36721 ,726,726,726 ,0,0,0}, + {35844,37036,35846 ,726,729,726 ,0,0,0}, {36731,36721,36730 ,726,726,726 ,0,0,0}, + {34322,34567,34319 ,726,726,726 ,0,0,0}, {36722,37407,36734 ,728,726,726 ,0,0,0}, + {36734,36720,36722 ,726,726,728 ,0,0,0}, {37407,34973,36734 ,726,729,726 ,0,0,0}, + {34330,34327,34972 ,726,726,726 ,0,0,0}, {34972,34973,34330 ,726,729,726 ,0,0,0}, + {34319,34567,36711 ,726,726,726 ,0,0,0}, {34327,36713,34972 ,726,726,726 ,0,0,0}, + {36711,34326,34319 ,726,726,726 ,0,0,0}, {36714,34326,36711 ,726,726,726 ,0,0,0}, + {34322,34321,37041 ,726,726,726 ,0,0,0}, {37451,36725,37403 ,726,726,726 ,0,0,0}, + {37035,35840,36718 ,726,726,726 ,0,0,0}, {37402,37403,36727 ,726,726,726 ,0,0,0}, + {37403,37402,37451 ,726,726,726 ,0,0,0}, {36718,36728,37035 ,726,726,726 ,0,0,0}, + {37035,35843,35840 ,726,726,726 ,0,0,0}, {35846,37408,35848 ,726,726,726 ,0,0,0}, + {37408,35846,37036 ,726,726,729 ,0,0,0}, {34344,35848,37409 ,726,726,726 ,0,0,0}, + {34333,34538,34340 ,726,726,726 ,0,0,0}, {34341,36190,36719 ,726,726,726 ,0,0,0}, + {34538,36189,34340 ,726,726,726 ,0,0,0}, {34333,34521,34537 ,726,726,726 ,0,0,0}, + {34336,34335,34522 ,726,726,726 ,0,0,0}, {34333,34336,34521 ,726,726,726 ,0,0,0}, + {34525,34335,34338 ,726,726,726 ,0,0,0}, {34522,34335,34524 ,726,726,726 ,0,0,0}, + {37270,34310,37295 ,726,726,727 ,0,0,0}, {37452,34294,37296 ,727,20124,20124 ,0,0,0}, + {37226,37275,37217 ,726,726,726 ,0,0,0}, {37275,37218,37217 ,726,727,726 ,0,0,0}, + {34291,34294,37452 ,20124,20124,727 ,0,0,0}, {36904,37224,35064 ,726,727,727 ,0,0,0}, + {35064,35077,36904 ,727,726,726 ,0,0,0}, {35065,37224,36872 ,20124,727,20124 ,0,0,0}, + {35067,34302,34299 ,726,727,726 ,0,0,0}, {34291,37452,37279 ,20124,727,726 ,0,0,0}, + {35068,35067,34299 ,726,726,726 ,0,0,0}, {34299,34298,37280 ,726,726,727 ,0,0,0}, + {37279,37278,34291 ,726,727,20124 ,0,0,0}, {37280,34291,37278 ,727,20124,727 ,0,0,0}, + {34298,34291,37280 ,726,20124,727 ,0,0,0}, {34293,37297,37296 ,20124,726,20124 ,0,0,0}, + {37453,36303,36302 ,726,726,726 ,0,0,0}, {36898,36897,34914 ,726,726,20124 ,0,0,0}, + {36302,37269,37453 ,726,726,726 ,0,0,0}, {34918,37225,34915 ,726,726,726 ,0,0,0}, + {36898,37223,36899 ,726,726,726 ,0,0,0}, {36892,36885,36884 ,20124,726,726 ,0,0,0}, + {36893,36892,36884 ,20124,20124,726 ,0,0,0}, {34316,36291,36893 ,20124,726,20124 ,0,0,0}, + {34872,34305,34874 ,726,20124,726 ,0,0,0}, {36284,34312,34870 ,726,726,20124 ,0,0,0}, + {34312,36889,34313 ,726,726,726 ,0,0,0}, {34312,34305,34872 ,726,20124,726 ,0,0,0}, + {34875,34308,37298 ,727,726,726 ,0,0,0}, {34305,34308,34874 ,20124,726,726 ,0,0,0}, + {37298,34307,37271 ,726,20124,727 ,0,0,0}, {37270,34307,34310 ,726,20124,726 ,0,0,0}, + {34282,34590,34587 ,726,727,726 ,0,0,0}, {36547,34266,37388 ,727,727,727 ,0,0,0}, + {36991,36993,36551 ,727,727,726 ,0,0,0}, {36993,36555,36551 ,727,727,726 ,0,0,0}, + {37379,36992,37377 ,727,726,726 ,0,0,0}, {36544,37378,37380 ,726,726,727 ,0,0,0}, + {36543,36545,34274 ,727,727,727 ,0,0,0}, {34271,37382,34274 ,727,727,727 ,0,0,0}, + {37381,36543,34274 ,726,727,727 ,0,0,0}, {34266,34627,34263 ,727,726,726 ,0,0,0}, + {37383,34270,36606 ,726,726,726 ,0,0,0}, {34270,37383,34271 ,726,726,727 ,0,0,0}, + {34627,36611,34263 ,726,727,726 ,0,0,0}, {36607,34263,36611 ,20124,726,727 ,0,0,0}, + {34266,34265,37388 ,727,726,727 ,0,0,0}, {37454,36604,37376 ,727,727,726 ,0,0,0}, + {36990,35884,36546 ,20124,726,726 ,0,0,0}, {37375,37376,36549 ,726,726,727 ,0,0,0}, + {37376,37375,37454 ,726,726,727 ,0,0,0}, {36546,36550,36990 ,726,727,20124 ,0,0,0}, + {36990,35887,35884 ,20124,20124,726 ,0,0,0}, {35890,37389,35892 ,726,20124,726 ,0,0,0}, + {37389,35890,36539 ,20124,726,726 ,0,0,0}, {34288,35892,37390 ,20124,726,20124 ,0,0,0}, + {34277,34599,34284 ,726,726,726 ,0,0,0}, {34285,36602,37384 ,726,727,20124 ,0,0,0}, + {34599,36601,34284 ,726,727,726 ,0,0,0}, {34277,34583,34598 ,726,20124,726 ,0,0,0}, + {34280,34279,34584 ,727,727,20124 ,0,0,0}, {34277,34280,34583 ,726,727,20124 ,0,0,0}, + {34587,34279,34282 ,726,727,726 ,0,0,0}, {34584,34279,34586 ,20124,727,20124 ,0,0,0}, + {34251,37014,37455 ,726,726,726 ,0,0,0}, {36709,34238,34237 ,726,726,726 ,0,0,0}, + {37433,37432,36700 ,726,726,728 ,0,0,0}, {37432,37414,36700 ,726,726,728 ,0,0,0}, + {37020,37434,37021 ,726,726,726 ,0,0,0}, {37022,37019,37415 ,726,726,726 ,0,0,0}, + {34235,34238,36708 ,726,726,726 ,0,0,0}, {37025,37024,37023 ,726,729,726 ,0,0,0}, + {34242,37416,34243 ,726,726,728 ,0,0,0}, {34243,37026,34246 ,728,726,728 ,0,0,0}, + {37033,34235,36708 ,726,726,726 ,0,0,0}, {34242,34235,37027 ,726,726,726 ,0,0,0}, + {34242,37028,37416 ,726,726,726 ,0,0,0}, {34235,37033,37417 ,726,726,729 ,0,0,0}, + {34237,37435,36709 ,726,726,726 ,0,0,0}, {37456,37015,37412 ,726,726,726 ,0,0,0}, + {36251,36250,34543 ,726,726,726 ,0,0,0}, {37412,37411,37456 ,726,726,726 ,0,0,0}, + {34547,37410,34544 ,726,726,726 ,0,0,0}, {36251,37018,36252 ,726,726,726 ,0,0,0}, + {36261,36996,36995 ,726,726,729 ,0,0,0}, {36262,36261,36995 ,726,726,729 ,0,0,0}, + {34260,36256,36262 ,726,726,726 ,0,0,0}, {34502,34249,34504 ,726,726,729 ,0,0,0}, + {36686,34256,34500 ,726,726,726 ,0,0,0}, {34256,36691,34257 ,726,726,726 ,0,0,0}, + {34256,34249,34502 ,726,726,726 ,0,0,0}, {34505,34252,37436 ,726,726,729 ,0,0,0}, + {34249,34252,34504 ,726,726,729 ,0,0,0}, {37436,34251,37455 ,729,726,726 ,0,0,0}, + {37014,34251,34254 ,726,726,726 ,0,0,0}, {36879,36875,36880 ,20124,20124,726 ,0,0,0}, + {34226,37285,37305 ,20124,727,726 ,0,0,0}, {36879,36881,37303 ,20124,20124,727 ,0,0,0}, + {36881,37304,37303 ,20124,726,727 ,0,0,0}, {37289,36880,36875 ,20124,726,20124 ,0,0,0}, + {36298,36874,36873 ,20124,726,20124 ,0,0,0}, {36297,36296,34218 ,727,726,20124 ,0,0,0}, + {37290,36297,34218 ,726,727,20124 ,0,0,0}, {34210,34889,34207 ,726,726,727 ,0,0,0}, + {34215,36888,34218 ,726,726,20124 ,0,0,0}, {34214,36887,34215 ,726,20124,726 ,0,0,0}, + {34889,37291,34207 ,726,20124,727 ,0,0,0}, {34214,36891,36887 ,726,20124,20124 ,0,0,0}, + {36890,34207,37291 ,20124,727,20124 ,0,0,0}, {34210,34209,34884 ,726,726,20124 ,0,0,0}, + {34877,34878,36231 ,727,727,20124 ,0,0,0}, {36240,36232,34865 ,726,726,20124 ,0,0,0}, + {34865,36233,36240 ,20124,20124,726 ,0,0,0}, {36231,36882,34861 ,20124,20124,726 ,0,0,0}, + {36240,36239,36232 ,726,726,726 ,0,0,0}, {36287,37309,35958 ,20124,726,727 ,0,0,0}, + {37309,36287,36238 ,726,20124,20124 ,0,0,0}, {34232,35958,37310 ,726,727,726 ,0,0,0}, + {34221,36228,34228 ,726,20124,726 ,0,0,0}, {36228,35950,34228 ,20124,20124,726 ,0,0,0}, + {34229,35949,35955 ,726,726,726 ,0,0,0}, {34221,37307,36227 ,726,20124,726 ,0,0,0}, + {34224,34223,37308 ,726,727,727 ,0,0,0}, {34221,34224,37307 ,726,726,20124 ,0,0,0}, + {37305,34223,34226 ,726,727,20124 ,0,0,0}, {37308,34223,37306 ,727,727,726 ,0,0,0}, + {34195,36980,37457 ,20124,726,727 ,0,0,0}, {36556,34182,34181 ,20124,20124,20124 ,0,0,0}, + {36004,36003,36982 ,726,727,726 ,0,0,0}, {36003,36561,36982 ,727,726,726 ,0,0,0}, + {36009,36006,36983 ,726,726,726 ,0,0,0}, {36010,36537,36012 ,726,20124,20124 ,0,0,0}, + {34182,36557,34179 ,20124,727,20124 ,0,0,0}, {36600,36012,36537 ,726,20124,20124 ,0,0,0}, + {34186,36985,34187 ,726,726,726 ,0,0,0}, {34187,36599,34190 ,726,726,727 ,0,0,0}, + {36987,34179,36557 ,726,20124,727 ,0,0,0}, {34179,36987,37396 ,20124,726,727 ,0,0,0}, + {34186,34179,37391 ,726,20124,727 ,0,0,0}, {34181,37394,36556 ,20124,726,20124 ,0,0,0}, + {37458,37395,37392 ,726,726,726 ,0,0,0}, {36981,37367,34604 ,726,726,20124 ,0,0,0}, + {37392,36587,37458 ,726,726,726 ,0,0,0}, {34608,36978,34605 ,726,726,726 ,0,0,0}, + {36981,37366,37369 ,726,726,726 ,0,0,0}, {36578,36964,36966 ,20124,726,726 ,0,0,0}, + {36576,36578,36966 ,20124,20124,726 ,0,0,0}, {34204,36577,36576 ,20124,726,20124 ,0,0,0}, + {34656,34193,34658 ,726,20124,726 ,0,0,0}, {36533,34200,34654 ,726,726,20124 ,0,0,0}, + {34200,36573,34201 ,726,726,726 ,0,0,0}, {34200,34193,34656 ,726,20124,726 ,0,0,0}, + {34659,34196,36597 ,727,726,726 ,0,0,0}, {34193,34196,34658 ,20124,726,726 ,0,0,0}, + {36597,34195,37457 ,726,20124,727 ,0,0,0}, {36980,34195,34198 ,726,20124,726 ,0,0,0}, + {37428,36070,36068 ,726,726,726 ,0,0,0}, {34170,37002,37437 ,726,726,729 ,0,0,0}, + {36068,36067,37428 ,726,726,726 ,0,0,0}, {36067,36685,37428 ,726,726,726 ,0,0,0}, + {36073,36070,36684 ,726,726,726 ,0,0,0}, {34154,34516,34518 ,726,726,728 ,0,0,0}, + {37429,36076,37005 ,726,728,726 ,0,0,0}, {37007,37429,34162 ,726,726,726 ,0,0,0}, + {34154,34518,34151 ,726,728,726 ,0,0,0}, {34159,37007,34162 ,726,726,726 ,0,0,0}, + {34158,37006,34159 ,726,728,726 ,0,0,0}, {34518,37430,34151 ,728,726,726 ,0,0,0}, + {34158,36689,37006 ,726,726,728 ,0,0,0}, {36690,34151,37430 ,729,726,726 ,0,0,0}, + {34154,34153,34513 ,726,726,726 ,0,0,0}, {34506,34507,36682 ,726,726,726 ,0,0,0}, + {36263,36598,34495 ,726,726,728 ,0,0,0}, {34495,37423,36263 ,728,726,726 ,0,0,0}, + {36682,37424,34491 ,726,726,726 ,0,0,0}, {36263,36185,36598 ,726,726,726 ,0,0,0}, + {37425,37441,35826 ,728,726,726 ,0,0,0}, {37441,37425,36186 ,726,728,726 ,0,0,0}, + {34176,35826,37442 ,726,726,726 ,0,0,0}, {34165,36258,34172 ,726,726,726 ,0,0,0}, + {36258,35818,34172 ,726,726,726 ,0,0,0}, {34173,35817,35823 ,728,726,729 ,0,0,0}, + {34165,37439,36257 ,726,726,726 ,0,0,0}, {34168,34167,37440 ,726,726,726 ,0,0,0}, + {34165,34168,37439 ,726,726,726 ,0,0,0}, {37437,34167,34170 ,729,726,726 ,0,0,0}, + {37440,34167,37438 ,726,726,728 ,0,0,0}, {34834,34126,34125 ,726,726,726 ,0,0,0}, + {36134,36132,36230 ,727,20124,726 ,0,0,0}, {36219,35940,35943 ,20124,20124,726 ,0,0,0}, + {36132,36131,36230 ,20124,726,726 ,0,0,0}, {36137,36134,36229 ,20124,727,20124 ,0,0,0}, + {36138,36281,36140 ,20124,20124,20124 ,0,0,0}, {34126,34832,34123 ,726,726,726 ,0,0,0}, + {37300,36140,36281 ,726,20124,20124 ,0,0,0}, {34134,34131,37301 ,727,726,20124 ,0,0,0}, + {37301,37300,34134 ,20124,726,727 ,0,0,0}, {34831,34123,34832 ,726,726,726 ,0,0,0}, + {34130,36278,34131 ,20124,726,726 ,0,0,0}, {34123,34831,36878 ,726,726,726 ,0,0,0}, + {34130,34123,37299 ,20124,726,726 ,0,0,0}, {34125,34835,34834 ,726,20124,726 ,0,0,0}, + {36221,35947,36241 ,20124,726,726 ,0,0,0}, {34842,34840,36248 ,726,20124,20124 ,0,0,0}, + {36248,34844,34842 ,20124,726,726 ,0,0,0}, {37311,36277,36276 ,726,726,727 ,0,0,0}, + {37312,34845,34844 ,726,727,726 ,0,0,0}, {36221,35943,35946 ,20124,726,20124 ,0,0,0}, + {35937,35940,36220 ,20124,20124,727 ,0,0,0}, {34148,35938,36264 ,726,726,20124 ,0,0,0}, + {36264,35937,36220 ,20124,20124,727 ,0,0,0}, {35964,34145,34144 ,726,20124,20124 ,0,0,0}, + {37257,34137,36871 ,726,726,726 ,0,0,0}, {35969,34144,37258 ,20124,20124,726 ,0,0,0}, + {34144,34137,37257 ,20124,726,726 ,0,0,0}, {34951,34140,34949 ,726,20124,726 ,0,0,0}, + {34137,34140,36871 ,726,20124,726 ,0,0,0}, {34949,34139,34946 ,726,726,726 ,0,0,0}, + {34945,34139,34142 ,20124,726,726 ,0,0,0}, {37365,36030,36031 ,20124,726,726 ,0,0,0}, + {34114,36532,37363 ,20124,727,726 ,0,0,0}, {36031,36034,37365 ,726,726,20124 ,0,0,0}, + {36034,36971,37365 ,726,727,20124 ,0,0,0}, {36028,36030,36972 ,20124,726,20124 ,0,0,0}, + {34098,34671,34673 ,726,20124,726 ,0,0,0}, {36022,36024,36568 ,726,727,726 ,0,0,0}, + {36019,36022,34106 ,20124,726,20124 ,0,0,0}, {34098,34673,34095 ,726,726,727 ,0,0,0}, + {34103,36019,34106 ,726,20124,20124 ,0,0,0}, {34103,36016,36018 ,726,726,20124 ,0,0,0}, + {35985,34095,34673 ,726,727,726 ,0,0,0}, {34102,36014,36016 ,726,726,726 ,0,0,0}, + {36014,34095,35982 ,726,727,726 ,0,0,0}, {34098,34097,34668 ,726,726,20124 ,0,0,0}, + {34661,34662,37361 ,727,727,20124 ,0,0,0}, {37362,37355,34649 ,726,726,20124 ,0,0,0}, + {34649,36530,37362 ,20124,20124,726 ,0,0,0}, {37361,36566,34645 ,20124,20124,726 ,0,0,0}, + {37362,36583,37355 ,726,726,726 ,0,0,0}, {37352,37356,35870 ,20124,726,727 ,0,0,0}, + {37356,37352,36581 ,726,20124,20124 ,0,0,0}, {34120,35870,37357 ,726,727,726 ,0,0,0}, + {34109,36579,34116 ,726,20124,726 ,0,0,0}, {36579,35862,34116 ,20124,20124,726 ,0,0,0}, + {34117,35861,35867 ,726,726,726 ,0,0,0}, {34109,37354,36580 ,726,20124,726 ,0,0,0}, + {34112,34111,37353 ,726,727,727 ,0,0,0}, {34109,34112,37354 ,726,726,20124 ,0,0,0}, + {37363,34111,34114 ,726,727,20124 ,0,0,0}, {37353,34111,37364 ,727,727,726 ,0,0,0}, + {34462,34070,34069 ,726,726,726 ,0,0,0}, {36094,36095,37000 ,726,726,726 ,0,0,0}, + {36716,35808,35811 ,726,728,726 ,0,0,0}, {36095,36098,37000 ,726,726,726 ,0,0,0}, + {36092,36094,36999 ,726,726,726 ,0,0,0}, {36088,36089,36247 ,726,726,728 ,0,0,0}, + {34070,34460,34067 ,726,726,728 ,0,0,0}, {36086,36088,36246 ,729,726,726 ,0,0,0}, + {34078,34075,36083 ,726,726,726 ,0,0,0}, {36083,36086,34078 ,726,729,726 ,0,0,0}, + {34459,34067,34460 ,726,728,726 ,0,0,0}, {34075,36080,36082 ,726,726,726 ,0,0,0}, + {34459,36049,34067 ,726,726,728 ,0,0,0}, {34074,34067,36078 ,726,728,729 ,0,0,0}, + {34069,34463,34462 ,726,728,726 ,0,0,0}, {36198,35815,36701 ,726,726,726 ,0,0,0}, + {34470,34468,36710 ,726,726,726 ,0,0,0}, {36710,34472,34470 ,726,729,726 ,0,0,0}, + {37443,36704,36703 ,729,726,726 ,0,0,0}, {37444,34473,34472 ,726,726,729 ,0,0,0}, + {36198,35811,35814 ,726,726,728 ,0,0,0}, {35805,35808,36715 ,726,728,726 ,0,0,0}, + {34092,35806,37398 ,726,728,726 ,0,0,0}, {37398,35805,36715 ,726,726,726 ,0,0,0}, + {35832,34089,34088 ,726,726,726 ,0,0,0}, {37399,34081,36197 ,726,726,726 ,0,0,0}, + {35837,34088,37400 ,726,726,726 ,0,0,0}, {34088,34081,37399 ,726,726,726 ,0,0,0}, + {34580,34084,34578 ,726,728,726 ,0,0,0}, {34081,34084,36197 ,726,728,726 ,0,0,0}, + {34578,34083,34575 ,726,726,726 ,0,0,0}, {34574,34083,34086 ,726,726,726 ,0,0,0}, + {34058,34900,34897 ,726,727,726 ,0,0,0}, {37459,34042,37265 ,727,727,727 ,0,0,0}, + {36159,36162,37262 ,726,20124,727 ,0,0,0}, {36162,36267,37262 ,20124,726,727 ,0,0,0}, + {36156,36158,37263 ,727,726,727 ,0,0,0}, {34042,37459,34937 ,727,727,726 ,0,0,0}, + {36150,36152,36265 ,726,20124,727 ,0,0,0}, {34050,34047,36147 ,727,727,727 ,0,0,0}, + {36147,36150,34050 ,727,726,727 ,0,0,0}, {34042,34937,34039 ,727,726,726 ,0,0,0}, + {34046,36142,36144 ,726,726,726 ,0,0,0}, {34047,36144,36146 ,727,726,726 ,0,0,0}, + {36113,34039,34937 ,727,726,726 ,0,0,0}, {36142,34039,36110 ,726,726,726 ,0,0,0}, + {34046,34039,36142 ,726,726,726 ,0,0,0}, {34042,34041,37265 ,727,726,727 ,0,0,0}, + {37460,36253,37261 ,727,727,726 ,0,0,0}, {36911,35972,36260 ,20124,726,726 ,0,0,0}, + {37260,37261,36226 ,726,726,727 ,0,0,0}, {37261,37260,37460 ,726,726,727 ,0,0,0}, + {36260,36224,36911 ,726,727,20124 ,0,0,0}, {36911,35975,35972 ,20124,20124,726 ,0,0,0}, + {35978,37266,35980 ,726,20124,726 ,0,0,0}, {37266,35978,36268 ,20124,726,726 ,0,0,0}, + {34064,35980,37267 ,20124,726,20124 ,0,0,0}, {34053,34909,34060 ,726,726,726 ,0,0,0}, + {34061,36274,37264 ,726,727,20124 ,0,0,0}, {34909,36273,34060 ,726,727,726 ,0,0,0}, + {34053,34893,34908 ,726,20124,726 ,0,0,0}, {34056,34055,34894 ,727,727,20124 ,0,0,0}, + {34053,34056,34893 ,726,727,20124 ,0,0,0}, {34897,34055,34058 ,726,727,726 ,0,0,0}, + {34894,34055,34896 ,20124,727,20124 ,0,0,0}, {35705,36469,35703 ,1793,726,1793 ,0,0,0}, + {37178,37179,36469 ,726,727,726 ,0,0,0}, {37461,37462,37463 ,730,730,730 ,0,0,0}, + {37464,37465,37466 ,730,730,730 ,0,0,0}, {35142,35140,37467 ,730,730,730 ,0,0,0}, + {37468,37469,37470 ,730,730,730 ,0,0,0}, {37471,37472,37463 ,730,730,730 ,0,0,0}, + {37462,37473,37463 ,730,730,730 ,0,0,0}, {37474,37475,37476 ,730,730,730 ,0,0,0}, + {37463,37477,37478 ,730,730,730 ,0,0,0}, {37477,37463,37472 ,730,730,730 ,0,0,0}, + {35956,34230,35957 ,730,730,730 ,0,0,0}, {34882,34211,34885 ,730,730,730 ,0,0,0}, + {37479,37480,35154 ,730,730,730 ,0,0,0}, {37478,37481,37482 ,730,730,730 ,0,0,0}, + {34205,34216,37483 ,730,730,730 ,0,0,0}, {34890,37484,37485 ,730,730,730 ,0,0,0}, + {37482,35158,37480 ,730,730,730 ,0,0,0}, {35160,37481,35161 ,730,730,730 ,0,0,0}, + {37478,37486,37487 ,730,730,730 ,0,0,0}, {37478,37487,37481 ,730,730,730 ,0,0,0}, + {37488,35178,35177 ,730,730,730 ,0,0,0}, {35182,35178,37488 ,730,730,730 ,0,0,0}, + {37489,35146,37490 ,730,730,730 ,0,0,0}, {37491,37492,37493 ,730,730,730 ,0,0,0}, + {37494,37495,37496 ,730,730,730 ,0,0,0}, {37497,37498,37499 ,730,730,730 ,0,0,0}, + {37500,37499,37498 ,730,730,730 ,0,0,0}, {37499,37501,37497 ,730,730,730 ,0,0,0}, + {37491,37500,37498 ,730,730,730 ,0,0,0}, {37491,37493,37500 ,730,730,730 ,0,0,0}, + {37502,37503,37501 ,730,730,730 ,0,0,0}, {37497,37501,37503 ,730,730,730 ,0,0,0}, + {37504,37505,34164 ,730,730,730 ,0,0,0}, {37506,37503,37502 ,730,730,730 ,0,0,0}, + {34517,34152,2073 ,730,730,730 ,0,0,0}, {37507,37508,37509 ,730,730,730 ,0,0,0}, + {37510,37511,37512 ,730,730,730 ,0,0,0}, {34234,37513,37514 ,730,730,730 ,0,0,0}, + {37515,37516,37517 ,730,730,730 ,0,0,0}, {37507,37518,37519 ,730,730,730 ,0,0,0}, + {36075,37520,37521 ,730,730,730 ,0,0,0}, {37522,37523,37524 ,730,730,730 ,0,0,0}, + {37525,37526,37527 ,730,730,730 ,0,0,0}, {36057,34480,36054 ,730,730,730 ,0,0,0}, + {37528,34071,34467 ,730,730,730 ,0,0,0}, {34552,37529,34570 ,730,730,730 ,0,0,0}, + {34040,34938,37530 ,730,730,730 ,0,0,0}, {34087,34576,34085 ,730,730,730 ,0,0,0}, + {34076,36084,36081 ,730,730,730 ,0,0,0}, {36051,34477,34458 ,730,730,730 ,0,0,0}, + {37525,37527,35819 ,730,730,730 ,0,0,0}, {36051,36053,34477 ,730,730,730 ,0,0,0}, + {35835,34079,35833 ,730,730,730 ,0,0,0}, {34885,34213,34886 ,730,730,730 ,0,0,0}, + {34049,4039,36149 ,730,730,730 ,0,0,0}, {37531,37532,37533 ,730,730,730 ,0,0,0}, + {36063,34488,34486 ,730,730,730 ,0,0,0}, {37534,37535,35942 ,730,730,730 ,0,0,0}, + {37536,34913,37537 ,730,730,730 ,0,0,0}, {37532,37538,37539 ,730,730,730 ,0,0,0}, + {37540,37541,37542 ,730,730,730 ,0,0,0}, {34892,34054,34052 ,730,730,730 ,0,0,0}, + {37543,37544,37545 ,730,730,730 ,0,0,0}, {34150,2073,34152 ,730,730,730 ,0,0,0}, + {34038,36109,36111 ,730,730,730 ,0,0,0}, {34854,34851,37546 ,730,730,730 ,0,0,0}, + {37547,37548,37549 ,730,730,730 ,0,0,0}, {35824,34174,35825 ,730,730,730 ,0,0,0}, + {34935,34938,36112 ,730,730,730 ,0,0,0}, {35951,37550,37551 ,730,730,730 ,0,0,0}, + {35828,37509,37508 ,730,730,730 ,0,0,0}, {34848,37552,37553 ,730,730,730 ,0,0,0}, + {35967,34135,35965 ,730,730,730 ,0,0,0}, {34497,34496,37554 ,730,730,730 ,0,0,0}, + {37555,34255,34250 ,730,730,730 ,0,0,0}, {37556,37557,34859 ,730,730,730 ,0,0,0}, + {37558,34244,37559 ,730,730,730 ,0,0,0}, {34247,34501,34248 ,730,730,730 ,0,0,0}, + {34248,34503,34250 ,730,730,730 ,0,0,0}, {37510,37560,37511 ,730,730,730 ,0,0,0}, + {34234,37561,34236 ,730,730,730 ,0,0,0}, {37562,34550,37563 ,730,730,730 ,0,0,0}, + {35824,35822,34174 ,730,730,730 ,0,0,0}, {34258,37564,37565 ,730,730,730 ,0,0,0}, + {37543,37523,37544 ,730,730,730 ,0,0,0}, {37566,37567,37568 ,730,730,730 ,0,0,0}, + {37569,34166,34164 ,730,730,730 ,0,0,0}, {37570,37571,37572 ,730,730,730 ,0,0,0}, + {37573,37574,37575 ,730,730,730 ,0,0,0}, {37576,37575,37577 ,730,730,730 ,0,0,0}, + {37578,34150,37579 ,730,730,730 ,0,0,0}, {34169,34171,37580 ,730,730,730 ,0,0,0}, + {37541,34545,37542 ,730,730,730 ,0,0,0}, {37581,37574,34974 ,730,730,730 ,0,0,0}, + {37582,37583,37584 ,730,730,730 ,0,0,0}, {37585,37579,34149 ,730,730,730 ,0,0,0}, + {37542,34545,34542 ,730,730,730 ,0,0,0}, {37581,34974,34329 ,730,730,730 ,0,0,0}, + {35821,35819,37586 ,730,730,730 ,0,0,0}, {37587,37588,37589 ,730,730,730 ,0,0,0}, + {34520,34519,34334 ,730,730,730 ,0,0,0}, {34483,36057,36059 ,730,730,730 ,0,0,0}, + {36059,36060,34484 ,730,730,730 ,0,0,0}, {34080,34079,37590 ,730,730,730 ,0,0,0}, + {34079,34090,35830 ,730,730,730 ,0,0,0}, {37591,37592,37593 ,730,730,730 ,0,0,0}, + {37594,35835,35836 ,730,730,730 ,0,0,0}, {35123,35122,37595 ,730,730,730 ,0,0,0}, + {34536,37596,37597 ,730,730,730 ,0,0,0}, {37506,37598,37599 ,730,730,730 ,0,0,0}, + {37600,37601,37602 ,730,730,730 ,0,0,0}, {37603,34342,37604 ,730,730,730 ,0,0,0}, + {37605,37601,37600 ,730,730,730 ,0,0,0}, {37606,37542,34542 ,730,730,730 ,0,0,0}, + {34956,34960,37607 ,730,730,730 ,0,0,0}, {37605,37608,37609 ,730,730,730 ,0,0,0}, + {37610,37611,37612 ,730,730,730 ,0,0,0}, {37613,37608,37614 ,730,730,730 ,0,0,0}, + {36107,36105,34558 ,730,730,730 ,0,0,0}, {37615,37616,37613 ,730,730,730 ,0,0,0}, + {37616,37615,34962 ,730,730,730 ,0,0,0}, {37617,34969,34968 ,730,730,730 ,0,0,0}, + {37595,34962,37615 ,730,730,730 ,0,0,0}, {34953,37618,37619 ,730,730,730 ,0,0,0}, + {37599,37598,35116 ,730,730,730 ,0,0,0}, {37502,37598,37506 ,730,730,730 ,0,0,0}, + {37620,35270,35261 ,730,730,730 ,0,0,0}, {37493,37492,37621 ,730,730,730 ,0,0,0}, + {35663,35666,37622 ,730,730,730 ,0,0,0}, {37623,35629,37624 ,730,730,730 ,0,0,0}, + {37625,37626,35264 ,730,730,730 ,0,0,0}, {35627,37627,37628 ,730,730,730 ,0,0,0}, + {37625,35273,37629 ,730,730,730 ,0,0,0}, {37630,37631,37632 ,730,730,730 ,0,0,0}, + {37633,37634,37635 ,730,730,730 ,0,0,0}, {37636,37637,37638 ,730,730,730 ,0,0,0}, + {37639,35247,35242 ,730,730,730 ,0,0,0}, {37640,37641,37642 ,730,730,730 ,0,0,0}, + {37637,37643,37644 ,730,730,730 ,0,0,0}, {37645,37646,37647 ,730,730,730 ,0,0,0}, + {37648,37649,37650 ,730,730,730 ,0,0,0}, {37651,37652,37653 ,730,730,730 ,0,0,0}, + {37648,35666,37654 ,730,730,730 ,0,0,0}, {35680,37655,37656 ,730,730,730 ,0,0,0}, + {35678,37657,37655 ,730,730,730 ,0,0,0}, {35680,35678,37655 ,730,730,730 ,0,0,0}, + {37642,37638,37658 ,730,730,730 ,0,0,0}, {37659,37660,37661 ,730,730,730 ,0,0,0}, + {37662,37657,35676 ,730,730,730 ,0,0,0}, {37663,35292,37664 ,730,730,730 ,0,0,0}, + {35238,35234,37665 ,730,730,730 ,0,0,0}, {37666,35614,37667 ,730,730,730 ,0,0,0}, + {37668,37669,37670 ,730,730,730 ,0,0,0}, {37671,37672,37673 ,730,730,730 ,0,0,0}, + {37674,37675,37494 ,730,730,730 ,0,0,0}, {37672,37676,37677 ,730,730,730 ,0,0,0}, + {37676,37672,37671 ,730,730,730 ,0,0,0}, {37678,37677,37679 ,730,730,730 ,0,0,0}, + {37676,37679,37677 ,730,730,730 ,0,0,0}, {37680,37681,37678 ,730,730,730 ,0,0,0}, + {37678,37679,37680 ,730,730,730 ,0,0,0}, {34606,37682,37683 ,730,730,730 ,0,0,0}, + {37684,37685,37686 ,730,730,730 ,0,0,0}, {37687,37688,37689 ,730,730,730 ,0,0,0}, + {37690,37691,37692 ,730,730,730 ,0,0,0}, {37693,37694,37695 ,730,730,730 ,0,0,0}, + {37696,37697,37698 ,730,730,730 ,0,0,0}, {37699,35872,37700 ,730,730,730 ,0,0,0}, + {37701,34191,37702 ,730,730,730 ,0,0,0}, {37703,34183,34185 ,730,730,730 ,0,0,0}, + {37704,37705,37706 ,730,730,730 ,0,0,0}, {34651,34650,37707 ,730,730,730 ,0,0,0}, + {37708,36013,37709 ,730,730,730 ,0,0,0}, {34650,34653,37710 ,730,730,730 ,0,0,0}, + {34657,34660,34194 ,730,730,730 ,0,0,0}, {37710,34653,37701 ,730,730,730 ,0,0,0}, + {37711,36011,37708 ,730,730,730 ,0,0,0}, {36005,37712,36002 ,730,730,730 ,0,0,0}, + {37683,34607,34606 ,730,730,730 ,0,0,0}, {37704,37699,37700 ,730,730,730 ,0,0,0}, + {37713,34202,37714 ,730,730,730 ,0,0,0}, {37715,37695,37716 ,730,730,730 ,0,0,0}, + {35866,34118,35868 ,730,730,730 ,0,0,0}, {34118,35869,35868 ,730,730,730 ,0,0,0}, + {37717,35987,37718 ,730,730,730 ,0,0,0}, {34670,34096,34672 ,730,730,730 ,0,0,0}, + {37719,37715,37716 ,730,730,730 ,0,0,0}, {37692,3049,37690 ,730,730,730 ,0,0,0}, + {34107,34118,35866 ,730,730,730 ,0,0,0}, {37720,34643,34647 ,730,730,730 ,0,0,0}, + {34674,34096,34094 ,730,730,730 ,0,0,0}, {37721,34113,37722 ,730,730,730 ,0,0,0}, + {34104,36020,36017 ,730,730,730 ,0,0,0}, {34110,37723,34115 ,730,730,730 ,0,0,0}, + {34110,34108,37724 ,730,730,730 ,0,0,0}, {34669,34666,34099 ,730,730,730 ,0,0,0}, + {37592,37725,37593 ,730,730,730 ,0,0,0}, {37682,37726,37683 ,730,730,730 ,0,0,0}, + {37688,37727,34273 ,730,730,730 ,0,0,0}, {3049,37728,34595 ,730,730,730 ,0,0,0}, + {34591,34281,34588 ,730,730,730 ,0,0,0}, {37682,34603,37729 ,730,730,730 ,0,0,0}, + {37730,34267,37731 ,730,730,730 ,0,0,0}, {34272,37732,34261 ,730,730,730 ,0,0,0}, + {34264,34628,37733 ,730,730,730 ,0,0,0}, {37734,34262,37735 ,730,730,730 ,0,0,0}, + {34600,34276,34601 ,730,730,730 ,0,0,0}, {37736,37737,37738 ,730,730,730 ,0,0,0}, + {37739,34286,37740 ,730,730,730 ,0,0,0}, {37741,34360,34359 ,730,730,730 ,0,0,0}, + {34618,34621,37742 ,730,730,730 ,0,0,0}, {34615,37743,34611 ,730,730,730 ,0,0,0}, + {34628,37744,34625 ,730,730,730 ,0,0,0}, {34621,34623,37745 ,730,730,730 ,0,0,0}, + {3171,37746,36026 ,730,730,730 ,0,0,0}, {37747,34365,34634 ,730,730,730 ,0,0,0}, + {34700,36043,36041 ,730,730,730 ,0,0,0}, {35252,37748,37749 ,730,730,730 ,0,0,0}, + {35035,37750,35037 ,730,730,730 ,0,0,0}, {37750,37681,37680 ,730,730,730 ,0,0,0}, + {34365,34637,34634 ,730,730,730 ,0,0,0}, {35863,37751,35865 ,730,730,730 ,0,0,0}, + {34703,34701,36039 ,730,730,730 ,0,0,0}, {34703,36038,3029 ,730,730,730 ,0,0,0}, + {35012,37752,35013 ,730,730,730 ,0,0,0}, {37753,37754,37755 ,730,730,730 ,0,0,0}, + {37756,37737,37757 ,730,730,730 ,0,0,0}, {37758,37755,37754 ,730,730,730 ,0,0,0}, + {34694,37759,34695 ,730,730,730 ,0,0,0}, {37758,37760,35007 ,730,730,730 ,0,0,0}, + {37761,37762,35863 ,730,730,730 ,0,0,0}, {37763,35003,35000 ,730,730,730 ,0,0,0}, + {37764,37765,37766 ,730,730,730 ,0,0,0}, {34997,37767,35010 ,730,730,730 ,0,0,0}, + {37766,37768,37769 ,730,730,730 ,0,0,0}, {35018,35015,37770 ,730,730,730 ,0,0,0}, + {37771,37671,37673 ,730,730,730 ,0,0,0}, {37674,37771,37675 ,730,730,730 ,0,0,0}, + {37673,37675,37771 ,730,730,730 ,0,0,0}, {37772,37773,37774 ,730,730,730 ,0,0,0}, + {37773,37775,37774 ,730,730,730 ,0,0,0}, {35615,35614,37666 ,730,730,730 ,0,0,0}, + {37772,37776,37777 ,730,730,730 ,0,0,0}, {37778,37779,37780 ,730,730,730 ,0,0,0}, + {37781,35611,35609 ,730,730,730 ,0,0,0}, {37782,35497,35498 ,730,730,730 ,0,0,0}, + {35370,35361,35208 ,730,730,730 ,0,0,0}, {35501,37783,35498 ,730,730,730 ,0,0,0}, + {37784,37785,37786 ,730,730,730 ,0,0,0}, {37787,37788,37789 ,730,730,730 ,0,0,0}, + {37790,37791,37792 ,730,730,730 ,0,0,0}, {37793,37787,37794 ,730,730,730 ,0,0,0}, + {35691,37795,35688 ,730,730,730 ,0,0,0}, {37796,35698,37785 ,730,730,730 ,0,0,0}, + {37797,37798,37799 ,730,730,730 ,0,0,0}, {37800,35681,35685 ,730,730,730 ,0,0,0}, + {37800,35689,35688 ,730,730,730 ,0,0,0}, {37801,35518,35520 ,730,730,730 ,0,0,0}, + {35695,37802,37803 ,730,730,730 ,0,0,0}, {37803,37795,35693 ,730,730,730 ,0,0,0}, + {37804,37805,37801 ,730,730,730 ,0,0,0}, {37806,37792,37784 ,730,730,730 ,0,0,0}, + {35366,35212,35371 ,730,730,730 ,0,0,0}, {35221,35224,35377 ,730,730,730 ,0,0,0}, + {35426,35427,37807 ,730,730,730 ,0,0,0}, {37808,37809,37810 ,730,730,730 ,0,0,0}, + {37635,37811,37812 ,730,730,730 ,0,0,0}, {37813,37814,37798 ,730,730,730 ,0,0,0}, + {37814,37813,37810 ,730,730,730 ,0,0,0}, {37813,37798,37797 ,730,730,730 ,0,0,0}, + {37815,37816,37799 ,730,730,730 ,0,0,0}, {37797,37799,37816 ,730,730,730 ,0,0,0}, + {37817,37816,37815 ,730,730,730 ,0,0,0}, {35907,37818,35909 ,730,730,730 ,0,0,0}, + {37819,34809,34811 ,730,730,730 ,0,0,0}, {37820,37821,37822 ,730,730,730 ,0,0,0}, + {37823,37824,34426 ,730,730,730 ,0,0,0}, {34407,37825,37826 ,730,730,730 ,0,0,0}, + {37827,34788,34787 ,730,730,730 ,0,0,0}, {35780,2131,34765 ,730,730,730 ,0,0,0}, + {37828,37829,37830 ,730,730,730 ,0,0,0}, {34732,34731,37831 ,730,730,730 ,0,0,0}, + {37832,37833,37834 ,730,730,730 ,0,0,0}, {37835,34747,37836 ,730,730,730 ,0,0,0}, + {37835,34744,34747 ,730,730,730 ,0,0,0}, {37837,34734,37838 ,730,730,730 ,0,0,0}, + {34751,2950,34390 ,730,730,730 ,0,0,0}, {34398,37839,37840 ,730,730,730 ,0,0,0}, + {37841,37842,37843 ,730,730,730 ,0,0,0}, {37844,37845,37846 ,730,730,730 ,0,0,0}, + {37847,37848,37849 ,730,730,730 ,0,0,0}, {37850,37851,37852 ,730,730,730 ,0,0,0}, + {37853,37854,37855 ,730,730,730 ,0,0,0}, {37856,34413,37857 ,730,730,730 ,0,0,0}, + {37858,37859,35797 ,730,730,730 ,0,0,0}, {37823,34426,37860 ,730,730,730 ,0,0,0}, + {34725,34416,34726 ,730,730,730 ,0,0,0}, {37861,37862,37863 ,730,730,730 ,0,0,0}, + {34440,37864,34429 ,730,730,730 ,0,0,0}, {37865,37866,37821 ,730,730,730 ,0,0,0}, + {34444,34443,37867 ,730,730,730 ,0,0,0}, {37868,34818,34800 ,730,730,730 ,0,0,0}, + {34437,34774,34435 ,730,730,730 ,0,0,0}, {37869,35933,37870 ,730,730,730 ,0,0,0}, + {37871,34807,37872 ,730,730,730 ,0,0,0}, {34449,34451,34824 ,730,730,730 ,0,0,0}, + {37873,37874,37875 ,730,730,730 ,0,0,0}, {34779,34781,37876 ,730,730,730 ,0,0,0}, + {37877,37878,35792 ,730,730,730 ,0,0,0}, {34811,37879,37819 ,730,730,730 ,0,0,0}, + {2941,37880,34404 ,730,730,730 ,0,0,0}, {34790,37881,37882 ,730,730,730 ,0,0,0}, + {37883,37884,34796 ,730,730,730 ,0,0,0}, {34409,37885,37825 ,730,730,730 ,0,0,0}, + {34454,35918,34443 ,730,730,730 ,0,0,0}, {37856,37886,34413 ,730,730,730 ,0,0,0}, + {34728,37887,37888 ,730,730,730 ,0,0,0}, {35802,35913,35912 ,730,730,730 ,0,0,0}, + {37874,37818,35907 ,730,730,730 ,0,0,0}, {37889,37830,37829 ,730,730,730 ,0,0,0}, + {37890,37851,37891 ,730,730,730 ,0,0,0}, {37888,34731,34728 ,730,730,730 ,0,0,0}, + {37888,37892,37831 ,730,730,730 ,0,0,0}, {37853,37893,37854 ,730,730,730 ,0,0,0}, + {34731,37888,37831 ,730,730,730 ,0,0,0}, {37847,37894,37895 ,730,730,730 ,0,0,0}, + {35720,37896,35721 ,730,730,730 ,0,0,0}, {37849,37848,37897 ,730,730,730 ,0,0,0}, + {37898,37899,37900 ,730,730,730 ,0,0,0}, {35916,35803,37901 ,730,730,730 ,0,0,0}, + {37902,34374,34373 ,730,730,730 ,0,0,0}, {34744,37903,34745 ,730,730,730 ,0,0,0}, + {37904,37905,37906 ,730,730,730 ,0,0,0}, {37907,34737,37908 ,730,730,730 ,0,0,0}, + {34765,34763,35780 ,730,730,730 ,0,0,0}, {35209,35366,35370 ,730,730,730 ,0,0,0}, + {34757,35783,34759 ,730,730,730 ,0,0,0}, {37909,37910,37911 ,730,730,730 ,0,0,0}, + {35777,35788,37912 ,730,730,730 ,0,0,0}, {35050,37913,37914 ,730,730,730 ,0,0,0}, + {37913,35050,35789 ,730,730,730 ,0,0,0}, {35041,37915,37916 ,730,730,730 ,0,0,0}, + {37917,35788,35789 ,730,730,730 ,0,0,0}, {37917,37918,35788 ,730,730,730 ,0,0,0}, + {35062,37919,37920 ,730,730,730 ,0,0,0}, {37921,37922,37918 ,730,730,730 ,0,0,0}, + {37904,37923,37905 ,730,730,730 ,0,0,0}, {37924,37905,37922 ,730,730,730 ,0,0,0}, + {37919,34984,37925 ,730,730,730 ,0,0,0}, {37814,37810,37809 ,730,730,730 ,0,0,0}, + {37809,37808,37926 ,730,730,730 ,0,0,0}, {37927,37928,37926 ,730,730,730 ,0,0,0}, + {37926,37808,37927 ,730,730,730 ,0,0,0}, {37811,37929,37812 ,730,730,730 ,0,0,0}, + {37807,35427,37930 ,730,730,730 ,0,0,0}, {37909,37633,37910 ,730,730,730 ,0,0,0}, + {35366,35209,35212 ,730,730,730 ,0,0,0}, {35361,35129,35208 ,730,730,730 ,0,0,0}, + {35189,37931,37932 ,730,730,730 ,0,0,0}, {35373,35214,35215 ,730,730,730 ,0,0,0}, + {37933,35733,35714 ,730,730,730 ,0,0,0}, {35734,35733,37934 ,730,730,730 ,0,0,0}, + {35736,35734,37935 ,730,730,730 ,0,0,0}, {35713,37936,37933 ,730,730,730 ,0,0,0}, + {35730,37937,37938 ,730,730,730 ,0,0,0}, {37939,37936,35717 ,730,730,730 ,0,0,0}, + {35720,35723,37896 ,730,730,730 ,0,0,0}, {37940,35742,35740 ,730,730,730 ,0,0,0}, + {35744,35742,37940 ,730,730,730 ,0,0,0}, {35725,37941,35723 ,730,730,730 ,0,0,0}, + {37942,35358,37943 ,730,730,730 ,0,0,0}, {33841,37944,37945 ,730,730,730 ,0,0,0}, + {35142,37946,35147 ,730,730,730 ,0,0,0}, {37947,35201,35203 ,730,730,730 ,0,0,0}, + {35567,37948,35563 ,730,730,730 ,0,0,0}, {37949,37950,37951 ,730,730,730 ,0,0,0}, + {37952,37953,37950 ,730,730,730 ,0,0,0}, {37468,37954,37469 ,730,730,730 ,0,0,0}, + {37955,37468,37470 ,730,730,730 ,0,0,0}, {37956,37957,37954 ,730,730,730 ,0,0,0}, + {37469,37954,37957 ,730,730,730 ,0,0,0}, {35072,37958,37959 ,730,730,730 ,0,0,0}, + {35072,37959,37960 ,730,730,730 ,0,0,0}, {37550,37961,37551 ,730,730,730 ,0,0,0}, + {34854,37546,37962 ,730,730,730 ,0,0,0}, {34848,37963,37552 ,730,730,730 ,0,0,0}, + {34132,37964,37965 ,730,730,730 ,0,0,0}, {37966,34121,37967 ,730,730,730 ,0,0,0}, + {37968,35977,37969 ,730,730,730 ,0,0,0}, {37970,37971,36139 ,730,730,730 ,0,0,0}, + {34136,34135,37972 ,730,730,730 ,0,0,0}, {34941,34922,37973 ,730,730,730 ,0,0,0}, + {36124,36127,34925 ,730,730,730 ,0,0,0}, {36139,37971,36136 ,730,730,730 ,0,0,0}, + {36124,34925,34929 ,730,730,730 ,0,0,0}, {34141,34143,34947 ,730,730,730 ,0,0,0}, + {34928,34931,36118 ,730,730,730 ,0,0,0}, {37974,37975,34062 ,730,730,730 ,0,0,0}, + {34052,34911,34910 ,730,730,730 ,0,0,0}, {34933,36117,34931 ,730,730,730 ,0,0,0}, + {34135,34146,35962 ,730,730,730 ,0,0,0}, {35962,34146,35961 ,730,730,730 ,0,0,0}, + {37976,35941,35939 ,730,730,730 ,0,0,0}, {37977,37978,34043 ,730,730,730 ,0,0,0}, + {37979,37980,37981 ,730,730,730 ,0,0,0}, {37982,37983,37984 ,730,730,730 ,0,0,0}, + {37536,34916,34913 ,730,730,730 ,0,0,0}, {4039,36154,36151 ,730,730,730 ,0,0,0}, + {37985,37986,3917 ,730,730,730 ,0,0,0}, {34873,34306,34304 ,730,730,730 ,0,0,0}, + {37987,34220,37988 ,730,730,730 ,0,0,0}, {34227,37989,34225 ,730,730,730 ,0,0,0}, + {34222,34220,37990 ,730,730,730 ,0,0,0}, {34208,34888,34886 ,730,730,730 ,0,0,0}, + {37991,37992,37993 ,730,730,730 ,0,0,0}, {35956,35954,34230 ,730,730,730 ,0,0,0}, + {35063,37994,35076 ,730,730,730 ,0,0,0}, {37995,37996,34295 ,730,730,730 ,0,0,0}, + {37474,37476,37997 ,730,730,730 ,0,0,0}, {34311,34306,37998 ,730,730,730 ,0,0,0}, + {37999,38000,38001 ,730,730,730 ,0,0,0}, {38002,37991,38003 ,730,730,730 ,0,0,0}, + {38004,38005,37536 ,730,730,730 ,0,0,0}, {38006,36155,38007 ,730,730,730 ,0,0,0}, + {38008,38009,34314 ,730,730,730 ,0,0,0}, {38010,38011,38012 ,730,730,730 ,0,0,0}, + {37994,35063,38013 ,730,730,730 ,0,0,0}, {37536,38005,34916 ,730,730,730 ,0,0,0}, + {38014,34292,34290 ,730,730,730 ,0,0,0}, {35081,38015,38016 ,730,730,730 ,0,0,0}, + {38017,34289,34300 ,730,730,730 ,0,0,0}, {38018,38019,38016 ,730,730,730 ,0,0,0}, + {35073,38020,35070 ,730,730,730 ,0,0,0}, {38021,37959,38022 ,730,730,730 ,0,0,0}, + {38023,38024,38025 ,730,730,730 ,0,0,0}, {37959,37958,38022 ,730,730,730 ,0,0,0}, + {38025,38026,38027 ,730,730,730 ,0,0,0}, {35101,38024,35103 ,730,730,730 ,0,0,0}, + {37955,37470,37949 ,730,730,730 ,0,0,0}, {37956,38026,38028 ,730,730,730 ,0,0,0}, + {37950,37953,37951 ,730,730,730 ,0,0,0}, {37949,37951,37955 ,730,730,730 ,0,0,0}, + {37952,37942,37953 ,730,730,730 ,0,0,0}, {37947,38029,35201 ,730,730,730 ,0,0,0}, + {37952,38030,37942 ,730,730,730 ,0,0,0}, {35579,35578,37948 ,730,730,730 ,0,0,0}, + {38031,38032,35195 ,730,730,730 ,0,0,0}, {35192,38033,35191 ,730,730,730 ,0,0,0}, + {38034,38035,38036 ,730,730,730 ,0,0,0}, {37629,35266,38037 ,730,730,730 ,0,0,0}, + {35151,38038,35152 ,730,730,730 ,0,0,0}, {38037,35270,37620 ,730,730,730 ,0,0,0}, + {35129,38030,35130 ,730,730,730 ,0,0,0}, {35165,35164,37488 ,730,730,730 ,0,0,0}, + {35165,37488,35177 ,730,730,730 ,0,0,0}, {37481,35164,35175 ,730,730,730 ,0,0,0}, + {35164,37481,37488 ,730,730,730 ,0,0,0}, {37481,35173,35171 ,730,730,730 ,0,0,0}, + {35175,35173,37481 ,730,730,730 ,0,0,0}, {37481,35166,35170 ,730,730,730 ,0,0,0}, + {35171,35166,37481 ,730,730,730 ,0,0,0}, {37461,37463,38039 ,730,730,730 ,0,0,0}, + {35170,35161,37481 ,730,730,730 ,0,0,0}, {38040,35776,38041 ,730,730,730 ,0,0,0}, + {38040,38039,35776 ,730,730,730 ,0,0,0}, {37479,35156,38042 ,730,730,730 ,0,0,0}, + {38043,35148,38044 ,730,730,730 ,0,0,0}, {38045,35762,38046 ,730,730,730 ,0,0,0}, + {38047,35138,38048 ,730,730,730 ,0,0,0}, {35142,37467,37946 ,730,730,730 ,0,0,0}, + {35135,38049,35133 ,730,730,730 ,0,0,0}, {35745,38050,35746 ,730,730,730 ,0,0,0}, + {35759,33209,35587 ,730,730,730 ,0,0,0}, {38033,35192,38032 ,730,730,730 ,0,0,0}, + {35581,35579,35753 ,730,730,730 ,0,0,0}, {35195,35197,38031 ,730,730,730 ,0,0,0}, + {38051,35130,38030 ,730,730,730 ,0,0,0}, {38029,35197,35198 ,730,730,730 ,0,0,0}, + {38052,35573,38053 ,730,730,730 ,0,0,0}, {38051,37947,35203 ,730,730,730 ,0,0,0}, + {35198,35201,38029 ,730,730,730 ,0,0,0}, {35204,35130,38051 ,730,730,730 ,0,0,0}, + {35203,35204,38051 ,730,730,730 ,0,0,0}, {35377,35365,35221 ,730,730,730 ,0,0,0}, + {35364,35375,35218 ,730,730,730 ,0,0,0}, {35373,35215,35375 ,730,730,730 ,0,0,0}, + {38054,38055,38056 ,730,730,730 ,0,0,0}, {35364,35220,35365 ,730,730,730 ,0,0,0}, + {35221,35365,35220 ,730,730,730 ,0,0,0}, {35414,38057,35412 ,730,730,730 ,0,0,0}, + {35378,35224,35226 ,730,730,730 ,0,0,0}, {35224,35378,35377 ,730,730,730 ,0,0,0}, + {35226,35382,35378 ,730,730,730 ,0,0,0}, {35129,35361,35360 ,730,730,730 ,0,0,0}, + {37942,38030,35360 ,730,730,730 ,0,0,0}, {35227,35382,35226 ,730,730,730 ,0,0,0}, + {38058,38059,38060 ,730,730,730 ,0,0,0}, {38061,38062,38063 ,730,730,730 ,0,0,0}, + {38064,38065,38066 ,730,730,730 ,0,0,0}, {38067,38068,38069 ,730,730,730 ,0,0,0}, + {38070,38071,38072 ,730,730,730 ,0,0,0}, {35420,37807,37668 ,730,730,730 ,0,0,0}, + {38073,37807,38074 ,730,730,730 ,0,0,0}, {35285,38075,38076 ,730,730,730 ,0,0,0}, + {38077,38078,38079 ,730,730,730 ,0,0,0}, {38080,38081,38082 ,730,730,730 ,0,0,0}, + {38083,35492,35495 ,730,730,730 ,0,0,0}, {38084,38085,35440 ,730,730,730 ,0,0,0}, + {38086,35458,38087 ,730,730,730 ,0,0,0}, {38088,35448,38089 ,730,730,730 ,0,0,0}, + {38090,38091,38092 ,730,730,730 ,0,0,0}, {38093,38094,35593 ,730,730,730 ,0,0,0}, + {38095,38096,35633 ,730,730,730 ,0,0,0}, {35633,33508,38095 ,730,730,730 ,0,0,0}, + {37748,35252,35251 ,730,730,730 ,0,0,0}, {35631,37624,35629 ,730,730,730 ,0,0,0}, + {38097,33525,38098 ,730,730,730 ,0,0,0}, {35638,38099,35639 ,730,730,730 ,0,0,0}, + {38099,35638,38100 ,730,730,730 ,0,0,0}, {35278,37626,35282 ,730,730,730 ,0,0,0}, + {35620,35619,38101 ,730,730,730 ,0,0,0}, {35256,38102,35254 ,730,730,730 ,0,0,0}, + {35256,37749,38102 ,730,730,730 ,0,0,0}, {37492,35254,37621 ,730,730,730 ,0,0,0}, + {37626,35278,35277 ,730,730,730 ,0,0,0}, {37626,35277,35265 ,730,730,730 ,0,0,0}, + {38103,35260,35258 ,730,730,730 ,0,0,0}, {35271,37629,35273 ,730,730,730 ,0,0,0}, + {35260,37620,35261 ,730,730,730 ,0,0,0}, {35254,37492,35258 ,730,730,730 ,0,0,0}, + {35258,37492,38103 ,730,730,730 ,0,0,0}, {38104,38035,38102 ,730,730,730 ,0,0,0}, + {37621,38102,38035 ,730,730,730 ,0,0,0}, {38034,38036,38105 ,730,730,730 ,0,0,0}, + {38035,38104,38036 ,730,730,730 ,0,0,0}, {38106,38107,38034 ,730,730,730 ,0,0,0}, + {38034,38105,38106 ,730,730,730 ,0,0,0}, {38107,37466,37465 ,730,730,730 ,0,0,0}, + {37466,38107,38106 ,730,730,730 ,0,0,0}, {38108,37465,37464 ,730,730,730 ,0,0,0}, + {38109,38108,38110 ,730,730,730 ,0,0,0}, {38108,38109,37465 ,730,730,730 ,0,0,0}, + {38111,37488,38110 ,730,730,730 ,0,0,0}, {38109,38110,37488 ,730,730,730 ,0,0,0}, + {38112,37488,38113 ,730,730,730 ,0,0,0}, {37488,38111,38113 ,730,730,730 ,0,0,0}, + {35182,37488,38114 ,730,730,730 ,0,0,0}, {37488,38112,38114 ,730,730,730 ,0,0,0}, + {38115,35227,38116 ,730,730,730 ,0,0,0}, {38117,35391,33824 ,730,730,730 ,0,0,0}, + {35218,35375,35215 ,730,730,730 ,0,0,0}, {35220,35364,35218 ,730,730,730 ,0,0,0}, + {35371,35214,35373 ,730,730,730 ,0,0,0}, {35214,35371,35212 ,730,730,730 ,0,0,0}, + {35208,35209,35370 ,730,730,730 ,0,0,0}, {38030,35129,35360 ,730,730,730 ,0,0,0}, + {35358,37942,35360 ,730,730,730 ,0,0,0}, {35354,35356,37943 ,730,730,730 ,0,0,0}, + {35354,37943,35358 ,730,730,730 ,0,0,0}, {38118,35356,35352 ,730,730,730 ,0,0,0}, + {35356,38118,37943 ,730,730,730 ,0,0,0}, {35351,37945,35352 ,730,730,730 ,0,0,0}, + {38118,35352,37945 ,730,730,730 ,0,0,0}, {33841,37945,35346 ,730,730,730 ,0,0,0}, + {37945,35351,35346 ,730,730,730 ,0,0,0}, {35347,38119,38120 ,730,730,730 ,0,0,0}, + {35346,35348,38121 ,730,730,730 ,0,0,0}, {37944,33841,35557 ,730,730,730 ,0,0,0}, + {35340,38122,35342 ,730,730,730 ,0,0,0}, {38123,35334,38124 ,730,730,730 ,0,0,0}, + {35338,38125,38126 ,730,730,730 ,0,0,0}, {38127,38128,35386 ,730,730,730 ,0,0,0}, + {38129,38130,35335 ,730,730,730 ,0,0,0}, {35389,38117,38127 ,730,730,730 ,0,0,0}, + {35392,35395,35543 ,730,730,730 ,0,0,0}, {33824,35391,35392 ,730,730,730 ,0,0,0}, + {35543,35395,37940 ,730,730,730 ,0,0,0}, {35385,38131,35335 ,730,730,730 ,0,0,0}, + {35541,37940,35539 ,730,730,730 ,0,0,0}, {38132,35530,35529 ,730,730,730 ,0,0,0}, + {35397,35398,35744 ,730,730,730 ,0,0,0}, {35397,35744,35395 ,730,730,730 ,0,0,0}, + {38133,38134,35403 ,730,730,730 ,0,0,0}, {38135,35401,38134 ,730,730,730 ,0,0,0}, + {35329,35408,38136 ,730,730,730 ,0,0,0}, {35404,35330,38137 ,730,730,730 ,0,0,0}, + {37941,35727,37938 ,730,730,730 ,0,0,0}, {37670,38138,37668 ,730,730,730 ,0,0,0}, + {35415,37668,35414 ,730,730,730 ,0,0,0}, {37669,37668,38139 ,730,730,730 ,0,0,0}, + {35420,37668,35418 ,730,730,730 ,0,0,0}, {37668,35415,35418 ,730,730,730 ,0,0,0}, + {37807,35420,35421 ,730,730,730 ,0,0,0}, {35426,37807,35424 ,730,730,730 ,0,0,0}, + {37807,35421,35424 ,730,730,730 ,0,0,0}, {37807,37930,38074 ,730,730,730 ,0,0,0}, + {37807,38073,38140 ,730,730,730 ,0,0,0}, {38140,37911,37910 ,730,730,730 ,0,0,0}, + {37910,37807,38140 ,730,730,730 ,0,0,0}, {37634,37633,38141 ,730,730,730 ,0,0,0}, + {37909,38141,37633 ,730,730,730 ,0,0,0}, {37635,37634,37811 ,730,730,730 ,0,0,0}, + {38080,37812,38081 ,730,730,730 ,0,0,0}, {38081,37812,37929 ,730,730,730 ,0,0,0}, + {38080,38082,37927 ,730,730,730 ,0,0,0}, {38142,37928,37927 ,730,730,730 ,0,0,0}, + {37927,38082,38142 ,730,730,730 ,0,0,0}, {35601,38143,38144 ,730,730,730 ,0,0,0}, + {38145,38083,35495 ,730,730,730 ,0,0,0}, {38146,38147,35503 ,730,730,730 ,0,0,0}, + {38148,38149,35248 ,730,730,730 ,0,0,0}, {38150,35486,35489 ,730,730,730 ,0,0,0}, + {38151,35491,38152 ,730,730,730 ,0,0,0}, {38153,35435,35485 ,730,730,730 ,0,0,0}, + {38154,35486,38150 ,730,730,730 ,0,0,0}, {38155,32893,37772 ,730,730,730 ,0,0,0}, + {38156,35434,35433 ,730,730,730 ,0,0,0}, {38157,38158,38159 ,730,730,730 ,0,0,0}, + {35448,35447,38089 ,730,730,730 ,0,0,0}, {38088,38160,35446 ,730,730,730 ,0,0,0}, + {38161,35447,35442 ,730,730,730 ,0,0,0}, {38162,38163,38164 ,730,730,730 ,0,0,0}, + {38165,35596,35599 ,730,730,730 ,0,0,0}, {38166,38167,38168 ,730,730,730 ,0,0,0}, + {35301,35303,38169 ,730,730,730 ,0,0,0}, {38170,35298,35301 ,730,730,730 ,0,0,0}, + {35608,38171,35609 ,730,730,730 ,0,0,0}, {38172,35246,38149 ,730,730,730 ,0,0,0}, + {35295,35297,38173 ,730,730,730 ,0,0,0}, {35233,38174,38175 ,730,730,730 ,0,0,0}, + {38086,38087,38068 ,730,730,730 ,0,0,0}, {35298,38176,35297 ,730,730,730 ,0,0,0}, + {38069,38177,38067 ,730,730,730 ,0,0,0}, {38087,38069,38068 ,730,730,730 ,0,0,0}, + {38070,38072,38177 ,730,730,730 ,0,0,0}, {38067,38177,38072 ,730,730,730 ,0,0,0}, + {38071,38070,38066 ,730,730,730 ,0,0,0}, {38178,38065,38064 ,730,730,730 ,0,0,0}, + {38065,38071,38066 ,730,730,730 ,0,0,0}, {38178,37780,37779 ,730,730,730 ,0,0,0}, + {37780,38178,38064 ,730,730,730 ,0,0,0}, {37778,38059,37779 ,730,730,730 ,0,0,0}, + {38060,38061,38058 ,730,730,730 ,0,0,0}, {37778,38060,38059 ,730,730,730 ,0,0,0}, + {38063,38062,38116 ,730,730,730 ,0,0,0}, {38058,38061,38063 ,730,730,730 ,0,0,0}, + {35227,38115,35382 ,730,730,730 ,0,0,0}, {38116,38062,38115 ,730,730,730 ,0,0,0}, + {38179,35953,35951 ,730,730,730 ,0,0,0}, {34905,3897,38180 ,730,730,730 ,0,0,0}, + {34141,34944,38181 ,730,730,730 ,0,0,0}, {38182,38011,38183 ,730,730,730 ,0,0,0}, + {36155,38006,36157 ,730,730,730 ,0,0,0}, {38184,36166,3897 ,730,730,730 ,0,0,0}, + {36161,38185,38186 ,730,730,730 ,0,0,0}, {38187,36169,36167 ,730,730,730 ,0,0,0}, + {38188,38189,38190 ,730,730,730 ,0,0,0}, {38015,35079,35078 ,730,730,730 ,0,0,0}, + {34866,38191,34867 ,730,730,730 ,0,0,0}, {38002,38003,35960 ,730,730,730 ,0,0,0}, + {38192,38193,38194 ,730,730,730 ,0,0,0}, {34208,34890,34888 ,730,730,730 ,0,0,0}, + {34890,34208,34206 ,730,730,730 ,0,0,0}, {37484,34206,38195 ,730,730,730 ,0,0,0}, + {34205,38196,38195 ,730,730,730 ,0,0,0}, {34219,34230,35954 ,730,730,730 ,0,0,0}, + {38197,38198,38199 ,730,730,730 ,0,0,0}, {38200,38201,38202 ,730,730,730 ,0,0,0}, + {3917,34857,37982 ,730,730,730 ,0,0,0}, {37962,38203,34855 ,730,730,730 ,0,0,0}, + {34855,34854,37962 ,730,730,730 ,0,0,0}, {34851,38204,37546 ,730,730,730 ,0,0,0}, + {34849,38204,34851 ,730,730,730 ,0,0,0}, {34841,34843,38205 ,730,730,730 ,0,0,0}, + {38206,37964,34133 ,730,730,730 ,0,0,0}, {34947,34944,34141 ,730,730,730 ,0,0,0}, + {37963,34830,38207 ,730,730,730 ,0,0,0}, {34829,34124,34122 ,730,730,730 ,0,0,0}, + {34952,34950,34138 ,730,730,730 ,0,0,0}, {38208,37973,34922 ,730,730,730 ,0,0,0}, + {38209,35967,35968 ,730,730,730 ,0,0,0}, {36130,36133,38210 ,730,730,730 ,0,0,0}, + {34921,36127,36129 ,730,730,730 ,0,0,0}, {38211,34062,37975 ,730,730,730 ,0,0,0}, + {36121,36123,34929 ,730,730,730 ,0,0,0}, {34928,36118,36121 ,730,730,730 ,0,0,0}, + {34052,34910,34892 ,730,730,730 ,0,0,0}, {36115,36117,34933 ,730,730,730 ,0,0,0}, + {36115,34935,36112 ,730,730,730 ,0,0,0}, {34040,37530,38212 ,730,730,730 ,0,0,0}, + {35791,35802,35910 ,730,730,730 ,0,0,0}, {34722,38213,34719 ,730,730,730 ,0,0,0}, + {37882,37883,34793 ,730,730,730 ,0,0,0}, {37833,38214,38215 ,730,730,730 ,0,0,0}, + {38216,37843,38217 ,730,730,730 ,0,0,0}, {37841,38218,34374 ,730,730,730 ,0,0,0}, + {34395,38219,34393 ,730,730,730 ,0,0,0}, {38220,34379,38221 ,730,730,730 ,0,0,0}, + {38222,38223,38224 ,730,730,730 ,0,0,0}, {34762,34759,35783 ,730,730,730 ,0,0,0}, + {34744,37835,37903 ,730,730,730 ,0,0,0}, {37908,34737,34741 ,730,730,730 ,0,0,0}, + {38225,37903,38226 ,730,730,730 ,0,0,0}, {34741,34745,37908 ,730,730,730 ,0,0,0}, + {38227,38228,38226 ,730,730,730 ,0,0,0}, {38229,34736,37837 ,730,730,730 ,0,0,0}, + {38228,38230,38231 ,730,730,730 ,0,0,0}, {35913,35802,35803 ,730,730,730 ,0,0,0}, + {35912,35910,35802 ,730,730,730 ,0,0,0}, {38232,35044,35048 ,730,730,730 ,0,0,0}, + {35051,38233,35048 ,730,730,730 ,0,0,0}, {38234,38235,38236 ,730,730,730 ,0,0,0}, + {38237,38238,38239 ,730,730,730 ,0,0,0}, {38239,34798,38240 ,730,730,730 ,0,0,0}, + {34794,37883,34796 ,730,730,730 ,0,0,0}, {34821,38241,34449 ,730,730,730 ,0,0,0}, + {38242,37827,34787 ,730,730,730 ,0,0,0}, {38243,38244,34441 ,730,730,730 ,0,0,0}, + {34824,34821,34449 ,730,730,730 ,0,0,0}, {34430,34767,34432 ,730,730,730 ,0,0,0}, + {38242,34768,38245 ,730,730,730 ,0,0,0}, {2165,34827,34446 ,730,730,730 ,0,0,0}, + {37868,34800,37863 ,730,730,730 ,0,0,0}, {38246,35923,35924 ,730,730,730 ,0,0,0}, + {37865,38247,37866 ,730,730,730 ,0,0,0}, {34799,34803,38248 ,730,730,730 ,0,0,0}, + {37871,38248,34803 ,730,730,730 ,0,0,0}, {37872,34807,34806 ,730,730,730 ,0,0,0}, + {38249,34806,34809 ,730,730,730 ,0,0,0}, {34416,34725,34706 ,730,730,730 ,0,0,0}, + {37879,34813,38250 ,730,730,730 ,0,0,0}, {34813,38251,38250 ,730,730,730 ,0,0,0}, + {34404,37880,37885 ,730,730,730 ,0,0,0}, {34108,38252,38253 ,730,730,730 ,0,0,0}, + {34603,37682,34606 ,730,730,730 ,0,0,0}, {38254,36033,36032 ,730,730,730 ,0,0,0}, + {38255,38256,38257 ,730,730,730 ,0,0,0}, {37589,38258,38255 ,730,730,730 ,0,0,0}, + {34180,34178,38259 ,730,730,730 ,0,0,0}, {34199,38260,34197 ,730,730,730 ,0,0,0}, + {34191,34655,34192 ,730,730,730 ,0,0,0}, {38261,38262,34183 ,730,730,730 ,0,0,0}, + {38263,38264,38265 ,730,730,730 ,0,0,0}, {38264,38263,38266 ,730,730,730 ,0,0,0}, + {36008,36011,37711 ,730,730,730 ,0,0,0}, {38267,35999,38268 ,730,730,730 ,0,0,0}, + {37718,35989,38269 ,730,730,730 ,0,0,0}, {34674,34094,35984 ,730,730,730 ,0,0,0}, + {34096,34674,34672 ,730,730,730 ,0,0,0}, {34099,34664,38270 ,730,730,730 ,0,0,0}, + {38271,34113,37721 ,730,730,730 ,0,0,0}, {35981,35983,34094 ,730,730,730 ,0,0,0}, + {38272,3029,38273 ,730,730,730 ,0,0,0}, {35854,38274,38275 ,730,730,730 ,0,0,0}, + {36035,3029,36038 ,730,730,730 ,0,0,0}, {34367,34637,34365 ,730,730,730 ,0,0,0}, + {34701,36041,36039 ,730,730,730 ,0,0,0}, {35873,35874,34370 ,730,730,730 ,0,0,0}, + {35874,34359,34370 ,730,730,730 ,0,0,0}, {36041,34701,34700 ,730,730,730 ,0,0,0}, + {34359,35877,35879 ,730,730,730 ,0,0,0}, {37754,37753,37736 ,730,730,730 ,0,0,0}, + {38276,37754,37736 ,730,730,730 ,0,0,0}, {34640,34362,34642 ,730,730,730 ,0,0,0}, + {34353,34682,34351 ,730,730,730 ,0,0,0}, {38277,34612,34611 ,730,730,730 ,0,0,0}, + {38278,34612,38277 ,730,730,730 ,0,0,0}, {38279,35889,38280 ,730,730,730 ,0,0,0}, + {38281,34286,37739 ,730,730,730 ,0,0,0}, {34619,38282,34615 ,730,730,730 ,0,0,0}, + {34618,37742,38282 ,730,730,730 ,0,0,0}, {34276,34600,34582 ,730,730,730 ,0,0,0}, + {38283,37745,34623 ,730,730,730 ,0,0,0}, {38283,34625,37744 ,730,730,730 ,0,0,0}, + {37733,38284,34264 ,730,730,730 ,0,0,0}, {38285,35810,38286 ,730,730,730 ,0,0,0}, + {36069,36071,38287 ,730,730,730 ,0,0,0}, {38288,34085,34573 ,730,730,730 ,0,0,0}, + {38289,37517,38290 ,730,730,730 ,0,0,0}, {38291,38292,38293 ,730,730,730 ,0,0,0}, + {38294,38295,34241 ,730,730,730 ,0,0,0}, {34233,38296,37513 ,730,730,730 ,0,0,0}, + {38297,37562,38298 ,730,730,730 ,0,0,0}, {38299,38300,38301 ,730,730,730 ,0,0,0}, + {38302,38303,38304 ,730,730,730 ,0,0,0}, {38305,38306,38303 ,730,730,730 ,0,0,0}, + {38307,37582,37584 ,730,730,730 ,0,0,0}, {38308,37548,38309 ,730,730,730 ,0,0,0}, + {37567,38310,38311 ,730,730,730 ,0,0,0}, {38312,2073,37578 ,730,730,730 ,0,0,0}, + {34152,34517,34515 ,730,730,730 ,0,0,0}, {34514,34157,34515 ,730,730,730 ,0,0,0}, + {34155,34514,34511 ,730,730,730 ,0,0,0}, {34155,34509,38313 ,730,730,730 ,0,0,0}, + {34488,37539,37538 ,730,730,730 ,0,0,0}, {34488,36063,36065 ,730,730,730 ,0,0,0}, + {34484,36060,34486 ,730,730,730 ,0,0,0}, {36059,34484,34483 ,730,730,730 ,0,0,0}, + {35830,34090,35829 ,730,730,730 ,0,0,0}, {34483,34480,36057 ,730,730,730 ,0,0,0}, + {34478,36054,34480 ,730,730,730 ,0,0,0}, {34077,36085,36084 ,730,730,730 ,0,0,0}, + {34469,34471,37528 ,730,730,730 ,0,0,0}, {34576,34573,34085 ,730,730,730 ,0,0,0}, + {34066,34458,34457 ,730,730,730 ,0,0,0}, {34068,34457,34461 ,730,730,730 ,0,0,0}, + {2082,34579,34082 ,730,730,730 ,0,0,0}, {34552,38314,37529 ,730,730,730 ,0,0,0}, + {36091,36090,38315 ,730,730,730 ,0,0,0}, {38315,38316,36091 ,730,730,730 ,0,0,0}, + {35845,38317,38318 ,730,730,730 ,0,0,0}, {36097,38314,36099 ,730,730,730 ,0,0,0}, + {37604,34342,38319 ,730,730,730 ,0,0,0}, {36102,36099,34551 ,730,730,730 ,0,0,0}, + {34520,34332,34539 ,730,730,730 ,0,0,0}, {36102,34555,36103 ,730,730,730 ,0,0,0}, + {34559,36105,36103 ,730,730,730 ,0,0,0}, {34971,38320,34328 ,730,730,730 ,0,0,0}, + {35051,38235,38233 ,730,730,730 ,0,0,0}, {2131,35778,38321 ,730,730,730 ,0,0,0}, + {35917,35918,34454 ,730,730,730 ,0,0,0}, {38234,38233,38235 ,730,730,730 ,0,0,0}, + {38234,38236,38240 ,730,730,730 ,0,0,0}, {38240,34798,37884 ,730,730,730 ,0,0,0}, + {37884,38234,38240 ,730,730,730 ,0,0,0}, {34796,37884,34798 ,730,730,730 ,0,0,0}, + {37818,38322,35904 ,730,730,730 ,0,0,0}, {38323,38324,35794 ,730,730,730 ,0,0,0}, + {34443,35921,35923 ,730,730,730 ,0,0,0}, {37883,34794,34793 ,730,730,730 ,0,0,0}, + {38325,35897,35895 ,730,730,730 ,0,0,0}, {35791,35910,35904 ,730,730,730 ,0,0,0}, + {35916,35913,35803 ,730,730,730 ,0,0,0}, {35916,37901,38231 ,730,730,730 ,0,0,0}, + {38231,38230,35916 ,730,730,730 ,0,0,0}, {38227,38230,38228 ,730,730,730 ,0,0,0}, + {38225,38226,38228 ,730,730,730 ,0,0,0}, {38326,38327,38328 ,730,730,730 ,0,0,0}, + {35780,34763,35785 ,730,730,730 ,0,0,0}, {37908,34745,38225 ,730,730,730 ,0,0,0}, + {38329,38330,38331 ,730,730,730 ,0,0,0}, {38332,38333,38334 ,730,730,730 ,0,0,0}, + {35778,2131,35780 ,730,730,730 ,0,0,0}, {38335,38336,38337 ,730,730,730 ,0,0,0}, + {35778,35777,38321 ,730,730,730 ,0,0,0}, {38338,38339,38340 ,730,730,730 ,0,0,0}, + {37912,35788,37918 ,730,730,730 ,0,0,0}, {38321,35777,37912 ,730,730,730 ,0,0,0}, + {37917,35789,35050 ,730,730,730 ,0,0,0}, {35776,38050,38041 ,730,730,730 ,0,0,0}, + {35133,38341,35134 ,730,730,730 ,0,0,0}, {35772,38050,35774 ,730,730,730 ,0,0,0}, + {38050,35776,35774 ,730,730,730 ,0,0,0}, {35768,38050,35771 ,730,730,730 ,0,0,0}, + {38050,35772,35771 ,730,730,730 ,0,0,0}, {35765,38050,35766 ,730,730,730 ,0,0,0}, + {38050,35768,35766 ,730,730,730 ,0,0,0}, {38050,35765,35746 ,730,730,730 ,0,0,0}, + {37948,38050,35749 ,730,730,730 ,0,0,0}, {35745,35749,38050 ,730,730,730 ,0,0,0}, + {35587,35757,35759 ,730,730,730 ,0,0,0}, {35755,35585,35584 ,730,730,730 ,0,0,0}, + {37948,35749,35753 ,730,730,730 ,0,0,0}, {35587,35585,35757 ,730,730,730 ,0,0,0}, + {35191,37931,35189 ,730,730,730 ,0,0,0}, {35138,38047,35140 ,730,730,730 ,0,0,0}, + {37467,35140,38046 ,730,730,730 ,0,0,0}, {35147,37946,38044 ,730,730,730 ,0,0,0}, + {35146,35148,38043 ,730,730,730 ,0,0,0}, {35148,35147,38044 ,730,730,730 ,0,0,0}, + {35151,35146,37489 ,730,730,730 ,0,0,0}, {37490,35146,38043 ,730,730,730 ,0,0,0}, + {38042,35152,38038 ,730,730,730 ,0,0,0}, {38038,35151,37489 ,730,730,730 ,0,0,0}, + {37479,35154,35156 ,730,730,730 ,0,0,0}, {38042,35156,35152 ,730,730,730 ,0,0,0}, + {37480,35158,35154 ,730,730,730 ,0,0,0}, {37482,35160,35158 ,730,730,730 ,0,0,0}, + {37477,37486,37478 ,730,730,730 ,0,0,0}, {35160,37482,37481 ,730,730,730 ,0,0,0}, + {37473,37471,37463 ,730,730,730 ,0,0,0}, {35776,38039,37463 ,730,730,730 ,0,0,0}, + {37940,35395,35744 ,730,730,730 ,0,0,0}, {35409,38342,35408 ,730,730,730 ,0,0,0}, + {35739,35736,37940 ,730,730,730 ,0,0,0}, {35739,37940,35740 ,730,730,730 ,0,0,0}, + {35736,37935,37940 ,730,730,730 ,0,0,0}, {35734,37934,37935 ,730,730,730 ,0,0,0}, + {35733,37933,37934 ,730,730,730 ,0,0,0}, {35713,37933,35714 ,730,730,730 ,0,0,0}, + {35717,37936,35713 ,730,730,730 ,0,0,0}, {35721,37896,37939 ,730,730,730 ,0,0,0}, + {35721,37939,35717 ,730,730,730 ,0,0,0}, {37941,37896,35723 ,730,730,730 ,0,0,0}, + {37941,35725,35727 ,730,730,730 ,0,0,0}, {37938,35727,35730 ,730,730,730 ,0,0,0}, + {38343,38344,37937 ,730,730,730 ,0,0,0}, {37937,35730,38343 ,730,730,730 ,0,0,0}, + {38343,38056,38344 ,730,730,730 ,0,0,0}, {38057,35414,38138 ,730,730,730 ,0,0,0}, + {38056,38055,38344 ,730,730,730 ,0,0,0}, {37668,38054,38139 ,730,730,730 ,0,0,0}, + {38055,38054,37668 ,730,730,730 ,0,0,0}, {35414,37668,38138 ,730,730,730 ,0,0,0}, + {35409,35412,38057 ,730,730,730 ,0,0,0}, {38136,35408,38342 ,730,730,730 ,0,0,0}, + {38342,35409,38057 ,730,730,730 ,0,0,0}, {38137,35329,38136 ,730,730,730 ,0,0,0}, + {38137,38133,35404 ,730,730,730 ,0,0,0}, {38137,35330,35329 ,730,730,730 ,0,0,0}, + {35403,38134,35401 ,730,730,730 ,0,0,0}, {35404,38133,35403 ,730,730,730 ,0,0,0}, + {35401,38135,35398 ,730,730,730 ,0,0,0}, {35744,35398,38135 ,730,730,730 ,0,0,0}, + {38345,37800,38346 ,730,730,730 ,0,0,0}, {38347,38348,38349 ,730,730,730 ,0,0,0}, + {37801,37805,38350 ,730,730,730 ,0,0,0}, {38346,37800,38351 ,730,730,730 ,0,0,0}, + {38352,32876,38353 ,730,730,730 ,0,0,0}, {38354,35504,35430 ,730,730,730 ,0,0,0}, + {35508,35509,38355 ,730,730,730 ,0,0,0}, {35451,38356,35452 ,730,730,730 ,0,0,0}, + {37801,35526,35527 ,730,730,730 ,0,0,0}, {35685,35689,37800 ,730,730,730 ,0,0,0}, + {35688,37795,37800 ,730,730,730 ,0,0,0}, {35693,37795,35691 ,730,730,730 ,0,0,0}, + {35695,37803,35693 ,730,730,730 ,0,0,0}, {35698,37796,37802 ,730,730,730 ,0,0,0}, + {35698,37802,35695 ,730,730,730 ,0,0,0}, {37785,37784,37796 ,730,730,730 ,0,0,0}, + {37806,37784,37786 ,730,730,730 ,0,0,0}, {37794,37792,37791 ,730,730,730 ,0,0,0}, + {37790,37792,37806 ,730,730,730 ,0,0,0}, {38357,37787,37793 ,730,730,730 ,0,0,0}, + {37793,37794,37791 ,730,730,730 ,0,0,0}, {38349,37789,37788 ,730,730,730 ,0,0,0}, + {37788,37787,38357 ,730,730,730 ,0,0,0}, {38347,38358,38348 ,730,730,730 ,0,0,0}, + {38349,38348,37789 ,730,730,730 ,0,0,0}, {38359,38358,38360 ,730,730,730 ,0,0,0}, + {38347,38360,38358 ,730,730,730 ,0,0,0}, {38361,38359,38362 ,730,730,730 ,0,0,0}, + {38359,38360,38362 ,730,730,730 ,0,0,0}, {38363,38364,35712 ,730,730,730 ,0,0,0}, + {38359,38361,38364 ,730,730,730 ,0,0,0}, {37657,35678,35676 ,730,730,730 ,0,0,0}, + {38099,38365,35641 ,730,730,730 ,0,0,0}, {37662,35675,38366 ,730,730,730 ,0,0,0}, + {35675,37662,35676 ,730,730,730 ,0,0,0}, {38366,35672,35670 ,730,730,730 ,0,0,0}, + {35675,35672,38366 ,730,730,730 ,0,0,0}, {38366,35669,35650 ,730,730,730 ,0,0,0}, + {35670,35669,38366 ,730,730,730 ,0,0,0}, {38367,38368,35653 ,730,730,730 ,0,0,0}, + {35657,38367,35653 ,730,730,730 ,0,0,0}, {35661,38369,35659 ,730,730,730 ,0,0,0}, + {35656,38370,38371 ,730,730,730 ,0,0,0}, {38372,35645,35644 ,730,730,730 ,0,0,0}, + {35644,38365,38372 ,730,730,730 ,0,0,0}, {35645,38373,35647 ,730,730,730 ,0,0,0}, + {38372,38373,35645 ,730,730,730 ,0,0,0}, {35647,38374,33525 ,730,730,730 ,0,0,0}, + {37654,37649,37648 ,730,730,730 ,0,0,0}, {37644,37643,37648 ,730,730,730 ,0,0,0}, + {37644,37648,37650 ,730,730,730 ,0,0,0}, {37637,37636,37643 ,730,730,730 ,0,0,0}, + {37638,37642,37636 ,730,730,730 ,0,0,0}, {38375,37641,37640 ,730,730,730 ,0,0,0}, + {37640,37642,37658 ,730,730,730 ,0,0,0}, {38376,38375,37647 ,730,730,730 ,0,0,0}, + {38375,38376,37641 ,730,730,730 ,0,0,0}, {37645,38377,37646 ,730,730,730 ,0,0,0}, + {38376,37647,37646 ,730,730,730 ,0,0,0}, {37651,37653,38377 ,730,730,730 ,0,0,0}, + {37646,38377,37653 ,730,730,730 ,0,0,0}, {37653,37652,37656 ,730,730,730 ,0,0,0}, + {35680,37656,37652 ,730,730,730 ,0,0,0}, {35641,35639,38099 ,730,730,730 ,0,0,0}, + {38378,33508,38379 ,730,730,730 ,0,0,0}, {38380,38381,38379 ,730,730,730 ,0,0,0}, + {35246,38172,35251 ,730,730,730 ,0,0,0}, {35309,35466,35470 ,730,730,730 ,0,0,0}, + {35470,35308,35309 ,730,730,730 ,0,0,0}, {35473,35315,35475 ,730,730,730 ,0,0,0}, + {35308,35461,35229 ,730,730,730 ,0,0,0}, {35460,35229,35461 ,730,730,730 ,0,0,0}, + {35324,35478,35477 ,730,730,730 ,0,0,0}, {35247,38148,35248 ,730,730,730 ,0,0,0}, + {37495,37494,38078 ,730,730,730 ,0,0,0}, {38382,35617,35615 ,730,730,730 ,0,0,0}, + {37667,35614,35611 ,730,730,730 ,0,0,0}, {35617,37776,32893 ,730,730,730 ,0,0,0}, + {38383,38384,38378 ,730,730,730 ,0,0,0}, {33508,38380,38379 ,730,730,730 ,0,0,0}, + {38381,38385,38386 ,730,730,730 ,0,0,0}, {38380,38385,38381 ,730,730,730 ,0,0,0}, + {38387,37661,38386 ,730,730,730 ,0,0,0}, {38381,38386,37661 ,730,730,730 ,0,0,0}, + {38388,37661,38389 ,730,730,730 ,0,0,0}, {37661,38387,38389 ,730,730,730 ,0,0,0}, + {37660,38390,37661 ,730,730,730 ,0,0,0}, {37661,38388,37659 ,730,730,730 ,0,0,0}, + {37648,37661,38391 ,730,730,730 ,0,0,0}, {38390,38391,37661 ,730,730,730 ,0,0,0}, + {38392,37648,38393 ,730,730,730 ,0,0,0}, {37648,38391,38393 ,730,730,730 ,0,0,0}, + {38097,37648,38394 ,730,730,730 ,0,0,0}, {37648,38392,38394 ,730,730,730 ,0,0,0}, + {38098,33525,38374 ,730,730,730 ,0,0,0}, {38395,38363,38396 ,730,730,730 ,0,0,0}, + {38087,35458,35454 ,730,730,730 ,0,0,0}, {38397,38398,38359 ,730,730,730 ,0,0,0}, + {35456,38399,38400 ,730,730,730 ,0,0,0}, {35454,35456,38400 ,730,730,730 ,0,0,0}, + {38399,35452,38356 ,730,730,730 ,0,0,0}, {38143,35601,35603 ,730,730,730 ,0,0,0}, + {38160,35451,35446 ,730,730,730 ,0,0,0}, {32876,38401,35603 ,730,730,730 ,0,0,0}, + {38401,32876,38352 ,730,730,730 ,0,0,0}, {37928,38142,35504 ,730,730,730 ,0,0,0}, + {38363,35682,35681 ,730,730,730 ,0,0,0}, {35702,38363,35704 ,730,730,730 ,0,0,0}, + {38402,38403,38363 ,730,730,730 ,0,0,0}, {38363,38404,38405 ,730,730,730 ,0,0,0}, + {35708,35707,38363 ,730,730,730 ,0,0,0}, {38405,38406,38363 ,730,730,730 ,0,0,0}, + {38407,38359,38353 ,730,730,730 ,0,0,0}, {38363,38359,38364 ,730,730,730 ,0,0,0}, + {38359,38408,38397 ,730,730,730 ,0,0,0}, {38359,38407,38408 ,730,730,730 ,0,0,0}, + {38409,38167,38398 ,730,730,730 ,0,0,0}, {38359,38398,38167 ,730,730,730 ,0,0,0}, + {38410,38167,38411 ,730,730,730 ,0,0,0}, {38167,38409,38411 ,730,730,730 ,0,0,0}, + {38168,38167,38412 ,730,730,730 ,0,0,0}, {38167,38410,38412 ,730,730,730 ,0,0,0}, + {38166,38413,38167 ,730,730,730 ,0,0,0}, {38091,38090,38413 ,730,730,730 ,0,0,0}, + {38167,38413,38090 ,730,730,730 ,0,0,0}, {38090,38092,38155 ,730,730,730 ,0,0,0}, + {32893,38155,38092 ,730,730,730 ,0,0,0}, {33209,35759,35762 ,730,730,730 ,0,0,0}, + {35186,38414,35185 ,730,730,730 ,0,0,0}, {35584,35752,35755 ,730,730,730 ,0,0,0}, + {35585,35755,35757 ,730,730,730 ,0,0,0}, {35752,35581,35753 ,730,730,730 ,0,0,0}, + {35584,35581,35752 ,730,730,730 ,0,0,0}, {35753,35579,37948 ,730,730,730 ,0,0,0}, + {37948,35560,35559 ,730,730,730 ,0,0,0}, {35578,35560,37948 ,730,730,730 ,0,0,0}, + {33192,35197,38029 ,730,730,730 ,0,0,0}, {35566,37948,35567 ,730,730,730 ,0,0,0}, + {35559,35563,37948 ,730,730,730 ,0,0,0}, {37948,35569,38052 ,730,730,730 ,0,0,0}, + {35569,37948,35566 ,730,730,730 ,0,0,0}, {33192,38029,38053 ,730,730,730 ,0,0,0}, + {38052,35571,35573 ,730,730,730 ,0,0,0}, {35569,35571,38052 ,730,730,730 ,0,0,0}, + {33192,38053,35573 ,730,730,730 ,0,0,0}, {33192,38031,35197 ,730,730,730 ,0,0,0}, + {38032,35192,35195 ,730,730,730 ,0,0,0}, {37931,35191,38033 ,730,730,730 ,0,0,0}, + {35186,35189,37932 ,730,730,730 ,0,0,0}, {38415,38414,35186 ,730,730,730 ,0,0,0}, + {38415,35186,37932 ,730,730,730 ,0,0,0}, {38416,35185,38414 ,730,730,730 ,0,0,0}, + {35135,38416,38049 ,730,730,730 ,0,0,0}, {38416,35135,35185 ,730,730,730 ,0,0,0}, + {38049,38417,35133 ,730,730,730 ,0,0,0}, {38341,38048,35134 ,730,730,730 ,0,0,0}, + {38417,38341,35133 ,730,730,730 ,0,0,0}, {38047,38046,35140 ,730,730,730 ,0,0,0}, + {35134,38048,35138 ,730,730,730 ,0,0,0}, {35762,38045,33209 ,730,730,730 ,0,0,0}, + {38046,38047,38045 ,730,730,730 ,0,0,0}, {35557,38418,37944 ,730,730,730 ,0,0,0}, + {35385,35386,38128 ,730,730,730 ,0,0,0}, {38418,35555,35554 ,730,730,730 ,0,0,0}, + {35557,35555,38418 ,730,730,730 ,0,0,0}, {35551,38132,35554 ,730,730,730 ,0,0,0}, + {38418,35554,38132 ,730,730,730 ,0,0,0}, {35548,38132,35549 ,730,730,730 ,0,0,0}, + {38132,35551,35549 ,730,730,730 ,0,0,0}, {38132,35548,35530 ,730,730,730 ,0,0,0}, + {38132,35533,35537 ,730,730,730 ,0,0,0}, {35529,35533,38132 ,730,730,730 ,0,0,0}, + {35536,37940,35537 ,730,730,730 ,0,0,0}, {38132,35537,37940 ,730,730,730 ,0,0,0}, + {35543,37940,35541 ,730,730,730 ,0,0,0}, {37940,35536,35539 ,730,730,730 ,0,0,0}, + {35543,33824,35392 ,730,730,730 ,0,0,0}, {38117,35389,35391 ,730,730,730 ,0,0,0}, + {38127,35386,35389 ,730,730,730 ,0,0,0}, {38131,35385,38128 ,730,730,730 ,0,0,0}, + {35333,35335,38130 ,730,730,730 ,0,0,0}, {38129,35335,38131 ,730,730,730 ,0,0,0}, + {35333,38124,35334 ,730,730,730 ,0,0,0}, {38124,35333,38130 ,730,730,730 ,0,0,0}, + {38123,35338,35334 ,730,730,730 ,0,0,0}, {38126,35340,35338 ,730,730,730 ,0,0,0}, + {38123,38125,35338 ,730,730,730 ,0,0,0}, {38122,38119,35342 ,730,730,730 ,0,0,0}, + {38126,38122,35340 ,730,730,730 ,0,0,0}, {35347,38120,35348 ,730,730,730 ,0,0,0}, + {35342,38119,35347 ,730,730,730 ,0,0,0}, {35346,38121,33841 ,730,730,730 ,0,0,0}, + {35348,38120,38121 ,730,730,730 ,0,0,0}, {38419,37639,35242 ,730,730,730 ,0,0,0}, + {38420,35590,35589 ,730,730,730 ,0,0,0}, {35233,35235,38174 ,730,730,730 ,0,0,0}, + {35286,38075,35285 ,730,730,730 ,0,0,0}, {35289,38421,38422 ,730,730,730 ,0,0,0}, + {35295,38173,37664 ,730,730,730 ,0,0,0}, {38423,38424,35304 ,730,730,730 ,0,0,0}, + {38087,35454,38400 ,730,730,730 ,0,0,0}, {35456,35452,38399 ,730,730,730 ,0,0,0}, + {35451,38160,38356 ,730,730,730 ,0,0,0}, {35448,38088,35446 ,730,730,730 ,0,0,0}, + {38161,38089,35447 ,730,730,730 ,0,0,0}, {35503,35504,38146 ,730,730,730 ,0,0,0}, + {35442,35440,38085 ,730,730,730 ,0,0,0}, {38085,38161,35442 ,730,730,730 ,0,0,0}, + {35438,38084,35440 ,730,730,730 ,0,0,0}, {38425,35438,35434 ,730,730,730 ,0,0,0}, + {35438,38425,38084 ,730,730,730 ,0,0,0}, {38156,35433,38426 ,730,730,730 ,0,0,0}, + {38425,35434,38156 ,730,730,730 ,0,0,0}, {35501,38147,37783 ,730,730,730 ,0,0,0}, + {35435,38153,38426 ,730,730,730 ,0,0,0}, {38426,35433,35435 ,730,730,730 ,0,0,0}, + {38154,38153,35485 ,730,730,730 ,0,0,0}, {35497,37782,38145 ,730,730,730 ,0,0,0}, + {35486,38154,35485 ,730,730,730 ,0,0,0}, {38151,35489,35491 ,730,730,730 ,0,0,0}, + {35489,38151,38150 ,730,730,730 ,0,0,0}, {35491,35492,38152 ,730,730,730 ,0,0,0}, + {35497,38145,35495 ,730,730,730 ,0,0,0}, {38152,35492,38083 ,730,730,730 ,0,0,0}, + {37783,37782,35498 ,730,730,730 ,0,0,0}, {35503,38147,35501 ,730,730,730 ,0,0,0}, + {38142,38146,35504 ,730,730,730 ,0,0,0}, {35504,38354,37928 ,730,730,730 ,0,0,0}, + {38354,35429,38355 ,730,730,730 ,0,0,0}, {35429,38354,35430 ,730,730,730 ,0,0,0}, + {35527,37804,37801 ,730,730,730 ,0,0,0}, {35429,35508,38355 ,730,730,730 ,0,0,0}, + {35512,38427,35509 ,730,730,730 ,0,0,0}, {38355,35509,38427 ,730,730,730 ,0,0,0}, + {35512,35514,38428 ,730,730,730 ,0,0,0}, {38428,38427,35512 ,730,730,730 ,0,0,0}, + {35526,37801,35524 ,730,730,730 ,0,0,0}, {38428,35515,38429 ,730,730,730 ,0,0,0}, + {35515,38428,35514 ,730,730,730 ,0,0,0}, {37801,38429,35518 ,730,730,730 ,0,0,0}, + {35515,35518,38429 ,730,730,730 ,0,0,0}, {35520,35521,37801 ,730,730,730 ,0,0,0}, + {35521,35524,37801 ,730,730,730 ,0,0,0}, {38351,37800,37801 ,730,730,730 ,0,0,0}, + {37801,38350,38351 ,730,730,730 ,0,0,0}, {38359,38363,38353 ,730,730,730 ,0,0,0}, + {37800,38345,38363 ,730,730,730 ,0,0,0}, {38345,38430,38363 ,730,730,730 ,0,0,0}, + {38430,38431,38363 ,730,730,730 ,0,0,0}, {35681,37800,38363 ,730,730,730 ,0,0,0}, + {38432,38353,38363 ,730,730,730 ,0,0,0}, {38396,38363,38431 ,730,730,730 ,0,0,0}, + {38363,38395,38402 ,730,730,730 ,0,0,0}, {35701,35682,38363 ,730,730,730 ,0,0,0}, + {38406,38432,38363 ,730,730,730 ,0,0,0}, {38363,35702,35701 ,730,730,730 ,0,0,0}, + {38363,38433,38404 ,730,730,730 ,0,0,0}, {35704,38363,35707 ,730,730,730 ,0,0,0}, + {38363,35710,35708 ,730,730,730 ,0,0,0}, {38363,35712,35710 ,730,730,730 ,0,0,0}, + {38432,38352,38353 ,730,730,730 ,0,0,0}, {38143,35603,38401 ,730,730,730 ,0,0,0}, + {38144,38165,35599 ,730,730,730 ,0,0,0}, {35599,35601,38144 ,730,730,730 ,0,0,0}, + {38093,35596,38165 ,730,730,730 ,0,0,0}, {35593,35597,38093 ,730,730,730 ,0,0,0}, + {38093,35597,35596 ,730,730,730 ,0,0,0}, {35593,38094,35589 ,730,730,730 ,0,0,0}, + {35590,38420,38171 ,730,730,730 ,0,0,0}, {35589,38094,38420 ,730,730,730 ,0,0,0}, + {37781,35609,38171 ,730,730,730 ,0,0,0}, {35608,35590,38171 ,730,730,730 ,0,0,0}, + {37667,35611,37781 ,730,730,730 ,0,0,0}, {37666,38382,35615 ,730,730,730 ,0,0,0}, + {37772,32893,37776 ,730,730,730 ,0,0,0}, {38382,37776,35617 ,730,730,730 ,0,0,0}, + {37772,37777,37773 ,730,730,730 ,0,0,0}, {38077,38079,37775 ,730,730,730 ,0,0,0}, + {38079,37774,37775 ,730,730,730 ,0,0,0}, {38079,38078,37494 ,730,730,730 ,0,0,0}, + {38434,37495,38435 ,730,730,730 ,0,0,0}, {38436,38437,37632 ,730,730,730 ,0,0,0}, + {37632,38437,37630 ,730,730,730 ,0,0,0}, {38159,38438,38157 ,730,730,730 ,0,0,0}, + {38438,38439,38440 ,730,730,730 ,0,0,0}, {38164,38163,38441 ,730,730,730 ,0,0,0}, + {38442,38443,38441 ,730,730,730 ,0,0,0}, {35326,35478,35324 ,730,730,730 ,0,0,0}, + {38444,35482,35327 ,730,730,730 ,0,0,0}, {35320,35465,35464 ,730,730,730 ,0,0,0}, + {35314,35315,35473 ,730,730,730 ,0,0,0}, {35312,35471,35466 ,730,730,730 ,0,0,0}, + {35314,35471,35312 ,730,730,730 ,0,0,0}, {38445,38446,38366 ,730,730,730 ,0,0,0}, + {35631,35633,38096 ,730,730,730 ,0,0,0}, {37625,35264,35275 ,730,730,730 ,0,0,0}, + {37626,35265,35264 ,730,730,730 ,0,0,0}, {35266,35270,38037 ,730,730,730 ,0,0,0}, + {37625,35275,35273 ,730,730,730 ,0,0,0}, {35271,35266,37629 ,730,730,730 ,0,0,0}, + {37620,35260,38103 ,730,730,730 ,0,0,0}, {37621,35254,38102 ,730,730,730 ,0,0,0}, + {35256,35252,37749 ,730,730,730 ,0,0,0}, {35251,38172,37748 ,730,730,730 ,0,0,0}, + {35248,38149,35246 ,730,730,730 ,0,0,0}, {37639,38148,35247 ,730,730,730 ,0,0,0}, + {35240,38447,38419 ,730,730,730 ,0,0,0}, {38419,35242,35240 ,730,730,730 ,0,0,0}, + {35460,35458,35230 ,730,730,730 ,0,0,0}, {38447,35238,37665 ,730,730,730 ,0,0,0}, + {35238,38447,35240 ,730,730,730 ,0,0,0}, {35234,38175,37665 ,730,730,730 ,0,0,0}, + {35230,38086,38423 ,730,730,730 ,0,0,0}, {35234,35233,38175 ,730,730,730 ,0,0,0}, + {38174,35235,38076 ,730,730,730 ,0,0,0}, {38423,35304,35230 ,730,730,730 ,0,0,0}, + {38076,35235,35285 ,730,730,730 ,0,0,0}, {38422,38075,35286 ,730,730,730 ,0,0,0}, + {35303,38424,38169 ,730,730,730 ,0,0,0}, {35291,38421,35289 ,730,730,730 ,0,0,0}, + {35289,38422,35286 ,730,730,730 ,0,0,0}, {38169,38170,35301 ,730,730,730 ,0,0,0}, + {37663,35291,35292 ,730,730,730 ,0,0,0}, {35291,37663,38421 ,730,730,730 ,0,0,0}, + {35292,35295,37664 ,730,730,730 ,0,0,0}, {38176,38173,35297 ,730,730,730 ,0,0,0}, + {38170,38176,35298 ,730,730,730 ,0,0,0}, {38424,35303,35304 ,730,730,730 ,0,0,0}, + {38086,35230,35458 ,730,730,730 ,0,0,0}, {35460,35230,35229 ,730,730,730 ,0,0,0}, + {35461,35308,35470 ,730,730,730 ,0,0,0}, {35309,35312,35466 ,730,730,730 ,0,0,0}, + {35314,35473,35471 ,730,730,730 ,0,0,0}, {38378,38448,38095 ,730,730,730 ,0,0,0}, + {35475,35318,35464 ,730,730,730 ,0,0,0}, {35318,35475,35315 ,730,730,730 ,0,0,0}, + {35320,35321,35465 ,730,730,730 ,0,0,0}, {35318,35320,35464 ,730,730,730 ,0,0,0}, + {35324,35477,35321 ,730,730,730 ,0,0,0}, {35465,35321,35477 ,730,730,730 ,0,0,0}, + {38448,38378,38384 ,730,730,730 ,0,0,0}, {35326,35327,35482 ,730,730,730 ,0,0,0}, + {35482,35478,35326 ,730,730,730 ,0,0,0}, {38162,38444,35327 ,730,730,730 ,0,0,0}, + {38383,38449,38384 ,730,730,730 ,0,0,0}, {38162,38164,38444 ,730,730,730 ,0,0,0}, + {38442,38440,38443 ,730,730,730 ,0,0,0}, {38163,38442,38441 ,730,730,730 ,0,0,0}, + {38449,38450,38451 ,730,730,730 ,0,0,0}, {38439,38438,38159 ,730,730,730 ,0,0,0}, + {38443,38440,38439 ,730,730,730 ,0,0,0}, {37631,38158,38157 ,730,730,730 ,0,0,0}, + {38158,37631,37630 ,730,730,730 ,0,0,0}, {38435,38436,38434 ,730,730,730 ,0,0,0}, + {38435,38437,38436 ,730,730,730 ,0,0,0}, {37494,37496,37674 ,730,730,730 ,0,0,0}, + {37496,37495,38434 ,730,730,730 ,0,0,0}, {38452,38450,37674 ,730,730,730 ,0,0,0}, + {37674,37496,38452 ,730,730,730 ,0,0,0}, {38451,38450,38452 ,730,730,730 ,0,0,0}, + {38383,38450,38449 ,730,730,730 ,0,0,0}, {38095,33508,38378 ,730,730,730 ,0,0,0}, + {37624,35631,38096 ,730,730,730 ,0,0,0}, {37623,37627,35626 ,730,730,730 ,0,0,0}, + {35626,35629,37623 ,730,730,730 ,0,0,0}, {37628,35623,35627 ,730,730,730 ,0,0,0}, + {37627,35627,35626 ,730,730,730 ,0,0,0}, {38101,35619,37628 ,730,730,730 ,0,0,0}, + {35623,37628,35619 ,730,730,730 ,0,0,0}, {35620,38101,38100 ,730,730,730 ,0,0,0}, + {35641,38365,35644 ,730,730,730 ,0,0,0}, {35638,35620,38100 ,730,730,730 ,0,0,0}, + {38097,38098,38453 ,730,730,730 ,0,0,0}, {35647,38373,38374 ,730,730,730 ,0,0,0}, + {37648,38453,35666 ,730,730,730 ,0,0,0}, {37648,38097,38453 ,730,730,730 ,0,0,0}, + {35666,38454,37622 ,730,730,730 ,0,0,0}, {38453,38454,35666 ,730,730,730 ,0,0,0}, + {37622,38455,35663 ,730,730,730 ,0,0,0}, {38369,35661,38455 ,730,730,730 ,0,0,0}, + {35663,38455,35661 ,730,730,730 ,0,0,0}, {35659,38369,38456 ,730,730,730 ,0,0,0}, + {38456,38370,35656 ,730,730,730 ,0,0,0}, {35656,35659,38456 ,730,730,730 ,0,0,0}, + {35657,35656,38371 ,730,730,730 ,0,0,0}, {35653,38368,35649 ,730,730,730 ,0,0,0}, + {38367,35657,38371 ,730,730,730 ,0,0,0}, {38457,38445,35649 ,730,730,730 ,0,0,0}, + {38457,35649,38368 ,730,730,730 ,0,0,0}, {38366,35650,38445 ,730,730,730 ,0,0,0}, + {38445,35650,35649 ,730,730,730 ,0,0,0}, {38446,38458,38366 ,730,730,730 ,0,0,0}, + {37626,38366,38459 ,730,730,730 ,0,0,0}, {38458,38459,38366 ,730,730,730 ,0,0,0}, + {38460,37626,38461 ,730,730,730 ,0,0,0}, {37626,38459,38461 ,730,730,730 ,0,0,0}, + {35282,37626,38462 ,730,730,730 ,0,0,0}, {37626,38460,38462 ,730,730,730 ,0,0,0}, + {37615,38463,38464 ,730,730,730 ,0,0,0}, {38465,37615,38466 ,730,730,730 ,0,0,0}, + {38467,37599,38468 ,730,730,730 ,0,0,0}, {37599,35116,38468 ,730,730,730 ,0,0,0}, + {38463,37599,38469 ,730,730,730 ,0,0,0}, {37599,38467,38469 ,730,730,730 ,0,0,0}, + {37615,37599,38463 ,730,730,730 ,0,0,0}, {38470,37615,38471 ,730,730,730 ,0,0,0}, + {37615,38464,38471 ,730,730,730 ,0,0,0}, {37615,38470,38466 ,730,730,730 ,0,0,0}, + {38465,35128,37615 ,730,730,730 ,0,0,0}, {37615,35128,37595 ,730,730,730 ,0,0,0}, + {35123,37595,35125 ,730,730,730 ,0,0,0}, {37595,35128,35125 ,730,730,730 ,0,0,0}, + {35113,37598,37595 ,730,730,730 ,0,0,0}, {35107,37595,35120 ,730,730,730 ,0,0,0}, + {37595,35122,35120 ,730,730,730 ,0,0,0}, {37595,35107,35113 ,730,730,730 ,0,0,0}, + {35114,37598,35110 ,730,730,730 ,0,0,0}, {37598,35113,35110 ,730,730,730 ,0,0,0}, + {35116,37598,35117 ,730,730,730 ,0,0,0}, {37598,35114,35117 ,730,730,730 ,0,0,0}, + {38028,38472,37956 ,730,730,730 ,0,0,0}, {38026,35094,38028 ,730,730,730 ,0,0,0}, + {37956,38473,38474 ,730,730,730 ,0,0,0}, {38472,38473,37956 ,730,730,730 ,0,0,0}, + {37957,37956,38475 ,730,730,730 ,0,0,0}, {38474,38475,37956 ,730,730,730 ,0,0,0}, + {38476,37957,38477 ,730,730,730 ,0,0,0}, {37957,38475,38477 ,730,730,730 ,0,0,0}, + {38478,37957,38479 ,730,730,730 ,0,0,0}, {37957,38476,38479 ,730,730,730 ,0,0,0}, + {38024,37957,38478 ,730,730,730 ,0,0,0}, {38024,38478,35106 ,730,730,730 ,0,0,0}, + {35098,38024,35100 ,730,730,730 ,0,0,0}, {38024,35106,35103 ,730,730,730 ,0,0,0}, + {38024,35101,35100 ,730,730,730 ,0,0,0}, {38026,38024,35085 ,730,730,730 ,0,0,0}, + {35098,35085,38024 ,730,730,730 ,0,0,0}, {35088,38026,35091 ,730,730,730 ,0,0,0}, + {38026,35085,35091 ,730,730,730 ,0,0,0}, {35095,38026,35092 ,730,730,730 ,0,0,0}, + {38026,35088,35092 ,730,730,730 ,0,0,0}, {35094,38026,35095 ,730,730,730 ,0,0,0}, + {38480,38481,38482 ,730,730,730 ,0,0,0}, {38024,38023,38482 ,730,730,730 ,0,0,0}, + {38481,38019,38018 ,730,730,730 ,0,0,0}, {38021,38483,38027 ,730,730,730 ,0,0,0}, + {38022,38483,38021 ,730,730,730 ,0,0,0}, {38021,38027,38026 ,730,730,730 ,0,0,0}, + {38026,38025,38024 ,730,730,730 ,0,0,0}, {38023,38480,38482 ,730,730,730 ,0,0,0}, + {38481,38018,38482 ,730,730,730 ,0,0,0}, {35084,38016,38019 ,730,730,730 ,0,0,0}, + {35081,38016,35084 ,730,730,730 ,0,0,0}, {35079,38015,35081 ,730,730,730 ,0,0,0}, + {38484,38485,38486 ,730,730,730 ,0,0,0}, {38487,38015,35078 ,730,730,730 ,0,0,0}, + {35066,34300,35069 ,730,730,730 ,0,0,0}, {34919,38488,38489 ,730,730,730 ,0,0,0}, + {34304,34303,34871 ,730,730,730 ,0,0,0}, {38490,34300,35066 ,730,730,730 ,0,0,0}, + {35070,38020,35066 ,730,730,730 ,0,0,0}, {38490,35066,38020 ,730,730,730 ,0,0,0}, + {38020,35073,37960 ,730,730,730 ,0,0,0}, {35072,37960,35073 ,730,730,730 ,0,0,0}, + {38491,35057,35056 ,730,730,730 ,0,0,0}, {37917,37921,37918 ,730,730,730 ,0,0,0}, + {38491,38492,35057 ,730,730,730 ,0,0,0}, {37921,37924,37922 ,730,730,730 ,0,0,0}, + {37924,37906,37905 ,730,730,730 ,0,0,0}, {38493,38494,37923 ,730,730,730 ,0,0,0}, + {38493,37923,37904 ,730,730,730 ,0,0,0}, {38495,38494,38496 ,730,730,730 ,0,0,0}, + {38494,38495,37923 ,730,730,730 ,0,0,0}, {37919,38496,37920 ,730,730,730 ,0,0,0}, + {38495,38496,37919 ,730,730,730 ,0,0,0}, {37919,35062,38492 ,730,730,730 ,0,0,0}, + {35059,35057,38492 ,730,730,730 ,0,0,0}, {35062,35059,38492 ,730,730,730 ,0,0,0}, + {35056,37916,38491 ,730,730,730 ,0,0,0}, {37916,35054,35041 ,730,730,730 ,0,0,0}, + {35056,35054,37916 ,730,730,730 ,0,0,0}, {35041,35047,37915 ,730,730,730 ,0,0,0}, + {38232,37915,35044 ,730,730,730 ,0,0,0}, {35047,35044,37915 ,730,730,730 ,0,0,0}, + {38232,35048,38233 ,730,730,730 ,0,0,0}, {35051,37914,38235 ,730,730,730 ,0,0,0}, + {35050,37914,35051 ,730,730,730 ,0,0,0}, {38497,38498,38499 ,730,730,730 ,0,0,0}, + {38500,38498,38501 ,730,730,730 ,0,0,0}, {38498,35028,38501 ,730,730,730 ,0,0,0}, + {38498,38500,38499 ,730,730,730 ,0,0,0}, {35037,37750,37767 ,730,730,730 ,0,0,0}, + {37767,38498,38502 ,730,730,730 ,0,0,0}, {38497,38502,38498 ,730,730,730 ,0,0,0}, + {38503,37767,38504 ,730,730,730 ,0,0,0}, {37767,38502,38504 ,730,730,730 ,0,0,0}, + {38505,37767,38506 ,730,730,730 ,0,0,0}, {37767,38503,38506 ,730,730,730 ,0,0,0}, + {37767,35040,35037 ,730,730,730 ,0,0,0}, {37767,38505,35040 ,730,730,730 ,0,0,0}, + {35035,35034,37750 ,730,730,730 ,0,0,0}, {37750,35032,35019 ,730,730,730 ,0,0,0}, + {35034,35032,37750 ,730,730,730 ,0,0,0}, {35025,37681,35019 ,730,730,730 ,0,0,0}, + {37750,35019,37681 ,730,730,730 ,0,0,0}, {35026,37681,35022 ,730,730,730 ,0,0,0}, + {37681,35025,35022 ,730,730,730 ,0,0,0}, {35029,35028,38498 ,730,730,730 ,0,0,0}, + {38498,37681,35029 ,730,730,730 ,0,0,0}, {37681,35026,35029 ,730,730,730 ,0,0,0}, + {37764,34356,37765 ,730,730,730 ,0,0,0}, {37758,35006,37755 ,730,730,730 ,0,0,0}, + {38507,37769,35018 ,730,730,730 ,0,0,0}, {37765,34356,38508 ,730,730,730 ,0,0,0}, + {38509,37756,37757 ,730,730,730 ,0,0,0}, {34694,38510,37759 ,730,730,730 ,0,0,0}, + {34676,34346,38510 ,730,730,730 ,0,0,0}, {38511,34345,34356 ,730,730,730 ,0,0,0}, + {37765,37768,37766 ,730,730,730 ,0,0,0}, {37769,38507,37766 ,730,730,730 ,0,0,0}, + {35018,37770,38507 ,730,730,730 ,0,0,0}, {35013,37770,35015 ,730,730,730 ,0,0,0}, + {35003,38498,34997 ,730,730,730 ,0,0,0}, {35013,37752,37770 ,730,730,730 ,0,0,0}, + {37752,35010,37767 ,730,730,730 ,0,0,0}, {35012,35010,37752 ,730,730,730 ,0,0,0}, + {37767,34997,38498 ,730,730,730 ,0,0,0}, {35000,35004,37763 ,730,730,730 ,0,0,0}, + {38498,35003,37763 ,730,730,730 ,0,0,0}, {35007,37760,35004 ,730,730,730 ,0,0,0}, + {37763,35004,37760 ,730,730,730 ,0,0,0}, {37758,35007,35006 ,730,730,730 ,0,0,0}, + {37919,38512,37815 ,730,730,730 ,0,0,0}, {37919,38492,34984 ,730,730,730 ,0,0,0}, + {38513,37815,38512 ,730,730,730 ,0,0,0}, {38514,37919,38515 ,730,730,730 ,0,0,0}, + {37919,37925,38515 ,730,730,730 ,0,0,0}, {38516,37919,38517 ,730,730,730 ,0,0,0}, + {37919,38514,38517 ,730,730,730 ,0,0,0}, {37919,38516,38512 ,730,730,730 ,0,0,0}, + {37815,38518,38519 ,730,730,730 ,0,0,0}, {38513,38518,37815 ,730,730,730 ,0,0,0}, + {38492,34988,34975 ,730,730,730 ,0,0,0}, {38519,34996,37815 ,730,730,730 ,0,0,0}, + {37815,34996,37817 ,730,730,730 ,0,0,0}, {34991,37817,34993 ,730,730,730 ,0,0,0}, + {37817,34996,34993 ,730,730,730 ,0,0,0}, {34988,37817,34990 ,730,730,730 ,0,0,0}, + {37817,34991,34990 ,730,730,730 ,0,0,0}, {38492,37817,34988 ,730,730,730 ,0,0,0}, + {34978,38492,34981 ,730,730,730 ,0,0,0}, {38492,34975,34981 ,730,730,730 ,0,0,0}, + {34985,38492,34982 ,730,730,730 ,0,0,0}, {38492,34978,34982 ,730,730,730 ,0,0,0}, + {34984,38492,34985 ,730,730,730 ,0,0,0}, {34969,38320,34971 ,730,730,730 ,0,0,0}, + {37613,37614,37615 ,730,730,730 ,0,0,0}, {37608,37605,37614 ,730,730,730 ,0,0,0}, + {37601,37605,37609 ,730,730,730 ,0,0,0}, {38520,37611,37600 ,730,730,730 ,0,0,0}, + {37600,37602,38520 ,730,730,730 ,0,0,0}, {37612,37611,38520 ,730,730,730 ,0,0,0}, + {34320,38521,38522 ,730,730,730 ,0,0,0}, {37573,37610,37612 ,730,730,730 ,0,0,0}, + {38523,34565,38524 ,730,730,730 ,0,0,0}, {1263,38521,34320 ,730,730,730 ,0,0,0}, + {34317,34328,38525 ,730,730,730 ,0,0,0}, {34968,37619,37617 ,730,730,730 ,0,0,0}, + {34969,37617,38320 ,730,730,730 ,0,0,0}, {37619,34966,34953 ,730,730,730 ,0,0,0}, + {34968,34966,37619 ,730,730,730 ,0,0,0}, {34953,34959,37618 ,730,730,730 ,0,0,0}, + {37607,37618,34956 ,730,730,730 ,0,0,0}, {34959,34956,37618 ,730,730,730 ,0,0,0}, + {37607,34960,37595 ,730,730,730 ,0,0,0}, {34962,37595,34963 ,730,730,730 ,0,0,0}, + {37595,34960,34963 ,730,730,730 ,0,0,0}, {38526,38527,35971 ,730,730,730 ,0,0,0}, + {37970,36139,36141 ,730,730,730 ,0,0,0}, {36141,38206,37970 ,730,730,730 ,0,0,0}, + {37971,38528,36136 ,730,730,730 ,0,0,0}, {36135,36136,38528 ,730,730,730 ,0,0,0}, + {36129,36130,38208 ,730,730,730 ,0,0,0}, {36127,34921,34925 ,730,730,730 ,0,0,0}, + {36124,34929,36123 ,730,730,730 ,0,0,0}, {36121,34929,34928 ,730,730,730 ,0,0,0}, + {36118,34931,36117 ,730,730,730 ,0,0,0}, {34933,34935,36115 ,730,730,730 ,0,0,0}, + {34038,36112,34938 ,730,730,730 ,0,0,0}, {34038,34938,34040 ,730,730,730 ,0,0,0}, + {38529,38530,34043 ,730,730,730 ,0,0,0}, {38212,38529,34045 ,730,730,730 ,0,0,0}, + {36109,34037,36143 ,730,730,730 ,0,0,0}, {34049,36149,36148 ,730,730,730 ,0,0,0}, + {34048,36148,36145 ,730,730,730 ,0,0,0}, {34057,34898,34901 ,730,730,730 ,0,0,0}, + {34057,34901,38531 ,730,730,730 ,0,0,0}, {38187,36167,38184 ,730,730,730 ,0,0,0}, + {35977,35979,37969 ,730,730,730 ,0,0,0}, {35979,37974,34063 ,730,730,730 ,0,0,0}, + {35973,35974,37968 ,730,730,730 ,0,0,0}, {35973,37968,38532 ,730,730,730 ,0,0,0}, + {38527,35968,35971 ,730,730,730 ,0,0,0}, {34135,38209,37972 ,730,730,730 ,0,0,0}, + {38527,38209,35968 ,730,730,730 ,0,0,0}, {34136,38533,34138 ,730,730,730 ,0,0,0}, + {34143,34138,34950 ,730,730,730 ,0,0,0}, {34952,34138,38533 ,730,730,730 ,0,0,0}, + {38534,38182,38183 ,730,730,730 ,0,0,0}, {38010,38012,38535 ,730,730,730 ,0,0,0}, + {38536,34913,34911 ,730,730,730 ,0,0,0}, {37537,34913,38536 ,730,730,730 ,0,0,0}, + {37979,38537,37980 ,730,730,730 ,0,0,0}, {34054,34892,34891 ,730,730,730 ,0,0,0}, + {34899,34898,34057 ,730,730,730 ,0,0,0}, {34059,34899,34057 ,730,730,730 ,0,0,0}, + {38211,34051,34062 ,730,730,730 ,0,0,0}, {34903,38531,34901 ,730,730,730 ,0,0,0}, + {4039,36151,36149 ,730,730,730 ,0,0,0}, {38007,36154,4039 ,730,730,730 ,0,0,0}, + {36155,36154,38007 ,730,730,730 ,0,0,0}, {38185,36161,36160 ,730,730,730 ,0,0,0}, + {36166,36163,3897 ,730,730,730 ,0,0,0}, {36167,36166,38184 ,730,730,730 ,0,0,0}, + {36169,38187,38538 ,730,730,730 ,0,0,0}, {38538,38189,36171 ,730,730,730 ,0,0,0}, + {36171,36169,38538 ,730,730,730 ,0,0,0}, {38486,38188,38190 ,730,730,730 ,0,0,0}, + {38189,38188,36171 ,730,730,730 ,0,0,0}, {38014,38539,34292 ,730,730,730 ,0,0,0}, + {38486,38485,38188 ,730,730,730 ,0,0,0}, {38540,34297,38539 ,730,730,730 ,0,0,0}, + {34297,38541,34295 ,730,730,730 ,0,0,0}, {38485,38484,34290 ,730,730,730 ,0,0,0}, + {34309,34311,38542 ,730,730,730 ,0,0,0}, {34866,38543,38191 ,730,730,730 ,0,0,0}, + {38544,38545,38546 ,730,730,730 ,0,0,0}, {34303,34314,38009 ,730,730,730 ,0,0,0}, + {38543,34866,34869 ,730,730,730 ,0,0,0}, {38008,34314,34315 ,730,730,730 ,0,0,0}, + {38547,38548,38549 ,730,730,730 ,0,0,0}, {38550,34217,38551 ,730,730,730 ,0,0,0}, + {34211,34880,38552 ,730,730,730 ,0,0,0}, {37556,34859,34863 ,730,730,730 ,0,0,0}, + {38553,38554,38555 ,730,730,730 ,0,0,0}, {34222,37990,38556 ,730,730,730 ,0,0,0}, + {35960,35957,34231 ,730,730,730 ,0,0,0}, {37993,38557,37991 ,730,730,730 ,0,0,0}, + {34869,38558,38543 ,730,730,730 ,0,0,0}, {34303,34869,34871 ,730,730,730 ,0,0,0}, + {3883,38489,38559 ,730,730,730 ,0,0,0}, {34306,34873,34876 ,730,730,730 ,0,0,0}, + {34309,38542,38544 ,730,730,730 ,0,0,0}, {34916,38005,34917 ,730,730,730 ,0,0,0}, + {34303,38560,38558 ,730,730,730 ,0,0,0}, {38544,38546,34309 ,730,730,730 ,0,0,0}, + {38561,37475,38546 ,730,730,730 ,0,0,0}, {3883,34919,38489 ,730,730,730 ,0,0,0}, + {38562,38559,37996 ,730,730,730 ,0,0,0}, {35063,34301,38013 ,730,730,730 ,0,0,0}, + {37994,38563,35076 ,730,730,730 ,0,0,0}, {38564,38565,37997 ,730,730,730 ,0,0,0}, + {38487,38563,38566 ,730,730,730 ,0,0,0}, {38547,38564,38548 ,730,730,730 ,0,0,0}, + {38564,38547,38565 ,730,730,730 ,0,0,0}, {38549,37999,38547 ,730,730,730 ,0,0,0}, + {38000,38194,38001 ,730,730,730 ,0,0,0}, {38549,38000,37999 ,730,730,730 ,0,0,0}, + {38193,38192,37485 ,730,730,730 ,0,0,0}, {38001,38194,38193 ,730,730,730 ,0,0,0}, + {34890,37485,38192 ,730,730,730 ,0,0,0}, {34857,34855,38203 ,730,730,730 ,0,0,0}, + {38203,37982,34857 ,730,730,730 ,0,0,0}, {34849,34848,37553 ,730,730,730 ,0,0,0}, + {34849,37553,38204 ,730,730,730 ,0,0,0}, {34848,34830,37963 ,730,730,730 ,0,0,0}, + {34833,34124,34829 ,730,730,730 ,0,0,0}, {34830,34829,34122 ,730,730,730 ,0,0,0}, + {34833,34837,34129 ,730,730,730 ,0,0,0}, {37966,38207,34122 ,730,730,730 ,0,0,0}, + {34129,34836,34127 ,730,730,730 ,0,0,0}, {34127,34839,38205 ,730,730,730 ,0,0,0}, + {34944,34942,38181 ,730,730,730 ,0,0,0}, {34133,37970,38206 ,730,730,730 ,0,0,0}, + {38567,38568,38569 ,730,730,730 ,0,0,0}, {35961,34146,34147 ,730,730,730 ,0,0,0}, + {37535,35944,35942 ,730,730,730 ,0,0,0}, {35945,37550,35951 ,730,730,730 ,0,0,0}, + {35948,35953,38179 ,730,730,730 ,0,0,0}, {35951,37551,38179 ,730,730,730 ,0,0,0}, + {37987,37990,34220 ,730,730,730 ,0,0,0}, {37988,35948,38179 ,730,730,730 ,0,0,0}, + {34222,38570,34227 ,730,730,730 ,0,0,0}, {38571,34225,37989 ,730,730,730 ,0,0,0}, + {38555,38554,34225 ,730,730,730 ,0,0,0}, {38555,34225,38571 ,730,730,730 ,0,0,0}, + {38553,37986,37985 ,730,730,730 ,0,0,0}, {38572,38199,38198 ,730,730,730 ,0,0,0}, + {38572,34217,38199 ,730,730,730 ,0,0,0}, {37557,34860,34859 ,730,730,730 ,0,0,0}, + {38573,38200,38574 ,730,730,730 ,0,0,0}, {38198,38197,38573 ,730,730,730 ,0,0,0}, + {37984,38575,38201 ,730,730,730 ,0,0,0}, {35927,38576,38577 ,730,730,730 ,0,0,0}, + {38578,38579,37865 ,730,730,730 ,0,0,0}, {37820,37822,38580 ,730,730,730 ,0,0,0}, + {37820,38580,34441 ,730,730,730 ,0,0,0}, {37866,37822,37821 ,730,730,730 ,0,0,0}, + {38579,38578,38581 ,730,730,730 ,0,0,0}, {37863,37862,38581 ,730,730,730 ,0,0,0}, + {38248,37861,34799 ,730,730,730 ,0,0,0}, {37871,34803,34807 ,730,730,730 ,0,0,0}, + {37872,34806,38249 ,730,730,730 ,0,0,0}, {38249,34809,37819 ,730,730,730 ,0,0,0}, + {34811,34813,37879 ,730,730,730 ,0,0,0}, {34813,2941,38251 ,730,730,730 ,0,0,0}, + {2941,34402,38251 ,730,730,730 ,0,0,0}, {2941,34404,34402 ,730,730,730 ,0,0,0}, + {34401,34412,38582 ,730,730,730 ,0,0,0}, {38583,34401,38584 ,730,730,730 ,0,0,0}, + {34706,34418,34416 ,730,730,730 ,0,0,0}, {38585,38586,34407 ,730,730,730 ,0,0,0}, + {34412,37886,38587 ,730,730,730 ,0,0,0}, {34712,34715,34421 ,730,730,730 ,0,0,0}, + {34421,34713,34712 ,730,730,730 ,0,0,0}, {38214,37899,38215 ,730,730,730 ,0,0,0}, + {35933,35935,37870 ,730,730,730 ,0,0,0}, {35935,37860,34427 ,730,730,730 ,0,0,0}, + {35929,35930,37869 ,730,730,730 ,0,0,0}, {35929,37869,38588 ,730,730,730 ,0,0,0}, + {38577,35924,35927 ,730,730,730 ,0,0,0}, {34443,38246,37867 ,730,730,730 ,0,0,0}, + {38577,38246,35924 ,730,730,730 ,0,0,0}, {34444,38589,34446 ,730,730,730 ,0,0,0}, + {34451,34446,34827 ,730,730,730 ,0,0,0}, {2165,34446,38589 ,730,730,730 ,0,0,0}, + {34793,34790,37882 ,730,730,730 ,0,0,0}, {35792,35791,38322 ,730,730,730 ,0,0,0}, + {37881,34788,37827 ,730,730,730 ,0,0,0}, {34790,34788,37881 ,730,730,730 ,0,0,0}, + {34787,34768,38242 ,730,730,730 ,0,0,0}, {34437,34771,34775 ,730,730,730 ,0,0,0}, + {34767,34771,34432 ,730,730,730 ,0,0,0}, {34430,38590,38245 ,730,730,730 ,0,0,0}, + {34767,34430,34768 ,730,730,730 ,0,0,0}, {38590,34429,38591 ,730,730,730 ,0,0,0}, + {37876,34435,34777 ,730,730,730 ,0,0,0}, {34821,34819,38241 ,730,730,730 ,0,0,0}, + {38243,34441,38580 ,730,730,730 ,0,0,0}, {38592,38593,38594 ,730,730,730 ,0,0,0}, + {35917,34454,34455 ,730,730,730 ,0,0,0}, {38595,38596,35898 ,730,730,730 ,0,0,0}, + {38596,35900,35898 ,730,730,730 ,0,0,0}, {37875,35907,35901 ,730,730,730 ,0,0,0}, + {37875,37874,35907 ,730,730,730 ,0,0,0}, {35909,37818,35904 ,730,730,730 ,0,0,0}, + {38322,35791,35904 ,730,730,730 ,0,0,0}, {38322,37877,35792 ,730,730,730 ,0,0,0}, + {35794,37878,38323 ,730,730,730 ,0,0,0}, {37878,35794,35792 ,730,730,730 ,0,0,0}, + {38324,35799,35794 ,730,730,730 ,0,0,0}, {35797,35799,37858 ,730,730,730 ,0,0,0}, + {38324,37858,35799 ,730,730,730 ,0,0,0}, {37859,38597,35797 ,730,730,730 ,0,0,0}, + {38238,38237,38597 ,730,730,730 ,0,0,0}, {35797,38597,38237 ,730,730,730 ,0,0,0}, + {38239,38238,38598 ,730,730,730 ,0,0,0}, {34798,38239,38598 ,730,730,730 ,0,0,0}, + {38224,38223,38327 ,730,730,730 ,0,0,0}, {2303,38599,38600 ,730,730,730 ,0,0,0}, + {34762,35783,35785 ,730,730,730 ,0,0,0}, {34762,35785,34763 ,730,730,730 ,0,0,0}, + {34757,34756,38601 ,730,730,730 ,0,0,0}, {38601,35783,34757 ,730,730,730 ,0,0,0}, + {34738,34737,37907 ,730,730,730 ,0,0,0}, {34738,37907,38601 ,730,730,730 ,0,0,0}, + {34738,38601,34756 ,730,730,730 ,0,0,0}, {38225,34745,37903 ,730,730,730 ,0,0,0}, + {38331,38602,38603 ,730,730,730 ,0,0,0}, {38600,38604,34385 ,730,730,730 ,0,0,0}, + {34387,34749,34388 ,730,730,730 ,0,0,0}, {34387,34747,34749 ,730,730,730 ,0,0,0}, + {34387,38605,37836 ,730,730,730 ,0,0,0}, {34390,34388,34751 ,730,730,730 ,0,0,0}, + {38606,34393,38219 ,730,730,730 ,0,0,0}, {38607,34395,34390 ,730,730,730 ,0,0,0}, + {37842,37841,34374 ,730,730,730 ,0,0,0}, {34384,38604,38608 ,730,730,730 ,0,0,0}, + {38603,38599,2303 ,730,730,730 ,0,0,0}, {38602,38599,38603 ,730,730,730 ,0,0,0}, + {38609,38330,38610 ,730,730,730 ,0,0,0}, {38333,38328,38611 ,730,730,730 ,0,0,0}, + {38610,38326,38609 ,730,730,730 ,0,0,0}, {38337,38332,38334 ,730,730,730 ,0,0,0}, + {38334,38333,38611 ,730,730,730 ,0,0,0}, {38335,38612,38336 ,730,730,730 ,0,0,0}, + {38337,38336,38332 ,730,730,730 ,0,0,0}, {38338,38612,38613 ,730,730,730 ,0,0,0}, + {38335,38613,38612 ,730,730,730 ,0,0,0}, {38338,38340,38321 ,730,730,730 ,0,0,0}, + {38338,38613,38339 ,730,730,730 ,0,0,0}, {2131,38321,38340 ,730,730,730 ,0,0,0}, + {37894,38614,37895 ,730,730,730 ,0,0,0}, {37900,37846,37898 ,730,730,730 ,0,0,0}, + {38615,34728,34726 ,730,730,730 ,0,0,0}, {37887,34728,38615 ,730,730,730 ,0,0,0}, + {34418,34706,34705 ,730,730,730 ,0,0,0}, {34715,38616,34421 ,730,730,730 ,0,0,0}, + {34423,34713,34421 ,730,730,730 ,0,0,0}, {37824,34415,34426 ,730,730,730 ,0,0,0}, + {34717,38616,34715 ,730,730,730 ,0,0,0}, {37857,37850,37856 ,730,730,730 ,0,0,0}, + {37851,37850,37857 ,730,730,730 ,0,0,0}, {37890,37852,37851 ,730,730,730 ,0,0,0}, + {37854,38617,37891 ,730,730,730 ,0,0,0}, {37845,34722,37846 ,730,730,730 ,0,0,0}, + {37900,37844,37846 ,730,730,730 ,0,0,0}, {37899,37898,38215 ,730,730,730 ,0,0,0}, + {38214,37833,37832 ,730,730,730 ,0,0,0}, {37832,37834,38217 ,730,730,730 ,0,0,0}, + {37843,38216,37841 ,730,730,730 ,0,0,0}, {38217,37834,38216 ,730,730,730 ,0,0,0}, + {38218,34376,34374 ,730,730,730 ,0,0,0}, {38618,34381,38619 ,730,730,730 ,0,0,0}, + {38619,34376,38218 ,730,730,730 ,0,0,0}, {34379,34381,38620 ,730,730,730 ,0,0,0}, + {34373,34384,38621 ,730,730,730 ,0,0,0}, {38622,38229,38220 ,730,730,730 ,0,0,0}, + {34736,34734,37837 ,730,730,730 ,0,0,0}, {38606,38623,34393 ,730,730,730 ,0,0,0}, + {38606,38624,38623 ,730,730,730 ,0,0,0}, {34398,37840,34387 ,730,730,730 ,0,0,0}, + {37839,34398,34399 ,730,730,730 ,0,0,0}, {34703,36039,36038 ,730,730,730 ,0,0,0}, + {38625,35853,35851 ,730,730,730 ,0,0,0}, {34697,37759,36043 ,730,730,730 ,0,0,0}, + {36043,34700,34697 ,730,730,730 ,0,0,0}, {34695,37759,34697 ,730,730,730 ,0,0,0}, + {34675,34679,34348 ,730,730,730 ,0,0,0}, {38510,34694,34676 ,730,730,730 ,0,0,0}, + {34679,34683,34353 ,730,730,730 ,0,0,0}, {34675,34348,34346 ,730,730,730 ,0,0,0}, + {37762,37761,38626 ,730,730,730 ,0,0,0}, {38627,38628,38629 ,730,730,730 ,0,0,0}, + {38630,34351,34685 ,730,730,730 ,0,0,0}, {34634,34632,37747 ,730,730,730 ,0,0,0}, + {35873,34370,34371 ,730,730,730 ,0,0,0}, {38275,35856,35854 ,730,730,730 ,0,0,0}, + {35857,37761,35863 ,730,730,730 ,0,0,0}, {35860,35865,37751 ,730,730,730 ,0,0,0}, + {35863,37762,37751 ,730,730,730 ,0,0,0}, {38253,37724,34108 ,730,730,730 ,0,0,0}, + {38252,35860,37751 ,730,730,730 ,0,0,0}, {37724,38631,34110 ,730,730,730 ,0,0,0}, + {34113,34115,37722 ,730,730,730 ,0,0,0}, {37707,34650,37710 ,730,730,730 ,0,0,0}, + {34669,34101,34670 ,730,730,730 ,0,0,0}, {36015,35981,34093 ,730,730,730 ,0,0,0}, + {36021,3171,36023 ,730,730,730 ,0,0,0}, {36023,3171,36026 ,730,730,730 ,0,0,0}, + {38632,34644,34643 ,730,730,730 ,0,0,0}, {36027,38633,36029 ,730,730,730 ,0,0,0}, + {36026,37746,36027 ,730,730,730 ,0,0,0}, {38634,36033,38254 ,730,730,730 ,0,0,0}, + {38635,35990,35993 ,730,730,730 ,0,0,0}, {35996,38636,35995 ,730,730,730 ,0,0,0}, + {38637,38272,38273 ,730,730,730 ,0,0,0}, {36021,36020,34105 ,730,730,730 ,0,0,0}, + {38637,38638,38271 ,730,730,730 ,0,0,0}, {37720,38632,34643 ,730,730,730 ,0,0,0}, + {38638,34113,38271 ,730,730,730 ,0,0,0}, {35872,35869,34119 ,730,730,730 ,0,0,0}, + {37706,38639,37704 ,730,730,730 ,0,0,0}, {36007,37712,36005 ,730,730,730 ,0,0,0}, + {38640,38641,38262 ,730,730,730 ,0,0,0}, {34191,34653,34655 ,730,730,730 ,0,0,0}, + {38642,38643,34609 ,730,730,730 ,0,0,0}, {34194,34192,34657 ,730,730,730 ,0,0,0}, + {38644,34197,38260 ,730,730,730 ,0,0,0}, {38645,34199,34194 ,730,730,730 ,0,0,0}, + {38646,38647,34185 ,730,730,730 ,0,0,0}, {38648,34177,38649 ,730,730,730 ,0,0,0}, + {37708,36011,36013 ,730,730,730 ,0,0,0}, {3063,38643,38641 ,730,730,730 ,0,0,0}, + {36007,36008,38650 ,730,730,730 ,0,0,0}, {36001,36002,38266 ,730,730,730 ,0,0,0}, + {35996,35999,38267 ,730,730,730 ,0,0,0}, {35999,36001,38268 ,730,730,730 ,0,0,0}, + {38636,35993,35995 ,730,730,730 ,0,0,0}, {38636,35996,38267 ,730,730,730 ,0,0,0}, + {38635,38269,35990 ,730,730,730 ,0,0,0}, {38636,38635,35993 ,730,730,730 ,0,0,0}, + {35989,37718,35987 ,730,730,730 ,0,0,0}, {35990,38269,35989 ,730,730,730 ,0,0,0}, + {35987,37717,35984 ,730,730,730 ,0,0,0}, {34674,35984,37717 ,730,730,730 ,0,0,0}, + {38651,35879,35880 ,730,730,730 ,0,0,0}, {38652,38653,35883 ,730,730,730 ,0,0,0}, + {34631,38278,37747 ,730,730,730 ,0,0,0}, {3015,38628,38627 ,730,730,730 ,0,0,0}, + {38508,34357,37757 ,730,730,730 ,0,0,0}, {37757,34357,38509 ,730,730,730 ,0,0,0}, + {37756,37738,37737 ,730,730,730 ,0,0,0}, {38276,37738,38654 ,730,730,730 ,0,0,0}, + {38282,37743,34615 ,730,730,730 ,0,0,0}, {38282,34619,34618 ,730,730,730 ,0,0,0}, + {37742,34621,37745 ,730,730,730 ,0,0,0}, {34623,34625,38283 ,730,730,730 ,0,0,0}, + {34628,37734,37744 ,730,730,730 ,0,0,0}, {34269,38284,38655 ,730,730,730 ,0,0,0}, + {34628,34264,34262 ,730,730,730 ,0,0,0}, {38655,38656,34267 ,730,730,730 ,0,0,0}, + {37735,34261,38657 ,730,730,730 ,0,0,0}, {34278,34276,34582 ,730,730,730 ,0,0,0}, + {34591,34593,38658 ,730,730,730 ,0,0,0}, {34273,37727,38659 ,730,730,730 ,0,0,0}, + {37697,38257,37698 ,730,730,730 ,0,0,0}, {35889,35891,38280 ,730,730,730 ,0,0,0}, + {35891,37740,34287 ,730,730,730 ,0,0,0}, {35885,35886,38279 ,730,730,730 ,0,0,0}, + {35885,38279,38660 ,730,730,730 ,0,0,0}, {38653,35880,35883 ,730,730,730 ,0,0,0}, + {34359,38651,37741 ,730,730,730 ,0,0,0}, {38653,38651,35880 ,730,730,730 ,0,0,0}, + {34360,38661,34362 ,730,730,730 ,0,0,0}, {34367,34362,34640 ,730,730,730 ,0,0,0}, + {34642,34362,38661 ,730,730,730 ,0,0,0}, {37694,37693,38662 ,730,730,730 ,0,0,0}, + {38663,37696,37691 ,730,730,730 ,0,0,0}, {38664,34603,34601 ,730,730,730 ,0,0,0}, + {37729,34603,38664 ,730,730,730 ,0,0,0}, {34278,34582,34581 ,730,730,730 ,0,0,0}, + {34591,38658,34281 ,730,730,730 ,0,0,0}, {34589,34588,34281 ,730,730,730 ,0,0,0}, + {34283,34589,34281 ,730,730,730 ,0,0,0}, {38281,34275,34286 ,730,730,730 ,0,0,0}, + {38665,37686,37685 ,730,730,730 ,0,0,0}, {34273,37689,37688 ,730,730,730 ,0,0,0}, + {37725,37687,37689 ,730,730,730 ,0,0,0}, {37592,37687,37725 ,730,730,730 ,0,0,0}, + {38666,38667,37593 ,730,730,730 ,0,0,0}, {38668,38669,37692 ,730,730,730 ,0,0,0}, + {37691,37690,38663 ,730,730,730 ,0,0,0}, {37696,38663,37697 ,730,730,730 ,0,0,0}, + {38256,38255,38258 ,730,730,730 ,0,0,0}, {37698,38257,38256 ,730,730,730 ,0,0,0}, + {38258,37589,38670 ,730,730,730 ,0,0,0}, {38671,37588,37587 ,730,730,730 ,0,0,0}, + {37588,38670,37589 ,730,730,730 ,0,0,0}, {34180,38259,38646 ,730,730,730 ,0,0,0}, + {37587,38259,34178 ,730,730,730 ,0,0,0}, {38671,34178,38648 ,730,730,730 ,0,0,0}, + {38672,34188,38673 ,730,730,730 ,0,0,0}, {3063,34609,38643 ,730,730,730 ,0,0,0}, + {37709,38673,34189 ,730,730,730 ,0,0,0}, {38644,38674,34197 ,730,730,730 ,0,0,0}, + {38644,38675,38674 ,730,730,730 ,0,0,0}, {34202,37713,34191 ,730,730,730 ,0,0,0}, + {37714,34202,34203 ,730,730,730 ,0,0,0}, {38676,38677,35839 ,730,730,730 ,0,0,0}, + {38315,36087,1435 ,730,730,730 ,0,0,0}, {36087,36085,1435 ,730,730,730 ,0,0,0}, + {36090,36087,38315 ,730,730,730 ,0,0,0}, {36093,36091,38316 ,730,730,730 ,0,0,0}, + {38678,36097,36096 ,730,730,730 ,0,0,0}, {36102,34551,34555 ,730,730,730 ,0,0,0}, + {36103,34555,34559 ,730,730,730 ,0,0,0}, {36105,34559,34558 ,730,730,730 ,0,0,0}, + {38523,34563,34565 ,730,730,730 ,0,0,0}, {34561,38523,36107 ,730,730,730 ,0,0,0}, + {36107,34558,34561 ,730,730,730 ,0,0,0}, {34563,38523,34561 ,730,730,730 ,0,0,0}, + {34332,34540,34539 ,730,730,730 ,0,0,0}, {38524,34565,1263 ,730,730,730 ,0,0,0}, + {38524,1263,34318 ,730,730,730 ,0,0,0}, {34325,38522,38679 ,730,730,730 ,0,0,0}, + {38680,38681,38682 ,730,730,730 ,0,0,0}, {34323,38679,38683 ,730,730,730 ,0,0,0}, + {34529,38684,34337 ,730,730,730 ,0,0,0}, {34520,34334,34332 ,730,730,730 ,0,0,0}, + {37571,37570,38685 ,730,730,730 ,0,0,0}, {35845,35847,38317 ,730,730,730 ,0,0,0}, + {35847,38319,34343 ,730,730,730 ,0,0,0}, {35841,35842,38318 ,730,730,730 ,0,0,0}, + {35841,38318,38686 ,730,730,730 ,0,0,0}, {38677,35836,35839 ,730,730,730 ,0,0,0}, + {34079,37594,37590 ,730,730,730 ,0,0,0}, {38677,37594,35836 ,730,730,730 ,0,0,0}, + {34080,38687,34082 ,730,730,730 ,0,0,0}, {34087,34082,34579 ,730,730,730 ,0,0,0}, + {2082,34082,38687 ,730,730,730 ,0,0,0}, {37522,37524,38688 ,730,730,730 ,0,0,0}, + {38685,37570,38689 ,730,730,730 ,0,0,0}, {38690,34542,34540 ,730,730,730 ,0,0,0}, + {37606,34542,38690 ,730,730,730 ,0,0,0}, {34339,34527,34337 ,730,730,730 ,0,0,0}, + {38684,34529,34531 ,730,730,730 ,0,0,0}, {34529,34337,34526 ,730,730,730 ,0,0,0}, + {34337,34527,34526 ,730,730,730 ,0,0,0}, {34342,37603,34331 ,730,730,730 ,0,0,0}, + {34533,37597,34531 ,730,730,730 ,0,0,0}, {38681,38691,38682 ,730,730,730 ,0,0,0}, + {34971,34329,34974 ,730,730,730 ,0,0,0}, {38692,38693,38691 ,730,730,730 ,0,0,0}, + {37574,37573,34974 ,730,730,730 ,0,0,0}, {37610,37575,37576 ,730,730,730 ,0,0,0}, + {38685,38689,34536 ,730,730,730 ,0,0,0}, {37570,37572,38290 ,730,730,730 ,0,0,0}, + {37517,38289,37515 ,730,730,730 ,0,0,0}, {38290,37572,38289 ,730,730,730 ,0,0,0}, + {37516,37515,38291 ,730,730,730 ,0,0,0}, {37514,38293,38292 ,730,730,730 ,0,0,0}, + {38293,37516,38291 ,730,730,730 ,0,0,0}, {38294,34236,37561 ,730,730,730 ,0,0,0}, + {38292,37561,34234 ,730,730,730 ,0,0,0}, {34239,34241,38694 ,730,730,730 ,0,0,0}, + {38298,34239,38695 ,730,730,730 ,0,0,0}, {38302,37559,34245 ,730,730,730 ,0,0,0}, + {38299,34253,38300 ,730,730,730 ,0,0,0}, {37554,34496,38696 ,730,730,730 ,0,0,0}, + {34247,34258,37565 ,730,730,730 ,0,0,0}, {38696,34496,34499 ,730,730,730 ,0,0,0}, + {37564,34258,34259 ,730,730,730 ,0,0,0}, {38697,38698,38699 ,730,730,730 ,0,0,0}, + {34161,38700,38701 ,730,730,730 ,0,0,0}, {34160,38701,38702 ,730,730,730 ,0,0,0}, + {35822,34163,34174 ,730,730,730 ,0,0,0}, {38703,34489,34493 ,730,730,730 ,0,0,0}, + {34166,37569,38704 ,730,730,730 ,0,0,0}, {35828,35825,34175 ,730,730,730 ,0,0,0}, + {37519,38705,37507 ,730,730,730 ,0,0,0}, {34499,38706,38696 ,730,730,730 ,0,0,0}, + {34247,34499,34501 ,730,730,730 ,0,0,0}, {37563,34548,38707 ,730,730,730 ,0,0,0}, + {34250,34503,1297 ,730,730,730 ,0,0,0}, {38708,38300,34253 ,730,730,730 ,0,0,0}, + {34253,34255,38708 ,730,730,730 ,0,0,0}, {34545,37541,34546 ,730,730,730 ,0,0,0}, + {38706,34247,38709 ,730,730,730 ,0,0,0}, {37563,34550,34548 ,730,730,730 ,0,0,0}, + {38303,38306,38304 ,730,730,730 ,0,0,0}, {38710,38306,38305 ,730,730,730 ,0,0,0}, + {38711,38710,38307 ,730,730,730 ,0,0,0}, {38712,37583,37560 ,730,730,730 ,0,0,0}, + {38713,37549,37548 ,730,730,730 ,0,0,0}, {38712,37560,37549 ,730,730,730 ,0,0,0}, + {38309,38698,38308 ,730,730,730 ,0,0,0}, {37548,38308,38713 ,730,730,730 ,0,0,0}, + {38699,38311,38697 ,730,730,730 ,0,0,0}, {38309,38699,38698 ,730,730,730 ,0,0,0}, + {38310,37567,37566 ,730,730,730 ,0,0,0}, {38697,38311,38310 ,730,730,730 ,0,0,0}, + {37566,37568,38312 ,730,730,730 ,0,0,0}, {2073,38312,37568 ,730,730,730 ,0,0,0}, + {34486,36060,36063 ,730,730,730 ,0,0,0}, {38714,35809,35807 ,730,730,730 ,0,0,0}, + {34478,34477,36053 ,730,730,730 ,0,0,0}, {34478,36053,36054 ,730,730,730 ,0,0,0}, + {34458,36048,36051 ,730,730,730 ,0,0,0}, {34461,34465,34073 ,730,730,730 ,0,0,0}, + {34068,34066,34457 ,730,730,730 ,0,0,0}, {34071,34073,34464 ,730,730,730 ,0,0,0}, + {34066,36048,34458 ,730,730,730 ,0,0,0}, {34065,34076,36079 ,730,730,730 ,0,0,0}, + {36047,34066,36045 ,730,730,730 ,0,0,0}, {34573,34571,38288 ,730,730,730 ,0,0,0}, + {34077,1435,36085 ,730,730,730 ,0,0,0}, {38715,38716,38717 ,730,730,730 ,0,0,0}, + {35829,34090,34091 ,730,730,730 ,0,0,0}, {38285,35812,35810 ,730,730,730 ,0,0,0}, + {35813,37525,35819 ,730,730,730 ,0,0,0}, {35816,35821,37586 ,730,730,730 ,0,0,0}, + {35819,37527,37586 ,730,730,730 ,0,0,0}, {37505,37569,34164 ,730,730,730 ,0,0,0}, + {37504,35816,37586 ,730,730,730 ,0,0,0}, {34166,38718,34171 ,730,730,730 ,0,0,0}, + {38719,34169,37580 ,730,730,730 ,0,0,0}, {37531,37533,34169 ,730,730,730 ,0,0,0}, + {37531,34169,38719 ,730,730,730 ,0,0,0}, {34489,38703,38720 ,730,730,730 ,0,0,0}, + {38700,37520,36077 ,730,730,730 ,0,0,0}, {36077,37520,36075 ,730,730,730 ,0,0,0}, + {38720,34490,34489 ,730,730,730 ,0,0,0}, {36072,38721,36071 ,730,730,730 ,0,0,0}, + {36075,37521,36072 ,730,730,730 ,0,0,0}, {38722,36066,38287 ,730,730,730 ,0,0,0}, + {34784,38593,38592 ,730,730,730 ,0,0,0}, {34818,37868,38241 ,730,730,730 ,0,0,0}, + {34781,34784,38592 ,730,730,730 ,0,0,0}, {37865,38579,38247 ,730,730,730 ,0,0,0}, + {34799,37863,34800 ,730,730,730 ,0,0,0}, {34799,37861,37863 ,730,730,730 ,0,0,0}, + {38578,37863,38581 ,730,730,730 ,0,0,0}, {38241,34819,34818 ,730,730,730 ,0,0,0}, + {34825,34451,34827 ,730,730,730 ,0,0,0}, {34825,34824,34451 ,730,730,730 ,0,0,0}, + {34443,35923,38246 ,730,730,730 ,0,0,0}, {38589,34444,37867 ,730,730,730 ,0,0,0}, + {34443,35918,35921 ,730,730,730 ,0,0,0}, {34455,38325,35895 ,730,730,730 ,0,0,0}, + {35895,35917,34455 ,730,730,730 ,0,0,0}, {38595,35898,35897 ,730,730,730 ,0,0,0}, + {38595,35897,38325 ,730,730,730 ,0,0,0}, {37873,38594,38593 ,730,730,730 ,0,0,0}, + {37875,35901,35900 ,730,730,730 ,0,0,0}, {37875,35900,38596 ,730,730,730 ,0,0,0}, + {37875,38594,37873 ,730,730,730 ,0,0,0}, {37876,34777,34779 ,730,730,730 ,0,0,0}, + {37876,34781,38592 ,730,730,730 ,0,0,0}, {34435,34774,34777 ,730,730,730 ,0,0,0}, + {34437,34775,34774 ,730,730,730 ,0,0,0}, {34430,38245,34768 ,730,730,730 ,0,0,0}, + {34437,34432,34771 ,730,730,730 ,0,0,0}, {34430,34429,38590 ,730,730,730 ,0,0,0}, + {38591,34429,37864 ,730,730,730 ,0,0,0}, {37864,34440,38244 ,730,730,730 ,0,0,0}, + {34441,38244,34440 ,730,730,730 ,0,0,0}, {37889,38586,38723 ,730,730,730 ,0,0,0}, + {34719,38213,34717 ,730,730,730 ,0,0,0}, {38723,37830,37889 ,730,730,730 ,0,0,0}, + {38213,34722,37855 ,730,730,730 ,0,0,0}, {37854,37893,38617 ,730,730,730 ,0,0,0}, + {37891,38617,37890 ,730,730,730 ,0,0,0}, {34722,37845,37855 ,730,730,730 ,0,0,0}, + {37853,37855,37845 ,730,730,730 ,0,0,0}, {38213,38616,34717 ,730,730,730 ,0,0,0}, + {34709,34713,34423 ,730,730,730 ,0,0,0}, {34415,38615,34726 ,730,730,730 ,0,0,0}, + {34709,34418,34705 ,730,730,730 ,0,0,0}, {34418,34709,34423 ,730,730,730 ,0,0,0}, + {34726,34416,34415 ,730,730,730 ,0,0,0}, {34415,37824,38615 ,730,730,730 ,0,0,0}, + {38724,35935,34427 ,730,730,730 ,0,0,0}, {34427,37860,34426 ,730,730,730 ,0,0,0}, + {35933,37869,35930 ,730,730,730 ,0,0,0}, {37870,35935,38724 ,730,730,730 ,0,0,0}, + {38576,35927,38588 ,730,730,730 ,0,0,0}, {35929,38588,35927 ,730,730,730 ,0,0,0}, + {37829,37828,38576 ,730,730,730 ,0,0,0}, {37829,38576,38588 ,730,730,730 ,0,0,0}, + {38725,38723,38586 ,730,730,730 ,0,0,0}, {34407,37826,38585 ,730,730,730 ,0,0,0}, + {38586,38585,38725 ,730,730,730 ,0,0,0}, {34407,34409,37825 ,730,730,730 ,0,0,0}, + {38583,38251,34402 ,730,730,730 ,0,0,0}, {34409,34404,37885 ,730,730,730 ,0,0,0}, + {38584,34401,38582 ,730,730,730 ,0,0,0}, {34402,34401,38583 ,730,730,730 ,0,0,0}, + {38582,34412,38587 ,730,730,730 ,0,0,0}, {37886,34412,34413 ,730,730,730 ,0,0,0}, + {38222,38224,38623 ,730,730,730 ,0,0,0}, {34385,2303,38600 ,730,730,730 ,0,0,0}, + {38329,38331,38603 ,730,730,730 ,0,0,0}, {38611,38327,38223 ,730,730,730 ,0,0,0}, + {38610,38330,38329 ,730,730,730 ,0,0,0}, {38610,38327,38326 ,730,730,730 ,0,0,0}, + {38327,38611,38328 ,730,730,730 ,0,0,0}, {38623,38624,38222 ,730,730,730 ,0,0,0}, + {34387,37836,34747 ,730,730,730 ,0,0,0}, {38726,38219,34395 ,730,730,730 ,0,0,0}, + {34395,38607,38726 ,730,730,730 ,0,0,0}, {34751,34388,34749 ,730,730,730 ,0,0,0}, + {34390,2950,38607 ,730,730,730 ,0,0,0}, {34387,37840,38605 ,730,730,730 ,0,0,0}, + {34399,37849,37897 ,730,730,730 ,0,0,0}, {37897,37839,34399 ,730,730,730 ,0,0,0}, + {37831,38614,37894 ,730,730,730 ,0,0,0}, {37847,37895,37848 ,730,730,730 ,0,0,0}, + {34732,37838,34734 ,730,730,730 ,0,0,0}, {37831,37892,38614 ,730,730,730 ,0,0,0}, + {37831,37838,34732 ,730,730,730 ,0,0,0}, {38220,38221,38622 ,730,730,730 ,0,0,0}, + {38220,38229,37837 ,730,730,730 ,0,0,0}, {34379,38620,38221 ,730,730,730 ,0,0,0}, + {34381,38618,38620 ,730,730,730 ,0,0,0}, {34381,34376,38619 ,730,730,730 ,0,0,0}, + {38727,37842,34374 ,730,730,730 ,0,0,0}, {37902,34373,38621 ,730,730,730 ,0,0,0}, + {38727,34374,37902 ,730,730,730 ,0,0,0}, {38621,34384,38608 ,730,730,730 ,0,0,0}, + {38604,34384,34385 ,730,730,730 ,0,0,0}, {38630,34687,34689 ,730,730,730 ,0,0,0}, + {34612,38278,34631 ,730,730,730 ,0,0,0}, {3015,38627,34689 ,730,730,730 ,0,0,0}, + {37736,37738,38276 ,730,730,730 ,0,0,0}, {37738,38728,38654 ,730,730,730 ,0,0,0}, + {34611,37743,38277 ,730,730,730 ,0,0,0}, {37743,38728,38277 ,730,730,730 ,0,0,0}, + {38654,38728,37743 ,730,730,730 ,0,0,0}, {37747,34632,34631 ,730,730,730 ,0,0,0}, + {34638,34367,34640 ,730,730,730 ,0,0,0}, {34638,34637,34367 ,730,730,730 ,0,0,0}, + {34359,35879,38651 ,730,730,730 ,0,0,0}, {38661,34360,37741 ,730,730,730 ,0,0,0}, + {34359,35874,35877 ,730,730,730 ,0,0,0}, {34371,38625,35851 ,730,730,730 ,0,0,0}, + {35851,35873,34371 ,730,730,730 ,0,0,0}, {38274,35854,35853 ,730,730,730 ,0,0,0}, + {38274,35853,38625 ,730,730,730 ,0,0,0}, {38626,38629,38628 ,730,730,730 ,0,0,0}, + {37761,35857,35856 ,730,730,730 ,0,0,0}, {37761,35856,38275 ,730,730,730 ,0,0,0}, + {37761,38629,38626 ,730,730,730 ,0,0,0}, {38630,34685,34687 ,730,730,730 ,0,0,0}, + {38630,34689,38627 ,730,730,730 ,0,0,0}, {34351,34682,34685 ,730,730,730 ,0,0,0}, + {34353,34683,34682 ,730,730,730 ,0,0,0}, {34346,34676,34675 ,730,730,730 ,0,0,0}, + {34353,34348,34679 ,730,730,730 ,0,0,0}, {38510,34346,38511 ,730,730,730 ,0,0,0}, + {38511,34356,37764 ,730,730,730 ,0,0,0}, {38511,34346,34345 ,730,730,730 ,0,0,0}, + {34356,34357,38508 ,730,730,730 ,0,0,0}, {38729,38692,34323 ,730,730,730 ,0,0,0}, + {37597,34533,34536 ,730,730,730 ,0,0,0}, {38682,38691,38693 ,730,730,730 ,0,0,0}, + {37596,34536,38689 ,730,730,730 ,0,0,0}, {37575,37610,37573 ,730,730,730 ,0,0,0}, + {37576,37596,38689 ,730,730,730 ,0,0,0}, {37577,37596,37576 ,730,730,730 ,0,0,0}, + {37597,38684,34531 ,730,730,730 ,0,0,0}, {34523,34527,34339 ,730,730,730 ,0,0,0}, + {34331,38690,34540 ,730,730,730 ,0,0,0}, {34523,34334,34519 ,730,730,730 ,0,0,0}, + {34334,34523,34339 ,730,730,730 ,0,0,0}, {34540,34332,34331 ,730,730,730 ,0,0,0}, + {34331,37603,38690 ,730,730,730 ,0,0,0}, {38730,35847,34343 ,730,730,730 ,0,0,0}, + {34343,38319,34342 ,730,730,730 ,0,0,0}, {35845,38318,35842 ,730,730,730 ,0,0,0}, + {38317,35847,38730 ,730,730,730 ,0,0,0}, {38676,35839,38686 ,730,730,730 ,0,0,0}, + {35841,38686,35839 ,730,730,730 ,0,0,0}, {38681,38680,38676 ,730,730,730 ,0,0,0}, + {38681,38676,38686 ,730,730,730 ,0,0,0}, {38731,38693,38692 ,730,730,730 ,0,0,0}, + {34323,38683,38729 ,730,730,730 ,0,0,0}, {38692,38729,38731 ,730,730,730 ,0,0,0}, + {34323,34325,38679 ,730,730,730 ,0,0,0}, {34318,1263,34320 ,730,730,730 ,0,0,0}, + {34325,34320,38522 ,730,730,730 ,0,0,0}, {34318,34317,38524 ,730,730,730 ,0,0,0}, + {38525,34328,38320 ,730,730,730 ,0,0,0}, {38524,34317,38525 ,730,730,730 ,0,0,0}, + {34971,34328,34329 ,730,730,730 ,0,0,0}, {37476,37475,38561 ,730,730,730 ,0,0,0}, + {34301,35063,35069 ,730,730,730 ,0,0,0}, {35078,35076,38563 ,730,730,730 ,0,0,0}, + {38563,38732,38566 ,730,730,730 ,0,0,0}, {38563,38487,35078 ,730,730,730 ,0,0,0}, + {37997,38565,37474 ,730,730,730 ,0,0,0}, {38565,38732,37474 ,730,730,730 ,0,0,0}, + {38566,38732,38565 ,730,730,730 ,0,0,0}, {38546,38545,38561 ,730,730,730 ,0,0,0}, + {34303,38558,34869 ,730,730,730 ,0,0,0}, {38733,38542,34311 ,730,730,730 ,0,0,0}, + {34311,37998,38733 ,730,730,730 ,0,0,0}, {34873,34304,34871 ,730,730,730 ,0,0,0}, + {34306,34876,37998 ,730,730,730 ,0,0,0}, {34303,38009,38560 ,730,730,730 ,0,0,0}, + {34315,38010,38535 ,730,730,730 ,0,0,0}, {38535,38008,34315 ,730,730,730 ,0,0,0}, + {38005,38534,38183 ,730,730,730 ,0,0,0}, {38011,38182,38012 ,730,730,730 ,0,0,0}, + {34917,38488,34919 ,730,730,730 ,0,0,0}, {38005,38004,38534 ,730,730,730 ,0,0,0}, + {38005,38488,34917 ,730,730,730 ,0,0,0}, {37996,37995,38562 ,730,730,730 ,0,0,0}, + {37996,38559,38489 ,730,730,730 ,0,0,0}, {34295,38541,37995 ,730,730,730 ,0,0,0}, + {34297,38540,38541 ,730,730,730 ,0,0,0}, {34297,34292,38539 ,730,730,730 ,0,0,0}, + {34290,38484,38014 ,730,730,730 ,0,0,0}, {38485,34290,38017 ,730,730,730 ,0,0,0}, + {38017,34300,38490 ,730,730,730 ,0,0,0}, {38017,34290,34289 ,730,730,730 ,0,0,0}, + {34300,34301,35069 ,730,730,730 ,0,0,0}, {37684,37730,38734 ,730,730,730 ,0,0,0}, + {34595,37728,34593 ,730,730,730 ,0,0,0}, {38734,37685,37684 ,730,730,730 ,0,0,0}, + {37728,3049,38669 ,730,730,730 ,0,0,0}, {38666,38735,38667 ,730,730,730 ,0,0,0}, + {37593,38667,37591 ,730,730,730 ,0,0,0}, {37692,38669,3049 ,730,730,730 ,0,0,0}, + {38735,38669,38668 ,730,730,730 ,0,0,0}, {38666,38669,38735 ,730,730,730 ,0,0,0}, + {37728,38658,34593 ,730,730,730 ,0,0,0}, {34585,34589,34283 ,730,730,730 ,0,0,0}, + {34275,38664,34601 ,730,730,730 ,0,0,0}, {34585,34278,34581 ,730,730,730 ,0,0,0}, + {34278,34585,34283 ,730,730,730 ,0,0,0}, {34601,34276,34275 ,730,730,730 ,0,0,0}, + {34275,38281,38664 ,730,730,730 ,0,0,0}, {38736,35891,34287 ,730,730,730 ,0,0,0}, + {34287,37740,34286 ,730,730,730 ,0,0,0}, {35889,38279,35886 ,730,730,730 ,0,0,0}, + {38280,35891,38736 ,730,730,730 ,0,0,0}, {38652,35883,38660 ,730,730,730 ,0,0,0}, + {35885,38660,35883 ,730,730,730 ,0,0,0}, {37686,38665,38652 ,730,730,730 ,0,0,0}, + {37686,38652,38660 ,730,730,730 ,0,0,0}, {38737,38734,37730 ,730,730,730 ,0,0,0}, + {34267,38656,37731 ,730,730,730 ,0,0,0}, {37730,37731,38737 ,730,730,730 ,0,0,0}, + {34267,34269,38655 ,730,730,730 ,0,0,0}, {34262,37734,34628 ,730,730,730 ,0,0,0}, + {34269,34264,38284 ,730,730,730 ,0,0,0}, {34262,34261,37735 ,730,730,730 ,0,0,0}, + {38657,34261,37732 ,730,730,730 ,0,0,0}, {37732,34272,38659 ,730,730,730 ,0,0,0}, + {34273,38659,34272 ,730,730,730 ,0,0,0}, {37512,37511,38299 ,730,730,730 ,0,0,0}, + {38303,38302,34245 ,730,730,730 ,0,0,0}, {38307,38710,38305 ,730,730,730 ,0,0,0}, + {37547,37560,37510 ,730,730,730 ,0,0,0}, {38307,37584,38711 ,730,730,730 ,0,0,0}, + {37547,37549,37560 ,730,730,730 ,0,0,0}, {37582,37560,37583 ,730,730,730 ,0,0,0}, + {38299,38301,37512 ,730,730,730 ,0,0,0}, {34247,38706,34499 ,730,730,730 ,0,0,0}, + {38738,38708,34255 ,730,730,730 ,0,0,0}, {34255,37555,38738 ,730,730,730 ,0,0,0}, + {34503,34248,34501 ,730,730,730 ,0,0,0}, {34250,1297,37555 ,730,730,730 ,0,0,0}, + {34247,37565,38709 ,730,730,730 ,0,0,0}, {34259,37543,37545 ,730,730,730 ,0,0,0}, + {37545,37564,34259 ,730,730,730 ,0,0,0}, {37541,38688,37524 ,730,730,730 ,0,0,0}, + {37523,37522,37544 ,730,730,730 ,0,0,0}, {34546,38707,34548 ,730,730,730 ,0,0,0}, + {37541,37540,38688 ,730,730,730 ,0,0,0}, {37541,38707,34546 ,730,730,730 ,0,0,0}, + {38298,38695,38297 ,730,730,730 ,0,0,0}, {38298,37562,37563 ,730,730,730 ,0,0,0}, + {34239,38694,38695 ,730,730,730 ,0,0,0}, {34241,38295,38694 ,730,730,730 ,0,0,0}, + {34241,34236,38294 ,730,730,730 ,0,0,0}, {34234,37514,38292 ,730,730,730 ,0,0,0}, + {34234,34233,37513 ,730,730,730 ,0,0,0}, {38296,34233,37558 ,730,730,730 ,0,0,0}, + {37559,34244,34245 ,730,730,730 ,0,0,0}, {37558,34233,34244 ,730,730,730 ,0,0,0}, + {38551,34217,38572 ,730,730,730 ,0,0,0}, {37557,38552,34860 ,730,730,730 ,0,0,0}, + {37985,3917,37984 ,730,730,730 ,0,0,0}, {38200,38573,38197 ,730,730,730 ,0,0,0}, + {38200,38202,38574 ,730,730,730 ,0,0,0}, {37982,37984,3917 ,730,730,730 ,0,0,0}, + {38201,38575,38202 ,730,730,730 ,0,0,0}, {38575,37984,37983 ,730,730,730 ,0,0,0}, + {37985,38554,38553 ,730,730,730 ,0,0,0}, {38570,37989,34227 ,730,730,730 ,0,0,0}, + {34219,35948,37988 ,730,730,730 ,0,0,0}, {37988,34220,34219 ,730,730,730 ,0,0,0}, + {34222,38556,38570 ,730,730,730 ,0,0,0}, {34219,35954,35948 ,730,730,730 ,0,0,0}, + {37993,37992,38191 ,730,730,730 ,0,0,0}, {38739,35960,34231 ,730,730,730 ,0,0,0}, + {34231,35957,34230 ,730,730,730 ,0,0,0}, {38739,38002,35960 ,730,730,730 ,0,0,0}, + {38003,37991,38557 ,730,730,730 ,0,0,0}, {37556,34867,37992 ,730,730,730 ,0,0,0}, + {37992,34867,38191 ,730,730,730 ,0,0,0}, {37556,34863,34867 ,730,730,730 ,0,0,0}, + {34879,34860,38552 ,730,730,730 ,0,0,0}, {34211,34882,34880 ,730,730,730 ,0,0,0}, + {38552,34880,34879 ,730,730,730 ,0,0,0}, {34213,34208,34886 ,730,730,730 ,0,0,0}, + {34211,34213,34885 ,730,730,730 ,0,0,0}, {34206,37484,34890 ,730,730,730 ,0,0,0}, + {34206,34205,38195 ,730,730,730 ,0,0,0}, {38196,34205,37483 ,730,730,730 ,0,0,0}, + {37483,34216,38550 ,730,730,730 ,0,0,0}, {34217,38550,34216 ,730,730,730 ,0,0,0}, + {38265,38264,38674 ,730,730,730 ,0,0,0}, {37708,37709,34189 ,730,730,730 ,0,0,0}, + {38650,36008,37711 ,730,730,730 ,0,0,0}, {38268,38266,38263 ,730,730,730 ,0,0,0}, + {37712,36007,38650 ,730,730,730 ,0,0,0}, {37712,38266,36002 ,730,730,730 ,0,0,0}, + {38266,38268,36001 ,730,730,730 ,0,0,0}, {38674,38675,38265 ,730,730,730 ,0,0,0}, + {34191,37701,34653 ,730,730,730 ,0,0,0}, {38740,38260,34199 ,730,730,730 ,0,0,0}, + {34199,38645,38740 ,730,730,730 ,0,0,0}, {34657,34192,34655 ,730,730,730 ,0,0,0}, + {34194,34660,38645 ,730,730,730 ,0,0,0}, {34191,37713,37702 ,730,730,730 ,0,0,0}, + {34203,37715,37719 ,730,730,730 ,0,0,0}, {37719,37714,34203 ,730,730,730 ,0,0,0}, + {37683,38662,37693 ,730,730,730 ,0,0,0}, {37695,37694,37716 ,730,730,730 ,0,0,0}, + {34607,38642,34609 ,730,730,730 ,0,0,0}, {37683,37726,38662 ,730,730,730 ,0,0,0}, + {37683,38642,34607 ,730,730,730 ,0,0,0}, {38262,38261,38640 ,730,730,730 ,0,0,0}, + {38262,38641,38643 ,730,730,730 ,0,0,0}, {34183,37703,38261 ,730,730,730 ,0,0,0}, + {34185,38647,37703 ,730,730,730 ,0,0,0}, {34185,34180,38646 ,730,730,730 ,0,0,0}, + {38671,37587,34178 ,730,730,730 ,0,0,0}, {34178,34177,38648 ,730,730,730 ,0,0,0}, + {38649,34177,38672 ,730,730,730 ,0,0,0}, {38673,34188,34189 ,730,730,730 ,0,0,0}, + {38672,34177,34188 ,730,730,730 ,0,0,0}, {34161,37520,38700 ,730,730,730 ,0,0,0}, + {38720,38313,34490 ,730,730,730 ,0,0,0}, {37539,34488,38722 ,730,730,730 ,0,0,0}, + {38721,36072,37521 ,730,730,730 ,0,0,0}, {38287,36071,38721 ,730,730,730 ,0,0,0}, + {34488,36065,38722 ,730,730,730 ,0,0,0}, {38287,36066,36069 ,730,730,730 ,0,0,0}, + {36066,38722,36065 ,730,730,730 ,0,0,0}, {37539,37533,37532 ,730,730,730 ,0,0,0}, + {38718,37580,34171 ,730,730,730 ,0,0,0}, {34163,35816,37504 ,730,730,730 ,0,0,0}, + {37504,34164,34163 ,730,730,730 ,0,0,0}, {34166,38704,38718 ,730,730,730 ,0,0,0}, + {34163,35822,35816 ,730,730,730 ,0,0,0}, {37519,37518,37554 ,730,730,730 ,0,0,0}, + {38741,35828,34175 ,730,730,730 ,0,0,0}, {34175,35825,34174 ,730,730,730 ,0,0,0}, + {38741,37509,35828 ,730,730,730 ,0,0,0}, {37508,37507,38705 ,730,730,730 ,0,0,0}, + {38703,34497,37518 ,730,730,730 ,0,0,0}, {37518,34497,37554 ,730,730,730 ,0,0,0}, + {38703,34493,34497 ,730,730,730 ,0,0,0}, {34508,34490,38313 ,730,730,730 ,0,0,0}, + {34155,34511,34509 ,730,730,730 ,0,0,0}, {38313,34509,34508 ,730,730,730 ,0,0,0}, + {34157,34152,34515 ,730,730,730 ,0,0,0}, {34155,34157,34514 ,730,730,730 ,0,0,0}, + {34150,37578,2073 ,730,730,730 ,0,0,0}, {34150,34149,37579 ,730,730,730 ,0,0,0}, + {37585,34149,38702 ,730,730,730 ,0,0,0}, {38701,34160,34161 ,730,730,730 ,0,0,0}, + {38702,34149,34160 ,730,730,730 ,0,0,0}, {3931,38568,38567 ,730,730,730 ,0,0,0}, + {34941,37973,38181 ,730,730,730 ,0,0,0}, {34843,3931,38567 ,730,730,730 ,0,0,0}, + {38210,36135,38528 ,730,730,730 ,0,0,0}, {34921,38208,34922 ,730,730,730 ,0,0,0}, + {38210,38208,36130 ,730,730,730 ,0,0,0}, {38210,36133,36135 ,730,730,730 ,0,0,0}, + {38208,34921,36129 ,730,730,730 ,0,0,0}, {38181,34942,34941 ,730,730,730 ,0,0,0}, + {34948,34143,34950 ,730,730,730 ,0,0,0}, {34948,34947,34143 ,730,730,730 ,0,0,0}, + {34135,35967,38209 ,730,730,730 ,0,0,0}, {38533,34136,37972 ,730,730,730 ,0,0,0}, + {34135,35962,35965 ,730,730,730 ,0,0,0}, {34147,37976,35939 ,730,730,730 ,0,0,0}, + {35939,35961,34147 ,730,730,730 ,0,0,0}, {37534,35942,35941 ,730,730,730 ,0,0,0}, + {37534,35941,37976 ,730,730,730 ,0,0,0}, {37961,38569,38568 ,730,730,730 ,0,0,0}, + {37550,35945,35944 ,730,730,730 ,0,0,0}, {37550,35944,37535 ,730,730,730 ,0,0,0}, + {37550,38569,37961 ,730,730,730 ,0,0,0}, {38205,34839,34841 ,730,730,730 ,0,0,0}, + {38205,34843,38567 ,730,730,730 ,0,0,0}, {34127,34836,34839 ,730,730,730 ,0,0,0}, + {34129,34837,34836 ,730,730,730 ,0,0,0}, {38207,34830,34122 ,730,730,730 ,0,0,0}, + {34129,34124,34833 ,730,730,730 ,0,0,0}, {34122,34121,37966 ,730,730,730 ,0,0,0}, + {37967,34121,37965 ,730,730,730 ,0,0,0}, {37964,34132,34133 ,730,730,730 ,0,0,0}, + {37965,34121,34132 ,730,730,730 ,0,0,0}, {34105,3171,36021 ,730,730,730 ,0,0,0}, + {38632,38270,34644 ,730,730,730 ,0,0,0}, {38273,3029,38634 ,730,730,730 ,0,0,0}, + {38633,36027,37746 ,730,730,730 ,0,0,0}, {38254,36029,38633 ,730,730,730 ,0,0,0}, + {36035,38634,3029 ,730,730,730 ,0,0,0}, {38254,36032,36029 ,730,730,730 ,0,0,0}, + {36033,38634,36035 ,730,730,730 ,0,0,0}, {38273,38638,38637 ,730,730,730 ,0,0,0}, + {37723,37722,34115 ,730,730,730 ,0,0,0}, {34107,35860,38252 ,730,730,730 ,0,0,0}, + {38252,34108,34107 ,730,730,730 ,0,0,0}, {34110,38631,37723 ,730,730,730 ,0,0,0}, + {34107,35866,35860 ,730,730,730 ,0,0,0}, {37706,37705,37707 ,730,730,730 ,0,0,0}, + {38742,35872,34119 ,730,730,730 ,0,0,0}, {34119,35869,34118 ,730,730,730 ,0,0,0}, + {38742,37700,35872 ,730,730,730 ,0,0,0}, {37699,37704,38639 ,730,730,730 ,0,0,0}, + {37720,34651,37705 ,730,730,730 ,0,0,0}, {37705,34651,37707 ,730,730,730 ,0,0,0}, + {37720,34647,34651 ,730,730,730 ,0,0,0}, {34663,34644,38270 ,730,730,730 ,0,0,0}, + {34099,34666,34664 ,730,730,730 ,0,0,0}, {38270,34664,34663 ,730,730,730 ,0,0,0}, + {34101,34096,34670 ,730,730,730 ,0,0,0}, {34099,34101,34669 ,730,730,730 ,0,0,0}, + {35984,34094,35983 ,730,730,730 ,0,0,0}, {34094,34093,35981 ,730,730,730 ,0,0,0}, + {34093,34104,36015 ,730,730,730 ,0,0,0}, {36020,34104,34105 ,730,730,730 ,0,0,0}, + {36015,34104,36017 ,730,730,730 ,0,0,0}, {34474,38716,38715 ,730,730,730 ,0,0,0}, + {34570,37529,38288 ,730,730,730 ,0,0,0}, {34471,34474,38715 ,730,730,730 ,0,0,0}, + {38678,36093,38316 ,730,730,730 ,0,0,0}, {34551,38314,34552 ,730,730,730 ,0,0,0}, + {38678,38314,36097 ,730,730,730 ,0,0,0}, {38678,36096,36093 ,730,730,730 ,0,0,0}, + {38314,34551,36099 ,730,730,730 ,0,0,0}, {38288,34571,34570 ,730,730,730 ,0,0,0}, + {34577,34087,34579 ,730,730,730 ,0,0,0}, {34577,34576,34087 ,730,730,730 ,0,0,0}, + {34079,35835,37594 ,730,730,730 ,0,0,0}, {38687,34080,37590 ,730,730,730 ,0,0,0}, + {34079,35830,35833 ,730,730,730 ,0,0,0}, {34091,38714,35807 ,730,730,730 ,0,0,0}, + {35807,35829,34091 ,730,730,730 ,0,0,0}, {38286,35810,35809 ,730,730,730 ,0,0,0}, + {38286,35809,38714 ,730,730,730 ,0,0,0}, {37526,38717,38716 ,730,730,730 ,0,0,0}, + {37525,35813,35812 ,730,730,730 ,0,0,0}, {37525,35812,38285 ,730,730,730 ,0,0,0}, + {37525,38717,37526 ,730,730,730 ,0,0,0}, {37528,34467,34469 ,730,730,730 ,0,0,0}, + {37528,34471,38715 ,730,730,730 ,0,0,0}, {34071,34464,34467 ,730,730,730 ,0,0,0}, + {34073,34465,34464 ,730,730,730 ,0,0,0}, {36047,36048,34066 ,730,730,730 ,0,0,0}, + {34073,34068,34461 ,730,730,730 ,0,0,0}, {34066,34065,36045 ,730,730,730 ,0,0,0}, + {36079,34076,36081 ,730,730,730 ,0,0,0}, {36045,34065,36079 ,730,730,730 ,0,0,0}, + {36084,34076,34077 ,730,730,730 ,0,0,0}, {37981,37978,38743 ,730,730,730 ,0,0,0}, + {34905,38180,34903 ,730,730,730 ,0,0,0}, {38743,37979,37981 ,730,730,730 ,0,0,0}, + {38180,3897,38186 ,730,730,730 ,0,0,0}, {36157,38185,36160 ,730,730,730 ,0,0,0}, + {38185,36157,38006 ,730,730,730 ,0,0,0}, {36163,38186,3897 ,730,730,730 ,0,0,0}, + {36161,38186,36163 ,730,730,730 ,0,0,0}, {38180,38531,34903 ,730,730,730 ,0,0,0}, + {34895,34899,34059 ,730,730,730 ,0,0,0}, {34051,38536,34911 ,730,730,730 ,0,0,0}, + {34895,34054,34891 ,730,730,730 ,0,0,0}, {34054,34895,34059 ,730,730,730 ,0,0,0}, + {34911,34052,34051 ,730,730,730 ,0,0,0}, {34051,38211,38536 ,730,730,730 ,0,0,0}, + {38744,35979,34063 ,730,730,730 ,0,0,0}, {34063,37974,34062 ,730,730,730 ,0,0,0}, + {35977,37968,35974 ,730,730,730 ,0,0,0}, {37969,35979,38744 ,730,730,730 ,0,0,0}, + {38526,35971,38532 ,730,730,730 ,0,0,0}, {35973,38532,35971 ,730,730,730 ,0,0,0}, + {37980,38537,38526 ,730,730,730 ,0,0,0}, {37980,38526,38532 ,730,730,730 ,0,0,0}, + {38745,38743,37978 ,730,730,730 ,0,0,0}, {34043,38530,37977 ,730,730,730 ,0,0,0}, + {37978,37977,38745 ,730,730,730 ,0,0,0}, {34043,34045,38529 ,730,730,730 ,0,0,0}, + {36112,34038,36111 ,730,730,730 ,0,0,0}, {34045,34040,38212 ,730,730,730 ,0,0,0}, + {34038,34037,36109 ,730,730,730 ,0,0,0}, {34037,34048,36143 ,730,730,730 ,0,0,0}, + {36148,34048,34049 ,730,730,730 ,0,0,0}, {36143,34048,36145 ,730,730,730 ,0,0,0}, + {38403,38746,38363 ,730,730,730 ,0,0,0}, {38363,38746,38433 ,730,730,730 ,0,0,0}, + {37815,36352,36448 ,20176,20176,20176 ,0,0,0}, {37815,36448,37919 ,20176,20176,20176 ,0,0,0}, + {36374,36373,37850 ,20177,20178,20179 ,0,0,0}, {37852,36381,36374 ,20180,20181,20177 ,0,0,0}, + {36374,37850,37852 ,20177,20179,20180 ,0,0,0}, {36381,37890,36379 ,20181,20182,20183 ,0,0,0}, + {37890,36381,37852 ,20182,20181,20180 ,0,0,0}, {36376,36379,38617 ,20184,20183,20185 ,0,0,0}, + {37890,38617,36379 ,20182,20185,20183 ,0,0,0}, {37893,37341,36376 ,20186,20187,20184 ,0,0,0}, + {36376,38617,37893 ,20184,20185,20186 ,0,0,0}, {37341,37853,36364 ,20187,20188,20189 ,0,0,0}, + {37853,37341,37893 ,20188,20187,20186 ,0,0,0}, {36365,36364,37845 ,20190,20189,20191 ,0,0,0}, + {37853,37845,36364 ,20188,20191,20189 ,0,0,0}, {37844,36957,36365 ,20192,20193,20190 ,0,0,0}, + {36365,37845,37844 ,20190,20191,20192 ,0,0,0}, {36957,37900,36956 ,20193,20194,20195 ,0,0,0}, + {37900,36957,37844 ,20194,20193,20192 ,0,0,0}, {37338,36956,37899 ,20196,20195,20197 ,0,0,0}, + {37900,37899,36956 ,20194,20197,20195 ,0,0,0}, {38214,37339,37338 ,20198,20199,20196 ,0,0,0}, + {37338,37899,38214 ,20196,20197,20198 ,0,0,0}, {37339,37832,36400 ,20199,20200,20201 ,0,0,0}, + {37832,37339,38214 ,20200,20199,20198 ,0,0,0}, {36399,36400,38217 ,20202,20201,20203 ,0,0,0}, + {37832,38217,36400 ,20200,20203,20201 ,0,0,0}, {37843,36397,36399 ,20204,20205,20202 ,0,0,0}, + {36399,38217,37843 ,20202,20203,20204 ,0,0,0}, {36397,37842,36951 ,20205,20206,20207 ,0,0,0}, + {37842,36397,37843 ,20206,20205,20204 ,0,0,0}, {36952,36951,38727 ,20208,20207,20209 ,0,0,0}, + {37842,38727,36951 ,20206,20209,20207 ,0,0,0}, {37902,36949,36952 ,20210,20211,20208 ,0,0,0}, + {36952,38727,37902 ,20208,20209,20210 ,0,0,0}, {36949,38621,36950 ,20211,20212,20213 ,0,0,0}, + {38621,36949,37902 ,20212,20211,20210 ,0,0,0}, {37449,36950,38608 ,20214,20213,20215 ,0,0,0}, + {38621,38608,36950 ,20212,20215,20213 ,0,0,0}, {38604,36403,37449 ,20216,20217,20214 ,0,0,0}, + {37449,38608,38604 ,20214,20215,20216 ,0,0,0}, {36403,38600,36404 ,20217,20218,20219 ,0,0,0}, + {38600,36403,38604 ,20218,20217,20216 ,0,0,0}, {36948,36404,38599 ,20220,20219,20221 ,0,0,0}, + {38600,38599,36404 ,20218,20221,20219 ,0,0,0}, {38602,36407,36948 ,20222,20223,20220 ,0,0,0}, + {36948,38599,38602 ,20220,20221,20222 ,0,0,0}, {36407,38331,36405 ,20223,20224,20225 ,0,0,0}, + {38331,36407,38602 ,20224,20223,20222 ,0,0,0}, {36945,36405,38330 ,20226,20225,20227 ,0,0,0}, + {38331,38330,36405 ,20224,20227,20225 ,0,0,0}, {38609,37345,36945 ,20228,20229,20226 ,0,0,0}, + {36945,38330,38609 ,20226,20227,20228 ,0,0,0}, {37345,38326,36939 ,20229,20230,20231 ,0,0,0}, + {38326,37345,38609 ,20230,20229,20228 ,0,0,0}, {36938,36939,38328 ,20232,20231,20233 ,0,0,0}, + {38326,38328,36939 ,20230,20233,20231 ,0,0,0}, {38333,36935,36938 ,20234,20235,20232 ,0,0,0}, + {36938,38328,38333 ,20232,20233,20234 ,0,0,0}, {36935,38332,36936 ,20235,20236,20237 ,0,0,0}, + {38332,36935,38333 ,20236,20235,20234 ,0,0,0}, {37053,36936,38336 ,20238,20237,20239 ,0,0,0}, + {38332,38336,36936 ,20236,20239,20237 ,0,0,0}, {38612,37055,37053 ,20240,20240,20238 ,0,0,0}, + {37053,38336,38612 ,20238,20239,20240 ,0,0,0}, {37850,36373,37856 ,20179,20178,20241 ,0,0,0}, + {37886,37856,37322 ,20242,20241,20243 ,0,0,0}, {36373,37322,37856 ,20178,20243,20241 ,0,0,0}, + {37445,38587,37886 ,20244,20245,20242 ,0,0,0}, {37886,37322,37445 ,20242,20243,20244 ,0,0,0}, + {38587,36369,38582 ,20245,20246,20247 ,0,0,0}, {36369,38587,37445 ,20246,20245,20244 ,0,0,0}, + {38584,38582,37446 ,20248,20247,20249 ,0,0,0}, {36369,37446,38582 ,20246,20249,20247 ,0,0,0}, + {36370,38583,38584 ,20250,20251,20248 ,0,0,0}, {38584,37446,36370 ,20248,20249,20250 ,0,0,0}, + {38583,36371,38251 ,20251,20252,20253 ,0,0,0}, {36371,38583,36370 ,20252,20251,20250 ,0,0,0}, + {38250,38251,36375 ,20254,20253,20255 ,0,0,0}, {36371,36375,38251 ,20252,20255,20253 ,0,0,0}, + {36368,37879,38250 ,20256,20257,20254 ,0,0,0}, {38250,36375,36368 ,20254,20255,20256 ,0,0,0}, + {37879,36383,37819 ,20257,20258,20259 ,0,0,0}, {36383,37879,36368 ,20258,20257,20256 ,0,0,0}, + {38249,37819,36387 ,20260,20259,20261 ,0,0,0}, {36383,36387,37819 ,20258,20261,20259 ,0,0,0}, + {36388,37872,38249 ,20262,20263,20260 ,0,0,0}, {38249,36387,36388 ,20260,20261,20262 ,0,0,0}, + {37872,36391,37871 ,20263,20264,20265 ,0,0,0}, {36391,37872,36388 ,20264,20263,20262 ,0,0,0}, + {38248,37871,36394 ,20266,20265,20267 ,0,0,0}, {36391,36394,37871 ,20264,20267,20265 ,0,0,0}, + {36393,37861,38248 ,20268,20269,20266 ,0,0,0}, {38248,36394,36393 ,20266,20267,20268 ,0,0,0}, + {37861,37314,37862 ,20269,20270,20271 ,0,0,0}, {37314,37861,36393 ,20270,20269,20268 ,0,0,0}, + {38581,37862,36354 ,20272,20271,20273 ,0,0,0}, {37314,36354,37862 ,20270,20273,20271 ,0,0,0}, + {36353,38579,38581 ,20274,20275,20272 ,0,0,0}, {38581,36354,36353 ,20272,20273,20274 ,0,0,0}, + {38579,37323,38247 ,20275,20276,20277 ,0,0,0}, {37323,38579,36353 ,20276,20275,20274 ,0,0,0}, + {37866,38247,37325 ,20278,20277,20279 ,0,0,0}, {37323,37325,38247 ,20276,20279,20277 ,0,0,0}, + {37061,37822,37866 ,20280,20281,20278 ,0,0,0}, {37866,37325,37061 ,20278,20279,20280 ,0,0,0}, + {37822,37060,38580 ,20281,20282,20283 ,0,0,0}, {37060,37822,37061 ,20282,20281,20280 ,0,0,0}, + {38243,38580,36917 ,20284,20283,20285 ,0,0,0}, {37060,36917,38580 ,20282,20285,20283 ,0,0,0}, + {36918,38244,38243 ,20286,20287,20284 ,0,0,0}, {38243,36917,36918 ,20284,20285,20286 ,0,0,0}, + {38244,36924,37864 ,20287,20288,20289 ,0,0,0}, {36924,38244,36918 ,20288,20287,20286 ,0,0,0}, + {38591,37864,36923 ,20290,20289,20291 ,0,0,0}, {36924,36923,37864 ,20288,20291,20289 ,0,0,0}, + {36925,38590,38591 ,20292,20293,20290 ,0,0,0}, {38591,36923,36925 ,20290,20291,20292 ,0,0,0}, + {38590,36437,38245 ,20293,20294,20295 ,0,0,0}, {36437,38590,36925 ,20294,20293,20292 ,0,0,0}, + {38242,38245,36436 ,20296,20295,20297 ,0,0,0}, {36437,36436,38245 ,20294,20297,20295 ,0,0,0}, + {37043,37827,38242 ,20298,20299,20296 ,0,0,0}, {38242,36436,37043 ,20296,20297,20298 ,0,0,0}, + {37827,37328,37881 ,20299,20300,20301 ,0,0,0}, {37328,37827,37043 ,20300,20299,20298 ,0,0,0}, + {37328,36447,37881 ,20300,20302,20301 ,0,0,0}, {37881,36447,37882 ,20301,20302,20302 ,0,0,0}, + {38492,36443,37817 ,20303,9968,20303 ,0,0,0}, {36443,38492,36449 ,9968,20303,9968 ,0,0,0}, + {36327,37668,37807 ,4303,4303,4303 ,0,0,0}, {36327,37807,36337 ,4303,4303,4303 ,0,0,0}, + {37940,36213,36833 ,21,20304,20304 ,0,0,0}, {37940,36833,38132 ,21,20304,21 ,0,0,0}, + {36306,37956,36293 ,20305,20306,20305 ,0,0,0}, {37956,36306,38026 ,20306,20305,20306 ,0,0,0}, + {37300,36141,36140 ,20307,20308,20309 ,0,0,0}, {37967,37965,36279 ,20310,20311,20312 ,0,0,0}, + {36278,37964,37301 ,20313,20314,20315 ,0,0,0}, {38207,36243,37963 ,20316,20317,20318 ,0,0,0}, + {37299,36878,37966 ,20319,20320,20321 ,0,0,0}, {36237,38204,36285 ,20322,20323,20324 ,0,0,0}, + {37553,37552,36286 ,20325,20326,20327 ,0,0,0}, {38203,36235,36234 ,20328,20329,20330 ,0,0,0}, + {37546,36236,37962 ,20331,20332,20333 ,0,0,0}, {36881,36880,38575 ,20334,20335,20336 ,0,0,0}, + {37304,37983,37982 ,20337,20338,20339 ,0,0,0}, {36298,38573,36874 ,20340,20341,20342 ,0,0,0}, + {38574,38202,37289 ,20343,20344,20345 ,0,0,0}, {38551,38572,37290 ,20346,20347,20348 ,0,0,0}, + {38198,36297,38572 ,20349,20350,20347 ,0,0,0}, {37483,38550,36887 ,20351,20352,20353 ,0,0,0}, + {38551,36888,38550 ,20346,20354,20352 ,0,0,0}, {36891,38196,37483 ,20355,20356,20351 ,0,0,0}, + {37483,36887,36891 ,20351,20353,20355 ,0,0,0}, {38196,36890,38195 ,20356,20357,20358 ,0,0,0}, + {36890,38196,36891 ,20357,20356,20355 ,0,0,0}, {37484,38195,37291 ,20359,20358,20360 ,0,0,0}, + {36890,37291,38195 ,20357,20360,20358 ,0,0,0}, {37282,37485,37484 ,20361,20362,20359 ,0,0,0}, + {37484,37291,37282 ,20359,20360,20361 ,0,0,0}, {37485,36896,38193 ,20362,20363,20364 ,0,0,0}, + {36896,37485,37282 ,20363,20362,20361 ,0,0,0}, {38001,38193,36895 ,20365,20364,20366 ,0,0,0}, + {36896,36895,38193 ,20363,20366,20364 ,0,0,0}, {37293,37999,38001 ,20367,20367,20365 ,0,0,0}, + {38001,36895,37293 ,20365,20366,20367 ,0,0,0}, {37290,36888,38551 ,20348,20354,20346 ,0,0,0}, + {38550,36888,36887 ,20352,20354,20353 ,0,0,0}, {36298,36297,38198 ,20340,20350,20349 ,0,0,0}, + {38572,36297,37290 ,20347,20350,20348 ,0,0,0}, {38573,38574,36874 ,20341,20343,20342 ,0,0,0}, + {38198,38573,36298 ,20349,20341,20340 ,0,0,0}, {37289,38202,36880 ,20345,20344,20335 ,0,0,0}, + {36874,38574,37289 ,20342,20343,20345 ,0,0,0}, {36881,38575,37983 ,20334,20336,20338 ,0,0,0}, + {36880,38202,38575 ,20335,20344,20336 ,0,0,0}, {36234,37304,37982 ,20330,20337,20339 ,0,0,0}, + {37304,36881,37983 ,20337,20334,20338 ,0,0,0}, {37962,36235,38203 ,20333,20329,20328 ,0,0,0}, + {38203,36234,37982 ,20328,20330,20339 ,0,0,0}, {37546,36237,36236 ,20331,20322,20332 ,0,0,0}, + {37962,36236,36235 ,20333,20332,20329 ,0,0,0}, {38204,37553,36285 ,20323,20325,20324 ,0,0,0}, + {37546,38204,36237 ,20331,20323,20322 ,0,0,0}, {36286,37552,36242 ,20327,20326,20368 ,0,0,0}, + {36285,37553,36286 ,20324,20325,20327 ,0,0,0}, {37963,36243,36242 ,20318,20317,20368 ,0,0,0}, + {36242,37552,37963 ,20368,20326,20318 ,0,0,0}, {37966,36878,38207 ,20321,20320,20316 ,0,0,0}, + {36878,36243,38207 ,20320,20317,20316 ,0,0,0}, {37967,36279,37299 ,20310,20312,20319 ,0,0,0}, + {37967,37299,37966 ,20310,20319,20321 ,0,0,0}, {37965,37964,36278 ,20311,20314,20313 ,0,0,0}, + {37965,36278,36279 ,20311,20313,20312 ,0,0,0}, {37301,38206,37300 ,20315,20369,20307 ,0,0,0}, + {37964,38206,37301 ,20314,20369,20315 ,0,0,0}, {36141,37300,38206 ,20308,20307,20369 ,0,0,0}, + {36292,37957,38024 ,20370,20370,20370 ,0,0,0}, {36292,38024,36289 ,20370,20370,20370 ,0,0,0}, + {37948,36181,38050 ,20371,20372,20371 ,0,0,0}, {36181,37948,36199 ,20372,20371,20372 ,0,0,0}, + {37488,37481,36195 ,20373,126,126 ,0,0,0}, {37488,36195,36182 ,20373,126,20373 ,0,0,0}, + {37598,36677,37200 ,20374,20375,20375 ,0,0,0}, {37598,37200,37595 ,20374,20375,20374 ,0,0,0}, + {37429,36077,36076 ,20376,20377,20378 ,0,0,0}, {37585,38702,36689 ,20379,20380,20381 ,0,0,0}, + {37006,38701,37007 ,20382,20383,20384 ,0,0,0}, {37578,37009,38312 ,20385,20386,20387 ,0,0,0}, + {36690,37430,37579 ,20388,20389,20390 ,0,0,0}, {36693,38697,37010 ,20391,20392,20393 ,0,0,0}, + {38310,37566,37011 ,20394,20395,20396 ,0,0,0}, {38713,37431,36696 ,20397,20398,20399 ,0,0,0}, + {38698,37013,38308 ,20400,20401,20402 ,0,0,0}, {37432,37434,37583 ,20403,20404,20405 ,0,0,0}, + {37414,38712,37549 ,20406,20407,20408 ,0,0,0}, {37022,38710,37019 ,20409,20410,20411 ,0,0,0}, + {38711,37584,37020 ,20412,20413,20414 ,0,0,0}, {38302,38304,37025 ,20415,20416,20417 ,0,0,0}, + {38306,37024,38304 ,20418,20419,20416 ,0,0,0}, {37558,37559,37416 ,20420,20421,20422 ,0,0,0}, + {38302,37026,37559 ,20415,20423,20421 ,0,0,0}, {37028,38296,37558 ,20424,20425,20420 ,0,0,0}, + {37558,37416,37028 ,20420,20422,20424 ,0,0,0}, {38296,37027,37513 ,20425,20426,20427 ,0,0,0}, + {37027,38296,37028 ,20426,20425,20424 ,0,0,0}, {37514,37513,37417 ,20428,20427,20429 ,0,0,0}, + {37027,37417,37513 ,20426,20429,20427 ,0,0,0}, {37032,38293,37514 ,20430,20431,20428 ,0,0,0}, + {37514,37417,37032 ,20428,20429,20430 ,0,0,0}, {38293,37418,37516 ,20431,20432,20433 ,0,0,0}, + {37418,38293,37032 ,20432,20431,20430 ,0,0,0}, {37517,37516,37031 ,20434,20433,20435 ,0,0,0}, + {37418,37031,37516 ,20432,20435,20433 ,0,0,0}, {37030,38290,37517 ,20436,20436,20434 ,0,0,0}, + {37517,37031,37030 ,20434,20435,20436 ,0,0,0}, {37025,37026,38302 ,20417,20423,20415 ,0,0,0}, + {37559,37026,37416 ,20421,20423,20422 ,0,0,0}, {37022,37024,38306 ,20409,20419,20418 ,0,0,0}, + {38304,37024,37025 ,20416,20419,20417 ,0,0,0}, {38710,38711,37019 ,20410,20412,20411 ,0,0,0}, + {38306,38710,37022 ,20418,20410,20409 ,0,0,0}, {37020,37584,37434 ,20414,20413,20404 ,0,0,0}, + {37019,38711,37020 ,20411,20412,20414 ,0,0,0}, {37432,37583,38712 ,20403,20405,20407 ,0,0,0}, + {37434,37584,37583 ,20404,20413,20405 ,0,0,0}, {36696,37414,37549 ,20399,20406,20408 ,0,0,0}, + {37414,37432,38712 ,20406,20403,20407 ,0,0,0}, {38308,37431,38713 ,20402,20398,20397 ,0,0,0}, + {38713,36696,37549 ,20397,20399,20408 ,0,0,0}, {38698,36693,37013 ,20400,20391,20401 ,0,0,0}, + {38308,37013,37431 ,20402,20401,20398 ,0,0,0}, {38697,38310,37010 ,20392,20394,20393 ,0,0,0}, + {38698,38697,36693 ,20400,20392,20391 ,0,0,0}, {37011,37566,37422 ,20396,20395,20437 ,0,0,0}, + {37010,38310,37011 ,20393,20394,20396 ,0,0,0}, {38312,37009,37422 ,20387,20386,20437 ,0,0,0}, + {37422,37566,38312 ,20437,20395,20387 ,0,0,0}, {37579,37430,37578 ,20390,20389,20385 ,0,0,0}, + {37430,37009,37578 ,20389,20386,20385 ,0,0,0}, {37585,36689,36690 ,20379,20381,20388 ,0,0,0}, + {37585,36690,37579 ,20379,20388,20390 ,0,0,0}, {38702,38701,37006 ,20380,20383,20382 ,0,0,0}, + {38702,37006,36689 ,20380,20382,20381 ,0,0,0}, {37007,38700,37429 ,20384,20438,20376 ,0,0,0}, + {38701,38700,37007 ,20383,20438,20384 ,0,0,0}, {36077,37429,38700 ,20377,20376,20438 ,0,0,0}, + {37615,36676,37599 ,20439,20440,20439 ,0,0,0}, {36676,37615,36738 ,20440,20439,20440 ,0,0,0}, + {36645,38366,37626 ,7656,7656,7656 ,0,0,0}, {36645,37626,36653 ,7656,7656,7656 ,0,0,0}, + {37648,37094,36792 ,20441,9944,9944 ,0,0,0}, {37648,36792,37661 ,20441,9944,20441 ,0,0,0}, + {36623,37750,36528 ,20442,20443,20442 ,0,0,0}, {37750,36623,37767 ,20443,20442,20443 ,0,0,0}, + {36600,36013,36012 ,20444,20445,20446 ,0,0,0}, {38649,38672,36984 ,20447,20448,20449 ,0,0,0}, + {36985,38673,36599 ,20450,20451,20452 ,0,0,0}, {38671,36986,37588 ,20453,20454,20455 ,0,0,0}, + {37391,37396,38648 ,20456,20457,20458 ,0,0,0}, {37386,38256,37387 ,20459,20460,20461 ,0,0,0}, + {38258,38670,36962 ,20462,20463,20464 ,0,0,0}, {37691,36988,36552 ,20465,20466,20467 ,0,0,0}, + {37698,36559,37696 ,20468,20469,20470 ,0,0,0}, {36993,36992,38735 ,20471,20472,20473 ,0,0,0}, + {36555,38668,37692 ,20474,20475,20476 ,0,0,0}, {36544,37592,37378 ,20477,20478,20479 ,0,0,0}, + {37591,38667,37379 ,20480,20481,20482 ,0,0,0}, {37727,37688,37381 ,20483,20484,20485 ,0,0,0}, + {37687,36543,37688 ,20486,20487,20484 ,0,0,0}, {37732,38659,37383 ,20488,20489,20490 ,0,0,0}, + {37727,37382,38659 ,20483,20491,20489 ,0,0,0}, {36606,38657,37732 ,20492,20493,20488 ,0,0,0}, + {37732,37383,36606 ,20488,20490,20492 ,0,0,0}, {38657,36607,37735 ,20493,20494,20495 ,0,0,0}, + {36607,38657,36606 ,20494,20493,20492 ,0,0,0}, {37734,37735,36611 ,20496,20495,20497 ,0,0,0}, + {36607,36611,37735 ,20494,20497,20495 ,0,0,0}, {36610,37744,37734 ,20498,20499,20496 ,0,0,0}, + {37734,36611,36610 ,20496,20497,20498 ,0,0,0}, {37744,36613,38283 ,20499,20500,20501 ,0,0,0}, + {36613,37744,36610 ,20500,20499,20498 ,0,0,0}, {37745,38283,36969 ,20502,20501,20503 ,0,0,0}, + {36613,36969,38283 ,20500,20503,20501 ,0,0,0}, {36562,37742,37745 ,20504,20504,20502 ,0,0,0}, + {37745,36969,36562 ,20502,20503,20504 ,0,0,0}, {37381,37382,37727 ,20485,20491,20483 ,0,0,0}, + {38659,37382,37383 ,20489,20491,20490 ,0,0,0}, {36544,36543,37687 ,20477,20487,20486 ,0,0,0}, + {37688,36543,37381 ,20484,20487,20485 ,0,0,0}, {37592,37591,37378 ,20478,20480,20479 ,0,0,0}, + {37687,37592,36544 ,20486,20478,20477 ,0,0,0}, {37379,38667,36992 ,20482,20481,20472 ,0,0,0}, + {37378,37591,37379 ,20479,20480,20482 ,0,0,0}, {36993,38735,38668 ,20471,20473,20475 ,0,0,0}, + {36992,38667,38735 ,20472,20481,20473 ,0,0,0}, {36552,36555,37692 ,20467,20474,20476 ,0,0,0}, + {36555,36993,38668 ,20474,20471,20475 ,0,0,0}, {37696,36988,37691 ,20470,20466,20465 ,0,0,0}, + {37691,36552,37692 ,20465,20467,20476 ,0,0,0}, {37698,37386,36559 ,20468,20459,20469 ,0,0,0}, + {37696,36559,36988 ,20470,20469,20466 ,0,0,0}, {38256,38258,37387 ,20460,20462,20461 ,0,0,0}, + {37698,38256,37386 ,20468,20460,20459 ,0,0,0}, {36962,38670,37397 ,20464,20463,20505 ,0,0,0}, + {37387,38258,36962 ,20461,20462,20464 ,0,0,0}, {37588,36986,37397 ,20455,20454,20505 ,0,0,0}, + {37397,38670,37588 ,20505,20463,20455 ,0,0,0}, {38648,37396,38671 ,20458,20457,20453 ,0,0,0}, + {37396,36986,38671 ,20457,20454,20453 ,0,0,0}, {38649,36984,37391 ,20447,20449,20456 ,0,0,0}, + {38649,37391,38648 ,20447,20456,20458 ,0,0,0}, {38672,38673,36985 ,20448,20451,20450 ,0,0,0}, + {38672,36985,36984 ,20448,20450,20449 ,0,0,0}, {36599,37709,36600 ,20452,20506,20444 ,0,0,0}, + {38673,37709,36599 ,20451,20506,20452 ,0,0,0}, {36013,36600,37709 ,20445,20444,20506 ,0,0,0}, + {36526,37681,38498 ,20507,20508,20508 ,0,0,0}, {36526,38498,36619 ,20507,20508,20507 ,0,0,0}, + {38167,36497,38359 ,20509,11097,20509 ,0,0,0}, {36497,38167,36494 ,11097,20509,11097 ,0,0,0}, + {36341,37800,36849 ,8396,20510,8396 ,0,0,0}, {37800,36341,37801 ,20510,8396,20510 ,0,0,0}, + {37611,37610,36720 ,20511,20512,20513 ,0,0,0}, {37600,36679,36678 ,20514,20511,20514 ,0,0,0}, + {36679,37611,36720 ,20511,20511,20513 ,0,0,0}, {37600,36678,37605 ,20514,20514,20515 ,0,0,0}, + {37255,37615,37614 ,20516,20517,20516 ,0,0,0}, {37605,36678,36735 ,20515,20514,20515 ,0,0,0}, + {36735,37614,37605 ,20515,20516,20515 ,0,0,0}, {37614,36735,37255 ,20516,20515,20516 ,0,0,0}, + {37615,37255,36738 ,20517,20516,20518 ,0,0,0}, {36679,37600,37611 ,20511,20514,20511 ,0,0,0}, + {36721,36720,37610 ,20519,20513,20512 ,0,0,0}, {36730,36721,37576 ,20520,20519,20519 ,0,0,0}, + {37610,37576,36721 ,20512,20519,20519 ,0,0,0}, {38689,37037,36730 ,20520,20521,20520 ,0,0,0}, + {36730,37576,38689 ,20520,20519,20520 ,0,0,0}, {37037,37570,37030 ,20521,20522,20436 ,0,0,0}, + {37570,37037,38689 ,20522,20521,20520 ,0,0,0}, {37570,38290,37030 ,20522,20436,20436 ,0,0,0}, + {38320,37617,36732 ,20523,20524,20525 ,0,0,0}, {38525,36713,36714 ,20526,20523,20526 ,0,0,0}, + {36713,38320,36732 ,20523,20523,20525 ,0,0,0}, {38525,36714,38524 ,20526,20526,20527 ,0,0,0}, + {36188,36107,38523 ,20528,20060,20528 ,0,0,0}, {38524,36714,36711 ,20527,20526,20527 ,0,0,0}, + {36711,38523,38524 ,20527,20528,20527 ,0,0,0}, {38523,36711,36188 ,20528,20527,20528 ,0,0,0}, + {36107,36188,36108 ,20060,20528,20060 ,0,0,0}, {36713,38525,38320 ,20523,20526,20523 ,0,0,0}, + {37251,36732,37617 ,20529,20525,20524 ,0,0,0}, {37252,37251,37619 ,20530,20529,20529 ,0,0,0}, + {37617,37619,37251 ,20524,20529,20529 ,0,0,0}, {37618,36681,37252 ,20530,20531,20530 ,0,0,0}, + {37252,37619,37618 ,20530,20529,20530 ,0,0,0}, {36681,37607,37200 ,20531,20531,21 ,0,0,0}, + {37607,36681,37618 ,20531,20531,20530 ,0,0,0}, {37607,37595,37200 ,20531,20532,21 ,0,0,0}, + {37764,37766,36596 ,20533,20534,20534 ,0,0,0}, {38511,36595,37350 ,20535,20533,20535 ,0,0,0}, + {36595,37764,36596 ,20533,20533,20534 ,0,0,0}, {38511,37350,38510 ,20535,20535,20536 ,0,0,0}, + {36575,36043,37759 ,20537,19998,20537 ,0,0,0}, {38510,37350,36535 ,20536,20535,20536 ,0,0,0}, + {36535,37759,38510 ,20536,20537,20536 ,0,0,0}, {37759,36535,36575 ,20537,20536,20537 ,0,0,0}, + {36043,36575,36044 ,19998,20537,19998 ,0,0,0}, {36595,38511,37764 ,20533,20535,20533 ,0,0,0}, + {36617,36596,37766 ,20538,20534,20534 ,0,0,0}, {37235,36617,38507 ,20539,20538,20538 ,0,0,0}, + {37766,38507,36617 ,20534,20538,20538 ,0,0,0}, {37770,36618,37235 ,20539,20540,20539 ,0,0,0}, + {37235,38507,37770 ,20539,20538,20539 ,0,0,0}, {36618,37752,36623 ,20540,20540,20541 ,0,0,0}, + {37752,36618,37770 ,20540,20540,20539 ,0,0,0}, {37752,37767,36623 ,20540,20542,20541 ,0,0,0}, + {38015,38487,36905 ,20543,20544,20545 ,0,0,0}, {38016,37216,36311 ,20546,20543,20546 ,0,0,0}, + {37216,38015,36905 ,20543,20543,20545 ,0,0,0}, {38016,36311,38018 ,20546,20546,20547 ,0,0,0}, + {37220,38024,38482 ,20548,20549,20548 ,0,0,0}, {38018,36311,36301 ,20547,20546,20547 ,0,0,0}, + {36301,38482,38018 ,20547,20548,20547 ,0,0,0}, {38482,36301,37220 ,20548,20547,20548 ,0,0,0}, + {38024,37220,36289 ,20549,20548,20550 ,0,0,0}, {37216,38016,38015 ,20543,20546,20543 ,0,0,0}, + {37227,36905,38487 ,20551,20545,20544 ,0,0,0}, {37275,37227,38566 ,20552,20551,20551 ,0,0,0}, + {38487,38566,37227 ,20544,20551,20551 ,0,0,0}, {38565,36903,37275 ,20552,20553,20552 ,0,0,0}, + {37275,38566,38565 ,20552,20551,20552 ,0,0,0}, {36903,38547,37293 ,20553,20553,20367 ,0,0,0}, + {38547,36903,38565 ,20553,20553,20552 ,0,0,0}, {38547,37999,37293 ,20553,20367,20367 ,0,0,0}, + {38490,38020,36294 ,20554,20555,20556 ,0,0,0}, {38017,36900,37280 ,20557,20554,20557 ,0,0,0}, + {36900,38490,36294 ,20554,20554,20556 ,0,0,0}, {38017,37280,38485 ,20557,20557,20558 ,0,0,0}, + {36908,36171,38188 ,20559,20123,20559 ,0,0,0}, {38485,37280,37278 ,20558,20557,20558 ,0,0,0}, + {37278,38188,38485 ,20558,20559,20558 ,0,0,0}, {38188,37278,36908 ,20559,20558,20559 ,0,0,0}, + {36171,36908,36172 ,20123,20559,20123 ,0,0,0}, {36900,38017,38490 ,20554,20557,20554 ,0,0,0}, + {36295,36294,38020 ,20560,20556,20555 ,0,0,0}, {36304,36295,37960 ,20561,20560,20560 ,0,0,0}, + {38020,37960,36295 ,20555,20560,20560 ,0,0,0}, {37959,36308,36304 ,20561,20562,20561 ,0,0,0}, + {36304,37960,37959 ,20561,20560,20561 ,0,0,0}, {36308,38021,36306 ,20562,20562,20563 ,0,0,0}, + {38021,36308,37959 ,20562,20562,20561 ,0,0,0}, {38021,38026,36306 ,20562,20564,20563 ,0,0,0}, + {37754,38276,36592 ,20565,20566,20567 ,0,0,0}, {37758,36620,36608 ,20568,20565,20568 ,0,0,0}, + {36620,37754,36592 ,20565,20565,20567 ,0,0,0}, {37758,36608,37760 ,20568,20568,20569 ,0,0,0}, + {36621,38498,37763 ,20570,20571,20570 ,0,0,0}, {37760,36608,36609 ,20569,20568,20569 ,0,0,0}, + {36609,37763,37760 ,20569,20570,20569 ,0,0,0}, {37763,36609,36621 ,20570,20569,20570 ,0,0,0}, + {38498,36621,36619 ,20571,20570,20572 ,0,0,0}, {36620,37758,37754 ,20565,20568,20565 ,0,0,0}, + {37236,36592,38276 ,20573,20567,20566 ,0,0,0}, {37243,37236,38654 ,20574,20573,20573 ,0,0,0}, + {38276,38654,37236 ,20566,20573,20573 ,0,0,0}, {37743,37349,37243 ,20574,20575,20574 ,0,0,0}, + {37243,38654,37743 ,20574,20573,20574 ,0,0,0}, {37349,38282,36562 ,20575,20575,20504 ,0,0,0}, + {38282,37349,37743 ,20575,20575,20574 ,0,0,0}, {38282,37742,36562 ,20575,20504,20504 ,0,0,0}, + {37918,37922,36926 ,20576,20577,20577 ,0,0,0}, {37912,36928,36932 ,20578,20576,20578 ,0,0,0}, + {36928,37918,36926 ,20576,20576,20577 ,0,0,0}, {37912,36932,38321 ,20578,20578,20579 ,0,0,0}, + {36422,38612,38338 ,20580,20240,20580 ,0,0,0}, {38321,36932,36425 ,20579,20578,20579 ,0,0,0}, + {36425,38338,38321 ,20579,20580,20579 ,0,0,0}, {38338,36425,36422 ,20580,20579,20580 ,0,0,0}, + {38612,36422,37055 ,20240,20580,20240 ,0,0,0}, {36928,37912,37918 ,20576,20578,20576 ,0,0,0}, + {36429,36926,37922 ,20581,20577,20577 ,0,0,0}, {36930,36429,37905 ,20582,20581,20581 ,0,0,0}, + {37922,37905,36429 ,20577,20581,20581 ,0,0,0}, {37923,36460,36930 ,20582,20583,20582 ,0,0,0}, + {36930,37905,37923 ,20582,20581,20582 ,0,0,0}, {36460,38495,36448 ,20583,20583,20584 ,0,0,0}, + {38495,36460,37923 ,20583,20583,20582 ,0,0,0}, {38495,37919,36448 ,20583,324,20584 ,0,0,0}, + {38232,38233,37046 ,20585,20586,20586 ,0,0,0}, {37915,36454,36455 ,20587,20585,20587 ,0,0,0}, + {36454,38232,37046 ,20585,20585,20586 ,0,0,0}, {37915,36455,37916 ,20587,20587,20588 ,0,0,0}, + {36462,38492,38491 ,20589,20590,20589 ,0,0,0}, {37916,36455,36461 ,20588,20587,20588 ,0,0,0}, + {36461,38491,37916 ,20588,20589,20588 ,0,0,0}, {38491,36461,36462 ,20589,20588,20589 ,0,0,0}, + {38492,36462,36449 ,20590,20589,20591 ,0,0,0}, {36454,37915,38232 ,20585,20587,20585 ,0,0,0}, + {37045,37046,38233 ,20592,20586,20586 ,0,0,0}, {36445,37045,38234 ,20593,20592,20592 ,0,0,0}, + {38233,38234,37045 ,20586,20592,20592 ,0,0,0}, {37884,36453,36445 ,20593,20594,20593 ,0,0,0}, + {36445,38234,37884 ,20593,20592,20593 ,0,0,0}, {36453,37883,36447 ,20594,20594,20302 ,0,0,0}, + {37883,36453,37884 ,20594,20594,20593 ,0,0,0}, {37883,37882,36447 ,20594,20302,20302 ,0,0,0}, + {38051,38030,36206 ,20595,20596,20596 ,0,0,0}, {38051,36206,36205 ,20595,20596,20595 ,0,0,0}, + {37947,36205,36757 ,20597,20595,20597 ,0,0,0}, {36757,36758,38029 ,20597,20598,20598 ,0,0,0}, + {38029,37947,36757 ,20598,20597,20597 ,0,0,0}, {38051,36205,37947 ,20595,20595,20597 ,0,0,0}, + {38053,38029,36758 ,20599,20598,20598 ,0,0,0}, {38053,36759,38052 ,20599,20599,20600 ,0,0,0}, + {37139,37948,38052 ,20600,20601,20600 ,0,0,0}, {38053,36758,36759 ,20599,20598,20599 ,0,0,0}, + {37139,36199,37948 ,20600,20602,20601 ,0,0,0}, {37139,38052,36759 ,20600,20600,20599 ,0,0,0}, + {38030,37952,36211 ,20596,20603,20603 ,0,0,0}, {36211,36206,38030 ,20603,20596,20596 ,0,0,0}, + {36217,37952,37950 ,20604,20603,20604 ,0,0,0}, {37952,36217,36211 ,20603,20604,20603 ,0,0,0}, + {37949,36214,37950 ,20605,20605,20604 ,0,0,0}, {36217,37950,36214 ,20604,20604,20605 ,0,0,0}, + {37949,37470,36192 ,20605,20606,20606 ,0,0,0}, {36192,36214,37949 ,20606,20605,20605 ,0,0,0}, + {36193,37470,37469 ,20607,20606,20607 ,0,0,0}, {37470,36193,36192 ,20606,20607,20606 ,0,0,0}, + {36193,37469,36292 ,20607,20607,20608 ,0,0,0}, {36292,37469,37957 ,20608,20607,20609 ,0,0,0}, + {37926,37928,36347 ,20610,2038,2038 ,0,0,0}, {37926,36347,36346 ,20610,2038,20610 ,0,0,0}, + {37809,36346,36344 ,20611,20610,20611 ,0,0,0}, {36344,36343,37814 ,20611,20612,20612 ,0,0,0}, + {37814,37809,36344 ,20612,20611,20611 ,0,0,0}, {37926,36346,37809 ,20610,20610,20611 ,0,0,0}, + {37798,37814,36343 ,20613,20612,20612 ,0,0,0}, {37798,36331,37799 ,20613,20613,20614 ,0,0,0}, + {36348,37815,37799 ,20614,20615,20614 ,0,0,0}, {37798,36343,36331 ,20613,20612,20613 ,0,0,0}, + {36348,36352,37815 ,20614,20616,20615 ,0,0,0}, {36348,37799,36331 ,20614,20614,20613 ,0,0,0}, + {37928,38354,36859 ,2038,20617,20617 ,0,0,0}, {36859,36347,37928 ,20617,2038,2038 ,0,0,0}, + {36816,38354,38355 ,20618,20617,20618 ,0,0,0}, {38354,36816,36859 ,20617,20618,20617 ,0,0,0}, + {38427,36835,38355 ,20619,20619,20618 ,0,0,0}, {36816,38355,36835 ,20618,20618,20619 ,0,0,0}, + {38427,38428,36815 ,20619,20620,20620 ,0,0,0}, {36815,36835,38427 ,20620,20619,20619 ,0,0,0}, + {36466,38428,38429 ,20621,20620,20621 ,0,0,0}, {38428,36466,36815 ,20620,20621,20620 ,0,0,0}, + {36466,38429,36341 ,20621,20621,20622 ,0,0,0}, {36341,38429,37801 ,20622,20621,20623 ,0,0,0}, + {38079,37494,36628 ,20624,20625,20625 ,0,0,0}, {38079,36628,37148 ,20624,20625,20624 ,0,0,0}, + {37774,37148,37126 ,20626,20624,20626 ,0,0,0}, {37126,37117,37772 ,20626,2040,2040 ,0,0,0}, + {37772,37774,37126 ,2040,20626,20626 ,0,0,0}, {38079,37148,37774 ,20624,20624,20626 ,0,0,0}, + {38155,37772,37117 ,20627,2040,2040 ,0,0,0}, {38155,37118,38090 ,20627,20627,20628 ,0,0,0}, + {37119,38167,38090 ,20628,20629,20628 ,0,0,0}, {38155,37117,37118 ,20627,2040,20627 ,0,0,0}, + {37119,36494,38167 ,20628,20629,20629 ,0,0,0}, {37119,38090,37118 ,20628,20628,20627 ,0,0,0}, + {37494,37675,36626 ,20625,20630,20630 ,0,0,0}, {36626,36628,37494 ,20630,20625,20625 ,0,0,0}, + {36515,37675,37673 ,20631,20630,20631 ,0,0,0}, {37675,36515,36626 ,20630,20631,20630 ,0,0,0}, + {37672,36521,37673 ,20632,20632,20631 ,0,0,0}, {36515,37673,36521 ,20631,20631,20632 ,0,0,0}, + {37672,37677,36522 ,20632,20633,20633 ,0,0,0}, {36522,36521,37672 ,20633,20632,20632 ,0,0,0}, + {36525,37677,37678 ,20634,20633,20634 ,0,0,0}, {37677,36525,36522 ,20633,20634,20633 ,0,0,0}, + {36525,37678,36526 ,20634,20634,20635 ,0,0,0}, {36526,37678,37681 ,20635,20634,20636 ,0,0,0}, + {37771,37674,36627 ,20637,20638,20638 ,0,0,0}, {37771,36627,36517 ,20637,20638,20637 ,0,0,0}, + {37671,36517,36516 ,20639,20637,20639 ,0,0,0}, {36516,36523,37676 ,20639,20640,20640 ,0,0,0}, + {37676,37671,36516 ,20640,20639,20639 ,0,0,0}, {37771,36517,37671 ,20637,20637,20639 ,0,0,0}, + {37679,37676,36523 ,20641,20640,20640 ,0,0,0}, {37679,36524,37680 ,20641,20641,20642 ,0,0,0}, + {36527,37750,37680 ,20642,20643,20642 ,0,0,0}, {37679,36523,36524 ,20641,20640,20641 ,0,0,0}, + {36527,36528,37750 ,20642,20644,20643 ,0,0,0}, {36527,37680,36524 ,20642,20642,20641 ,0,0,0}, + {37674,38450,36519 ,20638,20645,20646 ,0,0,0}, {36519,36627,37674 ,20646,20638,20638 ,0,0,0}, + {36473,38450,38383 ,20647,20645,20647 ,0,0,0}, {38450,36473,36519 ,20645,20647,20646 ,0,0,0}, + {38378,36802,38383 ,20648,20648,20647 ,0,0,0}, {36473,38383,36802 ,20647,20647,20648 ,0,0,0}, + {38378,38379,36803 ,20648,20649,20649 ,0,0,0}, {36803,36802,38378 ,20649,20648,20648 ,0,0,0}, + {36800,38379,38381 ,20650,20649,20650 ,0,0,0}, {38379,36800,36803 ,20649,20650,20649 ,0,0,0}, + {36800,38381,36792 ,20650,20650,324 ,0,0,0}, {36792,38381,37661 ,324,20650,20651 ,0,0,0}, + {38103,37492,36742 ,20652,20653,20653 ,0,0,0}, {38103,36742,37090 ,20652,20653,20652 ,0,0,0}, + {37620,37090,37191 ,20654,20652,20654 ,0,0,0}, {37191,37192,38037 ,20654,20655,20655 ,0,0,0}, + {38037,37620,37191 ,20655,20654,20654 ,0,0,0}, {38103,37090,37620 ,20652,20652,20654 ,0,0,0}, + {37629,38037,37192 ,20656,20655,20655 ,0,0,0}, {37629,37092,37625 ,20656,20656,20657 ,0,0,0}, + {36654,37626,37625 ,20657,20658,20657 ,0,0,0}, {37629,37192,37092 ,20656,20655,20656 ,0,0,0}, + {36654,36653,37626 ,20657,20658,20658 ,0,0,0}, {36654,37625,37092 ,20657,20657,20656 ,0,0,0}, + {37492,37491,36673 ,20653,20659,20659 ,0,0,0}, {36673,36742,37492 ,20659,20653,20653 ,0,0,0}, + {36671,37491,37498 ,20660,20659,20660 ,0,0,0}, {37491,36671,36673 ,20659,20660,20659 ,0,0,0}, + {37497,36675,37498 ,20661,20661,20660 ,0,0,0}, {36671,37498,36675 ,20660,20660,20661 ,0,0,0}, + {37497,37503,36179 ,20661,20662,20662 ,0,0,0}, {36179,36675,37497 ,20662,20661,20661 ,0,0,0}, + {36674,37503,37506 ,20663,20662,20663 ,0,0,0}, {37503,36674,36179 ,20662,20663,20662 ,0,0,0}, + {36674,37506,36676 ,20663,20663,324 ,0,0,0}, {36676,37506,37599 ,324,20663,20664 ,0,0,0}, + {38080,37927,36345 ,20665,20666,20666 ,0,0,0}, {38080,36345,36861 ,20665,20666,20665 ,0,0,0}, + {37812,36861,36819 ,20667,20665,20667 ,0,0,0}, {36819,36863,37635 ,20667,20668,20668 ,0,0,0}, + {37635,37812,36819 ,20668,20667,20667 ,0,0,0}, {38080,36861,37812 ,20665,20665,20667 ,0,0,0}, + {37633,37635,36863 ,20669,20668,20668 ,0,0,0}, {37633,36318,37910 ,20669,20669,20670 ,0,0,0}, + {36865,37807,37910 ,20670,20671,20670 ,0,0,0}, {37633,36863,36318 ,20669,20668,20669 ,0,0,0}, + {36865,36337,37807 ,20670,20672,20671 ,0,0,0}, {36865,37910,36318 ,20670,20670,20669 ,0,0,0}, + {37927,37808,36465 ,20666,20673,20673 ,0,0,0}, {36465,36345,37927 ,20673,20666,20666 ,0,0,0}, + {36342,37808,37810 ,20674,20673,20674 ,0,0,0}, {37808,36342,36465 ,20673,20674,20673 ,0,0,0}, + {37813,36332,37810 ,20675,20675,20674 ,0,0,0}, {36342,37810,36332 ,20674,20674,20675 ,0,0,0}, + {37813,37797,36333 ,20675,20676,20676 ,0,0,0}, {36333,36332,37813 ,20676,20675,20675 ,0,0,0}, + {36349,37797,37816 ,20677,20676,20677 ,0,0,0}, {37797,36349,36333 ,20676,20677,20676 ,0,0,0}, + {36349,37816,36443 ,20677,20677,20678 ,0,0,0}, {36443,37816,37817 ,20678,20677,20679 ,0,0,0}, + {37953,37942,36210 ,20680,20681,20681 ,0,0,0}, {37953,36210,36212 ,20680,20681,20680 ,0,0,0}, + {37951,36212,36216 ,20682,20680,20682 ,0,0,0}, {36216,36215,37955 ,20682,20683,20683 ,0,0,0}, + {37955,37951,36216 ,20683,20682,20682 ,0,0,0}, {37953,36212,37951 ,20680,20680,20682 ,0,0,0}, + {37468,37955,36215 ,20684,20683,20683 ,0,0,0}, {37468,36191,37954 ,20684,20684,20685 ,0,0,0}, + {36218,37956,37954 ,20685,20686,20685 ,0,0,0}, {37468,36215,36191 ,20684,20683,20684 ,0,0,0}, + {36218,36293,37956 ,20685,82,20686 ,0,0,0}, {36218,37954,36191 ,20685,20685,20684 ,0,0,0}, + {37942,37943,36209 ,20681,20687,20687 ,0,0,0}, {36209,36210,37942 ,20687,20681,20681 ,0,0,0}, + {36750,37943,38118 ,20688,20687,20688 ,0,0,0}, {37943,36750,36209 ,20687,20688,20687 ,0,0,0}, + {37945,36753,38118 ,20689,20689,20688 ,0,0,0}, {36750,38118,36753 ,20688,20688,20689 ,0,0,0}, + {37945,37944,36834 ,20689,20690,20690 ,0,0,0}, {36834,36753,37945 ,20690,20689,20689 ,0,0,0}, + {36756,37944,38418 ,20691,20690,20691 ,0,0,0}, {37944,36756,36834 ,20690,20691,20690 ,0,0,0}, + {36756,38418,36833 ,20691,20691,20692 ,0,0,0}, {36833,38418,38132 ,20692,20691,20693 ,0,0,0}, + {37493,37621,36745 ,20694,20695,20695 ,0,0,0}, {37493,36745,36672 ,20694,20695,20694 ,0,0,0}, + {37500,36672,36670 ,20696,20694,20696 ,0,0,0}, {36670,36669,37499 ,20696,20697,20697 ,0,0,0}, + {37499,37500,36670 ,20697,20696,20696 ,0,0,0}, {37493,36672,37500 ,20694,20694,20696 ,0,0,0}, + {37501,37499,36669 ,20698,20697,20697 ,0,0,0}, {37501,36178,37502 ,20698,20698,20699 ,0,0,0}, + {36180,37598,37502 ,20699,20700,20699 ,0,0,0}, {37501,36669,36178 ,20698,20697,20698 ,0,0,0}, + {36180,36677,37598 ,20699,21,20700 ,0,0,0}, {36180,37502,36178 ,20699,20699,20698 ,0,0,0}, + {37621,38035,36512 ,20695,20701,20701 ,0,0,0}, {36512,36745,37621 ,20701,20695,20695 ,0,0,0}, + {36665,38035,38034 ,20702,20701,20702 ,0,0,0}, {38035,36665,36512 ,20701,20702,20701 ,0,0,0}, + {38107,36743,38034 ,20703,20703,20702 ,0,0,0}, {36665,38034,36743 ,20702,20702,20703 ,0,0,0}, + {38107,37465,36636 ,20703,20704,20704 ,0,0,0}, {36636,36743,38107 ,20704,20703,20703 ,0,0,0}, + {36667,37465,38109 ,20705,20704,20705 ,0,0,0}, {37465,36667,36636 ,20704,20705,20704 ,0,0,0}, + {36667,38109,36182 ,20705,20705,126 ,0,0,0}, {36182,38109,37488 ,126,20705,20706 ,0,0,0}, + {35960,38003,36287 ,8396,20707,7586 ,0,0,0}, {38191,36232,37993 ,20708,20709,20710 ,0,0,0}, + {36239,36282,38557 ,20711,20712,20713 ,0,0,0}, {36886,38560,36889 ,20714,20715,20716 ,0,0,0}, + {38543,38558,36284 ,4334,20717,20718 ,0,0,0}, {38012,36892,38535 ,20719,20720,20721 ,0,0,0}, + {36291,36290,38008 ,20722,20723,20724 ,0,0,0}, {36899,37223,38534 ,20725,20726,20727 ,0,0,0}, + {36885,38182,37223 ,20728,20729,20726 ,0,0,0}, {36272,37536,37537 ,20730,20731,20732 ,0,0,0}, + {36899,38004,36897 ,20725,20733,20734 ,0,0,0}, {38536,36273,37537 ,20735,20736,20732 ,0,0,0}, + {36272,37537,36273 ,20730,20732,20736 ,0,0,0}, {38536,38211,36274 ,20735,20737,20738 ,0,0,0}, + {36274,36273,38536 ,20738,20736,20735 ,0,0,0}, {37264,38211,37975 ,20739,20737,20740 ,0,0,0}, + {38211,37264,36274 ,20737,20739,20738 ,0,0,0}, {37974,36906,37975 ,20741,20742,20740 ,0,0,0}, + {37264,37975,36906 ,20739,20740,20742 ,0,0,0}, {37974,35979,35980 ,20741,4091,763 ,0,0,0}, + {35980,36906,37974 ,763,20742,20741 ,0,0,0}, {38534,37223,38182 ,20727,20726,20729 ,0,0,0}, + {37536,36897,38004 ,20731,20734,20733 ,0,0,0}, {36897,37536,36272 ,20734,20731,20730 ,0,0,0}, + {38534,38004,36899 ,20727,20733,20725 ,0,0,0}, {38012,38182,36885 ,20719,20729,20728 ,0,0,0}, + {36291,38008,38535 ,20722,20724,20721 ,0,0,0}, {36291,38535,36892 ,20722,20721,20720 ,0,0,0}, + {36885,36892,38012 ,20728,20720,20719 ,0,0,0}, {36290,38009,38008 ,20723,20743,20724 ,0,0,0}, + {38009,36290,36889 ,20743,20723,20716 ,0,0,0}, {38558,38560,36886 ,20717,20715,20714 ,0,0,0}, + {38560,38009,36889 ,20715,20743,20716 ,0,0,0}, {36284,38558,36886 ,20718,20717,20714 ,0,0,0}, + {36283,38191,38543 ,20744,20708,4334 ,0,0,0}, {36283,38543,36284 ,20744,4334,20718 ,0,0,0}, + {36232,36239,37993 ,20709,20711,20710 ,0,0,0}, {36283,36232,38191 ,20744,20709,20708 ,0,0,0}, + {36282,38003,38557 ,20712,20707,20713 ,0,0,0}, {37993,36239,38557 ,20710,20711,20713 ,0,0,0}, + {35960,36287,35958 ,8396,7586,9510 ,0,0,0}, {38003,36282,36287 ,20707,20712,7586 ,0,0,0}, + {35916,38230,36451 ,3370,20745,20746 ,0,0,0}, {37903,37052,38226 ,20747,20748,20749 ,0,0,0}, + {36433,36452,38227 ,20750,20751,20752 ,0,0,0}, {37332,38605,37048 ,20753,20754,20755 ,0,0,0}, + {37835,37836,36427 ,20756,20757,20758 ,0,0,0}, {37848,37050,37897 ,20759,20760,20761 ,0,0,0}, + {37049,36435,37839 ,20762,20763,20764 ,0,0,0}, {36942,37333,38614 ,20765,20766,20767 ,0,0,0}, + {36417,37895,37333 ,20768,20769,20766 ,0,0,0}, {37335,37888,37887 ,20770,20771,20772 ,0,0,0}, + {36942,37892,36940 ,20765,20773,20774 ,0,0,0}, {38615,36356,37887 ,20775,20776,20772 ,0,0,0}, + {37335,37887,36356 ,20770,20772,20776 ,0,0,0}, {38615,37824,36357 ,20775,20777,20778 ,0,0,0}, + {36357,36356,38615 ,20778,20776,20775 ,0,0,0}, {36953,37824,37823 ,20779,20777,20780 ,0,0,0}, + {37824,36953,36357 ,20777,20779,20778 ,0,0,0}, {37860,36912,37823 ,20781,20782,20780 ,0,0,0}, + {36953,37823,36912 ,20779,20780,20782 ,0,0,0}, {37860,35935,35936 ,20781,2614,126 ,0,0,0}, + {35936,36912,37860 ,126,20782,20781 ,0,0,0}, {38614,37333,37895 ,20767,20766,20769 ,0,0,0}, + {37888,36940,37892 ,20771,20774,20773 ,0,0,0}, {36940,37888,37335 ,20774,20771,20770 ,0,0,0}, + {38614,37892,36942 ,20767,20773,20765 ,0,0,0}, {37848,37895,36417 ,20759,20769,20768 ,0,0,0}, + {37049,37839,37897 ,20762,20764,20761 ,0,0,0}, {37049,37897,37050 ,20762,20761,20760 ,0,0,0}, + {36417,37050,37848 ,20768,20760,20759 ,0,0,0}, {36435,37840,37839 ,20763,20783,20764 ,0,0,0}, + {37840,36435,37048 ,20783,20763,20755 ,0,0,0}, {37836,38605,37332 ,20757,20754,20753 ,0,0,0}, + {38605,37840,37048 ,20754,20783,20755 ,0,0,0}, {36427,37836,37332 ,20758,20757,20753 ,0,0,0}, + {36431,37903,37835 ,20784,20747,20756 ,0,0,0}, {36431,37835,36427 ,20784,20756,20758 ,0,0,0}, + {37052,36433,38226 ,20748,20750,20749 ,0,0,0}, {36431,37052,37903 ,20784,20748,20747 ,0,0,0}, + {36452,38230,38227 ,20751,20745,20752 ,0,0,0}, {38226,36433,38227 ,20749,20750,20752 ,0,0,0}, + {35916,36451,35914 ,3370,20746,82 ,0,0,0}, {38230,36452,36451 ,20745,20751,20746 ,0,0,0}, + {35872,37699,37352 ,20785,20786,20787 ,0,0,0}, {37707,37355,37706 ,20788,20789,20790 ,0,0,0}, + {36583,36582,38639 ,20791,20792,20793 ,0,0,0}, {36534,37702,36573 ,20794,20795,7595 ,0,0,0}, + {37710,37701,36533 ,20796,4333,20797 ,0,0,0}, {37716,36578,37719 ,20798,20799,20721 ,0,0,0}, + {36577,36536,37714 ,20800,20801,20802 ,0,0,0}, {37369,37366,38662 ,20803,20804,20805 ,0,0,0}, + {36964,37694,37366 ,20806,20807,20804 ,0,0,0}, {37368,37682,37729 ,20808,20809,20810 ,0,0,0}, + {37369,37726,37367 ,20803,20811,20812 ,0,0,0}, {38664,36601,37729 ,20813,20814,20810 ,0,0,0}, + {37368,37729,36601 ,20808,20810,20814 ,0,0,0}, {38664,38281,36602 ,20813,20815,20816 ,0,0,0}, + {36602,36601,38664 ,20816,20814,20813 ,0,0,0}, {37384,38281,37739 ,20817,20815,20818 ,0,0,0}, + {38281,37384,36602 ,20815,20817,20816 ,0,0,0}, {37740,36603,37739 ,20819,20820,20818 ,0,0,0}, + {37384,37739,36603 ,20817,20818,20820 ,0,0,0}, {37740,35891,35892 ,20819,126,4090 ,0,0,0}, + {35892,36603,37740 ,4090,20820,20819 ,0,0,0}, {38662,37366,37694 ,20805,20804,20807 ,0,0,0}, + {37682,37367,37726 ,20809,20812,20811 ,0,0,0}, {37367,37682,37368 ,20812,20809,20808 ,0,0,0}, + {38662,37726,37369 ,20805,20811,20803 ,0,0,0}, {37716,37694,36964 ,20798,20807,20806 ,0,0,0}, + {36577,37714,37719 ,20800,20802,20721 ,0,0,0}, {36577,37719,36578 ,20800,20721,20799 ,0,0,0}, + {36964,36578,37716 ,20806,20799,20798 ,0,0,0}, {36536,37713,37714 ,20801,20821,20802 ,0,0,0}, + {37713,36536,36573 ,20821,20801,7595 ,0,0,0}, {37701,37702,36534 ,4333,20795,20794 ,0,0,0}, + {37702,37713,36573 ,20795,20821,7595 ,0,0,0}, {36533,37701,36534 ,20797,4333,20794 ,0,0,0}, + {36569,37707,37710 ,20822,20788,20796 ,0,0,0}, {36569,37710,36533 ,20822,20796,20797 ,0,0,0}, + {37355,36583,37706 ,20789,20791,20790 ,0,0,0}, {36569,37355,37707 ,20822,20789,20788 ,0,0,0}, + {36582,37699,38639 ,20792,20786,20793 ,0,0,0}, {37706,36583,38639 ,20790,20791,20793 ,0,0,0}, + {35872,37352,35870 ,20785,20787,878 ,0,0,0}, {37699,36582,37352 ,20786,20792,20787 ,0,0,0}, + {35828,37508,37425 ,2602,20745,20746 ,0,0,0}, {37554,36598,37519 ,20823,20824,20749 ,0,0,0}, + {36185,36187,38705 ,20750,20825,20826 ,0,0,0}, {36688,38709,36691 ,20827,20754,20755 ,0,0,0}, + {38696,38706,36686 ,20828,20829,20830 ,0,0,0}, {37544,36261,37545 ,20831,20832,20833 ,0,0,0}, + {36256,36255,37564 ,20834,20835,20836 ,0,0,0}, {36252,37018,38688 ,20837,20838,20839 ,0,0,0}, + {36996,37522,37018 ,20840,20841,20838 ,0,0,0}, {36245,37542,37606 ,20842,20843,20844 ,0,0,0}, + {36252,37540,36250 ,20837,20845,20846 ,0,0,0}, {38690,36189,37606 ,20847,20848,20844 ,0,0,0}, + {36245,37606,36189 ,20842,20844,20848 ,0,0,0}, {38690,37603,36190 ,20847,20849,20850 ,0,0,0}, + {36190,36189,38690 ,20850,20848,20847 ,0,0,0}, {36719,37603,37604 ,20851,20849,20852 ,0,0,0}, + {37603,36719,36190 ,20849,20851,20850 ,0,0,0}, {38319,36717,37604 ,20853,20854,20852 ,0,0,0}, + {36719,37604,36717 ,20851,20852,20854 ,0,0,0}, {38319,35847,35848 ,20853,3345,126 ,0,0,0}, + {35848,36717,38319 ,126,20854,20853 ,0,0,0}, {38688,37018,37522 ,20839,20838,20841 ,0,0,0}, + {37542,36250,37540 ,20843,20846,20845 ,0,0,0}, {36250,37542,36245 ,20846,20843,20842 ,0,0,0}, + {38688,37540,36252 ,20839,20845,20837 ,0,0,0}, {37544,37522,36996 ,20831,20841,20840 ,0,0,0}, + {36256,37564,37545 ,20834,20836,20833 ,0,0,0}, {36256,37545,36261 ,20834,20833,20832 ,0,0,0}, + {36996,36261,37544 ,20840,20832,20831 ,0,0,0}, {36255,37565,37564 ,20835,20783,20836 ,0,0,0}, + {37565,36255,36691 ,20783,20835,20755 ,0,0,0}, {38706,38709,36688 ,20829,20754,20827 ,0,0,0}, + {38709,37565,36691 ,20754,20783,20755 ,0,0,0}, {36686,38706,36688 ,20830,20829,20827 ,0,0,0}, + {36687,37554,38696 ,20855,20823,20828 ,0,0,0}, {36687,38696,36686 ,20855,20828,20830 ,0,0,0}, + {36598,36185,37519 ,20824,20750,20749 ,0,0,0}, {36687,36598,37554 ,20855,20824,20823 ,0,0,0}, + {36187,37508,38705 ,20825,20745,20826 ,0,0,0}, {37519,36185,38705 ,20749,20750,20826 ,0,0,0}, + {35828,37425,35826 ,2602,20746,82 ,0,0,0}, {37508,36187,37425 ,20745,20825,20746 ,0,0,0}, + {37913,36450,37914 ,20856,20857,18583 ,0,0,0}, {37913,35790,36450 ,20856,18588,20857 ,0,0,0}, + {35790,37913,35789 ,18588,20856,18588 ,0,0,0}, {36456,37914,36450 ,18583,18583,20857 ,0,0,0}, + {35797,38237,36440 ,18609,20858,20858 ,0,0,0}, {38236,37044,38240 ,20859,20859,20860 ,0,0,0}, + {36446,37062,38239 ,20860,20861,20861 ,0,0,0}, {38235,36456,36457 ,20862,18583,20862 ,0,0,0}, + {36457,38236,38235 ,20862,20859,20862 ,0,0,0}, {37914,36456,38235 ,18583,18583,20862 ,0,0,0}, + {36457,37044,38236 ,20862,20859,20859 ,0,0,0}, {36446,38240,37044 ,20860,20860,20859 ,0,0,0}, + {38240,36446,38239 ,20860,20860,20861 ,0,0,0}, {36440,35798,35797 ,20858,18609,18609 ,0,0,0}, + {38237,37062,36440 ,20858,20861,20858 ,0,0,0}, {38239,37062,38237 ,20861,20861,20858 ,0,0,0}, + {37901,35803,36439 ,20863,18594,20864 ,0,0,0}, {35803,35804,36439 ,18594,18594,20864 ,0,0,0}, + {36438,37901,36439 ,18575,20863,20864 ,0,0,0}, {37901,36438,38231 ,20863,18575,18575 ,0,0,0}, + {35783,38601,36933 ,18601,20865,20865 ,0,0,0}, {38225,36434,37908 ,20866,20866,20867 ,0,0,0}, + {36424,36426,37907 ,20867,20868,20868 ,0,0,0}, {38228,36438,36432 ,20869,18575,20869 ,0,0,0}, + {36432,38225,38228 ,20869,20866,20869 ,0,0,0}, {38231,36438,38228 ,18575,18575,20869 ,0,0,0}, + {36432,36434,38225 ,20869,20866,20866 ,0,0,0}, {36424,37908,36434 ,20867,20867,20866 ,0,0,0}, + {37908,36424,37907 ,20867,20867,20868 ,0,0,0}, {36933,35784,35783 ,20865,18601,18601 ,0,0,0}, + {38601,36426,36933 ,20865,20868,20865 ,0,0,0}, {37907,36426,38601 ,20868,20868,20865 ,0,0,0}, + {35761,36770,38046 ,20870,17362,20871 ,0,0,0}, {38043,38044,36772 ,20872,20873,20874 ,0,0,0}, + {37946,37467,36771 ,20875,20876,20877 ,0,0,0}, {37489,36777,38038 ,20878,20879,20880 ,0,0,0}, + {36773,36778,37490 ,20881,20882,20883 ,0,0,0}, {36775,36780,37479 ,20884,20885,20886 ,0,0,0}, + {36775,38042,36776 ,20884,20887,20888 ,0,0,0}, {36779,36194,37482 ,20889,20890,20891 ,0,0,0}, + {37482,37480,36779 ,20891,20892,20889 ,0,0,0}, {37478,36194,36196 ,20893,20890,20894 ,0,0,0}, + {36194,37478,37482 ,20890,20893,20891 ,0,0,0}, {36202,37463,36196 ,20895,20896,20894 ,0,0,0}, + {37478,36196,37463 ,20893,20894,20896 ,0,0,0}, {36202,35775,35776 ,20895,20897,82 ,0,0,0}, + {35776,37463,36202 ,82,20896,20895 ,0,0,0}, {36777,37489,36778 ,20879,20878,20882 ,0,0,0}, + {36780,37480,37479 ,20885,20892,20886 ,0,0,0}, {36779,37480,36780 ,20889,20892,20885 ,0,0,0}, + {36772,38044,36774 ,20874,20873,20898 ,0,0,0}, {36776,38042,38038 ,20888,20887,20880 ,0,0,0}, + {36775,37479,38042 ,20884,20886,20887 ,0,0,0}, {36777,36776,38038 ,20879,20888,20880 ,0,0,0}, + {37490,36778,37489 ,20883,20882,20878 ,0,0,0}, {38043,36772,36773 ,20872,20874,20881 ,0,0,0}, + {36773,37490,38043 ,20881,20883,20872 ,0,0,0}, {37467,36770,36771 ,20876,17362,20877 ,0,0,0}, + {36774,37946,36771 ,20898,20875,20877 ,0,0,0}, {38044,37946,36774 ,20873,20875,20898 ,0,0,0}, + {35761,38046,35762 ,20870,20871,8371 ,0,0,0}, {36770,37467,38046 ,17362,20876,20871 ,0,0,0}, + {35729,36326,38343 ,66,17362,20899 ,0,0,0}, {37669,38139,36328 ,20900,20901,20902 ,0,0,0}, + {38054,38056,36325 ,20875,20903,20877 ,0,0,0}, {38138,36335,38057 ,20904,20905,20906 ,0,0,0}, + {37071,36334,37670 ,20907,20908,20909 ,0,0,0}, {36820,37070,38136 ,20910,20911,20912 ,0,0,0}, + {36820,38342,37069 ,20910,20913,20914 ,0,0,0}, {36823,36821,38133 ,20915,20916,20917 ,0,0,0}, + {38133,38137,36823 ,20917,20918,20915 ,0,0,0}, {38134,36821,36822 ,20919,20916,20920 ,0,0,0}, + {36821,38134,38133 ,20916,20919,20917 ,0,0,0}, {36824,38135,36822 ,20921,20922,20920 ,0,0,0}, + {38134,36822,38135 ,20919,20920,20922 ,0,0,0}, {36824,35743,35744 ,20921,20923,82 ,0,0,0}, + {35744,38135,36824 ,82,20922,20921 ,0,0,0}, {36335,38138,36334 ,20905,20904,20908 ,0,0,0}, + {37070,38137,38136 ,20911,20918,20912 ,0,0,0}, {36823,38137,37070 ,20915,20918,20911 ,0,0,0}, + {36328,38139,36329 ,20902,20901,20924 ,0,0,0}, {37069,38342,38057 ,20914,20913,20906 ,0,0,0}, + {36820,38136,38342 ,20910,20912,20913 ,0,0,0}, {36335,37069,38057 ,20905,20914,20906 ,0,0,0}, + {37670,36334,38138 ,20909,20908,20904 ,0,0,0}, {37669,36328,37071 ,20900,20902,20907 ,0,0,0}, + {37071,37670,37669 ,20907,20909,20900 ,0,0,0}, {38056,36326,36325 ,20903,17362,20877 ,0,0,0}, + {36329,38054,36325 ,20924,20875,20877 ,0,0,0}, {38139,38054,36329 ,20901,20875,20924 ,0,0,0}, + {35729,38343,35730 ,66,20899,126 ,0,0,0}, {36326,38056,38343 ,17362,20903,20899 ,0,0,0}, + {35697,36482,37785 ,66,17362,20899 ,0,0,0}, {37791,37790,36491 ,20900,20925,20926 ,0,0,0}, + {37806,37786,36484 ,20927,20903,20928 ,0,0,0}, {38357,36504,37788 ,20929,20930,20931 ,0,0,0}, + {36493,37081,37793 ,20932,20933,20934 ,0,0,0}, {36500,36489,38347 ,20910,20935,20936 ,0,0,0}, + {36500,38349,36503 ,20910,20937,20938 ,0,0,0}, {36488,36502,38362 ,20939,20940,20941 ,0,0,0}, + {38362,38360,36488 ,20941,20942,20939 ,0,0,0}, {38361,36502,36501 ,20943,20940,20944 ,0,0,0}, + {36502,38361,38362 ,20940,20943,20941 ,0,0,0}, {36498,38364,36501 ,20945,20946,20944 ,0,0,0}, + {38361,36501,38364 ,20943,20944,20946 ,0,0,0}, {36498,35711,35712 ,20945,20923,82 ,0,0,0}, + {35712,38364,36498 ,82,20946,20945 ,0,0,0}, {36504,38357,37081 ,20930,20929,20933 ,0,0,0}, + {36489,38360,38347 ,20935,20942,20936 ,0,0,0}, {36488,38360,36489 ,20939,20942,20935 ,0,0,0}, + {36491,37790,37083 ,20926,20925,20924 ,0,0,0}, {36503,38349,37788 ,20938,20937,20931 ,0,0,0}, + {36500,38347,38349 ,20910,20936,20937 ,0,0,0}, {36504,36503,37788 ,20930,20938,20931 ,0,0,0}, + {37793,37081,38357 ,20934,20933,20929 ,0,0,0}, {37791,36491,36493 ,20900,20926,20932 ,0,0,0}, + {36493,37793,37791 ,20932,20934,20900 ,0,0,0}, {37786,36482,36484 ,20903,17362,20928 ,0,0,0}, + {37083,37806,36484 ,20924,20927,20928 ,0,0,0}, {37790,37806,37083 ,20925,20927,20924 ,0,0,0}, + {35697,37785,35698 ,66,20899,126 ,0,0,0}, {36482,37786,37785 ,17362,20903,20899 ,0,0,0}, + {35665,37098,37654 ,850,17362,20947 ,0,0,0}, {37637,37644,37095 ,20948,20949,20926 ,0,0,0}, + {37650,37649,37096 ,20950,20903,20928 ,0,0,0}, {37658,36657,37640 ,20951,20952,20953 ,0,0,0}, + {36660,36662,37638 ,20954,20955,20956 ,0,0,0}, {36650,36641,37647 ,20957,20958,20959 ,0,0,0}, + {36650,38375,36656 ,20957,20960,20938 ,0,0,0}, {36640,37086,38377 ,20961,20962,20963 ,0,0,0}, + {38377,37645,36640 ,20963,20964,20961 ,0,0,0}, {37651,37086,36649 ,20965,20962,20966 ,0,0,0}, + {37086,37651,38377 ,20962,20965,20963 ,0,0,0}, {36647,37652,36649 ,20967,20968,20966 ,0,0,0}, + {37651,36649,37652 ,20965,20966,20968 ,0,0,0}, {36647,35679,35680 ,20967,20969,82 ,0,0,0}, + {35680,37652,36647 ,82,20968,20967 ,0,0,0}, {36657,37658,36662 ,20952,20951,20955 ,0,0,0}, + {36641,37645,37647 ,20958,20964,20959 ,0,0,0}, {36640,37645,36641 ,20961,20964,20958 ,0,0,0}, + {37095,37644,37097 ,20926,20949,20924 ,0,0,0}, {36656,38375,37640 ,20938,20960,20953 ,0,0,0}, + {36650,37647,38375 ,20957,20959,20960 ,0,0,0}, {36657,36656,37640 ,20952,20938,20953 ,0,0,0}, + {37638,36662,37658 ,20956,20955,20951 ,0,0,0}, {37637,37095,36660 ,20948,20926,20954 ,0,0,0}, + {36660,37638,37637 ,20954,20956,20948 ,0,0,0}, {37649,37098,37096 ,20903,17362,20928 ,0,0,0}, + {37097,37650,37096 ,20924,20950,20928 ,0,0,0}, {37644,37650,37097 ,20949,20950,20924 ,0,0,0}, + {35665,37654,35666 ,850,20947,126 ,0,0,0}, {37098,37649,37654 ,17362,20903,20947 ,0,0,0}, + {35635,36799,38380 ,8371,17362,20947 ,0,0,0}, {38389,38387,36794 ,20872,20970,20926 ,0,0,0}, + {38386,38385,36798 ,20971,20972,20928 ,0,0,0}, {37659,37113,37660 ,20951,20973,20953 ,0,0,0}, + {36793,37115,38388 ,20932,20955,20934 ,0,0,0}, {37112,37100,38391 ,20884,20974,20975 ,0,0,0}, + {37112,38390,37114 ,20884,20976,20977 ,0,0,0}, {37099,37111,38392 ,20978,20979,20980 ,0,0,0}, + {38392,38393,37099 ,20980,20981,20978 ,0,0,0}, {38394,37111,37108 ,20982,20979,20983 ,0,0,0}, + {37111,38394,38392 ,20979,20982,20980 ,0,0,0}, {37088,38097,37108 ,20984,20985,20983 ,0,0,0}, + {38394,37108,38097 ,20982,20983,20985 ,0,0,0}, {37088,35648,33525 ,20984,20897,82 ,0,0,0}, + {33525,38097,37088 ,82,20985,20984 ,0,0,0}, {37113,37659,37115 ,20973,20951,20955 ,0,0,0}, + {37100,38393,38391 ,20974,20981,20975 ,0,0,0}, {37099,38393,37100 ,20978,20981,20974 ,0,0,0}, + {36794,38387,37116 ,20926,20970,20986 ,0,0,0}, {37114,38390,37660 ,20977,20976,20953 ,0,0,0}, + {37112,38391,38390 ,20884,20975,20976 ,0,0,0}, {37113,37114,37660 ,20973,20977,20953 ,0,0,0}, + {38388,37115,37659 ,20934,20955,20951 ,0,0,0}, {38389,36794,36793 ,20872,20926,20932 ,0,0,0}, + {36793,38388,38389 ,20932,20934,20872 ,0,0,0}, {38385,36799,36798 ,20972,17362,20928 ,0,0,0}, + {37116,38386,36798 ,20986,20971,20928 ,0,0,0}, {38387,38386,37116 ,20970,20971,20986 ,0,0,0}, + {35635,38380,33508 ,8371,20947,126 ,0,0,0}, {36799,38385,38380 ,17362,20972,20947 ,0,0,0}, + {35605,36467,38353 ,18751,17362,20871 ,0,0,0}, {38398,38397,37137 ,20872,20970,20926 ,0,0,0}, + {38408,38407,37138 ,20927,20876,20928 ,0,0,0}, {38411,36496,38410 ,20987,20988,20989 ,0,0,0}, + {37135,37134,38409 ,20932,20990,20991 ,0,0,0}, {37132,37133,38168 ,20992,20993,20994 ,0,0,0}, + {37132,38412,36495 ,20992,20995,20996 ,0,0,0}, {37131,37130,38413 ,20997,20998,20999 ,0,0,0}, + {38413,38166,37131 ,20999,20981,20997 ,0,0,0}, {38091,37130,37129 ,21000,20998,21001 ,0,0,0}, + {37130,38091,38413 ,20998,21000,20999 ,0,0,0}, {37120,38092,37129 ,21002,21003,21001 ,0,0,0}, + {38091,37129,38092 ,21000,21001,21003 ,0,0,0}, {37120,35618,32893 ,21002,21004,82 ,0,0,0}, + {32893,38092,37120 ,82,21003,21002 ,0,0,0}, {36496,38411,37134 ,20988,20987,20990 ,0,0,0}, + {37133,38166,38168 ,20993,20981,20994 ,0,0,0}, {37131,38166,37133 ,20997,20981,20993 ,0,0,0}, + {37137,38397,37136 ,20926,20970,20986 ,0,0,0}, {36495,38412,38410 ,20996,20995,20989 ,0,0,0}, + {37132,38168,38412 ,20992,20994,20995 ,0,0,0}, {36496,36495,38410 ,20988,20996,20989 ,0,0,0}, + {38409,37134,38411 ,20991,20990,20987 ,0,0,0}, {38398,37137,37135 ,20872,20926,20932 ,0,0,0}, + {37135,38409,38398 ,20932,20991,20872 ,0,0,0}, {38407,36467,37138 ,20876,17362,20928 ,0,0,0}, + {37136,38408,37138 ,20986,20927,20928 ,0,0,0}, {38397,38408,37136 ,20970,20927,20986 ,0,0,0}, + {35605,38353,32876 ,18751,20871,126 ,0,0,0}, {36467,38407,38353 ,17362,20876,20871 ,0,0,0}, + {35575,36760,38031 ,8371,17362,20947 ,0,0,0}, {37932,37931,36761 ,20872,21005,20902 ,0,0,0}, + {38033,38032,36203 ,21006,20972,20877 ,0,0,0}, {38414,36762,38416 ,21007,21008,21009 ,0,0,0}, + {36765,36764,38415 ,20907,20882,20909 ,0,0,0}, {36768,36767,38417 ,20884,21010,21011 ,0,0,0}, + {36768,38049,36763 ,20884,21012,21013 ,0,0,0}, {37065,36766,38048 ,21014,21015,21016 ,0,0,0}, + {38048,38341,37065 ,21016,21017,21014 ,0,0,0}, {38047,36766,36769 ,21018,21015,21019 ,0,0,0}, + {36766,38047,38048 ,21015,21018,21016 ,0,0,0}, {37064,38045,36769 ,21020,21021,21019 ,0,0,0}, + {38047,36769,38045 ,21018,21019,21021 ,0,0,0}, {37064,35588,33209 ,21020,20897,82 ,0,0,0}, + {33209,38045,37064 ,82,21021,21020 ,0,0,0}, {36762,38414,36764 ,21008,21007,20882 ,0,0,0}, + {36767,38341,38417 ,21010,21017,21011 ,0,0,0}, {37065,38341,36767 ,21014,21017,21010 ,0,0,0}, + {36761,37931,36204 ,20902,21005,20986 ,0,0,0}, {36763,38049,38416 ,21013,21012,21009 ,0,0,0}, + {36768,38417,38049 ,20884,21011,21012 ,0,0,0}, {36762,36763,38416 ,21008,21013,21009 ,0,0,0}, + {38415,36764,38414 ,20909,20882,21007 ,0,0,0}, {37932,36761,36765 ,20872,20902,20907 ,0,0,0}, + {36765,38415,37932 ,20907,20909,20872 ,0,0,0}, {38032,36760,36203 ,20972,17362,20877 ,0,0,0}, + {36204,38033,36203 ,20986,21006,20877 ,0,0,0}, {37931,38033,36204 ,21005,21006,20986 ,0,0,0}, + {35575,38031,33192 ,8371,20947,126 ,0,0,0}, {36760,38032,38031 ,17362,20972,20947 ,0,0,0}, + {35545,36826,38117 ,18751,17362,20871 ,0,0,0}, {38129,38131,36755 ,20872,21005,20902 ,0,0,0}, + {38128,38127,36828 ,20875,20876,20877 ,0,0,0}, {38124,36829,38123 ,21022,21023,21024 ,0,0,0}, + {37142,36830,38130 ,20907,21025,21026 ,0,0,0}, {37141,37140,38126 ,20992,20885,21027 ,0,0,0}, + {37141,38125,36754 ,20992,21028,21029 ,0,0,0}, {36314,36832,38119 ,21030,21031,21032 ,0,0,0}, + {38119,38122,36314 ,21032,21017,21030 ,0,0,0}, {38120,36832,36831 ,21033,21031,21034 ,0,0,0}, + {36832,38120,38119 ,21031,21033,21032 ,0,0,0}, {36275,38121,36831 ,21035,21036,21034 ,0,0,0}, + {38120,36831,38121 ,21033,21034,21036 ,0,0,0}, {36275,35558,33841 ,21035,21004,82 ,0,0,0}, + {33841,38121,36275 ,82,21036,21035 ,0,0,0}, {36829,38124,36830 ,21023,21022,21025 ,0,0,0}, + {37140,38122,38126 ,20885,21017,21027 ,0,0,0}, {36314,38122,37140 ,21030,21017,20885 ,0,0,0}, + {36755,38131,36827 ,20902,21005,20986 ,0,0,0}, {36754,38125,38123 ,21029,21028,21024 ,0,0,0}, + {37141,38126,38125 ,20992,21027,21028 ,0,0,0}, {36829,36754,38123 ,21023,21029,21024 ,0,0,0}, + {38130,36830,38124 ,21026,21025,21022 ,0,0,0}, {38129,36755,37142 ,20872,20902,20907 ,0,0,0}, + {37142,38130,38129 ,20907,21026,20872 ,0,0,0}, {38127,36826,36828 ,20876,17362,20877 ,0,0,0}, + {36827,38128,36828 ,20986,20875,20877 ,0,0,0}, {38131,38128,36827 ,21005,20875,20986 ,0,0,0}, + {35545,38117,33824 ,18751,20871,126 ,0,0,0}, {36826,38127,38117 ,17362,20876,20871 ,0,0,0}, + {35482,38444,37153 ,21037,21038,21039 ,0,0,0}, {38443,37155,38441 ,21040,21041,21042 ,0,0,0}, + {37154,37152,38164 ,21043,21044,21045 ,0,0,0}, {37165,38158,37198 ,21046,21047,21048 ,0,0,0}, + {37160,38439,37161 ,21049,21050,21051 ,0,0,0}, {37495,37170,38435 ,21052,21053,21054 ,0,0,0}, + {38437,37167,37630 ,21055,21056,21057 ,0,0,0}, {37128,37775,37125 ,21058,21059,21060 ,0,0,0}, + {37174,38078,37149 ,21061,21062,21063 ,0,0,0}, {38382,36796,37776 ,21064,21065,21066 ,0,0,0}, + {36797,37145,37777 ,21067,21068,21069 ,0,0,0}, {36851,37781,36850 ,21070,21071,21072 ,0,0,0}, + {37666,37667,37143 ,21073,21074,21075 ,0,0,0}, {38094,36852,36856 ,21076,21077,21078 ,0,0,0}, + {38420,36854,38171 ,21079,21080,21081 ,0,0,0}, {37079,37078,38144 ,21082,21083,21084 ,0,0,0}, + {36853,38093,38165 ,21085,21086,21087 ,0,0,0}, {36468,38401,38352 ,21088,21089,21090 ,0,0,0}, + {38143,38401,37080 ,21091,21089,21092 ,0,0,0}, {36470,38406,36471 ,21093,21094,21095 ,0,0,0}, + {38432,36470,37175 ,21096,21093,21097 ,0,0,0}, {37176,38404,37177 ,21098,21099,21100 ,0,0,0}, + {38405,37176,36471 ,21101,21098,21095 ,0,0,0}, {38746,38403,37179 ,21102,21103,21104 ,0,0,0}, + {38433,37178,37177 ,21105,21106,21100 ,0,0,0}, {37074,38403,38402 ,21107,21103,21108 ,0,0,0}, + {38403,37074,37179 ,21103,21107,21104 ,0,0,0}, {38395,37075,38402 ,21109,21110,21108 ,0,0,0}, + {37074,38402,37075 ,21107,21108,21110 ,0,0,0}, {38395,38396,37076 ,21109,21111,21112 ,0,0,0}, + {37076,37075,38395 ,21112,21110,21109 ,0,0,0}, {37077,38396,38431 ,21113,21111,21114 ,0,0,0}, + {38396,37077,37076 ,21111,21113,21112 ,0,0,0}, {38430,37180,38431 ,21115,21116,21114 ,0,0,0}, + {37077,38431,37180 ,21113,21114,21116 ,0,0,0}, {38430,38345,36848 ,21115,21117,21118 ,0,0,0}, + {36848,37180,38430 ,21118,21116,21115 ,0,0,0}, {37181,38345,38346 ,21119,21117,21120 ,0,0,0}, + {38345,37181,36848 ,21117,21119,21118 ,0,0,0}, {38351,37182,38346 ,21121,21122,21120 ,0,0,0}, + {37181,38346,37182 ,21119,21120,21122 ,0,0,0}, {38351,38350,37184 ,21121,21123,21124 ,0,0,0}, + {37184,37182,38351 ,21124,21122,21121 ,0,0,0}, {37183,38350,37805 ,21125,21123,21126 ,0,0,0}, + {38350,37183,37184 ,21123,21125,21124 ,0,0,0}, {37804,37185,37805 ,21127,21128,21126 ,0,0,0}, + {37183,37805,37185 ,21125,21126,21128 ,0,0,0}, {37804,35527,35528 ,21127,21129,21129 ,0,0,0}, + {35528,37185,37804 ,21129,21128,21127 ,0,0,0}, {37179,37178,38746 ,21104,21106,21102 ,0,0,0}, + {38433,38746,37178 ,21105,21102,21106 ,0,0,0}, {38404,38433,37177 ,21099,21105,21100 ,0,0,0}, + {38404,37176,38405 ,21099,21098,21101 ,0,0,0}, {38432,38406,36470 ,21096,21094,21093 ,0,0,0}, + {38406,38405,36471 ,21094,21101,21095 ,0,0,0}, {36468,38352,37175 ,21088,21090,21097 ,0,0,0}, + {38432,37175,38352 ,21096,21097,21090 ,0,0,0}, {37079,38143,37080 ,21082,21091,21092 ,0,0,0}, + {37080,38401,36468 ,21092,21089,21088 ,0,0,0}, {37079,38144,38143 ,21082,21084,21091 ,0,0,0}, + {37078,36853,38165 ,21083,21085,21087 ,0,0,0}, {37078,38165,38144 ,21083,21087,21084 ,0,0,0}, + {38093,36852,38094 ,21086,21077,21076 ,0,0,0}, {36853,36852,38093 ,21085,21077,21086 ,0,0,0}, + {36854,38420,36856 ,21080,21079,21078 ,0,0,0}, {38094,36856,38420 ,21076,21078,21079 ,0,0,0}, + {37781,38171,36850 ,21071,21081,21072 ,0,0,0}, {36854,36850,38171 ,21080,21072,21081 ,0,0,0}, + {37781,36851,37667 ,21071,21070,21074 ,0,0,0}, {37143,37667,36851 ,21075,21074,21070 ,0,0,0}, + {36796,38382,36836 ,21065,21064,21130 ,0,0,0}, {36836,38382,37666 ,21130,21064,21073 ,0,0,0}, + {36836,37666,37143 ,21130,21073,21075 ,0,0,0}, {36797,37776,36796 ,21067,21066,21065 ,0,0,0}, + {37145,37773,37777 ,21068,21131,21069 ,0,0,0}, {37776,36797,37777 ,21066,21067,21069 ,0,0,0}, + {37775,37773,37125 ,21059,21131,21060 ,0,0,0}, {37773,37145,37125 ,21131,21068,21060 ,0,0,0}, + {37149,38077,37128 ,21063,21132,21058 ,0,0,0}, {38077,37775,37128 ,21132,21059,21058 ,0,0,0}, + {37495,38078,37174 ,21052,21062,21061 ,0,0,0}, {37149,38078,38077 ,21063,21062,21132 ,0,0,0}, + {38159,37161,38439 ,21133,21051,21050 ,0,0,0}, {37197,38435,37170 ,21134,21054,21053 ,0,0,0}, + {37174,37170,37495 ,21061,21053,21052 ,0,0,0}, {38437,37197,37167 ,21055,21134,21056 ,0,0,0}, + {38435,37197,38437 ,21054,21134,21055 ,0,0,0}, {38158,37630,37198 ,21047,21057,21048 ,0,0,0}, + {37630,37167,37198 ,21057,21056,21048 ,0,0,0}, {37161,38159,37165 ,21051,21133,21046 ,0,0,0}, + {38159,38158,37165 ,21133,21047,21046 ,0,0,0}, {38443,38439,37160 ,21040,21050,21049 ,0,0,0}, + {37154,38164,38441 ,21043,21045,21042 ,0,0,0}, {37154,38441,37155 ,21043,21042,21041 ,0,0,0}, + {37160,37155,38443 ,21049,21041,21040 ,0,0,0}, {37152,38444,38164 ,21044,21038,21045 ,0,0,0}, + {35482,37153,35481 ,21037,21039,878 ,0,0,0}, {38444,37152,37153 ,21038,21044,21039 ,0,0,0}, + {35382,38115,36812 ,21135,21136,21039 ,0,0,0}, {38060,36811,38061 ,21137,21041,21042 ,0,0,0}, + {36339,36813,38062 ,21138,21139,21045 ,0,0,0}, {36175,38064,36480 ,21140,21141,21142 ,0,0,0}, + {36810,37778,36808 ,21143,21144,21145 ,0,0,0}, {38069,36806,38177 ,21146,21147,21148 ,0,0,0}, + {38070,36478,38066 ,21149,21150,21151 ,0,0,0}, {36805,38399,37147 ,21152,21059,21153 ,0,0,0}, + {36839,38087,36840 ,21154,21155,21156 ,0,0,0}, {38089,36790,38088 ,21157,21158,21159 ,0,0,0}, + {36795,36842,38160 ,21160,21161,21162 ,0,0,0}, {36843,38084,36801 ,21163,21164,21165 ,0,0,0}, + {38161,38085,37146 ,21166,21167,21168 ,0,0,0}, {38426,36847,36845 ,21169,21170,21171 ,0,0,0}, + {38156,36844,38425 ,21172,21173,21174 ,0,0,0}, {36507,37144,38150 ,21175,21176,21177 ,0,0,0}, + {37124,38153,38154 ,21178,21179,21180 ,0,0,0}, {37123,38152,38083 ,21181,21182,21183 ,0,0,0}, + {38151,38152,36508 ,21184,21182,21185 ,0,0,0}, {36479,37782,37121 ,21186,21187,21188 ,0,0,0}, + {38145,36479,37122 ,21189,21186,21190 ,0,0,0}, {36855,38147,36857 ,21191,21192,21193 ,0,0,0}, + {37783,36855,37121 ,21194,21191,21188 ,0,0,0}, {38142,38082,36860 ,21195,21196,21197 ,0,0,0}, + {38146,36858,36857 ,21198,21199,21193 ,0,0,0}, {36817,38082,38081 ,21200,21196,21201 ,0,0,0}, + {38082,36817,36860 ,21196,21200,21197 ,0,0,0}, {37929,36818,38081 ,21202,21203,21201 ,0,0,0}, + {36817,38081,36818 ,21200,21201,21203 ,0,0,0}, {37929,37811,36862 ,21202,21204,21205 ,0,0,0}, + {36862,36818,37929 ,21205,21203,21202 ,0,0,0}, {36319,37811,37634 ,21206,21204,21207 ,0,0,0}, + {37811,36319,36862 ,21204,21206,21205 ,0,0,0}, {38141,36320,37634 ,21208,21209,21207 ,0,0,0}, + {36319,37634,36320 ,21206,21207,21209 ,0,0,0}, {38141,37909,36864 ,21208,21210,21211 ,0,0,0}, + {36864,36320,38141 ,21211,21209,21208 ,0,0,0}, {36866,37909,37911 ,21212,21210,21213 ,0,0,0}, + {37909,36866,36864 ,21210,21212,21211 ,0,0,0}, {38140,36867,37911 ,21214,21215,21213 ,0,0,0}, + {36866,37911,36867 ,21212,21213,21215 ,0,0,0}, {38140,38073,36869 ,21214,21216,21217 ,0,0,0}, + {36869,36867,38140 ,21217,21215,21214 ,0,0,0}, {36868,38073,38074 ,21218,21216,21219 ,0,0,0}, + {38073,36868,36869 ,21216,21218,21217 ,0,0,0}, {37930,36870,38074 ,21220,21221,21219 ,0,0,0}, + {36868,38074,36870 ,21218,21219,21221 ,0,0,0}, {37930,35427,35428 ,21220,21129,21129 ,0,0,0}, + {35428,36870,37930 ,21129,21221,21220 ,0,0,0}, {36860,36858,38142 ,21197,21199,21195 ,0,0,0}, + {38146,38142,36858 ,21198,21195,21199 ,0,0,0}, {38147,38146,36857 ,21192,21198,21193 ,0,0,0}, + {38147,36855,37783 ,21192,21191,21194 ,0,0,0}, {38145,37782,36479 ,21189,21187,21186 ,0,0,0}, + {37782,37783,37121 ,21187,21194,21188 ,0,0,0}, {37123,38083,37122 ,21181,21183,21190 ,0,0,0}, + {38145,37122,38083 ,21189,21190,21183 ,0,0,0}, {36507,38151,36508 ,21175,21184,21185 ,0,0,0}, + {36508,38152,37123 ,21185,21182,21181 ,0,0,0}, {36507,38150,38151 ,21175,21177,21184 ,0,0,0}, + {37144,37124,38154 ,21176,21178,21180 ,0,0,0}, {37144,38154,38150 ,21176,21180,21177 ,0,0,0}, + {38153,36847,38426 ,21179,21170,21169 ,0,0,0}, {37124,36847,38153 ,21178,21170,21179 ,0,0,0}, + {36844,38156,36845 ,21173,21172,21171 ,0,0,0}, {38426,36845,38156 ,21169,21171,21172 ,0,0,0}, + {38084,38425,36801 ,21164,21174,21165 ,0,0,0}, {36844,36801,38425 ,21173,21165,21174 ,0,0,0}, + {38084,36843,38085 ,21164,21163,21167 ,0,0,0}, {37146,38085,36843 ,21168,21167,21163 ,0,0,0}, + {36790,38089,36804 ,21158,21157,21222 ,0,0,0}, {36804,38089,38161 ,21222,21157,21166 ,0,0,0}, + {36804,38161,37146 ,21222,21166,21168 ,0,0,0}, {36795,38088,36790 ,21160,21159,21158 ,0,0,0}, + {36842,38356,38160 ,21161,21223,21162 ,0,0,0}, {38088,36795,38160 ,21159,21160,21162 ,0,0,0}, + {38399,38356,37147 ,21059,21223,21153 ,0,0,0}, {38356,36842,37147 ,21223,21161,21153 ,0,0,0}, + {36840,38400,36805 ,21156,21224,21152 ,0,0,0}, {38400,38399,36805 ,21224,21059,21152 ,0,0,0}, + {38069,38087,36839 ,21146,21155,21154 ,0,0,0}, {36840,38087,38400 ,21156,21155,21224 ,0,0,0}, + {37780,36808,37778 ,21225,21145,21144 ,0,0,0}, {36476,38177,36806 ,21226,21148,21147 ,0,0,0}, + {36839,36806,38069 ,21154,21147,21146 ,0,0,0}, {38070,36476,36478 ,21149,21226,21150 ,0,0,0}, + {38177,36476,38070 ,21148,21226,21149 ,0,0,0}, {38064,38066,36480 ,21141,21151,21142 ,0,0,0}, + {38066,36478,36480 ,21151,21150,21142 ,0,0,0}, {36808,37780,36175 ,21145,21225,21140 ,0,0,0}, + {37780,38064,36175 ,21225,21141,21140 ,0,0,0}, {38060,37778,36810 ,21137,21144,21143 ,0,0,0}, + {36339,38062,38061 ,21138,21045,21042 ,0,0,0}, {36339,38061,36811 ,21138,21042,21041 ,0,0,0}, + {36810,36811,38060 ,21143,21041,21137 ,0,0,0}, {36813,38115,38062 ,21139,21136,21045 ,0,0,0}, + {35382,36812,35381 ,21135,21039,19477 ,0,0,0}, {38115,36813,36812 ,21136,21139,21039 ,0,0,0}, + {35282,38462,37087 ,18038,21227,21228 ,0,0,0}, {38459,37084,38461 ,21137,21229,21230 ,0,0,0}, + {36659,36658,38460 ,21231,21044,21045 ,0,0,0}, {37194,38445,37195 ,21046,21232,21233 ,0,0,0}, + {37085,38458,37193 ,21234,21235,21145 ,0,0,0}, {38371,37103,38367 ,21146,21236,21237 ,0,0,0}, + {38368,36791,38457 ,21238,21239,21240 ,0,0,0}, {37105,38369,37106 ,21241,21242,21243 ,0,0,0}, + {37102,38370,37104 ,21244,21245,21246 ,0,0,0}, {38453,37110,38454 ,21247,21248,21249 ,0,0,0}, + {37109,37107,37622 ,21250,21251,21252 ,0,0,0}, {37186,38373,37187 ,21253,21254,21255 ,0,0,0}, + {38098,38374,37091 ,21256,21257,21258 ,0,0,0}, {38099,37157,37158 ,21259,21260,21261 ,0,0,0}, + {38365,36846,38372 ,21262,21263,21264 ,0,0,0}, {36629,37166,37628 ,21265,21266,21267 ,0,0,0}, + {37159,38100,38101 ,21268,21269,21270 ,0,0,0}, {36630,37623,37624 ,21271,21272,21273 ,0,0,0}, + {37627,37623,36509 ,21274,21272,21275 ,0,0,0}, {36511,38095,37173 ,21276,21277,21278 ,0,0,0}, + {38096,36511,36510 ,21279,21276,21280 ,0,0,0}, {36474,38384,36472 ,21281,21282,21283 ,0,0,0}, + {38448,36474,37173 ,21284,21281,21278 ,0,0,0}, {38451,38452,36518 ,21285,21286,21287 ,0,0,0}, + {38449,36520,36472 ,21288,21289,21283 ,0,0,0}, {37171,38452,37496 ,21290,21286,21291 ,0,0,0}, + {38452,37171,36518 ,21286,21290,21287 ,0,0,0}, {38434,37172,37496 ,21292,21293,21291 ,0,0,0}, + {37171,37496,37172 ,21290,21291,21293 ,0,0,0}, {38434,38436,37168 ,21292,21294,21295 ,0,0,0}, + {37168,37172,38434 ,21295,21293,21292 ,0,0,0}, {37169,38436,37632 ,21296,21294,21297 ,0,0,0}, + {38436,37169,37168 ,21294,21296,21295 ,0,0,0}, {37631,37163,37632 ,21298,21299,21297 ,0,0,0}, + {37169,37632,37163 ,21296,21297,21299 ,0,0,0}, {37631,38157,37164 ,21298,21300,21301 ,0,0,0}, + {37164,37163,37631 ,21301,21299,21298 ,0,0,0}, {37162,38157,38438 ,21302,21300,21303 ,0,0,0}, + {38157,37162,37164 ,21300,21302,21301 ,0,0,0}, {38440,37199,38438 ,21304,21305,21303 ,0,0,0}, + {37162,38438,37199 ,21302,21303,21305 ,0,0,0}, {38440,38442,37156 ,21304,21306,21307 ,0,0,0}, + {37156,37199,38440 ,21307,21305,21304 ,0,0,0}, {37150,38442,38163 ,21308,21306,21309 ,0,0,0}, + {38442,37150,37156 ,21306,21308,21307 ,0,0,0}, {38162,37151,38163 ,21310,21311,21309 ,0,0,0}, + {37150,38163,37151 ,21308,21309,21311 ,0,0,0}, {38162,35327,35328 ,21310,21312,126 ,0,0,0}, + {35328,37151,38162 ,126,21311,21310 ,0,0,0}, {36518,36520,38451 ,21287,21289,21285 ,0,0,0}, + {38449,38451,36520 ,21288,21285,21289 ,0,0,0}, {38384,38449,36472 ,21282,21288,21283 ,0,0,0}, + {38384,36474,38448 ,21282,21281,21284 ,0,0,0}, {38096,38095,36511 ,21279,21277,21276 ,0,0,0}, + {38095,38448,37173 ,21277,21284,21278 ,0,0,0}, {36630,37624,36510 ,21271,21273,21280 ,0,0,0}, + {38096,36510,37624 ,21279,21280,21273 ,0,0,0}, {36629,37627,36509 ,21265,21274,21275 ,0,0,0}, + {36509,37623,36630 ,21275,21272,21271 ,0,0,0}, {36629,37628,37627 ,21265,21267,21274 ,0,0,0}, + {37166,37159,38101 ,21266,21268,21270 ,0,0,0}, {37166,38101,37628 ,21266,21270,21267 ,0,0,0}, + {38100,37157,38099 ,21269,21260,21259 ,0,0,0}, {37159,37157,38100 ,21268,21260,21269 ,0,0,0}, + {36846,38365,37158 ,21263,21262,21261 ,0,0,0}, {38099,37158,38365 ,21259,21261,21262 ,0,0,0}, + {38373,38372,37187 ,21254,21264,21255 ,0,0,0}, {36846,37187,38372 ,21263,21255,21264 ,0,0,0}, + {38373,37186,38374 ,21254,21253,21257 ,0,0,0}, {37091,38374,37186 ,21258,21257,21253 ,0,0,0}, + {37110,38453,37089 ,21248,21247,21313 ,0,0,0}, {37089,38453,38098 ,21313,21247,21256 ,0,0,0}, + {37089,38098,37091 ,21313,21256,21258 ,0,0,0}, {37109,38454,37110 ,21250,21249,21248 ,0,0,0}, + {37107,38455,37622 ,21251,21314,21252 ,0,0,0}, {38454,37109,37622 ,21249,21250,21252 ,0,0,0}, + {38369,38455,37106 ,21242,21314,21243 ,0,0,0}, {38455,37107,37106 ,21314,21251,21243 ,0,0,0}, + {37104,38456,37105 ,21246,21315,21241 ,0,0,0}, {38456,38369,37105 ,21315,21242,21241 ,0,0,0}, + {38371,38370,37102 ,21146,21245,21244 ,0,0,0}, {37104,38370,38456 ,21246,21245,21315 ,0,0,0}, + {38446,37193,38458 ,21316,21145,21235 ,0,0,0}, {37196,38367,37103 ,21317,21237,21236 ,0,0,0}, + {37102,37103,38371 ,21244,21236,21146 ,0,0,0}, {38368,37196,36791 ,21238,21317,21239 ,0,0,0}, + {38367,37196,38368 ,21237,21317,21238 ,0,0,0}, {38445,38457,37195 ,21232,21240,21233 ,0,0,0}, + {38457,36791,37195 ,21240,21239,21233 ,0,0,0}, {37193,38446,37194 ,21145,21316,21046 ,0,0,0}, + {38446,38445,37194 ,21316,21232,21046 ,0,0,0}, {38459,38458,37085 ,21137,21235,21234 ,0,0,0}, + {36659,38460,38461 ,21231,21045,21230 ,0,0,0}, {36659,38461,37084 ,21231,21230,21229 ,0,0,0}, + {37085,37084,38459 ,21234,21229,21137 ,0,0,0}, {36658,38462,38460 ,21044,21227,21045 ,0,0,0}, + {35282,37087,35281 ,18038,21228,21318 ,0,0,0}, {38462,36658,37087 ,21227,21044,21228 ,0,0,0}, + {35182,38114,36749 ,21319,21136,21320 ,0,0,0}, {38111,36783,38113 ,21321,21322,21323 ,0,0,0}, + {36184,36183,38112 ,21231,21139,21324 ,0,0,0}, {36634,37464,36635 ,21325,21232,21326 ,0,0,0}, + {36746,38110,36668 ,21327,21328,21329 ,0,0,0}, {38036,36513,38105 ,21146,21236,21330 ,0,0,0}, + {38106,36744,37466 ,21331,21332,21333 ,0,0,0}, {36664,37749,36663 ,21334,21335,21336 ,0,0,0}, + {36514,38104,36784 ,21337,21338,21339 ,0,0,0}, {38148,36637,38149 ,21340,21341,21249 ,0,0,0}, + {36612,36785,38172 ,21250,21342,21343 ,0,0,0}, {36748,38447,36747 ,21344,21345,21346 ,0,0,0}, + {37639,38419,36786 ,21347,21348,21168 ,0,0,0}, {38174,37189,36787 ,21349,21350,21351 ,0,0,0}, + {38175,37190,37665 ,21352,21353,21354 ,0,0,0}, {36788,37188,38422 ,21355,21356,21357 ,0,0,0}, + {36789,38076,38075 ,21358,21359,21360 ,0,0,0}, {36632,37663,37664 ,21361,21362,21363 ,0,0,0}, + {38421,37663,36633 ,21364,21362,21365 ,0,0,0}, {37101,38176,36208 ,21366,21367,21368 ,0,0,0}, + {38173,37101,36631 ,21369,21366,21370 ,0,0,0}, {36207,38169,36837 ,21371,21372,21373 ,0,0,0}, + {38170,36207,36208 ,21374,21371,21368 ,0,0,0}, {38423,38086,36841 ,21375,21376,21377 ,0,0,0}, + {38424,37127,36837 ,21378,21379,21373 ,0,0,0}, {36838,38086,38068 ,21380,21376,21381 ,0,0,0}, + {38086,36838,36841 ,21376,21380,21377 ,0,0,0}, {38067,36477,38068 ,21382,21383,21381 ,0,0,0}, + {36838,38068,36477 ,21380,21381,21383 ,0,0,0}, {38067,38072,36475 ,21382,21384,21385 ,0,0,0}, + {36475,36477,38067 ,21385,21383,21382 ,0,0,0}, {36481,38072,38071 ,21386,21384,21387 ,0,0,0}, + {38072,36481,36475 ,21384,21386,21385 ,0,0,0}, {38065,36176,38071 ,21388,21389,21387 ,0,0,0}, + {36481,38071,36176 ,21386,21387,21389 ,0,0,0}, {38065,38178,36177 ,21388,21390,21391 ,0,0,0}, + {36177,36176,38065 ,21391,21389,21388 ,0,0,0}, {36807,38178,37779 ,21392,21390,21393 ,0,0,0}, + {38178,36807,36177 ,21390,21392,21391 ,0,0,0}, {38059,36809,37779 ,21394,21395,21393 ,0,0,0}, + {36807,37779,36809 ,21392,21393,21395 ,0,0,0}, {38059,38058,36340 ,21394,21396,21397 ,0,0,0}, + {36340,36809,38059 ,21397,21395,21394 ,0,0,0}, {36338,38058,38063 ,21398,21396,21399 ,0,0,0}, + {38058,36338,36340 ,21396,21398,21397 ,0,0,0}, {38116,36814,38063 ,21400,21401,21399 ,0,0,0}, + {36338,38063,36814 ,21398,21399,21401 ,0,0,0}, {38116,35227,35228 ,21400,21312,126 ,0,0,0}, + {35228,36814,38116 ,126,21401,21400 ,0,0,0}, {36841,37127,38423 ,21377,21379,21375 ,0,0,0}, + {38424,38423,37127 ,21378,21375,21379 ,0,0,0}, {38169,38424,36837 ,21372,21378,21373 ,0,0,0}, + {38169,36207,38170 ,21372,21371,21374 ,0,0,0}, {38173,38176,37101 ,21369,21367,21366 ,0,0,0}, + {38176,38170,36208 ,21367,21374,21368 ,0,0,0}, {36632,37664,36631 ,21361,21363,21370 ,0,0,0}, + {38173,36631,37664 ,21369,21370,21363 ,0,0,0}, {36788,38421,36633 ,21355,21364,21365 ,0,0,0}, + {36633,37663,36632 ,21365,21362,21361 ,0,0,0}, {36788,38422,38421 ,21355,21357,21364 ,0,0,0}, + {37188,36789,38075 ,21356,21358,21360 ,0,0,0}, {37188,38075,38422 ,21356,21360,21357 ,0,0,0}, + {38076,37189,38174 ,21359,21350,21349 ,0,0,0}, {36789,37189,38076 ,21358,21350,21359 ,0,0,0}, + {37190,38175,36787 ,21353,21352,21351 ,0,0,0}, {38174,36787,38175 ,21349,21351,21352 ,0,0,0}, + {38447,37665,36747 ,21345,21354,21346 ,0,0,0}, {37190,36747,37665 ,21353,21346,21354 ,0,0,0}, + {38447,36748,38419 ,21345,21344,21348 ,0,0,0}, {36786,38419,36748 ,21168,21348,21344 ,0,0,0}, + {36637,38148,36638 ,21341,21340,21402 ,0,0,0}, {36638,38148,37639 ,21402,21340,21347 ,0,0,0}, + {36638,37639,36786 ,21402,21347,21168 ,0,0,0}, {36612,38149,36637 ,21250,21249,21341 ,0,0,0}, + {36785,37748,38172 ,21342,21403,21343 ,0,0,0}, {38149,36612,38172 ,21249,21250,21343 ,0,0,0}, + {37749,37748,36663 ,21335,21403,21336 ,0,0,0}, {37748,36785,36663 ,21403,21342,21336 ,0,0,0}, + {36784,38102,36664 ,21339,21404,21334 ,0,0,0}, {38102,37749,36664 ,21404,21335,21334 ,0,0,0}, + {38036,38104,36514 ,21146,21338,21337 ,0,0,0}, {36784,38104,38102 ,21339,21338,21404 ,0,0,0}, + {38108,36668,38110 ,21133,21329,21328 ,0,0,0}, {36666,38105,36513 ,21405,21330,21236 ,0,0,0}, + {36514,36513,38036 ,21337,21236,21146 ,0,0,0}, {38106,36666,36744 ,21331,21405,21332 ,0,0,0}, + {38105,36666,38106 ,21330,21405,21331 ,0,0,0}, {37464,37466,36635 ,21232,21333,21326 ,0,0,0}, + {37466,36744,36635 ,21333,21332,21326 ,0,0,0}, {36668,38108,36634 ,21329,21133,21325 ,0,0,0}, + {38108,37464,36634 ,21133,21232,21325 ,0,0,0}, {38111,38110,36746 ,21321,21328,21327 ,0,0,0}, + {36184,38112,38113 ,21231,21324,21323 ,0,0,0}, {36184,38113,36783 ,21231,21323,21322 ,0,0,0}, + {36746,36783,38111 ,21327,21322,21321 ,0,0,0}, {36183,38114,38112 ,21139,21136,21324 ,0,0,0}, + {35182,36749,35181 ,21319,21320,21406 ,0,0,0}, {38114,36183,36749 ,21136,21139,21320 ,0,0,0}, + {37473,36200,36752 ,1273,1273,21407 ,0,0,0}, {36751,37471,36752 ,21408,21409,21407 ,0,0,0}, + {37473,36752,37471 ,1273,21407,21409 ,0,0,0}, {36751,37067,37472 ,21408,1276,21408 ,0,0,0}, + {37472,37471,36751 ,21408,21409,21408 ,0,0,0}, {37477,37067,37068 ,1276,1276,21410 ,0,0,0}, + {37067,37477,37472 ,1276,1276,21408 ,0,0,0}, {37066,37486,37068 ,21411,21412,21410 ,0,0,0}, + {37477,37068,37486 ,1276,21410,21412 ,0,0,0}, {37066,36195,37487 ,21411,21413,21411 ,0,0,0}, + {37487,37486,37066 ,21411,21412,21411 ,0,0,0}, {36195,37481,37487 ,21413,20658,21411 ,0,0,0}, + {37462,36200,37473 ,21414,1273,1273 ,0,0,0}, {37462,37461,36201 ,21414,21415,21416 ,0,0,0}, + {36201,36200,37462 ,21416,1273,21414 ,0,0,0}, {36782,37461,38039 ,21415,21415,21417 ,0,0,0}, + {37461,36782,36201 ,21415,21415,21416 ,0,0,0}, {38040,36781,38039 ,21418,1275,21417 ,0,0,0}, + {36782,38039,36781 ,21415,21417,1275 ,0,0,0}, {38040,38041,36174 ,21418,21419,21420 ,0,0,0}, + {36174,36781,38040 ,21420,1275,21418 ,0,0,0}, {36173,38041,38050 ,21419,21419,21421 ,0,0,0}, + {38041,36173,36174 ,21419,21419,21420 ,0,0,0}, {36173,38050,36181 ,21419,21421,21422 ,0,0,0}, + {37646,36639,36652 ,1207,1207,21423 ,0,0,0}, {36651,38376,36652 ,21424,21425,21423 ,0,0,0}, + {37646,36652,38376 ,1207,21423,21425 ,0,0,0}, {36651,36655,37641 ,21424,1882,21424 ,0,0,0}, + {37641,38376,36651 ,21424,21425,21424 ,0,0,0}, {37642,36655,36661 ,1882,1882,21426 ,0,0,0}, + {36655,37642,37641 ,1882,1882,21424 ,0,0,0}, {37093,37636,36661 ,21427,21428,21426 ,0,0,0}, + {37642,36661,37636 ,1882,21426,21428 ,0,0,0}, {37093,37094,37643 ,21427,21429,21427 ,0,0,0}, + {37643,37636,37093 ,21427,21428,21427 ,0,0,0}, {37094,37648,37643 ,21429,21430,21427 ,0,0,0}, + {37653,36639,37646 ,21431,1207,1207 ,0,0,0}, {37653,37656,36648 ,21431,21432,21433 ,0,0,0}, + {36648,36639,37653 ,21433,1207,21431 ,0,0,0}, {36646,37656,37655 ,21432,21432,21434 ,0,0,0}, + {37656,36646,36648 ,21432,21432,21433 ,0,0,0}, {37657,36642,37655 ,21435,1887,21434 ,0,0,0}, + {36646,37655,36642 ,21432,21434,1887 ,0,0,0}, {37657,37662,36643 ,21435,21436,21437 ,0,0,0}, + {36643,36642,37657 ,21437,1887,21435 ,0,0,0}, {36644,37662,38366 ,21436,21436,21438 ,0,0,0}, + {37662,36644,36643 ,21436,21436,21437 ,0,0,0}, {36644,38366,36645 ,21436,21438,21439 ,0,0,0}, + {37792,36492,36483 ,2038,2038,21440 ,0,0,0}, {36487,37784,36483 ,21441,21442,21440 ,0,0,0}, + {37792,36483,37784 ,2038,21440,21442 ,0,0,0}, {36487,36486,37796 ,21441,2041,21441 ,0,0,0}, + {37796,37784,36487 ,21441,21442,21441 ,0,0,0}, {37802,36486,36485 ,2041,2041,21443 ,0,0,0}, + {36486,37802,37796 ,2041,2041,21441 ,0,0,0}, {36506,37803,36485 ,21444,21445,21443 ,0,0,0}, + {37802,36485,37803 ,2041,21443,21445 ,0,0,0}, {36506,36849,37795 ,21444,21446,21444 ,0,0,0}, + {37795,37803,36506 ,21444,21445,21444 ,0,0,0}, {36849,37800,37795 ,21446,21447,21444 ,0,0,0}, + {37794,36492,37792 ,21448,2038,2038 ,0,0,0}, {37794,37787,37082 ,21448,21449,21450 ,0,0,0}, + {37082,36492,37794 ,21450,2038,21448 ,0,0,0}, {36505,37787,37789 ,21449,21449,21451 ,0,0,0}, + {37787,36505,37082 ,21449,21449,21450 ,0,0,0}, {38348,37073,37789 ,21452,2040,21451 ,0,0,0}, + {36505,37789,37073 ,21449,21451,2040 ,0,0,0}, {38348,38358,36499 ,21452,21453,21454 ,0,0,0}, + {36499,37073,38348 ,21454,2040,21452 ,0,0,0}, {36490,38358,38359 ,21453,21453,21455 ,0,0,0}, + {38358,36490,36499 ,21453,21453,21454 ,0,0,0}, {36490,38359,36497 ,21453,21455,21429 ,0,0,0}, + {37896,36330,36336 ,1114,1114,21456 ,0,0,0}, {36315,37939,36336 ,21457,21458,21456 ,0,0,0}, + {37896,36336,37939 ,1114,21456,21458 ,0,0,0}, {36315,36316,37936 ,21457,1116,21457 ,0,0,0}, + {37936,37939,36315 ,21457,21458,21457 ,0,0,0}, {37933,36316,36825 ,1116,1116,21459 ,0,0,0}, + {36316,37933,37936 ,1116,1116,21457 ,0,0,0}, {36317,37934,36825 ,21460,21461,21459 ,0,0,0}, + {37933,36825,37934 ,1116,21459,21461 ,0,0,0}, {36317,36213,37935 ,21460,21462,21460 ,0,0,0}, + {37935,37934,36317 ,21460,21461,21460 ,0,0,0}, {36213,37940,37935 ,21462,21463,21460 ,0,0,0}, + {37941,36330,37896 ,21464,1114,1114 ,0,0,0}, {37941,37938,36321 ,21464,21465,21466 ,0,0,0}, + {36321,36330,37941 ,21466,1114,21464 ,0,0,0}, {36322,37938,37937 ,21465,21465,21467 ,0,0,0}, + {37938,36322,36321 ,21465,21465,21466 ,0,0,0}, {38344,36323,37937 ,21468,1121,21467 ,0,0,0}, + {36322,37937,36323 ,21465,21467,1121 ,0,0,0}, {38344,38055,36324 ,21468,21469,21470 ,0,0,0}, + {36324,36323,38344 ,21470,1121,21468 ,0,0,0}, {37072,38055,37668 ,21469,21469,21471 ,0,0,0}, + {38055,37072,36324 ,21469,21469,21470 ,0,0,0}, {37072,37668,36327 ,21469,21471,21472 ,0,0,0}, + {35119,37207,38468 ,21473,21474,21475 ,0,0,0}, {38464,38463,36740 ,21476,21477,21478 ,0,0,0}, + {38469,38467,37206 ,21479,21480,21481 ,0,0,0}, {38470,37203,37204 ,21482,21483,21484 ,0,0,0}, + {37205,37203,38471 ,21485,21483,21486 ,0,0,0}, {38465,38466,37201 ,21487,21488,21489 ,0,0,0}, + {37204,37201,38466 ,21484,21489,21488 ,0,0,0}, {37202,35128,38465 ,21490,82,21487 ,0,0,0}, + {38465,37201,37202 ,21487,21489,21490 ,0,0,0}, {35127,35128,37202 ,19633,82,21490 ,0,0,0}, + {38466,38470,37204 ,21488,21482,21484 ,0,0,0}, {38470,38471,37203 ,21482,21486,21483 ,0,0,0}, + {38464,36740,37205 ,21476,21478,21485 ,0,0,0}, {38464,37205,38471 ,21476,21485,21486 ,0,0,0}, + {38469,37206,36741 ,21479,21481,21491 ,0,0,0}, {38463,38469,36741 ,21477,21479,21491 ,0,0,0}, + {38463,36741,36740 ,21477,21491,21478 ,0,0,0}, {37207,38467,38468 ,21474,21480,21475 ,0,0,0}, + {37207,37206,38467 ,21474,21481,21480 ,0,0,0}, {38468,35116,35119 ,21475,21492,21473 ,0,0,0}, + {35097,37214,38028 ,21493,21494,21495 ,0,0,0}, {38475,38474,37213 ,21496,21497,21498 ,0,0,0}, + {38473,38472,37215 ,21499,21500,21501 ,0,0,0}, {38476,37210,37209 ,21502,21503,21504 ,0,0,0}, + {37211,37210,38477 ,21505,21503,21506 ,0,0,0}, {38478,38479,37208 ,21507,21508,21509 ,0,0,0}, + {37209,37208,38479 ,21504,21509,21508 ,0,0,0}, {36288,35106,38478 ,21510,761,21507 ,0,0,0}, + {38478,37208,36288 ,21507,21509,21510 ,0,0,0}, {35105,35106,36288 ,761,761,21510 ,0,0,0}, + {38479,38476,37209 ,21508,21502,21504 ,0,0,0}, {38476,38477,37210 ,21502,21506,21503 ,0,0,0}, + {38475,37213,37211 ,21496,21498,21505 ,0,0,0}, {38475,37211,38477 ,21496,21505,21506 ,0,0,0}, + {38473,37215,37212 ,21499,21501,21511 ,0,0,0}, {38474,38473,37212 ,21497,21499,21511 ,0,0,0}, + {38474,37212,37213 ,21497,21511,21498 ,0,0,0}, {37214,38472,38028 ,21494,21500,21495 ,0,0,0}, + {37214,37215,38472 ,21494,21501,21500 ,0,0,0}, {38028,35094,35097 ,21495,96,21493 ,0,0,0}, + {35075,36305,37958 ,21493,21512,21495 ,0,0,0}, {38025,38027,36307 ,21513,21497,21514 ,0,0,0}, + {38483,38022,36310 ,21515,21516,21517 ,0,0,0}, {38480,36313,37221 ,21518,21519,21520 ,0,0,0}, + {36312,36313,38023 ,21521,21519,21522 ,0,0,0}, {38019,38481,36300 ,21523,21524,21525 ,0,0,0}, + {37221,36300,38481 ,21520,21525,21524 ,0,0,0}, {36299,35084,38019 ,21526,761,21523 ,0,0,0}, + {38019,36300,36299 ,21523,21525,21526 ,0,0,0}, {35083,35084,36299 ,761,761,21526 ,0,0,0}, + {38481,38480,37221 ,21524,21518,21520 ,0,0,0}, {38480,38023,36313 ,21518,21522,21519 ,0,0,0}, + {38025,36307,36312 ,21513,21514,21521 ,0,0,0}, {38025,36312,38023 ,21513,21521,21522 ,0,0,0}, + {38483,36310,36309 ,21515,21517,21527 ,0,0,0}, {38027,38483,36309 ,21497,21515,21527 ,0,0,0}, + {38027,36309,36307 ,21497,21527,21514 ,0,0,0}, {36305,38022,37958 ,21512,21516,21495 ,0,0,0}, + {36305,36310,38022 ,21512,21517,21516 ,0,0,0}, {37958,35072,35075 ,21495,96,21493 ,0,0,0}, + {35053,37042,37917 ,850,21528,21529 ,0,0,0}, {37904,37906,36430 ,21530,21531,21532 ,0,0,0}, + {37924,37921,36927 ,21533,21534,21535 ,0,0,0}, {38494,36929,36931 ,21536,21537,21538 ,0,0,0}, + {37047,36929,38493 ,21539,21537,21540 ,0,0,0}, {37920,38496,36459 ,21541,21542,21543 ,0,0,0}, + {36931,36459,38496 ,21538,21543,21542 ,0,0,0}, {36458,35062,37920 ,21544,82,21541 ,0,0,0}, + {37920,36459,36458 ,21541,21543,21544 ,0,0,0}, {35061,35062,36458 ,19655,82,21544 ,0,0,0}, + {38496,38494,36931 ,21542,21536,21538 ,0,0,0}, {38494,38493,36929 ,21536,21540,21537 ,0,0,0}, + {37904,36430,37047 ,21530,21532,21539 ,0,0,0}, {37904,37047,38493 ,21530,21539,21540 ,0,0,0}, + {37924,36927,36428 ,21533,21535,21545 ,0,0,0}, {37906,37924,36428 ,21531,21533,21545 ,0,0,0}, + {37906,36428,36430 ,21531,21545,21532 ,0,0,0}, {37042,37921,37917 ,21528,21534,21529 ,0,0,0}, + {37042,36927,37921 ,21528,21535,21534 ,0,0,0}, {37917,35050,35053 ,21529,21492,850 ,0,0,0}, + {35031,37233,38501 ,21493,21512,21495 ,0,0,0}, {38502,38497,37232 ,21546,21547,21548 ,0,0,0}, + {38499,38500,37234 ,21549,21516,9914 ,0,0,0}, {38503,36625,36624 ,21550,21503,21551 ,0,0,0}, + {37230,36625,38504 ,21552,21503,21553 ,0,0,0}, {38505,38506,37228 ,21554,21555,21556 ,0,0,0}, + {36624,37228,38506 ,21551,21556,21555 ,0,0,0}, {37229,35040,38505 ,21557,761,21554 ,0,0,0}, + {38505,37228,37229 ,21554,21556,21557 ,0,0,0}, {35039,35040,37229 ,761,761,21557 ,0,0,0}, + {38506,38503,36624 ,21555,21550,21551 ,0,0,0}, {38503,38504,36625 ,21550,21553,21503 ,0,0,0}, + {38502,37232,37230 ,21546,21548,21552 ,0,0,0}, {38502,37230,38504 ,21546,21552,21553 ,0,0,0}, + {38499,37234,37231 ,21549,9914,21558 ,0,0,0}, {38497,38499,37231 ,21547,21549,21558 ,0,0,0}, + {38497,37231,37232 ,21547,21558,21548 ,0,0,0}, {37233,38500,38501 ,21512,21516,21495 ,0,0,0}, + {37233,37234,38500 ,21512,9914,21516 ,0,0,0}, {38501,35028,35031 ,21495,96,21493 ,0,0,0}, + {35009,36614,37755 ,21493,9918,21495 ,0,0,0}, {37757,37737,37238 ,21559,21560,9908 ,0,0,0}, + {37736,37753,36622 ,21561,21516,21501 ,0,0,0}, {37765,37241,36594 ,21550,21562,21563 ,0,0,0}, + {37240,37241,38508 ,21564,21562,21565 ,0,0,0}, {37769,37768,36616 ,21566,21567,21568 ,0,0,0}, + {36594,36616,37768 ,21563,21568,21567 ,0,0,0}, {36615,35018,37769 ,21569,761,21566 ,0,0,0}, + {37769,36616,36615 ,21566,21568,21569 ,0,0,0}, {35017,35018,36615 ,761,761,21569 ,0,0,0}, + {37768,37765,36594 ,21567,21550,21563 ,0,0,0}, {37765,38508,37241 ,21550,21565,21562 ,0,0,0}, + {37757,37238,37240 ,21559,9908,21564 ,0,0,0}, {37757,37240,38508 ,21559,21564,21565 ,0,0,0}, + {37736,36622,36591 ,21561,21501,21558 ,0,0,0}, {37737,37736,36591 ,21560,21561,21558 ,0,0,0}, + {37737,36591,37238 ,21560,21558,9908 ,0,0,0}, {36614,37753,37755 ,9918,21516,21495 ,0,0,0}, + {36614,36622,37753 ,9918,21501,21516 ,0,0,0}, {37755,35006,35009 ,21495,96,21493 ,0,0,0}, + {34987,36463,37925 ,19184,21570,21475 ,0,0,0}, {38516,38517,37250 ,21476,21571,21572 ,0,0,0}, + {38514,38515,36464 ,21573,21574,21575 ,0,0,0}, {38513,37244,37248 ,21576,21577,21578 ,0,0,0}, + {37245,37244,38512 ,21485,21577,21579 ,0,0,0}, {38519,38518,37246 ,21580,21581,21582 ,0,0,0}, + {37248,37246,38518 ,21578,21582,21581 ,0,0,0}, {37247,34996,38519 ,21583,82,21580 ,0,0,0}, + {38519,37246,37247 ,21580,21582,21583 ,0,0,0}, {34995,34996,37247 ,19655,82,21583 ,0,0,0}, + {38518,38513,37248 ,21581,21576,21578 ,0,0,0}, {38513,38512,37244 ,21576,21579,21577 ,0,0,0}, + {38516,37250,37245 ,21476,21572,21485 ,0,0,0}, {38516,37245,38512 ,21476,21485,21579 ,0,0,0}, + {38514,36464,37249 ,21573,21575,21584 ,0,0,0}, {38517,38514,37249 ,21571,21573,21584 ,0,0,0}, + {38517,37249,37250 ,21571,21584,21572 ,0,0,0}, {36463,38515,37925 ,21570,21574,21475 ,0,0,0}, + {36463,36464,38515 ,21570,21575,21574 ,0,0,0}, {37925,34984,34987 ,21475,21585,19184 ,0,0,0}, + {34965,36739,37616 ,21473,21586,21587 ,0,0,0}, {37601,37609,37253 ,21530,21588,21589 ,0,0,0}, + {37608,37613,37256 ,21590,21534,21591 ,0,0,0}, {38520,36737,36680 ,21592,21593,21594 ,0,0,0}, + {36736,36737,37602 ,21539,21593,21540 ,0,0,0}, {37573,37612,36733 ,21595,21596,21597 ,0,0,0}, + {36680,36733,37612 ,21594,21597,21596 ,0,0,0}, {36734,34974,37573 ,21598,19234,21595 ,0,0,0}, + {37573,36733,36734 ,21595,21597,21598 ,0,0,0}, {34973,34974,36734 ,21599,19234,21598 ,0,0,0}, + {37612,38520,36680 ,21596,21592,21594 ,0,0,0}, {38520,37602,36737 ,21592,21540,21593 ,0,0,0}, + {37601,37253,36736 ,21530,21589,21539 ,0,0,0}, {37601,36736,37602 ,21530,21539,21540 ,0,0,0}, + {37608,37256,37254 ,21590,21591,21600 ,0,0,0}, {37609,37608,37254 ,21588,21590,21600 ,0,0,0}, + {37609,37254,37253 ,21588,21600,21589 ,0,0,0}, {36739,37613,37616 ,21586,21534,21587 ,0,0,0}, + {36739,37256,37613 ,21586,21591,21534 ,0,0,0}, {37616,34962,34965 ,21587,21492,21473 ,0,0,0}, + {34937,37459,37530 ,2619,21601,21602 ,0,0,0}, {37977,38530,36254 ,21603,20873,21604 ,0,0,0}, + {38529,38212,37265 ,21605,21606,21607 ,0,0,0}, {38743,37260,37979 ,21608,21609,21610 ,0,0,0}, + {36253,37460,38745 ,21611,21612,21613 ,0,0,0}, {37259,36260,38526 ,21614,21615,21616 ,0,0,0}, + {37259,38537,36225 ,21614,21617,21618 ,0,0,0}, {36259,37258,38209 ,21619,21620,21621 ,0,0,0}, + {38209,38527,36259 ,21621,21622,21619 ,0,0,0}, {37972,37258,37257 ,21623,21620,21624 ,0,0,0}, + {37258,37972,38209 ,21620,21623,21621 ,0,0,0}, {36871,38533,37257 ,21625,21626,21624 ,0,0,0}, + {37972,37257,38533 ,21623,21624,21626 ,0,0,0}, {36871,34951,34952 ,21625,82,2602 ,0,0,0}, + {34952,38533,36871 ,2602,21626,21625 ,0,0,0}, {37260,38743,37460 ,21609,21608,21612 ,0,0,0}, + {36260,38527,38526 ,21615,21622,21616 ,0,0,0}, {36259,38527,36260 ,21619,21622,21615 ,0,0,0}, + {36254,38530,36269 ,21604,20873,21627 ,0,0,0}, {36225,38537,37979 ,21618,21617,21610 ,0,0,0}, + {37259,38526,38537 ,21614,21616,21617 ,0,0,0}, {37260,36225,37979 ,21609,21618,21610 ,0,0,0}, + {38745,37460,38743 ,21613,21612,21608 ,0,0,0}, {37977,36254,36253 ,21603,21604,21611 ,0,0,0}, + {36253,38745,37977 ,21611,21613,21603 ,0,0,0}, {38212,37459,37265 ,21606,21601,21607 ,0,0,0}, + {36269,38529,37265 ,21627,21605,21607 ,0,0,0}, {38530,38529,36269 ,20873,21605,21627 ,0,0,0}, + {34937,37530,34938 ,2619,21602,126 ,0,0,0}, {37459,38212,37530 ,21601,21606,21602 ,0,0,0}, + {34907,36910,38184 ,2619,17362,21602 ,0,0,0}, {38190,38189,36907 ,21628,21629,21630 ,0,0,0}, + {38538,38187,36909 ,21605,20903,21631 ,0,0,0}, {38484,37279,38014 ,21632,21609,21633 ,0,0,0}, + {37281,37277,38486 ,21634,21635,21636 ,0,0,0}, {37296,37297,38540 ,21637,21638,21639 ,0,0,0}, + {37296,38539,37452 ,21637,21640,21641 ,0,0,0}, {37222,36303,37995 ,21642,21643,21644 ,0,0,0}, + {37995,38541,37222 ,21644,21645,21642 ,0,0,0}, {38562,36303,37453 ,21646,21643,21647 ,0,0,0}, + {36303,38562,37995 ,21643,21646,21644 ,0,0,0}, {37269,38559,37453 ,21648,21649,21647 ,0,0,0}, + {38562,37453,38559 ,21646,21647,21649 ,0,0,0}, {37269,34920,3883 ,21648,21650,82 ,0,0,0}, + {3883,38559,37269 ,82,21649,21648 ,0,0,0}, {37279,38484,37277 ,21609,21632,21635 ,0,0,0}, + {37297,38541,38540 ,21638,21645,21639 ,0,0,0}, {37222,38541,37297 ,21642,21645,21638 ,0,0,0}, + {36907,38189,36271 ,21630,21629,21651 ,0,0,0}, {37452,38539,38014 ,21641,21640,21633 ,0,0,0}, + {37296,38540,38539 ,21637,21639,21640 ,0,0,0}, {37279,37452,38014 ,21609,21641,21633 ,0,0,0}, + {38486,37277,38484 ,21636,21635,21632 ,0,0,0}, {38190,36907,37281 ,21628,21630,21634 ,0,0,0}, + {37281,38486,38190 ,21634,21636,21628 ,0,0,0}, {38187,36910,36909 ,20903,17362,21631 ,0,0,0}, + {36271,38538,36909 ,21651,21605,21631 ,0,0,0}, {38189,38538,36271 ,21629,21605,21651 ,0,0,0}, + {34907,38184,3897 ,2619,21602,126 ,0,0,0}, {36910,38187,38184 ,17362,20903,21602 ,0,0,0}, + {34875,37298,37998 ,8383,21652,21653 ,0,0,0}, {38545,38544,37295 ,20948,21654,21655 ,0,0,0}, + {38542,38733,37271 ,21656,20903,21607 ,0,0,0}, {37476,37219,37997 ,21657,21609,21658 ,0,0,0}, + {37294,37272,38561 ,21659,21660,21661 ,0,0,0}, {37276,36902,38548 ,21662,21663,21664 ,0,0,0}, + {37276,38564,37218 ,21662,21665,21666 ,0,0,0}, {36901,37292,38000 ,21667,21668,21669 ,0,0,0}, + {38000,38549,36901 ,21669,21670,21667 ,0,0,0}, {38194,37292,36894 ,21671,21668,21672 ,0,0,0}, + {37292,38194,38000 ,21668,21671,21669 ,0,0,0}, {37283,38192,36894 ,21673,21674,21672 ,0,0,0}, + {38194,36894,38192 ,21671,21672,21674 ,0,0,0}, {37283,34889,34890 ,21673,2601,82 ,0,0,0}, + {34890,38192,37283 ,82,21674,21673 ,0,0,0}, {37219,37476,37272 ,21609,21657,21660 ,0,0,0}, + {36902,38549,38548 ,21663,21670,21664 ,0,0,0}, {36901,38549,36902 ,21667,21670,21663 ,0,0,0}, + {37295,38544,37270 ,21655,21654,21675 ,0,0,0}, {37218,38564,37997 ,21666,21665,21658 ,0,0,0}, + {37276,38548,38564 ,21662,21664,21665 ,0,0,0}, {37219,37218,37997 ,21609,21666,21658 ,0,0,0}, + {38561,37272,37476 ,21661,21660,21657 ,0,0,0}, {38545,37295,37294 ,20948,21655,21659 ,0,0,0}, + {37294,38561,38545 ,21659,21661,20948 ,0,0,0}, {38733,37298,37271 ,20903,21652,21607 ,0,0,0}, + {37270,38542,37271 ,21675,21656,21607 ,0,0,0}, {38544,38542,37270 ,21654,21656,21675 ,0,0,0}, + {34875,37998,34876 ,8383,21653,126 ,0,0,0}, {37298,38733,37998 ,21652,20903,21653 ,0,0,0}, + {34845,37311,38568 ,8383,21676,21653 ,0,0,0}, {37988,38179,36877 ,21603,20873,21677 ,0,0,0}, + {37551,37961,36276 ,21678,21679,21631 ,0,0,0}, {37990,37307,38556 ,21680,21681,21682 ,0,0,0}, + {36228,36227,37987 ,21683,21684,21685 ,0,0,0}, {37306,37305,37989 ,21686,21687,21688 ,0,0,0}, + {37306,38570,37308 ,21686,21689,21690 ,0,0,0}, {37285,37284,38555 ,21691,21692,21693 ,0,0,0}, + {38555,38571,37285 ,21693,21694,21691 ,0,0,0}, {38553,37284,37286 ,21695,21692,21696 ,0,0,0}, + {37284,38553,38555 ,21692,21695,21693 ,0,0,0}, {37302,37986,37286 ,21697,21698,21696 ,0,0,0}, + {38553,37286,37986 ,21695,21696,21698 ,0,0,0}, {37302,34858,3917 ,21697,2601,82 ,0,0,0}, + {3917,37986,37302 ,82,21698,21697 ,0,0,0}, {37307,37990,36227 ,21681,21680,21684 ,0,0,0}, + {37305,38571,37989 ,21687,21694,21688 ,0,0,0}, {37285,38571,37305 ,21691,21694,21687 ,0,0,0}, + {36877,38179,36241 ,21677,20873,21627 ,0,0,0}, {37308,38570,38556 ,21690,21689,21682 ,0,0,0}, + {37306,37989,38570 ,21686,21688,21689 ,0,0,0}, {37307,37308,38556 ,21681,21690,21682 ,0,0,0}, + {37987,36227,37990 ,21685,21684,21680 ,0,0,0}, {37988,36877,36228 ,21603,21677,21683 ,0,0,0}, + {36228,37987,37988 ,21683,21685,21603 ,0,0,0}, {37961,37311,36276 ,21679,21676,21631 ,0,0,0}, + {36241,37551,36276 ,21627,21678,21631 ,0,0,0}, {38179,37551,36241 ,20873,21678,21627 ,0,0,0}, + {34845,38568,3931 ,8383,21653,126 ,0,0,0}, {37311,37961,38568 ,21676,21679,21653 ,0,0,0}, + {34815,37321,37880 ,21585,17362,21699 ,0,0,0}, {38585,37826,36360 ,21700,21701,21702 ,0,0,0}, + {37825,37885,37340 ,21703,20903,21704 ,0,0,0}, {38723,37319,37830 ,21705,21706,21707 ,0,0,0}, + {36390,37447,38725 ,21708,21709,21710 ,0,0,0}, {37318,36382,38576 ,21711,21712,21713 ,0,0,0}, + {37318,37828,36385 ,21711,21714,21715 ,0,0,0}, {36367,37317,38246 ,21716,21717,21718 ,0,0,0}, + {38246,38577,36367 ,21718,21719,21716 ,0,0,0}, {37867,37317,37316 ,21720,21717,21721 ,0,0,0}, + {37317,37867,38246 ,21717,21720,21718 ,0,0,0}, {37315,38589,37316 ,21722,21723,21721 ,0,0,0}, + {37867,37316,38589 ,21720,21721,21723 ,0,0,0}, {37315,34828,2165 ,21722,19655,82 ,0,0,0}, + {2165,38589,37315 ,82,21723,21722 ,0,0,0}, {37319,38723,37447 ,21706,21705,21709 ,0,0,0}, + {36382,38577,38576 ,21712,21719,21713 ,0,0,0}, {36367,38577,36382 ,21716,21719,21712 ,0,0,0}, + {36360,37826,36361 ,21702,21701,21724 ,0,0,0}, {36385,37828,37830 ,21715,21714,21707 ,0,0,0}, + {37318,38576,37828 ,21711,21713,21714 ,0,0,0}, {37319,36385,37830 ,21706,21715,21707 ,0,0,0}, + {38725,37447,38723 ,21710,21709,21705 ,0,0,0}, {38585,36360,36390 ,21700,21702,21708 ,0,0,0}, + {36390,38725,38585 ,21708,21710,21700 ,0,0,0}, {37885,37321,37340 ,20903,17362,21704 ,0,0,0}, + {36361,37825,37340 ,21724,21703,21704 ,0,0,0}, {37826,37825,36361 ,21701,21703,21724 ,0,0,0}, + {34815,37880,2941 ,21585,21699,126 ,0,0,0}, {37321,37885,37880 ,17362,20903,21699 ,0,0,0}, + {34783,37330,38593 ,21585,21725,21726 ,0,0,0}, {38322,37818,37059 ,21727,21728,21729 ,0,0,0}, + {37874,37873,36915 ,21656,21730,21731 ,0,0,0}, {37878,37058,38323 ,21732,21733,21734 ,0,0,0}, + {36922,36921,37877 ,21735,21736,21710 ,0,0,0}, {36919,36920,37858 ,21737,21738,21739 ,0,0,0}, + {36919,38324,37329 ,21737,21740,21741 ,0,0,0}, {37326,36442,38597 ,21742,21743,21744 ,0,0,0}, + {38597,37859,37326 ,21744,21745,21742 ,0,0,0}, {38238,36442,36441 ,21746,21743,21747 ,0,0,0}, + {36442,38238,38597 ,21743,21746,21744 ,0,0,0}, {37063,38598,36441 ,21748,21749,21747 ,0,0,0}, + {38238,36441,38598 ,21746,21747,21749 ,0,0,0}, {37063,34797,34798 ,21748,21750,82 ,0,0,0}, + {34798,38598,37063 ,82,21749,21748 ,0,0,0}, {37058,37878,36921 ,21733,21732,21736 ,0,0,0}, + {36920,37859,37858 ,21738,21745,21739 ,0,0,0}, {37326,37859,36920 ,21742,21745,21738 ,0,0,0}, + {37059,37818,36444 ,21729,21728,21724 ,0,0,0}, {37329,38324,38323 ,21741,21740,21734 ,0,0,0}, + {36919,37858,38324 ,21737,21739,21740 ,0,0,0}, {37058,37329,38323 ,21733,21741,21734 ,0,0,0}, + {37877,36921,37878 ,21710,21736,21732 ,0,0,0}, {38322,37059,36922 ,21727,21729,21735 ,0,0,0}, + {36922,37877,38322 ,21735,21710,21727 ,0,0,0}, {37873,37330,36915 ,21730,21725,21731 ,0,0,0}, + {36444,37874,36915 ,21724,21656,21731 ,0,0,0}, {37818,37874,36444 ,21728,21656,21724 ,0,0,0}, + {34783,38593,34784 ,21585,21726,126 ,0,0,0}, {37330,37873,38593 ,21725,21730,21726 ,0,0,0}, + {34753,37334,38607 ,21585,21725,21726 ,0,0,0}, {38624,38606,36350 ,21751,20873,21752 ,0,0,0}, + {38219,38726,37448 ,21656,21730,21753 ,0,0,0}, {38223,36412,38611 ,21754,21755,21756 ,0,0,0}, + {36418,36420,38222 ,21757,21758,21710 ,0,0,0}, {36934,37054,38337 ,21759,21760,21761 ,0,0,0}, + {36934,38334,36411 ,21759,21762,21763 ,0,0,0}, {37057,37056,38613 ,21764,21765,21766 ,0,0,0}, + {38613,38335,37057 ,21766,21767,21764 ,0,0,0}, {38339,37056,36421 ,21768,21765,21769 ,0,0,0}, + {37056,38339,38613 ,21765,21768,21766 ,0,0,0}, {36423,38340,36421 ,21770,21771,21769 ,0,0,0}, + {38339,36421,38340 ,21768,21769,21771 ,0,0,0}, {36423,34766,2131 ,21770,21750,82 ,0,0,0}, + {2131,38340,36423 ,82,21771,21770 ,0,0,0}, {36412,38223,36420 ,21755,21754,21758 ,0,0,0}, + {37054,38335,38337 ,21760,21767,21761 ,0,0,0}, {37057,38335,37054 ,21764,21767,21760 ,0,0,0}, + {36350,38606,36351 ,21752,20873,21724 ,0,0,0}, {36411,38334,38611 ,21763,21762,21756 ,0,0,0}, + {36934,38337,38334 ,21759,21761,21762 ,0,0,0}, {36412,36411,38611 ,21755,21763,21756 ,0,0,0}, + {38222,36420,38223 ,21710,21758,21754 ,0,0,0}, {38624,36350,36418 ,21751,21752,21757 ,0,0,0}, + {36418,38222,38624 ,21757,21710,21751 ,0,0,0}, {38726,37334,37448 ,21730,21725,21753 ,0,0,0}, + {36351,38219,37448 ,21724,21656,21753 ,0,0,0}, {38606,38219,36351 ,20873,21656,21724 ,0,0,0}, + {34753,38607,2950 ,21585,21726,126 ,0,0,0}, {37334,38726,38607 ,21725,21730,21726 ,0,0,0}, + {34721,36955,37846 ,21585,17362,21699 ,0,0,0}, {37834,37833,36402 ,21772,21773,21774 ,0,0,0}, + {38215,37898,36954 ,21703,20903,21775 ,0,0,0}, {37841,37346,38218 ,21776,21777,21778 ,0,0,0}, + {36401,36398,38216 ,21779,21780,21710 ,0,0,0}, {36946,36408,38618 ,21781,21782,21783 ,0,0,0}, + {36946,38619,36947 ,21781,21784,21785 ,0,0,0}, {36409,37336,38221 ,21786,21787,21788 ,0,0,0}, + {38221,38620,36409 ,21788,21789,21786 ,0,0,0}, {38622,37336,37450 ,21790,21787,21791 ,0,0,0}, + {37336,38622,38221 ,21787,21790,21788 ,0,0,0}, {36937,38229,37450 ,21792,21793,21791 ,0,0,0}, + {38622,37450,38229 ,21790,21791,21793 ,0,0,0}, {36937,34735,34736 ,21792,19655,82 ,0,0,0}, + {34736,38229,36937 ,82,21793,21792 ,0,0,0}, {37346,37841,36398 ,21777,21776,21780 ,0,0,0}, + {36408,38620,38618 ,21782,21789,21783 ,0,0,0}, {36409,38620,36408 ,21786,21789,21782 ,0,0,0}, + {36402,37833,37337 ,21774,21773,21724 ,0,0,0}, {36947,38619,38218 ,21785,21784,21778 ,0,0,0}, + {36946,38618,38619 ,21781,21783,21784 ,0,0,0}, {37346,36947,38218 ,21777,21785,21778 ,0,0,0}, + {38216,36398,37841 ,21710,21780,21776 ,0,0,0}, {37834,36402,36401 ,21772,21774,21779 ,0,0,0}, + {36401,38216,37834 ,21779,21710,21772 ,0,0,0}, {37898,36955,36954 ,20903,17362,21775 ,0,0,0}, + {37337,38215,36954 ,21724,21703,21775 ,0,0,0}, {37833,38215,37337 ,21773,21703,21724 ,0,0,0}, + {34721,37846,34722 ,21585,21699,126 ,0,0,0}, {36955,37898,37846 ,17362,20903,21699 ,0,0,0}, + {34691,37358,38628 ,8383,17362,20947 ,0,0,0}, {38252,37751,36970 ,21794,21795,21796 ,0,0,0}, + {37762,38626,36590 ,21656,21797,21798 ,0,0,0}, {37724,37354,38631 ,21799,21800,21801 ,0,0,0}, + {36579,36580,38253 ,21802,21803,21804 ,0,0,0}, {37364,37363,37722 ,21662,21805,21806 ,0,0,0}, + {37364,37723,37353 ,21662,21807,21808 ,0,0,0}, {36532,36531,38271 ,21809,21810,21811 ,0,0,0}, + {38271,37721,36532 ,21811,21812,21809 ,0,0,0}, {38637,36531,36570 ,21813,21810,21814 ,0,0,0}, + {36531,38637,38271 ,21810,21813,21811 ,0,0,0}, {36572,38272,36570 ,21815,21816,21814 ,0,0,0}, + {38637,36570,38272 ,21813,21814,21816 ,0,0,0}, {36572,34704,3029 ,21815,2601,82 ,0,0,0}, + {3029,38272,36572 ,82,21816,21815 ,0,0,0}, {37354,37724,36580 ,21800,21799,21803 ,0,0,0}, + {37363,37721,37722 ,21805,21812,21806 ,0,0,0}, {36532,37721,37363 ,21809,21812,21805 ,0,0,0}, + {36970,37751,37348 ,21796,21795,21817 ,0,0,0}, {37353,37723,38631 ,21808,21807,21801 ,0,0,0}, + {37364,37722,37723 ,21662,21806,21807 ,0,0,0}, {37354,37353,38631 ,21800,21808,21801 ,0,0,0}, + {38253,36580,37724 ,21804,21803,21799 ,0,0,0}, {38252,36970,36579 ,21794,21796,21802 ,0,0,0}, + {36579,38253,38252 ,21802,21804,21794 ,0,0,0}, {38626,37358,36590 ,21797,17362,21798 ,0,0,0}, + {37348,37762,36590 ,21817,21656,21798 ,0,0,0}, {37751,37762,37348 ,21795,21656,21817 ,0,0,0}, + {34691,38628,3015 ,8383,20947,126 ,0,0,0}, {37358,38626,38628 ,17362,21797,20947 ,0,0,0}, + {34659,36597,38645 ,8383,21818,20947 ,0,0,0}, {38675,38644,36979 ,21819,21820,21821 ,0,0,0}, + {38260,38740,37457 ,21822,21823,21607 ,0,0,0}, {38263,36564,38268 ,21824,21825,21826 ,0,0,0}, + {36977,36976,38265 ,21611,21827,21828 ,0,0,0}, {36585,36974,38636 ,21686,21829,21830 ,0,0,0}, + {36585,38267,36584 ,21686,21831,21832 ,0,0,0}, {36973,36563,38269 ,21833,21834,21835 ,0,0,0}, + {38269,38635,36973 ,21835,21836,21833 ,0,0,0}, {37718,36563,37360 ,21837,21834,21838 ,0,0,0}, + {36563,37718,38269 ,21834,21837,21835 ,0,0,0}, {36574,37717,37360 ,21839,21840,21838 ,0,0,0}, + {37718,37360,37717 ,21837,21838,21840 ,0,0,0}, {36574,34673,34674 ,21839,2601,82 ,0,0,0}, + {34674,37717,36574 ,82,21840,21839 ,0,0,0}, {36564,38263,36976 ,21825,21824,21827 ,0,0,0}, + {36974,38635,38636 ,21829,21836,21830 ,0,0,0}, {36973,38635,36974 ,21833,21836,21829 ,0,0,0}, + {36979,38644,36980 ,21821,21820,21841 ,0,0,0}, {36584,38267,38268 ,21832,21831,21826 ,0,0,0}, + {36585,38636,38267 ,21686,21830,21831 ,0,0,0}, {36564,36584,38268 ,21825,21832,21826 ,0,0,0}, + {38265,36976,38263 ,21828,21827,21824 ,0,0,0}, {38675,36979,36977 ,21819,21821,21611 ,0,0,0}, + {36977,38265,38675 ,21611,21828,21819 ,0,0,0}, {38740,36597,37457 ,21823,21818,21607 ,0,0,0}, + {36980,38260,37457 ,21841,21822,21607 ,0,0,0}, {38644,38260,36980 ,21820,21822,21841 ,0,0,0}, + {34659,38645,34660 ,8383,20947,126 ,0,0,0}, {36597,38740,38645 ,21818,21823,20947 ,0,0,0}, + {34627,36547,37733 ,21842,21843,21844 ,0,0,0}, {37731,38656,36540 ,20948,21845,21796 ,0,0,0}, + {38655,38284,37388 ,21605,21846,21847 ,0,0,0}, {38734,37375,37685 ,21848,21849,21850 ,0,0,0}, + {36604,37454,38737 ,21802,21851,21852 ,0,0,0}, {37374,36546,38652 ,21662,21853,21854 ,0,0,0}, + {37374,38665,36548 ,21662,21855,21856 ,0,0,0}, {36542,37373,38651 ,21857,21858,21859 ,0,0,0}, + {38651,38653,36542 ,21859,21860,21857 ,0,0,0}, {37741,37373,37372 ,21861,21858,21862 ,0,0,0}, + {37373,37741,38651 ,21858,21861,21859 ,0,0,0}, {36605,38661,37372 ,21863,21864,21862 ,0,0,0}, + {37741,37372,38661 ,21861,21862,21864 ,0,0,0}, {36605,34641,34642 ,21863,21650,82 ,0,0,0}, + {34642,38661,36605 ,82,21864,21863 ,0,0,0}, {37375,38734,37454 ,21849,21848,21851 ,0,0,0}, + {36546,38653,38652 ,21853,21860,21854 ,0,0,0}, {36542,38653,36546 ,21857,21860,21853 ,0,0,0}, + {36540,38656,36541 ,21796,21845,21865 ,0,0,0}, {36548,38665,37685 ,21856,21855,21850 ,0,0,0}, + {37374,38652,38665 ,21662,21854,21855 ,0,0,0}, {37375,36548,37685 ,21849,21856,21850 ,0,0,0}, + {38737,37454,38734 ,21852,21851,21848 ,0,0,0}, {37731,36540,36604 ,20948,21796,21802 ,0,0,0}, + {36604,38737,37731 ,21802,21852,20948 ,0,0,0}, {38284,36547,37388 ,21846,21843,21847 ,0,0,0}, + {36541,38655,37388 ,21865,21605,21847 ,0,0,0}, {38656,38655,36541 ,21845,21605,21865 ,0,0,0}, + {34627,37733,34628 ,21842,21844,8383 ,0,0,0}, {36547,38284,37733 ,21843,21846,21844 ,0,0,0}, + {34597,36989,37690 ,2619,21818,21866 ,0,0,0}, {38255,38257,37385 ,21867,21868,21869 ,0,0,0}, + {37697,38663,36558 ,21870,20903,21607 ,0,0,0}, {37587,36987,38259 ,21871,21872,21873 ,0,0,0}, + {36961,36963,37589 ,21874,21875,21828 ,0,0,0}, {36556,37394,38647 ,21614,21876,21877 ,0,0,0}, + {36556,38646,36557 ,21614,21878,21879 ,0,0,0}, {37393,37395,38261 ,21880,21881,21882 ,0,0,0}, + {38261,37703,37393 ,21882,21883,21880 ,0,0,0}, {38640,37395,37458 ,21884,21881,21885 ,0,0,0}, + {37395,38640,38261 ,21881,21884,21882 ,0,0,0}, {36587,38641,37458 ,21886,21887,21885 ,0,0,0}, + {38640,37458,38641 ,21884,21885,21887 ,0,0,0}, {36587,34610,3063 ,21886,82,2602 ,0,0,0}, + {3063,38641,36587 ,2602,21887,21886 ,0,0,0}, {36987,37587,36963 ,21872,21871,21875 ,0,0,0}, + {37394,37703,38647 ,21876,21883,21877 ,0,0,0}, {37393,37703,37394 ,21880,21883,21876 ,0,0,0}, + {37385,38257,36560 ,21869,21868,21627 ,0,0,0}, {36557,38646,38259 ,21879,21878,21873 ,0,0,0}, + {36556,38647,38646 ,21614,21877,21878 ,0,0,0}, {36987,36557,38259 ,21872,21879,21873 ,0,0,0}, + {37589,36963,37587 ,21828,21875,21871 ,0,0,0}, {38255,37385,36961 ,21867,21869,21874 ,0,0,0}, + {36961,37589,38255 ,21874,21828,21867 ,0,0,0}, {38663,36989,36558 ,20903,21818,21607 ,0,0,0}, + {36560,37697,36558 ,21627,21870,21607 ,0,0,0}, {38257,37697,36560 ,21868,21870,21627 ,0,0,0}, + {34597,37690,3049 ,2619,21866,126 ,0,0,0}, {36989,38663,37690 ,21818,20903,21866 ,0,0,0}, + {34567,37040,38521 ,21492,17362,21726 ,0,0,0}, {38729,38683,36726 ,21888,21889,21890 ,0,0,0}, + {38679,38522,37041 ,21656,21730,21891 ,0,0,0}, {38693,37402,38682 ,21705,21892,21893 ,0,0,0}, + {36725,37451,38731 ,21894,21736,21895 ,0,0,0}, {37401,36718,38676 ,21896,21897,21713 ,0,0,0}, + {37401,38680,36729 ,21896,21898,21741 ,0,0,0}, {36712,37400,37594 ,21899,21900,21901 ,0,0,0}, + {37594,38677,36712 ,21901,21902,21899 ,0,0,0}, {37590,37400,37399 ,21903,21900,21904 ,0,0,0}, + {37400,37590,37594 ,21900,21903,21901 ,0,0,0}, {36197,38687,37399 ,21905,21906,21904 ,0,0,0}, + {37590,37399,38687 ,21903,21904,21906 ,0,0,0}, {36197,34580,2082 ,21905,21907,82 ,0,0,0}, + {2082,38687,36197 ,82,21906,21905 ,0,0,0}, {37402,38693,37451 ,21892,21705,21736 ,0,0,0}, + {36718,38677,38676 ,21897,21902,21713 ,0,0,0}, {36712,38677,36718 ,21899,21902,21897 ,0,0,0}, + {36726,38683,37404 ,21890,21889,21908 ,0,0,0}, {36729,38680,38682 ,21741,21898,21893 ,0,0,0}, + {37401,38676,38680 ,21896,21713,21898 ,0,0,0}, {37402,36729,38682 ,21892,21741,21893 ,0,0,0}, + {38731,37451,38693 ,21895,21736,21705 ,0,0,0}, {38729,36726,36725 ,21888,21890,21894 ,0,0,0}, + {36725,38731,38729 ,21894,21895,21888 ,0,0,0}, {38522,37040,37041 ,21730,17362,21891 ,0,0,0}, + {37404,38679,37041 ,21908,21656,21891 ,0,0,0}, {38683,38679,37404 ,21889,21656,21908 ,0,0,0}, + {34567,38521,1263 ,21492,21726,126 ,0,0,0}, {37040,38522,38521 ,17362,21730,21726 ,0,0,0}, + {34535,37039,38685 ,21492,17362,21726 ,0,0,0}, {37515,38289,37029 ,21909,21910,21911 ,0,0,0}, + {37572,37571,37038 ,21656,21730,21912 ,0,0,0}, {38292,37033,37561 ,21776,21913,21914 ,0,0,0}, + {37419,37034,38291 ,21915,21758,21895 ,0,0,0}, {36709,37435,38295 ,21916,21917,21783 ,0,0,0}, + {36709,38294,36708 ,21916,21918,21763 ,0,0,0}, {37016,37015,38695 ,21919,21920,21921 ,0,0,0}, + {38695,38694,37016 ,21921,21922,21919 ,0,0,0}, {38297,37015,37456 ,21923,21920,21924 ,0,0,0}, + {37015,38297,38695 ,21920,21923,21921 ,0,0,0}, {37411,37562,37456 ,21925,21926,21924 ,0,0,0}, + {38297,37456,37562 ,21923,21924,21926 ,0,0,0}, {37411,34549,34550 ,21925,21907,82 ,0,0,0}, + {34550,37562,37411 ,82,21926,21925 ,0,0,0}, {37033,38292,37034 ,21913,21776,21758 ,0,0,0}, + {37435,38694,38295 ,21917,21922,21783 ,0,0,0}, {37016,38694,37435 ,21919,21922,21917 ,0,0,0}, + {37029,38289,37420 ,21911,21910,21908 ,0,0,0}, {36708,38294,37561 ,21763,21918,21914 ,0,0,0}, + {36709,38295,38294 ,21916,21783,21918 ,0,0,0}, {37033,36708,37561 ,21913,21763,21914 ,0,0,0}, + {38291,37034,38292 ,21895,21758,21776 ,0,0,0}, {37515,37029,37419 ,21909,21911,21915 ,0,0,0}, + {37419,38291,37515 ,21915,21895,21909 ,0,0,0}, {37571,37039,37038 ,21730,17362,21912 ,0,0,0}, + {37420,37572,37038 ,21908,21656,21912 ,0,0,0}, {38289,37572,37420 ,21910,21656,21908 ,0,0,0}, + {34535,38685,34536 ,21492,21726,126 ,0,0,0}, {37039,37571,38685 ,17362,21730,21726 ,0,0,0}, + {34505,37436,37555 ,21492,17362,21726 ,0,0,0}, {38301,38300,36705 ,21909,21910,21911 ,0,0,0}, + {38708,38738,37455 ,21656,21927,21775 ,0,0,0}, {37510,36698,37547 ,21776,21913,21928 ,0,0,0}, + {36707,37413,37512 ,21915,21929,21930 ,0,0,0}, {36697,36692,38309 ,21916,21931,21932 ,0,0,0}, + {36697,37548,36695 ,21916,21933,21934 ,0,0,0}, {36694,37012,38311 ,21764,21935,21936 ,0,0,0}, + {38311,38699,36694 ,21936,21937,21764 ,0,0,0}, {37567,37012,37421 ,21938,21935,21939 ,0,0,0}, + {37012,37567,38311 ,21935,21938,21936 ,0,0,0}, {37008,37568,37421 ,21940,21941,21939 ,0,0,0}, + {37567,37421,37568 ,21938,21939,21941 ,0,0,0}, {37008,34518,2073 ,21940,19633,82 ,0,0,0}, + {2073,37568,37008 ,82,21941,21940 ,0,0,0}, {36698,37510,37413 ,21913,21776,21929 ,0,0,0}, + {36692,38699,38309 ,21931,21937,21932 ,0,0,0}, {36694,38699,36692 ,21764,21937,21931 ,0,0,0}, + {36705,38300,37014 ,21911,21910,21627 ,0,0,0}, {36695,37548,37547 ,21934,21933,21928 ,0,0,0}, + {36697,38309,37548 ,21916,21932,21933 ,0,0,0}, {36698,36695,37547 ,21913,21934,21928 ,0,0,0}, + {37512,37413,37510 ,21930,21929,21776 ,0,0,0}, {38301,36705,36707 ,21909,21911,21915 ,0,0,0}, + {36707,37512,38301 ,21915,21930,21909 ,0,0,0}, {38738,37436,37455 ,21927,17362,21775 ,0,0,0}, + {37014,38708,37455 ,21627,21656,21775 ,0,0,0}, {38300,38708,37014 ,21910,21656,21627 ,0,0,0}, + {34505,37555,1297 ,21492,21726,126 ,0,0,0}, {37436,38738,37555 ,17362,21927,21726 ,0,0,0}, + {34473,37443,38716 ,21492,17362,21726 ,0,0,0}, {37504,37586,36702 ,21888,21889,21890 ,0,0,0}, + {37527,37526,36703 ,21656,21927,21704 ,0,0,0}, {37569,37439,38704 ,21705,21892,21942 ,0,0,0}, + {36258,36257,37505 ,21894,21943,21930 ,0,0,0}, {37438,37437,37580 ,21896,21944,21945 ,0,0,0}, + {37438,38718,37440 ,21896,21946,21947 ,0,0,0}, {37002,37001,37531 ,21742,21948,21949 ,0,0,0}, + {37531,38719,37002 ,21949,21950,21742 ,0,0,0}, {37532,37001,37004 ,21951,21948,21952 ,0,0,0}, + {37001,37532,37531 ,21948,21951,21949 ,0,0,0}, {37426,37538,37004 ,21953,21954,21952 ,0,0,0}, + {37532,37004,37538 ,21951,21952,21954 ,0,0,0}, {37426,34487,34488 ,21953,19633,82 ,0,0,0}, + {34488,37538,37426 ,82,21954,21953 ,0,0,0}, {37439,37569,36257 ,21892,21705,21943 ,0,0,0}, + {37437,38719,37580 ,21944,21950,21945 ,0,0,0}, {37002,38719,37437 ,21742,21950,21944 ,0,0,0}, + {36702,37586,36701 ,21890,21889,21627 ,0,0,0}, {37440,38718,38704 ,21947,21946,21942 ,0,0,0}, + {37438,37580,38718 ,21896,21945,21946 ,0,0,0}, {37439,37440,38704 ,21892,21947,21942 ,0,0,0}, + {37505,36257,37569 ,21930,21943,21705 ,0,0,0}, {37504,36702,36258 ,21888,21890,21894 ,0,0,0}, + {36258,37505,37504 ,21894,21930,21888 ,0,0,0}, {37526,37443,36703 ,21927,17362,21704 ,0,0,0}, + {36701,37527,36703 ,21627,21656,21704 ,0,0,0}, {37586,37527,36701 ,21889,21656,21627 ,0,0,0}, + {34473,38716,34474 ,21492,21726,126 ,0,0,0}, {37443,37526,38716 ,17362,21927,21726 ,0,0,0}, + {37820,12921,37821 ,21955,21956,18609 ,0,0,0}, {37820,34442,12921 ,21955,18573,21956 ,0,0,0}, + {34442,37820,34441 ,18573,21955,18573 ,0,0,0}, {37327,37821,12921 ,18609,18609,21956 ,0,0,0}, + {34449,38241,36395 ,18594,21957,21957 ,0,0,0}, {38578,36355,37863 ,21958,21958,21959 ,0,0,0}, + {36396,36914,37868 ,21959,21960,21960 ,0,0,0}, {37865,37327,37324 ,21961,18609,21961 ,0,0,0}, + {37324,38578,37865 ,21961,21958,21961 ,0,0,0}, {37821,37327,37865 ,18609,18609,21961 ,0,0,0}, + {37324,36355,38578 ,21961,21958,21958 ,0,0,0}, {36396,37863,36355 ,21959,21959,21958 ,0,0,0}, + {37863,36396,37868 ,21959,21959,21960 ,0,0,0}, {36395,34450,34449 ,21957,18594,18594 ,0,0,0}, + {38241,36914,36395 ,21957,21960,21957 ,0,0,0}, {37868,36914,38241 ,21960,21960,21957 ,0,0,0}, + {38325,34455,37313 ,21962,18581,21963 ,0,0,0}, {34455,34456,37313 ,18581,18581,21963 ,0,0,0}, + {36363,38325,37313 ,18601,21962,21963 ,0,0,0}, {38325,36363,38595 ,21962,18601,18601 ,0,0,0}, + {34435,37876,36392 ,18588,21964,21964 ,0,0,0}, {37875,36389,38594 ,21965,21965,21966 ,0,0,0}, + {36916,37331,38592 ,21966,21967,21967 ,0,0,0}, {38596,36363,36362 ,21968,18601,21968 ,0,0,0}, + {36362,37875,38596 ,21968,21965,21968 ,0,0,0}, {38595,36363,38596 ,18601,18601,21968 ,0,0,0}, + {36362,36389,37875 ,21968,21965,21965 ,0,0,0}, {36916,38594,36389 ,21966,21966,21965 ,0,0,0}, + {38594,36916,38592 ,21966,21966,21967 ,0,0,0}, {36392,34436,34435 ,21964,18588,18588 ,0,0,0}, + {37876,37331,36392 ,21964,21967,21964 ,0,0,0}, {38592,37331,37876 ,21967,21967,21964 ,0,0,0}, + {37857,36372,37851 ,21969,21970,18594 ,0,0,0}, {37857,34414,36372 ,21969,18575,21970 ,0,0,0}, + {34414,37857,34413 ,18575,21969,18575 ,0,0,0}, {36380,37851,36372 ,18594,18594,21970 ,0,0,0}, + {34421,38616,36959 ,18581,21971,21971 ,0,0,0}, {37854,36377,37855 ,21972,21972,21973 ,0,0,0}, + {36366,36358,38213 ,21973,21974,21974 ,0,0,0}, {37891,36380,36378 ,21975,18594,21975 ,0,0,0}, + {36378,37854,37891 ,21975,21972,21975 ,0,0,0}, {37851,36380,37891 ,18594,18594,21975 ,0,0,0}, + {36378,36377,37854 ,21975,21972,21972 ,0,0,0}, {36366,37855,36377 ,21973,21973,21972 ,0,0,0}, + {37855,36366,38213 ,21973,21973,21974 ,0,0,0}, {36959,34422,34421 ,21971,18581,18581 ,0,0,0}, + {38616,36358,36959 ,21971,21974,21971 ,0,0,0}, {38213,36358,38616 ,21974,21974,21971 ,0,0,0}, + {38724,34427,37343 ,21976,18583,82 ,0,0,0}, {34427,34428,37343 ,18583,18583,82 ,0,0,0}, + {37342,38724,37343 ,18588,21976,82 ,0,0,0}, {38724,37342,37870 ,21976,18588,18588 ,0,0,0}, + {34407,38586,37320 ,18573,21977,21977 ,0,0,0}, {38588,36958,37829 ,21978,21978,21979 ,0,0,0}, + {36384,36386,37889 ,21979,21980,21980 ,0,0,0}, {37869,37342,36359 ,21981,18588,21981 ,0,0,0}, + {36359,38588,37869 ,21981,21978,21981 ,0,0,0}, {37870,37342,37869 ,18588,18588,21981 ,0,0,0}, + {36359,36958,38588 ,21981,21978,21978 ,0,0,0}, {36384,37829,36958 ,21979,21979,21978 ,0,0,0}, + {37829,36384,37889 ,21979,21979,21980 ,0,0,0}, {37320,34408,34407 ,21977,18573,18573 ,0,0,0}, + {38586,36386,37320 ,21977,21980,21977 ,0,0,0}, {37889,36386,38586 ,21980,21980,21977 ,0,0,0}, + {2303,12820,38603 ,21982,21983,18581 ,0,0,0}, {2303,34386,12820 ,21982,18601,21983 ,0,0,0}, + {34386,2303,34385 ,18601,21982,18601 ,0,0,0}, {36406,38603,12820 ,18581,18581,21983 ,0,0,0}, + {34393,38623,36419 ,18583,21984,21984 ,0,0,0}, {38610,36943,38327 ,21985,21985,21986 ,0,0,0}, + {36410,36913,38224 ,21986,21987,21987 ,0,0,0}, {38329,36406,36944 ,21988,18581,21988 ,0,0,0}, + {36944,38610,38329 ,21988,21985,21988 ,0,0,0}, {38603,36406,38329 ,18581,18581,21988 ,0,0,0}, + {36944,36943,38610 ,21988,21985,21985 ,0,0,0}, {36410,38327,36943 ,21986,21986,21985 ,0,0,0}, + {38327,36410,38224 ,21986,21986,21987 ,0,0,0}, {36419,34394,34393 ,21984,18583,18583 ,0,0,0}, + {38623,36913,36419 ,21984,21987,21984 ,0,0,0}, {38224,36913,38623 ,21987,21987,21984 ,0,0,0}, + {37849,34399,37051 ,21989,18609,21990 ,0,0,0}, {34399,34400,37051 ,18609,18609,21990 ,0,0,0}, + {36416,37849,37051 ,18573,21989,21990 ,0,0,0}, {37849,36416,37847 ,21989,18573,18573 ,0,0,0}, + {34379,38220,37344 ,18575,21991,21991 ,0,0,0}, {37831,36941,37838 ,21992,21992,21993 ,0,0,0}, + {36414,36413,37837 ,21993,21994,21994 ,0,0,0}, {37894,36416,36415 ,21995,18573,21996 ,0,0,0}, + {36415,37831,37894 ,21996,21992,21995 ,0,0,0}, {37847,36416,37894 ,18573,18573,21995 ,0,0,0}, + {36415,36941,37831 ,21996,21992,21992 ,0,0,0}, {36414,37838,36941 ,21993,21993,21992 ,0,0,0}, + {37838,36414,37837 ,21993,21993,21994 ,0,0,0}, {37344,34380,34379 ,21991,18575,18575 ,0,0,0}, + {38220,36413,37344 ,21991,21994,21991 ,0,0,0}, {37837,36413,38220 ,21994,21994,21991 ,0,0,0}, + {38509,37347,37756 ,21997,21998,18609 ,0,0,0}, {38509,34358,37347 ,21997,18573,21998 ,0,0,0}, + {34358,38509,34357 ,18573,21997,18573 ,0,0,0}, {37239,37756,37347 ,18609,18609,21998 ,0,0,0}, + {34365,37747,36960 ,18594,18610,18610 ,0,0,0}, {38728,37237,38277 ,21999,21999,22000 ,0,0,0}, + {37242,37371,38278 ,22000,22001,22001 ,0,0,0}, {37738,37239,36593 ,22002,18609,22002 ,0,0,0}, + {36593,38728,37738 ,22002,21999,22002 ,0,0,0}, {37756,37239,37738 ,18609,18609,22002 ,0,0,0}, + {36593,37237,38728 ,22002,21999,21999 ,0,0,0}, {37242,38277,37237 ,22000,22000,21999 ,0,0,0}, + {38277,37242,38278 ,22000,22000,22001 ,0,0,0}, {36960,34366,34365 ,18610,18594,18594 ,0,0,0}, + {37747,37371,36960 ,18610,22001,18610 ,0,0,0}, {38278,37371,37747 ,22001,22001,18610 ,0,0,0}, + {38625,34371,37370 ,22003,18581,22004 ,0,0,0}, {34371,34372,37370 ,18581,18581,22004 ,0,0,0}, + {36967,38625,37370 ,18601,22003,22004 ,0,0,0}, {38625,36967,38274 ,22003,18601,18601 ,0,0,0}, + {34351,38630,36529 ,18588,22005,22005 ,0,0,0}, {37761,36589,38629 ,22006,22006,22007 ,0,0,0}, + {36588,37359,38627 ,22007,22008,22008 ,0,0,0}, {38275,36967,36968 ,22009,18601,22009 ,0,0,0}, + {36968,37761,38275 ,22009,22006,22009 ,0,0,0}, {38274,36967,38275 ,18601,18601,22009 ,0,0,0}, + {36968,36589,37761 ,22009,22006,22006 ,0,0,0}, {36588,38629,36589 ,22007,22007,22006 ,0,0,0}, + {38629,36588,38627 ,22007,22007,22008 ,0,0,0}, {36529,34352,34351 ,22005,18588,18588 ,0,0,0}, + {38630,37359,36529 ,22005,22008,22005 ,0,0,0}, {38627,37359,38630 ,22008,22008,22005 ,0,0,0}, + {37581,37406,37574 ,22010,22011,18594 ,0,0,0}, {37581,34330,37406 ,22010,18575,22011 ,0,0,0}, + {34330,37581,34329 ,18575,22010,18575 ,0,0,0}, {37407,37574,37406 ,18594,18594,22011 ,0,0,0}, + {34337,38684,36723 ,18581,22012,22012 ,0,0,0}, {37577,37405,37596 ,22013,22013,22014 ,0,0,0}, + {36731,36724,37597 ,22014,22015,22015 ,0,0,0}, {37575,37407,36722 ,22016,18594,22016 ,0,0,0}, + {36722,37577,37575 ,22016,22013,22016 ,0,0,0}, {37574,37407,37575 ,18594,18594,22016 ,0,0,0}, + {36722,37405,37577 ,22016,22013,22013 ,0,0,0}, {36731,37596,37405 ,22014,22014,22013 ,0,0,0}, + {37596,36731,37597 ,22014,22014,22015 ,0,0,0}, {36723,34338,34337 ,22012,18581,18581 ,0,0,0}, + {38684,36724,36723 ,22012,22015,22012 ,0,0,0}, {37597,36724,38684 ,22015,22015,22012 ,0,0,0}, + {38730,34343,37409 ,22017,18583,22018 ,0,0,0}, {34343,34344,37409 ,18583,18583,22018 ,0,0,0}, + {37408,38730,37409 ,18588,22017,22018 ,0,0,0}, {38730,37408,38317 ,22017,18588,18588 ,0,0,0}, + {34323,38692,37403 ,18573,22019,22019 ,0,0,0}, {38686,37035,38681 ,22020,22020,22021 ,0,0,0}, + {36728,36727,38691 ,22021,22022,22022 ,0,0,0}, {38318,37408,37036 ,22023,18588,22023 ,0,0,0}, + {37036,38686,38318 ,22023,22020,22023 ,0,0,0}, {38317,37408,38318 ,18588,18588,22023 ,0,0,0}, + {37036,37035,38686 ,22023,22020,22020 ,0,0,0}, {36728,38681,37035 ,22021,22021,22020 ,0,0,0}, + {38681,36728,38691 ,22021,22021,22022 ,0,0,0}, {37403,34324,34323 ,22019,18573,18573 ,0,0,0}, + {38692,36727,37403 ,22019,22022,22019 ,0,0,0}, {38691,36727,38692 ,22022,22022,22019 ,0,0,0}, + {38013,36872,37994 ,22024,22025,18581 ,0,0,0}, {38013,34302,36872 ,22024,18601,22025 ,0,0,0}, + {34302,38013,34301 ,18601,22024,18601 ,0,0,0}, {37224,37994,36872 ,18581,18581,22025 ,0,0,0}, + {34309,38546,37273 ,18583,22026,22026 ,0,0,0}, {38732,37226,37474 ,22027,22027,22028 ,0,0,0}, + {37217,37274,37475 ,22028,22029,22029 ,0,0,0}, {38563,37224,36904 ,22030,18581,22030 ,0,0,0}, + {36904,38732,38563 ,22030,22027,22030 ,0,0,0}, {37994,37224,38563 ,18581,18581,22030 ,0,0,0}, + {36904,37226,38732 ,22030,22027,22027 ,0,0,0}, {37217,37474,37226 ,22028,22028,22027 ,0,0,0}, + {37474,37217,37475 ,22028,22028,22029 ,0,0,0}, {37273,34310,34309 ,22026,18583,18583 ,0,0,0}, + {38546,37274,37273 ,22026,22029,22026 ,0,0,0}, {37475,37274,38546 ,22029,22029,22026 ,0,0,0}, + {38010,34315,36893 ,22031,18609,22032 ,0,0,0}, {34315,34316,36893 ,18609,18609,22032 ,0,0,0}, + {36884,38010,36893 ,18573,22031,22032 ,0,0,0}, {38010,36884,38011 ,22031,18573,18573 ,0,0,0}, + {34295,37996,36302 ,18575,22033,22033 ,0,0,0}, {38005,36898,38488 ,22034,22034,22035 ,0,0,0}, + {37225,37268,38489 ,22035,22036,22036 ,0,0,0}, {38183,36884,36883 ,22037,18573,22037 ,0,0,0}, + {36883,38005,38183 ,22037,22034,22037 ,0,0,0}, {38011,36884,38183 ,18573,18573,22037 ,0,0,0}, + {36883,36898,38005 ,22037,22034,22034 ,0,0,0}, {37225,38488,36898 ,22035,22035,22034 ,0,0,0}, + {38488,37225,38489 ,22035,22035,22036 ,0,0,0}, {36302,34296,34295 ,22033,18575,18575 ,0,0,0}, + {37996,37268,36302 ,22033,22036,22033 ,0,0,0}, {38489,37268,37996 ,22036,22036,22033 ,0,0,0}, + {37689,36545,37725 ,22038,22039,18594 ,0,0,0}, {37689,34274,36545 ,22038,18575,22039 ,0,0,0}, + {34274,37689,34273 ,18575,22038,18575 ,0,0,0}, {37380,37725,36545 ,18594,18594,22039 ,0,0,0}, + {34281,38658,36553 ,18581,22040,22040 ,0,0,0}, {38666,36991,38669 ,22041,22041,22042 ,0,0,0}, + {36551,36554,37728 ,22042,22043,22043 ,0,0,0}, {37593,37380,37377 ,22044,18594,22044 ,0,0,0}, + {37377,38666,37593 ,22044,22041,22044 ,0,0,0}, {37725,37380,37593 ,18594,18594,22044 ,0,0,0}, + {37377,36991,38666 ,22044,22041,22041 ,0,0,0}, {36551,38669,36991 ,22042,22042,22041 ,0,0,0}, + {38669,36551,37728 ,22042,22042,22043 ,0,0,0}, {36553,34282,34281 ,22040,18581,18581 ,0,0,0}, + {38658,36554,36553 ,22040,22043,22040 ,0,0,0}, {37728,36554,38658 ,22043,22043,22040 ,0,0,0}, + {38736,34287,37390 ,22045,18583,22046 ,0,0,0}, {34287,34288,37390 ,18583,18583,22046 ,0,0,0}, + {37389,38736,37390 ,18588,22045,22046 ,0,0,0}, {38736,37389,38280 ,22045,18588,18588 ,0,0,0}, + {34267,37730,37376 ,18573,22047,22047 ,0,0,0}, {38660,36990,37686 ,22048,22048,22049 ,0,0,0}, + {36550,36549,37684 ,22049,22050,22050 ,0,0,0}, {38279,37389,36539 ,22051,18588,22051 ,0,0,0}, + {36539,38660,38279 ,22051,22048,22051 ,0,0,0}, {38280,37389,38279 ,18588,18588,22051 ,0,0,0}, + {36539,36990,38660 ,22051,22048,22048 ,0,0,0}, {36550,37686,36990 ,22049,22049,22048 ,0,0,0}, + {37686,36550,37684 ,22049,22049,22050 ,0,0,0}, {37376,34268,34267 ,22047,18573,18573 ,0,0,0}, + {37730,36549,37376 ,22047,22050,22047 ,0,0,0}, {37684,36549,37730 ,22050,22050,22047 ,0,0,0}, + {38303,37023,38305 ,22052,22053,18581 ,0,0,0}, {38303,34246,37023 ,22052,18601,22053 ,0,0,0}, + {34246,38303,34245 ,18601,22052,18601 ,0,0,0}, {37415,38305,37023 ,18581,18581,22053 ,0,0,0}, + {34253,38299,36706 ,18583,22054,22054 ,0,0,0}, {37582,37433,37560 ,22055,22055,22056 ,0,0,0}, + {36700,36699,37511 ,22056,22057,22057 ,0,0,0}, {38307,37415,37021 ,22058,18581,22058 ,0,0,0}, + {37021,37582,38307 ,22058,22055,22058 ,0,0,0}, {38305,37415,38307 ,18581,18581,22058 ,0,0,0}, + {37021,37433,37582 ,22058,22055,22055 ,0,0,0}, {36700,37560,37433 ,22056,22056,22055 ,0,0,0}, + {37560,36700,37511 ,22056,22056,22057 ,0,0,0}, {36706,34254,34253 ,22054,18583,18583 ,0,0,0}, + {38299,36699,36706 ,22054,22057,22054 ,0,0,0}, {37511,36699,38299 ,22057,22057,22054 ,0,0,0}, + {37543,34259,36262 ,22059,18609,21990 ,0,0,0}, {34259,34260,36262 ,18609,18609,21990 ,0,0,0}, + {36995,37543,36262 ,18573,22059,21990 ,0,0,0}, {37543,36995,37523 ,22059,18573,18573 ,0,0,0}, + {34239,38298,37412 ,18575,22060,22060 ,0,0,0}, {37541,36251,38707 ,22061,22061,22062 ,0,0,0}, + {37410,37017,37563 ,22062,22063,22063 ,0,0,0}, {37524,36995,36997 ,22064,18573,22065 ,0,0,0}, + {36997,37541,37524 ,22065,22061,22064 ,0,0,0}, {37523,36995,37524 ,18573,18573,22064 ,0,0,0}, + {36997,36251,37541 ,22065,22061,22061 ,0,0,0}, {37410,38707,36251 ,22062,22062,22061 ,0,0,0}, + {38707,37410,37563 ,22062,22062,22063 ,0,0,0}, {37412,34240,34239 ,22060,18575,18575 ,0,0,0}, + {38298,37017,37412 ,22060,22063,22060 ,0,0,0}, {37563,37017,38298 ,22063,22063,22060 ,0,0,0}, + {38199,36296,38197 ,22066,22067,18583 ,0,0,0}, {38199,34218,36296 ,22066,18588,22067 ,0,0,0}, + {34218,38199,34217 ,18588,22066,18588 ,0,0,0}, {36873,38197,36296 ,18583,18583,22067 ,0,0,0}, + {34225,38554,37287 ,18609,22068,22068 ,0,0,0}, {38201,36879,37984 ,22069,22069,22070 ,0,0,0}, + {37303,37288,37985 ,22070,20861,20861 ,0,0,0}, {38200,36873,36875 ,22071,18583,22071 ,0,0,0}, + {36875,38201,38200 ,22071,22069,22071 ,0,0,0}, {38197,36873,38200 ,18583,18583,22071 ,0,0,0}, + {36875,36879,38201 ,22071,22069,22069 ,0,0,0}, {37303,37984,36879 ,22070,22070,22069 ,0,0,0}, + {37984,37303,37985 ,22070,22070,20861 ,0,0,0}, {37287,34226,34225 ,22068,18609,18609 ,0,0,0}, + {38554,37288,37287 ,22068,20861,22068 ,0,0,0}, {37985,37288,38554 ,20861,20861,22068 ,0,0,0}, + {38739,34231,37310 ,22072,18594,22073 ,0,0,0}, {34231,34232,37310 ,18594,18594,22073 ,0,0,0}, + {37309,38739,37310 ,18575,22072,22073 ,0,0,0}, {38739,37309,38002 ,22072,18575,18575 ,0,0,0}, + {34211,38552,36231 ,18601,22074,18635 ,0,0,0}, {37992,36240,37556 ,22075,22075,22076 ,0,0,0}, + {36233,36882,37557 ,22076,22077,22077 ,0,0,0}, {37991,37309,36238 ,22078,18575,22078 ,0,0,0}, + {36238,37992,37991 ,22078,22075,22078 ,0,0,0}, {38002,37309,37991 ,18575,18575,22078 ,0,0,0}, + {36238,36240,37992 ,22078,22075,22075 ,0,0,0}, {36233,37556,36240 ,22076,22076,22075 ,0,0,0}, + {37556,36233,37557 ,22076,22076,22077 ,0,0,0}, {36231,34212,34211 ,18635,18601,18601 ,0,0,0}, + {38552,36882,36231 ,22074,22077,18635 ,0,0,0}, {37557,36882,38552 ,22077,22077,22074 ,0,0,0}, + {37708,36537,37711 ,22079,22080,18581 ,0,0,0}, {37708,34190,36537 ,22079,18601,22080 ,0,0,0}, + {34190,37708,34189 ,18601,22079,18601 ,0,0,0}, {36538,37711,36537 ,18581,18581,22080 ,0,0,0}, + {34197,38674,36975 ,18583,22081,22081 ,0,0,0}, {37712,36982,38266 ,22082,22082,22083 ,0,0,0}, + {36561,36565,38264 ,22083,18670,18670 ,0,0,0}, {38650,36538,36983 ,22084,18581,22084 ,0,0,0}, + {36983,37712,38650 ,22084,22082,22084 ,0,0,0}, {37711,36538,38650 ,18581,18581,22084 ,0,0,0}, + {36983,36982,37712 ,22084,22082,22082 ,0,0,0}, {36561,38266,36982 ,22083,22083,22082 ,0,0,0}, + {38266,36561,38264 ,22083,22083,18670 ,0,0,0}, {36975,34198,34197 ,22081,18583,18583 ,0,0,0}, + {38674,36565,36975 ,22081,18670,22081 ,0,0,0}, {38264,36565,38674 ,18670,18670,22081 ,0,0,0}, + {37715,34203,36576 ,22085,18609,324 ,0,0,0}, {34203,34204,36576 ,18609,18609,324 ,0,0,0}, + {36966,37715,36576 ,18573,22085,324 ,0,0,0}, {37715,36966,37695 ,22085,18573,18573 ,0,0,0}, + {34183,38262,37392 ,18575,22086,22086 ,0,0,0}, {37683,36981,38642 ,22087,22087,22088 ,0,0,0}, + {36978,36586,38643 ,22088,22089,22089 ,0,0,0}, {37693,36966,36965 ,22090,18573,22090 ,0,0,0}, + {36965,37683,37693 ,22090,22087,22090 ,0,0,0}, {37695,36966,37693 ,18573,18573,22090 ,0,0,0}, + {36965,36981,37683 ,22090,22087,22087 ,0,0,0}, {36978,38642,36981 ,22088,22088,22087 ,0,0,0}, + {38642,36978,38643 ,22088,22088,22089 ,0,0,0}, {37392,34184,34183 ,22086,18575,18575 ,0,0,0}, + {38262,36586,37392 ,22086,22089,22086 ,0,0,0}, {38643,36586,38262 ,22089,22089,22086 ,0,0,0}, + {37520,37005,37521 ,22091,22092,18583 ,0,0,0}, {37520,34162,37005 ,22091,18588,22092 ,0,0,0}, + {34162,37520,34161 ,18588,22091,18588 ,0,0,0}, {36683,37521,37005 ,18583,18583,22092 ,0,0,0}, + {34169,37533,37003 ,18609,22093,22093 ,0,0,0}, {38287,37428,38722 ,22094,22094,22095 ,0,0,0}, + {36685,37427,37539 ,22095,22096,22096 ,0,0,0}, {38721,36683,36684 ,22097,18583,22097 ,0,0,0}, + {36684,38287,38721 ,22097,22094,22097 ,0,0,0}, {37521,36683,38721 ,18583,18583,22097 ,0,0,0}, + {36684,37428,38287 ,22097,22094,22094 ,0,0,0}, {36685,38722,37428 ,22095,22095,22094 ,0,0,0}, + {38722,36685,37539 ,22095,22095,22096 ,0,0,0}, {37003,34170,34169 ,22093,18609,18609 ,0,0,0}, + {37533,37427,37003 ,22093,22096,22093 ,0,0,0}, {37539,37427,37533 ,22096,22096,22093 ,0,0,0}, + {38741,34175,37442 ,22098,18594,126 ,0,0,0}, {34175,34176,37442 ,18594,18594,126 ,0,0,0}, + {37441,38741,37442 ,18575,22098,126 ,0,0,0}, {38741,37441,37509 ,22098,18575,18575 ,0,0,0}, + {34155,38313,36682 ,18601,18635,18635 ,0,0,0}, {37518,36263,38703 ,22099,22099,22100 ,0,0,0}, + {37423,37424,38720 ,22100,22101,22101 ,0,0,0}, {37507,37441,36186 ,22102,18575,22102 ,0,0,0}, + {36186,37518,37507 ,22102,22099,22102 ,0,0,0}, {37509,37441,37507 ,18575,18575,22102 ,0,0,0}, + {36186,36263,37518 ,22102,22099,22099 ,0,0,0}, {37423,38703,36263 ,22100,22100,22099 ,0,0,0}, + {38703,37423,38720 ,22100,22100,22101 ,0,0,0}, {36682,34156,34155 ,18635,18601,18601 ,0,0,0}, + {38313,37424,36682 ,18635,22101,18635 ,0,0,0}, {38720,37424,38313 ,22101,22101,18635 ,0,0,0}, + {37970,36281,37971 ,22103,22104,18609 ,0,0,0}, {37970,34134,36281 ,22103,18573,22104 ,0,0,0}, + {34134,37970,34133 ,18573,22103,18573 ,0,0,0}, {36280,37971,36281 ,18609,18609,22104 ,0,0,0}, + {34141,38181,36876 ,18594,18653,18653 ,0,0,0}, {38210,36230,38208 ,22105,22105,22106 ,0,0,0}, + {36270,36249,37973 ,22106,22107,22107 ,0,0,0}, {38528,36280,36229 ,22108,18609,22108 ,0,0,0}, + {36229,38210,38528 ,22108,22105,22108 ,0,0,0}, {37971,36280,38528 ,18609,18609,22108 ,0,0,0}, + {36229,36230,38210 ,22108,22105,22105 ,0,0,0}, {36270,38208,36230 ,22106,22106,22105 ,0,0,0}, + {38208,36270,37973 ,22106,22106,22107 ,0,0,0}, {36876,34142,34141 ,18653,18594,18594 ,0,0,0}, + {38181,36249,36876 ,18653,22107,18653 ,0,0,0}, {37973,36249,38181 ,22107,22107,18653 ,0,0,0}, + {37976,34147,36264 ,22109,18581,22110 ,0,0,0}, {34147,34148,36264 ,18581,18581,22110 ,0,0,0}, + {36220,37976,36264 ,18601,22109,22110 ,0,0,0}, {37976,36220,37534 ,22109,18601,18601 ,0,0,0}, + {34127,38205,36248 ,18588,22111,22111 ,0,0,0}, {37550,36221,38569 ,22112,22112,22113 ,0,0,0}, + {36277,37312,38567 ,22113,22114,22114 ,0,0,0}, {37535,36220,36219 ,22115,18601,22115 ,0,0,0}, + {36219,37550,37535 ,22115,22112,22115 ,0,0,0}, {37534,36220,37535 ,18601,18601,22115 ,0,0,0}, + {36219,36221,37550 ,22115,22112,22112 ,0,0,0}, {36277,38569,36221 ,22113,22113,22112 ,0,0,0}, + {38569,36277,38567 ,22113,22113,22114 ,0,0,0}, {36248,34128,34127 ,22111,18588,18588 ,0,0,0}, + {38205,37312,36248 ,22111,22114,22111 ,0,0,0}, {38567,37312,38205 ,22114,22114,22111 ,0,0,0}, + {3171,36568,37746 ,22116,22117,18583 ,0,0,0}, {3171,34106,36568 ,22116,18588,22117 ,0,0,0}, + {34106,3171,34105 ,18588,22116,18588 ,0,0,0}, {36567,37746,36568 ,18583,18583,22117 ,0,0,0}, + {34113,38638,37351 ,18609,18683,18683 ,0,0,0}, {38254,37365,38634 ,22118,22118,22119 ,0,0,0}, + {36971,36571,38273 ,22119,22120,22120 ,0,0,0}, {38633,36567,36972 ,22121,18583,22121 ,0,0,0}, + {36972,38254,38633 ,22121,22118,22121 ,0,0,0}, {37746,36567,38633 ,18583,18583,22121 ,0,0,0}, + {36972,37365,38254 ,22121,22118,22118 ,0,0,0}, {36971,38634,37365 ,22119,22119,22118 ,0,0,0}, + {38634,36971,38273 ,22119,22119,22120 ,0,0,0}, {37351,34114,34113 ,18683,18609,18609 ,0,0,0}, + {38638,36571,37351 ,18683,22120,18683 ,0,0,0}, {38273,36571,38638 ,22120,22120,18683 ,0,0,0}, + {38742,34119,37357 ,22122,18594,22073 ,0,0,0}, {34119,34120,37357 ,18594,18594,22073 ,0,0,0}, + {37356,38742,37357 ,18575,22122,22073 ,0,0,0}, {38742,37356,37700 ,22122,18575,18575 ,0,0,0}, + {34099,38270,37361 ,18601,22123,22124 ,0,0,0}, {37705,37362,37720 ,22125,22125,22076 ,0,0,0}, + {36530,36566,38632 ,22076,22126,22126 ,0,0,0}, {37704,37356,36581 ,22127,18575,22127 ,0,0,0}, + {36581,37705,37704 ,22127,22125,22127 ,0,0,0}, {37700,37356,37704 ,18575,18575,22127 ,0,0,0}, + {36581,37362,37705 ,22127,22125,22125 ,0,0,0}, {36530,37720,37362 ,22076,22076,22125 ,0,0,0}, + {37720,36530,38632 ,22076,22076,22126 ,0,0,0}, {37361,34100,34099 ,22124,18601,18601 ,0,0,0}, + {38270,36566,37361 ,22123,22126,22124 ,0,0,0}, {38632,36566,38270 ,22126,22126,22123 ,0,0,0}, + {1435,36246,38315 ,22128,22129,18609 ,0,0,0}, {1435,34078,36246 ,22128,18573,22129 ,0,0,0}, + {34078,1435,34077 ,18573,22128,18573 ,0,0,0}, {36247,38315,36246 ,18609,18609,22129 ,0,0,0}, + {34085,38288,36244 ,18594,22130,22130 ,0,0,0}, {38678,37000,38314 ,22131,22131,22132 ,0,0,0}, + {36994,36998,37529 ,22132,22133,22133 ,0,0,0}, {38316,36247,36999 ,22134,18609,22134 ,0,0,0}, + {36999,38678,38316 ,22134,22131,22134 ,0,0,0}, {38315,36247,38316 ,18609,18609,22134 ,0,0,0}, + {36999,37000,38678 ,22134,22131,22131 ,0,0,0}, {36994,38314,37000 ,22132,22132,22131 ,0,0,0}, + {38314,36994,37529 ,22132,22132,22133 ,0,0,0}, {36244,34086,34085 ,22130,18594,18594 ,0,0,0}, + {38288,36998,36244 ,22130,22133,22130 ,0,0,0}, {37529,36998,38288 ,22133,22133,22130 ,0,0,0}, + {38714,34091,37398 ,22135,18581,21 ,0,0,0}, {34091,34092,37398 ,18581,18581,21 ,0,0,0}, + {36715,38714,37398 ,18601,22135,21 ,0,0,0}, {38714,36715,38286 ,22135,18601,18601 ,0,0,0}, + {34071,37528,36710 ,18588,22136,22136 ,0,0,0}, {37525,36198,38717 ,22137,22137,22138 ,0,0,0}, + {36704,37444,38715 ,22138,22139,22139 ,0,0,0}, {38285,36715,36716 ,22140,18601,22140 ,0,0,0}, + {36716,37525,38285 ,22140,22137,22140 ,0,0,0}, {38286,36715,38285 ,18601,18601,22140 ,0,0,0}, + {36716,36198,37525 ,22140,22137,22137 ,0,0,0}, {36704,38717,36198 ,22138,22138,22137 ,0,0,0}, + {38717,36704,38715 ,22138,22138,22139 ,0,0,0}, {36710,34072,34071 ,22136,18588,18588 ,0,0,0}, + {37528,37444,36710 ,22136,22139,22136 ,0,0,0}, {38715,37444,37528 ,22139,22139,22136 ,0,0,0}, + {4039,36265,38007 ,22141,22142,18594 ,0,0,0}, {4039,34050,36265 ,22141,18575,22142 ,0,0,0}, + {34050,4039,34049 ,18575,22141,18575 ,0,0,0}, {36222,38007,36265 ,18594,18594,22142 ,0,0,0}, + {34057,38531,36266 ,18581,22143,22143 ,0,0,0}, {38185,37262,38186 ,22144,22144,22145 ,0,0,0}, + {36267,36223,38180 ,22145,22146,22146 ,0,0,0}, {38006,36222,37263 ,22147,18594,22147 ,0,0,0}, + {37263,38185,38006 ,22147,22144,22147 ,0,0,0}, {38007,36222,38006 ,18594,18594,22147 ,0,0,0}, + {37263,37262,38185 ,22147,22144,22144 ,0,0,0}, {36267,38186,37262 ,22145,22145,22144 ,0,0,0}, + {38186,36267,38180 ,22145,22145,22146 ,0,0,0}, {36266,34058,34057 ,22143,18581,18581 ,0,0,0}, + {38531,36223,36266 ,22143,22146,22143 ,0,0,0}, {38180,36223,38531 ,22146,22146,22143 ,0,0,0}, + {38744,34063,37267 ,22148,18583,22149 ,0,0,0}, {34063,34064,37267 ,18583,18583,22149 ,0,0,0}, + {37266,38744,37267 ,18588,22148,22149 ,0,0,0}, {38744,37266,37969 ,22148,18588,18588 ,0,0,0}, + {34043,37978,37261 ,18573,22150,22150 ,0,0,0}, {38532,36911,37980 ,22151,22151,22152 ,0,0,0}, + {36224,36226,37981 ,22152,22153,22153 ,0,0,0}, {37968,37266,36268 ,22154,18588,22154 ,0,0,0}, + {36268,38532,37968 ,22154,22151,22154 ,0,0,0}, {37969,37266,37968 ,18588,18588,22154 ,0,0,0}, + {36268,36911,38532 ,22154,22151,22151 ,0,0,0}, {36224,37980,36911 ,22152,22152,22151 ,0,0,0}, + {37980,36224,37981 ,22152,22152,22153 ,0,0,0}, {37261,34044,34043 ,22150,18573,18573 ,0,0,0}, + {37978,36226,37261 ,22150,22153,22150 ,0,0,0}, {37981,36226,37978 ,22153,22153,22150 ,0,0,0} +}; +static GLfloat vertices [38747][3] = { +{-0.023239f,-0.071786f,0.0322314f},{-0.0231144f,-0.0708235f,0.0340958f},{-0.023239f,-0.0717882f,0.0340958f}, +{-0.0231106f,-0.0727502f,0.0322314f},{-0.0231103f,-0.0727513f,0.0340958f},{-0.0227371f,-0.0736484f,0.0322314f}, +{-0.0227371f,-0.0736484f,0.0340958f},{-0.0231141f,-0.0708224f,0.0322314f},{-0.0227444f,-0.0699238f,0.0340958f}, +{-0.0227444f,-0.0699238f,0.0322314f},{-0.0225127f,-0.00424291f,0.0322314f},{-0.0216035f,-0.00385992f,0.0340958f}, +{-0.0225146f,-0.00424405f,0.0340958f},{-0.0232912f,-0.00485238f,0.0322314f},{-0.023292f,-0.00485321f,0.0340958f}, +{-0.0238822f,-0.00564511f,0.0322314f},{-0.0238822f,-0.00564511f,0.0340958f},{-0.0216024f,-0.00385961f,0.0322314f}, +{-0.0206235f,-0.00372882f,0.0340958f},{-0.0206235f,-0.00372882f,0.0322314f},{-0.0243511f,0.0075482f,0.0322314f}, +{-0.024197f,0.00852259f,0.0340958f},{-0.0243512f,0.00754595f,0.0340958f},{-0.024244f,0.0065653f,0.0322314f}, +{-0.0242437f,0.00656417f,0.0340958f},{-0.0238822f,0.00564511f,0.0322314f},{-0.0238822f,0.00564511f,0.0340958f}, +{-0.0241967f,0.00852371f,0.0322314f},{-0.0237915f,0.00942436f,0.0340958f},{-0.0237915f,0.00942436f,0.0322314f}, +{-0.0213716f,0.0750107f,0.0322314f},{-0.0204747f,0.0753817f,0.0340958f},{-0.0213735f,0.0750096f,0.0340958f}, +{-0.022144f,0.0744194f,0.0322314f},{-0.0221448f,0.0744186f,0.0340958f},{-0.0227371f,0.0736484f,0.0322314f}, +{-0.0227371f,0.0736484f,0.0340958f},{-0.0204736f,0.075382f,0.0322314f},{-0.0195103f,0.0755086f,0.0340958f}, +{-0.0195103f,0.0755086f,0.0322314f},{-0.0391526f,-0.00279661f,0.0322314f},{-0.0397007f,-0.00274238f,0.0340958f}, +{-0.0391526f,-0.00279661f,0.0340958f},{-0.0380824f,-0.00258373f,0.0340958f},{-0.0380824f,-0.00258373f,0.0322314f}, +{-0.0386045f,-0.00274238f,0.0340958f},{-0.0386045f,-0.00274238f,0.0322314f},{-0.037601f,-0.00232674f,0.0322314f}, +{-0.0371751f,-0.00197751f,0.0322314f},{-0.0371751f,-0.00197751f,0.0340958f},{-0.0368259f,-0.00155157f,0.0322314f}, +{-0.0368259f,-0.00155157f,0.0340958f},{-0.037601f,-0.00232674f,0.0340958f},{-0.036356f,3.97423e-017f,0.0322314f}, +{-0.0364102f,-0.000548134f,0.0322314f},{-0.0364102f,-0.000548134f,0.0340958f},{-0.0365689f,-0.00107022f,0.0340958f}, +{-0.0365689f,-0.00107022f,0.0322314f},{-0.036356f,3.97423e-017f,0.0340958f},{-0.0397007f,-0.00274238f,0.0322314f}, +{-0.0402228f,-0.00258373f,0.0340958f},{-0.0402228f,-0.00258373f,0.0322314f},{-0.0407042f,-0.00232674f,0.0322314f}, +{-0.0407042f,-0.00232674f,0.0340958f},{-0.0411301f,-0.00197751f,0.0322314f},{-0.0411301f,-0.00197751f,0.0340958f}, +{-0.0414793f,-0.00155157f,0.0340958f},{-0.0414793f,-0.00155157f,0.0322314f},{-0.0417363f,-0.00107022f,0.0322314f}, +{-0.0417363f,-0.00107022f,0.0340958f},{-0.041895f,-0.000548134f,0.0322314f},{-0.041895f,-0.000548134f,0.0340958f}, +{-0.0419492f,3.97423e-017f,0.0340958f},{-0.0419492f,3.97423e-017f,0.0322314f},{0.0391526f,-0.00279661f,0.0322314f}, +{0.0386045f,-0.00274238f,0.0340958f},{0.0391526f,-0.00279661f,0.0340958f},{0.0402228f,-0.00258373f,0.0340958f}, +{0.0402228f,-0.00258373f,0.0322314f},{0.0397007f,-0.00274238f,0.0340958f},{0.0397007f,-0.00274238f,0.0322314f}, +{0.0407042f,-0.00232674f,0.0322314f},{0.0411301f,-0.00197751f,0.0322314f},{0.0411301f,-0.00197751f,0.0340958f}, +{0.0414793f,-0.00155157f,0.0322314f},{0.0414793f,-0.00155157f,0.0340958f},{0.0407042f,-0.00232674f,0.0340958f}, +{0.0419492f,3.97423e-017f,0.0322314f},{0.041895f,-0.000548134f,0.0322314f},{0.041895f,-0.000548134f,0.0340958f}, +{0.0417363f,-0.00107022f,0.0340958f},{0.0417363f,-0.00107022f,0.0322314f},{0.0419492f,3.97423e-017f,0.0340958f}, +{0.0386045f,-0.00274238f,0.0322314f},{0.0380824f,-0.00258373f,0.0340958f},{0.0380824f,-0.00258373f,0.0322314f}, +{0.037601f,-0.00232674f,0.0322314f},{0.037601f,-0.00232674f,0.0340958f},{0.0371751f,-0.00197751f,0.0322314f}, +{0.0371751f,-0.00197751f,0.0340958f},{0.0368259f,-0.00155157f,0.0340958f},{0.0368259f,-0.00155157f,0.0322314f}, +{0.0365689f,-0.00107022f,0.0322314f},{0.0365689f,-0.00107022f,0.0340958f},{0.0364102f,-0.000548134f,0.0322314f}, +{0.0364102f,-0.000548134f,0.0340958f},{0.036356f,3.97423e-017f,0.0340958f},{0.036356f,3.97423e-017f,0.0322314f}, +{-0.0391526f,0.0783052f,0.0322314f},{-0.0397007f,0.0783594f,0.0340958f},{-0.0391526f,0.0783052f,0.0340958f}, +{-0.0380824f,0.0785181f,0.0340958f},{-0.0380824f,0.0785181f,0.0322314f},{-0.0386045f,0.0783594f,0.0340958f}, +{-0.0386045f,0.0783594f,0.0322314f},{-0.037601f,0.0787751f,0.0322314f},{-0.0371751f,0.0791243f,0.0322314f}, +{-0.0371751f,0.0791243f,0.0340958f},{-0.0368259f,0.0795502f,0.0322314f},{-0.0368259f,0.0795502f,0.0340958f}, +{-0.037601f,0.0787751f,0.0340958f},{-0.036356f,0.0811018f,0.0322314f},{-0.0364102f,0.0805537f,0.0322314f}, +{-0.0364102f,0.0805537f,0.0340958f},{-0.0365689f,0.0800316f,0.0340958f},{-0.0365689f,0.0800316f,0.0322314f}, +{-0.036356f,0.0811018f,0.0340958f},{-0.0397007f,0.0783594f,0.0322314f},{-0.0402228f,0.0785181f,0.0340958f}, +{-0.0402228f,0.0785181f,0.0322314f},{-0.0407042f,0.0787751f,0.0322314f},{-0.0407042f,0.0787751f,0.0340958f}, +{-0.0411301f,0.0791243f,0.0322314f},{-0.0411301f,0.0791243f,0.0340958f},{-0.0414793f,0.0795502f,0.0340958f}, +{-0.0414793f,0.0795502f,0.0322314f},{-0.0417363f,0.0800316f,0.0322314f},{-0.0417363f,0.0800316f,0.0340958f}, +{-0.041895f,0.0805537f,0.0322314f},{-0.041895f,0.0805537f,0.0340958f},{-0.0419492f,0.0811018f,0.0340958f}, +{-0.0419492f,0.0811018f,0.0322314f},{0.0391526f,0.0783052f,0.0322314f},{0.0386045f,0.0783594f,0.0340958f}, +{0.0391526f,0.0783052f,0.0340958f},{0.0402228f,0.0785181f,0.0340958f},{0.0402228f,0.0785181f,0.0322314f}, +{0.0397007f,0.0783594f,0.0340958f},{0.0397007f,0.0783594f,0.0322314f},{0.0407042f,0.0787751f,0.0322314f}, +{0.0411301f,0.0791243f,0.0322314f},{0.0411301f,0.0791243f,0.0340958f},{0.0414793f,0.0795502f,0.0322314f}, +{0.0414793f,0.0795502f,0.0340958f},{0.0407042f,0.0787751f,0.0340958f},{0.0419492f,0.0811018f,0.0322314f}, +{0.041895f,0.0805537f,0.0322314f},{0.041895f,0.0805537f,0.0340958f},{0.0417363f,0.0800316f,0.0340958f}, +{0.0417363f,0.0800316f,0.0322314f},{0.0419492f,0.0811018f,0.0340958f},{0.0386045f,0.0783594f,0.0322314f}, +{0.0380824f,0.0785181f,0.0340958f},{0.0380824f,0.0785181f,0.0322314f},{0.037601f,0.0787751f,0.0322314f}, +{0.037601f,0.0787751f,0.0340958f},{0.0371751f,0.0791243f,0.0322314f},{0.0371751f,0.0791243f,0.0340958f}, +{0.0368259f,0.0795502f,0.0340958f},{0.0368259f,0.0795502f,0.0322314f},{0.0365689f,0.0800316f,0.0322314f}, +{0.0365689f,0.0800316f,0.0340958f},{0.0364102f,0.0805537f,0.0322314f},{0.0364102f,0.0805537f,0.0340958f}, +{0.036356f,0.0811018f,0.0340958f},{0.036356f,0.0811018f,0.0322314f},{0.0391526f,-0.0838984f,0.0322314f}, +{0.0386045f,-0.0838442f,0.0340958f},{0.0391526f,-0.0838984f,0.0340958f},{0.0402228f,-0.0836855f,0.0340958f}, +{0.0402228f,-0.0836855f,0.0322314f},{0.0397007f,-0.0838442f,0.0340958f},{0.0397007f,-0.0838442f,0.0322314f}, +{0.0407042f,-0.0834285f,0.0322314f},{0.0411301f,-0.0830793f,0.0322314f},{0.0411301f,-0.0830793f,0.0340958f}, +{0.0414793f,-0.0826534f,0.0322314f},{0.0414793f,-0.0826534f,0.0340958f},{0.0407042f,-0.0834285f,0.0340958f}, +{0.0419492f,-0.0811018f,0.0322314f},{0.041895f,-0.0816499f,0.0322314f},{0.041895f,-0.0816499f,0.0340958f}, +{0.0417363f,-0.082172f,0.0340958f},{0.0417363f,-0.082172f,0.0322314f},{0.0419492f,-0.0811018f,0.0340958f}, +{0.0386045f,-0.0838442f,0.0322314f},{0.0380824f,-0.0836855f,0.0340958f},{0.0380824f,-0.0836855f,0.0322314f}, +{0.037601f,-0.0834285f,0.0322314f},{0.037601f,-0.0834285f,0.0340958f},{0.0371751f,-0.0830793f,0.0322314f}, +{0.0371751f,-0.0830793f,0.0340958f},{0.0368259f,-0.0826534f,0.0340958f},{0.0368259f,-0.0826534f,0.0322314f}, +{0.0365689f,-0.082172f,0.0322314f},{0.0365689f,-0.082172f,0.0340958f},{0.0364102f,-0.0816499f,0.0322314f}, +{0.0364102f,-0.0816499f,0.0340958f},{0.036356f,-0.0811018f,0.0340958f},{0.036356f,-0.0811018f,0.0322314f}, +{-0.0391526f,-0.0838984f,0.0322314f},{-0.0397007f,-0.0838442f,0.0340958f},{-0.0391526f,-0.0838984f,0.0340958f}, +{-0.0380824f,-0.0836855f,0.0340958f},{-0.0380824f,-0.0836855f,0.0322314f},{-0.0386045f,-0.0838442f,0.0340958f}, +{-0.0386045f,-0.0838442f,0.0322314f},{-0.037601f,-0.0834285f,0.0322314f},{-0.0371751f,-0.0830793f,0.0322314f}, +{-0.0371751f,-0.0830793f,0.0340958f},{-0.0368259f,-0.0826534f,0.0322314f},{-0.0368259f,-0.0826534f,0.0340958f}, +{-0.037601f,-0.0834285f,0.0340958f},{-0.036356f,-0.0811018f,0.0322314f},{-0.0364102f,-0.0816499f,0.0322314f}, +{-0.0364102f,-0.0816499f,0.0340958f},{-0.0365689f,-0.082172f,0.0340958f},{-0.0365689f,-0.082172f,0.0322314f}, +{-0.036356f,-0.0811018f,0.0340958f},{-0.0397007f,-0.0838442f,0.0322314f},{-0.0402228f,-0.0836855f,0.0340958f}, +{-0.0402228f,-0.0836855f,0.0322314f},{-0.0407042f,-0.0834285f,0.0322314f},{-0.0407042f,-0.0834285f,0.0340958f}, +{-0.0411301f,-0.0830793f,0.0322314f},{-0.0411301f,-0.0830793f,0.0340958f},{-0.0414793f,-0.0826534f,0.0340958f}, +{-0.0414793f,-0.0826534f,0.0322314f},{-0.0417363f,-0.082172f,0.0322314f},{-0.0417363f,-0.082172f,0.0340958f}, +{-0.041895f,-0.0816499f,0.0322314f},{-0.041895f,-0.0816499f,0.0340958f},{-0.0419492f,-0.0811018f,0.0340958f}, +{-0.0419492f,-0.0811018f,0.0322314f},{0.0225785f,-0.0258241f,0.0322314f},{0.0237254f,-0.0222932f,0.0322314f}, +{0.0237253f,-0.0222933f,0.0340958f},{0.0216792f,-0.0294283f,0.0322314f},{0.0225785f,-0.0258242f,0.0340958f}, +{0.0216792f,-0.0294286f,0.0340958f},{0.0210317f,-0.0330928f,0.0322314f},{0.0206399f,-0.0368049f,0.0340958f}, +{0.0205085f,-0.0405509f,0.0322314f},{0.02064f,-0.0368047f,0.0322314f},{0.0210316f,-0.0330931f,0.0340958f}, +{0.0205085f,-0.0405509f,0.0340958f},{0.0251155f,-0.0188485f,0.0340958f},{0.0267447f,-0.0155029f,0.0340958f}, +{0.0251156f,-0.0188483f,0.0322314f},{0.0267448f,-0.0155026f,0.0322314f},{0.0286089f,-0.0122693f,0.0340958f}, +{0.028609f,-0.0122691f,0.0322314f},{0.0307038f,-0.00916071f,0.0340958f},{0.0307038f,-0.00916071f,0.0322314f}, +{-0.03984f,-0.0885276f,0.0340958f},{-0.0398371f,-0.0885279f,0.0322314f},{-0.0387004f,-0.0885456f,0.0322314f}, +{-0.0409568f,-0.0883379f,0.0322314f},{-0.0409588f,-0.0883374f,0.0340958f},{-0.0420378f,-0.0879786f,0.0340958f}, +{-0.042035f,-0.0879797f,0.0322314f},{-0.0430486f,-0.0874608f,0.0340958f},{-0.043047f,-0.0874618f,0.0322314f}, +{-0.0439672f,-0.0867969f,0.0322314f},{-0.0439685f,-0.086796f,0.0340958f},{-0.0447784f,-0.0859974f,0.0340958f}, +{-0.0447773f,-0.0859985f,0.0322314f},{-0.045456f,-0.0850872f,0.0340958f},{-0.0454557f,-0.0850877f,0.0322314f}, +{-0.0459883f,-0.0840833f,0.0340958f},{-0.0459883f,-0.0840833f,0.0322314f},{-0.0387033f,-0.0885458f,0.0340958f}, +{-0.037576f,-0.0883909f,0.0322314f},{-0.0375781f,-0.0883913f,0.0340958f},{-0.0364863f,-0.0880664f,0.0322314f}, +{-0.0364891f,-0.0880674f,0.0340958f},{-0.0354613f,-0.0875818f,0.0340958f},{-0.0354596f,-0.0875808f,0.0322314f}, +{-0.0345192f,-0.0869454f,0.0322314f},{-0.0345204f,-0.0869463f,0.0340958f},{-0.0336844f,-0.0861728f,0.0322314f}, +{-0.0336855f,-0.0861739f,0.0340958f},{-0.0329787f,-0.085285f,0.0340958f},{-0.0329784f,-0.0852846f,0.0322314f}, +{-0.0324146f,-0.0842979f,0.0322314f},{-0.0324146f,-0.0842979f,0.0340958f},{-0.0440592f,-0.00561614f,0.0322314f}, +{-0.0430328f,-0.00636862f,0.0322314f},{-0.0440603f,-0.00561515f,0.0340958f},{-0.044941f,-0.00470215f,0.0340958f}, +{-0.0449406f,-0.00470266f,0.0322314f},{-0.0456552f,-0.0036514f,0.0340958f},{-0.0456542f,-0.00365287f,0.0322314f}, +{-0.046181f,-0.00249363f,0.0322314f},{-0.0461811f,-0.00249326f,0.0340958f},{-0.046502f,-0.00126624f,0.0340958f}, +{-0.0465017f,-0.00126733f,0.0322314f},{-0.0466102f,3.97423e-017f,0.0340958f},{-0.0466102f,3.97423e-017f,0.0322314f}, +{-0.0430341f,-0.00636786f,0.0340958f},{-0.0418973f,-0.00693419f,0.0322314f},{-0.0418979f,-0.00693393f,0.0340958f}, +{-0.0406822f,-0.00729899f,0.0340958f},{-0.0406805f,-0.00729943f,0.0322314f},{-0.0394178f,-0.00745289f,0.0322314f}, +{-0.0394182f,-0.00745292f,0.0340958f},{-0.0381511f,-0.00739011f,0.0322314f},{-0.0381522f,-0.00739019f,0.0340958f}, +{-0.0369109f,-0.00711273f,0.0322314f},{-0.0369109f,-0.00711273f,0.0340958f},{-0.0450626f,0.0765535f,0.0340958f}, +{-0.0450608f,0.0765512f,0.0322314f},{-0.0443005f,0.075706f,0.0322314f},{-0.0456834f,0.0775011f,0.0322314f}, +{-0.0456844f,0.0775029f,0.0340958f},{-0.0461555f,0.0785378f,0.0340958f},{-0.0461544f,0.078535f,0.0322314f}, +{-0.0464637f,0.0796309f,0.0340958f},{-0.0464633f,0.079629f,0.0322314f},{-0.0466021f,0.0807558f,0.0322314f}, +{-0.0466023f,0.0807574f,0.0340958f},{-0.046568f,0.0818943f,0.0340958f},{-0.0465681f,0.0818927f,0.0322314f}, +{-0.046362f,0.0830101f,0.0340958f},{-0.0463621f,0.0830096f,0.0322314f},{-0.0459883f,0.0840833f,0.0340958f}, +{-0.0459883f,0.0840833f,0.0322314f},{-0.0443026f,0.0757081f,0.0340958f},{-0.0434222f,0.0749873f,0.0322314f}, +{-0.0434238f,0.0749885f,0.0340958f},{-0.0424429f,0.0744094f,0.0322314f},{-0.0424456f,0.0744107f,0.0340958f}, +{-0.0413904f,0.0739879f,0.0340958f},{-0.0413886f,0.0739873f,0.0322314f},{-0.040283f,0.0737303f,0.0322314f}, +{-0.0402846f,0.0737307f,0.0340958f},{-0.0391489f,0.0736442f,0.0322314f},{-0.0391504f,0.0736443f,0.0340958f}, +{-0.0380181f,0.073731f,0.0340958f},{-0.0380175f,0.073731f,0.0322314f},{-0.0369109f,0.0739891f,0.0322314f}, +{-0.0369109f,0.0739891f,0.0340958f},{0.0225785f,0.0552777f,0.0322314f},{0.0237254f,0.0588086f,0.0322314f}, +{0.0237253f,0.0588085f,0.0340958f},{0.0216792f,0.0516735f,0.0322314f},{0.0225785f,0.0552776f,0.0340958f}, +{0.0216792f,0.0516732f,0.0340958f},{0.0210317f,0.048009f,0.0322314f},{0.0206399f,0.0442969f,0.0340958f}, +{0.0205085f,0.0405509f,0.0322314f},{0.02064f,0.0442971f,0.0322314f},{0.0210316f,0.0480087f,0.0340958f}, +{0.0205085f,0.0405509f,0.0340958f},{0.0251155f,0.0622533f,0.0340958f},{0.0267447f,0.0655989f,0.0340958f}, +{0.0251156f,0.0622535f,0.0322314f},{0.0267448f,0.0655992f,0.0322314f},{0.0286089f,0.0688326f,0.0340958f}, +{0.028609f,0.0688327f,0.0322314f},{0.0307038f,0.0719411f,0.0340958f},{0.0307038f,0.0719411f,0.0322314f}, +{0.0167768f,-0.0552561f,0.0340958f},{0.0159195f,-0.0513911f,0.0340958f},{0.0167768f,-0.0552561f,0.0322314f}, +{0.0159195f,-0.0513911f,0.0322314f},{0.0153227f,-0.0474729f,0.0340958f},{0.0149897f,-0.0435148f,0.0340958f}, +{0.0153227f,-0.0474729f,0.0322314f},{0.0149241f,-0.0395297f,0.0340958f},{0.0149897f,-0.0435148f,0.0322314f}, +{0.0149241f,-0.0395297f,0.0322314f},{0.0178914f,-0.059055f,0.0322314f},{0.0192597f,-0.0627747f,0.0322314f}, +{0.0178914f,-0.059055f,0.0340958f},{0.0208785f,-0.066402f,0.0322314f},{0.0192597f,-0.0627747f,0.0340958f}, +{0.0208785f,-0.066402f,0.0340958f},{0.0227444f,-0.0699238f,0.0322314f},{0.0227444f,-0.0699238f,0.0340958f}, +{0.0173199f,0.0238768f,0.0340958f},{0.0163293f,0.0277099f,0.0340958f},{0.0173199f,0.0238768f,0.0322314f}, +{0.0163293f,0.0277099f,0.0322314f},{0.0155973f,0.031605f,0.0340958f},{0.0151276f,0.0355493f,0.0340958f}, +{0.0155973f,0.031605f,0.0322314f},{0.0149241f,0.0395297f,0.0340958f},{0.0151276f,0.0355493f,0.0322314f}, +{0.0149241f,0.0395297f,0.0322314f},{0.0185653f,0.0201187f,0.0322314f},{0.0200615f,0.0164487f,0.0322314f}, +{0.0185653f,0.0201187f,0.0340958f},{0.0218049f,0.0128796f,0.0322314f},{0.0200615f,0.0164487f,0.0340958f}, +{0.0218049f,0.0128796f,0.0340958f},{0.0237915f,0.00942436f,0.0322314f},{0.0237915f,0.00942436f,0.0340958f}, +{0.0149897f,0.0435148f,0.0340958f},{0.0167768f,0.0552561f,0.0340958f},{0.0159195f,0.0513911f,0.0322314f}, +{0.0159195f,0.0513911f,0.0340958f},{0.0153227f,0.0474729f,0.0340958f},{0.0153227f,0.0474729f,0.0322314f}, +{0.0149897f,0.0435148f,0.0322314f},{0.0192597f,0.0627747f,0.0322314f},{0.0192597f,0.0627747f,0.0340958f}, +{0.0208785f,0.066402f,0.0340958f},{0.0167768f,0.0552561f,0.0322314f},{0.0178914f,0.059055f,0.0340958f}, +{0.0178914f,0.059055f,0.0322314f},{0.0227444f,0.0699238f,0.0340958f},{0.0208785f,0.066402f,0.0322314f}, +{0.0227444f,0.0699238f,0.0322314f},{-0.0206235f,0.00372882f,0.0322314f},{-0.0206235f,0.00372882f,0.0340958f}, +{0.0206235f,0.00372882f,0.0340958f},{0.0206235f,0.00372882f,0.0322314f},{-0.0149256f,0.0416576f,0.0340958f}, +{-0.0149993f,0.0374031f,0.0340958f},{-0.0149257f,0.0416577f,0.0322314f},{-0.0151577f,0.0458938f,0.0322314f}, +{-0.0151576f,0.0458937f,0.0340958f},{-0.0156914f,0.0500904f,0.0322314f},{-0.0156914f,0.0500902f,0.0340958f}, +{-0.0165229f,0.0542313f,0.0340958f},{-0.016523f,0.0542315f,0.0322314f},{-0.0176481f,0.0583013f,0.0322314f}, +{-0.017648f,0.0583011f,0.0340958f},{-0.0190628f,0.0622838f,0.0322314f},{-0.0190627f,0.0622837f,0.0340958f}, +{-0.0207629f,0.0661632f,0.0340958f},{-0.0207629f,0.0661633f,0.0322314f},{-0.0227444f,0.0699238f,0.0322314f}, +{-0.0227444f,0.0699238f,0.0340958f},{-0.0149993f,0.0374031f,0.0322314f},{-0.0153777f,0.0331776f,0.0322314f}, +{-0.0153777f,0.0331775f,0.0340958f},{-0.0160564f,0.0290019f,0.0340958f},{-0.0160564f,0.0290021f,0.0322314f}, +{-0.0170307f,0.024892f,0.0340958f},{-0.0170307f,0.0248922f,0.0322314f},{-0.018296f,0.0208638f,0.0322314f}, +{-0.018296f,0.0208636f,0.0340958f},{-0.0198477f,0.0169324f,0.0340958f},{-0.0198476f,0.0169326f,0.0322314f}, +{-0.021681f,0.0131141f,0.0340958f},{-0.021681f,0.0131142f,0.0322314f},{0.0151276f,-0.0355493f,0.0340958f}, +{0.0173199f,-0.0238768f,0.0340958f},{0.0163293f,-0.0277099f,0.0322314f},{0.0163293f,-0.0277099f,0.0340958f}, +{0.0155973f,-0.031605f,0.0340958f},{0.0155973f,-0.031605f,0.0322314f},{0.0151276f,-0.0355493f,0.0322314f}, +{0.0200615f,-0.0164487f,0.0322314f},{0.0200615f,-0.0164487f,0.0340958f},{0.0218049f,-0.0128796f,0.0340958f}, +{0.0173199f,-0.0238768f,0.0322314f},{0.0185653f,-0.0201187f,0.0340958f},{0.0185653f,-0.0201187f,0.0322314f}, +{0.0237915f,-0.00942436f,0.0340958f},{0.0218049f,-0.0128796f,0.0322314f},{0.0237915f,-0.00942436f,0.0322314f}, +{-0.0195103f,-0.0755086f,0.0322314f},{0.0195103f,-0.0755086f,0.0340958f},{0.0195103f,-0.0755086f,0.0322314f}, +{-0.0195103f,-0.0755086f,0.0340958f},{-0.0149993f,-0.0374031f,0.0340958f},{-0.0149257f,-0.0416576f,0.0340958f}, +{-0.0149993f,-0.0374031f,0.0322314f},{-0.0153777f,-0.0331775f,0.0322314f},{-0.0153777f,-0.0331776f,0.0340958f}, +{-0.0160564f,-0.0290019f,0.0322314f},{-0.0160564f,-0.0290021f,0.0340958f},{-0.0170307f,-0.0248922f,0.0340958f}, +{-0.0170307f,-0.024892f,0.0322314f},{-0.018296f,-0.0208636f,0.0322314f},{-0.018296f,-0.0208638f,0.0340958f}, +{-0.0198477f,-0.0169324f,0.0322314f},{-0.0198476f,-0.0169326f,0.0340958f},{-0.021681f,-0.0131142f,0.0340958f}, +{-0.021681f,-0.0131141f,0.0322314f},{-0.0237915f,-0.00942436f,0.0322314f},{-0.0237915f,-0.00942436f,0.0340958f}, +{-0.0149256f,-0.0416576f,0.0322314f},{-0.0151576f,-0.0458937f,0.0322314f},{-0.0151577f,-0.0458938f,0.0340958f}, +{-0.0156914f,-0.0500904f,0.0340958f},{-0.0156914f,-0.0500902f,0.0322314f},{-0.016523f,-0.0542315f,0.0340958f}, +{-0.0165229f,-0.0542313f,0.0322314f},{-0.017648f,-0.0583011f,0.0322314f},{-0.0176481f,-0.0583013f,0.0340958f}, +{-0.0190628f,-0.0622838f,0.0340958f},{-0.0190627f,-0.0622837f,0.0322314f},{-0.0207629f,-0.0661633f,0.0340958f}, +{-0.0207629f,-0.0661632f,0.0322314f},{0.02064f,0.0368047f,0.0340958f},{0.0206399f,0.0368049f,0.0322314f}, +{0.0225785f,0.0258241f,0.0340958f},{0.0225785f,0.0258242f,0.0322314f},{0.0216792f,0.0294283f,0.0340958f}, +{0.0216792f,0.0294286f,0.0322314f},{0.0210316f,0.0330931f,0.0322314f},{0.0210317f,0.0330928f,0.0340958f}, +{0.0267447f,0.0155029f,0.0322314f},{0.0251156f,0.0188483f,0.0340958f},{0.0267448f,0.0155026f,0.0340958f}, +{0.0237253f,0.0222933f,0.0322314f},{0.0237254f,0.0222932f,0.0340958f},{0.0251155f,0.0188485f,0.0322314f}, +{0.028609f,0.0122691f,0.0340958f},{0.0286089f,0.0122693f,0.0322314f},{0.0307038f,0.00916071f,0.0340958f}, +{0.0307038f,0.00916071f,0.0322314f},{0.0462025f,0.0835337f,0.0340958f},{0.0457312f,0.0846141f,0.0322314f}, +{0.0457326f,0.0846116f,0.0340958f},{0.0450998f,0.0856014f,0.0340958f},{0.0450987f,0.085603f,0.0322314f}, +{0.044317f,0.0864818f,0.0322314f},{0.0443187f,0.0864801f,0.0340958f},{0.0434093f,0.0872252f,0.0340958f}, +{0.0434083f,0.0872259f,0.0322314f},{0.0423945f,0.087818f,0.0322314f},{0.0423947f,0.0878178f,0.0340958f}, +{0.0412975f,0.0882443f,0.0322314f},{0.041298f,0.0882442f,0.0340958f},{0.040151f,0.0884923f,0.0340958f}, +{0.0401493f,0.0884924f,0.0322314f},{0.0389772f,0.0885573f,0.0340958f},{0.0389749f,0.0885572f,0.0322314f}, +{0.0378063f,0.0884369f,0.0322314f},{0.0378083f,0.0884373f,0.0340958f},{0.0366734f,0.0881351f,0.0340958f}, +{0.0366703f,0.0881341f,0.0322314f},{0.0355963f,0.0876568f,0.0322314f},{0.0355984f,0.087658f,0.0340958f}, +{0.0346116f,0.0870176f,0.0322314f},{0.0346134f,0.0870188f,0.0340958f},{0.0337395f,0.0862314f,0.0340958f}, +{0.0337379f,0.0862299f,0.0322314f},{0.0330004f,0.0853169f,0.0322314f},{0.0330008f,0.0853175f,0.0340958f}, +{0.0324146f,0.0842979f,0.0322314f},{0.0324146f,0.0842979f,0.0340958f},{0.0462016f,0.0835364f,0.0322314f}, +{0.0464969f,0.0823973f,0.0340958f},{0.0464965f,0.0823992f,0.0322314f},{0.0466091f,0.0812265f,0.0340958f}, +{0.046609f,0.0812289f,0.0322314f},{0.0465363f,0.0800543f,0.0340958f},{0.0465364f,0.0800555f,0.0322314f}, +{0.0462805f,0.0789088f,0.0322314f},{0.0462804f,0.0789085f,0.0340958f},{0.0458466f,0.0778144f,0.0340958f}, +{0.0458468f,0.0778149f,0.0322314f},{0.0452473f,0.0768042f,0.0340958f},{0.0452483f,0.0768055f,0.0322314f}, +{0.0444957f,0.0758993f,0.0340958f},{0.0444974f,0.075901f,0.0322314f},{0.0436142f,0.075126f,0.0322314f}, +{0.0436125f,0.0751248f,0.0340958f},{0.0426177f,0.0744982f,0.0340958f},{0.0426206f,0.0744998f,0.0322314f}, +{0.0415395f,0.0740365f,0.0322314f},{0.0415373f,0.0740358f,0.0340958f},{0.0403988f,0.073749f,0.0340958f}, +{0.0404009f,0.0737495f,0.0322314f},{0.0392271f,0.0736446f,0.0340958f},{0.0392293f,0.0736447f,0.0322314f}, +{0.038057f,0.0737251f,0.0322314f},{0.0380562f,0.0737252f,0.0340958f},{0.0369109f,0.0739891f,0.0340958f}, +{0.0369109f,0.0739891f,0.0322314f},{0.027361f,0.0811018f,0.0322314f},{-0.027361f,0.0811018f,0.0322314f}, +{-0.027361f,0.0811018f,0.0340958f},{0.027361f,0.0811018f,0.0340958f},{-0.0454557f,0.0850877f,0.0340958f}, +{-0.043047f,0.0874618f,0.0340958f},{-0.0430486f,0.0874608f,0.0322314f},{-0.0439672f,0.0867969f,0.0340958f}, +{-0.0447773f,0.0859985f,0.0340958f},{-0.0439685f,0.086796f,0.0322314f},{-0.0447784f,0.0859974f,0.0322314f}, +{-0.03984f,0.0885276f,0.0322314f},{-0.0409568f,0.0883379f,0.0340958f},{-0.0398371f,0.0885279f,0.0340958f}, +{-0.0420378f,0.0879786f,0.0322314f},{-0.042035f,0.0879797f,0.0340958f},{-0.0409588f,0.0883374f,0.0322314f}, +{-0.037576f,0.0883909f,0.0340958f},{-0.0364863f,0.0880664f,0.0340958f},{-0.0364891f,0.0880674f,0.0322314f}, +{-0.0387004f,0.0885456f,0.0340958f},{-0.0375781f,0.0883913f,0.0322314f},{-0.0387033f,0.0885458f,0.0322314f}, +{-0.0354596f,0.0875809f,0.0340958f},{-0.0345192f,0.0869454f,0.0340958f},{-0.0345204f,0.0869463f,0.0322314f}, +{-0.0354613f,0.0875818f,0.0322314f},{-0.0336855f,0.0861739f,0.0322314f},{-0.0336844f,0.0861728f,0.0340958f}, +{-0.0329784f,0.0852846f,0.0340958f},{-0.0329787f,0.085285f,0.0322314f},{-0.0324146f,0.0842979f,0.0340958f}, +{-0.0324146f,0.0842979f,0.0322314f},{-0.045456f,0.0850872f,0.0322314f},{-0.021027f,0.0331264f,0.0340958f}, +{-0.0206381f,0.0368319f,0.0340958f},{-0.0206381f,0.0368317f,0.0322314f},{-0.0205085f,0.0405509f,0.0340958f}, +{-0.0205085f,0.0405509f,0.0322314f},{-0.021027f,0.0331261f,0.0322314f},{-0.0216751f,0.0294476f,0.0322314f}, +{-0.0216749f,0.0294486f,0.0340958f},{-0.0237299f,0.0222807f,0.0340958f},{-0.0225785f,0.0258242f,0.0340958f}, +{-0.0225785f,0.025824f,0.0322314f},{-0.0237299f,0.0222806f,0.0322314f},{-0.0267542f,0.0154851f,0.0340958f}, +{-0.0251237f,0.01883f,0.0322314f},{-0.0267544f,0.0154848f,0.0322314f},{-0.0286161f,0.0122577f,0.0340958f}, +{-0.0251236f,0.0188302f,0.0340958f},{-0.0286162f,0.0122575f,0.0322314f},{-0.0307038f,0.00916071f,0.0340958f}, +{-0.0307038f,0.00916071f,0.0322314f},{-0.0206381f,0.0442701f,0.0340958f},{-0.0206381f,0.0442699f,0.0322314f}, +{-0.021027f,0.0479754f,0.0322314f},{-0.021027f,0.0479757f,0.0340958f},{-0.0216751f,0.0516542f,0.0340958f}, +{-0.0216749f,0.0516532f,0.0322314f},{-0.0225785f,0.0552778f,0.0340958f},{-0.0225785f,0.0552777f,0.0322314f}, +{-0.0237299f,0.0588211f,0.0322314f},{-0.0237299f,0.0588212f,0.0340958f},{-0.0251237f,0.0622718f,0.0340958f}, +{-0.0251236f,0.0622716f,0.0322314f},{-0.0267544f,0.065617f,0.0340958f},{-0.0267542f,0.0656167f,0.0322314f}, +{-0.0286161f,0.0688441f,0.0322314f},{-0.0286162f,0.0688443f,0.0340958f},{-0.0307038f,0.0719411f,0.0322314f}, +{-0.0307038f,0.0719411f,0.0340958f},{-0.0465017f,0.00126733f,0.0340958f},{-0.044941f,0.00470215f,0.0322314f}, +{-0.0456552f,0.0036514f,0.0322314f},{-0.0449406f,0.00470266f,0.0340958f},{-0.0456542f,0.00365287f,0.0340958f}, +{-0.0461811f,0.00249326f,0.0322314f},{-0.046181f,0.00249363f,0.0340958f},{-0.0430341f,0.00636786f,0.0322314f}, +{-0.0418973f,0.00693419f,0.0340958f},{-0.0418979f,0.00693393f,0.0322314f},{-0.0440592f,0.00561614f,0.0340958f}, +{-0.0430328f,0.00636862f,0.0340958f},{-0.0440603f,0.00561515f,0.0322314f},{-0.0406822f,0.00729899f,0.0322314f}, +{-0.0394178f,0.00745289f,0.0340958f},{-0.0394182f,0.00745292f,0.0322314f},{-0.0406805f,0.00729943f,0.0340958f}, +{-0.0381522f,0.00739019f,0.0322314f},{-0.0381511f,0.00739011f,0.0340958f},{-0.0369109f,0.00711273f,0.0340958f}, +{-0.0369109f,0.00711273f,0.0322314f},{-0.046502f,0.00126624f,0.0322314f},{-0.021027f,-0.0479754f,0.0340958f}, +{-0.0206381f,-0.0442699f,0.0340958f},{-0.0206381f,-0.0442701f,0.0322314f},{-0.0205085f,-0.0405509f,0.0340958f}, +{-0.0205085f,-0.0405509f,0.0322314f},{-0.021027f,-0.0479757f,0.0322314f},{-0.0216751f,-0.0516542f,0.0322314f}, +{-0.0216749f,-0.0516532f,0.0340958f},{-0.0237299f,-0.0588211f,0.0340958f},{-0.0225785f,-0.0552777f,0.0340958f}, +{-0.0225785f,-0.0552778f,0.0322314f},{-0.0237299f,-0.0588212f,0.0322314f},{-0.0267542f,-0.0656167f,0.0340958f}, +{-0.0251237f,-0.0622718f,0.0322314f},{-0.0267544f,-0.065617f,0.0322314f},{-0.0286161f,-0.0688441f,0.0340958f}, +{-0.0251236f,-0.0622716f,0.0340958f},{-0.0286162f,-0.0688443f,0.0322314f},{-0.0307038f,-0.0719411f,0.0340958f}, +{-0.0307038f,-0.0719411f,0.0322314f},{-0.0206381f,-0.0368317f,0.0340958f},{-0.0206381f,-0.0368319f,0.0322314f}, +{-0.021027f,-0.0331264f,0.0322314f},{-0.021027f,-0.0331261f,0.0340958f},{-0.0216751f,-0.0294476f,0.0340958f}, +{-0.0216749f,-0.0294486f,0.0322314f},{-0.0225785f,-0.025824f,0.0340958f},{-0.0225785f,-0.0258241f,0.0322314f}, +{-0.0237299f,-0.0222807f,0.0322314f},{-0.0237299f,-0.0222806f,0.0340958f},{-0.0251237f,-0.01883f,0.0340958f}, +{-0.0251236f,-0.0188302f,0.0322314f},{-0.0267544f,-0.0154848f,0.0340958f},{-0.0267542f,-0.0154851f,0.0322314f}, +{-0.0286161f,-0.0122577f,0.0322314f},{-0.0286162f,-0.0122575f,0.0340958f},{-0.0307038f,-0.00916071f,0.0322314f}, +{-0.0307038f,-0.00916071f,0.0340958f},{-0.0463621f,-0.0830096f,0.0340958f},{-0.0464633f,-0.079629f,0.0340958f}, +{-0.0464637f,-0.0796309f,0.0322314f},{-0.0466021f,-0.0807558f,0.0340958f},{-0.0465681f,-0.0818927f,0.0340958f}, +{-0.0466023f,-0.0807574f,0.0322314f},{-0.046568f,-0.0818943f,0.0322314f},{-0.0450626f,-0.0765535f,0.0322314f}, +{-0.0456834f,-0.0775011f,0.0340958f},{-0.0450608f,-0.0765512f,0.0340958f},{-0.0461555f,-0.0785378f,0.0322314f}, +{-0.0461544f,-0.078535f,0.0340958f},{-0.0456844f,-0.0775029f,0.0322314f},{-0.0434222f,-0.0749873f,0.0340958f}, +{-0.0424429f,-0.0744094f,0.0340958f},{-0.0424456f,-0.0744108f,0.0322314f},{-0.0443005f,-0.075706f,0.0340958f}, +{-0.0434238f,-0.0749885f,0.0322314f},{-0.0443026f,-0.0757081f,0.0322314f},{-0.0413886f,-0.0739873f,0.0340958f}, +{-0.040283f,-0.0737303f,0.0340958f},{-0.0402846f,-0.0737307f,0.0322314f},{-0.0413904f,-0.0739879f,0.0322314f}, +{-0.0391504f,-0.0736443f,0.0322314f},{-0.0391489f,-0.0736442f,0.0340958f},{-0.0380175f,-0.073731f,0.0340958f}, +{-0.0380181f,-0.073731f,0.0322314f},{-0.0369109f,-0.0739891f,0.0340958f},{-0.0369109f,-0.0739891f,0.0322314f}, +{-0.046362f,-0.0830101f,0.0322314f},{0.027361f,-0.0811018f,0.0340958f},{-0.027361f,-0.0811018f,0.0322314f}, +{0.027361f,-0.0811018f,0.0322314f},{-0.027361f,-0.0811018f,0.0340958f},{0.0457312f,-0.0846141f,0.0340958f}, +{0.0462025f,-0.0835337f,0.0322314f},{0.0462016f,-0.0835364f,0.0340958f},{0.0464965f,-0.0823992f,0.0340958f}, +{0.0464969f,-0.0823973f,0.0322314f},{0.0466091f,-0.0812265f,0.0322314f},{0.046609f,-0.0812289f,0.0340958f}, +{0.0465364f,-0.0800555f,0.0340958f},{0.0465363f,-0.0800543f,0.0322314f},{0.0462804f,-0.0789085f,0.0322314f}, +{0.0462805f,-0.0789088f,0.0340958f},{0.0458466f,-0.0778144f,0.0322314f},{0.0458468f,-0.0778149f,0.0340958f}, +{0.0452483f,-0.0768055f,0.0340958f},{0.0452473f,-0.0768041f,0.0322314f},{0.0444974f,-0.075901f,0.0340958f}, +{0.0444957f,-0.0758994f,0.0322314f},{0.0436125f,-0.0751248f,0.0322314f},{0.0436142f,-0.075126f,0.0340958f}, +{0.0426206f,-0.0744997f,0.0340958f},{0.0426177f,-0.0744982f,0.0322314f},{0.0415373f,-0.0740358f,0.0322314f}, +{0.0415395f,-0.0740365f,0.0340958f},{0.0403988f,-0.073749f,0.0322314f},{0.0404009f,-0.0737495f,0.0340958f}, +{0.0392293f,-0.0736447f,0.0340958f},{0.0392271f,-0.0736446f,0.0322314f},{0.0380562f,-0.0737252f,0.0322314f}, +{0.038057f,-0.0737251f,0.0340958f},{0.0369109f,-0.0739891f,0.0322314f},{0.0369109f,-0.0739891f,0.0340958f}, +{0.0457326f,-0.0846116f,0.0322314f},{0.0450987f,-0.085603f,0.0340958f},{0.0450998f,-0.0856014f,0.0322314f}, +{0.044317f,-0.0864818f,0.0340958f},{0.0443187f,-0.0864801f,0.0322314f},{0.0434083f,-0.0872259f,0.0340958f}, +{0.0434093f,-0.0872252f,0.0322314f},{0.0423947f,-0.0878178f,0.0322314f},{0.0423945f,-0.087818f,0.0340958f}, +{0.0412975f,-0.0882443f,0.0340958f},{0.041298f,-0.0882442f,0.0322314f},{0.0401493f,-0.0884924f,0.0340958f}, +{0.040151f,-0.0884923f,0.0322314f},{0.0389749f,-0.0885572f,0.0340958f},{0.0389772f,-0.0885573f,0.0322314f}, +{0.0378083f,-0.0884373f,0.0322314f},{0.0378063f,-0.0884369f,0.0340958f},{0.0366703f,-0.088134f,0.0340958f}, +{0.0366734f,-0.0881351f,0.0322314f},{0.0355984f,-0.087658f,0.0322314f},{0.0355963f,-0.0876568f,0.0340958f}, +{0.0346116f,-0.0870176f,0.0340958f},{0.0346134f,-0.0870188f,0.0322314f},{0.0337379f,-0.0862299f,0.0340958f}, +{0.0337395f,-0.0862314f,0.0322314f},{0.0330008f,-0.0853175f,0.0322314f},{0.0330004f,-0.0853169f,0.0340958f}, +{0.0324146f,-0.0842979f,0.0340958f},{0.0324146f,-0.0842979f,0.0322314f},{0.02064f,-0.0442971f,0.0340958f}, +{0.0206399f,-0.0442969f,0.0322314f},{0.0225785f,-0.0552777f,0.0340958f},{0.0225785f,-0.0552776f,0.0322314f}, +{0.0216792f,-0.0516735f,0.0340958f},{0.0216792f,-0.0516732f,0.0322314f},{0.0210316f,-0.0480087f,0.0322314f}, +{0.0210317f,-0.048009f,0.0340958f},{0.0267447f,-0.0655989f,0.0322314f},{0.0251156f,-0.0622535f,0.0340958f}, +{0.0267448f,-0.0655992f,0.0340958f},{0.0237253f,-0.0588085f,0.0322314f},{0.0237254f,-0.0588086f,0.0340958f}, +{0.0251155f,-0.0622533f,0.0322314f},{0.028609f,-0.0688327f,0.0340958f},{0.0286089f,-0.0688325f,0.0322314f}, +{0.0307038f,-0.0719411f,0.0340958f},{0.0307038f,-0.0719411f,0.0322314f},{0.0206235f,-0.00372882f,0.0322314f}, +{0.0206235f,-0.00372882f,0.0340958f},{0.0466102f,3.97423e-017f,0.0340958f},{0.0466102f,3.97423e-017f,0.0322314f}, +{0.0465018f,0.00126639f,0.0322314f},{0.0461802f,0.00249579f,0.0322314f},{0.0465022f,0.00126441f,0.0340958f}, +{0.0456552f,0.00365135f,0.0322314f},{0.0461804f,0.00249531f,0.0340958f},{0.0456558f,0.00365019f,0.0340958f}, +{0.0449402f,0.00470316f,0.0322314f},{0.0440587f,0.00561661f,0.0322314f},{0.0449409f,0.00470218f,0.0340958f}, +{0.043034f,0.00636795f,0.0322314f},{0.0440594f,0.00561601f,0.0340958f},{0.0430353f,0.00636709f,0.0340958f}, +{0.0418963f,0.00693455f,0.0322314f},{0.040681f,0.00729936f,0.0322314f},{0.0418969f,0.00693434f,0.0340958f}, +{0.0394182f,0.00745287f,0.0322314f},{0.0406822f,0.00729903f,0.0340958f},{0.0394186f,0.0074529f,0.0340958f}, +{0.0381506f,0.00739003f,0.0322314f},{0.0369109f,0.00711273f,0.0322314f},{0.0381517f,0.00739014f,0.0340958f}, +{0.0369109f,0.00711273f,0.0340958f},{0.0465018f,-0.00126639f,0.0340958f},{0.0465022f,-0.00126441f,0.0322314f}, +{0.0461802f,-0.00249579f,0.0340958f},{0.0456552f,-0.00365135f,0.0340958f},{0.0461804f,-0.00249531f,0.0322314f}, +{0.0449402f,-0.00470316f,0.0340958f},{0.0456558f,-0.00365019f,0.0322314f},{0.0449409f,-0.00470218f,0.0322314f}, +{0.0440587f,-0.00561661f,0.0340958f},{0.043034f,-0.00636795f,0.0340958f},{0.0440594f,-0.00561601f,0.0322314f}, +{0.0418963f,-0.00693455f,0.0340958f},{0.0430353f,-0.00636709f,0.0322314f},{0.0418969f,-0.00693434f,0.0322314f}, +{0.040681f,-0.00729936f,0.0340958f},{0.0394182f,-0.00745287f,0.0340958f},{0.0406822f,-0.00729903f,0.0322314f}, +{0.0381506f,-0.00739003f,0.0340958f},{0.0394186f,-0.0074529f,0.0322314f},{0.0381517f,-0.00739014f,0.0322314f}, +{0.0369109f,-0.00711273f,0.0340958f},{0.0369109f,-0.00711273f,0.0322314f},{0.0195103f,0.0755086f,0.0322314f}, +{0.0195103f,0.0755086f,0.0340958f},{0.0418944f,0.000544649f,0.0340958f},{-0.0396981f,0.00274259f,0.0340958f}, +{-0.0346445f,-0.00688452f,0.0340958f},{-0.033477f,-0.00713571f,0.0340958f},{0.0417351f,0.00106869f,0.0340958f}, +{-0.0323894f,-0.0734732f,0.0340958f},{-0.033477f,-0.0739661f,0.0340958f},{-0.029784f,-0.081654f,0.0340958f}, +{0.0396989f,-0.0783596f,0.0340958f},{0.0402234f,-0.0785201f,0.0340958f},{0.038082f,0.0836861f,0.0340958f}, +{0.0386071f,0.0838444f,0.0340958f},{0.041477f,0.00155172f,0.0340958f},{0.041477f,-0.0795501f,0.0340958f}, +{0.0411295f,-0.0791268f,0.0340958f},{0.0417351f,-0.0800331f,0.0340958f},{0.0411295f,0.00197505f,0.0340958f}, +{0.0418944f,-0.0805572f,0.0340958f},{0.0407062f,0.00232262f,0.0340958f},{0.0402234f,0.00258168f,0.0340958f}, +{0.0396989f,0.00274216f,0.0340958f},{0.0391526f,0.00279661f,0.0340958f},{0.0386071f,0.00274259f,0.0340958f}, +{0.038082f,0.00258432f,0.0340958f},{0.0358134f,0.00688407f,0.0340958f},{0.0375977f,0.00232618f,0.0340958f}, +{0.0364081f,0.000545524f,0.0340958f},{0.0236456f,0.00527349f,0.0340958f},{0.0365672f,0.00107021f,0.0340958f}, +{0.033477f,0.00713571f,0.0340958f},{0.0371735f,0.00197799f,0.0340958f},{0.0346445f,0.00688452f,0.0340958f}, +{0.0346482f,-0.00688511f,0.0340958f},{0.0241643f,0.0086281f,0.0340958f},{0.0243399f,0.00776655f,0.0340958f}, +{0.0230511f,-0.00462716f,0.0340958f},{0.023646f,-0.00527393f,0.0340958f},{-0.0396981f,0.0838444f,0.0340958f}, +{-0.0402232f,0.0836861f,0.0340958f},{-0.0386063f,0.083844f,0.0340958f},{-0.0380818f,0.0836835f,0.0340958f}, +{-0.0346445f,0.0742173f,0.0340958f},{-0.0308772f,0.0823454f,0.0340958f},{0.0211824f,0.075113f,0.0340958f}, +{0.0219051f,0.0746381f,0.0340958f},{0.0358165f,0.0742161f,0.0340958f},{0.0323894f,0.0734732f,0.0340958f}, +{0.033477f,0.0739661f,0.0340958f},{0.029784f,0.081654f,0.0340958f},{0.03177f,0.0832527f,0.0340958f}, +{0.0364081f,0.0816473f,0.0340958f},{0.0375977f,0.083428f,0.0340958f},{0.0371735f,0.0830798f,0.0340958f}, +{0.0407062f,0.0834244f,0.0340958f},{0.0417351f,0.0821705f,0.0340958f},{0.0418944f,0.0816464f,0.0340958f}, +{0.041477f,0.0826535f,0.0340958f},{0.0411295f,0.0830768f,0.0340958f},{0.0396989f,0.083844f,0.0340958f}, +{0.0402234f,0.0836835f,0.0340958f},{0.0391526f,0.0838984f,0.0340958f},{0.0365672f,0.082172f,0.0340958f}, +{0.0368257f,0.0826556f,0.0340958f},{0.0346482f,0.0742167f,0.0340958f},{0.0308757f,0.0823441f,0.0340958f}, +{0.0285789f,0.0812367f,0.0340958f},{0.0314497f,0.072778f,0.0340958f},{0.0224988f,0.0740097f,0.0340958f}, +{0.0229321f,0.0732614f,0.0340958f},{0.0203695f,0.0754087f,0.0340958f},{-0.0314481f,0.0727748f,0.0340958f}, +{-0.0285817f,0.0812363f,0.0340958f},{-0.0231141f,0.0708224f,0.0340958f},{-0.0407075f,0.083428f,0.0340958f}, +{-0.0411317f,0.0830798f,0.0340958f},{-0.0417379f,0.082172f,0.0340958f},{-0.0418971f,0.0816473f,0.0340958f}, +{-0.0414795f,0.0826556f,0.0340958f},{-0.0391526f,0.0838984f,0.0340958f},{-0.0358134f,0.0742177f,0.0340958f}, +{-0.037599f,0.0834244f,0.0340958f},{-0.033477f,0.0739661f,0.0340958f},{-0.0418971f,0.000545524f,0.0340958f}, +{-0.0371757f,0.0830768f,0.0340958f},{-0.0368282f,0.0826535f,0.0340958f},{-0.0365701f,0.0821705f,0.0340958f}, +{-0.0323867f,0.0734705f,0.0340958f},{-0.0297859f,0.0816548f,0.0340958f},{-0.0231106f,0.0727502f,0.0340958f}, +{-0.0241967f,-0.00852371f,0.0340958f},{-0.0323867f,-0.00763125f,0.0340958f},{-0.0314481f,-0.00832702f,0.0340958f}, +{-0.033477f,0.00713571f,0.0340958f},{-0.0365701f,0.00106869f,0.0340958f},{-0.0364108f,0.000544649f,0.0340958f}, +{-0.0323894f,0.00762858f,0.0340958f},{-0.0386063f,0.00274216f,0.0340958f},{-0.0391526f,0.00279661f,0.0340958f}, +{-0.0368282f,0.00155172f,0.0340958f},{-0.0417379f,0.00107021f,0.0340958f},{-0.0414795f,0.0015538f,0.0340958f}, +{-0.0411317f,0.00197799f,0.0340958f},{-0.0407075f,0.00232618f,0.0340958f},{-0.0402232f,0.00258432f,0.0340958f}, +{-0.0418971f,-0.0805563f,0.0340958f},{-0.0417379f,-0.0800316f,0.0340958f},{-0.0358134f,-0.00688407f,0.0340958f}, +{-0.0225127f,0.00424291f,0.0340958f},{-0.0380818f,0.00258168f,0.0340958f},{-0.0358165f,0.00688568f,0.0340958f}, +{0.0214967f,-0.00383203f,0.0340958f},{0.0223196f,0.0041374f,0.0340958f},{0.0214955f,0.00383263f,0.0340958f}, +{-0.0216024f,0.00385961f,0.0340958f},{-0.024244f,-0.0065653f,0.0340958f},{0.0314497f,-0.00832383f,0.0340958f}, +{0.0243085f,-0.00688932f,0.0340958f},{0.0364081f,-0.0805563f,0.0340958f},{0.0308772f,-0.0823454f,0.0340958f}, +{0.0314481f,-0.0727748f,0.0340958f},{0.0285817f,-0.0812363f,0.0340958f},{0.0230854f,-0.0707188f,0.0340958f}, +{-0.0285788f,-0.0812367f,0.0340958f},{-0.0213716f,-0.0750107f,0.0340958f},{-0.022144f,-0.0744194f,0.0340958f}, +{-0.0365701f,-0.0800331f,0.0340958f},{-0.0391526f,-0.0783052f,0.0340958f},{-0.03177f,-0.0832527f,0.0340958f}, +{-0.0308757f,-0.0823441f,0.0340958f},{-0.0364108f,-0.0805572f,0.0340958f},{-0.0414795f,-0.079548f,0.0340958f}, +{-0.0411317f,-0.0791238f,0.0340958f},{-0.0407075f,-0.0787756f,0.0340958f},{-0.0402232f,-0.0785175f,0.0340958f}, +{-0.0396981f,-0.0783592f,0.0340958f},{-0.0386063f,-0.0783596f,0.0340958f},{-0.0368282f,-0.0795501f,0.0340958f}, +{-0.0371757f,-0.0791268f,0.0340958f},{-0.0346482f,-0.0742167f,0.0340958f},{-0.0358165f,-0.0742161f,0.0340958f}, +{0.0386071f,-0.0783592f,0.0340958f},{0.038082f,-0.0785175f,0.0340958f},{-0.0314497f,-0.072778f,0.0340958f}, +{0.0391526f,-0.0783052f,0.0340958f},{0.0407062f,-0.0787792f,0.0340958f},{0.0358134f,-0.0742177f,0.0340958f}, +{0.0375977f,-0.0787756f,0.0340958f},{0.0368257f,-0.079548f,0.0340958f},{0.0346445f,-0.0742173f,0.0340958f}, +{0.0365672f,-0.0800316f,0.0340958f},{0.0371735f,-0.0791238f,0.0340958f},{0.0297859f,-0.0816548f,0.0340958f}, +{0.033477f,-0.0739661f,0.0340958f},{0.0317708f,-0.0832554f,0.0340958f},{0.0323867f,-0.0734706f,0.0340958f}, +{0.0229318f,-0.0732619f,0.0340958f},{0.0223212f,-0.0041373f,0.0340958f},{0.0240731f,-0.00604206f,0.0340958f}, +{0.0323894f,-0.00762858f,0.0340958f},{0.0243087f,0.00688805f,0.0340958f},{0.0314481f,0.00832702f,0.0340958f}, +{0.0323867f,0.00763125f,0.0340958f},{0.0358165f,-0.00688568f,0.0340958f},{-0.023239f,0.071786f,0.0340958f}, +{0.0232328f,0.0715697f,0.0340958f},{0.0230844f,0.0707181f,0.0340958f},{0.0231812f,0.072433f,0.0340958f}, +{0.0240729f,0.00604156f,0.0340958f},{0.02305f,0.00462664f,0.0340958f},{0.033477f,-0.00713571f,0.0340958f}, +{0.024339f,-0.00776783f,0.0340958f},{0.0241632f,-0.00862874f,0.0340958f},{-0.0314497f,0.00832383f,0.0340958f}, +{-0.0346482f,0.00688511f,0.0340958f},{0.0231813f,-0.0724342f,0.0340958f},{0.0232336f,-0.071571f,0.0340958f}, +{0.021904f,-0.0746385f,0.0340958f},{0.0224985f,-0.0740101f,0.0340958f},{0.0203684f,-0.0754081f,0.0340958f}, +{0.0211809f,-0.0751129f,0.0340958f},{-0.0204736f,-0.075382f,0.0340958f},{-0.0243511f,-0.0075482f,0.0340958f}, +{-0.0232912f,0.00485238f,0.0340958f},{-0.0380818f,-0.0785201f,0.0340958f},{-0.037599f,-0.0787792f,0.0340958f}, +{-0.0364108f,0.0816464f,0.0340958f},{-0.0317708f,0.0832554f,0.0340958f},{0.0368257f,0.0015538f,0.0340958f}, +{-0.037599f,0.00232262f,0.0340958f},{-0.0371757f,0.00197505f,0.0340958f},{0.0314481f,0.0727748f,0.0322314f}, +{0.0229318f,0.0732619f,0.0322314f},{-0.0358134f,-0.0742177f,0.0322314f},{-0.0375977f,-0.0787756f,0.0322314f}, +{-0.038082f,-0.0785175f,0.0322314f},{-0.0391526f,-0.0783052f,0.0322314f},{0.0243399f,-0.00776655f,0.0322314f}, +{0.0243087f,-0.00688805f,0.0322314f},{0.0358165f,0.00688568f,0.0322314f},{0.0380818f,0.00258168f,0.0322314f}, +{0.037599f,0.00232262f,0.0322314f},{0.0241643f,-0.0086281f,0.0322314f},{0.033477f,-0.00713571f,0.0322314f}, +{0.0323867f,-0.00763125f,0.0322314f},{0.0396981f,0.00274259f,0.0322314f},{0.0391526f,0.00279661f,0.0322314f}, +{0.0407075f,0.00232618f,0.0322314f},{0.0402232f,0.00258432f,0.0322314f},{0.0417379f,0.00107021f,0.0322314f}, +{0.0358134f,-0.00688407f,0.0322314f},{0.0346445f,-0.00688452f,0.0322314f},{0.0417379f,0.082172f,0.0322314f}, +{0.0407075f,0.083428f,0.0322314f},{0.0402232f,0.0836861f,0.0322314f},{0.0396981f,0.0838444f,0.0322314f}, +{0.0418971f,0.000545524f,0.0322314f},{0.0414795f,0.0015538f,0.0322314f},{0.0411317f,0.00197799f,0.0322314f}, +{0.0386063f,0.00274216f,0.0322314f},{0.033477f,0.00713571f,0.0322314f},{0.0364108f,0.000544649f,0.0322314f}, +{0.0323894f,0.00762858f,0.0322314f},{0.0240729f,-0.00604156f,0.0322314f},{0.0236456f,-0.00527349f,0.0322314f}, +{0.0223212f,0.0041373f,0.0322314f},{0.0230511f,0.00462716f,0.0322314f},{0.0223196f,-0.0041374f,0.0322314f}, +{0.0346482f,0.00688511f,0.0322314f},{0.0368282f,0.00155172f,0.0322314f},{0.0365701f,0.00106869f,0.0322314f}, +{-0.0346445f,-0.0742173f,0.0322314f},{-0.0371735f,-0.0791238f,0.0322314f},{-0.0386071f,-0.0783592f,0.0322314f}, +{-0.0396989f,-0.0783596f,0.0322314f},{-0.0402234f,-0.0785201f,0.0322314f},{-0.0417351f,-0.0800331f,0.0322314f}, +{-0.0407062f,-0.0787792f,0.0322314f},{-0.0411295f,-0.0791268f,0.0322314f},{-0.041477f,-0.0795501f,0.0322314f}, +{-0.0285817f,-0.0812363f,0.0322314f},{-0.0323867f,-0.0734706f,0.0322314f},{-0.0314481f,-0.0727748f,0.0322314f}, +{-0.0365672f,-0.0800316f,0.0322314f},{-0.0308772f,-0.0823454f,0.0322314f},{-0.0364081f,-0.0805563f,0.0322314f}, +{0.029784f,-0.081654f,0.0322314f},{0.0323894f,-0.0734732f,0.0322314f},{0.033477f,-0.0739661f,0.0322314f}, +{0.0219051f,-0.0746381f,0.0322314f},{0.0211824f,-0.075113f,0.0322314f},{0.0391526f,-0.0783052f,0.0322314f}, +{0.0396981f,-0.0783592f,0.0322314f},{0.0386063f,-0.0783596f,0.0322314f},{0.0411317f,-0.0791238f,0.0322314f}, +{0.0407075f,-0.0787756f,0.0322314f},{0.0414795f,-0.079548f,0.0322314f},{0.0365701f,-0.0800331f,0.0322314f}, +{0.0417379f,-0.0800316f,0.0322314f},{0.0418971f,-0.0805563f,0.0322314f},{0.03177f,-0.0832527f,0.0322314f}, +{0.0308757f,-0.0823441f,0.0322314f},{0.0364108f,-0.0805572f,0.0322314f},{0.0402232f,-0.0785175f,0.0322314f}, +{0.0380818f,-0.0785201f,0.0322314f},{0.0346482f,-0.0742167f,0.0322314f},{0.0368282f,-0.0795501f,0.0322314f}, +{0.0371757f,-0.0791268f,0.0322314f},{0.0285789f,-0.0812367f,0.0322314f},{0.0314497f,-0.072778f,0.0322314f}, +{0.0224988f,-0.0740097f,0.0322314f},{0.0229321f,-0.0732614f,0.0322314f},{0.0230844f,-0.0707181f,0.0322314f}, +{-0.0418944f,-0.0805572f,0.0322314f},{-0.033477f,-0.0739661f,0.0322314f},{-0.0297859f,-0.0816548f,0.0322314f}, +{-0.0317708f,-0.0832554f,0.0322314f},{-0.0243512f,-0.00754595f,0.0322314f},{-0.0242437f,-0.00656417f,0.0322314f}, +{-0.0216035f,0.00385992f,0.0322314f},{-0.024197f,-0.00852259f,0.0322314f},{-0.0323867f,0.00763125f,0.0322314f}, +{-0.0364081f,0.000545524f,0.0322314f},{-0.0418944f,0.000544649f,0.0322314f},{-0.0411295f,0.00197505f,0.0322314f}, +{-0.0407062f,0.00232262f,0.0322314f},{-0.0386071f,0.00274259f,0.0322314f},{-0.0391526f,0.00279661f,0.0322314f}, +{-0.0358134f,0.00688407f,0.0322314f},{-0.0375977f,0.00232618f,0.0322314f},{-0.038082f,0.00258432f,0.0322314f}, +{-0.041477f,0.00155172f,0.0322314f},{-0.0417351f,0.00106869f,0.0322314f},{-0.0402234f,0.00258168f,0.0322314f}, +{-0.0371735f,0.00197799f,0.0322314f},{-0.0346445f,0.00688452f,0.0322314f},{-0.0396989f,0.00274216f,0.0322314f}, +{-0.0358165f,-0.00688568f,0.0322314f},{-0.033477f,0.00713571f,0.0322314f},{-0.023292f,0.00485321f,0.0322314f}, +{-0.0346482f,-0.00688511f,0.0322314f},{0.0314497f,0.00832383f,0.0322314f},{0.0243085f,0.00688932f,0.0322314f}, +{0.0230854f,0.0707188f,0.0322314f},{-0.0346482f,0.0742167f,0.0322314f},{-0.033477f,0.0739661f,0.0322314f}, +{-0.0231144f,0.0708235f,0.0322314f},{-0.0368257f,0.0826556f,0.0322314f},{-0.0396989f,0.083844f,0.0322314f}, +{-0.0391526f,0.0838984f,0.0322314f},{-0.0375977f,0.083428f,0.0322314f},{-0.038082f,0.0836861f,0.0322314f}, +{-0.0411295f,0.0830768f,0.0322314f},{-0.041477f,0.0826535f,0.0322314f},{-0.0371735f,0.0830798f,0.0322314f}, +{-0.0418944f,0.0816464f,0.0322314f},{-0.0417351f,0.0821705f,0.0322314f},{-0.0402234f,0.0836835f,0.0322314f}, +{-0.0386071f,0.0838444f,0.0322314f},{-0.0407062f,0.0834244f,0.0322314f},{-0.0364081f,0.0816473f,0.0322314f}, +{-0.0365672f,0.082172f,0.0322314f},{-0.03177f,0.0832527f,0.0322314f},{-0.0308757f,0.0823441f,0.0322314f}, +{-0.0358165f,0.0742161f,0.0322314f},{-0.029784f,0.081654f,0.0322314f},{-0.0323894f,0.0734732f,0.0322314f}, +{-0.0285788f,0.0812367f,0.0322314f},{-0.0314497f,0.072778f,0.0322314f},{-0.0231103f,0.0727513f,0.0322314f}, +{0.0391526f,0.0838984f,0.0322314f},{0.0380818f,0.0836835f,0.0322314f},{0.0386063f,0.083844f,0.0322314f}, +{0.0414795f,0.0826556f,0.0322314f},{0.0411317f,0.0830798f,0.0322314f},{0.0418971f,0.0816473f,0.0322314f}, +{0.0358134f,0.0742177f,0.0322314f},{0.0346445f,0.0742173f,0.0322314f},{0.033477f,0.0739661f,0.0322314f}, +{0.0371757f,0.0830768f,0.0322314f},{0.037599f,0.0834244f,0.0322314f},{0.0368282f,0.0826535f,0.0322314f}, +{0.0308772f,0.0823454f,0.0322314f},{0.0323867f,0.0734705f,0.0322314f},{0.0297859f,0.0816548f,0.0322314f}, +{0.0285817f,0.0812363f,0.0322314f},{0.0187991f,0.0422603f,0.0322314f},{0.0232336f,0.071571f,0.0322314f}, +{0.0231813f,0.0724342f,0.0322314f},{0.021904f,0.0746385f,0.0322314f},{0.0224985f,0.0740101f,0.0322314f}, +{0.0203684f,0.0754081f,0.0322314f},{0.0211809f,0.0751129f,0.0322314f},{-0.023239f,0.0717882f,0.0322314f}, +{0.024339f,0.00776783f,0.0322314f},{0.0241632f,0.00862874f,0.0322314f},{-0.0314481f,0.00832702f,0.0322314f}, +{-0.0225146f,0.00424405f,0.0322314f},{-0.0323894f,-0.00762858f,0.0322314f},{-0.0314497f,-0.00832383f,0.0322314f}, +{0.023646f,0.00527393f,0.0322314f},{0.0240731f,0.00604206f,0.0322314f},{0.0314481f,-0.00832702f,0.0322314f}, +{0.02305f,-0.00462664f,0.0322314f},{0.0214955f,-0.00383263f,0.0322314f},{0.0214967f,0.00383203f,0.0322314f}, +{-0.033477f,-0.00713571f,0.0322314f},{-0.0213735f,-0.0750096f,0.0322314f},{-0.0221448f,-0.0744186f,0.0322314f}, +{-0.0204747f,-0.0753817f,0.0322314f},{0.0232328f,-0.0715697f,0.0322314f},{0.0231812f,-0.072433f,0.0322314f}, +{0.0203695f,-0.0754087f,0.0322314f},{-0.0368257f,-0.079548f,0.0322314f},{0.0358165f,-0.0742161f,0.0322314f}, +{0.037599f,-0.0787792f,0.0322314f},{0.0365701f,0.0821705f,0.0322314f},{0.0364108f,0.0816464f,0.0322314f}, +{0.0317708f,0.0832554f,0.0322314f},{0.0371757f,0.00197505f,0.0322314f},{-0.0368257f,0.0015538f,0.0322314f}, +{-0.0365672f,0.00107021f,0.0322314f},{-0.285968f,-0.0125242f,0.0900281f},{-0.286022f,-0.0130723f,0.0918925f}, +{-0.285968f,-0.0125242f,0.0918925f},{-0.286181f,-0.011454f,0.0918925f},{-0.286181f,-0.011454f,0.0900281f}, +{-0.286022f,-0.0119761f,0.0918925f},{-0.286022f,-0.0119761f,0.0900281f},{-0.286438f,-0.0109726f,0.0900281f}, +{-0.286787f,-0.0105467f,0.0900281f},{-0.286787f,-0.0105467f,0.0918925f},{-0.287213f,-0.0101975f,0.0900281f}, +{-0.287213f,-0.0101975f,0.0918925f},{-0.286438f,-0.0109726f,0.0918925f},{-0.288764f,-0.00972758f,0.0900281f}, +{-0.288216f,-0.00978182f,0.0900281f},{-0.288216f,-0.00978182f,0.0918925f},{-0.287694f,-0.00994047f,0.0918925f}, +{-0.287694f,-0.00994047f,0.0900281f},{-0.288764f,-0.00972758f,0.0918925f},{-0.286022f,-0.0130723f,0.0900281f}, +{-0.286181f,-0.0135944f,0.0918925f},{-0.286181f,-0.0135944f,0.0900281f},{-0.286438f,-0.0140758f,0.0900281f}, +{-0.286438f,-0.0140758f,0.0918925f},{-0.286787f,-0.0145017f,0.0900281f},{-0.286787f,-0.0145017f,0.0918925f}, +{-0.287213f,-0.0148509f,0.0918925f},{-0.287213f,-0.0148509f,0.0900281f},{-0.287694f,-0.0151079f,0.0900281f}, +{-0.287694f,-0.0151079f,0.0918925f},{-0.288216f,-0.0152666f,0.0900281f},{-0.288216f,-0.0152666f,0.0918925f}, +{-0.288764f,-0.0153208f,0.0918925f},{-0.288764f,-0.0153208f,0.0900281f},{-0.311016f,0.0125242f,0.0900281f}, +{-0.31107f,0.0119761f,0.0918925f},{-0.311016f,0.0125242f,0.0918925f},{-0.311229f,0.0135944f,0.0918925f}, +{-0.311229f,0.0135944f,0.0900281f},{-0.31107f,0.0130723f,0.0918925f},{-0.31107f,0.0130723f,0.0900281f}, +{-0.311486f,0.0140758f,0.0900281f},{-0.311835f,0.0145017f,0.0900281f},{-0.311835f,0.0145017f,0.0918925f}, +{-0.312261f,0.0148509f,0.0900281f},{-0.312261f,0.0148509f,0.0918925f},{-0.311486f,0.0140758f,0.0918925f}, +{-0.313813f,0.0153208f,0.0900281f},{-0.313265f,0.0152666f,0.0900281f},{-0.313265f,0.0152666f,0.0918925f}, +{-0.312743f,0.0151079f,0.0918925f},{-0.312743f,0.0151079f,0.0900281f},{-0.313813f,0.0153208f,0.0918925f}, +{-0.31107f,0.0119761f,0.0900281f},{-0.311229f,0.011454f,0.0918925f},{-0.311229f,0.011454f,0.0900281f}, +{-0.311486f,0.0109726f,0.0900281f},{-0.311486f,0.0109726f,0.0918925f},{-0.311835f,0.0105467f,0.0900281f}, +{-0.311835f,0.0105467f,0.0918925f},{-0.312261f,0.0101975f,0.0918925f},{-0.312261f,0.0101975f,0.0900281f}, +{-0.312743f,0.00994047f,0.0900281f},{-0.312743f,0.00994047f,0.0918925f},{-0.313265f,0.00978182f,0.0900281f}, +{-0.313265f,0.00978182f,0.0918925f},{-0.313813f,0.00972758f,0.0918925f},{-0.313813f,0.00972758f,0.0900281f}, +{-0.284736f,-0.0073455f,0.0900281f},{-0.285954f,-0.00738926f,0.0918925f},{-0.284736f,-0.00734538f,0.0918925f}, +{-0.283556f,-0.00703877f,0.0900281f},{-0.283555f,-0.0070384f,0.0918925f},{-0.28247f,-0.00648281f,0.0900281f}, +{-0.28247f,-0.00648282f,0.0918925f},{-0.285956f,-0.00738915f,0.0900281f},{-0.287154f,-0.00716427f,0.0918925f}, +{-0.287154f,-0.00716427f,0.0900281f},{-0.309858f,0.00856857f,0.0918925f},{-0.310706f,0.0078732f,0.0918925f}, +{-0.309857f,0.00856991f,0.0900281f},{-0.310705f,0.00787361f,0.0900281f},{-0.311673f,0.0073566f,0.0918925f}, +{-0.312722f,0.00703838f,0.0918925f},{-0.311672f,0.00735691f,0.0900281f},{-0.313813f,0.00693097f,0.0918925f}, +{-0.312721f,0.00703853f,0.0900281f},{-0.313813f,0.00693097f,0.0900281f},{-0.309162f,0.00941743f,0.0900281f}, +{-0.308645f,0.0103841f,0.0900281f},{-0.309162f,0.00941663f,0.0918925f},{-0.308327f,0.0114331f,0.0900281f}, +{-0.308645f,0.0103834f,0.0918925f},{-0.308327f,0.0114326f,0.0918925f},{-0.30822f,0.0125242f,0.0900281f}, +{-0.30822f,0.0125242f,0.0918925f},{-0.401959f,-0.065917f,0.0918925f},{-0.398048f,-0.0617984f,0.0918925f}, +{-0.40196f,-0.0659174f,0.0900281f},{-0.405692f,-0.07019f,0.0900281f},{-0.405691f,-0.0701898f,0.0918925f}, +{-0.409237f,-0.0746077f,0.0900281f},{-0.409237f,-0.0746076f,0.0918925f},{-0.412592f,-0.0791643f,0.0918925f}, +{-0.412592f,-0.0791644f,0.0900281f},{-0.415754f,-0.0838538f,0.0900281f},{-0.415754f,-0.0838537f,0.0918925f}, +{-0.418717f,-0.0886696f,0.0900281f},{-0.418717f,-0.0886696f,0.0918925f},{-0.421479f,-0.0936056f,0.0918925f}, +{-0.421479f,-0.0936057f,0.0900281f},{-0.424035f,-0.0986557f,0.0900281f},{-0.424035f,-0.0986556f,0.0918925f}, +{-0.426382f,-0.103813f,0.0900281f},{-0.426382f,-0.103813f,0.0918925f},{-0.428515f,-0.109072f,0.0918925f}, +{-0.428515f,-0.109073f,0.0900281f},{-0.430428f,-0.11442f,0.0900281f},{-0.430428f,-0.11442f,0.0918925f}, +{-0.432114f,-0.119834f,0.0900281f},{-0.432114f,-0.119834f,0.0918925f},{-0.433572f,-0.125306f,0.0918925f}, +{-0.433572f,-0.125307f,0.0900281f},{-0.4348f,-0.130829f,0.0900281f},{-0.4348f,-0.130829f,0.0918925f}, +{-0.435797f,-0.136396f,0.0900281f},{-0.435797f,-0.136396f,0.0918925f},{-0.436561f,-0.141999f,0.0918925f}, +{-0.436561f,-0.141999f,0.0900281f},{-0.437093f,-0.147631f,0.0900281f},{-0.437093f,-0.147631f,0.0918925f}, +{-0.437391f,-0.153284f,0.0900281f},{-0.437391f,-0.153284f,0.0918925f},{-0.437453f,-0.158952f,0.0918925f}, +{-0.437453f,-0.158952f,0.0900281f},{-0.437279f,-0.164627f,0.0900281f},{-0.437279f,-0.164627f,0.0918925f}, +{-0.398048f,-0.0617987f,0.0900281f},{-0.393973f,-0.0578515f,0.0900281f},{-0.393973f,-0.0578514f,0.0918925f}, +{-0.389744f,-0.054083f,0.0918925f},{-0.389744f,-0.0540831f,0.0900281f},{-0.385366f,-0.0504973f,0.0918925f}, +{-0.385366f,-0.0504974f,0.0900281f},{-0.380846f,-0.0470986f,0.0900281f},{-0.380846f,-0.0470985f,0.0918925f}, +{-0.376189f,-0.0438908f,0.0918925f},{-0.376189f,-0.0438908f,0.0900281f},{-0.371402f,-0.0408784f,0.0918925f}, +{-0.371402f,-0.0408785f,0.0900281f},{-0.36649f,-0.0380656f,0.0900281f},{-0.36649f,-0.0380655f,0.0918925f}, +{-0.36146f,-0.0354565f,0.0918925f},{-0.36146f,-0.0354565f,0.0900281f},{-0.356317f,-0.0330551f,0.0918925f}, +{-0.356318f,-0.0330554f,0.0900281f},{-0.351076f,-0.0308688f,0.0900281f},{-0.351076f,-0.0308688f,0.0918925f}, +{-0.345756f,-0.0289059f,0.0918925f},{-0.345756f,-0.0289059f,0.0900281f},{-0.340366f,-0.0271683f,0.0918925f}, +{-0.340366f,-0.0271684f,0.0900281f},{-0.334914f,-0.0256577f,0.0900281f},{-0.334914f,-0.0256577f,0.0918925f}, +{-0.329406f,-0.0243753f,0.0918925f},{-0.329406f,-0.0243754f,0.0900281f},{-0.32385f,-0.0233228f,0.0918925f}, +{-0.32385f,-0.0233228f,0.0900281f},{-0.318253f,-0.0225016f,0.0900281f},{-0.318253f,-0.0225016f,0.0918925f}, +{-0.312622f,-0.0219132f,0.0918925f},{-0.312623f,-0.0219132f,0.0900281f},{-0.306965f,-0.0215591f,0.0918925f}, +{-0.306965f,-0.0215591f,0.0900281f},{-0.301289f,-0.0214407f,0.0918925f},{-0.301289f,-0.0214407f,0.0900281f}, +{-0.300061f,-0.0214056f,0.0918925f},{-0.300061f,-0.0214056f,0.0900281f},{-0.298838f,-0.0213002f,0.0900281f}, +{-0.298838f,-0.0213002f,0.0918925f},{-0.29272f,-0.00857005f,0.0900281f},{-0.293362f,-0.00933952f,0.0900281f}, +{-0.292718f,-0.00856812f,0.0918925f},{-0.293856f,-0.0102104f,0.0918925f},{-0.293362f,-0.00933867f,0.0918925f}, +{-0.293857f,-0.010212f,0.0900281f},{-0.294188f,-0.0111572f,0.0918925f},{-0.294188f,-0.0111588f,0.0900281f}, +{-0.294345f,-0.0121484f,0.0918925f},{-0.294322f,-0.0131504f,0.0918925f},{-0.294345f,-0.0121494f,0.0900281f}, +{-0.294121f,-0.0141339f,0.0900281f},{-0.294322f,-0.0131516f,0.0900281f},{-0.294121f,-0.0141339f,0.0918925f}, +{-0.291949f,-0.00792586f,0.0918925f},{-0.29195f,-0.00792654f,0.0900281f},{-0.291078f,-0.00743177f,0.0900281f}, +{-0.290131f,-0.00710074f,0.0900281f},{-0.291076f,-0.00743116f,0.0918925f},{-0.290129f,-0.00710007f,0.0918925f}, +{-0.28914f,-0.00694354f,0.0900281f},{-0.289139f,-0.00694356f,0.0918925f},{-0.288138f,-0.00696625f,0.0900281f}, +{-0.288136f,-0.00696632f,0.0918925f},{-0.283634f,0.0121669f,0.0900281f},{-0.282482f,0.0102959f,0.0900281f}, +{-0.282482f,0.0102961f,0.0918925f},{-0.283634f,0.012167f,0.0918925f},{-0.284976f,0.013914f,0.0900281f}, +{-0.281528f,0.008319f,0.0918925f},{-0.281527f,0.00831882f,0.0900281f},{-0.280779f,0.00625128f,0.0918925f}, +{-0.280779f,0.00625078f,0.0900281f},{-0.280246f,0.00411456f,0.0918925f},{-0.280246f,0.00411435f,0.0900281f}, +{-0.279936f,0.00194003f,0.0900281f},{-0.279936f,0.0019402f,0.0918925f},{-0.279849f,-0.000253827f,0.0918925f}, +{-0.279988f,-0.00245022f,0.0918925f},{-0.279849f,-0.00025393f,0.0900281f},{-0.279988f,-0.00245022f,0.0900281f}, +{-0.286486f,0.0155106f,0.0900281f},{-0.284976f,0.0139141f,0.0918925f},{-0.286486f,0.0155107f,0.0918925f}, +{-0.288149f,0.016943f,0.0900281f},{-0.28815f,0.0169431f,0.0918925f},{-0.289954f,0.0181996f,0.0900281f}, +{-0.29188f,0.0192663f,0.0900281f},{-0.289954f,0.0181999f,0.0918925f},{-0.291881f,0.0192664f,0.0918925f}, +{-0.293901f,0.0201277f,0.0900281f},{-0.293901f,0.0201278f,0.0918925f},{-0.295998f,0.0207778f,0.0900281f}, +{-0.298156f,0.0212106f,0.0900281f},{-0.295998f,0.0207778f,0.0918925f},{-0.298156f,0.0212106f,0.0918925f}, +{-0.303955f,0.0200545f,0.0900281f},{-0.302604f,0.0207145f,0.0918925f},{-0.303956f,0.020054f,0.0918925f}, +{-0.305176f,0.0191712f,0.0900281f},{-0.302603f,0.0207149f,0.0900281f},{-0.301156f,0.0211353f,0.0918925f}, +{-0.305176f,0.0191712f,0.0918925f},{-0.301155f,0.0211356f,0.0900281f},{-0.29966f,0.021302f,0.0918925f}, +{-0.299659f,0.0213021f,0.0900281f},{-0.306228f,0.0180928f,0.0900281f},{-0.306229f,0.018092f,0.0918925f}, +{-0.307079f,0.0168512f,0.0918925f},{-0.307079f,0.0168521f,0.0900281f},{-0.307707f,0.0154797f,0.0918925f}, +{-0.307707f,0.0154807f,0.0900281f},{-0.30809f,0.0140259f,0.0900281f},{-0.30809f,0.014025f,0.0918925f}, +{-0.314904f,0.00703853f,0.0918925f},{-0.317768f,0.00856991f,0.0918925f},{-0.31692f,0.0078732f,0.0900281f}, +{-0.31692f,0.00787361f,0.0918925f},{-0.315954f,0.00735691f,0.0918925f},{-0.315953f,0.0073566f,0.0900281f}, +{-0.314904f,0.00703838f,0.0900281f},{-0.31898f,0.0103834f,0.0900281f},{-0.31898f,0.0103841f,0.0918925f}, +{-0.319299f,0.0114331f,0.0918925f},{-0.317767f,0.00856857f,0.0900281f},{-0.318464f,0.00941743f,0.0918925f}, +{-0.318463f,0.00941663f,0.0900281f},{-0.319406f,0.0125242f,0.0918925f},{-0.319298f,0.0114326f,0.0900281f}, +{-0.319406f,0.0125242f,0.0900281f},{-0.32063f,0.017806f,0.0900281f},{-0.32063f,0.0178073f,0.0918925f}, +{-0.321554f,0.0193785f,0.0900281f},{-0.321554f,0.0193787f,0.0918925f},{-0.319955f,0.0161135f,0.0918925f}, +{-0.319955f,0.0161128f,0.0900281f},{-0.319544f,0.0143418f,0.0900281f},{-0.319544f,0.0143423f,0.0918925f}, +{-0.322701f,0.0207886f,0.0900281f},{-0.324052f,0.0220123f,0.0900281f},{-0.322701f,0.0207888f,0.0918925f}, +{-0.324053f,0.0220132f,0.0918925f},{-0.325573f,0.023018f,0.0900281f},{-0.325573f,0.0230183f,0.0918925f}, +{-0.327224f,0.02378f,0.0900281f},{-0.328976f,0.0242851f,0.0900281f},{-0.327224f,0.0237802f,0.0918925f}, +{-0.328976f,0.0242851f,0.0918925f},{-0.409092f,0.0744192f,0.0918925f},{-0.409092f,0.0744192f,0.0900281f}, +{-0.405539f,0.0700077f,0.0900281f},{-0.401803f,0.065746f,0.0900281f},{-0.405539f,0.0700077f,0.0918925f}, +{-0.397891f,0.06164f,0.0900281f},{-0.401803f,0.0657461f,0.0918925f},{-0.397891f,0.0616401f,0.0918925f}, +{-0.393805f,0.0576956f,0.0900281f},{-0.389551f,0.0539185f,0.0900281f},{-0.393805f,0.0576957f,0.0918925f}, +{-0.385134f,0.0503158f,0.0900281f},{-0.389551f,0.0539186f,0.0918925f},{-0.385135f,0.050316f,0.0918925f}, +{-0.380577f,0.0469052f,0.0900281f},{-0.375889f,0.0436939f,0.0900281f},{-0.380577f,0.0469052f,0.0918925f}, +{-0.371079f,0.0406851f,0.0900281f},{-0.375889f,0.0436939f,0.0918925f},{-0.371079f,0.0406851f,0.0918925f}, +{-0.366152f,0.0378819f,0.0900281f},{-0.361116f,0.0352877f,0.0900281f},{-0.366152f,0.037882f,0.0918925f}, +{-0.355977f,0.0329054f,0.0900281f},{-0.361116f,0.0352877f,0.0918925f},{-0.355977f,0.0329055f,0.0918925f}, +{-0.350742f,0.0307383f,0.0900281f},{-0.345418f,0.0287896f,0.0900281f},{-0.350742f,0.0307384f,0.0918925f}, +{-0.340011f,0.0270624f,0.0900281f},{-0.345418f,0.0287897f,0.0918925f},{-0.340011f,0.0270624f,0.0918925f}, +{-0.334528f,0.0255598f,0.0900281f},{-0.334528f,0.0255599f,0.0918925f},{-0.412458f,0.0789746f,0.0918925f}, +{-0.412458f,0.0789746f,0.0900281f},{-0.415634f,0.0836681f,0.0918925f},{-0.418614f,0.0884938f,0.0918925f}, +{-0.415634f,0.083668f,0.0900281f},{-0.421394f,0.0934459f,0.0918925f},{-0.418614f,0.0884937f,0.0900281f}, +{-0.421394f,0.0934458f,0.0900281f},{-0.423969f,0.0985185f,0.0918925f},{-0.426335f,0.103704f,0.0918925f}, +{-0.423969f,0.0985183f,0.0900281f},{-0.428478f,0.108978f,0.0918925f},{-0.426334f,0.103704f,0.0900281f}, +{-0.428478f,0.108977f,0.0900281f},{-0.430397f,0.114326f,0.0918925f},{-0.432088f,0.119742f,0.0918925f}, +{-0.430397f,0.114326f,0.0900281f},{-0.43355f,0.125218f,0.0918925f},{-0.432088f,0.119742f,0.0900281f}, +{-0.43355f,0.125218f,0.0900281f},{-0.434783f,0.130747f,0.0918925f},{-0.435785f,0.136322f,0.0918925f}, +{-0.434783f,0.130747f,0.0900281f},{-0.436554f,0.141936f,0.0918925f},{-0.435785f,0.136322f,0.0900281f}, +{-0.436554f,0.141935f,0.0900281f},{-0.43709f,0.14758f,0.0918925f},{-0.43739f,0.153248f,0.0918925f}, +{-0.43709f,0.14758f,0.0900281f},{-0.437453f,0.158933f,0.0918925f},{-0.43739f,0.153248f,0.0900281f}, +{-0.437453f,0.158933f,0.0900281f},{-0.437279f,0.164627f,0.0918925f},{-0.437279f,0.164627f,0.0900281f}, +{-0.445352f,0.169288f,0.0900281f},{-0.445352f,0.169288f,0.0918925f},{-0.489867f,0.0239114f,0.0918925f}, +{-0.490408f,0.0143525f,0.0918925f},{-0.490408f,0.0143527f,0.0900281f},{-0.490679f,-0.00478512f,0.0900281f}, +{-0.490679f,0.00478519f,0.0900281f},{-0.490679f,0.00478512f,0.0918925f},{-0.489867f,0.0239115f,0.0900281f}, +{-0.489056f,0.0334558f,0.0918925f},{-0.489056f,0.0334558f,0.0900281f},{-0.487973f,0.0429801f,0.0900281f}, +{-0.487973f,0.04298f,0.0918925f},{-0.486621f,0.0524782f,0.0918925f},{-0.486621f,0.0524784f,0.0900281f}, +{-0.484998f,0.0619436f,0.0900281f},{-0.484998f,0.0619434f,0.0918925f},{-0.480955f,0.0806965f,0.0900281f}, +{-0.47854f,0.089968f,0.0900281f},{-0.47854f,0.0899679f,0.0918925f},{-0.483109f,0.0713532f,0.0918925f}, +{-0.483109f,0.0713532f,0.0900281f},{-0.480955f,0.0806964f,0.0918925f},{-0.475866f,0.0991622f,0.0918925f}, +{-0.475866f,0.0991623f,0.0900281f},{-0.472933f,0.108274f,0.0900281f},{-0.472933f,0.108274f,0.0918925f}, +{-0.469745f,0.117298f,0.0918925f},{-0.469745f,0.117298f,0.0900281f},{-0.466302f,0.126228f,0.0918925f}, +{-0.458664f,0.143787f,0.0900281f},{-0.458664f,0.143786f,0.0918925f},{-0.462608f,0.135059f,0.0900281f}, +{-0.462608f,0.135059f,0.0918925f},{-0.466302f,0.126228f,0.0900281f},{-0.454472f,0.152404f,0.0900281f}, +{-0.454472f,0.152404f,0.0918925f},{-0.450034f,0.160907f,0.0900281f},{-0.450034f,0.160906f,0.0918925f}, +{-0.490679f,-0.00478519f,0.0918925f},{-0.490408f,-0.0143525f,0.0900281f},{-0.490408f,-0.0143527f,0.0918925f}, +{-0.489867f,-0.0239114f,0.0900281f},{-0.489056f,-0.0334558f,0.0900281f},{-0.489867f,-0.0239115f,0.0918925f}, +{-0.489056f,-0.0334558f,0.0918925f},{-0.487973f,-0.04298f,0.0900281f},{-0.487973f,-0.0429801f,0.0918925f}, +{-0.486621f,-0.0524782f,0.0900281f},{-0.484998f,-0.0619434f,0.0900281f},{-0.486621f,-0.0524784f,0.0918925f}, +{-0.484998f,-0.0619436f,0.0918925f},{-0.483109f,-0.0713532f,0.0900281f},{-0.483109f,-0.0713532f,0.0918925f}, +{-0.480955f,-0.0806964f,0.0900281f},{-0.47854f,-0.0899679f,0.0900281f},{-0.480955f,-0.0806965f,0.0918925f}, +{-0.47854f,-0.089968f,0.0918925f},{-0.475866f,-0.0991622f,0.0900281f},{-0.475866f,-0.0991623f,0.0918925f}, +{-0.472933f,-0.108274f,0.0900281f},{-0.469745f,-0.117298f,0.0900281f},{-0.472933f,-0.108274f,0.0918925f}, +{-0.469745f,-0.117298f,0.0918925f},{-0.466302f,-0.126228f,0.0900281f},{-0.466302f,-0.126228f,0.0918925f}, +{-0.462608f,-0.135059f,0.0900281f},{-0.458664f,-0.143786f,0.0900281f},{-0.462608f,-0.135059f,0.0918925f}, +{-0.458664f,-0.143787f,0.0918925f},{-0.454472f,-0.152404f,0.0900281f},{-0.454472f,-0.152404f,0.0918925f}, +{-0.450034f,-0.160906f,0.0900281f},{-0.445352f,-0.169288f,0.0900281f},{-0.450034f,-0.160907f,0.0918925f}, +{-0.445352f,-0.169288f,0.0918925f},{-0.427553f,0.169776f,0.0918925f},{-0.448656f,0.18196f,0.0900281f}, +{-0.448656f,0.18196f,0.0918925f},{-0.427553f,0.169776f,0.0900281f},{-0.400468f,0.0785294f,0.0900281f}, +{-0.403757f,0.0828396f,0.0900281f},{-0.403757f,0.0828395f,0.0918925f},{-0.396993f,0.0743574f,0.0900281f}, +{-0.396993f,0.074357f,0.0918925f},{-0.393337f,0.0703325f,0.0900281f},{-0.406855f,0.0872815f,0.0918925f}, +{-0.400468f,0.0785292f,0.0918925f},{-0.406855f,0.0872816f,0.0900281f},{-0.409759f,0.0918488f,0.0918925f}, +{-0.409759f,0.091849f,0.0900281f},{-0.412465f,0.0965352f,0.0900281f},{-0.412465f,0.0965352f,0.0918925f}, +{-0.41497f,0.101334f,0.0918925f},{-0.41497f,0.101334f,0.0900281f},{-0.417269f,0.106239f,0.0900281f}, +{-0.419359f,0.111243f,0.0918925f},{-0.417269f,0.106239f,0.0918925f},{-0.419359f,0.111243f,0.0900281f}, +{-0.421236f,0.116342f,0.0900281f},{-0.421236f,0.116341f,0.0918925f},{-0.425533f,0.132038f,0.0918925f}, +{-0.424327f,0.126754f,0.0900281f},{-0.425533f,0.132038f,0.0900281f},{-0.422894f,0.121519f,0.0918925f}, +{-0.422894f,0.121519f,0.0900281f},{-0.424327f,0.126754f,0.0918925f},{-0.426511f,0.137363f,0.0918925f}, +{-0.427261f,0.142723f,0.0918925f},{-0.426511f,0.137364f,0.0900281f},{-0.427261f,0.142723f,0.0900281f}, +{-0.427781f,0.14811f,0.0900281f},{-0.428071f,0.153516f,0.0900281f},{-0.428071f,0.153516f,0.0918925f}, +{-0.427781f,0.14811f,0.0918925f},{-0.428131f,0.158934f,0.0900281f},{-0.428131f,0.158934f,0.0918925f}, +{-0.427958f,0.164357f,0.0900281f},{-0.427958f,0.164356f,0.0918925f},{-0.389518f,0.0664729f,0.0900281f}, +{-0.393337f,0.0703321f,0.0918925f},{-0.389518f,0.0664728f,0.0918925f},{-0.385543f,0.0627861f,0.0900281f}, +{-0.385543f,0.0627861f,0.0918925f},{-0.381418f,0.0592762f,0.0900281f},{-0.37715f,0.0559475f,0.0900281f}, +{-0.381418f,0.0592761f,0.0918925f},{-0.37715f,0.0559474f,0.0918925f},{-0.372745f,0.0528044f,0.0900281f}, +{-0.372745f,0.0528044f,0.0918925f},{-0.368209f,0.0498513f,0.0900281f},{-0.363547f,0.0470924f,0.0900281f}, +{-0.368209f,0.0498511f,0.0918925f},{-0.363547f,0.0470923f,0.0918925f},{-0.358766f,0.0445321f,0.0900281f}, +{-0.358766f,0.0445321f,0.0918925f},{-0.353872f,0.042175f,0.0900281f},{-0.348877f,0.0400276f,0.0900281f}, +{-0.353871f,0.0421746f,0.0918925f},{-0.348877f,0.0400276f,0.0918925f},{-0.343803f,0.0380996f,0.0900281f}, +{-0.343803f,0.0380996f,0.0918925f},{-0.338659f,0.0363926f,0.0900281f},{-0.333452f,0.0349082f,0.0900281f}, +{-0.338659f,0.0363926f,0.0918925f},{-0.333452f,0.0349082f,0.0918925f},{-0.328189f,0.033648f,0.0900281f}, +{-0.328189f,0.0336479f,0.0918925f},{-0.322877f,0.0326134f,0.0900281f},{-0.317524f,0.031806f,0.0900281f}, +{-0.322877f,0.0326134f,0.0918925f},{-0.317524f,0.031806f,0.0918925f},{-0.312137f,0.0312275f,0.0900281f}, +{-0.312136f,0.0312274f,0.0918925f},{-0.306722f,0.0308792f,0.0900281f},{-0.301289f,0.0307628f,0.0900281f}, +{-0.306722f,0.0308792f,0.0918925f},{-0.301289f,0.0307628f,0.0918925f},{-0.270526f,-2.46733e-016f,0.0918925f}, +{-0.270526f,-1.77184e-016f,0.0900281f},{-0.270571f,0.00166887f,0.0900281f},{-0.270707f,0.0033296f,0.0900281f}, +{-0.270571f,0.00166875f,0.0918925f},{-0.270931f,0.00497861f,0.0900281f},{-0.270706f,0.00332938f,0.0918925f}, +{-0.270931f,0.00497832f,0.0918925f},{-0.271245f,0.00661229f,0.0900281f},{-0.271646f,0.00822706f,0.0900281f}, +{-0.271245f,0.00661197f,0.0918925f},{-0.272135f,0.00981931f,0.0900281f},{-0.271646f,0.00822672f,0.0918925f}, +{-0.272135f,0.009819f,0.0918925f},{-0.27271f,0.0113858f,0.0900281f},{-0.27337f,0.0129196f,0.0900281f}, +{-0.27271f,0.0113852f,0.0918925f},{-0.274111f,0.0144128f,0.0900281f},{-0.27337f,0.0129192f,0.0918925f}, +{-0.274111f,0.0144127f,0.0918925f},{-0.27493f,0.0158618f,0.0900281f},{-0.275826f,0.0172635f,0.0900281f}, +{-0.27493f,0.0158617f,0.0918925f},{-0.276797f,0.0186148f,0.0900281f},{-0.275826f,0.0172633f,0.0918925f}, +{-0.276797f,0.0186146f,0.0918925f},{-0.27784f,0.0199127f,0.0900281f},{-0.278954f,0.0211544f,0.0900281f}, +{-0.27784f,0.0199124f,0.0918925f},{-0.280135f,0.0223352f,0.0900281f},{-0.278953f,0.0211538f,0.0918925f}, +{-0.280134f,0.0223347f,0.0918925f},{-0.281376f,0.0234487f,0.0900281f},{-0.282674f,0.0244917f,0.0900281f}, +{-0.281376f,0.0234485f,0.0918925f},{-0.284025f,0.0254622f,0.0900281f},{-0.282674f,0.0244916f,0.0918925f}, +{-0.284025f,0.0254621f,0.0918925f},{-0.285427f,0.0263582f,0.0900281f},{-0.286876f,0.0271776f,0.0900281f}, +{-0.285427f,0.0263581f,0.0918925f},{-0.288369f,0.0279185f,0.0900281f},{-0.286876f,0.0271775f,0.0918925f}, +{-0.288369f,0.0279183f,0.0918925f},{-0.289903f,0.0285784f,0.0900281f},{-0.29147f,0.0291536f,0.0900281f}, +{-0.289903f,0.0285781f,0.0918925f},{-0.293062f,0.0296423f,0.0900281f},{-0.291469f,0.0291535f,0.0918925f}, +{-0.293061f,0.0296423f,0.0918925f},{-0.294677f,0.0300438f,0.0900281f},{-0.29631f,0.0303573f,0.0900281f}, +{-0.294676f,0.0300437f,0.0918925f},{-0.297959f,0.0305821f,0.0900281f},{-0.29631f,0.0303572f,0.0918925f}, +{-0.297959f,0.030582f,0.0918925f},{-0.29962f,0.0307175f,0.0900281f},{-0.29962f,0.0307174f,0.0918925f}, +{-0.270571f,-0.00166887f,0.0918925f},{-0.270571f,-0.00166875f,0.0900281f},{-0.270707f,-0.0033296f,0.0918925f}, +{-0.270931f,-0.00497861f,0.0918925f},{-0.270706f,-0.00332938f,0.0900281f},{-0.271245f,-0.00661229f,0.0918925f}, +{-0.270931f,-0.00497832f,0.0900281f},{-0.271245f,-0.00661197f,0.0900281f},{-0.271646f,-0.00822706f,0.0918925f}, +{-0.272135f,-0.00981931f,0.0918925f},{-0.271646f,-0.00822672f,0.0900281f},{-0.27271f,-0.0113858f,0.0918925f}, +{-0.272135f,-0.009819f,0.0900281f},{-0.27271f,-0.0113852f,0.0900281f},{-0.27337f,-0.0129196f,0.0918925f}, +{-0.274111f,-0.0144128f,0.0918925f},{-0.27337f,-0.0129192f,0.0900281f},{-0.27493f,-0.0158618f,0.0918925f}, +{-0.274111f,-0.0144127f,0.0900281f},{-0.27493f,-0.0158617f,0.0900281f},{-0.275826f,-0.0172635f,0.0918925f}, +{-0.276797f,-0.0186148f,0.0918925f},{-0.275826f,-0.0172633f,0.0900281f},{-0.27784f,-0.0199127f,0.0918925f}, +{-0.276797f,-0.0186146f,0.0900281f},{-0.27784f,-0.0199124f,0.0900281f},{-0.278954f,-0.0211544f,0.0918925f}, +{-0.280135f,-0.0223352f,0.0918925f},{-0.278953f,-0.0211538f,0.0900281f},{-0.281376f,-0.0234487f,0.0918925f}, +{-0.280134f,-0.0223347f,0.0900281f},{-0.281376f,-0.0234485f,0.0900281f},{-0.282674f,-0.0244917f,0.0918925f}, +{-0.284025f,-0.0254622f,0.0918925f},{-0.282674f,-0.0244916f,0.0900281f},{-0.285427f,-0.0263582f,0.0918925f}, +{-0.284025f,-0.0254621f,0.0900281f},{-0.285427f,-0.0263581f,0.0900281f},{-0.286876f,-0.0271776f,0.0918925f}, +{-0.288369f,-0.0279185f,0.0918925f},{-0.286876f,-0.0271775f,0.0900281f},{-0.289903f,-0.0285784f,0.0918925f}, +{-0.288369f,-0.0279183f,0.0900281f},{-0.289903f,-0.0285781f,0.0900281f},{-0.29147f,-0.0291536f,0.0918925f}, +{-0.293062f,-0.0296423f,0.0918925f},{-0.291469f,-0.0291535f,0.0900281f},{-0.294677f,-0.0300438f,0.0918925f}, +{-0.293061f,-0.0296423f,0.0900281f},{-0.294676f,-0.0300437f,0.0900281f},{-0.29631f,-0.0303573f,0.0918925f}, +{-0.297959f,-0.0305821f,0.0918925f},{-0.29631f,-0.0303572f,0.0900281f},{-0.29962f,-0.0307175f,0.0918925f}, +{-0.297959f,-0.030582f,0.0900281f},{-0.29962f,-0.0307174f,0.0900281f},{-0.301289f,-0.0307628f,0.0918925f}, +{-0.301289f,-0.0307628f,0.0900281f},{-0.389518f,-0.0664728f,0.0900281f},{-0.385543f,-0.0627861f,0.0900281f}, +{-0.385543f,-0.0627861f,0.0918925f},{-0.393337f,-0.0703321f,0.0900281f},{-0.393337f,-0.0703325f,0.0918925f}, +{-0.396993f,-0.074357f,0.0900281f},{-0.381418f,-0.0592762f,0.0918925f},{-0.389518f,-0.0664729f,0.0918925f}, +{-0.381418f,-0.0592761f,0.0900281f},{-0.37715f,-0.0559475f,0.0918925f},{-0.37715f,-0.0559474f,0.0900281f}, +{-0.372745f,-0.0528044f,0.0900281f},{-0.372745f,-0.0528044f,0.0918925f},{-0.368209f,-0.0498513f,0.0918925f}, +{-0.368209f,-0.0498511f,0.0900281f},{-0.363547f,-0.0470923f,0.0900281f},{-0.358766f,-0.0445321f,0.0918925f}, +{-0.363547f,-0.0470924f,0.0918925f},{-0.358766f,-0.0445321f,0.0900281f},{-0.353871f,-0.0421746f,0.0900281f}, +{-0.353872f,-0.042175f,0.0918925f},{-0.338659f,-0.0363926f,0.0918925f},{-0.343803f,-0.0380996f,0.0900281f}, +{-0.338659f,-0.0363926f,0.0900281f},{-0.348877f,-0.0400276f,0.0918925f},{-0.348877f,-0.0400276f,0.0900281f}, +{-0.343803f,-0.0380996f,0.0918925f},{-0.333452f,-0.0349082f,0.0918925f},{-0.328189f,-0.033648f,0.0918925f}, +{-0.333452f,-0.0349082f,0.0900281f},{-0.328189f,-0.0336479f,0.0900281f},{-0.322877f,-0.0326134f,0.0900281f}, +{-0.317524f,-0.031806f,0.0900281f},{-0.317524f,-0.031806f,0.0918925f},{-0.322877f,-0.0326134f,0.0918925f}, +{-0.312136f,-0.0312274f,0.0900281f},{-0.312137f,-0.0312275f,0.0918925f},{-0.306722f,-0.0308792f,0.0900281f}, +{-0.306722f,-0.0308792f,0.0918925f},{-0.400468f,-0.0785292f,0.0900281f},{-0.396993f,-0.0743574f,0.0918925f}, +{-0.400468f,-0.0785294f,0.0918925f},{-0.403757f,-0.0828395f,0.0900281f},{-0.403757f,-0.0828396f,0.0918925f}, +{-0.406855f,-0.0872815f,0.0900281f},{-0.409759f,-0.0918488f,0.0900281f},{-0.406855f,-0.0872816f,0.0918925f}, +{-0.409759f,-0.091849f,0.0918925f},{-0.412465f,-0.0965352f,0.0900281f},{-0.412465f,-0.0965352f,0.0918925f}, +{-0.41497f,-0.101334f,0.0900281f},{-0.417269f,-0.106239f,0.0900281f},{-0.41497f,-0.101334f,0.0918925f}, +{-0.417269f,-0.106239f,0.0918925f},{-0.419359f,-0.111243f,0.0900281f},{-0.419359f,-0.111243f,0.0918925f}, +{-0.421236f,-0.116341f,0.0900281f},{-0.422894f,-0.121519f,0.0900281f},{-0.421236f,-0.116342f,0.0918925f}, +{-0.422894f,-0.121519f,0.0918925f},{-0.424327f,-0.126754f,0.0900281f},{-0.424327f,-0.126754f,0.0918925f}, +{-0.425533f,-0.132038f,0.0900281f},{-0.426511f,-0.137363f,0.0900281f},{-0.425533f,-0.132038f,0.0918925f}, +{-0.426511f,-0.137364f,0.0918925f},{-0.427261f,-0.142723f,0.0900281f},{-0.427261f,-0.142723f,0.0918925f}, +{-0.427781f,-0.14811f,0.0900281f},{-0.428071f,-0.153516f,0.0900281f},{-0.427781f,-0.14811f,0.0918925f}, +{-0.428071f,-0.153516f,0.0918925f},{-0.428131f,-0.158934f,0.0900281f},{-0.428131f,-0.158934f,0.0918925f}, +{-0.427958f,-0.164356f,0.0900281f},{-0.427553f,-0.169776f,0.0900281f},{-0.427958f,-0.164357f,0.0918925f}, +{-0.427553f,-0.169776f,0.0918925f},{-0.448656f,-0.18196f,0.0918925f},{-0.448656f,-0.18196f,0.0900281f}, +{-0.5f,-0.0049028f,0.0918925f},{-0.5f,0.00490289f,0.0918925f},{-0.5f,-0.00490289f,0.0900281f}, +{-0.499724f,-0.0147057f,0.0900281f},{-0.499724f,-0.0147055f,0.0918925f},{-0.499171f,-0.0244996f,0.0900281f}, +{-0.499171f,-0.0244996f,0.0918925f},{-0.498342f,-0.0342788f,0.0918925f},{-0.498342f,-0.034279f,0.0900281f}, +{-0.497236f,-0.0440377f,0.0900281f},{-0.497236f,-0.0440376f,0.0918925f},{-0.495854f,-0.05377f,0.0900281f}, +{-0.495854f,-0.05377f,0.0918925f},{-0.494196f,-0.0634697f,0.0918925f},{-0.494196f,-0.0634706f,0.0900281f}, +{-0.492264f,-0.0731194f,0.0900281f},{-0.492264f,-0.0731193f,0.0918925f},{-0.490062f,-0.0826996f,0.0900281f}, +{-0.490062f,-0.0826996f,0.0918925f},{-0.487593f,-0.0922052f,0.0918925f},{-0.487593f,-0.0922054f,0.0900281f}, +{-0.484859f,-0.101631f,0.0900281f},{-0.484859f,-0.101631f,0.0918925f},{-0.481861f,-0.110971f,0.0900281f}, +{-0.481861f,-0.110971f,0.0918925f},{-0.478603f,-0.120221f,0.0918925f},{-0.478602f,-0.120221f,0.0900281f}, +{-0.475085f,-0.129374f,0.0900281f},{-0.475085f,-0.129374f,0.0918925f},{-0.47131f,-0.138425f,0.0900281f}, +{-0.47131f,-0.138425f,0.0918925f},{-0.46728f,-0.147368f,0.0918925f},{-0.46728f,-0.147369f,0.0900281f}, +{-0.462998f,-0.156199f,0.0900281f},{-0.462998f,-0.156199f,0.0918925f},{-0.458465f,-0.164912f,0.0900281f}, +{-0.458465f,-0.164912f,0.0918925f},{-0.453684f,-0.173501f,0.0918925f},{-0.453684f,-0.173501f,0.0900281f}, +{-0.5f,0.0049028f,0.0900281f},{-0.499724f,0.0147055f,0.0900281f},{-0.499724f,0.0147057f,0.0918925f}, +{-0.499171f,0.0244996f,0.0918925f},{-0.499171f,0.0244996f,0.0900281f},{-0.498342f,0.034279f,0.0918925f}, +{-0.498342f,0.0342788f,0.0900281f},{-0.497236f,0.0440376f,0.0900281f},{-0.497236f,0.0440377f,0.0918925f}, +{-0.495854f,0.05377f,0.0918925f},{-0.495854f,0.05377f,0.0900281f},{-0.494196f,0.0634706f,0.0918925f}, +{-0.494196f,0.0634697f,0.0900281f},{-0.492264f,0.0731193f,0.0900281f},{-0.492264f,0.0731194f,0.0918925f}, +{-0.490062f,0.0826996f,0.0918925f},{-0.490062f,0.0826996f,0.0900281f},{-0.487593f,0.0922054f,0.0918925f}, +{-0.487593f,0.0922052f,0.0900281f},{-0.484859f,0.101631f,0.0900281f},{-0.484859f,0.101631f,0.0918925f}, +{-0.481861f,0.110971f,0.0918925f},{-0.481861f,0.110971f,0.0900281f},{-0.478602f,0.120221f,0.0918925f}, +{-0.478603f,0.120221f,0.0900281f},{-0.475085f,0.129374f,0.0900281f},{-0.475085f,0.129374f,0.0918925f}, +{-0.47131f,0.138425f,0.0918925f},{-0.47131f,0.138425f,0.0900281f},{-0.46728f,0.147369f,0.0918925f}, +{-0.46728f,0.147368f,0.0900281f},{-0.462998f,0.156199f,0.0900281f},{-0.462998f,0.156199f,0.0918925f}, +{-0.458465f,0.164912f,0.0918925f},{-0.458465f,0.164912f,0.0900281f},{-0.453684f,0.173501f,0.0918925f}, +{-0.453684f,0.173501f,0.0900281f},{-0.295886f,-0.0200317f,0.0918925f},{-0.280259f,-0.0036392f,0.0918925f}, +{-0.280781f,-0.00474168f,0.0918925f},{-0.28931f,-0.0152687f,0.0918925f},{-0.29453f,-0.0183517f,0.0918925f}, +{-0.28153f,-0.0057053f,0.0918925f},{-0.291507f,-0.0130697f,0.0918925f},{-0.289835f,-0.0151095f,0.0918925f}, +{-0.294119f,-0.0173478f,0.0918925f},{-0.291087f,-0.0109706f,0.0918925f},{-0.290739f,-0.0105473f,0.0918925f}, +{-0.295126f,-0.0192577f,0.0918925f},{-0.296782f,-0.0206442f,0.0918925f},{-0.297778f,-0.0210723f,0.0918925f}, +{-0.290316f,-0.0101998f,0.0918925f},{-0.291091f,-0.0140791f,0.0918925f},{-0.293911f,-0.0151984f,0.0918925f}, +{-0.290742f,-0.0145033f,0.0918925f},{-0.315791f,0.0105451f,0.0918925f},{-0.315367f,0.0101973f,0.0918925f}, +{-0.316139f,0.0109693f,0.0918925f},{-0.314358f,0.00977971f,0.0918925f},{-0.314883f,0.00993885f,0.0918925f}, +{-0.314881f,0.0151067f,0.0918925f},{-0.316555f,0.0119787f,0.0918925f},{-0.316397f,0.0114536f,0.0918925f}, +{-0.316609f,0.0125242f,0.0918925f},{-0.316394f,0.013595f,0.0918925f},{-0.316135f,0.0140778f,0.0918925f}, +{-0.315788f,0.0145011f,0.0918925f},{-0.315364f,0.0148486f,0.0918925f},{-0.314357f,0.015266f,0.0918925f}, +{-0.290318f,-0.0148511f,0.0918925f},{-0.29391f,-0.0162833f,0.0918925f},{-0.291506f,-0.0119779f,0.0918925f}, +{-0.291561f,-0.0125242f,0.0918925f},{-0.291346f,-0.0114534f,0.0918925f},{-0.291349f,-0.0135948f,0.0918925f}, +{-0.289833f,-0.00994166f,0.0918925f},{-0.316555f,0.0130705f,0.0918925f},{-0.289309f,-0.00978241f,0.0918925f}, +{-0.280782f,-0.00474296f,0.0900281f},{-0.297777f,-0.0210725f,0.0900281f},{-0.296781f,-0.020644f,0.0900281f}, +{-0.290742f,-0.0105451f,0.0900281f},{-0.280259f,-0.00364027f,0.0900281f},{-0.289835f,-0.00993885f,0.0900281f}, +{-0.295886f,-0.0200312f,0.0900281f},{-0.295126f,-0.0192574f,0.0900281f},{-0.29391f,-0.0162822f,0.0900281f}, +{-0.290739f,-0.0145011f,0.0900281f},{-0.290316f,-0.0148486f,0.0900281f},{-0.291561f,-0.0125242f,0.0900281f}, +{-0.28931f,-0.00977971f,0.0900281f},{-0.291091f,-0.0109693f,0.0900281f},{-0.290318f,-0.0101973f,0.0900281f}, +{-0.291349f,-0.0114536f,0.0900281f},{-0.315791f,0.0145033f,0.0900281f},{-0.316139f,0.0140791f,0.0900281f}, +{-0.314357f,0.00978241f,0.0900281f},{-0.314881f,0.00994166f,0.0900281f},{-0.294529f,-0.0183513f,0.0900281f}, +{-0.294119f,-0.0173468f,0.0900281f},{-0.289833f,-0.0151067f,0.0900281f},{-0.289309f,-0.015266f,0.0900281f}, +{-0.291087f,-0.0140778f,0.0900281f},{-0.293911f,-0.0151976f,0.0900281f},{-0.291346f,-0.013595f,0.0900281f}, +{-0.28153f,-0.00570553f,0.0900281f},{-0.316555f,0.0119779f,0.0900281f},{-0.315364f,0.0101998f,0.0900281f}, +{-0.316609f,0.0125242f,0.0900281f},{-0.316555f,0.0130697f,0.0900281f},{-0.316397f,0.0135948f,0.0900281f}, +{-0.315367f,0.0148511f,0.0900281f},{-0.314883f,0.0151095f,0.0900281f},{-0.316135f,0.0109706f,0.0900281f}, +{-0.314358f,0.0152687f,0.0900281f},{-0.316394f,0.0114534f,0.0900281f},{-0.315788f,0.0105473f,0.0900281f}, +{-0.291507f,-0.0119787f,0.0900281f},{-0.291506f,-0.0130705f,0.0900281f},{0.285968f,0.0125242f,0.0900281f}, +{0.286022f,0.0130723f,0.0918925f},{0.285968f,0.0125242f,0.0918925f},{0.286181f,0.011454f,0.0918925f}, +{0.286181f,0.011454f,0.0900281f},{0.286022f,0.0119761f,0.0918925f},{0.286022f,0.0119761f,0.0900281f}, +{0.286438f,0.0109726f,0.0900281f},{0.286787f,0.0105467f,0.0900281f},{0.286787f,0.0105467f,0.0918925f}, +{0.287213f,0.0101975f,0.0900281f},{0.287213f,0.0101975f,0.0918925f},{0.286438f,0.0109726f,0.0918925f}, +{0.288764f,0.00972758f,0.0900281f},{0.288216f,0.00978182f,0.0900281f},{0.288216f,0.00978182f,0.0918925f}, +{0.287694f,0.00994047f,0.0918925f},{0.287694f,0.00994047f,0.0900281f},{0.288764f,0.00972758f,0.0918925f}, +{0.286022f,0.0130723f,0.0900281f},{0.286181f,0.0135944f,0.0918925f},{0.286181f,0.0135944f,0.0900281f}, +{0.286438f,0.0140758f,0.0900281f},{0.286438f,0.0140758f,0.0918925f},{0.286787f,0.0145017f,0.0900281f}, +{0.286787f,0.0145017f,0.0918925f},{0.287213f,0.0148509f,0.0918925f},{0.287213f,0.0148509f,0.0900281f}, +{0.287694f,0.0151079f,0.0900281f},{0.287694f,0.0151079f,0.0918925f},{0.288216f,0.0152666f,0.0900281f}, +{0.288216f,0.0152666f,0.0918925f},{0.288764f,0.0153208f,0.0918925f},{0.288764f,0.0153208f,0.0900281f}, +{0.311016f,-0.0125242f,0.0900281f},{0.31107f,-0.0119761f,0.0918925f},{0.311016f,-0.0125242f,0.0918925f}, +{0.311229f,-0.0135944f,0.0918925f},{0.311229f,-0.0135944f,0.0900281f},{0.31107f,-0.0130723f,0.0918925f}, +{0.31107f,-0.0130723f,0.0900281f},{0.311486f,-0.0140758f,0.0900281f},{0.311835f,-0.0145017f,0.0900281f}, +{0.311835f,-0.0145017f,0.0918925f},{0.312261f,-0.0148509f,0.0900281f},{0.312261f,-0.0148509f,0.0918925f}, +{0.311486f,-0.0140758f,0.0918925f},{0.313813f,-0.0153208f,0.0900281f},{0.313265f,-0.0152666f,0.0900281f}, +{0.313265f,-0.0152666f,0.0918925f},{0.312743f,-0.0151079f,0.0918925f},{0.312743f,-0.0151079f,0.0900281f}, +{0.313813f,-0.0153208f,0.0918925f},{0.31107f,-0.0119761f,0.0900281f},{0.311229f,-0.011454f,0.0918925f}, +{0.311229f,-0.011454f,0.0900281f},{0.311486f,-0.0109726f,0.0900281f},{0.311486f,-0.0109726f,0.0918925f}, +{0.311835f,-0.0105467f,0.0900281f},{0.311835f,-0.0105467f,0.0918925f},{0.312261f,-0.0101975f,0.0918925f}, +{0.312261f,-0.0101975f,0.0900281f},{0.312743f,-0.00994047f,0.0900281f},{0.312743f,-0.00994047f,0.0918925f}, +{0.313265f,-0.00978182f,0.0900281f},{0.313265f,-0.00978182f,0.0918925f},{0.313813f,-0.00972758f,0.0918925f}, +{0.313813f,-0.00972758f,0.0900281f},{0.284736f,0.0073455f,0.0900281f},{0.285954f,0.00738926f,0.0918925f}, +{0.284736f,0.00734538f,0.0918925f},{0.283556f,0.00703877f,0.0900281f},{0.283555f,0.0070384f,0.0918925f}, +{0.28247f,0.00648281f,0.0900281f},{0.28247f,0.00648282f,0.0918925f},{0.285956f,0.00738915f,0.0900281f}, +{0.287154f,0.00716427f,0.0918925f},{0.287154f,0.00716427f,0.0900281f},{0.309858f,-0.00856857f,0.0918925f}, +{0.310706f,-0.0078732f,0.0918925f},{0.309857f,-0.00856991f,0.0900281f},{0.310705f,-0.00787361f,0.0900281f}, +{0.311673f,-0.0073566f,0.0918925f},{0.312722f,-0.00703838f,0.0918925f},{0.311672f,-0.00735691f,0.0900281f}, +{0.313813f,-0.00693097f,0.0918925f},{0.312721f,-0.00703853f,0.0900281f},{0.313813f,-0.00693097f,0.0900281f}, +{0.309162f,-0.00941743f,0.0900281f},{0.308645f,-0.0103841f,0.0900281f},{0.309162f,-0.00941663f,0.0918925f}, +{0.308327f,-0.0114331f,0.0900281f},{0.308645f,-0.0103834f,0.0918925f},{0.308327f,-0.0114326f,0.0918925f}, +{0.30822f,-0.0125242f,0.0900281f},{0.30822f,-0.0125242f,0.0918925f},{0.401959f,0.065917f,0.0918925f}, +{0.398048f,0.0617984f,0.0918925f},{0.40196f,0.0659174f,0.0900281f},{0.405692f,0.07019f,0.0900281f}, +{0.405691f,0.0701898f,0.0918925f},{0.409237f,0.0746077f,0.0900281f},{0.409237f,0.0746076f,0.0918925f}, +{0.412592f,0.0791643f,0.0918925f},{0.412592f,0.0791644f,0.0900281f},{0.415754f,0.0838538f,0.0900281f}, +{0.415754f,0.0838537f,0.0918925f},{0.418717f,0.0886696f,0.0900281f},{0.418717f,0.0886696f,0.0918925f}, +{0.421479f,0.0936056f,0.0918925f},{0.421479f,0.0936057f,0.0900281f},{0.424035f,0.0986557f,0.0900281f}, +{0.424035f,0.0986556f,0.0918925f},{0.426382f,0.103813f,0.0900281f},{0.426382f,0.103813f,0.0918925f}, +{0.428515f,0.109072f,0.0918925f},{0.428515f,0.109073f,0.0900281f},{0.430428f,0.11442f,0.0900281f}, +{0.430428f,0.11442f,0.0918925f},{0.432114f,0.119834f,0.0900281f},{0.432114f,0.119834f,0.0918925f}, +{0.433572f,0.125306f,0.0918925f},{0.433572f,0.125307f,0.0900281f},{0.4348f,0.130829f,0.0900281f}, +{0.4348f,0.130829f,0.0918925f},{0.435797f,0.136396f,0.0900281f},{0.435797f,0.136396f,0.0918925f}, +{0.436561f,0.141999f,0.0918925f},{0.436561f,0.141999f,0.0900281f},{0.437093f,0.147631f,0.0900281f}, +{0.437093f,0.147631f,0.0918925f},{0.437391f,0.153284f,0.0900281f},{0.437391f,0.153284f,0.0918925f}, +{0.437453f,0.158952f,0.0918925f},{0.437453f,0.158952f,0.0900281f},{0.437279f,0.164627f,0.0900281f}, +{0.437279f,0.164627f,0.0918925f},{0.398048f,0.0617987f,0.0900281f},{0.393973f,0.0578515f,0.0900281f}, +{0.393973f,0.0578514f,0.0918925f},{0.389744f,0.054083f,0.0918925f},{0.389744f,0.0540831f,0.0900281f}, +{0.385366f,0.0504973f,0.0918925f},{0.385366f,0.0504974f,0.0900281f},{0.380846f,0.0470986f,0.0900281f}, +{0.380846f,0.0470985f,0.0918925f},{0.376189f,0.0438908f,0.0918925f},{0.376189f,0.0438908f,0.0900281f}, +{0.371402f,0.0408784f,0.0918925f},{0.371402f,0.0408785f,0.0900281f},{0.36649f,0.0380656f,0.0900281f}, +{0.36649f,0.0380655f,0.0918925f},{0.36146f,0.0354565f,0.0918925f},{0.36146f,0.0354565f,0.0900281f}, +{0.356317f,0.0330551f,0.0918925f},{0.356318f,0.0330554f,0.0900281f},{0.351076f,0.0308688f,0.0900281f}, +{0.351076f,0.0308688f,0.0918925f},{0.345756f,0.0289059f,0.0918925f},{0.345756f,0.0289059f,0.0900281f}, +{0.340366f,0.0271683f,0.0918925f},{0.340366f,0.0271684f,0.0900281f},{0.334914f,0.0256577f,0.0900281f}, +{0.334914f,0.0256577f,0.0918925f},{0.329406f,0.0243753f,0.0918925f},{0.329406f,0.0243754f,0.0900281f}, +{0.32385f,0.0233228f,0.0918925f},{0.32385f,0.0233228f,0.0900281f},{0.318253f,0.0225016f,0.0900281f}, +{0.318253f,0.0225016f,0.0918925f},{0.312622f,0.0219132f,0.0918925f},{0.312623f,0.0219132f,0.0900281f}, +{0.306965f,0.0215591f,0.0918925f},{0.306965f,0.0215591f,0.0900281f},{0.301289f,0.0214407f,0.0918925f}, +{0.301289f,0.0214407f,0.0900281f},{0.300061f,0.0214056f,0.0918925f},{0.300061f,0.0214056f,0.0900281f}, +{0.298838f,0.0213002f,0.0900281f},{0.298838f,0.0213002f,0.0918925f},{0.29272f,0.00857005f,0.0900281f}, +{0.293362f,0.00933952f,0.0900281f},{0.292718f,0.00856812f,0.0918925f},{0.293856f,0.0102104f,0.0918925f}, +{0.293362f,0.00933867f,0.0918925f},{0.293857f,0.010212f,0.0900281f},{0.294188f,0.0111572f,0.0918925f}, +{0.294188f,0.0111588f,0.0900281f},{0.294345f,0.0121484f,0.0918925f},{0.294322f,0.0131504f,0.0918925f}, +{0.294345f,0.0121494f,0.0900281f},{0.294121f,0.0141339f,0.0900281f},{0.294322f,0.0131516f,0.0900281f}, +{0.294121f,0.0141339f,0.0918925f},{0.291949f,0.00792586f,0.0918925f},{0.29195f,0.00792654f,0.0900281f}, +{0.291078f,0.00743177f,0.0900281f},{0.290131f,0.00710074f,0.0900281f},{0.291076f,0.00743116f,0.0918925f}, +{0.290129f,0.00710007f,0.0918925f},{0.28914f,0.00694354f,0.0900281f},{0.289139f,0.00694356f,0.0918925f}, +{0.288138f,0.00696625f,0.0900281f},{0.288136f,0.00696632f,0.0918925f},{0.283634f,-0.0121669f,0.0900281f}, +{0.282482f,-0.0102959f,0.0900281f},{0.282482f,-0.0102961f,0.0918925f},{0.283634f,-0.012167f,0.0918925f}, +{0.284976f,-0.013914f,0.0900281f},{0.281528f,-0.008319f,0.0918925f},{0.281527f,-0.00831882f,0.0900281f}, +{0.280779f,-0.00625128f,0.0918925f},{0.280779f,-0.00625078f,0.0900281f},{0.280246f,-0.00411456f,0.0918925f}, +{0.280246f,-0.00411435f,0.0900281f},{0.279936f,-0.00194003f,0.0900281f},{0.279936f,-0.0019402f,0.0918925f}, +{0.279849f,0.000253827f,0.0918925f},{0.279988f,0.00245022f,0.0918925f},{0.279849f,0.00025393f,0.0900281f}, +{0.279988f,0.00245022f,0.0900281f},{0.286486f,-0.0155106f,0.0900281f},{0.284976f,-0.0139141f,0.0918925f}, +{0.286486f,-0.0155107f,0.0918925f},{0.288149f,-0.016943f,0.0900281f},{0.28815f,-0.0169431f,0.0918925f}, +{0.289954f,-0.0181996f,0.0900281f},{0.29188f,-0.0192663f,0.0900281f},{0.289954f,-0.0181999f,0.0918925f}, +{0.291881f,-0.0192664f,0.0918925f},{0.293901f,-0.0201277f,0.0900281f},{0.293901f,-0.0201278f,0.0918925f}, +{0.295998f,-0.0207778f,0.0900281f},{0.298156f,-0.0212106f,0.0900281f},{0.295998f,-0.0207778f,0.0918925f}, +{0.298156f,-0.0212106f,0.0918925f},{0.303955f,-0.0200545f,0.0900281f},{0.302604f,-0.0207145f,0.0918925f}, +{0.303956f,-0.020054f,0.0918925f},{0.305176f,-0.0191712f,0.0900281f},{0.302603f,-0.0207149f,0.0900281f}, +{0.301156f,-0.0211353f,0.0918925f},{0.305176f,-0.0191712f,0.0918925f},{0.301155f,-0.0211356f,0.0900281f}, +{0.29966f,-0.021302f,0.0918925f},{0.299659f,-0.0213021f,0.0900281f},{0.306228f,-0.0180928f,0.0900281f}, +{0.306229f,-0.018092f,0.0918925f},{0.307079f,-0.0168512f,0.0918925f},{0.307079f,-0.0168521f,0.0900281f}, +{0.307707f,-0.0154797f,0.0918925f},{0.307707f,-0.0154807f,0.0900281f},{0.30809f,-0.0140259f,0.0900281f}, +{0.30809f,-0.014025f,0.0918925f},{0.314904f,-0.00703853f,0.0918925f},{0.317768f,-0.00856991f,0.0918925f}, +{0.31692f,-0.0078732f,0.0900281f},{0.31692f,-0.00787361f,0.0918925f},{0.315954f,-0.00735691f,0.0918925f}, +{0.315953f,-0.0073566f,0.0900281f},{0.314904f,-0.00703838f,0.0900281f},{0.31898f,-0.0103834f,0.0900281f}, +{0.31898f,-0.0103841f,0.0918925f},{0.319299f,-0.0114331f,0.0918925f},{0.317767f,-0.00856857f,0.0900281f}, +{0.318464f,-0.00941743f,0.0918925f},{0.318463f,-0.00941663f,0.0900281f},{0.319406f,-0.0125242f,0.0918925f}, +{0.319298f,-0.0114326f,0.0900281f},{0.319406f,-0.0125242f,0.0900281f},{0.32063f,-0.017806f,0.0900281f}, +{0.32063f,-0.0178073f,0.0918925f},{0.321554f,-0.0193785f,0.0900281f},{0.321554f,-0.0193787f,0.0918925f}, +{0.319955f,-0.0161135f,0.0918925f},{0.319955f,-0.0161128f,0.0900281f},{0.319544f,-0.0143418f,0.0900281f}, +{0.319544f,-0.0143423f,0.0918925f},{0.322701f,-0.0207886f,0.0900281f},{0.324052f,-0.0220123f,0.0900281f}, +{0.322701f,-0.0207888f,0.0918925f},{0.324053f,-0.0220132f,0.0918925f},{0.325573f,-0.023018f,0.0900281f}, +{0.325573f,-0.0230183f,0.0918925f},{0.327224f,-0.02378f,0.0900281f},{0.328976f,-0.0242851f,0.0900281f}, +{0.327224f,-0.0237802f,0.0918925f},{0.328976f,-0.0242851f,0.0918925f},{0.409092f,-0.0744192f,0.0918925f}, +{0.409092f,-0.0744192f,0.0900281f},{0.405539f,-0.0700077f,0.0900281f},{0.401803f,-0.065746f,0.0900281f}, +{0.405539f,-0.0700077f,0.0918925f},{0.397891f,-0.06164f,0.0900281f},{0.401803f,-0.0657461f,0.0918925f}, +{0.397891f,-0.0616401f,0.0918925f},{0.393805f,-0.0576956f,0.0900281f},{0.389551f,-0.0539185f,0.0900281f}, +{0.393805f,-0.0576957f,0.0918925f},{0.385134f,-0.0503158f,0.0900281f},{0.389551f,-0.0539186f,0.0918925f}, +{0.385135f,-0.050316f,0.0918925f},{0.380577f,-0.0469052f,0.0900281f},{0.375889f,-0.0436939f,0.0900281f}, +{0.380577f,-0.0469052f,0.0918925f},{0.371079f,-0.0406851f,0.0900281f},{0.375889f,-0.0436939f,0.0918925f}, +{0.371079f,-0.0406851f,0.0918925f},{0.366152f,-0.0378819f,0.0900281f},{0.361116f,-0.0352877f,0.0900281f}, +{0.366152f,-0.037882f,0.0918925f},{0.355977f,-0.0329054f,0.0900281f},{0.361116f,-0.0352877f,0.0918925f}, +{0.355977f,-0.0329055f,0.0918925f},{0.350742f,-0.0307383f,0.0900281f},{0.345418f,-0.0287896f,0.0900281f}, +{0.350742f,-0.0307384f,0.0918925f},{0.340011f,-0.0270624f,0.0900281f},{0.345418f,-0.0287897f,0.0918925f}, +{0.340011f,-0.0270624f,0.0918925f},{0.334528f,-0.0255598f,0.0900281f},{0.334528f,-0.0255599f,0.0918925f}, +{0.412458f,-0.0789746f,0.0918925f},{0.412458f,-0.0789746f,0.0900281f},{0.415634f,-0.0836681f,0.0918925f}, +{0.418614f,-0.0884938f,0.0918925f},{0.415634f,-0.083668f,0.0900281f},{0.421394f,-0.0934459f,0.0918925f}, +{0.418614f,-0.0884937f,0.0900281f},{0.421394f,-0.0934458f,0.0900281f},{0.423969f,-0.0985185f,0.0918925f}, +{0.426335f,-0.103704f,0.0918925f},{0.423969f,-0.0985183f,0.0900281f},{0.428478f,-0.108978f,0.0918925f}, +{0.426334f,-0.103704f,0.0900281f},{0.428478f,-0.108977f,0.0900281f},{0.430397f,-0.114326f,0.0918925f}, +{0.432088f,-0.119742f,0.0918925f},{0.430397f,-0.114326f,0.0900281f},{0.43355f,-0.125218f,0.0918925f}, +{0.432088f,-0.119742f,0.0900281f},{0.43355f,-0.125218f,0.0900281f},{0.434783f,-0.130747f,0.0918925f}, +{0.435785f,-0.136322f,0.0918925f},{0.434783f,-0.130747f,0.0900281f},{0.436554f,-0.141936f,0.0918925f}, +{0.435785f,-0.136322f,0.0900281f},{0.436554f,-0.141935f,0.0900281f},{0.43709f,-0.14758f,0.0918925f}, +{0.43739f,-0.153248f,0.0918925f},{0.43709f,-0.14758f,0.0900281f},{0.437453f,-0.158933f,0.0918925f}, +{0.43739f,-0.153248f,0.0900281f},{0.437453f,-0.158933f,0.0900281f},{0.437279f,-0.164627f,0.0918925f}, +{0.437279f,-0.164627f,0.0900281f},{0.445352f,-0.169288f,0.0900281f},{0.445352f,-0.169288f,0.0918925f}, +{0.489867f,-0.0239114f,0.0918925f},{0.490408f,-0.0143525f,0.0918925f},{0.490408f,-0.0143527f,0.0900281f}, +{0.490679f,0.00478512f,0.0900281f},{0.490679f,-0.00478519f,0.0900281f},{0.490679f,-0.00478512f,0.0918925f}, +{0.489867f,-0.0239115f,0.0900281f},{0.489056f,-0.0334558f,0.0918925f},{0.489056f,-0.0334558f,0.0900281f}, +{0.487973f,-0.0429801f,0.0900281f},{0.487973f,-0.04298f,0.0918925f},{0.486621f,-0.0524782f,0.0918925f}, +{0.486621f,-0.0524784f,0.0900281f},{0.484998f,-0.0619436f,0.0900281f},{0.484998f,-0.0619434f,0.0918925f}, +{0.480955f,-0.0806965f,0.0900281f},{0.47854f,-0.089968f,0.0900281f},{0.47854f,-0.0899679f,0.0918925f}, +{0.483109f,-0.0713532f,0.0918925f},{0.483109f,-0.0713532f,0.0900281f},{0.480955f,-0.0806964f,0.0918925f}, +{0.475866f,-0.0991622f,0.0918925f},{0.475866f,-0.0991623f,0.0900281f},{0.472933f,-0.108274f,0.0900281f}, +{0.472933f,-0.108274f,0.0918925f},{0.469745f,-0.117298f,0.0918925f},{0.469745f,-0.117298f,0.0900281f}, +{0.466302f,-0.126228f,0.0918925f},{0.458664f,-0.143787f,0.0900281f},{0.458664f,-0.143786f,0.0918925f}, +{0.462608f,-0.135059f,0.0900281f},{0.462608f,-0.135059f,0.0918925f},{0.466302f,-0.126228f,0.0900281f}, +{0.454472f,-0.152404f,0.0900281f},{0.454472f,-0.152404f,0.0918925f},{0.450034f,-0.160907f,0.0900281f}, +{0.450034f,-0.160906f,0.0918925f},{0.490679f,0.00478519f,0.0918925f},{0.490408f,0.0143525f,0.0900281f}, +{0.490408f,0.0143527f,0.0918925f},{0.489867f,0.0239114f,0.0900281f},{0.489056f,0.0334558f,0.0900281f}, +{0.489867f,0.0239115f,0.0918925f},{0.489056f,0.0334558f,0.0918925f},{0.487973f,0.04298f,0.0900281f}, +{0.487973f,0.0429801f,0.0918925f},{0.486621f,0.0524782f,0.0900281f},{0.484998f,0.0619434f,0.0900281f}, +{0.486621f,0.0524784f,0.0918925f},{0.484998f,0.0619436f,0.0918925f},{0.483109f,0.0713532f,0.0900281f}, +{0.483109f,0.0713532f,0.0918925f},{0.480955f,0.0806964f,0.0900281f},{0.47854f,0.0899679f,0.0900281f}, +{0.480955f,0.0806965f,0.0918925f},{0.47854f,0.089968f,0.0918925f},{0.475866f,0.0991622f,0.0900281f}, +{0.475866f,0.0991623f,0.0918925f},{0.472933f,0.108274f,0.0900281f},{0.469745f,0.117298f,0.0900281f}, +{0.472933f,0.108274f,0.0918925f},{0.469745f,0.117298f,0.0918925f},{0.466302f,0.126228f,0.0900281f}, +{0.466302f,0.126228f,0.0918925f},{0.462608f,0.135059f,0.0900281f},{0.458664f,0.143786f,0.0900281f}, +{0.462608f,0.135059f,0.0918925f},{0.458664f,0.143787f,0.0918925f},{0.454472f,0.152404f,0.0900281f}, +{0.454472f,0.152404f,0.0918925f},{0.450034f,0.160906f,0.0900281f},{0.445352f,0.169288f,0.0900281f}, +{0.450034f,0.160907f,0.0918925f},{0.445352f,0.169288f,0.0918925f},{0.427553f,-0.169776f,0.0918925f}, +{0.448656f,-0.18196f,0.0900281f},{0.448656f,-0.18196f,0.0918925f},{0.427553f,-0.169776f,0.0900281f}, +{0.400468f,-0.0785294f,0.0900281f},{0.403757f,-0.0828396f,0.0900281f},{0.403757f,-0.0828395f,0.0918925f}, +{0.396993f,-0.0743574f,0.0900281f},{0.396993f,-0.074357f,0.0918925f},{0.393337f,-0.0703325f,0.0900281f}, +{0.406855f,-0.0872815f,0.0918925f},{0.400468f,-0.0785292f,0.0918925f},{0.406855f,-0.0872816f,0.0900281f}, +{0.409759f,-0.0918488f,0.0918925f},{0.409759f,-0.091849f,0.0900281f},{0.412465f,-0.0965352f,0.0900281f}, +{0.412465f,-0.0965352f,0.0918925f},{0.41497f,-0.101334f,0.0918925f},{0.41497f,-0.101334f,0.0900281f}, +{0.417269f,-0.106239f,0.0900281f},{0.419359f,-0.111243f,0.0918925f},{0.417269f,-0.106239f,0.0918925f}, +{0.419359f,-0.111243f,0.0900281f},{0.421236f,-0.116342f,0.0900281f},{0.421236f,-0.116341f,0.0918925f}, +{0.425533f,-0.132038f,0.0918925f},{0.424327f,-0.126754f,0.0900281f},{0.425533f,-0.132038f,0.0900281f}, +{0.422894f,-0.121519f,0.0918925f},{0.422894f,-0.121519f,0.0900281f},{0.424327f,-0.126754f,0.0918925f}, +{0.426511f,-0.137363f,0.0918925f},{0.427261f,-0.142723f,0.0918925f},{0.426511f,-0.137364f,0.0900281f}, +{0.427261f,-0.142723f,0.0900281f},{0.427781f,-0.14811f,0.0900281f},{0.428071f,-0.153516f,0.0900281f}, +{0.428071f,-0.153516f,0.0918925f},{0.427781f,-0.14811f,0.0918925f},{0.428131f,-0.158934f,0.0900281f}, +{0.428131f,-0.158934f,0.0918925f},{0.427958f,-0.164357f,0.0900281f},{0.427958f,-0.164356f,0.0918925f}, +{0.389518f,-0.0664729f,0.0900281f},{0.393337f,-0.0703321f,0.0918925f},{0.389518f,-0.0664728f,0.0918925f}, +{0.385543f,-0.0627861f,0.0900281f},{0.385543f,-0.0627861f,0.0918925f},{0.381418f,-0.0592762f,0.0900281f}, +{0.37715f,-0.0559475f,0.0900281f},{0.381418f,-0.0592761f,0.0918925f},{0.37715f,-0.0559474f,0.0918925f}, +{0.372745f,-0.0528044f,0.0900281f},{0.372745f,-0.0528044f,0.0918925f},{0.368209f,-0.0498513f,0.0900281f}, +{0.363547f,-0.0470924f,0.0900281f},{0.368209f,-0.0498511f,0.0918925f},{0.363547f,-0.0470923f,0.0918925f}, +{0.358766f,-0.0445321f,0.0900281f},{0.358766f,-0.0445321f,0.0918925f},{0.353872f,-0.042175f,0.0900281f}, +{0.348877f,-0.0400276f,0.0900281f},{0.353871f,-0.0421746f,0.0918925f},{0.348877f,-0.0400276f,0.0918925f}, +{0.343803f,-0.0380996f,0.0900281f},{0.343803f,-0.0380996f,0.0918925f},{0.338659f,-0.0363926f,0.0900281f}, +{0.333452f,-0.0349082f,0.0900281f},{0.338659f,-0.0363926f,0.0918925f},{0.333452f,-0.0349082f,0.0918925f}, +{0.328189f,-0.033648f,0.0900281f},{0.328189f,-0.0336479f,0.0918925f},{0.322877f,-0.0326134f,0.0900281f}, +{0.317524f,-0.031806f,0.0900281f},{0.322877f,-0.0326134f,0.0918925f},{0.317524f,-0.031806f,0.0918925f}, +{0.312137f,-0.0312275f,0.0900281f},{0.312136f,-0.0312274f,0.0918925f},{0.306722f,-0.0308792f,0.0900281f}, +{0.301289f,-0.0307628f,0.0900281f},{0.306722f,-0.0308792f,0.0918925f},{0.301289f,-0.0307628f,0.0918925f}, +{0.270526f,-1.77184e-016f,0.0918925f},{0.270526f,-2.46733e-016f,0.0900281f},{0.270571f,-0.00166887f,0.0900281f}, +{0.270707f,-0.0033296f,0.0900281f},{0.270571f,-0.00166875f,0.0918925f},{0.270931f,-0.00497861f,0.0900281f}, +{0.270706f,-0.00332938f,0.0918925f},{0.270931f,-0.00497832f,0.0918925f},{0.271245f,-0.00661229f,0.0900281f}, +{0.271646f,-0.00822706f,0.0900281f},{0.271245f,-0.00661197f,0.0918925f},{0.272135f,-0.00981931f,0.0900281f}, +{0.271646f,-0.00822672f,0.0918925f},{0.272135f,-0.009819f,0.0918925f},{0.27271f,-0.0113858f,0.0900281f}, +{0.27337f,-0.0129196f,0.0900281f},{0.27271f,-0.0113852f,0.0918925f},{0.274111f,-0.0144128f,0.0900281f}, +{0.27337f,-0.0129192f,0.0918925f},{0.274111f,-0.0144127f,0.0918925f},{0.27493f,-0.0158618f,0.0900281f}, +{0.275826f,-0.0172635f,0.0900281f},{0.27493f,-0.0158617f,0.0918925f},{0.276797f,-0.0186148f,0.0900281f}, +{0.275826f,-0.0172633f,0.0918925f},{0.276797f,-0.0186146f,0.0918925f},{0.27784f,-0.0199127f,0.0900281f}, +{0.278954f,-0.0211544f,0.0900281f},{0.27784f,-0.0199124f,0.0918925f},{0.280135f,-0.0223352f,0.0900281f}, +{0.278953f,-0.0211538f,0.0918925f},{0.280134f,-0.0223347f,0.0918925f},{0.281376f,-0.0234487f,0.0900281f}, +{0.282674f,-0.0244917f,0.0900281f},{0.281376f,-0.0234485f,0.0918925f},{0.284025f,-0.0254622f,0.0900281f}, +{0.282674f,-0.0244916f,0.0918925f},{0.284025f,-0.0254621f,0.0918925f},{0.285427f,-0.0263582f,0.0900281f}, +{0.286876f,-0.0271776f,0.0900281f},{0.285427f,-0.0263581f,0.0918925f},{0.288369f,-0.0279185f,0.0900281f}, +{0.286876f,-0.0271775f,0.0918925f},{0.288369f,-0.0279183f,0.0918925f},{0.289903f,-0.0285784f,0.0900281f}, +{0.29147f,-0.0291536f,0.0900281f},{0.289903f,-0.0285781f,0.0918925f},{0.293062f,-0.0296423f,0.0900281f}, +{0.291469f,-0.0291535f,0.0918925f},{0.293061f,-0.0296423f,0.0918925f},{0.294677f,-0.0300438f,0.0900281f}, +{0.29631f,-0.0303573f,0.0900281f},{0.294676f,-0.0300437f,0.0918925f},{0.297959f,-0.0305821f,0.0900281f}, +{0.29631f,-0.0303572f,0.0918925f},{0.297959f,-0.030582f,0.0918925f},{0.29962f,-0.0307175f,0.0900281f}, +{0.29962f,-0.0307174f,0.0918925f},{0.270571f,0.00166887f,0.0918925f},{0.270571f,0.00166875f,0.0900281f}, +{0.270707f,0.0033296f,0.0918925f},{0.270931f,0.00497861f,0.0918925f},{0.270706f,0.00332938f,0.0900281f}, +{0.271245f,0.00661229f,0.0918925f},{0.270931f,0.00497832f,0.0900281f},{0.271245f,0.00661197f,0.0900281f}, +{0.271646f,0.00822706f,0.0918925f},{0.272135f,0.00981931f,0.0918925f},{0.271646f,0.00822672f,0.0900281f}, +{0.27271f,0.0113858f,0.0918925f},{0.272135f,0.009819f,0.0900281f},{0.27271f,0.0113852f,0.0900281f}, +{0.27337f,0.0129196f,0.0918925f},{0.274111f,0.0144128f,0.0918925f},{0.27337f,0.0129192f,0.0900281f}, +{0.27493f,0.0158618f,0.0918925f},{0.274111f,0.0144127f,0.0900281f},{0.27493f,0.0158617f,0.0900281f}, +{0.275826f,0.0172635f,0.0918925f},{0.276797f,0.0186148f,0.0918925f},{0.275826f,0.0172633f,0.0900281f}, +{0.27784f,0.0199127f,0.0918925f},{0.276797f,0.0186146f,0.0900281f},{0.27784f,0.0199124f,0.0900281f}, +{0.278954f,0.0211544f,0.0918925f},{0.280135f,0.0223352f,0.0918925f},{0.278953f,0.0211538f,0.0900281f}, +{0.281376f,0.0234487f,0.0918925f},{0.280134f,0.0223347f,0.0900281f},{0.281376f,0.0234485f,0.0900281f}, +{0.282674f,0.0244917f,0.0918925f},{0.284025f,0.0254622f,0.0918925f},{0.282674f,0.0244916f,0.0900281f}, +{0.285427f,0.0263582f,0.0918925f},{0.284025f,0.0254621f,0.0900281f},{0.285427f,0.0263581f,0.0900281f}, +{0.286876f,0.0271776f,0.0918925f},{0.288369f,0.0279185f,0.0918925f},{0.286876f,0.0271775f,0.0900281f}, +{0.289903f,0.0285784f,0.0918925f},{0.288369f,0.0279183f,0.0900281f},{0.289903f,0.0285781f,0.0900281f}, +{0.29147f,0.0291536f,0.0918925f},{0.293062f,0.0296423f,0.0918925f},{0.291469f,0.0291535f,0.0900281f}, +{0.294677f,0.0300438f,0.0918925f},{0.293061f,0.0296423f,0.0900281f},{0.294676f,0.0300437f,0.0900281f}, +{0.29631f,0.0303573f,0.0918925f},{0.297959f,0.0305821f,0.0918925f},{0.29631f,0.0303572f,0.0900281f}, +{0.29962f,0.0307175f,0.0918925f},{0.297959f,0.030582f,0.0900281f},{0.29962f,0.0307174f,0.0900281f}, +{0.301289f,0.0307628f,0.0918925f},{0.301289f,0.0307628f,0.0900281f},{0.389518f,0.0664728f,0.0900281f}, +{0.385543f,0.0627861f,0.0900281f},{0.385543f,0.0627861f,0.0918925f},{0.393337f,0.0703321f,0.0900281f}, +{0.393337f,0.0703325f,0.0918925f},{0.396993f,0.074357f,0.0900281f},{0.381418f,0.0592762f,0.0918925f}, +{0.389518f,0.0664729f,0.0918925f},{0.381418f,0.0592761f,0.0900281f},{0.37715f,0.0559475f,0.0918925f}, +{0.37715f,0.0559474f,0.0900281f},{0.372745f,0.0528044f,0.0900281f},{0.372745f,0.0528044f,0.0918925f}, +{0.368209f,0.0498513f,0.0918925f},{0.368209f,0.0498511f,0.0900281f},{0.363547f,0.0470923f,0.0900281f}, +{0.358766f,0.0445321f,0.0918925f},{0.363547f,0.0470924f,0.0918925f},{0.358766f,0.0445321f,0.0900281f}, +{0.353871f,0.0421746f,0.0900281f},{0.353872f,0.042175f,0.0918925f},{0.338659f,0.0363926f,0.0918925f}, +{0.343803f,0.0380996f,0.0900281f},{0.338659f,0.0363926f,0.0900281f},{0.348877f,0.0400276f,0.0918925f}, +{0.348877f,0.0400276f,0.0900281f},{0.343803f,0.0380996f,0.0918925f},{0.333452f,0.0349082f,0.0918925f}, +{0.328189f,0.033648f,0.0918925f},{0.333452f,0.0349082f,0.0900281f},{0.328189f,0.0336479f,0.0900281f}, +{0.322877f,0.0326134f,0.0900281f},{0.317524f,0.031806f,0.0900281f},{0.317524f,0.031806f,0.0918925f}, +{0.322877f,0.0326134f,0.0918925f},{0.312136f,0.0312274f,0.0900281f},{0.312137f,0.0312275f,0.0918925f}, +{0.306722f,0.0308792f,0.0900281f},{0.306722f,0.0308792f,0.0918925f},{0.400468f,0.0785292f,0.0900281f}, +{0.396993f,0.0743574f,0.0918925f},{0.400468f,0.0785294f,0.0918925f},{0.403757f,0.0828395f,0.0900281f}, +{0.403757f,0.0828396f,0.0918925f},{0.406855f,0.0872815f,0.0900281f},{0.409759f,0.0918488f,0.0900281f}, +{0.406855f,0.0872816f,0.0918925f},{0.409759f,0.091849f,0.0918925f},{0.412465f,0.0965352f,0.0900281f}, +{0.412465f,0.0965352f,0.0918925f},{0.41497f,0.101334f,0.0900281f},{0.417269f,0.106239f,0.0900281f}, +{0.41497f,0.101334f,0.0918925f},{0.417269f,0.106239f,0.0918925f},{0.419359f,0.111243f,0.0900281f}, +{0.419359f,0.111243f,0.0918925f},{0.421236f,0.116341f,0.0900281f},{0.422894f,0.121519f,0.0900281f}, +{0.421236f,0.116342f,0.0918925f},{0.422894f,0.121519f,0.0918925f},{0.424327f,0.126754f,0.0900281f}, +{0.424327f,0.126754f,0.0918925f},{0.425533f,0.132038f,0.0900281f},{0.426511f,0.137363f,0.0900281f}, +{0.425533f,0.132038f,0.0918925f},{0.426511f,0.137364f,0.0918925f},{0.427261f,0.142723f,0.0900281f}, +{0.427261f,0.142723f,0.0918925f},{0.427781f,0.14811f,0.0900281f},{0.428071f,0.153516f,0.0900281f}, +{0.427781f,0.14811f,0.0918925f},{0.428071f,0.153516f,0.0918925f},{0.428131f,0.158934f,0.0900281f}, +{0.428131f,0.158934f,0.0918925f},{0.427958f,0.164356f,0.0900281f},{0.427553f,0.169776f,0.0900281f}, +{0.427958f,0.164357f,0.0918925f},{0.427553f,0.169776f,0.0918925f},{0.448656f,0.18196f,0.0918925f}, +{0.448656f,0.18196f,0.0900281f},{0.5f,0.0049028f,0.0918925f},{0.5f,-0.00490289f,0.0918925f}, +{0.5f,0.00490289f,0.0900281f},{0.499724f,0.0147057f,0.0900281f},{0.499724f,0.0147055f,0.0918925f}, +{0.499171f,0.0244996f,0.0900281f},{0.499171f,0.0244996f,0.0918925f},{0.498342f,0.0342788f,0.0918925f}, +{0.498342f,0.034279f,0.0900281f},{0.497236f,0.0440377f,0.0900281f},{0.497236f,0.0440376f,0.0918925f}, +{0.495854f,0.05377f,0.0900281f},{0.495854f,0.05377f,0.0918925f},{0.494196f,0.0634697f,0.0918925f}, +{0.494196f,0.0634706f,0.0900281f},{0.492264f,0.0731194f,0.0900281f},{0.492264f,0.0731193f,0.0918925f}, +{0.490062f,0.0826996f,0.0900281f},{0.490062f,0.0826996f,0.0918925f},{0.487593f,0.0922052f,0.0918925f}, +{0.487593f,0.0922054f,0.0900281f},{0.484859f,0.101631f,0.0900281f},{0.484859f,0.101631f,0.0918925f}, +{0.481861f,0.110971f,0.0900281f},{0.481861f,0.110971f,0.0918925f},{0.478603f,0.120221f,0.0918925f}, +{0.478602f,0.120221f,0.0900281f},{0.475085f,0.129374f,0.0900281f},{0.475085f,0.129374f,0.0918925f}, +{0.47131f,0.138425f,0.0900281f},{0.47131f,0.138425f,0.0918925f},{0.46728f,0.147368f,0.0918925f}, +{0.46728f,0.147369f,0.0900281f},{0.462998f,0.156199f,0.0900281f},{0.462998f,0.156199f,0.0918925f}, +{0.458465f,0.164912f,0.0900281f},{0.458465f,0.164912f,0.0918925f},{0.453684f,0.173501f,0.0918925f}, +{0.453684f,0.173501f,0.0900281f},{0.5f,-0.0049028f,0.0900281f},{0.499724f,-0.0147055f,0.0900281f}, +{0.499724f,-0.0147057f,0.0918925f},{0.499171f,-0.0244996f,0.0918925f},{0.499171f,-0.0244996f,0.0900281f}, +{0.498342f,-0.034279f,0.0918925f},{0.498342f,-0.0342788f,0.0900281f},{0.497236f,-0.0440376f,0.0900281f}, +{0.497236f,-0.0440377f,0.0918925f},{0.495854f,-0.05377f,0.0918925f},{0.495854f,-0.05377f,0.0900281f}, +{0.494196f,-0.0634706f,0.0918925f},{0.494196f,-0.0634697f,0.0900281f},{0.492264f,-0.0731193f,0.0900281f}, +{0.492264f,-0.0731194f,0.0918925f},{0.490062f,-0.0826996f,0.0918925f},{0.490062f,-0.0826996f,0.0900281f}, +{0.487593f,-0.0922054f,0.0918925f},{0.487593f,-0.0922052f,0.0900281f},{0.484859f,-0.101631f,0.0900281f}, +{0.484859f,-0.101631f,0.0918925f},{0.481861f,-0.110971f,0.0918925f},{0.481861f,-0.110971f,0.0900281f}, +{0.478602f,-0.120221f,0.0918925f},{0.478603f,-0.120221f,0.0900281f},{0.475085f,-0.129374f,0.0900281f}, +{0.475085f,-0.129374f,0.0918925f},{0.47131f,-0.138425f,0.0918925f},{0.47131f,-0.138425f,0.0900281f}, +{0.46728f,-0.147369f,0.0918925f},{0.46728f,-0.147368f,0.0900281f},{0.462998f,-0.156199f,0.0900281f}, +{0.462998f,-0.156199f,0.0918925f},{0.458465f,-0.164912f,0.0918925f},{0.458465f,-0.164912f,0.0900281f}, +{0.453684f,-0.173501f,0.0918925f},{0.453684f,-0.173501f,0.0900281f},{0.295886f,0.0200317f,0.0918925f}, +{0.280259f,0.0036392f,0.0918925f},{0.280781f,0.00474168f,0.0918925f},{0.28931f,0.0152687f,0.0918925f}, +{0.29453f,0.0183517f,0.0918925f},{0.28153f,0.0057053f,0.0918925f},{0.291507f,0.0130697f,0.0918925f}, +{0.289835f,0.0151095f,0.0918925f},{0.294119f,0.0173478f,0.0918925f},{0.291087f,0.0109706f,0.0918925f}, +{0.290739f,0.0105473f,0.0918925f},{0.295126f,0.0192577f,0.0918925f},{0.296782f,0.0206442f,0.0918925f}, +{0.297778f,0.0210723f,0.0918925f},{0.290316f,0.0101998f,0.0918925f},{0.291091f,0.0140791f,0.0918925f}, +{0.293911f,0.0151984f,0.0918925f},{0.290742f,0.0145033f,0.0918925f},{0.315791f,-0.0105451f,0.0918925f}, +{0.315367f,-0.0101973f,0.0918925f},{0.316139f,-0.0109693f,0.0918925f},{0.314358f,-0.00977971f,0.0918925f}, +{0.314883f,-0.00993885f,0.0918925f},{0.314881f,-0.0151067f,0.0918925f},{0.316555f,-0.0119787f,0.0918925f}, +{0.316397f,-0.0114536f,0.0918925f},{0.316609f,-0.0125242f,0.0918925f},{0.316394f,-0.013595f,0.0918925f}, +{0.316135f,-0.0140778f,0.0918925f},{0.315788f,-0.0145011f,0.0918925f},{0.315364f,-0.0148486f,0.0918925f}, +{0.314357f,-0.015266f,0.0918925f},{0.290318f,0.0148511f,0.0918925f},{0.29391f,0.0162833f,0.0918925f}, +{0.291506f,0.0119779f,0.0918925f},{0.291561f,0.0125242f,0.0918925f},{0.291346f,0.0114534f,0.0918925f}, +{0.291349f,0.0135948f,0.0918925f},{0.289833f,0.00994166f,0.0918925f},{0.316555f,-0.0130705f,0.0918925f}, +{0.289309f,0.00978241f,0.0918925f},{0.280782f,0.00474296f,0.0900281f},{0.297777f,0.0210725f,0.0900281f}, +{0.296781f,0.020644f,0.0900281f},{0.290742f,0.0105451f,0.0900281f},{0.280259f,0.00364027f,0.0900281f}, +{0.289835f,0.00993885f,0.0900281f},{0.295886f,0.0200312f,0.0900281f},{0.295126f,0.0192574f,0.0900281f}, +{0.29391f,0.0162822f,0.0900281f},{0.290739f,0.0145011f,0.0900281f},{0.290316f,0.0148486f,0.0900281f}, +{0.291561f,0.0125242f,0.0900281f},{0.28931f,0.00977971f,0.0900281f},{0.291091f,0.0109693f,0.0900281f}, +{0.290318f,0.0101973f,0.0900281f},{0.291349f,0.0114536f,0.0900281f},{0.315791f,-0.0145033f,0.0900281f}, +{0.316139f,-0.0140791f,0.0900281f},{0.314357f,-0.00978241f,0.0900281f},{0.314881f,-0.00994166f,0.0900281f}, +{0.294529f,0.0183513f,0.0900281f},{0.294119f,0.0173468f,0.0900281f},{0.289833f,0.0151067f,0.0900281f}, +{0.289309f,0.015266f,0.0900281f},{0.291087f,0.0140778f,0.0900281f},{0.293911f,0.0151976f,0.0900281f}, +{0.291346f,0.013595f,0.0900281f},{0.28153f,0.00570553f,0.0900281f},{0.316555f,-0.0119779f,0.0900281f}, +{0.315364f,-0.0101998f,0.0900281f},{0.316609f,-0.0125242f,0.0900281f},{0.316555f,-0.0130697f,0.0900281f}, +{0.316397f,-0.0135948f,0.0900281f},{0.315367f,-0.0148511f,0.0900281f},{0.314883f,-0.0151095f,0.0900281f}, +{0.316135f,-0.0109706f,0.0900281f},{0.314358f,-0.0152687f,0.0900281f},{0.316394f,-0.0114534f,0.0900281f}, +{0.315788f,-0.0105473f,0.0900281f},{0.291507f,0.0119787f,0.0900281f},{0.291506f,0.0130705f,0.0900281f}, +{-0.0125242f,0.285968f,0.0900281f},{-0.0130723f,0.286022f,0.0918925f},{-0.0125242f,0.285968f,0.0918925f}, +{-0.011454f,0.286181f,0.0918925f},{-0.011454f,0.286181f,0.0900281f},{-0.0119761f,0.286022f,0.0918925f}, +{-0.0119761f,0.286022f,0.0900281f},{-0.0109726f,0.286438f,0.0900281f},{-0.0105467f,0.286787f,0.0900281f}, +{-0.0105467f,0.286787f,0.0918925f},{-0.0101975f,0.287213f,0.0900281f},{-0.0101975f,0.287213f,0.0918925f}, +{-0.0109726f,0.286438f,0.0918925f},{-0.00972758f,0.288764f,0.0900281f},{-0.00978182f,0.288216f,0.0900281f}, +{-0.00978182f,0.288216f,0.0918925f},{-0.00994047f,0.287694f,0.0918925f},{-0.00994047f,0.287694f,0.0900281f}, +{-0.00972758f,0.288764f,0.0918925f},{-0.0130723f,0.286022f,0.0900281f},{-0.0135944f,0.286181f,0.0918925f}, +{-0.0135944f,0.286181f,0.0900281f},{-0.0140758f,0.286438f,0.0900281f},{-0.0140758f,0.286438f,0.0918925f}, +{-0.0145017f,0.286787f,0.0900281f},{-0.0145017f,0.286787f,0.0918925f},{-0.0148509f,0.287213f,0.0918925f}, +{-0.0148509f,0.287213f,0.0900281f},{-0.0151079f,0.287694f,0.0900281f},{-0.0151079f,0.287694f,0.0918925f}, +{-0.0152666f,0.288216f,0.0900281f},{-0.0152666f,0.288216f,0.0918925f},{-0.0153208f,0.288764f,0.0918925f}, +{-0.0153208f,0.288764f,0.0900281f},{0.0125242f,0.311016f,0.0900281f},{0.0119761f,0.31107f,0.0918925f}, +{0.0125242f,0.311016f,0.0918925f},{0.0135944f,0.311229f,0.0918925f},{0.0135944f,0.311229f,0.0900281f}, +{0.0130723f,0.31107f,0.0918925f},{0.0130723f,0.31107f,0.0900281f},{0.0140758f,0.311486f,0.0900281f}, +{0.0145017f,0.311835f,0.0900281f},{0.0145017f,0.311835f,0.0918925f},{0.0148509f,0.312261f,0.0900281f}, +{0.0148509f,0.312261f,0.0918925f},{0.0140758f,0.311486f,0.0918925f},{0.0153208f,0.313813f,0.0900281f}, +{0.0152666f,0.313265f,0.0900281f},{0.0152666f,0.313265f,0.0918925f},{0.0151079f,0.312743f,0.0918925f}, +{0.0151079f,0.312743f,0.0900281f},{0.0153208f,0.313813f,0.0918925f},{0.0119761f,0.31107f,0.0900281f}, +{0.011454f,0.311229f,0.0918925f},{0.011454f,0.311229f,0.0900281f},{0.0109726f,0.311486f,0.0900281f}, +{0.0109726f,0.311486f,0.0918925f},{0.0105467f,0.311835f,0.0900281f},{0.0105467f,0.311835f,0.0918925f}, +{0.0101975f,0.312261f,0.0918925f},{0.0101975f,0.312261f,0.0900281f},{0.00994047f,0.312743f,0.0900281f}, +{0.00994047f,0.312743f,0.0918925f},{0.00978182f,0.313265f,0.0900281f},{0.00978182f,0.313265f,0.0918925f}, +{0.00972758f,0.313813f,0.0918925f},{0.00972758f,0.313813f,0.0900281f},{-0.0073455f,0.284736f,0.0900281f}, +{-0.00738926f,0.285954f,0.0918925f},{-0.00734538f,0.284736f,0.0918925f},{-0.00703877f,0.283556f,0.0900281f}, +{-0.0070384f,0.283555f,0.0918925f},{-0.00648281f,0.28247f,0.0900281f},{-0.00648282f,0.28247f,0.0918925f}, +{-0.00738915f,0.285956f,0.0900281f},{-0.00716427f,0.287154f,0.0918925f},{-0.00716427f,0.287154f,0.0900281f}, +{0.00856857f,0.309858f,0.0918925f},{0.0078732f,0.310706f,0.0918925f},{0.00856991f,0.309857f,0.0900281f}, +{0.00787361f,0.310705f,0.0900281f},{0.0073566f,0.311673f,0.0918925f},{0.00703838f,0.312722f,0.0918925f}, +{0.00735691f,0.311672f,0.0900281f},{0.00693097f,0.313813f,0.0918925f},{0.00703853f,0.312721f,0.0900281f}, +{0.00693097f,0.313813f,0.0900281f},{0.00941743f,0.309162f,0.0900281f},{0.0103841f,0.308645f,0.0900281f}, +{0.00941663f,0.309162f,0.0918925f},{0.0114331f,0.308327f,0.0900281f},{0.0103834f,0.308645f,0.0918925f}, +{0.0114326f,0.308327f,0.0918925f},{0.0125242f,0.30822f,0.0900281f},{0.0125242f,0.30822f,0.0918925f}, +{-0.065917f,0.401959f,0.0918925f},{-0.0617984f,0.398048f,0.0918925f},{-0.0659174f,0.40196f,0.0900281f}, +{-0.07019f,0.405692f,0.0900281f},{-0.0701898f,0.405691f,0.0918925f},{-0.0746077f,0.409237f,0.0900281f}, +{-0.0746076f,0.409237f,0.0918925f},{-0.0791643f,0.412592f,0.0918925f},{-0.0791644f,0.412592f,0.0900281f}, +{-0.0838538f,0.415754f,0.0900281f},{-0.0838537f,0.415754f,0.0918925f},{-0.0886696f,0.418717f,0.0900281f}, +{-0.0886696f,0.418717f,0.0918925f},{-0.0936056f,0.421479f,0.0918925f},{-0.0936057f,0.421479f,0.0900281f}, +{-0.0986557f,0.424035f,0.0900281f},{-0.0986556f,0.424035f,0.0918925f},{-0.103813f,0.426382f,0.0900281f}, +{-0.103813f,0.426382f,0.0918925f},{-0.109072f,0.428515f,0.0918925f},{-0.109073f,0.428515f,0.0900281f}, +{-0.11442f,0.430428f,0.0900281f},{-0.11442f,0.430428f,0.0918925f},{-0.119834f,0.432114f,0.0900281f}, +{-0.119834f,0.432114f,0.0918925f},{-0.125306f,0.433572f,0.0918925f},{-0.125307f,0.433572f,0.0900281f}, +{-0.130829f,0.4348f,0.0900281f},{-0.130829f,0.4348f,0.0918925f},{-0.136396f,0.435797f,0.0900281f}, +{-0.136396f,0.435797f,0.0918925f},{-0.141999f,0.436561f,0.0918925f},{-0.141999f,0.436561f,0.0900281f}, +{-0.147631f,0.437093f,0.0900281f},{-0.147631f,0.437093f,0.0918925f},{-0.153284f,0.437391f,0.0900281f}, +{-0.153284f,0.437391f,0.0918925f},{-0.158952f,0.437453f,0.0918925f},{-0.158952f,0.437453f,0.0900281f}, +{-0.164627f,0.437279f,0.0900281f},{-0.164627f,0.437279f,0.0918925f},{-0.0617987f,0.398048f,0.0900281f}, +{-0.0578515f,0.393973f,0.0900281f},{-0.0578514f,0.393973f,0.0918925f},{-0.054083f,0.389744f,0.0918925f}, +{-0.0540831f,0.389744f,0.0900281f},{-0.0504973f,0.385366f,0.0918925f},{-0.0504974f,0.385366f,0.0900281f}, +{-0.0470986f,0.380846f,0.0900281f},{-0.0470985f,0.380846f,0.0918925f},{-0.0438908f,0.376189f,0.0918925f}, +{-0.0438908f,0.376189f,0.0900281f},{-0.0408784f,0.371402f,0.0918925f},{-0.0408785f,0.371402f,0.0900281f}, +{-0.0380656f,0.36649f,0.0900281f},{-0.0380655f,0.36649f,0.0918925f},{-0.0354565f,0.36146f,0.0918925f}, +{-0.0354565f,0.36146f,0.0900281f},{-0.0330551f,0.356317f,0.0918925f},{-0.0330554f,0.356318f,0.0900281f}, +{-0.0308688f,0.351076f,0.0900281f},{-0.0308688f,0.351076f,0.0918925f},{-0.0289059f,0.345756f,0.0918925f}, +{-0.0289059f,0.345756f,0.0900281f},{-0.0271683f,0.340366f,0.0918925f},{-0.0271684f,0.340366f,0.0900281f}, +{-0.0256577f,0.334914f,0.0900281f},{-0.0256577f,0.334914f,0.0918925f},{-0.0243753f,0.329406f,0.0918925f}, +{-0.0243754f,0.329406f,0.0900281f},{-0.0233228f,0.32385f,0.0918925f},{-0.0233228f,0.32385f,0.0900281f}, +{-0.0225016f,0.318253f,0.0900281f},{-0.0225016f,0.318253f,0.0918925f},{-0.0219132f,0.312622f,0.0918925f}, +{-0.0219132f,0.312623f,0.0900281f},{-0.0215591f,0.306965f,0.0918925f},{-0.0215591f,0.306965f,0.0900281f}, +{-0.0214407f,0.301289f,0.0918925f},{-0.0214407f,0.301289f,0.0900281f},{-0.0214056f,0.300061f,0.0918925f}, +{-0.0214056f,0.300061f,0.0900281f},{-0.0213002f,0.298838f,0.0900281f},{-0.0213002f,0.298838f,0.0918925f}, +{-0.00857005f,0.29272f,0.0900281f},{-0.00933952f,0.293362f,0.0900281f},{-0.00856812f,0.292718f,0.0918925f}, +{-0.0102104f,0.293856f,0.0918925f},{-0.00933867f,0.293362f,0.0918925f},{-0.010212f,0.293857f,0.0900281f}, +{-0.0111572f,0.294188f,0.0918925f},{-0.0111588f,0.294188f,0.0900281f},{-0.0121484f,0.294345f,0.0918925f}, +{-0.0131504f,0.294322f,0.0918925f},{-0.0121494f,0.294345f,0.0900281f},{-0.0141339f,0.294121f,0.0900281f}, +{-0.0131516f,0.294322f,0.0900281f},{-0.0141339f,0.294121f,0.0918925f},{-0.00792586f,0.291949f,0.0918925f}, +{-0.00792654f,0.29195f,0.0900281f},{-0.00743177f,0.291078f,0.0900281f},{-0.00710074f,0.290131f,0.0900281f}, +{-0.00743116f,0.291076f,0.0918925f},{-0.00710007f,0.290129f,0.0918925f},{-0.00694354f,0.28914f,0.0900281f}, +{-0.00694356f,0.289139f,0.0918925f},{-0.00696625f,0.288138f,0.0900281f},{-0.00696632f,0.288136f,0.0918925f}, +{0.0121669f,0.283634f,0.0900281f},{0.0102959f,0.282482f,0.0900281f},{0.0102961f,0.282482f,0.0918925f}, +{0.012167f,0.283634f,0.0918925f},{0.013914f,0.284976f,0.0900281f},{0.008319f,0.281528f,0.0918925f}, +{0.00831882f,0.281527f,0.0900281f},{0.00625128f,0.280779f,0.0918925f},{0.00625078f,0.280779f,0.0900281f}, +{0.00411456f,0.280246f,0.0918925f},{0.00411435f,0.280246f,0.0900281f},{0.00194003f,0.279936f,0.0900281f}, +{0.0019402f,0.279936f,0.0918925f},{-0.000253827f,0.279849f,0.0918925f},{-0.00245022f,0.279988f,0.0918925f}, +{-0.00025393f,0.279849f,0.0900281f},{-0.00245022f,0.279988f,0.0900281f},{0.0155106f,0.286486f,0.0900281f}, +{0.0139141f,0.284976f,0.0918925f},{0.0155107f,0.286486f,0.0918925f},{0.016943f,0.288149f,0.0900281f}, +{0.0169431f,0.28815f,0.0918925f},{0.0181996f,0.289954f,0.0900281f},{0.0192663f,0.29188f,0.0900281f}, +{0.0181999f,0.289954f,0.0918925f},{0.0192664f,0.291881f,0.0918925f},{0.0201277f,0.293901f,0.0900281f}, +{0.0201278f,0.293901f,0.0918925f},{0.0207778f,0.295998f,0.0900281f},{0.0212106f,0.298156f,0.0900281f}, +{0.0207778f,0.295998f,0.0918925f},{0.0212106f,0.298156f,0.0918925f},{0.0200545f,0.303955f,0.0900281f}, +{0.0207145f,0.302604f,0.0918925f},{0.020054f,0.303956f,0.0918925f},{0.0191712f,0.305176f,0.0900281f}, +{0.0207149f,0.302603f,0.0900281f},{0.0211353f,0.301156f,0.0918925f},{0.0191712f,0.305176f,0.0918925f}, +{0.0211356f,0.301155f,0.0900281f},{0.021302f,0.29966f,0.0918925f},{0.0213021f,0.299659f,0.0900281f}, +{0.0180928f,0.306228f,0.0900281f},{0.018092f,0.306229f,0.0918925f},{0.0168512f,0.307079f,0.0918925f}, +{0.0168521f,0.307079f,0.0900281f},{0.0154797f,0.307707f,0.0918925f},{0.0154807f,0.307707f,0.0900281f}, +{0.0140259f,0.30809f,0.0900281f},{0.014025f,0.30809f,0.0918925f},{0.00703853f,0.314904f,0.0918925f}, +{0.00856991f,0.317768f,0.0918925f},{0.0078732f,0.31692f,0.0900281f},{0.00787361f,0.31692f,0.0918925f}, +{0.00735691f,0.315954f,0.0918925f},{0.0073566f,0.315953f,0.0900281f},{0.00703838f,0.314904f,0.0900281f}, +{0.0103834f,0.31898f,0.0900281f},{0.0103841f,0.31898f,0.0918925f},{0.0114331f,0.319299f,0.0918925f}, +{0.00856857f,0.317767f,0.0900281f},{0.00941743f,0.318464f,0.0918925f},{0.00941663f,0.318463f,0.0900281f}, +{0.0125242f,0.319406f,0.0918925f},{0.0114326f,0.319298f,0.0900281f},{0.0125242f,0.319406f,0.0900281f}, +{0.017806f,0.32063f,0.0900281f},{0.0178073f,0.32063f,0.0918925f},{0.0193785f,0.321554f,0.0900281f}, +{0.0193787f,0.321554f,0.0918925f},{0.0161135f,0.319955f,0.0918925f},{0.0161128f,0.319955f,0.0900281f}, +{0.0143418f,0.319544f,0.0900281f},{0.0143423f,0.319544f,0.0918925f},{0.0207886f,0.322701f,0.0900281f}, +{0.0220123f,0.324052f,0.0900281f},{0.0207888f,0.322701f,0.0918925f},{0.0220132f,0.324053f,0.0918925f}, +{0.023018f,0.325573f,0.0900281f},{0.0230183f,0.325573f,0.0918925f},{0.02378f,0.327224f,0.0900281f}, +{0.0242851f,0.328976f,0.0900281f},{0.0237802f,0.327224f,0.0918925f},{0.0242851f,0.328976f,0.0918925f}, +{0.0744192f,0.409092f,0.0918925f},{0.0744192f,0.409092f,0.0900281f},{0.0700077f,0.405539f,0.0900281f}, +{0.065746f,0.401803f,0.0900281f},{0.0700077f,0.405539f,0.0918925f},{0.06164f,0.397891f,0.0900281f}, +{0.0657461f,0.401803f,0.0918925f},{0.0616401f,0.397891f,0.0918925f},{0.0576956f,0.393805f,0.0900281f}, +{0.0539185f,0.389551f,0.0900281f},{0.0576957f,0.393805f,0.0918925f},{0.0503158f,0.385134f,0.0900281f}, +{0.0539186f,0.389551f,0.0918925f},{0.050316f,0.385135f,0.0918925f},{0.0469052f,0.380577f,0.0900281f}, +{0.0436939f,0.375889f,0.0900281f},{0.0469052f,0.380577f,0.0918925f},{0.0406851f,0.371079f,0.0900281f}, +{0.0436939f,0.375889f,0.0918925f},{0.0406851f,0.371079f,0.0918925f},{0.0378819f,0.366152f,0.0900281f}, +{0.0352877f,0.361116f,0.0900281f},{0.037882f,0.366152f,0.0918925f},{0.0329054f,0.355977f,0.0900281f}, +{0.0352877f,0.361116f,0.0918925f},{0.0329055f,0.355977f,0.0918925f},{0.0307383f,0.350742f,0.0900281f}, +{0.0287896f,0.345418f,0.0900281f},{0.0307384f,0.350742f,0.0918925f},{0.0270624f,0.340011f,0.0900281f}, +{0.0287897f,0.345418f,0.0918925f},{0.0270624f,0.340011f,0.0918925f},{0.0255598f,0.334528f,0.0900281f}, +{0.0255599f,0.334528f,0.0918925f},{0.0789746f,0.412458f,0.0918925f},{0.0789746f,0.412458f,0.0900281f}, +{0.0836681f,0.415634f,0.0918925f},{0.0884938f,0.418614f,0.0918925f},{0.083668f,0.415634f,0.0900281f}, +{0.0934459f,0.421394f,0.0918925f},{0.0884937f,0.418614f,0.0900281f},{0.0934458f,0.421394f,0.0900281f}, +{0.0985185f,0.423969f,0.0918925f},{0.103704f,0.426335f,0.0918925f},{0.0985183f,0.423969f,0.0900281f}, +{0.108978f,0.428478f,0.0918925f},{0.103704f,0.426334f,0.0900281f},{0.108977f,0.428478f,0.0900281f}, +{0.114326f,0.430397f,0.0918925f},{0.119742f,0.432088f,0.0918925f},{0.114326f,0.430397f,0.0900281f}, +{0.125218f,0.43355f,0.0918925f},{0.119742f,0.432088f,0.0900281f},{0.125218f,0.43355f,0.0900281f}, +{0.130747f,0.434783f,0.0918925f},{0.136322f,0.435785f,0.0918925f},{0.130747f,0.434783f,0.0900281f}, +{0.141936f,0.436554f,0.0918925f},{0.136322f,0.435785f,0.0900281f},{0.141935f,0.436554f,0.0900281f}, +{0.14758f,0.43709f,0.0918925f},{0.153248f,0.43739f,0.0918925f},{0.14758f,0.43709f,0.0900281f}, +{0.158933f,0.437453f,0.0918925f},{0.153248f,0.43739f,0.0900281f},{0.158933f,0.437453f,0.0900281f}, +{0.164627f,0.437279f,0.0918925f},{0.164627f,0.437279f,0.0900281f},{0.169288f,0.445352f,0.0900281f}, +{0.169288f,0.445352f,0.0918925f},{0.0239114f,0.489867f,0.0918925f},{0.0143525f,0.490408f,0.0918925f}, +{0.0143527f,0.490408f,0.0900281f},{-0.00478512f,0.490679f,0.0900281f},{0.00478519f,0.490679f,0.0900281f}, +{0.00478512f,0.490679f,0.0918925f},{0.0239115f,0.489867f,0.0900281f},{0.0334558f,0.489056f,0.0918925f}, +{0.0334558f,0.489056f,0.0900281f},{0.0429801f,0.487973f,0.0900281f},{0.04298f,0.487973f,0.0918925f}, +{0.0524782f,0.486621f,0.0918925f},{0.0524784f,0.486621f,0.0900281f},{0.0619436f,0.484998f,0.0900281f}, +{0.0619434f,0.484998f,0.0918925f},{0.0806965f,0.480955f,0.0900281f},{0.089968f,0.47854f,0.0900281f}, +{0.0899679f,0.47854f,0.0918925f},{0.0713532f,0.483109f,0.0918925f},{0.0713532f,0.483109f,0.0900281f}, +{0.0806964f,0.480955f,0.0918925f},{0.0991622f,0.475866f,0.0918925f},{0.0991623f,0.475866f,0.0900281f}, +{0.108274f,0.472933f,0.0900281f},{0.108274f,0.472933f,0.0918925f},{0.117298f,0.469745f,0.0918925f}, +{0.117298f,0.469745f,0.0900281f},{0.126228f,0.466302f,0.0918925f},{0.143787f,0.458664f,0.0900281f}, +{0.143786f,0.458664f,0.0918925f},{0.135059f,0.462608f,0.0900281f},{0.135059f,0.462608f,0.0918925f}, +{0.126228f,0.466302f,0.0900281f},{0.152404f,0.454472f,0.0900281f},{0.152404f,0.454472f,0.0918925f}, +{0.160907f,0.450034f,0.0900281f},{0.160906f,0.450034f,0.0918925f},{-0.00478519f,0.490679f,0.0918925f}, +{-0.0143525f,0.490408f,0.0900281f},{-0.0143527f,0.490408f,0.0918925f},{-0.0239114f,0.489867f,0.0900281f}, +{-0.0334558f,0.489056f,0.0900281f},{-0.0239115f,0.489867f,0.0918925f},{-0.0334558f,0.489056f,0.0918925f}, +{-0.04298f,0.487973f,0.0900281f},{-0.0429801f,0.487973f,0.0918925f},{-0.0524782f,0.486621f,0.0900281f}, +{-0.0619434f,0.484998f,0.0900281f},{-0.0524784f,0.486621f,0.0918925f},{-0.0619436f,0.484998f,0.0918925f}, +{-0.0713532f,0.483109f,0.0900281f},{-0.0713532f,0.483109f,0.0918925f},{-0.0806964f,0.480955f,0.0900281f}, +{-0.0899679f,0.47854f,0.0900281f},{-0.0806965f,0.480955f,0.0918925f},{-0.089968f,0.47854f,0.0918925f}, +{-0.0991622f,0.475866f,0.0900281f},{-0.0991623f,0.475866f,0.0918925f},{-0.108274f,0.472933f,0.0900281f}, +{-0.117298f,0.469745f,0.0900281f},{-0.108274f,0.472933f,0.0918925f},{-0.117298f,0.469745f,0.0918925f}, +{-0.126228f,0.466302f,0.0900281f},{-0.126228f,0.466302f,0.0918925f},{-0.135059f,0.462608f,0.0900281f}, +{-0.143786f,0.458664f,0.0900281f},{-0.135059f,0.462608f,0.0918925f},{-0.143787f,0.458664f,0.0918925f}, +{-0.152404f,0.454472f,0.0900281f},{-0.152404f,0.454472f,0.0918925f},{-0.160906f,0.450034f,0.0900281f}, +{-0.169288f,0.445352f,0.0900281f},{-0.160907f,0.450034f,0.0918925f},{-0.169288f,0.445352f,0.0918925f}, +{0.169776f,0.427553f,0.0918925f},{0.18196f,0.448656f,0.0900281f},{0.18196f,0.448656f,0.0918925f}, +{0.169776f,0.427553f,0.0900281f},{0.0785294f,0.400468f,0.0900281f},{0.0828396f,0.403757f,0.0900281f}, +{0.0828395f,0.403757f,0.0918925f},{0.0743574f,0.396993f,0.0900281f},{0.074357f,0.396993f,0.0918925f}, +{0.0703325f,0.393337f,0.0900281f},{0.0872815f,0.406855f,0.0918925f},{0.0785292f,0.400468f,0.0918925f}, +{0.0872816f,0.406855f,0.0900281f},{0.0918488f,0.409759f,0.0918925f},{0.091849f,0.409759f,0.0900281f}, +{0.0965352f,0.412465f,0.0900281f},{0.0965352f,0.412465f,0.0918925f},{0.101334f,0.41497f,0.0918925f}, +{0.101334f,0.41497f,0.0900281f},{0.106239f,0.417269f,0.0900281f},{0.111243f,0.419359f,0.0918925f}, +{0.106239f,0.417269f,0.0918925f},{0.111243f,0.419359f,0.0900281f},{0.116342f,0.421236f,0.0900281f}, +{0.116341f,0.421236f,0.0918925f},{0.132038f,0.425533f,0.0918925f},{0.126754f,0.424327f,0.0900281f}, +{0.132038f,0.425533f,0.0900281f},{0.121519f,0.422894f,0.0918925f},{0.121519f,0.422894f,0.0900281f}, +{0.126754f,0.424327f,0.0918925f},{0.137363f,0.426511f,0.0918925f},{0.142723f,0.427261f,0.0918925f}, +{0.137364f,0.426511f,0.0900281f},{0.142723f,0.427261f,0.0900281f},{0.14811f,0.427781f,0.0900281f}, +{0.153516f,0.428071f,0.0900281f},{0.153516f,0.428071f,0.0918925f},{0.14811f,0.427781f,0.0918925f}, +{0.158934f,0.428131f,0.0900281f},{0.158934f,0.428131f,0.0918925f},{0.164357f,0.427958f,0.0900281f}, +{0.164356f,0.427958f,0.0918925f},{0.0664729f,0.389518f,0.0900281f},{0.0703321f,0.393337f,0.0918925f}, +{0.0664728f,0.389518f,0.0918925f},{0.0627861f,0.385543f,0.0900281f},{0.0627861f,0.385543f,0.0918925f}, +{0.0592762f,0.381418f,0.0900281f},{0.0559475f,0.37715f,0.0900281f},{0.0592761f,0.381418f,0.0918925f}, +{0.0559474f,0.37715f,0.0918925f},{0.0528044f,0.372745f,0.0900281f},{0.0528044f,0.372745f,0.0918925f}, +{0.0498513f,0.368209f,0.0900281f},{0.0470924f,0.363547f,0.0900281f},{0.0498511f,0.368209f,0.0918925f}, +{0.0470923f,0.363547f,0.0918925f},{0.0445321f,0.358766f,0.0900281f},{0.0445321f,0.358766f,0.0918925f}, +{0.042175f,0.353872f,0.0900281f},{0.0400276f,0.348877f,0.0900281f},{0.0421746f,0.353871f,0.0918925f}, +{0.0400276f,0.348877f,0.0918925f},{0.0380996f,0.343803f,0.0900281f},{0.0380996f,0.343803f,0.0918925f}, +{0.0363926f,0.338659f,0.0900281f},{0.0349082f,0.333452f,0.0900281f},{0.0363926f,0.338659f,0.0918925f}, +{0.0349082f,0.333452f,0.0918925f},{0.033648f,0.328189f,0.0900281f},{0.0336479f,0.328189f,0.0918925f}, +{0.0326134f,0.322877f,0.0900281f},{0.031806f,0.317524f,0.0900281f},{0.0326134f,0.322877f,0.0918925f}, +{0.031806f,0.317524f,0.0918925f},{0.0312275f,0.312137f,0.0900281f},{0.0312274f,0.312136f,0.0918925f}, +{0.0308792f,0.306722f,0.0900281f},{0.0307628f,0.301289f,0.0900281f},{0.0308792f,0.306722f,0.0918925f}, +{0.0307628f,0.301289f,0.0918925f},{3.36153e-016f,0.270526f,0.0918925f},{4.05702e-016f,0.270526f,0.0900281f}, +{0.00166887f,0.270571f,0.0900281f},{0.0033296f,0.270707f,0.0900281f},{0.00166875f,0.270571f,0.0918925f}, +{0.00497861f,0.270931f,0.0900281f},{0.00332938f,0.270706f,0.0918925f},{0.00497832f,0.270931f,0.0918925f}, +{0.00661229f,0.271245f,0.0900281f},{0.00822706f,0.271646f,0.0900281f},{0.00661197f,0.271245f,0.0918925f}, +{0.00981931f,0.272135f,0.0900281f},{0.00822672f,0.271646f,0.0918925f},{0.009819f,0.272135f,0.0918925f}, +{0.0113858f,0.27271f,0.0900281f},{0.0129196f,0.27337f,0.0900281f},{0.0113852f,0.27271f,0.0918925f}, +{0.0144128f,0.274111f,0.0900281f},{0.0129192f,0.27337f,0.0918925f},{0.0144127f,0.274111f,0.0918925f}, +{0.0158618f,0.27493f,0.0900281f},{0.0172635f,0.275826f,0.0900281f},{0.0158617f,0.27493f,0.0918925f}, +{0.0186148f,0.276797f,0.0900281f},{0.0172633f,0.275826f,0.0918925f},{0.0186146f,0.276797f,0.0918925f}, +{0.0199127f,0.27784f,0.0900281f},{0.0211544f,0.278954f,0.0900281f},{0.0199124f,0.27784f,0.0918925f}, +{0.0223352f,0.280135f,0.0900281f},{0.0211538f,0.278953f,0.0918925f},{0.0223347f,0.280134f,0.0918925f}, +{0.0234487f,0.281376f,0.0900281f},{0.0244917f,0.282674f,0.0900281f},{0.0234485f,0.281376f,0.0918925f}, +{0.0254622f,0.284025f,0.0900281f},{0.0244916f,0.282674f,0.0918925f},{0.0254621f,0.284025f,0.0918925f}, +{0.0263582f,0.285427f,0.0900281f},{0.0271776f,0.286876f,0.0900281f},{0.0263581f,0.285427f,0.0918925f}, +{0.0279185f,0.288369f,0.0900281f},{0.0271775f,0.286876f,0.0918925f},{0.0279183f,0.288369f,0.0918925f}, +{0.0285784f,0.289903f,0.0900281f},{0.0291536f,0.29147f,0.0900281f},{0.0285781f,0.289903f,0.0918925f}, +{0.0296423f,0.293062f,0.0900281f},{0.0291535f,0.291469f,0.0918925f},{0.0296423f,0.293061f,0.0918925f}, +{0.0300438f,0.294677f,0.0900281f},{0.0303573f,0.29631f,0.0900281f},{0.0300437f,0.294676f,0.0918925f}, +{0.0305821f,0.297959f,0.0900281f},{0.0303572f,0.29631f,0.0918925f},{0.030582f,0.297959f,0.0918925f}, +{0.0307175f,0.29962f,0.0900281f},{0.0307174f,0.29962f,0.0918925f},{-0.00166887f,0.270571f,0.0918925f}, +{-0.00166875f,0.270571f,0.0900281f},{-0.0033296f,0.270707f,0.0918925f},{-0.00497861f,0.270931f,0.0918925f}, +{-0.00332938f,0.270706f,0.0900281f},{-0.00661229f,0.271245f,0.0918925f},{-0.00497832f,0.270931f,0.0900281f}, +{-0.00661197f,0.271245f,0.0900281f},{-0.00822706f,0.271646f,0.0918925f},{-0.00981931f,0.272135f,0.0918925f}, +{-0.00822672f,0.271646f,0.0900281f},{-0.0113858f,0.27271f,0.0918925f},{-0.009819f,0.272135f,0.0900281f}, +{-0.0113852f,0.27271f,0.0900281f},{-0.0129196f,0.27337f,0.0918925f},{-0.0144128f,0.274111f,0.0918925f}, +{-0.0129192f,0.27337f,0.0900281f},{-0.0158618f,0.27493f,0.0918925f},{-0.0144127f,0.274111f,0.0900281f}, +{-0.0158617f,0.27493f,0.0900281f},{-0.0172635f,0.275826f,0.0918925f},{-0.0186148f,0.276797f,0.0918925f}, +{-0.0172633f,0.275826f,0.0900281f},{-0.0199127f,0.27784f,0.0918925f},{-0.0186146f,0.276797f,0.0900281f}, +{-0.0199124f,0.27784f,0.0900281f},{-0.0211544f,0.278954f,0.0918925f},{-0.0223352f,0.280135f,0.0918925f}, +{-0.0211538f,0.278953f,0.0900281f},{-0.0234487f,0.281376f,0.0918925f},{-0.0223347f,0.280134f,0.0900281f}, +{-0.0234485f,0.281376f,0.0900281f},{-0.0244917f,0.282674f,0.0918925f},{-0.0254622f,0.284025f,0.0918925f}, +{-0.0244916f,0.282674f,0.0900281f},{-0.0263582f,0.285427f,0.0918925f},{-0.0254621f,0.284025f,0.0900281f}, +{-0.0263581f,0.285427f,0.0900281f},{-0.0271776f,0.286876f,0.0918925f},{-0.0279185f,0.288369f,0.0918925f}, +{-0.0271775f,0.286876f,0.0900281f},{-0.0285784f,0.289903f,0.0918925f},{-0.0279183f,0.288369f,0.0900281f}, +{-0.0285781f,0.289903f,0.0900281f},{-0.0291536f,0.29147f,0.0918925f},{-0.0296423f,0.293062f,0.0918925f}, +{-0.0291535f,0.291469f,0.0900281f},{-0.0300438f,0.294677f,0.0918925f},{-0.0296423f,0.293061f,0.0900281f}, +{-0.0300437f,0.294676f,0.0900281f},{-0.0303573f,0.29631f,0.0918925f},{-0.0305821f,0.297959f,0.0918925f}, +{-0.0303572f,0.29631f,0.0900281f},{-0.0307175f,0.29962f,0.0918925f},{-0.030582f,0.297959f,0.0900281f}, +{-0.0307174f,0.29962f,0.0900281f},{-0.0307628f,0.301289f,0.0918925f},{-0.0307628f,0.301289f,0.0900281f}, +{-0.0664728f,0.389518f,0.0900281f},{-0.0627861f,0.385543f,0.0900281f},{-0.0627861f,0.385543f,0.0918925f}, +{-0.0703321f,0.393337f,0.0900281f},{-0.0703325f,0.393337f,0.0918925f},{-0.074357f,0.396993f,0.0900281f}, +{-0.0592762f,0.381418f,0.0918925f},{-0.0664729f,0.389518f,0.0918925f},{-0.0592761f,0.381418f,0.0900281f}, +{-0.0559475f,0.37715f,0.0918925f},{-0.0559474f,0.37715f,0.0900281f},{-0.0528044f,0.372745f,0.0900281f}, +{-0.0528044f,0.372745f,0.0918925f},{-0.0498513f,0.368209f,0.0918925f},{-0.0498511f,0.368209f,0.0900281f}, +{-0.0470923f,0.363547f,0.0900281f},{-0.0445321f,0.358766f,0.0918925f},{-0.0470924f,0.363547f,0.0918925f}, +{-0.0445321f,0.358766f,0.0900281f},{-0.0421746f,0.353871f,0.0900281f},{-0.042175f,0.353872f,0.0918925f}, +{-0.0363926f,0.338659f,0.0918925f},{-0.0380996f,0.343803f,0.0900281f},{-0.0363926f,0.338659f,0.0900281f}, +{-0.0400276f,0.348877f,0.0918925f},{-0.0400276f,0.348877f,0.0900281f},{-0.0380996f,0.343803f,0.0918925f}, +{-0.0349082f,0.333452f,0.0918925f},{-0.033648f,0.328189f,0.0918925f},{-0.0349082f,0.333452f,0.0900281f}, +{-0.0336479f,0.328189f,0.0900281f},{-0.0326134f,0.322877f,0.0900281f},{-0.031806f,0.317524f,0.0900281f}, +{-0.031806f,0.317524f,0.0918925f},{-0.0326134f,0.322877f,0.0918925f},{-0.0312274f,0.312136f,0.0900281f}, +{-0.0312275f,0.312137f,0.0918925f},{-0.0308792f,0.306722f,0.0900281f},{-0.0308792f,0.306722f,0.0918925f}, +{-0.0785292f,0.400468f,0.0900281f},{-0.0743574f,0.396993f,0.0918925f},{-0.0785294f,0.400468f,0.0918925f}, +{-0.0828395f,0.403757f,0.0900281f},{-0.0828396f,0.403757f,0.0918925f},{-0.0872815f,0.406855f,0.0900281f}, +{-0.0918488f,0.409759f,0.0900281f},{-0.0872816f,0.406855f,0.0918925f},{-0.091849f,0.409759f,0.0918925f}, +{-0.0965352f,0.412465f,0.0900281f},{-0.0965352f,0.412465f,0.0918925f},{-0.101334f,0.41497f,0.0900281f}, +{-0.106239f,0.417269f,0.0900281f},{-0.101334f,0.41497f,0.0918925f},{-0.106239f,0.417269f,0.0918925f}, +{-0.111243f,0.419359f,0.0900281f},{-0.111243f,0.419359f,0.0918925f},{-0.116341f,0.421236f,0.0900281f}, +{-0.121519f,0.422894f,0.0900281f},{-0.116342f,0.421236f,0.0918925f},{-0.121519f,0.422894f,0.0918925f}, +{-0.126754f,0.424327f,0.0900281f},{-0.126754f,0.424327f,0.0918925f},{-0.132038f,0.425533f,0.0900281f}, +{-0.137363f,0.426511f,0.0900281f},{-0.132038f,0.425533f,0.0918925f},{-0.137364f,0.426511f,0.0918925f}, +{-0.142723f,0.427261f,0.0900281f},{-0.142723f,0.427261f,0.0918925f},{-0.14811f,0.427781f,0.0900281f}, +{-0.153516f,0.428071f,0.0900281f},{-0.14811f,0.427781f,0.0918925f},{-0.153516f,0.428071f,0.0918925f}, +{-0.158934f,0.428131f,0.0900281f},{-0.158934f,0.428131f,0.0918925f},{-0.164356f,0.427958f,0.0900281f}, +{-0.169776f,0.427553f,0.0900281f},{-0.164357f,0.427958f,0.0918925f},{-0.169776f,0.427553f,0.0918925f}, +{-0.18196f,0.448656f,0.0918925f},{-0.18196f,0.448656f,0.0900281f},{-0.0049028f,0.5f,0.0918925f}, +{0.00490289f,0.5f,0.0918925f},{-0.00490289f,0.5f,0.0900281f},{-0.0147057f,0.499724f,0.0900281f}, +{-0.0147055f,0.499724f,0.0918925f},{-0.0244996f,0.499171f,0.0900281f},{-0.0244996f,0.499171f,0.0918925f}, +{-0.0342788f,0.498342f,0.0918925f},{-0.034279f,0.498342f,0.0900281f},{-0.0440377f,0.497236f,0.0900281f}, +{-0.0440376f,0.497236f,0.0918925f},{-0.05377f,0.495854f,0.0900281f},{-0.05377f,0.495854f,0.0918925f}, +{-0.0634697f,0.494196f,0.0918925f},{-0.0634706f,0.494196f,0.0900281f},{-0.0731194f,0.492264f,0.0900281f}, +{-0.0731193f,0.492264f,0.0918925f},{-0.0826996f,0.490062f,0.0900281f},{-0.0826996f,0.490062f,0.0918925f}, +{-0.0922052f,0.487593f,0.0918925f},{-0.0922054f,0.487593f,0.0900281f},{-0.101631f,0.484859f,0.0900281f}, +{-0.101631f,0.484859f,0.0918925f},{-0.110971f,0.481861f,0.0900281f},{-0.110971f,0.481861f,0.0918925f}, +{-0.120221f,0.478603f,0.0918925f},{-0.120221f,0.478602f,0.0900281f},{-0.129374f,0.475085f,0.0900281f}, +{-0.129374f,0.475085f,0.0918925f},{-0.138425f,0.47131f,0.0900281f},{-0.138425f,0.47131f,0.0918925f}, +{-0.147368f,0.46728f,0.0918925f},{-0.147369f,0.46728f,0.0900281f},{-0.156199f,0.462998f,0.0900281f}, +{-0.156199f,0.462998f,0.0918925f},{-0.164912f,0.458465f,0.0900281f},{-0.164912f,0.458465f,0.0918925f}, +{-0.173501f,0.453684f,0.0918925f},{-0.173501f,0.453684f,0.0900281f},{0.0049028f,0.5f,0.0900281f}, +{0.0147055f,0.499724f,0.0900281f},{0.0147057f,0.499724f,0.0918925f},{0.0244996f,0.499171f,0.0918925f}, +{0.0244996f,0.499171f,0.0900281f},{0.034279f,0.498342f,0.0918925f},{0.0342788f,0.498342f,0.0900281f}, +{0.0440376f,0.497236f,0.0900281f},{0.0440377f,0.497236f,0.0918925f},{0.05377f,0.495854f,0.0918925f}, +{0.05377f,0.495854f,0.0900281f},{0.0634706f,0.494196f,0.0918925f},{0.0634697f,0.494196f,0.0900281f}, +{0.0731193f,0.492264f,0.0900281f},{0.0731194f,0.492264f,0.0918925f},{0.0826996f,0.490062f,0.0918925f}, +{0.0826996f,0.490062f,0.0900281f},{0.0922054f,0.487593f,0.0918925f},{0.0922052f,0.487593f,0.0900281f}, +{0.101631f,0.484859f,0.0900281f},{0.101631f,0.484859f,0.0918925f},{0.110971f,0.481861f,0.0918925f}, +{0.110971f,0.481861f,0.0900281f},{0.120221f,0.478602f,0.0918925f},{0.120221f,0.478603f,0.0900281f}, +{0.129374f,0.475085f,0.0900281f},{0.129374f,0.475085f,0.0918925f},{0.138425f,0.47131f,0.0918925f}, +{0.138425f,0.47131f,0.0900281f},{0.147369f,0.46728f,0.0918925f},{0.147368f,0.46728f,0.0900281f}, +{0.156199f,0.462998f,0.0900281f},{0.156199f,0.462998f,0.0918925f},{0.164912f,0.458465f,0.0918925f}, +{0.164912f,0.458465f,0.0900281f},{0.173501f,0.453684f,0.0918925f},{0.173501f,0.453684f,0.0900281f}, +{-0.0200317f,0.295886f,0.0918925f},{-0.0036392f,0.280259f,0.0918925f},{-0.00474168f,0.280781f,0.0918925f}, +{-0.0152687f,0.28931f,0.0918925f},{-0.0183517f,0.29453f,0.0918925f},{-0.0057053f,0.28153f,0.0918925f}, +{-0.0130697f,0.291507f,0.0918925f},{-0.0151095f,0.289835f,0.0918925f},{-0.0173478f,0.294119f,0.0918925f}, +{-0.0109706f,0.291087f,0.0918925f},{-0.0105473f,0.290739f,0.0918925f},{-0.0192577f,0.295126f,0.0918925f}, +{-0.0206442f,0.296782f,0.0918925f},{-0.0210723f,0.297778f,0.0918925f},{-0.0101998f,0.290316f,0.0918925f}, +{-0.0140791f,0.291091f,0.0918925f},{-0.0151984f,0.293911f,0.0918925f},{-0.0145033f,0.290742f,0.0918925f}, +{0.0105451f,0.315791f,0.0918925f},{0.0101973f,0.315367f,0.0918925f},{0.0109693f,0.316139f,0.0918925f}, +{0.00977971f,0.314358f,0.0918925f},{0.00993885f,0.314883f,0.0918925f},{0.0151067f,0.314881f,0.0918925f}, +{0.0119787f,0.316555f,0.0918925f},{0.0114536f,0.316397f,0.0918925f},{0.0125242f,0.316609f,0.0918925f}, +{0.013595f,0.316394f,0.0918925f},{0.0140778f,0.316135f,0.0918925f},{0.0145011f,0.315788f,0.0918925f}, +{0.0148486f,0.315364f,0.0918925f},{0.015266f,0.314357f,0.0918925f},{-0.0148511f,0.290318f,0.0918925f}, +{-0.0162833f,0.29391f,0.0918925f},{-0.0119779f,0.291506f,0.0918925f},{-0.0125242f,0.291561f,0.0918925f}, +{-0.0114534f,0.291346f,0.0918925f},{-0.0135948f,0.291349f,0.0918925f},{-0.00994166f,0.289833f,0.0918925f}, +{0.0130705f,0.316555f,0.0918925f},{-0.00978241f,0.289309f,0.0918925f},{-0.00474296f,0.280782f,0.0900281f}, +{-0.0210725f,0.297777f,0.0900281f},{-0.020644f,0.296781f,0.0900281f},{-0.0105451f,0.290742f,0.0900281f}, +{-0.00364027f,0.280259f,0.0900281f},{-0.00993885f,0.289835f,0.0900281f},{-0.0200312f,0.295886f,0.0900281f}, +{-0.0192574f,0.295126f,0.0900281f},{-0.0162822f,0.29391f,0.0900281f},{-0.0145011f,0.290739f,0.0900281f}, +{-0.0148486f,0.290316f,0.0900281f},{-0.0125242f,0.291561f,0.0900281f},{-0.00977971f,0.28931f,0.0900281f}, +{-0.0109693f,0.291091f,0.0900281f},{-0.0101973f,0.290318f,0.0900281f},{-0.0114536f,0.291349f,0.0900281f}, +{0.0145033f,0.315791f,0.0900281f},{0.0140791f,0.316139f,0.0900281f},{0.00978241f,0.314357f,0.0900281f}, +{0.00994166f,0.314881f,0.0900281f},{-0.0183513f,0.294529f,0.0900281f},{-0.0173468f,0.294119f,0.0900281f}, +{-0.0151067f,0.289833f,0.0900281f},{-0.015266f,0.289309f,0.0900281f},{-0.0140778f,0.291087f,0.0900281f}, +{-0.0151976f,0.293911f,0.0900281f},{-0.013595f,0.291346f,0.0900281f},{-0.00570553f,0.28153f,0.0900281f}, +{0.0119779f,0.316555f,0.0900281f},{0.0101998f,0.315364f,0.0900281f},{0.0125242f,0.316609f,0.0900281f}, +{0.0130697f,0.316555f,0.0900281f},{0.0135948f,0.316397f,0.0900281f},{0.0148511f,0.315367f,0.0900281f}, +{0.0151095f,0.314883f,0.0900281f},{0.0109706f,0.316135f,0.0900281f},{0.0152687f,0.314358f,0.0900281f}, +{0.0114534f,0.316394f,0.0900281f},{0.0105473f,0.315788f,0.0900281f},{-0.0119787f,0.291507f,0.0900281f}, +{-0.0130705f,0.291506f,0.0900281f},{0.0125242f,-0.285968f,0.0900281f},{0.0130723f,-0.286022f,0.0918925f}, +{0.0125242f,-0.285968f,0.0918925f},{0.011454f,-0.286181f,0.0918925f},{0.011454f,-0.286181f,0.0900281f}, +{0.0119761f,-0.286022f,0.0918925f},{0.0119761f,-0.286022f,0.0900281f},{0.0109726f,-0.286438f,0.0900281f}, +{0.0105467f,-0.286787f,0.0900281f},{0.0105467f,-0.286787f,0.0918925f},{0.0101975f,-0.287213f,0.0900281f}, +{0.0101975f,-0.287213f,0.0918925f},{0.0109726f,-0.286438f,0.0918925f},{0.00972758f,-0.288764f,0.0900281f}, +{0.00978182f,-0.288216f,0.0900281f},{0.00978182f,-0.288216f,0.0918925f},{0.00994047f,-0.287694f,0.0918925f}, +{0.00994047f,-0.287694f,0.0900281f},{0.00972758f,-0.288764f,0.0918925f},{0.0130723f,-0.286022f,0.0900281f}, +{0.0135944f,-0.286181f,0.0918925f},{0.0135944f,-0.286181f,0.0900281f},{0.0140758f,-0.286438f,0.0900281f}, +{0.0140758f,-0.286438f,0.0918925f},{0.0145017f,-0.286787f,0.0900281f},{0.0145017f,-0.286787f,0.0918925f}, +{0.0148509f,-0.287213f,0.0918925f},{0.0148509f,-0.287213f,0.0900281f},{0.0151079f,-0.287694f,0.0900281f}, +{0.0151079f,-0.287694f,0.0918925f},{0.0152666f,-0.288216f,0.0900281f},{0.0152666f,-0.288216f,0.0918925f}, +{0.0153208f,-0.288764f,0.0918925f},{0.0153208f,-0.288764f,0.0900281f},{-0.0125242f,-0.311016f,0.0900281f}, +{-0.0119761f,-0.31107f,0.0918925f},{-0.0125242f,-0.311016f,0.0918925f},{-0.0135944f,-0.311229f,0.0918925f}, +{-0.0135944f,-0.311229f,0.0900281f},{-0.0130723f,-0.31107f,0.0918925f},{-0.0130723f,-0.31107f,0.0900281f}, +{-0.0140758f,-0.311486f,0.0900281f},{-0.0145017f,-0.311835f,0.0900281f},{-0.0145017f,-0.311835f,0.0918925f}, +{-0.0148509f,-0.312261f,0.0900281f},{-0.0148509f,-0.312261f,0.0918925f},{-0.0140758f,-0.311486f,0.0918925f}, +{-0.0153208f,-0.313813f,0.0900281f},{-0.0152666f,-0.313265f,0.0900281f},{-0.0152666f,-0.313265f,0.0918925f}, +{-0.0151079f,-0.312743f,0.0918925f},{-0.0151079f,-0.312743f,0.0900281f},{-0.0153208f,-0.313813f,0.0918925f}, +{-0.0119761f,-0.31107f,0.0900281f},{-0.011454f,-0.311229f,0.0918925f},{-0.011454f,-0.311229f,0.0900281f}, +{-0.0109726f,-0.311486f,0.0900281f},{-0.0109726f,-0.311486f,0.0918925f},{-0.0105467f,-0.311835f,0.0900281f}, +{-0.0105467f,-0.311835f,0.0918925f},{-0.0101975f,-0.312261f,0.0918925f},{-0.0101975f,-0.312261f,0.0900281f}, +{-0.00994047f,-0.312743f,0.0900281f},{-0.00994047f,-0.312743f,0.0918925f},{-0.00978182f,-0.313265f,0.0900281f}, +{-0.00978182f,-0.313265f,0.0918925f},{-0.00972758f,-0.313813f,0.0918925f},{-0.00972758f,-0.313813f,0.0900281f}, +{0.0073455f,-0.284736f,0.0900281f},{0.00738926f,-0.285954f,0.0918925f},{0.00734538f,-0.284736f,0.0918925f}, +{0.00703877f,-0.283556f,0.0900281f},{0.0070384f,-0.283555f,0.0918925f},{0.00648281f,-0.28247f,0.0900281f}, +{0.00648282f,-0.28247f,0.0918925f},{0.00738915f,-0.285956f,0.0900281f},{0.00716427f,-0.287154f,0.0918925f}, +{0.00716427f,-0.287154f,0.0900281f},{-0.00856857f,-0.309858f,0.0918925f},{-0.0078732f,-0.310706f,0.0918925f}, +{-0.00856991f,-0.309857f,0.0900281f},{-0.00787361f,-0.310705f,0.0900281f},{-0.0073566f,-0.311673f,0.0918925f}, +{-0.00703838f,-0.312722f,0.0918925f},{-0.00735691f,-0.311672f,0.0900281f},{-0.00693097f,-0.313813f,0.0918925f}, +{-0.00703853f,-0.312721f,0.0900281f},{-0.00693097f,-0.313813f,0.0900281f},{-0.00941743f,-0.309162f,0.0900281f}, +{-0.0103841f,-0.308645f,0.0900281f},{-0.00941663f,-0.309162f,0.0918925f},{-0.0114331f,-0.308327f,0.0900281f}, +{-0.0103834f,-0.308645f,0.0918925f},{-0.0114326f,-0.308327f,0.0918925f},{-0.0125242f,-0.30822f,0.0900281f}, +{-0.0125242f,-0.30822f,0.0918925f},{0.065917f,-0.401959f,0.0918925f},{0.0617984f,-0.398048f,0.0918925f}, +{0.0659174f,-0.40196f,0.0900281f},{0.07019f,-0.405692f,0.0900281f},{0.0701898f,-0.405691f,0.0918925f}, +{0.0746077f,-0.409237f,0.0900281f},{0.0746076f,-0.409237f,0.0918925f},{0.0791643f,-0.412592f,0.0918925f}, +{0.0791644f,-0.412592f,0.0900281f},{0.0838538f,-0.415754f,0.0900281f},{0.0838537f,-0.415754f,0.0918925f}, +{0.0886696f,-0.418717f,0.0900281f},{0.0886696f,-0.418717f,0.0918925f},{0.0936056f,-0.421479f,0.0918925f}, +{0.0936057f,-0.421479f,0.0900281f},{0.0986557f,-0.424035f,0.0900281f},{0.0986556f,-0.424035f,0.0918925f}, +{0.103813f,-0.426382f,0.0900281f},{0.103813f,-0.426382f,0.0918925f},{0.109072f,-0.428515f,0.0918925f}, +{0.109073f,-0.428515f,0.0900281f},{0.11442f,-0.430428f,0.0900281f},{0.11442f,-0.430428f,0.0918925f}, +{0.119834f,-0.432114f,0.0900281f},{0.119834f,-0.432114f,0.0918925f},{0.125306f,-0.433572f,0.0918925f}, +{0.125307f,-0.433572f,0.0900281f},{0.130829f,-0.4348f,0.0900281f},{0.130829f,-0.4348f,0.0918925f}, +{0.136396f,-0.435797f,0.0900281f},{0.136396f,-0.435797f,0.0918925f},{0.141999f,-0.436561f,0.0918925f}, +{0.141999f,-0.436561f,0.0900281f},{0.147631f,-0.437093f,0.0900281f},{0.147631f,-0.437093f,0.0918925f}, +{0.153284f,-0.437391f,0.0900281f},{0.153284f,-0.437391f,0.0918925f},{0.158952f,-0.437453f,0.0918925f}, +{0.158952f,-0.437453f,0.0900281f},{0.164627f,-0.437279f,0.0900281f},{0.164627f,-0.437279f,0.0918925f}, +{0.0617987f,-0.398048f,0.0900281f},{0.0578515f,-0.393973f,0.0900281f},{0.0578514f,-0.393973f,0.0918925f}, +{0.054083f,-0.389744f,0.0918925f},{0.0540831f,-0.389744f,0.0900281f},{0.0504973f,-0.385366f,0.0918925f}, +{0.0504974f,-0.385366f,0.0900281f},{0.0470986f,-0.380846f,0.0900281f},{0.0470985f,-0.380846f,0.0918925f}, +{0.0438908f,-0.376189f,0.0918925f},{0.0438908f,-0.376189f,0.0900281f},{0.0408784f,-0.371402f,0.0918925f}, +{0.0408785f,-0.371402f,0.0900281f},{0.0380656f,-0.36649f,0.0900281f},{0.0380655f,-0.36649f,0.0918925f}, +{0.0354565f,-0.36146f,0.0918925f},{0.0354565f,-0.36146f,0.0900281f},{0.0330551f,-0.356317f,0.0918925f}, +{0.0330554f,-0.356318f,0.0900281f},{0.0308688f,-0.351076f,0.0900281f},{0.0308688f,-0.351076f,0.0918925f}, +{0.0289059f,-0.345756f,0.0918925f},{0.0289059f,-0.345756f,0.0900281f},{0.0271683f,-0.340366f,0.0918925f}, +{0.0271684f,-0.340366f,0.0900281f},{0.0256577f,-0.334914f,0.0900281f},{0.0256577f,-0.334914f,0.0918925f}, +{0.0243753f,-0.329406f,0.0918925f},{0.0243754f,-0.329406f,0.0900281f},{0.0233228f,-0.32385f,0.0918925f}, +{0.0233228f,-0.32385f,0.0900281f},{0.0225016f,-0.318253f,0.0900281f},{0.0225016f,-0.318253f,0.0918925f}, +{0.0219132f,-0.312622f,0.0918925f},{0.0219132f,-0.312623f,0.0900281f},{0.0215591f,-0.306965f,0.0918925f}, +{0.0215591f,-0.306965f,0.0900281f},{0.0214407f,-0.301289f,0.0918925f},{0.0214407f,-0.301289f,0.0900281f}, +{0.0214056f,-0.300061f,0.0918925f},{0.0214056f,-0.300061f,0.0900281f},{0.0213002f,-0.298838f,0.0900281f}, +{0.0213002f,-0.298838f,0.0918925f},{0.00857005f,-0.29272f,0.0900281f},{0.00933952f,-0.293362f,0.0900281f}, +{0.00856812f,-0.292718f,0.0918925f},{0.0102104f,-0.293856f,0.0918925f},{0.00933867f,-0.293362f,0.0918925f}, +{0.010212f,-0.293857f,0.0900281f},{0.0111572f,-0.294188f,0.0918925f},{0.0111588f,-0.294188f,0.0900281f}, +{0.0121484f,-0.294345f,0.0918925f},{0.0131504f,-0.294322f,0.0918925f},{0.0121494f,-0.294345f,0.0900281f}, +{0.0141339f,-0.294121f,0.0900281f},{0.0131516f,-0.294322f,0.0900281f},{0.0141339f,-0.294121f,0.0918925f}, +{0.00792586f,-0.291949f,0.0918925f},{0.00792654f,-0.29195f,0.0900281f},{0.00743177f,-0.291078f,0.0900281f}, +{0.00710074f,-0.290131f,0.0900281f},{0.00743116f,-0.291076f,0.0918925f},{0.00710007f,-0.290129f,0.0918925f}, +{0.00694354f,-0.28914f,0.0900281f},{0.00694356f,-0.289139f,0.0918925f},{0.00696625f,-0.288138f,0.0900281f}, +{0.00696632f,-0.288136f,0.0918925f},{-0.0121669f,-0.283634f,0.0900281f},{-0.0102959f,-0.282482f,0.0900281f}, +{-0.0102961f,-0.282482f,0.0918925f},{-0.012167f,-0.283634f,0.0918925f},{-0.013914f,-0.284976f,0.0900281f}, +{-0.008319f,-0.281528f,0.0918925f},{-0.00831882f,-0.281527f,0.0900281f},{-0.00625128f,-0.280779f,0.0918925f}, +{-0.00625078f,-0.280779f,0.0900281f},{-0.00411456f,-0.280246f,0.0918925f},{-0.00411435f,-0.280246f,0.0900281f}, +{-0.00194003f,-0.279936f,0.0900281f},{-0.0019402f,-0.279936f,0.0918925f},{0.000253827f,-0.279849f,0.0918925f}, +{0.00245022f,-0.279988f,0.0918925f},{0.00025393f,-0.279849f,0.0900281f},{0.00245022f,-0.279988f,0.0900281f}, +{-0.0155106f,-0.286486f,0.0900281f},{-0.0139141f,-0.284976f,0.0918925f},{-0.0155107f,-0.286486f,0.0918925f}, +{-0.016943f,-0.288149f,0.0900281f},{-0.0169431f,-0.28815f,0.0918925f},{-0.0181996f,-0.289954f,0.0900281f}, +{-0.0192663f,-0.29188f,0.0900281f},{-0.0181999f,-0.289954f,0.0918925f},{-0.0192664f,-0.291881f,0.0918925f}, +{-0.0201277f,-0.293901f,0.0900281f},{-0.0201278f,-0.293901f,0.0918925f},{-0.0207778f,-0.295998f,0.0900281f}, +{-0.0212106f,-0.298156f,0.0900281f},{-0.0207778f,-0.295998f,0.0918925f},{-0.0212106f,-0.298156f,0.0918925f}, +{-0.0200545f,-0.303955f,0.0900281f},{-0.0207145f,-0.302604f,0.0918925f},{-0.020054f,-0.303956f,0.0918925f}, +{-0.0191712f,-0.305176f,0.0900281f},{-0.0207149f,-0.302603f,0.0900281f},{-0.0211353f,-0.301156f,0.0918925f}, +{-0.0191712f,-0.305176f,0.0918925f},{-0.0211356f,-0.301155f,0.0900281f},{-0.021302f,-0.29966f,0.0918925f}, +{-0.0213021f,-0.299659f,0.0900281f},{-0.0180928f,-0.306228f,0.0900281f},{-0.018092f,-0.306229f,0.0918925f}, +{-0.0168512f,-0.307079f,0.0918925f},{-0.0168521f,-0.307079f,0.0900281f},{-0.0154797f,-0.307707f,0.0918925f}, +{-0.0154807f,-0.307707f,0.0900281f},{-0.0140259f,-0.30809f,0.0900281f},{-0.014025f,-0.30809f,0.0918925f}, +{-0.00703853f,-0.314904f,0.0918925f},{-0.00856991f,-0.317768f,0.0918925f},{-0.0078732f,-0.31692f,0.0900281f}, +{-0.00787361f,-0.31692f,0.0918925f},{-0.00735691f,-0.315954f,0.0918925f},{-0.0073566f,-0.315953f,0.0900281f}, +{-0.00703838f,-0.314904f,0.0900281f},{-0.0103834f,-0.31898f,0.0900281f},{-0.0103841f,-0.31898f,0.0918925f}, +{-0.0114331f,-0.319299f,0.0918925f},{-0.00856857f,-0.317767f,0.0900281f},{-0.00941743f,-0.318464f,0.0918925f}, +{-0.00941663f,-0.318463f,0.0900281f},{-0.0125242f,-0.319406f,0.0918925f},{-0.0114326f,-0.319298f,0.0900281f}, +{-0.0125242f,-0.319406f,0.0900281f},{-0.017806f,-0.32063f,0.0900281f},{-0.0178073f,-0.32063f,0.0918925f}, +{-0.0193785f,-0.321554f,0.0900281f},{-0.0193787f,-0.321554f,0.0918925f},{-0.0161135f,-0.319955f,0.0918925f}, +{-0.0161128f,-0.319955f,0.0900281f},{-0.0143418f,-0.319544f,0.0900281f},{-0.0143423f,-0.319544f,0.0918925f}, +{-0.0207886f,-0.322701f,0.0900281f},{-0.0220123f,-0.324052f,0.0900281f},{-0.0207888f,-0.322701f,0.0918925f}, +{-0.0220132f,-0.324053f,0.0918925f},{-0.023018f,-0.325573f,0.0900281f},{-0.0230183f,-0.325573f,0.0918925f}, +{-0.02378f,-0.327224f,0.0900281f},{-0.0242851f,-0.328976f,0.0900281f},{-0.0237802f,-0.327224f,0.0918925f}, +{-0.0242851f,-0.328976f,0.0918925f},{-0.0744192f,-0.409092f,0.0918925f},{-0.0744192f,-0.409092f,0.0900281f}, +{-0.0700077f,-0.405539f,0.0900281f},{-0.065746f,-0.401803f,0.0900281f},{-0.0700077f,-0.405539f,0.0918925f}, +{-0.06164f,-0.397891f,0.0900281f},{-0.0657461f,-0.401803f,0.0918925f},{-0.0616401f,-0.397891f,0.0918925f}, +{-0.0576956f,-0.393805f,0.0900281f},{-0.0539185f,-0.389551f,0.0900281f},{-0.0576957f,-0.393805f,0.0918925f}, +{-0.0503158f,-0.385134f,0.0900281f},{-0.0539186f,-0.389551f,0.0918925f},{-0.050316f,-0.385135f,0.0918925f}, +{-0.0469052f,-0.380577f,0.0900281f},{-0.0436939f,-0.375889f,0.0900281f},{-0.0469052f,-0.380577f,0.0918925f}, +{-0.0406851f,-0.371079f,0.0900281f},{-0.0436939f,-0.375889f,0.0918925f},{-0.0406851f,-0.371079f,0.0918925f}, +{-0.0378819f,-0.366152f,0.0900281f},{-0.0352877f,-0.361116f,0.0900281f},{-0.037882f,-0.366152f,0.0918925f}, +{-0.0329054f,-0.355977f,0.0900281f},{-0.0352877f,-0.361116f,0.0918925f},{-0.0329055f,-0.355977f,0.0918925f}, +{-0.0307383f,-0.350742f,0.0900281f},{-0.0287896f,-0.345418f,0.0900281f},{-0.0307384f,-0.350742f,0.0918925f}, +{-0.0270624f,-0.340011f,0.0900281f},{-0.0287897f,-0.345418f,0.0918925f},{-0.0270624f,-0.340011f,0.0918925f}, +{-0.0255598f,-0.334528f,0.0900281f},{-0.0255599f,-0.334528f,0.0918925f},{-0.0789746f,-0.412458f,0.0918925f}, +{-0.0789746f,-0.412458f,0.0900281f},{-0.0836681f,-0.415634f,0.0918925f},{-0.0884938f,-0.418614f,0.0918925f}, +{-0.083668f,-0.415634f,0.0900281f},{-0.0934459f,-0.421394f,0.0918925f},{-0.0884937f,-0.418614f,0.0900281f}, +{-0.0934458f,-0.421394f,0.0900281f},{-0.0985185f,-0.423969f,0.0918925f},{-0.103704f,-0.426335f,0.0918925f}, +{-0.0985183f,-0.423969f,0.0900281f},{-0.108978f,-0.428478f,0.0918925f},{-0.103704f,-0.426334f,0.0900281f}, +{-0.108977f,-0.428478f,0.0900281f},{-0.114326f,-0.430397f,0.0918925f},{-0.119742f,-0.432088f,0.0918925f}, +{-0.114326f,-0.430397f,0.0900281f},{-0.125218f,-0.43355f,0.0918925f},{-0.119742f,-0.432088f,0.0900281f}, +{-0.125218f,-0.43355f,0.0900281f},{-0.130747f,-0.434783f,0.0918925f},{-0.136322f,-0.435785f,0.0918925f}, +{-0.130747f,-0.434783f,0.0900281f},{-0.141936f,-0.436554f,0.0918925f},{-0.136322f,-0.435785f,0.0900281f}, +{-0.141935f,-0.436554f,0.0900281f},{-0.14758f,-0.43709f,0.0918925f},{-0.153248f,-0.43739f,0.0918925f}, +{-0.14758f,-0.43709f,0.0900281f},{-0.158933f,-0.437453f,0.0918925f},{-0.153248f,-0.43739f,0.0900281f}, +{-0.158933f,-0.437453f,0.0900281f},{-0.164627f,-0.437279f,0.0918925f},{-0.164627f,-0.437279f,0.0900281f}, +{-0.169288f,-0.445352f,0.0900281f},{-0.169288f,-0.445352f,0.0918925f},{-0.0239114f,-0.489867f,0.0918925f}, +{-0.0143525f,-0.490408f,0.0918925f},{-0.0143527f,-0.490408f,0.0900281f},{0.00478512f,-0.490679f,0.0900281f}, +{-0.00478519f,-0.490679f,0.0900281f},{-0.00478512f,-0.490679f,0.0918925f},{-0.0239115f,-0.489867f,0.0900281f}, +{-0.0334558f,-0.489056f,0.0918925f},{-0.0334558f,-0.489056f,0.0900281f},{-0.0429801f,-0.487973f,0.0900281f}, +{-0.04298f,-0.487973f,0.0918925f},{-0.0524782f,-0.486621f,0.0918925f},{-0.0524784f,-0.486621f,0.0900281f}, +{-0.0619436f,-0.484998f,0.0900281f},{-0.0619434f,-0.484998f,0.0918925f},{-0.0806965f,-0.480955f,0.0900281f}, +{-0.089968f,-0.47854f,0.0900281f},{-0.0899679f,-0.47854f,0.0918925f},{-0.0713532f,-0.483109f,0.0918925f}, +{-0.0713532f,-0.483109f,0.0900281f},{-0.0806964f,-0.480955f,0.0918925f},{-0.0991622f,-0.475866f,0.0918925f}, +{-0.0991623f,-0.475866f,0.0900281f},{-0.108274f,-0.472933f,0.0900281f},{-0.108274f,-0.472933f,0.0918925f}, +{-0.117298f,-0.469745f,0.0918925f},{-0.117298f,-0.469745f,0.0900281f},{-0.126228f,-0.466302f,0.0918925f}, +{-0.143787f,-0.458664f,0.0900281f},{-0.143786f,-0.458664f,0.0918925f},{-0.135059f,-0.462608f,0.0900281f}, +{-0.135059f,-0.462608f,0.0918925f},{-0.126228f,-0.466302f,0.0900281f},{-0.152404f,-0.454472f,0.0900281f}, +{-0.152404f,-0.454472f,0.0918925f},{-0.160907f,-0.450034f,0.0900281f},{-0.160906f,-0.450034f,0.0918925f}, +{0.00478519f,-0.490679f,0.0918925f},{0.0143525f,-0.490408f,0.0900281f},{0.0143527f,-0.490408f,0.0918925f}, +{0.0239114f,-0.489867f,0.0900281f},{0.0334558f,-0.489056f,0.0900281f},{0.0239115f,-0.489867f,0.0918925f}, +{0.0334558f,-0.489056f,0.0918925f},{0.04298f,-0.487973f,0.0900281f},{0.0429801f,-0.487973f,0.0918925f}, +{0.0524782f,-0.486621f,0.0900281f},{0.0619434f,-0.484998f,0.0900281f},{0.0524784f,-0.486621f,0.0918925f}, +{0.0619436f,-0.484998f,0.0918925f},{0.0713532f,-0.483109f,0.0900281f},{0.0713532f,-0.483109f,0.0918925f}, +{0.0806964f,-0.480955f,0.0900281f},{0.0899679f,-0.47854f,0.0900281f},{0.0806965f,-0.480955f,0.0918925f}, +{0.089968f,-0.47854f,0.0918925f},{0.0991622f,-0.475866f,0.0900281f},{0.0991623f,-0.475866f,0.0918925f}, +{0.108274f,-0.472933f,0.0900281f},{0.117298f,-0.469745f,0.0900281f},{0.108274f,-0.472933f,0.0918925f}, +{0.117298f,-0.469745f,0.0918925f},{0.126228f,-0.466302f,0.0900281f},{0.126228f,-0.466302f,0.0918925f}, +{0.135059f,-0.462608f,0.0900281f},{0.143786f,-0.458664f,0.0900281f},{0.135059f,-0.462608f,0.0918925f}, +{0.143787f,-0.458664f,0.0918925f},{0.152404f,-0.454472f,0.0900281f},{0.152404f,-0.454472f,0.0918925f}, +{0.160906f,-0.450034f,0.0900281f},{0.169288f,-0.445352f,0.0900281f},{0.160907f,-0.450034f,0.0918925f}, +{0.169288f,-0.445352f,0.0918925f},{-0.169776f,-0.427553f,0.0918925f},{-0.18196f,-0.448656f,0.0900281f}, +{-0.18196f,-0.448656f,0.0918925f},{-0.169776f,-0.427553f,0.0900281f},{-0.0785294f,-0.400468f,0.0900281f}, +{-0.0828396f,-0.403757f,0.0900281f},{-0.0828395f,-0.403757f,0.0918925f},{-0.0743574f,-0.396993f,0.0900281f}, +{-0.074357f,-0.396993f,0.0918925f},{-0.0703325f,-0.393337f,0.0900281f},{-0.0872815f,-0.406855f,0.0918925f}, +{-0.0785292f,-0.400468f,0.0918925f},{-0.0872816f,-0.406855f,0.0900281f},{-0.0918488f,-0.409759f,0.0918925f}, +{-0.091849f,-0.409759f,0.0900281f},{-0.0965352f,-0.412465f,0.0900281f},{-0.0965352f,-0.412465f,0.0918925f}, +{-0.101334f,-0.41497f,0.0918925f},{-0.101334f,-0.41497f,0.0900281f},{-0.106239f,-0.417269f,0.0900281f}, +{-0.111243f,-0.419359f,0.0918925f},{-0.106239f,-0.417269f,0.0918925f},{-0.111243f,-0.419359f,0.0900281f}, +{-0.116342f,-0.421236f,0.0900281f},{-0.116341f,-0.421236f,0.0918925f},{-0.132038f,-0.425533f,0.0918925f}, +{-0.126754f,-0.424327f,0.0900281f},{-0.132038f,-0.425533f,0.0900281f},{-0.121519f,-0.422894f,0.0918925f}, +{-0.121519f,-0.422894f,0.0900281f},{-0.126754f,-0.424327f,0.0918925f},{-0.137363f,-0.426511f,0.0918925f}, +{-0.142723f,-0.427261f,0.0918925f},{-0.137364f,-0.426511f,0.0900281f},{-0.142723f,-0.427261f,0.0900281f}, +{-0.14811f,-0.427781f,0.0900281f},{-0.153516f,-0.428071f,0.0900281f},{-0.153516f,-0.428071f,0.0918925f}, +{-0.14811f,-0.427781f,0.0918925f},{-0.158934f,-0.428131f,0.0900281f},{-0.158934f,-0.428131f,0.0918925f}, +{-0.164357f,-0.427958f,0.0900281f},{-0.164356f,-0.427958f,0.0918925f},{-0.0664729f,-0.389518f,0.0900281f}, +{-0.0703321f,-0.393337f,0.0918925f},{-0.0664728f,-0.389518f,0.0918925f},{-0.0627861f,-0.385543f,0.0900281f}, +{-0.0627861f,-0.385543f,0.0918925f},{-0.0592762f,-0.381418f,0.0900281f},{-0.0559475f,-0.37715f,0.0900281f}, +{-0.0592761f,-0.381418f,0.0918925f},{-0.0559474f,-0.37715f,0.0918925f},{-0.0528044f,-0.372745f,0.0900281f}, +{-0.0528044f,-0.372745f,0.0918925f},{-0.0498513f,-0.368209f,0.0900281f},{-0.0470924f,-0.363547f,0.0900281f}, +{-0.0498511f,-0.368209f,0.0918925f},{-0.0470923f,-0.363547f,0.0918925f},{-0.0445321f,-0.358766f,0.0900281f}, +{-0.0445321f,-0.358766f,0.0918925f},{-0.042175f,-0.353872f,0.0900281f},{-0.0400276f,-0.348877f,0.0900281f}, +{-0.0421746f,-0.353871f,0.0918925f},{-0.0400276f,-0.348877f,0.0918925f},{-0.0380996f,-0.343803f,0.0900281f}, +{-0.0380996f,-0.343803f,0.0918925f},{-0.0363926f,-0.338659f,0.0900281f},{-0.0349082f,-0.333452f,0.0900281f}, +{-0.0363926f,-0.338659f,0.0918925f},{-0.0349082f,-0.333452f,0.0918925f},{-0.033648f,-0.328189f,0.0900281f}, +{-0.0336479f,-0.328189f,0.0918925f},{-0.0326134f,-0.322877f,0.0900281f},{-0.031806f,-0.317524f,0.0900281f}, +{-0.0326134f,-0.322877f,0.0918925f},{-0.031806f,-0.317524f,0.0918925f},{-0.0312275f,-0.312137f,0.0900281f}, +{-0.0312274f,-0.312136f,0.0918925f},{-0.0308792f,-0.306722f,0.0900281f},{-0.0307628f,-0.301289f,0.0900281f}, +{-0.0308792f,-0.306722f,0.0918925f},{-0.0307628f,-0.301289f,0.0918925f},{-2.84358e-015f,-0.270526f,0.0918925f}, +{-2.91313e-015f,-0.270526f,0.0900281f},{-0.00166887f,-0.270571f,0.0900281f},{-0.0033296f,-0.270707f,0.0900281f}, +{-0.00166875f,-0.270571f,0.0918925f},{-0.00497861f,-0.270931f,0.0900281f},{-0.00332938f,-0.270706f,0.0918925f}, +{-0.00497832f,-0.270931f,0.0918925f},{-0.00661229f,-0.271245f,0.0900281f},{-0.00822706f,-0.271646f,0.0900281f}, +{-0.00661197f,-0.271245f,0.0918925f},{-0.00981931f,-0.272135f,0.0900281f},{-0.00822672f,-0.271646f,0.0918925f}, +{-0.009819f,-0.272135f,0.0918925f},{-0.0113858f,-0.27271f,0.0900281f},{-0.0129196f,-0.27337f,0.0900281f}, +{-0.0113852f,-0.27271f,0.0918925f},{-0.0144128f,-0.274111f,0.0900281f},{-0.0129192f,-0.27337f,0.0918925f}, +{-0.0144127f,-0.274111f,0.0918925f},{-0.0158618f,-0.27493f,0.0900281f},{-0.0172635f,-0.275826f,0.0900281f}, +{-0.0158617f,-0.27493f,0.0918925f},{-0.0186148f,-0.276797f,0.0900281f},{-0.0172633f,-0.275826f,0.0918925f}, +{-0.0186146f,-0.276797f,0.0918925f},{-0.0199127f,-0.27784f,0.0900281f},{-0.0211544f,-0.278954f,0.0900281f}, +{-0.0199124f,-0.27784f,0.0918925f},{-0.0223352f,-0.280135f,0.0900281f},{-0.0211538f,-0.278953f,0.0918925f}, +{-0.0223347f,-0.280134f,0.0918925f},{-0.0234487f,-0.281376f,0.0900281f},{-0.0244917f,-0.282674f,0.0900281f}, +{-0.0234485f,-0.281376f,0.0918925f},{-0.0254622f,-0.284025f,0.0900281f},{-0.0244916f,-0.282674f,0.0918925f}, +{-0.0254621f,-0.284025f,0.0918925f},{-0.0263582f,-0.285427f,0.0900281f},{-0.0271776f,-0.286876f,0.0900281f}, +{-0.0263581f,-0.285427f,0.0918925f},{-0.0279185f,-0.288369f,0.0900281f},{-0.0271775f,-0.286876f,0.0918925f}, +{-0.0279183f,-0.288369f,0.0918925f},{-0.0285784f,-0.289903f,0.0900281f},{-0.0291536f,-0.29147f,0.0900281f}, +{-0.0285781f,-0.289903f,0.0918925f},{-0.0296423f,-0.293062f,0.0900281f},{-0.0291535f,-0.291469f,0.0918925f}, +{-0.0296423f,-0.293061f,0.0918925f},{-0.0300438f,-0.294677f,0.0900281f},{-0.0303573f,-0.29631f,0.0900281f}, +{-0.0300437f,-0.294676f,0.0918925f},{-0.0305821f,-0.297959f,0.0900281f},{-0.0303572f,-0.29631f,0.0918925f}, +{-0.030582f,-0.297959f,0.0918925f},{-0.0307175f,-0.29962f,0.0900281f},{-0.0307174f,-0.29962f,0.0918925f}, +{0.00166887f,-0.270571f,0.0918925f},{0.00166875f,-0.270571f,0.0900281f},{0.0033296f,-0.270707f,0.0918925f}, +{0.00497861f,-0.270931f,0.0918925f},{0.00332938f,-0.270706f,0.0900281f},{0.00661229f,-0.271245f,0.0918925f}, +{0.00497832f,-0.270931f,0.0900281f},{0.00661197f,-0.271245f,0.0900281f},{0.00822706f,-0.271646f,0.0918925f}, +{0.00981931f,-0.272135f,0.0918925f},{0.00822672f,-0.271646f,0.0900281f},{0.0113858f,-0.27271f,0.0918925f}, +{0.009819f,-0.272135f,0.0900281f},{0.0113852f,-0.27271f,0.0900281f},{0.0129196f,-0.27337f,0.0918925f}, +{0.0144128f,-0.274111f,0.0918925f},{0.0129192f,-0.27337f,0.0900281f},{0.0158618f,-0.27493f,0.0918925f}, +{0.0144127f,-0.274111f,0.0900281f},{0.0158617f,-0.27493f,0.0900281f},{0.0172635f,-0.275826f,0.0918925f}, +{0.0186148f,-0.276797f,0.0918925f},{0.0172633f,-0.275826f,0.0900281f},{0.0199127f,-0.27784f,0.0918925f}, +{0.0186146f,-0.276797f,0.0900281f},{0.0199124f,-0.27784f,0.0900281f},{0.0211544f,-0.278954f,0.0918925f}, +{0.0223352f,-0.280135f,0.0918925f},{0.0211538f,-0.278953f,0.0900281f},{0.0234487f,-0.281376f,0.0918925f}, +{0.0223347f,-0.280134f,0.0900281f},{0.0234485f,-0.281376f,0.0900281f},{0.0244917f,-0.282674f,0.0918925f}, +{0.0254622f,-0.284025f,0.0918925f},{0.0244916f,-0.282674f,0.0900281f},{0.0263582f,-0.285427f,0.0918925f}, +{0.0254621f,-0.284025f,0.0900281f},{0.0263581f,-0.285427f,0.0900281f},{0.0271776f,-0.286876f,0.0918925f}, +{0.0279185f,-0.288369f,0.0918925f},{0.0271775f,-0.286876f,0.0900281f},{0.0285784f,-0.289903f,0.0918925f}, +{0.0279183f,-0.288369f,0.0900281f},{0.0285781f,-0.289903f,0.0900281f},{0.0291536f,-0.29147f,0.0918925f}, +{0.0296423f,-0.293062f,0.0918925f},{0.0291535f,-0.291469f,0.0900281f},{0.0300438f,-0.294677f,0.0918925f}, +{0.0296423f,-0.293061f,0.0900281f},{0.0300437f,-0.294676f,0.0900281f},{0.0303573f,-0.29631f,0.0918925f}, +{0.0305821f,-0.297959f,0.0918925f},{0.0303572f,-0.29631f,0.0900281f},{0.0307175f,-0.29962f,0.0918925f}, +{0.030582f,-0.297959f,0.0900281f},{0.0307174f,-0.29962f,0.0900281f},{0.0307628f,-0.301289f,0.0918925f}, +{0.0307628f,-0.301289f,0.0900281f},{0.0664728f,-0.389518f,0.0900281f},{0.0627861f,-0.385543f,0.0900281f}, +{0.0627861f,-0.385543f,0.0918925f},{0.0703321f,-0.393337f,0.0900281f},{0.0703325f,-0.393337f,0.0918925f}, +{0.074357f,-0.396993f,0.0900281f},{0.0592762f,-0.381418f,0.0918925f},{0.0664729f,-0.389518f,0.0918925f}, +{0.0592761f,-0.381418f,0.0900281f},{0.0559475f,-0.37715f,0.0918925f},{0.0559474f,-0.37715f,0.0900281f}, +{0.0528044f,-0.372745f,0.0900281f},{0.0528044f,-0.372745f,0.0918925f},{0.0498513f,-0.368209f,0.0918925f}, +{0.0498511f,-0.368209f,0.0900281f},{0.0470923f,-0.363547f,0.0900281f},{0.0445321f,-0.358766f,0.0918925f}, +{0.0470924f,-0.363547f,0.0918925f},{0.0445321f,-0.358766f,0.0900281f},{0.0421746f,-0.353871f,0.0900281f}, +{0.042175f,-0.353872f,0.0918925f},{0.0363926f,-0.338659f,0.0918925f},{0.0380996f,-0.343803f,0.0900281f}, +{0.0363926f,-0.338659f,0.0900281f},{0.0400276f,-0.348877f,0.0918925f},{0.0400276f,-0.348877f,0.0900281f}, +{0.0380996f,-0.343803f,0.0918925f},{0.0349082f,-0.333452f,0.0918925f},{0.033648f,-0.328189f,0.0918925f}, +{0.0349082f,-0.333452f,0.0900281f},{0.0336479f,-0.328189f,0.0900281f},{0.0326134f,-0.322877f,0.0900281f}, +{0.031806f,-0.317524f,0.0900281f},{0.031806f,-0.317524f,0.0918925f},{0.0326134f,-0.322877f,0.0918925f}, +{0.0312274f,-0.312136f,0.0900281f},{0.0312275f,-0.312137f,0.0918925f},{0.0308792f,-0.306722f,0.0900281f}, +{0.0308792f,-0.306722f,0.0918925f},{0.0785292f,-0.400468f,0.0900281f},{0.0743574f,-0.396993f,0.0918925f}, +{0.0785294f,-0.400468f,0.0918925f},{0.0828395f,-0.403757f,0.0900281f},{0.0828396f,-0.403757f,0.0918925f}, +{0.0872815f,-0.406855f,0.0900281f},{0.0918488f,-0.409759f,0.0900281f},{0.0872816f,-0.406855f,0.0918925f}, +{0.091849f,-0.409759f,0.0918925f},{0.0965352f,-0.412465f,0.0900281f},{0.0965352f,-0.412465f,0.0918925f}, +{0.101334f,-0.41497f,0.0900281f},{0.106239f,-0.417269f,0.0900281f},{0.101334f,-0.41497f,0.0918925f}, +{0.106239f,-0.417269f,0.0918925f},{0.111243f,-0.419359f,0.0900281f},{0.111243f,-0.419359f,0.0918925f}, +{0.116341f,-0.421236f,0.0900281f},{0.121519f,-0.422894f,0.0900281f},{0.116342f,-0.421236f,0.0918925f}, +{0.121519f,-0.422894f,0.0918925f},{0.126754f,-0.424327f,0.0900281f},{0.126754f,-0.424327f,0.0918925f}, +{0.132038f,-0.425533f,0.0900281f},{0.137363f,-0.426511f,0.0900281f},{0.132038f,-0.425533f,0.0918925f}, +{0.137364f,-0.426511f,0.0918925f},{0.142723f,-0.427261f,0.0900281f},{0.142723f,-0.427261f,0.0918925f}, +{0.14811f,-0.427781f,0.0900281f},{0.153516f,-0.428071f,0.0900281f},{0.14811f,-0.427781f,0.0918925f}, +{0.153516f,-0.428071f,0.0918925f},{0.158934f,-0.428131f,0.0900281f},{0.158934f,-0.428131f,0.0918925f}, +{0.164356f,-0.427958f,0.0900281f},{0.169776f,-0.427553f,0.0900281f},{0.164357f,-0.427958f,0.0918925f}, +{0.169776f,-0.427553f,0.0918925f},{0.18196f,-0.448656f,0.0918925f},{0.18196f,-0.448656f,0.0900281f}, +{0.0049028f,-0.5f,0.0918925f},{-0.00490289f,-0.5f,0.0918925f},{0.00490289f,-0.5f,0.0900281f}, +{0.0147057f,-0.499724f,0.0900281f},{0.0147055f,-0.499724f,0.0918925f},{0.0244996f,-0.499171f,0.0900281f}, +{0.0244996f,-0.499171f,0.0918925f},{0.0342788f,-0.498342f,0.0918925f},{0.034279f,-0.498342f,0.0900281f}, +{0.0440377f,-0.497236f,0.0900281f},{0.0440376f,-0.497236f,0.0918925f},{0.05377f,-0.495854f,0.0900281f}, +{0.05377f,-0.495854f,0.0918925f},{0.0634697f,-0.494196f,0.0918925f},{0.0634706f,-0.494196f,0.0900281f}, +{0.0731194f,-0.492264f,0.0900281f},{0.0731193f,-0.492264f,0.0918925f},{0.0826996f,-0.490062f,0.0900281f}, +{0.0826996f,-0.490062f,0.0918925f},{0.0922052f,-0.487593f,0.0918925f},{0.0922054f,-0.487593f,0.0900281f}, +{0.101631f,-0.484859f,0.0900281f},{0.101631f,-0.484859f,0.0918925f},{0.110971f,-0.481861f,0.0900281f}, +{0.110971f,-0.481861f,0.0918925f},{0.120221f,-0.478603f,0.0918925f},{0.120221f,-0.478602f,0.0900281f}, +{0.129374f,-0.475085f,0.0900281f},{0.129374f,-0.475085f,0.0918925f},{0.138425f,-0.47131f,0.0900281f}, +{0.138425f,-0.47131f,0.0918925f},{0.147368f,-0.46728f,0.0918925f},{0.147369f,-0.46728f,0.0900281f}, +{0.156199f,-0.462998f,0.0900281f},{0.156199f,-0.462998f,0.0918925f},{0.164912f,-0.458465f,0.0900281f}, +{0.164912f,-0.458465f,0.0918925f},{0.173501f,-0.453684f,0.0918925f},{0.173501f,-0.453684f,0.0900281f}, +{-0.0049028f,-0.5f,0.0900281f},{-0.0147055f,-0.499724f,0.0900281f},{-0.0147057f,-0.499724f,0.0918925f}, +{-0.0244996f,-0.499171f,0.0918925f},{-0.0244996f,-0.499171f,0.0900281f},{-0.034279f,-0.498342f,0.0918925f}, +{-0.0342788f,-0.498342f,0.0900281f},{-0.0440376f,-0.497236f,0.0900281f},{-0.0440377f,-0.497236f,0.0918925f}, +{-0.05377f,-0.495854f,0.0918925f},{-0.05377f,-0.495854f,0.0900281f},{-0.0634706f,-0.494196f,0.0918925f}, +{-0.0634697f,-0.494196f,0.0900281f},{-0.0731193f,-0.492264f,0.0900281f},{-0.0731194f,-0.492264f,0.0918925f}, +{-0.0826996f,-0.490062f,0.0918925f},{-0.0826996f,-0.490062f,0.0900281f},{-0.0922054f,-0.487593f,0.0918925f}, +{-0.0922052f,-0.487593f,0.0900281f},{-0.101631f,-0.484859f,0.0900281f},{-0.101631f,-0.484859f,0.0918925f}, +{-0.110971f,-0.481861f,0.0918925f},{-0.110971f,-0.481861f,0.0900281f},{-0.120221f,-0.478602f,0.0918925f}, +{-0.120221f,-0.478603f,0.0900281f},{-0.129374f,-0.475085f,0.0900281f},{-0.129374f,-0.475085f,0.0918925f}, +{-0.138425f,-0.47131f,0.0918925f},{-0.138425f,-0.47131f,0.0900281f},{-0.147369f,-0.46728f,0.0918925f}, +{-0.147368f,-0.46728f,0.0900281f},{-0.156199f,-0.462998f,0.0900281f},{-0.156199f,-0.462998f,0.0918925f}, +{-0.164912f,-0.458465f,0.0918925f},{-0.164912f,-0.458465f,0.0900281f},{-0.173501f,-0.453684f,0.0918925f}, +{-0.173501f,-0.453684f,0.0900281f},{0.0200317f,-0.295886f,0.0918925f},{0.0036392f,-0.280259f,0.0918925f}, +{0.00474168f,-0.280781f,0.0918925f},{0.0152687f,-0.28931f,0.0918925f},{0.0183517f,-0.29453f,0.0918925f}, +{0.0057053f,-0.28153f,0.0918925f},{0.0130697f,-0.291507f,0.0918925f},{0.0151095f,-0.289835f,0.0918925f}, +{0.0173478f,-0.294119f,0.0918925f},{0.0109706f,-0.291087f,0.0918925f},{0.0105473f,-0.290739f,0.0918925f}, +{0.0192577f,-0.295126f,0.0918925f},{0.0206442f,-0.296782f,0.0918925f},{0.0210723f,-0.297778f,0.0918925f}, +{0.0101998f,-0.290316f,0.0918925f},{0.0140791f,-0.291091f,0.0918925f},{0.0151984f,-0.293911f,0.0918925f}, +{0.0145033f,-0.290742f,0.0918925f},{-0.0105451f,-0.315791f,0.0918925f},{-0.0101973f,-0.315367f,0.0918925f}, +{-0.0109693f,-0.316139f,0.0918925f},{-0.00977971f,-0.314358f,0.0918925f},{-0.00993885f,-0.314883f,0.0918925f}, +{-0.0151067f,-0.314881f,0.0918925f},{-0.0119787f,-0.316555f,0.0918925f},{-0.0114536f,-0.316397f,0.0918925f}, +{-0.0125242f,-0.316609f,0.0918925f},{-0.013595f,-0.316394f,0.0918925f},{-0.0140778f,-0.316135f,0.0918925f}, +{-0.0145011f,-0.315788f,0.0918925f},{-0.0148486f,-0.315364f,0.0918925f},{-0.015266f,-0.314357f,0.0918925f}, +{0.0148511f,-0.290318f,0.0918925f},{0.0162833f,-0.29391f,0.0918925f},{0.0119779f,-0.291506f,0.0918925f}, +{0.0125242f,-0.291561f,0.0918925f},{0.0114534f,-0.291346f,0.0918925f},{0.0135948f,-0.291349f,0.0918925f}, +{0.00994166f,-0.289833f,0.0918925f},{-0.0130705f,-0.316555f,0.0918925f},{0.00978241f,-0.289309f,0.0918925f}, +{0.00474296f,-0.280782f,0.0900281f},{0.0210725f,-0.297777f,0.0900281f},{0.020644f,-0.296781f,0.0900281f}, +{0.0105451f,-0.290742f,0.0900281f},{0.00364027f,-0.280259f,0.0900281f},{0.00993885f,-0.289835f,0.0900281f}, +{0.0200312f,-0.295886f,0.0900281f},{0.0192574f,-0.295126f,0.0900281f},{0.0162822f,-0.29391f,0.0900281f}, +{0.0145011f,-0.290739f,0.0900281f},{0.0148486f,-0.290316f,0.0900281f},{0.0125242f,-0.291561f,0.0900281f}, +{0.00977971f,-0.28931f,0.0900281f},{0.0109693f,-0.291091f,0.0900281f},{0.0101973f,-0.290318f,0.0900281f}, +{0.0114536f,-0.291349f,0.0900281f},{-0.0145033f,-0.315791f,0.0900281f},{-0.0140791f,-0.316139f,0.0900281f}, +{-0.00978241f,-0.314357f,0.0900281f},{-0.00994166f,-0.314881f,0.0900281f},{0.0183513f,-0.294529f,0.0900281f}, +{0.0173468f,-0.294119f,0.0900281f},{0.0151067f,-0.289833f,0.0900281f},{0.015266f,-0.289309f,0.0900281f}, +{0.0140778f,-0.291087f,0.0900281f},{0.0151976f,-0.293911f,0.0900281f},{0.013595f,-0.291346f,0.0900281f}, +{0.00570553f,-0.28153f,0.0900281f},{-0.0119779f,-0.316555f,0.0900281f},{-0.0101998f,-0.315364f,0.0900281f}, +{-0.0125242f,-0.316609f,0.0900281f},{-0.0130697f,-0.316555f,0.0900281f},{-0.0135948f,-0.316397f,0.0900281f}, +{-0.0148511f,-0.315367f,0.0900281f},{-0.0151095f,-0.314883f,0.0900281f},{-0.0109706f,-0.316135f,0.0900281f}, +{-0.0152687f,-0.314358f,0.0900281f},{-0.0114534f,-0.316394f,0.0900281f},{-0.0105473f,-0.315788f,0.0900281f}, +{0.0119787f,-0.291507f,0.0900281f},{0.0130705f,-0.291506f,0.0900281f},{-0.301289f,0.00279661f,0.127503f}, +{-0.301289f,0.00279661f,0.13496f},{-0.3008f,0.00275356f,0.13496f},{-0.300331f,0.00262748f,0.13496f}, +{-0.300801f,0.00275376f,0.127503f},{-0.300332f,0.00262801f,0.127503f},{-0.299893f,0.00242333f,0.127503f}, +{-0.299493f,0.00214411f,0.127503f},{-0.299891f,0.00242266f,0.13496f},{-0.299491f,0.00214219f,0.13496f}, +{-0.299146f,0.00179767f,0.127503f},{-0.299144f,0.00179504f,0.13496f},{-0.298866f,0.00139727f,0.127503f}, +{-0.298661f,0.000957717f,0.127503f},{-0.298865f,0.00139564f,0.13496f},{-0.298661f,0.000956449f,0.13496f}, +{-0.298535f,0.000488516f,0.127503f},{-0.298535f,0.000488516f,0.13496f},{-0.298492f,3.42486e-019f,0.13496f}, +{-0.298492f,3.42486e-019f,0.127503f},{-0.301777f,0.00275356f,0.127503f},{-0.302246f,0.00262748f,0.127503f}, +{-0.301776f,0.00275376f,0.13496f},{-0.302684f,0.00242333f,0.13496f},{-0.302245f,0.00262801f,0.13496f}, +{-0.302686f,0.00242266f,0.127503f},{-0.303084f,0.00214411f,0.13496f},{-0.303086f,0.00214219f,0.127503f}, +{-0.303431f,0.00179767f,0.13496f},{-0.303711f,0.00139727f,0.13496f},{-0.303433f,0.00179504f,0.127503f}, +{-0.303712f,0.00139564f,0.127503f},{-0.303916f,0.000957717f,0.13496f},{-0.303917f,0.000956449f,0.127503f}, +{-0.304042f,0.000488516f,0.13496f},{-0.304042f,0.000488516f,0.127503f},{-0.304085f,0.0f,0.127503f}, +{-0.304085f,0.0f,0.13496f},{-0.301289f,0.00466102f,0.125638f},{-0.301289f,0.00466102f,0.127503f}, +{-0.300676f,0.00462052f,0.127503f},{-0.300079f,0.00450127f,0.127503f},{-0.300676f,0.00462066f,0.125638f}, +{-0.299505f,0.00430621f,0.127503f},{-0.300079f,0.00450141f,0.125638f},{-0.299505f,0.00430621f,0.125638f}, +{-0.298961f,0.00403818f,0.127503f},{-0.298454f,0.00370041f,0.127503f},{-0.298961f,0.00403832f,0.125638f}, +{-0.297993f,0.00329584f,0.127503f},{-0.298455f,0.00370055f,0.125638f},{-0.297993f,0.00329584f,0.125638f}, +{-0.297588f,0.00283386f,0.127503f},{-0.29725f,0.00232743f,0.127503f},{-0.297588f,0.0028342f,0.125638f}, +{-0.296982f,0.00178369f,0.127503f},{-0.29725f,0.00232777f,0.125638f},{-0.296787f,0.00120978f,0.125638f}, +{-0.296982f,0.00178369f,0.125638f},{-0.296787f,0.00120944f,0.127503f},{-0.296668f,0.000612842f,0.125638f}, +{-0.296668f,0.000612502f,0.127503f},{-0.296628f,5.70811e-019f,0.125638f},{-0.296628f,5.70811e-019f,0.127503f}, +{-0.301901f,0.00462052f,0.125638f},{-0.302498f,0.00450127f,0.125638f},{-0.301901f,0.00462066f,0.127503f}, +{-0.302498f,0.00450141f,0.127503f},{-0.303072f,0.00430621f,0.125638f},{-0.303616f,0.00403818f,0.125638f}, +{-0.303072f,0.00430621f,0.127503f},{-0.304123f,0.00370041f,0.125638f},{-0.303616f,0.00403832f,0.127503f}, +{-0.304122f,0.00370055f,0.127503f},{-0.304584f,0.00329584f,0.125638f},{-0.304989f,0.00283386f,0.125638f}, +{-0.304584f,0.00329584f,0.127503f},{-0.305327f,0.00232743f,0.125638f},{-0.304989f,0.0028342f,0.127503f}, +{-0.305327f,0.00232777f,0.127503f},{-0.305595f,0.00178369f,0.125638f},{-0.30579f,0.00120978f,0.127503f}, +{-0.305595f,0.00178369f,0.127503f},{-0.30579f,0.00120944f,0.125638f},{-0.305909f,0.000612842f,0.127503f}, +{-0.30595f,0.0f,0.127503f},{-0.305909f,0.000612502f,0.125638f},{-0.30595f,0.0f,0.125638f}, +{-0.29833f,-0.00883211f,0.125638f},{-0.298135f,-0.00916975f,0.125638f},{-0.298136f,-0.00916839f,0.121909f}, +{-0.298331f,-0.00883048f,0.121909f},{-0.298451f,-0.00846133f,0.125638f},{-0.298451f,-0.00845974f,0.121909f}, +{-0.298492f,-0.0080728f,0.121909f},{-0.298451f,-0.00768692f,0.125638f},{-0.298492f,-0.00807384f,0.125638f}, +{-0.298451f,-0.00768446f,0.121909f},{-0.298331f,-0.00731545f,0.125638f},{-0.29833f,-0.00731401f,0.121909f}, +{-0.298136f,-0.00697763f,0.125638f},{-0.298136f,-0.00697682f,0.121909f},{-0.297876f,-0.00668858f,0.125638f}, +{-0.297875f,-0.0066878f,0.121909f},{-0.29756f,-0.0064585f,0.121909f},{-0.29756f,-0.0064585f,0.125638f}, +{-0.297876f,-0.00945833f,0.121909f},{-0.29756f,-0.00968734f,0.121909f},{-0.297874f,-0.00945929f,0.125638f}, +{-0.297559f,-0.00968796f,0.125638f},{-0.297205f,-0.00984564f,0.121909f},{-0.297203f,-0.00984651f,0.125638f}, +{-0.296823f,-0.00992724f,0.121909f},{-0.296433f,-0.00992738f,0.121909f},{-0.296822f,-0.00992734f,0.125638f}, +{-0.296432f,-0.00992724f,0.125638f},{-0.296053f,-0.00984657f,0.121909f},{-0.296052f,-0.00984636f,0.125638f}, +{-0.295695f,-0.00968775f,0.121909f},{-0.295695f,-0.00968775f,0.125638f},{-0.293346f,-0.00814348f,0.125638f}, +{-0.293065f,-0.00862894f,0.125638f},{-0.293067f,-0.00862571f,0.121909f},{-0.29355f,-0.00762194f,0.125638f}, +{-0.293347f,-0.00813961f,0.121909f},{-0.29355f,-0.00762066f,0.121909f},{-0.293673f,-0.00708133f,0.125638f}, +{-0.293673f,-0.00708043f,0.121909f},{-0.293715f,-0.0065271f,0.121909f},{-0.293715f,-0.00652944f,0.125638f}, +{-0.293674f,-0.00597413f,0.125638f},{-0.293344f,-0.00490426f,0.121909f},{-0.293067f,-0.00442484f,0.125638f}, +{-0.293344f,-0.00490499f,0.125638f},{-0.293673f,-0.00596985f,0.121909f},{-0.293549f,-0.00542656f,0.125638f}, +{-0.293548f,-0.00542408f,0.121909f},{-0.293066f,-0.00442313f,0.121909f},{-0.292722f,-0.00399173f,0.125638f}, +{-0.29272f,-0.00398963f,0.121909f},{-0.292314f,-0.00361295f,0.121909f},{-0.291851f,-0.00329618f,0.125638f}, +{-0.292314f,-0.00361295f,0.125638f},{-0.291851f,-0.00329618f,0.121909f},{-0.292718f,-0.00906373f,0.121909f}, +{-0.292311f,-0.00944065f,0.121909f},{-0.292717f,-0.00906452f,0.125638f},{-0.29231f,-0.00944121f,0.125638f}, +{-0.291854f,-0.00975253f,0.121909f},{-0.291852f,-0.00975397f,0.125638f},{-0.291352f,-0.00999456f,0.121909f}, +{-0.290816f,-0.0101607f,0.121909f},{-0.291349f,-0.0099963f,0.125638f},{-0.290813f,-0.010161f,0.125638f}, +{-0.290262f,-0.010244f,0.121909f},{-0.290261f,-0.0102441f,0.125638f},{-0.289707f,-0.0102439f,0.121909f}, +{-0.28916f,-0.0101614f,0.121909f},{-0.289705f,-0.0102436f,0.125638f},{-0.289157f,-0.010161f,0.125638f}, +{-0.288628f,-0.0099979f,0.121909f},{-0.288628f,-0.0099979f,0.125638f},{-0.288122f,-0.00975468f,0.121909f}, +{-0.288122f,-0.00975468f,0.125638f},{-0.307458f,-0.00697787f,0.125638f},{-0.307653f,-0.00731578f,0.125638f}, +{-0.307652f,-0.00731414f,0.121909f},{-0.307457f,-0.0069765f,0.121909f},{-0.307198f,-0.00668793f,0.125638f}, +{-0.307196f,-0.00668696f,0.121909f},{-0.306881f,-0.0064583f,0.121909f},{-0.306527f,-0.00630061f,0.125638f}, +{-0.306882f,-0.00645891f,0.125638f},{-0.306525f,-0.00629975f,0.121909f},{-0.306145f,-0.00621902f,0.125638f}, +{-0.306144f,-0.00621892f,0.121909f},{-0.305755f,-0.00621887f,0.125638f},{-0.305754f,-0.00621902f,0.121909f}, +{-0.305375f,-0.00629969f,0.125638f},{-0.305374f,-0.0062999f,0.121909f},{-0.305017f,-0.0064585f,0.121909f}, +{-0.305017f,-0.0064585f,0.125638f},{-0.307773f,-0.00768493f,0.121909f},{-0.307814f,-0.00807242f,0.121909f}, +{-0.307773f,-0.00768652f,0.125638f},{-0.307814f,-0.00807346f,0.125638f},{-0.307773f,-0.00845934f,0.121909f}, +{-0.307773f,-0.0084618f,0.125638f},{-0.307653f,-0.0088308f,0.121909f},{-0.307458f,-0.00916863f,0.121909f}, +{-0.307652f,-0.00883225f,0.125638f},{-0.307458f,-0.00916944f,0.125638f},{-0.307198f,-0.00945768f,0.121909f}, +{-0.307197f,-0.00945846f,0.125638f},{-0.306882f,-0.00968775f,0.121909f},{-0.306882f,-0.00968775f,0.125638f}, +{-0.304369f,-0.0109506f,0.125638f},{-0.304649f,-0.0114367f,0.125638f},{-0.304648f,-0.0114328f,0.121909f}, +{-0.30402f,-0.0105126f,0.125638f},{-0.304367f,-0.0109474f,0.121909f},{-0.304019f,-0.0105118f,0.121909f}, +{-0.303614f,-0.0101356f,0.125638f},{-0.303613f,-0.0101351f,0.121909f},{-0.303154f,-0.00982233f,0.121909f}, +{-0.303156f,-0.00982376f,0.125638f},{-0.302655f,-0.00958174f,0.125638f},{-0.301564f,-0.00933222f,0.121909f}, +{-0.30101f,-0.00933241f,0.125638f},{-0.301564f,-0.00933231f,0.125638f},{-0.302651f,-0.00958f,0.121909f}, +{-0.302118f,-0.00941561f,0.125638f},{-0.302116f,-0.00941532f,0.121909f},{-0.301008f,-0.0093327f,0.121909f}, +{-0.300462f,-0.00941491f,0.125638f},{-0.300459f,-0.00941526f,0.121909f},{-0.29993f,-0.0095784f,0.121909f}, +{-0.299424f,-0.00982161f,0.125638f},{-0.29993f,-0.0095784f,0.125638f},{-0.299424f,-0.00982161f,0.121909f}, +{-0.304853f,-0.0119544f,0.121909f},{-0.304976f,-0.012495f,0.121909f},{-0.304853f,-0.0119556f,0.125638f}, +{-0.304976f,-0.0124959f,0.125638f},{-0.305017f,-0.0130469f,0.121909f},{-0.305017f,-0.0130492f,0.125638f}, +{-0.304976f,-0.0136022f,0.121909f},{-0.304852f,-0.0141497f,0.121909f},{-0.304976f,-0.0136064f,0.125638f}, +{-0.304851f,-0.0141522f,0.125638f},{-0.304647f,-0.0146713f,0.121909f},{-0.304646f,-0.014672f,0.125638f}, +{-0.304369f,-0.0151515f,0.121909f},{-0.304024f,-0.0155846f,0.121909f},{-0.304368f,-0.0151532f,0.125638f}, +{-0.304023f,-0.0155867f,0.125638f},{-0.303617f,-0.0159633f,0.121909f},{-0.303617f,-0.0159633f,0.125638f}, +{-0.303153f,-0.0162801f,0.121909f},{-0.303153f,-0.0162801f,0.125638f},{-0.310416f,0.00185425f,0.125638f}, +{-0.310806f,0.00185398f,0.125638f},{-0.310805f,0.00185425f,0.121909f},{-0.310415f,0.00185398f,0.121909f}, +{-0.310035f,0.0017734f,0.125638f},{-0.310034f,0.00177278f,0.121909f},{-0.309678f,0.0016145f,0.121909f}, +{-0.309364f,0.0013863f,0.125638f},{-0.309679f,0.00161492f,0.125638f},{-0.309362f,0.00138471f,0.121909f}, +{-0.309103f,0.00109643f,0.125638f},{-0.309102f,0.00109509f,0.121909f},{-0.308908f,0.000758756f,0.125638f}, +{-0.308907f,0.000757801f,0.121909f},{-0.308787f,0.000388892f,0.125638f},{-0.308787f,0.000387896f,0.121909f}, +{-0.308746f,3.69669e-018f,0.121909f},{-0.308746f,3.69669e-018f,0.125638f},{-0.311186f,0.0017734f,0.121909f}, +{-0.311542f,0.00161492f,0.121909f},{-0.311188f,0.00177278f,0.125638f},{-0.311543f,0.0016145f,0.125638f}, +{-0.311857f,0.0013863f,0.121909f},{-0.311859f,0.00138471f,0.125638f},{-0.312119f,0.00109643f,0.121909f}, +{-0.312314f,0.000758756f,0.121909f},{-0.312119f,0.00109509f,0.125638f},{-0.312314f,0.000757801f,0.125638f}, +{-0.312434f,0.000388892f,0.121909f},{-0.312434f,0.000387896f,0.125638f},{-0.312475f,4.75298e-018f,0.121909f}, +{-0.312475f,4.75298e-018f,0.125638f},{-0.312313f,-0.00280711f,0.125638f},{-0.312873f,-0.00280775f,0.125638f}, +{-0.312869f,-0.00280711f,0.121909f},{-0.311758f,-0.00289062f,0.125638f},{-0.312308f,-0.00280775f,0.121909f}, +{-0.311757f,-0.00289112f,0.121909f},{-0.311229f,-0.00305432f,0.125638f},{-0.311228f,-0.00305467f,0.121909f}, +{-0.310728f,-0.00329522f,0.121909f},{-0.31073f,-0.00329432f,0.125638f},{-0.31027f,-0.00360761f,0.125638f}, +{-0.309508f,-0.00442796f,0.121909f},{-0.309231f,-0.00490757f,0.125638f},{-0.309508f,-0.00442732f,0.125638f}, +{-0.310266f,-0.00361015f,0.121909f},{-0.309858f,-0.00398905f,0.125638f},{-0.309856f,-0.00399124f,0.121909f}, +{-0.30923f,-0.00490957f,0.121909f},{-0.309029f,-0.00542319f,0.125638f},{-0.309028f,-0.00542563f,0.121909f}, +{-0.308905f,-0.00596545f,0.121909f},{-0.308862f,-0.00652543f,0.125638f},{-0.308905f,-0.00596545f,0.125638f}, +{-0.308862f,-0.00652543f,0.121909f},{-0.313423f,-0.00289062f,0.121909f},{-0.313953f,-0.00305432f,0.121909f}, +{-0.313425f,-0.00289112f,0.125638f},{-0.313954f,-0.00305467f,0.125638f},{-0.314452f,-0.00329432f,0.121909f}, +{-0.314454f,-0.00329522f,0.125638f},{-0.314912f,-0.00360761f,0.121909f},{-0.315324f,-0.00398905f,0.121909f}, +{-0.314916f,-0.00361015f,0.125638f},{-0.315326f,-0.00399124f,0.125638f},{-0.315673f,-0.00442732f,0.121909f}, +{-0.315674f,-0.00442796f,0.125638f},{-0.315951f,-0.00490757f,0.121909f},{-0.316153f,-0.00542319f,0.121909f}, +{-0.315951f,-0.00490957f,0.125638f},{-0.316154f,-0.00542563f,0.125638f},{-0.316277f,-0.00596545f,0.121909f}, +{-0.316277f,-0.00596545f,0.125638f},{-0.31632f,-0.00652543f,0.121909f},{-0.31632f,-0.00652543f,0.125638f}, +{-0.304247f,0.00883211f,0.125638f},{-0.304442f,0.00916975f,0.125638f},{-0.304441f,0.00916839f,0.121909f}, +{-0.304246f,0.00883048f,0.121909f},{-0.304126f,0.00846133f,0.125638f},{-0.304126f,0.00845974f,0.121909f}, +{-0.304085f,0.0080728f,0.121909f},{-0.304126f,0.00768692f,0.125638f},{-0.304085f,0.00807384f,0.125638f}, +{-0.304126f,0.00768446f,0.121909f},{-0.304246f,0.00731545f,0.125638f},{-0.304247f,0.00731401f,0.121909f}, +{-0.304441f,0.00697763f,0.125638f},{-0.304442f,0.00697682f,0.121909f},{-0.304701f,0.00668858f,0.125638f}, +{-0.304702f,0.0066878f,0.121909f},{-0.305017f,0.0064585f,0.121909f},{-0.305017f,0.0064585f,0.125638f}, +{-0.304702f,0.00945833f,0.121909f},{-0.305017f,0.00968734f,0.121909f},{-0.304703f,0.00945929f,0.125638f}, +{-0.305018f,0.00968796f,0.125638f},{-0.305372f,0.00984564f,0.121909f},{-0.305375f,0.00984651f,0.125638f}, +{-0.305754f,0.00992724f,0.121909f},{-0.306144f,0.00992738f,0.121909f},{-0.305756f,0.00992734f,0.125638f}, +{-0.306145f,0.00992724f,0.125638f},{-0.306524f,0.00984657f,0.121909f},{-0.306525f,0.00984636f,0.125638f}, +{-0.306882f,0.00968775f,0.121909f},{-0.306882f,0.00968775f,0.125638f},{-0.309232f,0.00814348f,0.125638f}, +{-0.309513f,0.00862894f,0.125638f},{-0.30951f,0.00862571f,0.121909f},{-0.309027f,0.00762194f,0.125638f}, +{-0.30923f,0.00813961f,0.121909f},{-0.309027f,0.00762066f,0.121909f},{-0.308904f,0.00708133f,0.125638f}, +{-0.308904f,0.00708043f,0.121909f},{-0.308862f,0.0065271f,0.121909f},{-0.308862f,0.00652944f,0.125638f}, +{-0.308903f,0.00597413f,0.125638f},{-0.309233f,0.00490426f,0.121909f},{-0.30951f,0.00442484f,0.125638f}, +{-0.309233f,0.00490499f,0.125638f},{-0.308904f,0.00596985f,0.121909f},{-0.309028f,0.00542656f,0.125638f}, +{-0.309029f,0.00542408f,0.121909f},{-0.309511f,0.00442313f,0.121909f},{-0.309855f,0.00399173f,0.125638f}, +{-0.309857f,0.00398963f,0.121909f},{-0.310263f,0.00361295f,0.121909f},{-0.310726f,0.00329618f,0.125638f}, +{-0.310263f,0.00361295f,0.125638f},{-0.310726f,0.00329618f,0.121909f},{-0.309859f,0.00906373f,0.121909f}, +{-0.310266f,0.00944065f,0.121909f},{-0.30986f,0.00906452f,0.125638f},{-0.310267f,0.00944121f,0.125638f}, +{-0.310723f,0.00975253f,0.121909f},{-0.310725f,0.00975397f,0.125638f},{-0.311225f,0.00999456f,0.121909f}, +{-0.311761f,0.0101607f,0.121909f},{-0.311229f,0.0099963f,0.125638f},{-0.311764f,0.010161f,0.125638f}, +{-0.312315f,0.010244f,0.121909f},{-0.312316f,0.0102441f,0.125638f},{-0.31287f,0.0102439f,0.121909f}, +{-0.313417f,0.0101614f,0.121909f},{-0.312872f,0.0102436f,0.125638f},{-0.31342f,0.010161f,0.125638f}, +{-0.313949f,0.0099979f,0.121909f},{-0.313949f,0.0099979f,0.125638f},{-0.314455f,0.00975468f,0.121909f}, +{-0.314455f,0.00975468f,0.125638f},{-0.295119f,0.00697787f,0.125638f},{-0.294924f,0.00731578f,0.125638f}, +{-0.294925f,0.00731414f,0.121909f},{-0.29512f,0.0069765f,0.121909f},{-0.29538f,0.00668793f,0.125638f}, +{-0.295381f,0.00668696f,0.121909f},{-0.295696f,0.0064583f,0.121909f},{-0.29605f,0.00630061f,0.125638f}, +{-0.295695f,0.00645891f,0.125638f},{-0.296052f,0.00629975f,0.121909f},{-0.296432f,0.00621902f,0.125638f}, +{-0.296434f,0.00621892f,0.121909f},{-0.296822f,0.00621887f,0.125638f},{-0.296823f,0.00621902f,0.121909f}, +{-0.297202f,0.00629969f,0.125638f},{-0.297203f,0.0062999f,0.121909f},{-0.29756f,0.0064585f,0.121909f}, +{-0.29756f,0.0064585f,0.125638f},{-0.294804f,0.00768493f,0.121909f},{-0.294763f,0.00807242f,0.121909f}, +{-0.294804f,0.00768652f,0.125638f},{-0.294763f,0.00807346f,0.125638f},{-0.294804f,0.00845934f,0.121909f}, +{-0.294804f,0.0084618f,0.125638f},{-0.294924f,0.0088308f,0.121909f},{-0.295119f,0.00916863f,0.121909f}, +{-0.294925f,0.00883225f,0.125638f},{-0.29512f,0.00916944f,0.125638f},{-0.295379f,0.00945768f,0.121909f}, +{-0.29538f,0.00945846f,0.125638f},{-0.295695f,0.00968775f,0.121909f},{-0.295695f,0.00968775f,0.125638f}, +{-0.298208f,0.0109506f,0.125638f},{-0.297928f,0.0114367f,0.125638f},{-0.297929f,0.0114328f,0.121909f}, +{-0.298557f,0.0105126f,0.125638f},{-0.29821f,0.0109474f,0.121909f},{-0.298558f,0.0105118f,0.121909f}, +{-0.298964f,0.0101356f,0.125638f},{-0.298964f,0.0101351f,0.121909f},{-0.299423f,0.00982233f,0.121909f}, +{-0.299421f,0.00982376f,0.125638f},{-0.299922f,0.00958174f,0.125638f},{-0.301014f,0.00933222f,0.121909f}, +{-0.301567f,0.00933241f,0.125638f},{-0.301013f,0.00933231f,0.125638f},{-0.299926f,0.00958f,0.121909f}, +{-0.300459f,0.00941561f,0.125638f},{-0.300461f,0.00941532f,0.121909f},{-0.301569f,0.0093327f,0.121909f}, +{-0.302115f,0.00941491f,0.125638f},{-0.302118f,0.00941526f,0.121909f},{-0.302647f,0.0095784f,0.121909f}, +{-0.303153f,0.00982161f,0.125638f},{-0.302647f,0.0095784f,0.125638f},{-0.303153f,0.00982161f,0.121909f}, +{-0.297725f,0.0119544f,0.121909f},{-0.297601f,0.012495f,0.121909f},{-0.297724f,0.0119556f,0.125638f}, +{-0.297601f,0.0124959f,0.125638f},{-0.29756f,0.0130469f,0.121909f},{-0.29756f,0.0130492f,0.125638f}, +{-0.297601f,0.0136022f,0.121909f},{-0.297725f,0.0141497f,0.121909f},{-0.297601f,0.0136064f,0.125638f}, +{-0.297726f,0.0141522f,0.125638f},{-0.29793f,0.0146713f,0.121909f},{-0.297931f,0.014672f,0.125638f}, +{-0.298208f,0.0151515f,0.121909f},{-0.298553f,0.0155846f,0.121909f},{-0.298209f,0.0151532f,0.125638f}, +{-0.298555f,0.0155867f,0.125638f},{-0.29896f,0.0159633f,0.121909f},{-0.29896f,0.0159633f,0.125638f}, +{-0.299424f,0.0162801f,0.121909f},{-0.299424f,0.0162801f,0.125638f},{-0.292161f,-0.00185425f,0.125638f}, +{-0.291771f,-0.00185398f,0.125638f},{-0.291772f,-0.00185425f,0.121909f},{-0.292162f,-0.00185398f,0.121909f}, +{-0.292542f,-0.0017734f,0.125638f},{-0.292544f,-0.00177278f,0.121909f},{-0.292899f,-0.0016145f,0.121909f}, +{-0.293213f,-0.0013863f,0.125638f},{-0.292898f,-0.00161492f,0.125638f},{-0.293215f,-0.00138471f,0.121909f}, +{-0.293474f,-0.00109643f,0.125638f},{-0.293475f,-0.00109509f,0.121909f},{-0.29367f,-0.000758756f,0.125638f}, +{-0.29367f,-0.000757801f,0.121909f},{-0.29379f,-0.000388892f,0.125638f},{-0.29379f,-0.000387896f,0.121909f}, +{-0.293831f,1.53975e-019f,0.121909f},{-0.293831f,1.53975e-019f,0.125638f},{-0.291391f,-0.0017734f,0.121909f}, +{-0.291035f,-0.00161492f,0.121909f},{-0.291389f,-0.00177278f,0.125638f},{-0.291034f,-0.0016145f,0.125638f}, +{-0.29072f,-0.0013863f,0.121909f},{-0.290718f,-0.00138471f,0.125638f},{-0.290459f,-0.00109643f,0.121909f}, +{-0.290263f,-0.000758756f,0.121909f},{-0.290458f,-0.00109509f,0.125638f},{-0.290263f,-0.000757801f,0.125638f}, +{-0.290143f,-0.000388892f,0.121909f},{-0.290143f,-0.000387896f,0.125638f},{-0.290102f,-7.4349e-020f,0.121909f}, +{-0.290102f,-7.4349e-020f,0.125638f},{-0.290265f,0.00280711f,0.125638f},{-0.289704f,0.00280775f,0.125638f}, +{-0.289708f,0.00280711f,0.121909f},{-0.290819f,0.00289062f,0.125638f},{-0.290269f,0.00280775f,0.121909f}, +{-0.29082f,0.00289112f,0.121909f},{-0.291348f,0.00305432f,0.125638f},{-0.291349f,0.00305467f,0.121909f}, +{-0.291849f,0.00329522f,0.121909f},{-0.291847f,0.00329432f,0.125638f},{-0.292307f,0.00360761f,0.125638f}, +{-0.293069f,0.00442796f,0.121909f},{-0.293346f,0.00490757f,0.125638f},{-0.293069f,0.00442732f,0.125638f}, +{-0.292311f,0.00361015f,0.121909f},{-0.292719f,0.00398905f,0.125638f},{-0.292721f,0.00399124f,0.121909f}, +{-0.293347f,0.00490957f,0.121909f},{-0.293548f,0.00542319f,0.125638f},{-0.293549f,0.00542563f,0.121909f}, +{-0.293673f,0.00596545f,0.121909f},{-0.293715f,0.00652543f,0.125638f},{-0.293673f,0.00596545f,0.125638f}, +{-0.293715f,0.00652543f,0.121909f},{-0.289154f,0.00289062f,0.121909f},{-0.288624f,0.00305432f,0.121909f}, +{-0.289153f,0.00289112f,0.125638f},{-0.288623f,0.00305467f,0.125638f},{-0.288125f,0.00329432f,0.121909f}, +{-0.288123f,0.00329522f,0.125638f},{-0.287665f,0.00360761f,0.121909f},{-0.287253f,0.00398905f,0.121909f}, +{-0.287661f,0.00361015f,0.125638f},{-0.287251f,0.00399124f,0.125638f},{-0.286904f,0.00442732f,0.121909f}, +{-0.286903f,0.00442796f,0.125638f},{-0.286627f,0.00490757f,0.121909f},{-0.286424f,0.00542319f,0.121909f}, +{-0.286626f,0.00490957f,0.125638f},{-0.286423f,0.00542563f,0.125638f},{-0.2863f,0.00596545f,0.121909f}, +{-0.2863f,0.00596545f,0.125638f},{-0.286257f,0.00652543f,0.121909f},{-0.286257f,0.00652543f,0.125638f}, +{-0.301289f,0.00279661f,0.100469f},{-0.301289f,0.00279661f,0.0986044f},{-0.301777f,0.00275356f,0.0986044f}, +{-0.302246f,0.00262748f,0.0986044f},{-0.301776f,0.00275376f,0.100469f},{-0.302245f,0.00262801f,0.100469f}, +{-0.302684f,0.00242333f,0.100469f},{-0.303084f,0.00214411f,0.100469f},{-0.302686f,0.00242266f,0.0986044f}, +{-0.303086f,0.00214219f,0.0986044f},{-0.303431f,0.00179767f,0.100469f},{-0.303433f,0.00179504f,0.0986044f}, +{-0.303711f,0.00139727f,0.100469f},{-0.303916f,0.000957717f,0.100469f},{-0.303712f,0.00139564f,0.0986044f}, +{-0.303917f,0.000956449f,0.0986044f},{-0.304042f,0.000488516f,0.100469f},{-0.304042f,0.000488516f,0.0986044f}, +{-0.304085f,3.42486e-019f,0.0986044f},{-0.304085f,3.42486e-019f,0.100469f},{-0.3008f,0.00275356f,0.100469f}, +{-0.300331f,0.00262748f,0.100469f},{-0.300801f,0.00275376f,0.0986044f},{-0.299893f,0.00242333f,0.0986044f}, +{-0.300332f,0.00262801f,0.0986044f},{-0.299891f,0.00242266f,0.100469f},{-0.299493f,0.00214411f,0.0986044f}, +{-0.299491f,0.00214219f,0.100469f},{-0.299146f,0.00179767f,0.0986044f},{-0.298866f,0.00139727f,0.0986044f}, +{-0.299144f,0.00179504f,0.100469f},{-0.298865f,0.00139564f,0.100469f},{-0.298661f,0.000957717f,0.0986044f}, +{-0.298661f,0.000956449f,0.100469f},{-0.298535f,0.000488516f,0.0986044f},{-0.298535f,0.000488516f,0.100469f}, +{-0.298492f,0.0f,0.100469f},{-0.298492f,0.0f,0.0986044f},{-0.301289f,0.00745764f,0.100469f}, +{-0.302026f,0.00742114f,0.100469f},{-0.301289f,0.00745764f,0.101401f},{-0.302026f,0.00742114f,0.101401f}, +{-0.30275f,0.00731301f,0.100469f},{-0.303457f,0.00713527f,0.100469f},{-0.30275f,0.00731301f,0.101401f}, +{-0.304142f,0.00688994f,0.100469f},{-0.303457f,0.00713527f,0.101401f},{-0.304142f,0.00688994f,0.101401f}, +{-0.3048f,0.00657906f,0.100469f},{-0.305426f,0.00620465f,0.100469f},{-0.3048f,0.00657906f,0.101401f}, +{-0.306015f,0.00576874f,0.100469f},{-0.305426f,0.00620465f,0.101401f},{-0.306015f,0.00576874f,0.101401f}, +{-0.306562f,0.00527335f,0.100469f},{-0.307057f,0.00472635f,0.100469f},{-0.306562f,0.00527335f,0.101401f}, +{-0.307493f,0.00413751f,0.100469f},{-0.307057f,0.00472635f,0.101401f},{-0.307493f,0.00413751f,0.101401f}, +{-0.307868f,0.00351173f,0.100469f},{-0.308178f,0.00285391f,0.100469f},{-0.307868f,0.00351173f,0.101401f}, +{-0.308424f,0.00216893f,0.100469f},{-0.308178f,0.00285391f,0.101401f},{-0.308424f,0.00216893f,0.101401f}, +{-0.308602f,0.00146169f,0.100469f},{-0.30871f,0.000737081f,0.100469f},{-0.308602f,0.00146169f,0.101401f}, +{-0.308746f,9.13297e-019f,0.100469f},{-0.30871f,0.000737081f,0.101401f},{-0.308746f,9.13297e-019f,0.101401f}, +{-0.300551f,0.00742114f,0.101401f},{-0.299827f,0.00731301f,0.101401f},{-0.300551f,0.00742114f,0.100469f}, +{-0.29912f,0.00713527f,0.101401f},{-0.299827f,0.00731301f,0.100469f},{-0.29912f,0.00713527f,0.100469f}, +{-0.298435f,0.00688994f,0.101401f},{-0.297777f,0.00657906f,0.101401f},{-0.298435f,0.00688994f,0.100469f}, +{-0.297151f,0.00620465f,0.101401f},{-0.297777f,0.00657906f,0.100469f},{-0.297151f,0.00620465f,0.100469f}, +{-0.296562f,0.00576874f,0.101401f},{-0.296015f,0.00527335f,0.101401f},{-0.296562f,0.00576874f,0.100469f}, +{-0.29552f,0.00472635f,0.101401f},{-0.296015f,0.00527335f,0.100469f},{-0.29552f,0.00472635f,0.100469f}, +{-0.295084f,0.00413751f,0.101401f},{-0.294709f,0.00351173f,0.101401f},{-0.295084f,0.00413751f,0.100469f}, +{-0.294399f,0.00285391f,0.101401f},{-0.294709f,0.00351173f,0.100469f},{-0.294399f,0.00285391f,0.100469f}, +{-0.294153f,0.00216893f,0.101401f},{-0.293976f,0.00146169f,0.101401f},{-0.294153f,0.00216893f,0.100469f}, +{-0.293867f,0.000737081f,0.101401f},{-0.293976f,0.00146169f,0.100469f},{-0.293867f,0.000737081f,0.100469f}, +{-0.293831f,0.0f,0.101401f},{-0.293831f,0.0f,0.100469f},{-0.305909f,0.0173925f,0.101401f}, +{-0.305909f,0.0173922f,0.104198f},{-0.30595f,0.0167797f,0.101401f},{-0.305909f,0.0161668f,0.104198f}, +{-0.305909f,0.0161672f,0.101401f},{-0.30595f,0.0167797f,0.104198f},{-0.305595f,0.014996f,0.101401f}, +{-0.305595f,0.014996f,0.104198f},{-0.305327f,0.0144523f,0.101401f},{-0.30579f,0.0155699f,0.104198f}, +{-0.30579f,0.0155702f,0.101401f},{-0.305327f,0.0144519f,0.104198f},{-0.304989f,0.0139455f,0.104198f}, +{-0.304989f,0.0139458f,0.101401f},{-0.304584f,0.0134838f,0.101401f},{-0.304584f,0.0134838f,0.104198f}, +{-0.304122f,0.0130791f,0.104198f},{-0.304123f,0.0130793f,0.101401f},{-0.303616f,0.0127415f,0.101401f}, +{-0.303616f,0.0127414f,0.104198f},{-0.303072f,0.0124735f,0.101401f},{-0.303072f,0.0124735f,0.104198f}, +{-0.302498f,0.0122783f,0.104198f},{-0.302498f,0.0122784f,0.101401f},{-0.301289f,0.0121187f,0.101401f}, +{-0.301901f,0.0121592f,0.101401f},{-0.301901f,0.012159f,0.104198f},{-0.301289f,0.0121187f,0.104198f}, +{-0.30579f,0.0179891f,0.104198f},{-0.30579f,0.0179895f,0.101401f},{-0.305595f,0.0185634f,0.104198f}, +{-0.305327f,0.0191071f,0.104198f},{-0.305595f,0.0185634f,0.101401f},{-0.305327f,0.0191075f,0.101401f}, +{-0.304989f,0.0196135f,0.104198f},{-0.304989f,0.0196139f,0.101401f},{-0.304584f,0.0200755f,0.104198f}, +{-0.304123f,0.0204801f,0.104198f},{-0.304584f,0.0200755f,0.101401f},{-0.304122f,0.0204802f,0.101401f}, +{-0.303616f,0.0208179f,0.104198f},{-0.303616f,0.020818f,0.101401f},{-0.303072f,0.0210859f,0.104198f}, +{-0.302498f,0.0212809f,0.104198f},{-0.303072f,0.0210859f,0.101401f},{-0.302498f,0.0212811f,0.101401f}, +{-0.301901f,0.0214002f,0.104198f},{-0.301901f,0.0214003f,0.101401f},{-0.301289f,0.0214407f,0.104198f}, +{-0.301289f,0.0214407f,0.101401f},{-0.283896f,0.00462066f,0.101401f},{-0.284509f,0.00466102f,0.101401f}, +{-0.283896f,0.00462066f,0.104198f},{-0.285122f,0.00462052f,0.104198f},{-0.284509f,0.00466102f,0.104198f}, +{-0.285122f,0.00462052f,0.101401f},{-0.286293f,0.00430621f,0.101401f},{-0.286837f,0.00403818f,0.101401f}, +{-0.286293f,0.00430621f,0.104198f},{-0.285719f,0.00450127f,0.104198f},{-0.285719f,0.00450127f,0.101401f}, +{-0.286837f,0.00403818f,0.104198f},{-0.287343f,0.00370041f,0.101401f},{-0.287343f,0.00370041f,0.104198f}, +{-0.287805f,0.00329584f,0.101401f},{-0.287805f,0.00329584f,0.104198f},{-0.288209f,0.00283386f,0.101401f}, +{-0.288209f,0.00283386f,0.104198f},{-0.288547f,0.00232743f,0.101401f},{-0.288815f,0.00178369f,0.101401f}, +{-0.288547f,0.00232743f,0.104198f},{-0.288815f,0.00178369f,0.104198f},{-0.28901f,0.00120944f,0.101401f}, +{-0.28901f,0.00120944f,0.104198f},{-0.28917f,-2.05485e-018f,0.101401f},{-0.28913f,0.000612502f,0.104198f}, +{-0.28913f,0.000612502f,0.101401f},{-0.28917f,-2.05485e-018f,0.104198f},{-0.283299f,0.00450141f,0.104198f}, +{-0.282725f,0.00430621f,0.104198f},{-0.283299f,0.00450141f,0.101401f},{-0.282181f,0.00403832f,0.104198f}, +{-0.282725f,0.00430621f,0.101401f},{-0.282181f,0.00403832f,0.101401f},{-0.281675f,0.00370055f,0.104198f}, +{-0.281213f,0.00329584f,0.104198f},{-0.281675f,0.00370055f,0.101401f},{-0.280808f,0.0028342f,0.104198f}, +{-0.281213f,0.00329584f,0.101401f},{-0.280808f,0.0028342f,0.101401f},{-0.280471f,0.00232777f,0.104198f}, +{-0.280203f,0.00178369f,0.104198f},{-0.280471f,0.00232777f,0.101401f},{-0.280008f,0.00120978f,0.104198f}, +{-0.280203f,0.00178369f,0.101401f},{-0.280008f,0.00120978f,0.101401f},{-0.279888f,0.000612842f,0.104198f}, +{-0.279848f,-1.48404e-018f,0.104198f},{-0.279888f,0.000612842f,0.101401f},{-0.279848f,-1.48404e-018f,0.101401f}, +{-0.296668f,-0.0173922f,0.104198f},{-0.296628f,-0.0167797f,0.104198f},{-0.296641f,-0.0171394f,0.101401f}, +{-0.2967f,-0.0159621f,0.101401f},{-0.296633f,-0.0165489f,0.101401f},{-0.296668f,-0.0161668f,0.104198f}, +{-0.296982f,-0.014996f,0.104198f},{-0.29725f,-0.0144519f,0.104198f},{-0.297052f,-0.0148373f,0.101401f}, +{-0.29684f,-0.0153885f,0.101401f},{-0.296787f,-0.0155699f,0.104198f},{-0.297588f,-0.0139455f,0.104198f}, +{-0.297675f,-0.0138368f,0.101401f},{-0.297331f,-0.0143174f,0.101401f},{-0.297993f,-0.0134838f,0.104198f}, +{-0.298455f,-0.0130791f,0.104198f},{-0.298528f,-0.0130241f,0.101401f},{-0.298076f,-0.0134033f,0.101401f}, +{-0.298961f,-0.0127414f,0.104198f},{-0.299505f,-0.0124735f,0.104198f},{-0.299025f,-0.0127048f,0.101401f}, +{-0.300079f,-0.0122783f,0.104198f},{-0.30012f,-0.0122704f,0.101401f},{-0.299559f,-0.0124544f,0.101401f}, +{-0.300699f,-0.0121554f,0.101401f},{-0.300676f,-0.012159f,0.104198f},{-0.301289f,-0.0121187f,0.104198f}, +{-0.301289f,-0.0121187f,0.101401f},{-0.296724f,-0.0177242f,0.101401f},{-0.29688f,-0.018294f,0.101401f}, +{-0.296787f,-0.0179891f,0.104198f},{-0.296982f,-0.0185634f,0.104198f},{-0.297107f,-0.0188393f,0.101401f}, +{-0.297401f,-0.0193514f,0.101401f},{-0.29725f,-0.0191071f,0.104198f},{-0.297757f,-0.0198223f,0.101401f}, +{-0.297588f,-0.0196135f,0.104198f},{-0.297993f,-0.0200755f,0.104198f},{-0.29817f,-0.0202443f,0.101401f}, +{-0.298633f,-0.0206107f,0.101401f},{-0.298454f,-0.0204801f,0.104198f},{-0.299139f,-0.0209155f,0.101401f}, +{-0.298961f,-0.0208179f,0.104198f},{-0.299505f,-0.0210859f,0.104198f},{-0.299679f,-0.0211542f,0.101401f}, +{-0.300248f,-0.0213103f,0.101401f},{-0.300079f,-0.0212809f,0.104198f},{-0.300827f,-0.0214362f,0.101401f}, +{-0.300676f,-0.0214002f,0.104198f},{-0.301289f,-0.0214407f,0.104198f},{-0.301289f,-0.0214407f,0.101401f}, +{-0.315677f,0.0125242f,0.110723f},{-0.315667f,0.01233f,0.101401f},{-0.315667f,0.0127201f,0.101401f}, +{-0.315586f,0.0131013f,0.101401f},{-0.315641f,0.0128878f,0.110723f},{-0.315536f,0.0132379f,0.110723f}, +{-0.315197f,0.0137725f,0.101401f},{-0.315363f,0.0135608f,0.110723f},{-0.315427f,0.0134567f,0.101401f}, +{-0.314908f,0.014033f,0.101401f},{-0.315131f,0.0138436f,0.110723f},{-0.314849f,0.0140755f,0.110723f}, +{-0.314571f,0.0142276f,0.101401f},{-0.314201f,0.0143478f,0.101401f},{-0.314526f,0.0142478f,0.110723f}, +{-0.313813f,0.0143886f,0.101401f},{-0.313813f,0.0143886f,0.110723f},{-0.314176f,0.0143539f,0.110723f}, +{-0.315641f,0.01216f,0.110723f},{-0.315586f,0.0119486f,0.101401f},{-0.315534f,0.0118103f,0.110723f}, +{-0.315361f,0.0114885f,0.110723f},{-0.315428f,0.0115926f,0.101401f},{-0.315129f,0.0112063f,0.110723f}, +{-0.315199f,0.0112779f,0.101401f},{-0.314909f,0.0110163f,0.101401f},{-0.314847f,0.0109746f,0.110723f}, +{-0.314525f,0.0108025f,0.110723f},{-0.314571f,0.0108212f,0.101401f},{-0.314176f,0.0106963f,0.110723f}, +{-0.314202f,0.0107009f,0.101401f},{-0.313813f,0.0106598f,0.101401f},{-0.313813f,0.0106598f,0.110723f}, +{-0.313813f,0.0125242f,0.111843f},{-0.292606f,0.0105467f,0.110723f},{-0.292596f,0.0103525f,0.101401f}, +{-0.292596f,0.0107426f,0.101401f},{-0.292515f,0.0111238f,0.101401f},{-0.29257f,0.0109103f,0.110723f}, +{-0.292465f,0.0112604f,0.110723f},{-0.292127f,0.011795f,0.101401f},{-0.292293f,0.0115833f,0.110723f}, +{-0.292356f,0.0114792f,0.101401f},{-0.291837f,0.0120555f,0.101401f},{-0.29206f,0.0118661f,0.110723f}, +{-0.291778f,0.012098f,0.110723f},{-0.2915f,0.0122501f,0.101401f},{-0.29113f,0.0123703f,0.101401f}, +{-0.291455f,0.0122703f,0.110723f},{-0.290742f,0.0124111f,0.101401f},{-0.290742f,0.0124111f,0.110723f}, +{-0.291106f,0.0123763f,0.110723f},{-0.29257f,0.0101825f,0.110723f},{-0.292515f,0.00997107f,0.101401f}, +{-0.292463f,0.00983283f,0.110723f},{-0.29229f,0.00951095f,0.110723f},{-0.292357f,0.00961513f,0.101401f}, +{-0.292059f,0.00922876f,0.110723f},{-0.292128f,0.00930035f,0.101401f},{-0.291838f,0.00903878f,0.101401f}, +{-0.291776f,0.0089971f,0.110723f},{-0.291454f,0.008825f,0.110723f},{-0.291501f,0.00884365f,0.101401f}, +{-0.291105f,0.00871884f,0.110723f},{-0.291131f,0.00872342f,0.101401f},{-0.290742f,0.00868228f,0.101401f}, +{-0.290742f,0.00868228f,0.110723f},{-0.290742f,0.0105467f,0.111843f},{-0.290629f,-0.0125242f,0.110723f}, +{-0.290619f,-0.0127183f,0.101401f},{-0.290618f,-0.0123283f,0.101401f},{-0.290537f,-0.0119471f,0.101401f}, +{-0.290593f,-0.0121606f,0.110723f},{-0.290487f,-0.0118105f,0.110723f},{-0.290149f,-0.0112759f,0.101401f}, +{-0.290315f,-0.0114876f,0.110723f},{-0.290379f,-0.0115917f,0.101401f},{-0.289859f,-0.0110154f,0.101401f}, +{-0.290083f,-0.0112048f,0.110723f},{-0.2898f,-0.0109729f,0.110723f},{-0.289522f,-0.0108208f,0.101401f}, +{-0.289152f,-0.0107006f,0.101401f},{-0.289478f,-0.0108006f,0.110723f},{-0.288764f,-0.0106598f,0.101401f}, +{-0.288764f,-0.0106598f,0.110723f},{-0.289128f,-0.0106945f,0.110723f},{-0.290592f,-0.0128884f,0.110723f}, +{-0.290538f,-0.0130998f,0.101401f},{-0.290485f,-0.0132381f,0.110723f},{-0.290313f,-0.0135599f,0.110723f}, +{-0.290379f,-0.0134558f,0.101401f},{-0.290081f,-0.0138421f,0.110723f},{-0.290151f,-0.0137705f,0.101401f}, +{-0.289861f,-0.0140321f,0.101401f},{-0.289799f,-0.0140738f,0.110723f},{-0.289477f,-0.0142459f,0.110723f}, +{-0.289523f,-0.0142272f,0.101401f},{-0.289127f,-0.0143521f,0.110723f},{-0.289153f,-0.0143475f,0.101401f}, +{-0.288764f,-0.0143886f,0.101401f},{-0.288764f,-0.0143886f,0.110723f},{-0.288764f,-0.0125242f,0.111843f}, +{-0.3137f,-0.0105467f,0.110723f},{-0.313689f,-0.0107408f,0.101401f},{-0.313689f,-0.0103508f,0.101401f}, +{-0.313608f,-0.0099696f,0.101401f},{-0.313664f,-0.010183f,0.110723f},{-0.313558f,-0.00983297f,0.110723f}, +{-0.31322f,-0.00929843f,0.101401f},{-0.313386f,-0.00951009f,0.110723f},{-0.31345f,-0.00961418f,0.101401f}, +{-0.31293f,-0.00903788f,0.101401f},{-0.313154f,-0.0092273f,0.110723f},{-0.312871f,-0.00899543f,0.110723f}, +{-0.312593f,-0.00884326f,0.101401f},{-0.312223f,-0.0087231f,0.101401f},{-0.312549f,-0.00882313f,0.110723f}, +{-0.311835f,-0.00868228f,0.101401f},{-0.311835f,-0.00868228f,0.110723f},{-0.312199f,-0.00871703f,0.110723f}, +{-0.313663f,-0.0109109f,0.110723f},{-0.313609f,-0.0111223f,0.101401f},{-0.313556f,-0.0112606f,0.110723f}, +{-0.313384f,-0.0115824f,0.110723f},{-0.31345f,-0.0114782f,0.101401f},{-0.313152f,-0.0118646f,0.110723f}, +{-0.313222f,-0.011793f,0.101401f},{-0.312932f,-0.0120546f,0.101401f},{-0.31287f,-0.0120963f,0.110723f}, +{-0.312548f,-0.0122684f,0.110723f},{-0.312594f,-0.0122497f,0.101401f},{-0.312198f,-0.0123745f,0.110723f}, +{-0.312224f,-0.01237f,0.101401f},{-0.311835f,-0.0124111f,0.101401f},{-0.311835f,-0.0124111f,0.110723f}, +{-0.311835f,-0.0105467f,0.111843f},{-0.318681f,-0.00462052f,0.101401f},{-0.318681f,-0.00462066f,0.104198f}, +{-0.318068f,-0.00466102f,0.101401f},{-0.317455f,-0.00462052f,0.104198f},{-0.317456f,-0.00462066f,0.101401f}, +{-0.318068f,-0.00466102f,0.104198f},{-0.316285f,-0.00430621f,0.101401f},{-0.316285f,-0.00430621f,0.104198f}, +{-0.315741f,-0.00403832f,0.101401f},{-0.316858f,-0.00450127f,0.104198f},{-0.316859f,-0.00450141f,0.101401f}, +{-0.31574f,-0.00403818f,0.104198f},{-0.315234f,-0.00370041f,0.104198f},{-0.315234f,-0.00370055f,0.101401f}, +{-0.314772f,-0.00329584f,0.101401f},{-0.314772f,-0.00329584f,0.104198f},{-0.314368f,-0.00283386f,0.104198f}, +{-0.314368f,-0.0028342f,0.101401f},{-0.31403f,-0.00232777f,0.101401f},{-0.31403f,-0.00232743f,0.104198f}, +{-0.313762f,-0.00178369f,0.101401f},{-0.313762f,-0.00178369f,0.104198f},{-0.313567f,-0.00120944f,0.104198f}, +{-0.313567f,-0.00120978f,0.101401f},{-0.313407f,5.70811e-019f,0.101401f},{-0.313448f,-0.000612842f,0.101401f}, +{-0.313448f,-0.000612502f,0.104198f},{-0.313407f,5.70811e-019f,0.104198f},{-0.319278f,-0.00450141f,0.104198f}, +{-0.319278f,-0.00450127f,0.101401f},{-0.319852f,-0.00430621f,0.104198f},{-0.320396f,-0.00403832f,0.104198f}, +{-0.319852f,-0.00430621f,0.101401f},{-0.320396f,-0.00403818f,0.101401f},{-0.320902f,-0.00370055f,0.104198f}, +{-0.320902f,-0.00370041f,0.101401f},{-0.321364f,-0.00329584f,0.104198f},{-0.321769f,-0.0028342f,0.104198f}, +{-0.321364f,-0.00329584f,0.101401f},{-0.321769f,-0.00283386f,0.101401f},{-0.322106f,-0.00232777f,0.104198f}, +{-0.322107f,-0.00232743f,0.101401f},{-0.322374f,-0.00178369f,0.104198f},{-0.322569f,-0.00120978f,0.104198f}, +{-0.322374f,-0.00178369f,0.101401f},{-0.32257f,-0.00120944f,0.101401f},{-0.322689f,-0.000612842f,0.104198f}, +{-0.322689f,-0.000612502f,0.101401f},{-0.322729f,1.4722e-032f,0.104198f},{-0.322729f,1.4722e-032f,0.101401f}, +{-0.275798f,0.00272711f,0.121909f},{-0.27569f,0.00137858f,0.120045f},{-0.2758f,0.00274679f,0.120045f}, +{-0.276233f,0.00542344f,0.121909f},{-0.276237f,0.00544141f,0.120045f},{-0.276561f,0.00676244f,0.120045f}, +{-0.275689f,0.00136573f,0.121909f},{-0.275653f,3.13946e-018f,0.120045f},{-0.275653f,1.34638e-013f,0.121909f}, +{-0.27598f,0.0040808f,0.121909f},{-0.275983f,0.00410196f,0.120045f},{-0.277098f,0.00848488f,0.121909f}, +{-0.276634f,0.00696342f,0.121909f},{-0.276954f,0.00806238f,0.120045f},{-0.279087f,0.0128178f,0.121909f}, +{-0.278335f,0.0114155f,0.121909f},{-0.278535f,0.0118088f,0.120045f},{-0.277671f,0.00996949f,0.121909f}, +{-0.277414f,0.00933854f,0.120045f},{-0.277942f,0.0105882f,0.120045f},{-0.280696f,0.0152688f,0.120045f}, +{-0.28154f,0.0163461f,0.120045f},{-0.280846f,0.0154686f,0.121909f},{-0.279192f,0.0129975f,0.120045f}, +{-0.279913f,0.0141518f,0.120045f},{-0.279925f,0.0141704f,0.121909f},{-0.283407f,0.0183698f,0.120045f}, +{-0.284064f,0.0189869f,0.121909f},{-0.282925f,0.017875f,0.121909f},{-0.282445f,0.0173811f,0.120045f}, +{-0.281845f,0.0167072f,0.121909f},{-0.287538f,0.0216356f,0.121909f},{-0.285747f,0.0203871f,0.121909f}, +{-0.286574f,0.0209918f,0.120045f},{-0.28442f,0.0193037f,0.120045f},{-0.290086f,0.0230585f,0.120045f}, +{-0.291322f,0.0236188f,0.120045f},{-0.291403f,0.0236531f,0.121909f},{-0.288881f,0.0224332f,0.120045f}, +{-0.289427f,0.0227263f,0.121909f},{-0.295184f,0.0248983f,0.120045f},{-0.295163f,0.024878f,0.121909f}, +{-0.293873f,0.0245398f,0.120045f},{-0.293458f,0.0244103f,0.121909f},{-0.292585f,0.0241129f,0.120045f}, +{-0.298641f,0.0254985f,0.121909f},{-0.297863f,0.0254058f,0.120045f},{-0.299225f,0.0255525f,0.120045f}, +{-0.296515f,0.0251874f,0.120045f},{-0.296889f,0.0252555f,0.121909f},{-0.300404f,0.0256204f,0.121909f}, +{-0.301979f,0.0256263f,0.120045f},{-0.302172f,0.0256204f,0.121909f},{-0.300599f,0.0256264f,0.120045f}, +{-0.304715f,0.0254057f,0.120045f},{-0.306062f,0.0251873f,0.120045f},{-0.305688f,0.0252554f,0.121909f}, +{-0.303936f,0.0254985f,0.121909f},{-0.303353f,0.0255524f,0.120045f},{-0.309992f,0.0241129f,0.120045f}, +{-0.309119f,0.0244103f,0.121909f},{-0.308704f,0.0245398f,0.120045f},{-0.307416f,0.0248864f,0.121909f}, +{-0.307393f,0.0248983f,0.120045f},{-0.31315f,0.0227264f,0.121909f},{-0.311173f,0.0236533f,0.121909f}, +{-0.312491f,0.0230584f,0.120045f},{-0.311255f,0.0236187f,0.120045f},{-0.315039f,0.0216357f,0.121909f}, +{-0.314868f,0.0217438f,0.120045f},{-0.316004f,0.0209917f,0.120045f},{-0.313696f,0.0224331f,0.120045f}, +{-0.318157f,0.0193036f,0.120045f},{-0.31917f,0.0183692f,0.120045f},{-0.318513f,0.0189869f,0.121909f}, +{-0.31683f,0.0203873f,0.121909f},{-0.317101f,0.020178f,0.120045f},{-0.320133f,0.0173806f,0.120045f}, +{-0.321037f,0.016346f,0.120045f},{-0.320732f,0.0167073f,0.121909f},{-0.319646f,0.0178697f,0.121909f}, +{-0.321731f,0.0154687f,0.121909f},{-0.321881f,0.0152688f,0.120045f},{-0.322664f,0.0141517f,0.120045f}, +{-0.322652f,0.0141707f,0.121909f},{-0.323385f,0.0129974f,0.120045f},{-0.32349f,0.0128178f,0.121909f}, +{-0.324042f,0.0118086f,0.120045f},{-0.324242f,0.0114158f,0.121909f},{-0.324906f,0.0099697f,0.121909f}, +{-0.324635f,0.010588f,0.120045f},{-0.325163f,0.00933828f,0.120045f},{-0.325479f,0.00848516f,0.121909f}, +{-0.325623f,0.00806211f,0.120045f},{-0.32595f,0.00696571f,0.121909f},{-0.326344f,0.00542344f,0.121909f}, +{-0.326016f,0.00676218f,0.120045f},{-0.326594f,0.00410176f,0.120045f},{-0.32634f,0.00544117f,0.120045f}, +{-0.326777f,0.00274665f,0.120045f},{-0.326597f,0.00408095f,0.121909f},{-0.326779f,0.00272732f,0.121909f}, +{-0.326887f,0.0013785f,0.120045f},{-0.326924f,0.0f,0.120045f},{-0.326888f,0.00136552f,0.121909f}, +{-0.326924f,-1.34635e-013f,0.121909f},{-0.28771f,0.0217439f,0.120045f},{-0.285476f,0.0201781f,0.120045f}, +{-0.276585f,-3.95917e-017f,0.104011f},{-0.275187f,-8.69362e-018f,0.10513f},{-0.275244f,-0.00172399f,0.10513f}, +{-0.286411f,0.0173288f,0.10252f},{-0.287162f,0.0161291f,0.101401f},{-0.288252f,0.0170222f,0.101401f}, +{-0.286128f,0.0151609f,0.101401f},{-0.2881f,0.0186467f,0.10252f},{-0.286807f,0.0217163f,0.10513f}, +{-0.288937f,0.0213938f,0.104011f},{-0.288254f,0.0226142f,0.10513f},{-0.289393f,0.0178384f,0.101401f}, +{-0.289869f,0.0197792f,0.10252f},{-0.289753f,0.0234144f,0.10513f},{-0.291813f,0.0192333f,0.101401f}, +{-0.2913f,0.0241148f,0.10513f},{-0.293084f,0.0198086f,0.101401f},{-0.292889f,0.0247131f,0.10513f}, +{-0.294389f,0.0203001f,0.101401f},{-0.295724f,0.0207061f,0.101401f},{-0.294514f,0.0252074f,0.10513f}, +{-0.297086f,0.0210249f,0.101401f},{-0.296173f,0.0255955f,0.10513f},{-0.297858f,0.0258753f,0.10513f}, +{-0.29847f,0.0212548f,0.101401f},{-0.299565f,0.0260447f,0.10513f},{-0.299873f,0.021394f,0.101401f}, +{-0.301289f,0.0261017f,0.10513f},{-0.284828f,0.0158329f,0.10252f},{-0.285159f,0.0141266f,0.101401f}, +{-0.283379f,0.0141734f,0.10252f},{-0.284266f,0.0130367f,0.101401f},{-0.28345f,0.0118953f,0.101401f}, +{-0.282089f,0.0123685f,0.10252f},{-0.282713f,0.010707f,0.101401f},{-0.280977f,0.0104425f,0.10252f}, +{-0.282055f,0.00947547f,0.101401f},{-0.280059f,0.00842229f,0.10252f},{-0.28148f,0.00820499f,0.101401f}, +{-0.276081f,0.00677384f,0.10513f},{-0.275693f,0.00511591f,0.10513f},{-0.27701f,0.0045642f,0.104011f}, +{-0.279347f,0.00633756f,0.10252f},{-0.280988f,0.0069f,0.101401f},{-0.278843f,0.00421935f,0.10252f}, +{-0.280582f,0.00556442f,0.101401f},{-0.280264f,0.00420236f,0.101401f},{-0.278546f,0.00209692f,0.10252f}, +{-0.280034f,0.00281829f,0.101401f},{-0.275244f,0.00172376f,0.10513f},{-0.27845f,-3.77853e-017f,0.10252f}, +{-0.279895f,0.00141614f,0.101401f},{-0.280042f,-0.00288015f,0.101401f},{-0.279896f,-0.00144343f,0.101401f}, +{-0.275413f,-0.00343096f,0.10513f},{-0.281053f,-0.00708591f,0.101401f},{-0.280622f,-0.00570761f,0.101401f}, +{-0.276575f,-0.0084f,0.10513f},{-0.280284f,-0.00430368f,0.101401f},{-0.275693f,-0.00511591f,0.10513f}, +{-0.276081f,-0.00677408f,0.10513f},{-0.282188f,-0.00973971f,0.101401f},{-0.278674f,-0.0130346f,0.10513f}, +{-0.282887f,-0.0110032f,0.101401f},{-0.277174f,-0.00998868f,0.10513f},{-0.277874f,-0.0115354f,0.10513f}, +{-0.281576f,-0.00843197f,0.101401f},{-0.280566f,-0.0158708f,0.10513f},{-0.281653f,-0.0171976f,0.10513f}, +{-0.284531f,-0.0133753f,0.101401f},{-0.283669f,-0.012217f,0.101401f},{-0.279572f,-0.0144813f,0.10513f}, +{-0.285418f,-0.0207227f,0.10513f},{-0.287557f,-0.0164663f,0.101401f},{-0.284091f,-0.0196355f,0.10513f}, +{-0.28648f,-0.0155046f,0.101401f},{-0.28547f,-0.0144728f,0.101401f},{-0.282832f,-0.0184567f,0.10513f}, +{-0.291141f,-0.0188871f,0.101401f},{-0.289893f,-0.0181615f,0.101401f},{-0.289869f,-0.0197792f,0.10252f}, +{-0.288696f,-0.0173533f,0.101401f},{-0.288937f,-0.0213938f,0.104011f},{-0.288254f,-0.0226143f,0.10513f}, +{-0.290308f,-0.0221291f,0.104011f},{-0.291745f,-0.0227855f,0.104011f},{-0.2913f,-0.0241148f,0.10513f}, +{-0.29324f,-0.0233556f,0.104011f},{-0.289753f,-0.0234145f,0.10513f},{-0.294786f,-0.0238322f,0.104011f}, +{-0.294515f,-0.0252075f,0.10513f},{-0.296374f,-0.0242096f,0.104011f},{-0.292889f,-0.0247132f,0.10513f}, +{-0.297994f,-0.0244827f,0.104011f},{-0.296173f,-0.0255955f,0.10513f},{-0.297858f,-0.0258754f,0.10513f}, +{-0.299565f,-0.0260448f,0.10513f},{-0.299636f,-0.0246481f,0.104011f},{-0.301289f,-0.0261017f,0.10513f}, +{-0.301289f,-0.0247034f,0.104011f},{-0.286807f,-0.0217163f,0.10513f},{-0.296745f,-0.0223824f,0.10252f}, +{-0.296535f,-0.0209041f,0.101401f},{-0.295277f,-0.0220336f,0.10252f},{-0.298242f,-0.022635f,0.10252f}, +{-0.297953f,-0.0211784f,0.101401f},{-0.299386f,-0.0213558f,0.101401f},{-0.29976f,-0.0227878f,0.10252f}, +{-0.301289f,-0.022839f,0.10252f},{-0.295138f,-0.0205399f,0.101401f},{-0.29377f,-0.0200791f,0.101401f}, +{-0.292465f,-0.0210659f,0.10252f},{-0.293848f,-0.0215929f,0.10252f},{-0.292435f,-0.0195273f,0.101401f}, +{-0.291137f,-0.0204589f,0.10252f},{-0.287025f,0.0201691f,0.104011f},{-0.290582f,0.018576f,0.101401f}, +{-0.285197f,0.0187435f,0.104011f},{-0.285418f,0.0207226f,0.10513f},{-0.282832f,0.0184567f,0.10513f}, +{-0.284091f,0.0196354f,0.10513f},{-0.283485f,0.017126f,0.104011f},{-0.281918f,0.015331f,0.104011f}, +{-0.281653f,0.0171974f,0.10513f},{-0.279572f,0.0144813f,0.10513f},{-0.280566f,0.0158706f,0.10513f}, +{-0.280522f,0.0133791f,0.104011f},{-0.279319f,0.011296f,0.104011f},{-0.278674f,0.0130343f,0.10513f}, +{-0.277874f,0.0115351f,0.10513f},{-0.278326f,0.00911062f,0.104011f},{-0.277174f,0.00998868f,0.10513f}, +{-0.277555f,0.00685616f,0.104011f},{-0.276575f,0.00839976f,0.10513f},{-0.276689f,0.00226928f,0.104011f}, +{-0.275413f,0.00343072f,0.10513f},{-0.279848f,3.60164e-017f,0.10513f},{-0.279848f,-9.52159e-018f,0.106062f}, +{-0.279885f,-0.00125938f,0.106062f},{-0.279995f,-0.00250813f,0.106062f},{-0.279885f,-0.00125925f,0.10513f}, +{-0.280177f,-0.00374334f,0.106062f},{-0.279995f,-0.00250793f,0.10513f},{-0.280177f,-0.00374312f,0.10513f}, +{-0.28043f,-0.00496208f,0.106062f},{-0.280752f,-0.00616144f,0.106062f},{-0.28043f,-0.00496191f,0.10513f}, +{-0.281143f,-0.00733859f,0.106062f},{-0.280752f,-0.00616138f,0.10513f},{-0.281143f,-0.0073385f,0.10513f}, +{-0.281601f,-0.00849054f,0.106062f},{-0.282124f,-0.0096143f,0.106062f},{-0.281601f,-0.00849036f,0.10513f}, +{-0.282713f,-0.010707f,0.106062f},{-0.282124f,-0.00961408f,0.10513f},{-0.282713f,-0.0107068f,0.10513f}, +{-0.283364f,-0.0117656f,0.106062f},{-0.284078f,-0.0127873f,0.106062f},{-0.283364f,-0.0117655f,0.10513f}, +{-0.284853f,-0.0137693f,0.106062f},{-0.284078f,-0.0127873f,0.10513f},{-0.284853f,-0.0137691f,0.10513f}, +{-0.285689f,-0.0147088f,0.106062f},{-0.28658f,-0.0156004f,0.106062f},{-0.285688f,-0.0147082f,0.10513f}, +{-0.287519f,-0.0164352f,0.106062f},{-0.28658f,-0.0155998f,0.10513f},{-0.287519f,-0.0164352f,0.10513f}, +{-0.288501f,-0.0172102f,0.106062f},{-0.289523f,-0.0179243f,0.106062f},{-0.288501f,-0.0172102f,0.10513f}, +{-0.290582f,-0.018576f,0.106062f},{-0.289523f,-0.0179242f,0.10513f},{-0.290582f,-0.018576f,0.10513f}, +{-0.291674f,-0.0191643f,0.106062f},{-0.292798f,-0.019688f,0.106062f},{-0.291674f,-0.0191643f,0.10513f}, +{-0.29395f,-0.0201457f,0.106062f},{-0.292798f,-0.0196879f,0.10513f},{-0.29395f,-0.0201457f,0.10513f}, +{-0.295127f,-0.0205363f,0.106062f},{-0.296327f,-0.0208587f,0.106062f},{-0.295127f,-0.0205363f,0.10513f}, +{-0.296326f,-0.0208586f,0.10513f},{-0.297545f,-0.0211114f,0.10513f},{-0.29878f,-0.0212935f,0.10513f}, +{-0.297545f,-0.0211115f,0.106062f},{-0.300029f,-0.0214037f,0.106062f},{-0.298781f,-0.0212936f,0.106062f}, +{-0.301289f,-0.0214407f,0.106062f},{-0.300029f,-0.0214037f,0.10513f},{-0.301289f,-0.0214407f,0.10513f}, +{-0.279885f,0.00125938f,0.10513f},{-0.279995f,0.00250813f,0.10513f},{-0.279885f,0.00125925f,0.106062f}, +{-0.279995f,0.00250793f,0.106062f},{-0.280177f,0.00374334f,0.10513f},{-0.28043f,0.00496208f,0.10513f}, +{-0.280177f,0.00374312f,0.106062f},{-0.280752f,0.00616144f,0.10513f},{-0.28043f,0.00496191f,0.106062f}, +{-0.280752f,0.00616138f,0.106062f},{-0.281143f,0.00733859f,0.10513f},{-0.281601f,0.00849054f,0.10513f}, +{-0.281143f,0.0073385f,0.106062f},{-0.282124f,0.0096143f,0.10513f},{-0.281601f,0.00849036f,0.106062f}, +{-0.282124f,0.00961408f,0.106062f},{-0.282713f,0.010707f,0.10513f},{-0.283364f,0.0117656f,0.10513f}, +{-0.282713f,0.0107068f,0.106062f},{-0.284078f,0.0127873f,0.10513f},{-0.283364f,0.0117655f,0.106062f}, +{-0.284078f,0.0127873f,0.106062f},{-0.284853f,0.0137693f,0.10513f},{-0.285689f,0.0147088f,0.10513f}, +{-0.284853f,0.0137691f,0.106062f},{-0.28658f,0.0156004f,0.10513f},{-0.285688f,0.0147082f,0.106062f}, +{-0.28658f,0.0155998f,0.106062f},{-0.287519f,0.0164352f,0.10513f},{-0.288501f,0.0172102f,0.10513f}, +{-0.287519f,0.0164352f,0.106062f},{-0.289523f,0.0179243f,0.10513f},{-0.288501f,0.0172102f,0.106062f}, +{-0.289523f,0.0179242f,0.106062f},{-0.290582f,0.018576f,0.10513f},{-0.291674f,0.0191643f,0.10513f}, +{-0.290582f,0.018576f,0.106062f},{-0.292798f,0.019688f,0.10513f},{-0.291674f,0.0191643f,0.106062f}, +{-0.292798f,0.0196879f,0.106062f},{-0.29395f,0.0201457f,0.10513f},{-0.295127f,0.0205363f,0.10513f}, +{-0.29395f,0.0201457f,0.106062f},{-0.296327f,0.0208587f,0.10513f},{-0.295127f,0.0205363f,0.106062f}, +{-0.297545f,0.0211114f,0.106062f},{-0.296326f,0.0208586f,0.106062f},{-0.297545f,0.0211115f,0.10513f}, +{-0.29878f,0.0212935f,0.106062f},{-0.298781f,0.0212936f,0.10513f},{-0.300029f,0.0214037f,0.10513f}, +{-0.300029f,0.0214037f,0.106062f},{-0.301289f,0.0214407f,0.10513f},{-0.301289f,0.0214407f,0.106062f}, +{-0.275187f,1.78012e-017f,0.106062f},{-0.275187f,2.1941e-017f,0.120045f},{-0.275223f,-0.00138032f,0.120045f}, +{-0.275332f,-0.00275048f,0.120045f},{-0.275223f,-0.00138025f,0.106062f},{-0.275512f,-0.0041079f,0.120045f}, +{-0.275332f,-0.00275036f,0.106062f},{-0.275512f,-0.00410773f,0.106062f},{-0.275762f,-0.00544996f,0.120045f}, +{-0.276081f,-0.00677408f,0.120045f},{-0.275762f,-0.00544975f,0.106062f},{-0.276468f,-0.00807765f,0.120045f}, +{-0.276081f,-0.00677384f,0.106062f},{-0.276468f,-0.0080774f,0.106062f},{-0.276922f,-0.00935809f,0.120045f}, +{-0.277442f,-0.0106128f,0.120045f},{-0.276922f,-0.00935782f,0.106062f},{-0.278026f,-0.0118391f,0.120045f}, +{-0.277442f,-0.0106125f,0.106062f},{-0.278026f,-0.0118389f,0.106062f},{-0.278674f,-0.0130346f,0.120045f}, +{-0.279385f,-0.0141964f,0.120045f},{-0.278674f,-0.0130343f,0.106062f},{-0.280157f,-0.0153222f,0.120045f}, +{-0.279385f,-0.0141962f,0.106062f},{-0.280157f,-0.015322f,0.106062f},{-0.28099f,-0.0164092f,0.120045f}, +{-0.281882f,-0.0174549f,0.120045f},{-0.28099f,-0.0164091f,0.106062f},{-0.282832f,-0.0184567f,0.120045f}, +{-0.281882f,-0.0174549f,0.106062f},{-0.282832f,-0.0184567f,0.106062f},{-0.283834f,-0.0194069f,0.120045f}, +{-0.284879f,-0.0202989f,0.120045f},{-0.283834f,-0.0194069f,0.106062f},{-0.285967f,-0.0211315f,0.120045f}, +{-0.284879f,-0.0202988f,0.106062f},{-0.285966f,-0.0211314f,0.106062f},{-0.287092f,-0.0219036f,0.120045f}, +{-0.288254f,-0.0226143f,0.120045f},{-0.287092f,-0.0219036f,0.106062f},{-0.28945f,-0.0232624f,0.120045f}, +{-0.288254f,-0.0226142f,0.106062f},{-0.289449f,-0.0232623f,0.106062f},{-0.290676f,-0.0238468f,0.120045f}, +{-0.291931f,-0.0243666f,0.120045f},{-0.290676f,-0.0238467f,0.106062f},{-0.293211f,-0.0248205f,0.120045f}, +{-0.29193f,-0.0243664f,0.106062f},{-0.293211f,-0.0248204f,0.106062f},{-0.294515f,-0.0252075f,0.120045f}, +{-0.295839f,-0.0255265f,0.120045f},{-0.294514f,-0.0252074f,0.106062f},{-0.297181f,-0.0257766f,0.120045f}, +{-0.295839f,-0.0255265f,0.106062f},{-0.297181f,-0.0257765f,0.106062f},{-0.298538f,-0.0259565f,0.120045f}, +{-0.299908f,-0.0260653f,0.120045f},{-0.298538f,-0.0259565f,0.106062f},{-0.301289f,-0.0261017f,0.120045f}, +{-0.299908f,-0.0260652f,0.106062f},{-0.301289f,-0.0261017f,0.106062f},{-0.275223f,0.00138032f,0.106062f}, +{-0.275332f,0.00275048f,0.106062f},{-0.275223f,0.00138025f,0.120045f},{-0.275332f,0.00275036f,0.120045f}, +{-0.275512f,0.0041079f,0.106062f},{-0.275762f,0.00544996f,0.106062f},{-0.275512f,0.00410773f,0.120045f}, +{-0.276081f,0.00677408f,0.106062f},{-0.275762f,0.00544975f,0.120045f},{-0.276081f,0.00677384f,0.120045f}, +{-0.276468f,0.00807765f,0.106062f},{-0.276922f,0.00935809f,0.106062f},{-0.276468f,0.0080774f,0.120045f}, +{-0.277442f,0.0106128f,0.106062f},{-0.276922f,0.00935782f,0.120045f},{-0.277442f,0.0106125f,0.120045f}, +{-0.278026f,0.0118391f,0.106062f},{-0.278674f,0.0130346f,0.106062f},{-0.278026f,0.0118389f,0.120045f}, +{-0.279385f,0.0141964f,0.106062f},{-0.278674f,0.0130343f,0.120045f},{-0.279385f,0.0141962f,0.120045f}, +{-0.280157f,0.0153222f,0.106062f},{-0.28099f,0.0164092f,0.106062f},{-0.280157f,0.015322f,0.120045f}, +{-0.281882f,0.0174549f,0.106062f},{-0.28099f,0.0164091f,0.120045f},{-0.281882f,0.0174549f,0.120045f}, +{-0.282832f,0.0184567f,0.106062f},{-0.283834f,0.0194069f,0.106062f},{-0.282832f,0.0184567f,0.120045f}, +{-0.284879f,0.0202989f,0.106062f},{-0.283834f,0.0194069f,0.120045f},{-0.284879f,0.0202988f,0.120045f}, +{-0.285967f,0.0211315f,0.106062f},{-0.287092f,0.0219036f,0.106062f},{-0.285966f,0.0211314f,0.120045f}, +{-0.288254f,0.0226143f,0.106062f},{-0.287092f,0.0219036f,0.120045f},{-0.288254f,0.0226142f,0.120045f}, +{-0.28945f,0.0232624f,0.106062f},{-0.290676f,0.0238468f,0.106062f},{-0.289449f,0.0232623f,0.120045f}, +{-0.291931f,0.0243666f,0.106062f},{-0.290676f,0.0238467f,0.120045f},{-0.29193f,0.0243664f,0.120045f}, +{-0.293211f,0.0248205f,0.106062f},{-0.294515f,0.0252075f,0.106062f},{-0.293211f,0.0248204f,0.120045f}, +{-0.295839f,0.0255265f,0.106062f},{-0.294514f,0.0252074f,0.120045f},{-0.295839f,0.0255265f,0.120045f}, +{-0.297181f,0.0257766f,0.106062f},{-0.298538f,0.0259565f,0.106062f},{-0.297181f,0.0257765f,0.120045f}, +{-0.299908f,0.0260653f,0.106062f},{-0.298538f,0.0259565f,0.120045f},{-0.299908f,0.0260652f,0.120045f}, +{-0.301289f,0.0261017f,0.106062f},{-0.301289f,0.0261017f,0.120045f},{-0.289155f,-0.00289006f,0.125638f}, +{-0.316278f,0.00596973f,0.125638f},{-0.316319f,0.00652514f,0.125638f},{-0.320415f,0.00374099f,0.125638f}, +{-0.309396f,-0.0152805f,0.125638f},{-0.309911f,0.0149353f,0.125638f},{-0.305018f,0.0130513f,0.125638f}, +{-0.309397f,0.0152802f,0.125638f},{-0.313508f,0.0144863f,0.125638f},{-0.314092f,0.0146944f,0.125638f}, +{-0.314299f,0.0103166f,0.125638f},{-0.296052f,0.00984656f,0.125638f},{-0.296433f,0.00992732f,0.125638f}, +{-0.303153f,0.0162797f,0.125638f},{-0.305069f,0.0215779f,0.125638f},{-0.307586f,0.019053f,0.125638f}, +{-0.29185f,0.00975506f,0.125638f},{-0.29211f,0.0146618f,0.125638f},{-0.292666f,0.0149353f,0.125638f}, +{-0.292311f,0.00944145f,0.125638f},{-0.284043f,9.3146e-019f,0.125638f},{-0.284001f,0.000618856f,0.125638f}, +{-0.290295f,0.0143109f,0.125638f},{-0.290264f,0.0102438f,0.125638f},{-0.289707f,0.0102437f,0.125638f}, +{-0.28049f,-0.00452954f,0.125638f},{-0.280243f,-0.00608354f,0.125638f},{-0.279878f,-0.00463457f,0.125638f}, +{-0.283879f,-0.00122583f,0.125638f},{-0.284002f,-0.000618365f,0.125638f},{-0.287661f,-0.00361044f,0.125638f}, +{-0.282163f,-0.00374099f,0.125638f},{-0.286299f,-0.00596973f,0.125638f},{-0.286258f,-0.00652514f,0.125638f}, +{-0.281077f,-0.00433369f,0.125638f},{-0.286299f,-0.00708106f,0.125638f},{-0.286424f,-0.00762403f,0.125638f}, +{-0.28128f,-0.00891935f,0.125638f},{-0.291348f,-0.00305413f,0.125638f},{-0.290815f,-0.00288693f,0.125638f}, +{-0.286907f,-0.00862484f,0.125638f},{-0.282708f,-0.0116055f,0.125638f},{-0.281947f,-0.0102864f,0.125638f}, +{-0.280711f,-0.00751463f,0.125638f},{-0.281639f,-0.00407246f,0.125638f},{-0.284491f,-0.0140624f,0.125638f}, +{-0.287935f,-0.0149788f,0.125638f},{-0.285497f,-0.0151839f,0.125638f},{-0.287661f,-0.00944085f,0.125638f}, +{-0.287426f,-0.015333f,0.125638f},{-0.286967f,-0.0157495f,0.125638f},{-0.286569f,-0.0162251f,0.125638f}, +{-0.286629f,-0.00814252f,0.125638f},{-0.286299f,0.00708097f,0.125638f},{-0.280711f,0.00751594f,0.125638f}, +{-0.286423f,-0.00542663f,0.125638f},{-0.282634f,-0.00333905f,0.125638f},{-0.283048f,-0.00287783f,0.125638f}, +{-0.283398f,-0.0023656f,0.125638f},{-0.286905f,-0.00442541f,0.125638f},{-0.286626f,-0.00490799f,0.125638f}, +{-0.29072f,0.0013863f,0.125638f},{-0.290459f,0.00109643f,0.125638f},{-0.283878f,0.00122657f,0.125638f}, +{-0.291035f,0.00161492f,0.125638f},{-0.293181f,0.0152805f,0.125638f},{-0.293646f,0.0156909f,0.125638f}, +{-0.282161f,0.00374048f,0.125638f},{-0.287937f,0.0149805f,0.125638f},{-0.285497f,0.0151839f,0.125638f}, +{-0.28743f,0.0153371f,0.125638f},{-0.286966f,0.0157476f,0.125638f},{-0.286569f,0.0162251f,0.125638f}, +{-0.288624f,0.00999629f,0.125638f},{-0.288486f,0.0146931f,0.125638f},{-0.28907f,0.0144856f,0.125638f}, +{-0.289676f,0.0143575f,0.125638f},{-0.289156f,0.0101606f,0.125638f},{-0.287254f,0.00906122f,0.125638f}, +{-0.28356f,0.0128683f,0.125638f},{-0.287662f,0.00944057f,0.125638f},{-0.288122f,0.00975455f,0.125638f}, +{-0.281948f,0.0102881f,0.125638f},{-0.28271f,0.0116071f,0.125638f},{-0.286629f,0.00814199f,0.125638f}, +{-0.284492f,0.0140632f,0.125638f},{-0.281639f,0.00407552f,0.125638f},{-0.281079f,0.00433883f,0.125638f}, +{-0.280243f,0.00608354f,0.125638f},{-0.280488f,0.0045282f,0.125638f},{-0.279878f,0.00463457f,0.125638f}, +{-0.286907f,0.00862459f,0.125638f},{-0.28128f,0.008921f,0.125638f},{-0.286424f,0.00762395f,0.125638f}, +{-0.307641f,0.0196708f,0.125638f},{-0.306543f,0.0212675f,0.125638f},{-0.307765f,0.0202771f,0.125638f}, +{-0.294052f,0.0161593f,0.125638f},{-0.294392f,0.0166773f,0.125638f},{-0.282634f,0.00333893f,0.125638f}, +{-0.294964f,0.0184349f,0.125638f},{-0.294853f,0.0178252f,0.125638f},{-0.283397f,0.00236609f,0.125638f}, +{-0.283048f,0.00287783f,0.125638f},{-0.311664f,0.0143468f,0.125638f},{-0.312283f,0.0143112f,0.125638f}, +{-0.309678f,-0.0016145f,0.125638f},{-0.304976f,0.0136072f,0.125638f},{-0.304852f,0.0141506f,0.125638f}, +{-0.308932f,0.0156903f,0.125638f},{-0.307612f,0.0184341f,0.125638f},{-0.307724f,0.0178247f,0.125638f}, +{-0.303613f,0.015966f,0.125638f},{-0.302118f,0.0166853f,0.125638f},{-0.303568f,0.0217877f,0.125638f}, +{-0.302651f,0.0165216f,0.125638f},{-0.307916f,0.0172353f,0.125638f},{-0.304022f,0.0155872f,0.125638f}, +{-0.297509f,0.0215784f,0.125638f},{-0.299926f,0.0165218f,0.125638f},{-0.30101f,0.0167668f,0.125638f}, +{-0.300528f,0.0218936f,0.125638f},{-0.301567f,0.0167671f,0.125638f},{-0.294994f,0.0190544f,0.125638f}, +{-0.296034f,0.0212675f,0.125638f},{-0.30798f,0.0208597f,0.125638f},{-0.294941f,0.0196718f,0.125638f}, +{-0.29481f,0.0202777f,0.125638f},{-0.294597f,0.0208597f,0.125638f},{-0.304369f,0.0151517f,0.125638f}, +{-0.308185f,0.0166765f,0.125638f},{-0.304648f,0.0146693f,0.125638f},{-0.29901f,0.0217881f,0.125638f}, +{-0.300459f,0.0166848f,0.125638f},{-0.315951f,0.00490799f,0.125638f},{-0.319179f,0.0023656f,0.125638f}, +{-0.315672f,0.00442541f,0.125638f},{-0.297205f,0.00984589f,0.125638f},{-0.296823f,0.00992719f,0.125638f}, +{-0.310468f,0.0146616f,0.125638f},{-0.314299f,-0.00115727f,0.125638f},{-0.307613f,-0.0184349f,0.125638f}, +{-0.307724f,-0.0178252f,0.125638f},{-0.311056f,0.0144643f,0.125638f},{-0.321866f,0.00751463f,0.125638f}, +{-0.322334f,0.00608354f,0.125638f},{-0.320938f,0.00407246f,0.125638f},{-0.314916f,0.00944085f,0.125638f}, +{-0.319018f,0.0128671f,0.125638f},{-0.315323f,0.00906082f,0.125638f},{-0.307198f,0.00945782f,0.125638f}, +{-0.322087f,0.00452954f,0.125638f},{-0.322699f,0.00463457f,0.125638f},{-0.315325f,0.00398966f,0.125638f}, +{-0.318698f,0.00122583f,0.125638f},{-0.314916f,0.00361044f,0.125638f},{-0.319529f,0.00287783f,0.125638f}, +{-0.316154f,0.00542663f,0.125638f},{-0.319943f,0.00333905f,0.125638f},{-0.3215f,0.00433369f,0.125638f}, +{-0.316278f,0.00708106f,0.125638f},{-0.316153f,0.00762403f,0.125638f},{-0.321297f,0.00891935f,0.125638f}, +{-0.32063f,0.0102864f,0.125638f},{-0.31567f,0.00862484f,0.125638f},{-0.319869f,0.0116055f,0.125638f}, +{-0.315948f,0.00814252f,0.125638f},{-0.314643f,0.0149788f,0.125638f},{-0.31708f,0.0151839f,0.125638f}, +{-0.318086f,0.0140624f,0.125638f},{-0.315151f,0.015333f,0.125638f},{-0.311055f,-0.0144645f,0.125638f}, +{-0.310468f,-0.0146618f,0.125638f},{-0.311229f,-0.00999677f,0.125638f},{-0.31561f,0.0157495f,0.125638f}, +{-0.316008f,0.0162251f,0.125638f},{-0.307653f,0.00883069f,0.125638f},{-0.307773f,0.00845974f,0.125638f}, +{-0.318901f,-0.00181243f,0.125638f},{-0.31918f,-0.00236609f,0.125638f},{-0.312901f,0.014358f,0.125638f}, +{-0.309911f,-0.0149353f,0.125638f},{-0.310727f,-0.00975506f,0.125638f},{-0.304441f,-0.00916839f,0.125638f}, +{-0.304246f,-0.00883048f,0.125638f},{-0.311762f,-0.0101609f,0.125638f},{-0.320938f,-0.00407552f,0.125638f}, +{-0.321866f,-0.00751594f,0.125638f},{-0.318085f,-0.0140632f,0.125638f},{-0.31708f,-0.0151839f,0.125638f}, +{-0.314299f,-0.0126311f,0.125638f},{-0.313507f,-0.0144856f,0.125638f},{-0.312901f,-0.0143575f,0.125638f}, +{-0.318576f,0.000618365f,0.125638f},{-0.318699f,-0.00122657f,0.125638f},{-0.318534f,4.85606e-018f,0.125638f}, +{-0.308525f,-0.0161593f,0.125638f},{-0.308185f,-0.0166773f,0.125638f},{-0.315148f,-0.0153371f,0.125638f}, +{-0.31464f,-0.0149805f,0.125638f},{-0.31287f,-0.0102437f,0.125638f},{-0.313421f,-0.0101606f,0.125638f}, +{-0.315324f,-0.00906122f,0.125638f},{-0.319017f,-0.0128683f,0.125638f},{-0.314916f,-0.00944057f,0.125638f}, +{-0.31567f,-0.00862459f,0.125638f},{-0.319868f,-0.0116071f,0.125638f},{-0.320629f,-0.0102881f,0.125638f}, +{-0.315948f,-0.00814199f,0.125638f},{-0.316278f,-0.00708097f,0.125638f},{-0.314455f,-0.00975455f,0.125638f}, +{-0.313953f,-0.00999629f,0.125638f},{-0.322334f,-0.00608354f,0.125638f},{-0.315611f,-0.0157476f,0.125638f}, +{-0.321499f,-0.00433883f,0.125638f},{-0.322089f,-0.0045282f,0.125638f},{-0.316008f,-0.0162251f,0.125638f}, +{-0.322699f,-0.00463457f,0.125638f},{-0.312313f,-0.0102438f,0.125638f},{-0.292544f,0.00177278f,0.125638f}, +{-0.292899f,0.0016145f,0.125638f},{-0.306524f,-0.00984657f,0.125638f},{-0.306144f,-0.00992738f,0.125638f}, +{-0.294925f,-0.00731413f,0.125638f},{-0.29512f,-0.00697672f,0.125638f},{-0.307584f,-0.0190544f,0.125638f}, +{-0.305068f,-0.0215784f,0.125638f},{-0.291351f,-0.0126311f,0.125638f},{-0.290294f,-0.0143112f,0.125638f}, +{-0.289676f,-0.014358f,0.125638f},{-0.297726f,-0.0141506f,0.125638f},{-0.293645f,-0.0156903f,0.125638f}, +{-0.297601f,-0.0136072f,0.125638f},{-0.291521f,-0.0144643f,0.125638f},{-0.292109f,-0.0146616f,0.125638f}, +{-0.294853f,-0.0178247f,0.125638f},{-0.298964f,-0.015966f,0.125638f},{-0.294965f,-0.0184341f,0.125638f}, +{-0.293181f,-0.0152802f,0.125638f},{-0.292666f,-0.0149353f,0.125638f},{-0.29756f,-0.0130513f,0.125638f}, +{-0.297508f,-0.0215779f,0.125638f},{-0.294991f,-0.019053f,0.125638f},{-0.299424f,-0.0162797f,0.125638f}, +{-0.290143f,0.000388892f,0.125638f},{-0.290263f,0.000758756f,0.125638f},{-0.321297f,-0.008921f,0.125638f}, +{-0.316153f,-0.00762395f,0.125638f},{-0.312283f,-0.0143109f,0.125638f},{-0.293552f,0.00762671f,0.125638f}, +{-0.312314f,-0.000758756f,0.125638f},{-0.312434f,-0.000388892f,0.125638f},{-0.308931f,-0.0156909f,0.125638f}, +{-0.311857f,-0.0013863f,0.125638f},{-0.293215f,0.00138471f,0.125638f},{-0.302118f,-0.0166848f,0.125638f}, +{-0.302651f,-0.0165218f,0.125638f},{-0.303567f,-0.0217881f,0.125638f},{-0.301567f,-0.0167668f,0.125638f}, +{-0.302049f,-0.0218936f,0.125638f},{-0.30101f,-0.0167671f,0.125638f},{-0.300459f,-0.0166853f,0.125638f}, +{-0.299009f,-0.0217877f,0.125638f},{-0.299926f,-0.0165216f,0.125638f},{-0.306543f,-0.0212675f,0.125638f}, +{-0.307636f,-0.0196718f,0.125638f},{-0.307767f,-0.0202777f,0.125638f},{-0.30798f,-0.0208597f,0.125638f}, +{-0.297929f,-0.0146693f,0.125638f},{-0.298208f,-0.0151517f,0.125638f},{-0.294392f,-0.0166765f,0.125638f}, +{-0.298555f,-0.0155872f,0.125638f},{-0.294661f,-0.0172353f,0.125638f},{-0.296034f,-0.0212675f,0.125638f}, +{-0.294936f,-0.0196708f,0.125638f},{-0.294597f,-0.0208597f,0.125638f},{-0.294812f,-0.0202771f,0.125638f}, +{-0.283676f,0.00181243f,0.125638f},{-0.291348f,0.00999677f,0.125638f},{-0.290913f,0.0143468f,0.125638f}, +{-0.291522f,0.0144645f,0.125638f},{-0.290815f,0.0101609f,0.125638f},{-0.292162f,0.00185398f,0.125638f}, +{-0.291772f,0.00185425f,0.125638f},{-0.291391f,0.0017734f,0.125638f},{-0.287252f,-0.00398966f,0.125638f}, +{-0.290264f,-0.00281666f,0.125638f},{-0.283559f,-0.0128671f,0.125638f},{-0.287254f,-0.00906082f,0.125638f}, +{-0.293062f,0.00862453f,0.125638f},{-0.305373f,0.00630002f,0.125638f},{-0.305754f,0.00621904f,0.125638f}, +{-0.319944f,-0.00333893f,0.125638f},{-0.320416f,-0.00374048f,0.125638f},{-0.298136f,0.00916836f,0.125638f}, +{-0.298331f,0.00883081f,0.125638f},{-0.297875f,0.0066875f,0.125638f},{-0.29379f,0.000387896f,0.125638f}, +{-0.29367f,0.000757801f,0.125638f},{-0.288623f,-0.00305438f,0.125638f},{-0.288121f,-0.00329623f,0.125638f}, +{-0.289706f,-0.00281186f,0.125638f},{-0.289069f,-0.0144863f,0.125638f},{-0.288486f,-0.0146944f,0.125638f}, +{-0.295379f,-0.00945782f,0.125638f},{-0.294924f,-0.00883069f,0.125638f},{-0.294804f,-0.00845974f,0.125638f}, +{-0.305372f,-0.00984564f,0.125638f},{-0.305754f,-0.00992724f,0.125638f},{-0.309362f,-0.00138471f,0.125638f}, +{-0.305592f,-0.00178272f,0.125638f},{-0.298451f,-0.00369829f,0.125638f},{-0.297204f,-0.00630002f,0.125638f}, +{-0.296823f,-0.00621904f,0.125638f},{-0.310034f,-0.00177278f,0.125638f},{-0.318576f,-0.000618856f,0.125638f}, +{-0.293673f,0.00708155f,0.125638f},{-0.292719f,0.00906268f,0.125638f},{-0.308526f,0.0161585f,0.125638f}, +{-0.302051f,0.0218934f,0.125638f},{-0.29466f,0.0172358f,0.125638f},{-0.297876f,0.00945796f,0.125638f}, +{-0.29756f,0.00968738f,0.125638f},{-0.298492f,0.00807261f,0.125638f},{-0.298451f,0.00845965f,0.125638f}, +{-0.298451f,0.00768455f,0.125638f},{-0.304644f,0.0114364f,0.125638f},{-0.293337f,0.00813915f,0.125638f}, +{-0.304986f,-0.00283697f,0.125638f},{-0.29833f,0.00731409f,0.125638f},{-0.298135f,0.00697679f,0.125638f}, +{-0.306525f,0.00629974f,0.125638f},{-0.307457f,0.00697672f,0.125638f},{-0.307652f,0.00731413f,0.125638f}, +{-0.304025f,0.0105136f,0.125638f},{-0.303614f,0.0101357f,0.125638f},{-0.304852f,0.0119527f,0.125638f}, +{-0.314456f,0.00329623f,0.125638f},{-0.318901f,0.00181168f,0.125638f},{-0.307458f,0.00916838f,0.125638f}, +{-0.307773f,0.00768456f,0.125638f},{-0.307814f,0.00807245f,0.125638f},{-0.306881f,0.00645825f,0.125638f}, +{-0.307196f,0.00668694f,0.125638f},{-0.306144f,0.00621891f,0.125638f},{-0.304361f,0.0109558f,0.125638f}, +{-0.312313f,0.00281666f,0.125638f},{-0.310805f,-0.00185425f,0.125638f},{-0.304976f,0.0124958f,0.125638f}, +{-0.310266f,-0.00944145f,0.125638f},{-0.311664f,-0.0143468f,0.125638f},{-0.314091f,-0.0146931f,0.125638f}, +{-0.319529f,-0.00287783f,0.125638f},{-0.312119f,-0.00109643f,0.125638f},{-0.311542f,-0.00161492f,0.125638f}, +{-0.310415f,-0.00185398f,0.125638f},{-0.311186f,-0.0017734f,0.125638f},{-0.312871f,0.00281186f,0.125638f}, +{-0.313422f,0.00289006f,0.125638f},{-0.311762f,0.00288693f,0.125638f},{-0.311229f,0.00305413f,0.125638f}, +{-0.30591f,-0.0006084f,0.125638f},{-0.308907f,-0.000757801f,0.125638f},{-0.305788f,-0.00120559f,0.125638f}, +{-0.308787f,-0.000387896f,0.125638f},{-0.308904f,-0.00708155f,0.125638f},{-0.309858f,-0.00906268f,0.125638f}, +{-0.309515f,-0.00862453f,0.125638f},{-0.309025f,-0.00762671f,0.125638f},{-0.305326f,-0.00233026f,0.125638f}, +{-0.313954f,0.00305438f,0.125638f},{-0.295696f,-0.00645825f,0.125638f},{-0.294051f,-0.0161585f,0.125638f}, +{-0.300526f,-0.0218934f,0.125638f},{-0.307917f,-0.0172358f,0.125638f},{-0.304702f,-0.00945833f,0.125638f}, +{-0.305017f,-0.00968734f,0.125638f},{-0.304085f,-0.0080728f,0.125638f},{-0.304126f,-0.00845974f,0.125638f}, +{-0.304126f,-0.00768446f,0.125638f},{-0.300083f,-0.00450236f,0.125638f},{-0.30924f,-0.00813915f,0.125638f}, +{-0.297591f,-0.00283787f,0.125638f},{-0.297992f,-0.00329614f,0.125638f},{-0.296433f,-0.00621891f,0.125638f}, +{-0.296052f,-0.00629974f,0.125638f},{-0.293475f,0.00109509f,0.125638f},{-0.296982f,-0.00178435f,0.125638f}, +{-0.297725f,-0.0119527f,0.125638f},{-0.304126f,-0.00369728f,0.125638f},{-0.304584f,-0.00329545f,0.125638f}, +{-0.299505f,-0.00430656f,0.125638f},{-0.30068f,-0.00462115f,0.125638f},{-0.301289f,-0.00466102f,0.125638f}, +{-0.304702f,-0.0066878f,0.125638f},{-0.303619f,-0.00403597f,0.125638f},{-0.304247f,-0.00731401f,0.125638f}, +{-0.302495f,-0.00450189f,0.125638f},{-0.304442f,-0.00697682f,0.125638f},{-0.283676f,-0.00181168f,0.125638f}, +{-0.290913f,-0.0143468f,0.125638f},{-0.295119f,-0.00916838f,0.125638f},{-0.294804f,-0.00768456f,0.125638f}, +{-0.294763f,-0.00807245f,0.125638f},{-0.296793f,-0.00120563f,0.125638f},{-0.295381f,-0.00668694f,0.125638f}, +{-0.298552f,-0.0105136f,0.125638f},{-0.297933f,-0.0114364f,0.125638f},{-0.298963f,-0.0101357f,0.125638f}, +{-0.298216f,-0.0109558f,0.125638f},{-0.296671f,-0.00060826f,0.125638f},{-0.297252f,-0.002331f,0.125638f}, +{-0.297601f,-0.0124958f,0.125638f},{-0.298958f,-0.00403701f,0.125638f},{-0.301897f,-0.00462104f,0.125638f}, +{-0.303073f,-0.00430572f,0.125638f},{-0.309102f,-0.00109509f,0.125638f},{-0.279665f,-0.00625082f,0.12559f}, +{-0.280145f,-0.00772125f,0.12559f},{-0.279565f,-0.00793332f,0.125434f},{-0.281997f,-0.0161504f,0.12373f}, +{-0.280926f,-0.0147775f,0.12373f},{-0.281237f,-0.0145522f,0.12429f},{-0.280275f,-0.0131254f,0.12429f}, +{-0.27995f,-0.0133286f,0.12373f},{-0.282662f,-0.0155937f,0.124775f},{-0.283091f,-0.0152344f,0.125161f}, +{-0.283778f,-0.0168374f,0.124775f},{-0.284618f,-0.0160299f,0.125434f},{-0.285432f,-0.0174787f,0.125232f}, +{-0.284181f,-0.0164494f,0.125161f},{-0.286175f,-0.0166602f,0.125592f},{-0.285793f,-0.0170806f,0.125455f}, +{-0.285063f,-0.0156014f,0.12559f},{-0.279414f,-0.0116335f,0.12429f},{-0.279075f,-0.0118136f,0.12373f}, +{-0.278659f,-0.0100875f,0.12429f},{-0.27972f,-0.013472f,0.123126f},{-0.279587f,-0.0135551f,0.122512f}, +{-0.278836f,-0.0119407f,0.123126f},{-0.279926f,-0.0141705f,0.121909f},{-0.279088f,-0.0128179f,0.121909f}, +{-0.28058f,-0.0150287f,0.122512f},{-0.280846f,-0.0154687f,0.121909f},{-0.281669f,-0.0164249f,0.122512f}, +{-0.278698f,-0.0120144f,0.122512f},{-0.278335f,-0.0114156f,0.121909f},{-0.282919f,-0.0178815f,0.121909f}, +{-0.281845f,-0.0167073f,0.121909f},{-0.282845f,-0.0177348f,0.122512f},{-0.284064f,-0.0189869f,0.121909f}, +{-0.284095f,-0.0189523f,0.122497f},{-0.277919f,-0.0104178f,0.122512f},{-0.277671f,-0.00996957f,0.121909f}, +{-0.277254f,-0.00877706f,0.122512f},{-0.277098f,-0.00848485f,0.121909f},{-0.276617f,-0.0069676f,0.121909f}, +{-0.276708f,-0.00710556f,0.122512f},{-0.276279f,-0.00541355f,0.122497f},{-0.276413f,-0.00538462f,0.123065f}, +{-0.278309f,-0.0102436f,0.12373f},{-0.283153f,-0.0174384f,0.12373f},{-0.282291f,-0.0159041f,0.12429f}, +{-0.276233f,-0.00542344f,0.121909f},{-0.278062f,-0.0103538f,0.123126f},{-0.277952f,-0.006746f,0.124775f}, +{-0.277739f,-0.00509752f,0.124929f},{-0.278489f,-0.00659057f,0.125161f},{-0.277301f,-0.00519238f,0.124546f}, +{-0.277487f,-0.00688027f,0.12429f},{-0.280335f,-0.0111437f,0.125161f},{-0.279612f,-0.00966271f,0.125161f}, +{-0.280165f,-0.00941631f,0.125434f},{-0.279303f,-0.00475885f,0.125592f},{-0.276859f,-0.00706195f,0.123126f}, +{-0.27663f,-0.00533751f,0.123602f},{-0.277119f,-0.0069868f,0.12373f},{-0.277402f,-0.00872319f,0.123126f}, +{-0.280707f,-0.0149364f,0.123126f},{-0.281789f,-0.0163241f,0.123126f},{-0.282958f,-0.0176259f,0.123126f}, +{-0.284187f,-0.0188517f,0.123062f},{-0.276929f,-0.00527292f,0.1241f},{-0.277656f,-0.00863036f,0.12373f}, +{-0.284336f,-0.0186868f,0.1236f},{-0.279071f,-0.0064225f,0.125434f},{-0.278226f,-0.00499215f,0.125233f}, +{-0.278016f,-0.00849877f,0.12429f},{-0.281628f,-0.0142682f,0.124775f},{-0.283429f,-0.0171725f,0.12429f}, +{-0.284541f,-0.0184612f,0.124098f},{-0.279101f,-0.0098906f,0.124775f},{-0.27847f,-0.00833292f,0.124775f}, +{-0.279841f,-0.0114065f,0.124775f},{-0.280685f,-0.0128692f,0.124775f},{-0.284798f,-0.018178f,0.124546f}, +{-0.278996f,-0.00814092f,0.125161f},{-0.28116f,-0.0125727f,0.125161f},{-0.282081f,-0.0139394f,0.125161f}, +{-0.285098f,-0.0178475f,0.124927f},{-0.278751f,-0.00487843f,0.125456f},{-0.280869f,-0.0108595f,0.125434f}, +{-0.281673f,-0.0122521f,0.125434f},{-0.282571f,-0.013584f,0.125434f},{-0.284029f,-0.0144491f,0.12559f}, +{-0.283555f,-0.014846f,0.125434f},{-0.28073f,-0.00916459f,0.12559f},{-0.281415f,-0.0105692f,0.12559f}, +{-0.282198f,-0.0119246f,0.12559f},{-0.283071f,-0.0132209f,0.12559f},{-0.300403f,-0.0254145f,0.123126f}, +{-0.29867f,-0.0250226f,0.12373f},{-0.300413f,-0.0251441f,0.12373f},{-0.296873f,-0.0252029f,0.122512f}, +{-0.298626f,-0.0254479f,0.122512f},{-0.298641f,-0.0254985f,0.121909f},{-0.29871f,-0.0246411f,0.12429f}, +{-0.300404f,-0.0256204f,0.121909f},{-0.295189f,-0.0246879f,0.123126f},{-0.295152f,-0.0248403f,0.122512f}, +{-0.293514f,-0.0242356f,0.123065f},{-0.295163f,-0.024878f,0.121909f},{-0.293472f,-0.0243658f,0.122497f}, +{-0.29589f,-0.0218522f,0.12559f},{-0.297404f,-0.0221712f,0.12559f},{-0.297297f,-0.0227801f,0.125434f}, +{-0.293458f,-0.0244103f,0.121909f},{-0.296889f,-0.0252555f,0.121909f},{-0.293791f,-0.0233704f,0.124546f}, +{-0.295462f,-0.0235834f,0.124775f},{-0.295346f,-0.0240528f,0.12429f},{-0.298819f,-0.0236035f,0.125161f}, +{-0.298882f,-0.0230016f,0.125434f},{-0.300462f,-0.0237181f,0.125161f},{-0.295597f,-0.02304f,0.125161f}, +{-0.293928f,-0.0229434f,0.124929f},{-0.300398f,-0.0255715f,0.122512f},{-0.298642f,-0.0252917f,0.123126f}, +{-0.305563f,-0.0244044f,0.12429f},{-0.307323f,-0.0244252f,0.12373f},{-0.305629f,-0.0247822f,0.12373f}, +{-0.294417f,-0.0214191f,0.125592f},{-0.302149f,-0.0247609f,0.12429f},{-0.303905f,-0.0250231f,0.12373f}, +{-0.302162f,-0.0251442f,0.12373f},{-0.300426f,-0.0247607f,0.12429f},{-0.307115f,-0.0235834f,0.124775f}, +{-0.30548f,-0.0239281f,0.124775f},{-0.305383f,-0.0233768f,0.125161f},{-0.306835f,-0.0224524f,0.125434f}, +{-0.308497f,-0.0224714f,0.125232f},{-0.306981f,-0.02304f,0.125161f},{-0.303865f,-0.0246415f,0.12429f}, +{-0.30816f,-0.0214191f,0.125592f},{-0.308333f,-0.0219595f,0.125455f},{-0.306687f,-0.0218522f,0.12559f}, +{-0.302177f,-0.0255716f,0.122512f},{-0.302171f,-0.0254147f,0.123126f},{-0.302172f,-0.0256204f,0.121909f}, +{-0.30395f,-0.0254484f,0.122512f},{-0.303936f,-0.0254985f,0.121909f},{-0.305703f,-0.0252035f,0.122512f}, +{-0.305688f,-0.0252554f,0.121909f},{-0.307416f,-0.0248864f,0.121909f},{-0.307425f,-0.0248403f,0.122512f}, +{-0.309119f,-0.0244103f,0.121909f},{-0.293582f,-0.0240236f,0.123602f},{-0.295254f,-0.0244252f,0.12373f}, +{-0.2969f,-0.0250482f,0.123126f},{-0.303933f,-0.0252922f,0.123126f},{-0.307388f,-0.0246879f,0.123126f}, +{-0.305676f,-0.0250488f,0.123126f},{-0.309105f,-0.0243658f,0.122497f},{-0.309064f,-0.0242365f,0.123062f}, +{-0.293675f,-0.0237329f,0.1241f},{-0.296946f,-0.0247816f,0.12373f},{-0.308996f,-0.0240245f,0.1236f}, +{-0.295742f,-0.0224524f,0.125434f},{-0.29408f,-0.0224691f,0.125233f},{-0.297013f,-0.0244038f,0.12429f}, +{-0.303815f,-0.0241606f,0.124775f},{-0.307231f,-0.0240528f,0.12429f},{-0.308903f,-0.0237345f,0.124098f}, +{-0.29876f,-0.0241602f,0.124775f},{-0.297096f,-0.0239275f,0.124775f},{-0.300443f,-0.0242775f,0.124775f}, +{-0.302132f,-0.0242776f,0.124775f},{-0.308786f,-0.0233704f,0.124546f},{-0.297193f,-0.0233762f,0.125161f}, +{-0.302113f,-0.0237183f,0.125161f},{-0.303757f,-0.023604f,0.125161f},{-0.308649f,-0.0229455f,0.124927f}, +{-0.294245f,-0.0219573f,0.125456f},{-0.300484f,-0.0231133f,0.125434f},{-0.302091f,-0.0231134f,0.125434f}, +{-0.303694f,-0.023002f,0.125434f},{-0.305172f,-0.0221717f,0.12559f},{-0.305279f,-0.0227807f,0.125434f}, +{-0.298946f,-0.0223867f,0.12559f},{-0.300505f,-0.0224954f,0.12559f},{-0.30207f,-0.0224956f,0.12559f}, +{-0.303629f,-0.0223872f,0.12559f},{-0.322989f,-0.013557f,0.122512f},{-0.321869f,-0.0149379f,0.123126f}, +{-0.322856f,-0.0134738f,0.123126f},{-0.321996f,-0.0150302f,0.122512f},{-0.322651f,-0.0141709f,0.121909f}, +{-0.321731f,-0.0154689f,0.121909f},{-0.32165f,-0.0147789f,0.12373f},{-0.322626f,-0.0133304f,0.12373f}, +{-0.321339f,-0.0145536f,0.12429f},{-0.319619f,-0.0176259f,0.123126f},{-0.319733f,-0.0177348f,0.122512f}, +{-0.31839f,-0.0188513f,0.123063f},{-0.318239f,-0.0186852f,0.123604f},{-0.318547f,-0.0144499f,0.12559f}, +{-0.319021f,-0.0148468f,0.125434f},{-0.317514f,-0.0156014f,0.12559f},{-0.318482f,-0.0189527f,0.122494f}, +{-0.319658f,-0.0178817f,0.121909f},{-0.318513f,-0.0189869f,0.121909f},{-0.320907f,-0.0164258f,0.122512f}, +{-0.320732f,-0.0167075f,0.121909f},{-0.318396f,-0.0164494f,0.125161f},{-0.318799f,-0.0168374f,0.124775f}, +{-0.31748f,-0.0178479f,0.124927f},{-0.321416f,-0.0125744f,0.125161f},{-0.320495f,-0.0139408f,0.125161f}, +{-0.320005f,-0.0135853f,0.125434f},{-0.3164f,-0.0166578f,0.125592f},{-0.319148f,-0.0171725f,0.12429f}, +{-0.317779f,-0.018178f,0.124546f},{-0.324561f,-0.00850026f,0.12429f},{-0.325458f,-0.0069868f,0.12373f}, +{-0.324921f,-0.00863187f,0.12373f},{-0.322301f,-0.0131272f,0.12429f},{-0.323506f,-0.0064225f,0.125434f}, +{-0.324354f,-0.00499264f,0.125232f},{-0.324088f,-0.00659057f,0.125161f},{-0.32374f,-0.0119427f,0.123126f}, +{-0.323878f,-0.0120165f,0.122512f},{-0.324625f,-0.006746f,0.124775f},{-0.324106f,-0.00833438f,0.124775f}, +{-0.323581f,-0.00814234f,0.125161f},{-0.324267f,-0.0102456f,0.12373f},{-0.323917f,-0.0100893f,0.12429f}, +{-0.323162f,-0.0116355f,0.12429f},{-0.323501f,-0.0118156f,0.12373f},{-0.323274f,-0.00475885f,0.125592f}, +{-0.323828f,-0.00487893f,0.125455f},{-0.322912f,-0.00625082f,0.12559f},{-0.32349f,-0.012818f,0.121909f}, +{-0.324658f,-0.0104197f,0.122512f},{-0.324242f,-0.011416f,0.121909f},{-0.325323f,-0.0087786f,0.122512f}, +{-0.324906f,-0.00996985f,0.121909f},{-0.325477f,-0.00848443f,0.121909f},{-0.325869f,-0.00710556f,0.122512f}, +{-0.325951f,-0.00696541f,0.121909f},{-0.326344f,-0.00542344f,0.121909f},{-0.326298f,-0.00541355f,0.122497f}, +{-0.319424f,-0.0174384f,0.12373f},{-0.320786f,-0.016325f,0.123126f},{-0.324515f,-0.0103558f,0.123126f}, +{-0.325175f,-0.00872472f,0.123126f},{-0.325718f,-0.00706195f,0.123126f},{-0.326165f,-0.00538482f,0.123062f}, +{-0.318034f,-0.0184588f,0.124102f},{-0.320579f,-0.0161513f,0.12373f},{-0.325948f,-0.00533772f,0.1236f}, +{-0.31796f,-0.0160299f,0.125434f},{-0.317144f,-0.0174779f,0.125233f},{-0.320285f,-0.015905f,0.12429f}, +{-0.323475f,-0.00989244f,0.124775f},{-0.32509f,-0.00688027f,0.12429f},{-0.32565f,-0.00527328f,0.124098f}, +{-0.320948f,-0.0142696f,0.124775f},{-0.319914f,-0.0155946f,0.124775f},{-0.321891f,-0.012871f,0.124775f}, +{-0.322735f,-0.0114084f,0.124775f},{-0.325276f,-0.00519238f,0.124546f},{-0.319485f,-0.0152353f,0.125161f}, +{-0.322241f,-0.0111456f,0.125161f},{-0.322964f,-0.00966451f,0.125161f},{-0.32484f,-0.005098f,0.124927f}, +{-0.316781f,-0.0170773f,0.125456f},{-0.320903f,-0.0122538f,0.125434f},{-0.321707f,-0.0108613f,0.125434f}, +{-0.322411f,-0.00941806f,0.125434f},{-0.322432f,-0.0077226f,0.12559f},{-0.323012f,-0.00793471f,0.125434f}, +{-0.319505f,-0.0132221f,0.12559f},{-0.320378f,-0.0119262f,0.12559f},{-0.321161f,-0.010571f,0.12559f}, +{-0.321847f,-0.0091663f,0.12559f},{-0.323879f,0.0120144f,0.122512f},{-0.324515f,0.0103538f,0.123126f}, +{-0.323741f,0.0119407f,0.123126f},{-0.324659f,0.0104178f,0.122512f},{-0.324268f,0.0102436f,0.12373f}, +{-0.323502f,0.0118136f,0.12373f},{-0.323918f,0.0100875f,0.12429f},{-0.325718f,0.00706195f,0.123126f}, +{-0.325869f,0.00710556f,0.122512f},{-0.326165f,0.00538462f,0.123065f},{-0.325947f,0.00533751f,0.123602f}, +{-0.322432f,0.00772125f,0.12559f},{-0.323012f,0.00793332f,0.125434f},{-0.322912f,0.00625082f,0.12559f}, +{-0.326298f,0.00541355f,0.122497f},{-0.325323f,0.00877706f,0.122512f},{-0.324088f,0.00659057f,0.125161f}, +{-0.324625f,0.006746f,0.124775f},{-0.324838f,0.00509752f,0.124929f},{-0.322242f,0.0111437f,0.125161f}, +{-0.322965f,0.00966271f,0.125161f},{-0.322412f,0.00941631f,0.125434f},{-0.323274f,0.00475885f,0.125592f}, +{-0.32509f,0.00688027f,0.12429f},{-0.325276f,0.00519238f,0.124546f},{-0.320286f,0.0159041f,0.12429f}, +{-0.319424f,0.0174384f,0.12373f},{-0.32058f,0.0161504f,0.12373f},{-0.323163f,0.0116335f,0.12429f}, +{-0.31796f,0.0160299f,0.125434f},{-0.317146f,0.0174801f,0.125231f},{-0.318396f,0.0164494f,0.125161f}, +{-0.322857f,0.013472f,0.123126f},{-0.32299f,0.0135551f,0.122512f},{-0.318799f,0.0168374f,0.124775f}, +{-0.319915f,0.0155937f,0.124775f},{-0.319486f,0.0152344f,0.125161f},{-0.321651f,0.0147775f,0.12373f}, +{-0.32134f,0.0145522f,0.12429f},{-0.322302f,0.0131254f,0.12429f},{-0.322627f,0.0133286f,0.12373f}, +{-0.3164f,0.0166578f,0.125592f},{-0.316783f,0.0170797f,0.125455f},{-0.317514f,0.0156014f,0.12559f}, +{-0.321997f,0.0150287f,0.122512f},{-0.320908f,0.0164249f,0.122512f},{-0.319733f,0.0177348f,0.122512f}, +{-0.318482f,0.0189527f,0.122494f},{-0.325458f,0.0069868f,0.12373f},{-0.325175f,0.00872319f,0.123126f}, +{-0.32187f,0.0149364f,0.123126f},{-0.320788f,0.0163241f,0.123126f},{-0.319619f,0.0176259f,0.123126f}, +{-0.318391f,0.018852f,0.12306f},{-0.325649f,0.00527292f,0.1241f},{-0.324921f,0.00863036f,0.12373f}, +{-0.31824f,0.0186863f,0.123601f},{-0.323506f,0.0064225f,0.125434f},{-0.324351f,0.00499215f,0.125233f}, +{-0.324561f,0.00849877f,0.12429f},{-0.320949f,0.0142682f,0.124775f},{-0.319148f,0.0171725f,0.12429f}, +{-0.318035f,0.0184598f,0.1241f},{-0.323476f,0.0098906f,0.124775f},{-0.324107f,0.00833292f,0.124775f}, +{-0.322736f,0.0114065f,0.124775f},{-0.321892f,0.0128692f,0.124775f},{-0.317779f,0.018178f,0.124546f}, +{-0.323581f,0.00814092f,0.125161f},{-0.321417f,0.0125727f,0.125161f},{-0.320496f,0.0139394f,0.125161f}, +{-0.317481f,0.0178492f,0.124925f},{-0.323826f,0.00487843f,0.125456f},{-0.321708f,0.0108595f,0.125434f}, +{-0.320904f,0.0122521f,0.125434f},{-0.320006f,0.013584f,0.125434f},{-0.318548f,0.0144491f,0.12559f}, +{-0.319022f,0.014846f,0.125434f},{-0.321847f,0.00916459f,0.12559f},{-0.321162f,0.0105692f,0.12559f}, +{-0.32038f,0.0119246f,0.12559f},{-0.319506f,0.0132209f,0.12559f},{-0.302174f,0.0254145f,0.123126f}, +{-0.303907f,0.0250226f,0.12373f},{-0.302164f,0.0251441f,0.12373f},{-0.305705f,0.0252029f,0.122512f}, +{-0.303952f,0.0254479f,0.122512f},{-0.303867f,0.0246411f,0.12429f},{-0.307388f,0.0246879f,0.123126f}, +{-0.307425f,0.0248403f,0.122512f},{-0.309063f,0.0242356f,0.123065f},{-0.309105f,0.0243658f,0.122497f}, +{-0.306687f,0.0218522f,0.12559f},{-0.305173f,0.0221712f,0.12559f},{-0.30528f,0.0227801f,0.125434f}, +{-0.308786f,0.0233704f,0.124546f},{-0.307115f,0.0235834f,0.124775f},{-0.307231f,0.0240528f,0.12429f}, +{-0.303759f,0.0236035f,0.125161f},{-0.303695f,0.0230016f,0.125434f},{-0.302115f,0.0237181f,0.125161f}, +{-0.306981f,0.02304f,0.125161f},{-0.308649f,0.0229434f,0.124929f},{-0.302179f,0.0255715f,0.122512f}, +{-0.303935f,0.0252917f,0.123126f},{-0.297014f,0.0244044f,0.12429f},{-0.295254f,0.0244252f,0.12373f}, +{-0.296948f,0.0247822f,0.12373f},{-0.30816f,0.0214191f,0.125592f},{-0.300428f,0.0247609f,0.12429f}, +{-0.298672f,0.0250231f,0.12373f},{-0.300415f,0.0251442f,0.12373f},{-0.302151f,0.0247607f,0.12429f}, +{-0.295462f,0.0235834f,0.124775f},{-0.297097f,0.0239281f,0.124775f},{-0.297194f,0.0233768f,0.125161f}, +{-0.295742f,0.0224524f,0.125434f},{-0.29408f,0.0224714f,0.125232f},{-0.295597f,0.02304f,0.125161f}, +{-0.298712f,0.0246415f,0.12429f},{-0.294417f,0.0214191f,0.125592f},{-0.294244f,0.0219595f,0.125455f}, +{-0.29589f,0.0218522f,0.12559f},{-0.3004f,0.0255716f,0.122512f},{-0.300406f,0.0254147f,0.123126f}, +{-0.298628f,0.0254484f,0.122512f},{-0.296874f,0.0252035f,0.122512f},{-0.295152f,0.0248403f,0.122512f}, +{-0.308995f,0.0240236f,0.123602f},{-0.307323f,0.0244252f,0.12373f},{-0.305677f,0.0250482f,0.123126f}, +{-0.298644f,0.0252922f,0.123126f},{-0.295189f,0.0246879f,0.123126f},{-0.296901f,0.0250488f,0.123126f}, +{-0.293472f,0.0243658f,0.122497f},{-0.293513f,0.0242365f,0.123062f},{-0.308902f,0.0237329f,0.1241f}, +{-0.305631f,0.0247816f,0.12373f},{-0.293581f,0.0240245f,0.1236f},{-0.306835f,0.0224524f,0.125434f}, +{-0.308497f,0.0224691f,0.125233f},{-0.305565f,0.0244038f,0.12429f},{-0.298762f,0.0241606f,0.124775f}, +{-0.295346f,0.0240528f,0.12429f},{-0.293674f,0.0237345f,0.124098f},{-0.303817f,0.0241602f,0.124775f}, +{-0.305481f,0.0239275f,0.124775f},{-0.302134f,0.0242775f,0.124775f},{-0.300445f,0.0242776f,0.124775f}, +{-0.293791f,0.0233704f,0.124546f},{-0.305384f,0.0233762f,0.125161f},{-0.300465f,0.0237183f,0.125161f}, +{-0.29882f,0.023604f,0.125161f},{-0.293928f,0.0229455f,0.124927f},{-0.308332f,0.0219573f,0.125456f}, +{-0.302094f,0.0231133f,0.125434f},{-0.300486f,0.0231134f,0.125434f},{-0.298883f,0.023002f,0.125434f}, +{-0.297405f,0.0221717f,0.12559f},{-0.297298f,0.0227807f,0.125434f},{-0.303631f,0.0223867f,0.12559f}, +{-0.302072f,0.0224954f,0.12559f},{-0.300507f,0.0224956f,0.12559f},{-0.298948f,0.0223872f,0.12559f}, +{-0.279588f,0.013557f,0.122512f},{-0.280709f,0.0149379f,0.123126f},{-0.279721f,0.0134738f,0.123126f}, +{-0.280581f,0.0150302f,0.122512f},{-0.280928f,0.0147789f,0.12373f},{-0.279951f,0.0133304f,0.12373f}, +{-0.281238f,0.0145536f,0.12429f},{-0.282958f,0.0176259f,0.123126f},{-0.282845f,0.0177348f,0.122512f}, +{-0.284187f,0.018851f,0.123065f},{-0.284337f,0.0186861f,0.123602f},{-0.28403f,0.0144499f,0.12559f}, +{-0.283556f,0.0148468f,0.125434f},{-0.285063f,0.0156014f,0.12559f},{-0.284095f,0.0189523f,0.122497f}, +{-0.28167f,0.0164258f,0.122512f},{-0.284181f,0.0164494f,0.125161f},{-0.283778f,0.0168374f,0.124775f}, +{-0.285099f,0.0178459f,0.124929f},{-0.281161f,0.0125744f,0.125161f},{-0.282082f,0.0139408f,0.125161f}, +{-0.282572f,0.0135853f,0.125434f},{-0.286175f,0.0166602f,0.125592f},{-0.283429f,0.0171725f,0.12429f}, +{-0.284798f,0.018178f,0.124546f},{-0.278016f,0.00850026f,0.12429f},{-0.277119f,0.0069868f,0.12373f}, +{-0.277656f,0.00863187f,0.12373f},{-0.280276f,0.0131272f,0.12429f},{-0.279071f,0.0064225f,0.125434f}, +{-0.278223f,0.00499264f,0.125232f},{-0.278489f,0.00659057f,0.125161f},{-0.278837f,0.0119427f,0.123126f}, +{-0.278699f,0.0120165f,0.122512f},{-0.277952f,0.006746f,0.124775f},{-0.278471f,0.00833438f,0.124775f}, +{-0.278996f,0.00814234f,0.125161f},{-0.27831f,0.0102456f,0.12373f},{-0.27866f,0.0100893f,0.12429f}, +{-0.279415f,0.0116355f,0.12429f},{-0.279076f,0.0118156f,0.12373f},{-0.279303f,0.00475885f,0.125592f}, +{-0.278749f,0.00487893f,0.125455f},{-0.279665f,0.00625082f,0.12559f},{-0.277919f,0.0104197f,0.122512f}, +{-0.277254f,0.0087786f,0.122512f},{-0.276708f,0.00710556f,0.122512f},{-0.276279f,0.00541355f,0.122497f}, +{-0.283153f,0.0174384f,0.12373f},{-0.281791f,0.016325f,0.123126f},{-0.278063f,0.0103558f,0.123126f}, +{-0.277402f,0.00872472f,0.123126f},{-0.276859f,0.00706195f,0.123126f},{-0.276412f,0.00538482f,0.123062f}, +{-0.284542f,0.0184599f,0.1241f},{-0.281998f,0.0161513f,0.12373f},{-0.276629f,0.00533772f,0.1236f}, +{-0.284618f,0.0160299f,0.125434f},{-0.285434f,0.017477f,0.125233f},{-0.282292f,0.015905f,0.12429f}, +{-0.279102f,0.00989244f,0.124775f},{-0.277487f,0.00688027f,0.12429f},{-0.276927f,0.00527328f,0.124098f}, +{-0.281629f,0.0142696f,0.124775f},{-0.282663f,0.0155946f,0.124775f},{-0.280686f,0.012871f,0.124775f}, +{-0.279842f,0.0114084f,0.124775f},{-0.277301f,0.00519238f,0.124546f},{-0.283092f,0.0152353f,0.125161f}, +{-0.280336f,0.0111456f,0.125161f},{-0.279613f,0.00966451f,0.125161f},{-0.277737f,0.005098f,0.124927f}, +{-0.285795f,0.0170789f,0.125456f},{-0.281674f,0.0122538f,0.125434f},{-0.28087f,0.0108613f,0.125434f}, +{-0.280166f,0.00941806f,0.125434f},{-0.280146f,0.0077226f,0.12559f},{-0.279565f,0.00793471f,0.125434f}, +{-0.283072f,0.0132221f,0.12559f},{-0.282199f,0.0119262f,0.12559f},{-0.281416f,0.010571f,0.12559f}, +{-0.28073f,0.0091663f,0.12559f},{-0.297145f,-0.00620072f,0.100469f},{-0.299891f,-0.00241971f,0.100469f}, +{-0.299492f,-0.00214016f,0.100469f},{-0.298434f,-0.00688999f,0.100469f},{-0.297772f,-0.00657676f,0.100469f}, +{-0.299123f,-0.00713669f,0.100469f},{-0.300332f,-0.00262702f,0.100469f},{-0.296557f,-0.00576486f,0.100469f}, +{-0.296014f,-0.00527335f,0.100469f},{-0.299834f,-0.00731445f,0.100469f},{-0.300803f,-0.00275405f,0.100469f}, +{-0.299147f,-0.00179629f,0.100469f},{-0.295523f,-0.004731f,0.100469f},{-0.300558f,-0.00742168f,0.100469f}, +{-0.301289f,-0.00279661f,0.100469f},{-0.295087f,-0.00414307f,0.100469f},{-0.298867f,-0.00139723f,0.100469f}, +{-0.301289f,-0.00745764f,0.100469f},{-0.30202f,-0.0074216f,0.100469f},{-0.302744f,-0.00731392f,0.100469f}, +{-0.301774f,-0.00275426f,0.100469f},{-0.303454f,-0.00713585f,0.100469f},{-0.302244f,-0.0026284f,0.100469f}, +{-0.294398f,-0.0028536f,0.100469f},{-0.294711f,-0.00351526f,0.100469f},{-0.304805f,-0.00657672f,0.100469f}, +{-0.304143f,-0.0068893f,0.100469f},{-0.294152f,-0.00216444f,0.100469f},{-0.298661f,-0.000955369f,0.100469f}, +{-0.298535f,-0.000484912f,0.100469f},{-0.302684f,-0.00241949f,0.100469f},{-0.293866f,-0.000730865f,0.100469f}, +{-0.293974f,-0.00145464f,0.100469f},{-0.303432f,-0.0018009f,0.100469f},{-0.303078f,-0.00213198f,0.100469f}, +{-0.306562f,-0.00527224f,0.100469f},{-0.307865f,-0.00351451f,0.100469f},{-0.308178f,-0.00285307f,0.100469f}, +{-0.303917f,-0.000957231f,0.100469f},{-0.304044f,-0.000485989f,0.100469f},{-0.30871f,-0.000730708f,0.100469f}, +{-0.308425f,-0.00216422f,0.100469f},{-0.308603f,-0.00145452f,0.100469f},{-0.30602f,-0.00576389f,0.100469f}, +{-0.305432f,-0.00620014f,0.100469f},{-0.307489f,-0.00414214f,0.100469f},{-0.303711f,-0.00139896f,0.100469f}, +{-0.307053f,-0.00472993f,0.100469f},{-0.30068f,0.0121618f,0.101401f},{-0.299504f,0.0124736f,0.101401f}, +{-0.298958f,0.0127432f,0.101401f},{-0.299123f,-0.00713585f,0.101401f},{-0.295928f,-0.0107204f,0.101401f}, +{-0.293867f,-0.000730708f,0.101401f},{-0.289127f,-0.00060826f,0.101401f},{-0.294152f,-0.00216422f,0.101401f}, +{-0.288545f,-0.002331f,0.101401f},{-0.294399f,-0.00285307f,0.101401f},{-0.297252f,0.0144494f,0.101401f}, +{-0.296983f,0.0185639f,0.101401f},{-0.286992f,-0.0131013f,0.101401f},{-0.304087f,0.021256f,0.101401f}, +{-0.279887f,-0.0006084f,0.101401f},{-0.308181f,0.0203028f,0.101401f},{-0.309493f,0.0198085f,0.101401f}, +{-0.280009f,-0.00120559f,0.101401f},{-0.280205f,-0.00178272f,0.101401f},{-0.287805f,-0.00329614f,0.101401f}, +{-0.294712f,-0.00351451f,0.101401f},{-0.288207f,-0.00283787f,0.101401f},{-0.310221f,-0.0114792f,0.101401f}, +{-0.305015f,-0.0139787f,0.101401f},{-0.305351f,-0.0144948f,0.101401f},{-0.280472f,-0.00233026f,0.101401f}, +{-0.281213f,-0.00329545f,0.101401f},{-0.280811f,-0.00283697f,0.101401f},{-0.281671f,-0.00369728f,0.101401f}, +{-0.287378f,-0.0112779f,0.101401f},{-0.287149f,-0.0115926f,0.101401f},{-0.303454f,-0.00713669f,0.101401f}, +{-0.303642f,-0.0127563f,0.101401f},{-0.304143f,-0.00688999f,0.101401f},{-0.282178f,-0.00403597f,0.101401f}, +{-0.282725f,-0.00430572f,0.101401f},{-0.284509f,-0.00466102f,0.101401f},{-0.2839f,-0.00462104f,0.101401f}, +{-0.283302f,-0.00450189f,0.101401f},{-0.315425f,0.0161201f,0.101401f},{-0.310771f,0.0192295f,0.101401f}, +{-0.302507f,-0.0122874f,0.101401f},{-0.302744f,-0.00731445f,0.101401f},{-0.302019f,-0.00742168f,0.101401f}, +{-0.285117f,-0.00462115f,0.101401f},{-0.303091f,-0.0124812f,0.101401f},{-0.295088f,-0.00414214f,0.101401f}, +{-0.304152f,-0.0131016f,0.101401f},{-0.28691f,-0.01233f,0.101401f},{-0.31204f,0.0119471f,0.101401f}, +{-0.312198f,0.0115917f,0.101401f},{-0.302691f,0.0213951f,0.101401f},{-0.297993f,0.0200754f,0.101401f}, +{-0.297591f,0.0196172f,0.101401f},{-0.295524f,-0.00472993f,0.101401f},{-0.296628f,0.0167797f,0.101401f}, +{-0.296667f,0.0173884f,0.101401f},{-0.293974f,-0.00145452f,0.101401f},{-0.288815f,-0.00178435f,0.101401f}, +{-0.289127f,0.00961418f,0.101401f},{-0.290354f,0.0087231f,0.101401f},{-0.289984f,0.00884326f,0.101401f}, +{-0.288969f,0.0099696f,0.101401f},{-0.289647f,0.00903788f,0.101401f},{-0.289357f,0.00929843f,0.101401f}, +{-0.287668f,-0.0110163f,0.101401f},{-0.287669f,-0.014033f,0.101401f},{-0.288007f,-0.0142276f,0.101401f}, +{-0.288006f,-0.0108212f,0.101401f},{-0.285715f,-0.00450236f,0.101401f},{-0.296557f,-0.00576389f,0.101401f}, +{-0.296015f,-0.00527224f,0.101401f},{-0.318298f,0.0130525f,0.101401f},{-0.308808f,-0.0200792f,0.101401f}, +{-0.310142f,-0.0195277f,0.101401f},{-0.305898f,-0.0174727f,0.101401f},{-0.298434f,-0.0068893f,0.101401f}, +{-0.297772f,-0.00657672f,0.101401f},{-0.300557f,-0.0074216f,0.101401f},{-0.299833f,-0.00731392f,0.101401f}, +{-0.316449f,0.0151611f,0.101401f},{-0.317408f,0.0141371f,0.101401f},{-0.313762f,0.00178435f,0.101401f}, +{-0.313573f,0.00120563f,0.101401f},{-0.301289f,-0.00745764f,0.101401f},{-0.305617f,-0.0150508f,0.101401f}, +{-0.310451f,-0.011795f,0.101401f},{-0.312009f,0.00536018f,0.101401f},{-0.309981f,-0.0107426f,0.101401f}, +{-0.304612f,-0.0135115f,0.101401f},{-0.319116f,0.0119121f,0.101401f},{-0.308603f,-0.00145464f,0.101401f}, +{-0.308426f,-0.00216444f,0.101401f},{-0.308711f,-0.000730865f,0.101401f},{-0.320906f,0.00369728f,0.101401f}, +{-0.321364f,0.00329545f,0.101401f},{-0.322317f,0.00418323f,0.101401f},{-0.317108f,-0.0144727f,0.101401f}, +{-0.318046f,-0.0133751f,0.101401f},{-0.318908f,-0.0122169f,0.101401f},{-0.305919f,-0.0162427f,0.101401f}, +{-0.311436f,-0.0188874f,0.101401f},{-0.313881f,-0.0173532f,0.101401f},{-0.315021f,-0.0164664f,0.101401f}, +{-0.305949f,-0.0168584f,0.101401f},{-0.305556f,-0.018654f,0.101401f},{-0.307439f,-0.0205396f,0.101401f}, +{-0.305766f,-0.0180747f,0.101401f},{-0.302944f,-0.0211335f,0.101401f},{-0.303192f,-0.0213586f,0.101401f}, +{-0.303505f,-0.0208805f,0.101401f},{-0.304917f,-0.0197045f,0.101401f},{-0.306043f,-0.0209071f,0.101401f}, +{-0.305271f,-0.0192003f,0.101401f},{-0.304499f,-0.0201577f,0.101401f},{-0.304026f,-0.0205519f,0.101401f}, +{-0.304622f,-0.0211663f,0.101401f},{-0.302355f,-0.0213146f,0.101401f},{-0.301748f,-0.021419f,0.101401f}, +{-0.311447f,-0.0123703f,0.101401f},{-0.312685f,-0.0181614f,0.101401f},{-0.316098f,-0.0155048f,0.101401f}, +{-0.319691f,-0.0110032f,0.101401f},{-0.322535f,-0.00287961f,0.101401f},{-0.322293f,-0.00430325f,0.101401f}, +{-0.321956f,-0.00570752f,0.101401f},{-0.289004f,-0.00120563f,0.101401f},{-0.30602f,-0.00576486f,0.101401f}, +{-0.31022f,-0.00961513f,0.101401f},{-0.310449f,-0.00930035f,0.101401f},{-0.32039f,-0.00973944f,0.101401f}, +{-0.311077f,-0.0122501f,0.101401f},{-0.322681f,-0.00144304f,0.101401f},{-0.312428f,0.0112759f,0.101401f}, +{-0.312718f,0.0110154f,0.101401f},{-0.307054f,-0.004731f,0.101401f},{-0.306563f,-0.00527335f,0.101401f}, +{-0.310739f,-0.00903878f,0.101401f},{-0.311076f,-0.00884365f,0.101401f},{-0.311446f,-0.00872342f,0.101401f}, +{-0.30749f,-0.00414307f,0.101401f},{-0.310062f,-0.00997107f,0.101401f},{-0.305432f,-0.00620072f,0.101401f}, +{-0.304805f,-0.00657676f,0.101401f},{-0.305807f,-0.0156368f,0.101401f},{-0.31074f,-0.0120555f,0.101401f}, +{-0.301903f,-0.0121629f,0.101401f},{-0.287346f,-0.00369829f,0.101401f},{-0.297145f,-0.00620014f,0.101401f}, +{-0.286839f,-0.00403701f,0.101401f},{-0.288888f,0.0107408f,0.101401f},{-0.289356f,0.011793f,0.101401f}, +{-0.296982f,0.0149963f,0.101401f},{-0.299506f,0.0210836f,0.101401f},{-0.305471f,0.0210266f,0.101401f}, +{-0.311959f,0.0123283f,0.101401f},{-0.306838f,0.0207091f,0.101401f},{-0.31437f,0.00283787f,0.101401f}, +{-0.314772f,0.00329614f,0.101401f},{-0.314341f,0.0170101f,0.101401f},{-0.319856f,0.0107207f,0.101401f}, +{-0.321591f,0.00689212f,0.101401f},{-0.319852f,0.00430572f,0.101401f},{-0.321998f,0.00554954f,0.101401f}, +{-0.308179f,-0.0028536f,0.101401f},{-0.3132f,0.0178274f,0.101401f},{-0.313054f,0.0142272f,0.101401f}, +{-0.313424f,0.0143475f,0.101401f},{-0.320518f,0.00948339f,0.101401f},{-0.316285f,0.00430656f,0.101401f}, +{-0.31345f,0.00060826f,0.101401f},{-0.312198f,0.0134558f,0.101401f},{-0.312426f,0.0137705f,0.101401f}, +{-0.311958f,0.0127183f,0.101401f},{-0.312009f,0.0185682f,0.101401f},{-0.312716f,0.0140321f,0.101401f}, +{-0.300083f,0.0122844f,0.101401f},{-0.289645f,0.0120546f,0.101401f},{-0.289983f,0.0122497f,0.101401f}, +{-0.288888f,0.0103508f,0.101401f},{-0.296667f,0.0161715f,0.101401f},{-0.298451f,0.0130817f,0.101401f}, +{-0.297992f,0.0134836f,0.101401f},{-0.29759f,0.0139422f,0.101401f},{-0.288968f,0.0111223f,0.101401f}, +{-0.289127f,0.0114782f,0.101401f},{-0.290353f,0.01237f,0.101401f},{-0.286292f,-0.00430656f,0.101401f}, +{-0.288375f,-0.0107009f,0.101401f},{-0.288376f,-0.0143478f,0.101401f},{-0.28738f,-0.0137725f,0.101401f}, +{-0.28715f,-0.0134567f,0.101401f},{-0.28691f,-0.0127201f,0.101401f},{-0.286991f,-0.0119486f,0.101401f}, +{-0.321525f,-0.00708565f,0.101401f},{-0.321002f,-0.00843163f,0.101401f},{-0.309981f,-0.0103525f,0.101401f}, +{-0.310062f,-0.0111238f,0.101401f},{-0.307866f,-0.00351526f,0.101401f},{-0.312039f,0.0130998f,0.101401f}, +{-0.296786f,0.0155736f,0.101401f},{-0.296787f,0.0179866f,0.101401f},{-0.297253f,0.0191105f,0.101401f}, +{-0.298452f,0.0204775f,0.101401f},{-0.298958f,0.0208166f,0.101401f},{-0.30068f,0.0214014f,0.101401f}, +{-0.300083f,0.021279f,0.101401f},{-0.322372f,0.00178272f,0.101401f},{-0.322683f,0.00140253f,0.101401f}, +{-0.322546f,0.00279893f,0.101401f},{-0.321097f,0.00820537f,0.101401f},{-0.318068f,0.00466102f,0.101401f}, +{-0.318677f,0.00462104f,0.101401f},{-0.31746f,0.00462115f,0.101401f},{-0.314032f,0.002331f,0.101401f}, +{-0.316862f,0.00450236f,0.101401f},{-0.315231f,0.00369829f,0.101401f},{-0.315738f,0.00403701f,0.101401f}, +{-0.313425f,0.0107006f,0.101401f},{-0.313055f,0.0108208f,0.101401f},{-0.319275f,0.00450189f,0.101401f}, +{-0.320399f,0.00403597f,0.101401f},{-0.321766f,0.00283697f,0.101401f},{-0.322105f,0.00233026f,0.101401f}, +{-0.32269f,0.0006084f,0.101401f},{-0.322568f,0.00120559f,0.101401f},{-0.279202f,-0.0130142f,0.120045f}, +{-0.281553f,-0.0163617f,0.120045f},{-0.317715f,0.0202853f,0.120045f},{-0.318754f,0.0193978f,0.120045f}, +{-0.27854f,-0.0118202f,0.120045f},{-0.314339f,0.0226051f,0.120045f},{-0.315504f,0.0218911f,0.120045f}, +{-0.27695f,-0.00805156f,0.120045f},{-0.310642f,0.0243682f,0.120045f},{-0.311905f,0.0238452f,0.120045f}, +{-0.275979f,-0.0040778f,0.120045f},{-0.306715f,0.0255314f,0.120045f},{-0.305372f,0.0257805f,0.120045f}, +{-0.308044f,0.0252126f,0.120045f},{-0.309354f,0.0248245f,0.120045f},{-0.302654f,0.0260573f,0.120045f}, +{-0.304017f,0.0259588f,0.120045f},{-0.275698f,-0.00136419f,0.120045f},{-0.275798f,-0.00272502f,0.120045f}, +{-0.313138f,0.023257f,0.120045f},{-0.276556f,-0.00674482f,0.120045f},{-0.276232f,-0.00541896f,0.120045f}, +{-0.316631f,0.0211172f,0.120045f},{-0.277944f,-0.0105928f,0.120045f},{-0.277413f,-0.00933541f,0.120045f}, +{-0.319745f,0.0184571f,0.120045f},{-0.320686f,0.0174659f,0.120045f},{-0.279926f,-0.0141713f,0.120045f}, +{-0.321573f,0.0164267f,0.120045f},{-0.322405f,0.0153425f,0.120045f},{-0.323179f,0.0142163f,0.120045f}, +{-0.28071f,-0.0152881f,0.120045f},{-0.323893f,0.0130512f,0.120045f},{-0.324545f,0.0118502f,0.120045f}, +{-0.282452f,-0.0173888f,0.120045f},{-0.325134f,0.0106168f,0.120045f},{-0.283404f,-0.0183667f,0.120045f}, +{-0.325657f,0.00935425f,0.120045f},{-0.284407f,-0.0192925f,0.120045f},{-0.326113f,0.00806608f,0.120045f}, +{-0.285457f,-0.0201635f,0.120045f},{-0.326501f,0.00675581f,0.120045f},{-0.286553f,-0.0209774f,0.120045f}, +{-0.32682f,0.00542697f,0.120045f},{-0.28769f,-0.021732f,0.120045f},{-0.327069f,0.00408325f,0.120045f}, +{-0.288866f,-0.022425f,0.120045f},{-0.327247f,0.00272836f,0.120045f},{-0.290078f,-0.0230545f,0.120045f}, +{-0.327354f,0.00136603f,0.120045f},{-0.291321f,-0.0236185f,0.120045f},{-0.32739f,5.19219e-017f,0.120045f}, +{-0.292592f,-0.0241155f,0.120045f},{-0.326879f,-0.00136408f,0.120045f},{-0.327354f,-0.0013662f,0.120045f}, +{-0.293888f,-0.0245441f,0.120045f},{-0.326779f,-0.00272485f,0.120045f},{-0.327247f,-0.00272864f,0.120045f}, +{-0.295204f,-0.0249032f,0.120045f},{-0.326598f,-0.0040775f,0.120045f},{-0.327069f,-0.00408356f,0.120045f}, +{-0.296539f,-0.0251918f,0.120045f},{-0.297886f,-0.0254089f,0.120045f},{-0.300606f,-0.0256265f,0.120045f}, +{-0.326345f,-0.00541865f,0.120045f},{-0.32682f,-0.00542725f,0.120045f},{-0.304017f,-0.025959f,0.120045f}, +{-0.304691f,-0.0254087f,0.120045f},{-0.305372f,-0.0257802f,0.120045f},{-0.325164f,-0.00933492f,0.120045f}, +{-0.325627f,-0.00805103f,0.120045f},{-0.325656f,-0.00935456f,0.120045f},{-0.308044f,-0.0252123f,0.120045f}, +{-0.30869f,-0.0245439f,0.120045f},{-0.309354f,-0.0248241f,0.120045f},{-0.323893f,-0.0130514f,0.120045f}, +{-0.324037f,-0.0118198f,0.120045f},{-0.324545f,-0.0118505f,0.120045f},{-0.313138f,-0.0232571f,0.120045f}, +{-0.311905f,-0.0238453f,0.120045f},{-0.3125f,-0.0230539f,0.120045f},{-0.321573f,-0.0164269f,0.120045f}, +{-0.321867f,-0.0152875f,0.120045f},{-0.322405f,-0.0153428f,0.120045f},{-0.317714f,-0.0202852f,0.120045f}, +{-0.31817f,-0.019292f,0.120045f},{-0.318753f,-0.0193978f,0.120045f},{-0.314339f,-0.022605f,0.120045f}, +{-0.313711f,-0.0224246f,0.120045f},{-0.320125f,-0.0173882f,0.120045f},{-0.320685f,-0.017466f,0.120045f}, +{-0.319745f,-0.0184572f,0.120045f},{-0.319173f,-0.0183661f,0.120045f},{-0.31663f,-0.021117f,0.120045f}, +{-0.315504f,-0.021891f,0.120045f},{-0.316024f,-0.0209773f,0.120045f},{-0.314887f,-0.0217317f,0.120045f}, +{-0.321024f,-0.016361f,0.120045f},{-0.31712f,-0.0201633f,0.120045f},{-0.309986f,-0.0241152f,0.120045f}, +{-0.310642f,-0.024368f,0.120045f},{-0.311257f,-0.023618f,0.120045f},{-0.323375f,-0.0130136f,0.120045f}, +{-0.323179f,-0.0142166f,0.120045f},{-0.322651f,-0.0141706f,0.120045f},{-0.306039f,-0.0251915f,0.120045f}, +{-0.306715f,-0.0255313f,0.120045f},{-0.307373f,-0.024903f,0.120045f},{-0.324633f,-0.0105924f,0.120045f}, +{-0.325133f,-0.0106171f,0.120045f},{-0.301971f,-0.0256265f,0.120045f},{-0.302654f,-0.0260568f,0.120045f}, +{-0.303334f,-0.0255538f,0.120045f},{-0.326501f,-0.00675606f,0.120045f},{-0.326021f,-0.00674437f,0.120045f}, +{-0.326113f,-0.00806637f,0.120045f},{-0.299243f,-0.0255539f,0.120045f},{-0.306738f,-0.0255265f,0.106062f}, +{-0.305396f,-0.0257766f,0.106062f},{-0.304039f,-0.0259565f,0.106062f},{-0.310646f,-0.0243666f,0.106062f}, +{-0.308062f,-0.0252075f,0.106062f},{-0.315485f,-0.0219036f,0.106062f},{-0.314323f,-0.0226143f,0.106062f}, +{-0.313127f,-0.0232624f,0.106062f},{-0.311901f,-0.0238468f,0.106062f},{-0.318743f,-0.0194069f,0.106062f}, +{-0.316611f,-0.0211315f,0.106062f},{-0.32242f,-0.0153222f,0.106062f},{-0.321587f,-0.0164092f,0.106062f}, +{-0.320695f,-0.0174549f,0.106062f},{-0.319745f,-0.0184567f,0.106062f},{-0.324551f,-0.0118391f,0.106062f}, +{-0.323192f,-0.0141964f,0.106062f},{-0.326496f,-0.00677408f,0.106062f},{-0.326109f,-0.00807765f,0.106062f}, +{-0.325655f,-0.00935809f,0.106062f},{-0.325135f,-0.0106128f,0.106062f},{-0.327065f,-0.0041079f,0.106062f}, +{-0.327245f,-0.00275048f,0.106062f},{-0.326815f,-0.00544996f,0.106062f},{-0.327354f,0.00138025f,0.106062f}, +{-0.32739f,2.06991e-018f,0.106062f},{-0.327354f,-0.00138032f,0.106062f},{-0.326815f,0.00544975f,0.106062f}, +{-0.327065f,0.00410773f,0.106062f},{-0.327245f,0.00275036f,0.106062f},{-0.326109f,0.0080774f,0.106062f}, +{-0.326496f,0.00677384f,0.106062f},{-0.325135f,0.0106125f,0.106062f},{-0.324551f,0.0118389f,0.106062f}, +{-0.325655f,0.00935782f,0.106062f},{-0.323192f,0.0141962f,0.106062f},{-0.323903f,0.0130343f,0.106062f}, +{-0.321587f,0.0164091f,0.106062f},{-0.32242f,0.015322f,0.106062f},{-0.319745f,0.0184567f,0.106062f}, +{-0.320695f,0.0174549f,0.106062f},{-0.318743f,0.0194069f,0.106062f},{-0.317698f,0.0202988f,0.106062f}, +{-0.316611f,0.0211314f,0.106062f},{-0.315485f,0.0219036f,0.106062f},{-0.314323f,0.0226142f,0.106062f}, +{-0.313128f,0.0232623f,0.106062f},{-0.311901f,0.0238467f,0.106062f},{-0.310647f,0.0243664f,0.106062f}, +{-0.309366f,0.0248204f,0.106062f},{-0.308063f,0.0252074f,0.106062f},{-0.306739f,0.0255265f,0.106062f}, +{-0.305396f,0.0257765f,0.106062f},{-0.304039f,0.0259565f,0.106062f},{-0.302669f,0.0260652f,0.106062f}, +{-0.323903f,-0.0130346f,0.106062f},{-0.317698f,-0.0202989f,0.106062f},{-0.309366f,-0.0248205f,0.106062f}, +{-0.302669f,-0.0260653f,0.106062f},{-0.317713f,-0.013782f,0.106062f},{-0.314092f,-0.0171983f,0.106062f}, +{-0.30978f,-0.0196871f,0.106062f},{-0.305011f,-0.0211136f,0.106062f},{-0.302535f,-0.0214048f,0.106062f}, +{-0.303778f,-0.0212945f,0.106062f},{-0.308622f,-0.0201477f,0.106062f},{-0.310911f,-0.01916f,0.106062f}, +{-0.312009f,-0.0185682f,0.106062f},{-0.31307f,-0.0179136f,0.106062f},{-0.316884f,-0.0147136f,0.106062f}, +{-0.316002f,-0.0155955f,0.106062f},{-0.31507f,-0.0164247f,0.106062f},{-0.319856f,-0.0107207f,0.106062f}, +{-0.319202f,-0.0117822f,0.106062f},{-0.318486f,-0.0128038f,0.106062f},{-0.320448f,-0.00962296f,0.106062f}, +{-0.320975f,-0.00849262f,0.106062f},{-0.321436f,-0.00733354f,0.106062f},{-0.321828f,-0.00614966f,0.106062f}, +{-0.322151f,-0.00494495f,0.106062f},{-0.322403f,-0.00372348f,0.106062f},{-0.322584f,-0.00248937f,0.106062f}, +{-0.322693f,-0.00124681f,0.106062f},{-0.322729f,-1.73872e-017f,0.106062f},{-0.322693f,0.00124661f,0.106062f}, +{-0.322584f,0.00248903f,0.106062f},{-0.322404f,0.00372306f,0.106062f},{-0.322151f,0.0049445f,0.106062f}, +{-0.321829f,0.00614923f,0.106062f},{-0.321436f,0.00733314f,0.106062f},{-0.320976f,0.00849224f,0.106062f}, +{-0.319857f,0.0107204f,0.106062f},{-0.303778f,0.0212927f,0.106062f},{-0.302536f,0.0214054f,0.106062f}, +{-0.317713f,0.013782f,0.106062f},{-0.306234f,0.0208628f,0.106062f},{-0.307438f,0.0205399f,0.106062f}, +{-0.31507f,0.0164248f,0.106062f},{-0.316002f,0.0155957f,0.106062f},{-0.312009f,0.0185682f,0.106062f}, +{-0.31307f,0.0179135f,0.106062f},{-0.314092f,0.0171982f,0.106062f},{-0.309781f,0.0196873f,0.106062f}, +{-0.308622f,0.0201477f,0.106062f},{-0.310911f,0.0191602f,0.106062f},{-0.305011f,0.0211056f,0.106062f}, +{-0.316884f,0.0147138f,0.106062f},{-0.319202f,0.011782f,0.106062f},{-0.318487f,0.0128037f,0.106062f}, +{-0.320449f,0.0096226f,0.106062f},{-0.306233f,-0.02086f,0.106062f},{-0.307438f,-0.0205402f,0.106062f}, +{-0.30625f,-0.0208587f,0.10513f},{-0.305032f,-0.0211115f,0.10513f},{-0.303796f,-0.0212936f,0.10513f}, +{-0.309779f,-0.019688f,0.10513f},{-0.30745f,-0.0205363f,0.10513f},{-0.314076f,-0.0172102f,0.10513f}, +{-0.313054f,-0.0179243f,0.10513f},{-0.311995f,-0.018576f,0.10513f},{-0.310903f,-0.0191643f,0.10513f}, +{-0.316888f,-0.0147088f,0.10513f},{-0.315058f,-0.0164352f,0.10513f},{-0.319865f,-0.010707f,0.10513f}, +{-0.319213f,-0.0117656f,0.10513f},{-0.318499f,-0.0127873f,0.10513f},{-0.321434f,-0.00733859f,0.10513f}, +{-0.320976f,-0.00849054f,0.10513f},{-0.320453f,-0.0096143f,0.10513f},{-0.322582f,-0.00250813f,0.10513f}, +{-0.3224f,-0.00374334f,0.10513f},{-0.322147f,-0.00496208f,0.10513f},{-0.321825f,-0.00616144f,0.10513f}, +{-0.322729f,-2.2769e-017f,0.10513f},{-0.322692f,0.00125925f,0.10513f},{-0.322692f,-0.00125938f,0.10513f}, +{-0.3224f,0.00374312f,0.10513f},{-0.322582f,0.00250793f,0.10513f},{-0.321434f,0.0073385f,0.10513f}, +{-0.321825f,0.00616138f,0.10513f},{-0.322147f,0.00496191f,0.10513f},{-0.320453f,0.00961408f,0.10513f}, +{-0.320976f,0.00849036f,0.10513f},{-0.318499f,0.0127873f,0.10513f},{-0.319213f,0.0117655f,0.10513f}, +{-0.319865f,0.0107068f,0.10513f},{-0.316889f,0.0147082f,0.10513f},{-0.317724f,0.0137691f,0.10513f}, +{-0.315997f,0.0155998f,0.10513f},{-0.315058f,0.0164352f,0.10513f},{-0.314076f,0.0172102f,0.10513f}, +{-0.313054f,0.0179242f,0.10513f},{-0.311996f,0.018576f,0.10513f},{-0.310903f,0.0191643f,0.10513f}, +{-0.309779f,0.0196879f,0.10513f},{-0.308627f,0.0201457f,0.10513f},{-0.30745f,0.0205363f,0.10513f}, +{-0.305032f,0.0211114f,0.10513f},{-0.306251f,0.0208586f,0.10513f},{-0.303797f,0.0212935f,0.10513f}, +{-0.302548f,0.0214037f,0.10513f},{-0.317724f,-0.0137693f,0.10513f},{-0.315997f,-0.0156004f,0.10513f}, +{-0.308627f,-0.0201457f,0.10513f},{-0.302548f,-0.0214037f,0.10513f},{-0.317178f,-0.0207081f,0.10513f}, +{-0.32739f,2.25963e-017f,0.10513f},{-0.327334f,-0.00170747f,0.10513f},{-0.325403f,-0.0099892f,0.10513f}, +{-0.326889f,-0.00509254f,0.10513f},{-0.326501f,-0.00675606f,0.10513f},{-0.324698f,-0.0115449f,0.10513f}, +{-0.322991f,-0.0145019f,0.10513f},{-0.321996f,-0.0158902f,0.10513f},{-0.308044f,-0.0252123f,0.10513f}, +{-0.30638f,-0.0256001f,0.10513f},{-0.302995f,-0.0260375f,0.10513f},{-0.314339f,-0.022605f,0.10513f}, +{-0.312833f,-0.0234101f,0.10513f},{-0.311277f,-0.0241149f,0.10513f},{-0.309678f,-0.0247164f,0.10513f}, +{-0.315789f,-0.0217031f,0.10513f},{-0.319745f,-0.0184572f,0.10513f},{-0.318498f,-0.0196247f,0.10513f}, +{-0.304695f,-0.0258794f,0.10513f},{-0.320912f,-0.0172106f,0.10513f},{-0.323893f,-0.0130514f,0.10513f}, +{-0.326005f,-0.00839068f,0.10513f},{-0.327167f,-0.00340738f,0.10513f},{-0.327334f,0.00170697f,0.10513f}, +{-0.327167f,0.0034068f,0.10513f},{-0.326005f,0.00839024f,0.10513f},{-0.326501f,0.00675581f,0.10513f}, +{-0.326889f,0.00509225f,0.10513f},{-0.325404f,0.00998889f,0.10513f},{-0.324699f,0.0115449f,0.10513f}, +{-0.323893f,0.0130512f,0.10513f},{-0.321996f,0.0158901f,0.10513f},{-0.322991f,0.0145016f,0.10513f}, +{-0.320913f,0.0172105f,0.10513f},{-0.318498f,0.0196248f,0.10513f},{-0.31579f,0.0217032f,0.10513f}, +{-0.317178f,0.0207084f,0.10513f},{-0.314339f,0.0226051f,0.10513f},{-0.312833f,0.0234102f,0.10513f}, +{-0.304696f,0.0258786f,0.10513f},{-0.302996f,0.0260403f,0.10513f},{-0.306381f,0.0256003f,0.10513f}, +{-0.308044f,0.0252126f,0.10513f},{-0.309679f,0.0247167f,0.10513f},{-0.319745f,0.0184571f,0.10513f}, +{-0.311277f,0.024115f,0.10513f},{-0.312708f,0.0197792f,0.10252f},{-0.314476f,0.0186469f,0.10252f}, +{-0.31364f,0.0213938f,0.104011f},{-0.319197f,0.0141739f,0.10252f},{-0.317748f,0.0158335f,0.10252f}, +{-0.316165f,0.0173289f,0.10252f},{-0.323734f,0.00421973f,0.10252f},{-0.32323f,0.00633871f,0.10252f}, +{-0.322518f,0.00842303f,0.10252f},{-0.324128f,4.29036e-018f,0.10252f},{-0.324031f,0.00209801f,0.10252f}, +{-0.31364f,-0.0213938f,0.104011f},{-0.312708f,-0.0197792f,0.10252f},{-0.31144f,-0.0204589f,0.10252f}, +{-0.310112f,-0.0210659f,0.10252f},{-0.308729f,-0.0215929f,0.10252f},{-0.3073f,-0.0220336f,0.10252f}, +{-0.305832f,-0.0223824f,0.10252f},{-0.304335f,-0.022635f,0.10252f},{-0.302817f,-0.0227878f,0.10252f}, +{-0.307791f,-0.0238322f,0.104011f},{-0.306203f,-0.0242096f,0.104011f},{-0.312269f,-0.0221291f,0.104011f}, +{-0.304583f,-0.0244827f,0.104011f},{-0.302942f,-0.0246481f,0.104011f},{-0.309337f,-0.0233556f,0.104011f}, +{-0.310832f,-0.0227855f,0.104011f},{-0.320488f,0.0123693f,0.10252f},{-0.3216f,0.0104434f,0.10252f}, +{-0.31738f,0.0187434f,0.104011f},{-0.325992f,6.69898e-018f,0.104011f},{-0.325887f,0.00226809f,0.104011f}, +{-0.325567f,0.00456378f,0.104011f},{-0.325022f,0.00685491f,0.104011f},{-0.324251f,0.00910982f,0.104011f}, +{-0.323259f,0.011295f,0.104011f},{-0.322056f,0.0133782f,0.104011f},{-0.32066f,0.0153304f,0.104011f}, +{-0.319093f,0.0171254f,0.104011f},{-0.315553f,0.0201689f,0.104011f},{-0.275689f,-0.00136552f,0.121909f}, +{-0.275798f,-0.00272732f,0.121909f},{-0.287538f,-0.0216357f,0.121909f},{-0.285747f,-0.0203873f,0.121909f}, +{-0.289427f,-0.0227264f,0.121909f},{-0.291404f,-0.0236533f,0.121909f},{-0.311174f,-0.0236531f,0.121909f}, +{-0.31315f,-0.0227263f,0.121909f},{-0.316831f,-0.0203871f,0.121909f},{-0.315039f,-0.0216356f,0.121909f}, +{-0.326597f,-0.0040808f,0.121909f},{-0.326779f,-0.00272711f,0.121909f},{-0.326888f,-0.00136573f,0.121909f}, +{-0.27598f,-0.00408095f,0.121909f},{-0.313448f,0.000612842f,0.104198f},{-0.31403f,0.00232777f,0.104198f}, +{-0.313762f,0.00178369f,0.104198f},{-0.313567f,0.00120978f,0.104198f},{-0.315234f,0.00370055f,0.104198f}, +{-0.314368f,0.0028342f,0.104198f},{-0.314772f,0.00329584f,0.104198f},{-0.317456f,0.00462066f,0.104198f}, +{-0.316859f,0.00450141f,0.104198f},{-0.316285f,0.00430621f,0.104198f},{-0.318681f,0.00462052f,0.104198f}, +{-0.319278f,0.00450127f,0.104198f},{-0.318068f,0.00466102f,0.104198f},{-0.320396f,0.00403818f,0.104198f}, +{-0.319852f,0.00430621f,0.104198f},{-0.321364f,0.00329584f,0.104198f},{-0.320902f,0.00370041f,0.104198f}, +{-0.321769f,0.00283386f,0.104198f},{-0.322107f,0.00232743f,0.104198f},{-0.322374f,0.00178369f,0.104198f}, +{-0.32257f,0.00120944f,0.104198f},{-0.322689f,0.000612502f,0.104198f},{-0.315741f,0.00403832f,0.104198f}, +{-0.311076f,-0.00884266f,0.110723f},{-0.310739f,-0.00903773f,0.110723f},{-0.311447f,-0.00872205f,0.110723f}, +{-0.310449f,-0.00929879f,0.110723f},{-0.31022f,-0.00961469f,0.110723f},{-0.310062f,-0.00997137f,0.110723f}, +{-0.309981f,-0.0103527f,0.110723f},{-0.309981f,-0.0107427f,0.110723f},{-0.310223f,-0.0114796f,0.110723f}, +{-0.310063f,-0.011124f,0.110723f},{-0.310741f,-0.0120547f,0.110723f},{-0.310452f,-0.0117943f,0.110723f}, +{-0.311448f,-0.0123696f,0.110723f},{-0.311078f,-0.0122492f,0.110723f},{-0.288006f,-0.0108202f,0.110723f}, +{-0.287668f,-0.0110152f,0.110723f},{-0.288376f,-0.0106996f,0.110723f},{-0.287378f,-0.0112763f,0.110723f}, +{-0.287149f,-0.0115922f,0.110723f},{-0.286991f,-0.0119489f,0.110723f},{-0.28691f,-0.0123302f,0.110723f}, +{-0.286911f,-0.0127202f,0.110723f},{-0.287152f,-0.0134571f,0.110723f},{-0.286993f,-0.0131015f,0.110723f}, +{-0.28767f,-0.0140322f,0.110723f},{-0.287381f,-0.0137718f,0.110723f},{-0.288378f,-0.0143471f,0.110723f}, +{-0.288007f,-0.0142268f,0.110723f},{-0.289983f,0.0122507f,0.110723f},{-0.289645f,0.0120557f,0.110723f}, +{-0.290354f,0.0123713f,0.110723f},{-0.289355f,0.0117946f,0.110723f},{-0.289126f,0.0114787f,0.110723f}, +{-0.288968f,0.011122f,0.110723f},{-0.288888f,0.0107407f,0.110723f},{-0.288888f,0.0103507f,0.110723f}, +{-0.289129f,0.00961383f,0.110723f},{-0.28897f,0.00996936f,0.110723f},{-0.289648f,0.00903866f,0.110723f}, +{-0.289358f,0.00929907f,0.110723f},{-0.290355f,0.00872375f,0.110723f},{-0.289985f,0.00884413f,0.110723f}, +{-0.313054f,0.0142282f,0.110723f},{-0.312716f,0.0140332f,0.110723f},{-0.313425f,0.0143488f,0.110723f}, +{-0.312426f,0.0137721f,0.110723f},{-0.312197f,0.0134562f,0.110723f},{-0.312039f,0.0130995f,0.110723f}, +{-0.311959f,0.0127182f,0.110723f},{-0.311959f,0.0123282f,0.110723f},{-0.3122f,0.0115913f,0.110723f}, +{-0.312041f,0.0119469f,0.110723f},{-0.312719f,0.0110162f,0.110723f},{-0.312429f,0.0112766f,0.110723f}, +{-0.313426f,0.0107013f,0.110723f},{-0.313056f,0.0108216f,0.110723f},{-0.301901f,-0.0121592f,0.104198f}, +{-0.303616f,-0.0127415f,0.104198f},{-0.302498f,-0.0122784f,0.104198f},{-0.303072f,-0.0124735f,0.104198f}, +{-0.304989f,-0.0139458f,0.104198f},{-0.305327f,-0.0144523f,0.104198f},{-0.304584f,-0.0134838f,0.104198f}, +{-0.305909f,-0.0161672f,0.104198f},{-0.305595f,-0.014996f,0.104198f},{-0.30579f,-0.0155702f,0.104198f}, +{-0.30579f,-0.0179895f,0.104198f},{-0.30595f,-0.0167797f,0.104198f},{-0.305909f,-0.0173925f,0.104198f}, +{-0.305327f,-0.0191075f,0.104198f},{-0.304989f,-0.0196139f,0.104198f},{-0.305595f,-0.0185634f,0.104198f}, +{-0.304584f,-0.0200755f,0.104198f},{-0.304122f,-0.0204802f,0.104198f},{-0.303616f,-0.020818f,0.104198f}, +{-0.303072f,-0.0210859f,0.104198f},{-0.302498f,-0.0212811f,0.104198f},{-0.301901f,-0.0214003f,0.104198f}, +{-0.304123f,-0.0130793f,0.104198f},{-0.289129f,-0.000612842f,0.104198f},{-0.288547f,-0.00232777f,0.104198f}, +{-0.288815f,-0.00178369f,0.104198f},{-0.28901f,-0.00120978f,0.104198f},{-0.287343f,-0.00370055f,0.104198f}, +{-0.288209f,-0.0028342f,0.104198f},{-0.287805f,-0.00329584f,0.104198f},{-0.285121f,-0.00462066f,0.104198f}, +{-0.285718f,-0.00450141f,0.104198f},{-0.286293f,-0.00430621f,0.104198f},{-0.283299f,-0.00450127f,0.104198f}, +{-0.283896f,-0.00462052f,0.104198f},{-0.284509f,-0.00466102f,0.104198f},{-0.282181f,-0.00403818f,0.104198f}, +{-0.282725f,-0.00430621f,0.104198f},{-0.281213f,-0.00329584f,0.104198f},{-0.281675f,-0.00370041f,0.104198f}, +{-0.280808f,-0.00283386f,0.104198f},{-0.280471f,-0.00232743f,0.104198f},{-0.280203f,-0.00178369f,0.104198f}, +{-0.280007f,-0.00120944f,0.104198f},{-0.279888f,-0.000612502f,0.104198f},{-0.286836f,-0.00403832f,0.104198f}, +{-0.300676f,0.0121592f,0.104198f},{-0.298961f,0.0127415f,0.104198f},{-0.299505f,0.0124735f,0.104198f}, +{-0.300079f,0.0122784f,0.104198f},{-0.297588f,0.0139458f,0.104198f},{-0.298454f,0.0130793f,0.104198f}, +{-0.297993f,0.0134838f,0.104198f},{-0.296668f,0.0161672f,0.104198f},{-0.296787f,0.0155702f,0.104198f}, +{-0.296982f,0.014996f,0.104198f},{-0.296668f,0.0173925f,0.104198f},{-0.296787f,0.0179895f,0.104198f}, +{-0.296628f,0.0167797f,0.104198f},{-0.29725f,0.0191075f,0.104198f},{-0.296982f,0.0185634f,0.104198f}, +{-0.297993f,0.0200755f,0.104198f},{-0.297588f,0.0196139f,0.104198f},{-0.298455f,0.0204802f,0.104198f}, +{-0.298961f,0.020818f,0.104198f},{-0.299505f,0.0210859f,0.104198f},{-0.300079f,0.0212811f,0.104198f}, +{-0.300676f,0.0214003f,0.104198f},{-0.29725f,0.0144523f,0.104198f},{-0.289869f,-0.0197792f,0.104198f}, +{-0.291807f,-0.0207778f,0.104198f},{-0.298032f,-0.0226057f,0.104198f},{-0.293823f,-0.0215843f,0.104198f}, +{-0.304545f,-0.0226056f,0.104198f},{-0.300198f,-0.022813f,0.104198f},{-0.30238f,-0.0228129f,0.104198f}, +{-0.308755f,-0.0215842f,0.104198f},{-0.306675f,-0.0221948f,0.104198f},{-0.310771f,-0.0207777f,0.104198f}, +{-0.312708f,-0.0197792f,0.104198f},{-0.295903f,-0.0221949f,0.104198f},{-0.288937f,-0.0213938f,0.104198f}, +{-0.31364f,-0.0213938f,0.104198f},{-0.311544f,-0.022474f,0.104198f},{-0.304811f,-0.0244511f,0.104198f}, +{-0.309364f,-0.0233463f,0.104198f},{-0.297766f,-0.024451f,0.104198f},{-0.302468f,-0.0246752f,0.104198f}, +{-0.300108f,-0.0246752f,0.104198f},{-0.293213f,-0.0233462f,0.104198f},{-0.291032f,-0.0224738f,0.104198f}, +{-0.295463f,-0.0240066f,0.104198f},{-0.307114f,-0.0240067f,0.104198f},{-0.288035f,0.0186002f,0.104198f}, +{-0.289869f,0.0197792f,0.104198f},{-0.28334f,0.0141228f,0.104198f},{-0.28476f,0.0157616f,0.104198f}, +{-0.286329f,0.0172577f,0.104198f},{-0.280986f,0.0104612f,0.104198f},{-0.280083f,0.00848256f,0.104198f}, +{-0.282077f,0.0123508f,0.104198f},{-0.278863f,0.00432634f,0.104198f},{-0.279374f,0.00643279f,0.104198f}, +{-0.278553f,0.00217707f,0.104198f},{-0.27845f,-1.74881e-017f,0.104198f},{-0.288937f,0.0213938f,0.104198f}, +{-0.276585f,-1.89158e-017f,0.104198f},{-0.276698f,0.00235542f,0.104198f},{-0.278352f,0.00917539f,0.104198f}, +{-0.277585f,0.0069585f,0.104198f},{-0.277032f,0.00467972f,0.104198f},{-0.28051f,0.01336f,0.104198f}, +{-0.281875f,0.015276f,0.104198f},{-0.279329f,0.0113162f,0.104198f},{-0.283411f,0.0170487f,0.104198f}, +{-0.285108f,0.0186667f,0.104198f},{-0.286954f,0.020119f,0.104198f},{-0.324023f,0.00217765f,0.104198f}, +{-0.324128f,0.0f,0.104198f},{-0.322494f,0.00848291f,0.104198f},{-0.323203f,0.00643333f,0.104198f}, +{-0.323714f,0.00432654f,0.104198f},{-0.320499f,0.0123517f,0.104198f},{-0.319237f,0.0141231f,0.104198f}, +{-0.32159f,0.0104622f,0.104198f},{-0.316248f,0.0172579f,0.104198f},{-0.317817f,0.015762f,0.104198f}, +{-0.314541f,0.0186006f,0.104198f},{-0.312708f,0.0197792f,0.104198f},{-0.325992f,8.08559e-018f,0.104198f}, +{-0.31364f,0.0213938f,0.104198f},{-0.315624f,0.0201186f,0.104198f},{-0.320703f,0.0152757f,0.104198f}, +{-0.319166f,0.0170482f,0.104198f},{-0.317469f,0.0186665f,0.104198f},{-0.323248f,0.0113151f,0.104198f}, +{-0.324225f,0.00917501f,0.104198f},{-0.322068f,0.013359f,0.104198f},{-0.324992f,0.00695792f,0.104198f}, +{-0.325545f,0.00467951f,0.104198f},{-0.32588f,0.00235479f,0.104198f},{-0.304042f,-0.000488516f,0.0986044f}, +{-0.303431f,-0.00179767f,0.0986044f},{-0.303711f,-0.00139727f,0.0986044f},{-0.303916f,-0.000957717f,0.0986044f}, +{-0.302245f,-0.00262801f,0.0986044f},{-0.301776f,-0.00275376f,0.0986044f},{-0.303084f,-0.00214411f,0.0986044f}, +{-0.302684f,-0.00242333f,0.0986044f},{-0.300331f,-0.00262748f,0.0986044f},{-0.3008f,-0.00275356f,0.0986044f}, +{-0.301289f,-0.00279661f,0.0986044f},{-0.299491f,-0.00214219f,0.0986044f},{-0.299891f,-0.00242266f,0.0986044f}, +{-0.299144f,-0.00179504f,0.0986044f},{-0.298865f,-0.00139564f,0.0986044f},{-0.298661f,-0.000956449f,0.0986044f}, +{-0.298535f,-0.000488516f,0.0986044f},{-0.283879f,-0.00122594f,0.121909f},{-0.284001f,-0.00061944f,0.121909f}, +{-0.284043f,-1.93104e-018f,0.121909f},{-0.283676f,-0.0018111f,0.121909f},{-0.283048f,-0.00287862f,0.121909f}, +{-0.283397f,-0.00236645f,0.121909f},{-0.282634f,-0.00333866f,0.121909f},{-0.282162f,-0.00374077f,0.121909f}, +{-0.28164f,-0.00407752f,0.121909f},{-0.281079f,-0.00434093f,0.121909f},{-0.280489f,-0.00452747f,0.121909f}, +{-0.279878f,-0.00463457f,0.121909f},{-0.284001f,0.000619763f,0.121909f},{-0.283879f,0.00122605f,0.121909f}, +{-0.283676f,0.00181151f,0.121909f},{-0.283397f,0.00236685f,0.121909f},{-0.283047f,0.00287881f,0.121909f}, +{-0.282634f,0.00333885f,0.121909f},{-0.282162f,0.00374104f,0.121909f},{-0.281639f,0.00407771f,0.121909f}, +{-0.281079f,0.00434097f,0.121909f},{-0.280489f,0.00452758f,0.121909f},{-0.279878f,0.00463457f,0.121909f}, +{-0.293673f,0.00708542f,0.121909f},{-0.293069f,0.00862355f,0.121909f},{-0.293346f,0.0081433f,0.121909f}, +{-0.293548f,0.00762768f,0.121909f},{-0.291847f,0.00975654f,0.121909f},{-0.292719f,0.00906182f,0.121909f}, +{-0.292307f,0.00944325f,0.121909f},{-0.289704f,0.0102431f,0.121909f},{-0.290265f,0.0102438f,0.121909f}, +{-0.290819f,0.0101602f,0.121909f},{-0.288623f,0.0099962f,0.121909f},{-0.289153f,0.0101597f,0.121909f}, +{-0.287661f,0.00944071f,0.121909f},{-0.287251f,0.00905963f,0.121909f},{-0.288123f,0.00975564f,0.121909f}, +{-0.286903f,0.00862291f,0.121909f},{-0.286626f,0.0081413f,0.121909f},{-0.286423f,0.00762524f,0.121909f}, +{-0.2863f,0.00708542f,0.121909f},{-0.291348f,0.00999655f,0.121909f},{-0.29379f,0.000388892f,0.121909f}, +{-0.293213f,0.0013863f,0.121909f},{-0.29367f,0.000758756f,0.121909f},{-0.292161f,0.00185425f,0.121909f}, +{-0.292898f,0.00161492f,0.121909f},{-0.292542f,0.0017734f,0.121909f},{-0.291389f,0.00177278f,0.121909f}, +{-0.291034f,0.0016145f,0.121909f},{-0.291771f,0.00185398f,0.121909f},{-0.290718f,0.00138471f,0.121909f}, +{-0.290458f,0.00109509f,0.121909f},{-0.290263f,0.000757801f,0.121909f},{-0.290143f,0.000387896f,0.121909f}, +{-0.293474f,0.00109643f,0.121909f},{-0.294965f,0.0184341f,0.121909f},{-0.294991f,0.019053f,0.121909f}, +{-0.294936f,0.0196708f,0.121909f},{-0.294853f,0.0178247f,0.121909f},{-0.294661f,0.0172353f,0.121909f}, +{-0.294392f,0.0166765f,0.121909f},{-0.294051f,0.0161585f,0.121909f},{-0.292666f,0.0149353f,0.121909f}, +{-0.292109f,0.0146616f,0.121909f},{-0.293645f,0.0156903f,0.121909f},{-0.293181f,0.0152802f,0.121909f}, +{-0.290913f,0.0143468f,0.121909f},{-0.290294f,0.0143112f,0.121909f},{-0.286967f,0.0157495f,0.121909f}, +{-0.287426f,0.015333f,0.121909f},{-0.289069f,0.0144863f,0.121909f},{-0.288486f,0.0146944f,0.121909f}, +{-0.287935f,0.0149788f,0.121909f},{-0.286569f,0.0162251f,0.121909f},{-0.289676f,0.014358f,0.121909f}, +{-0.291521f,0.0144643f,0.121909f},{-0.294812f,0.0202771f,0.121909f},{-0.294597f,0.0208597f,0.121909f}, +{-0.303617f,0.0101384f,0.121909f},{-0.304647f,0.0114304f,0.121909f},{-0.304369f,0.0109503f,0.121909f}, +{-0.304024f,0.0105172f,0.121909f},{-0.305017f,0.0130549f,0.121909f},{-0.304852f,0.011952f,0.121909f}, +{-0.304976f,0.0124996f,0.121909f},{-0.304367f,0.0151544f,0.121909f},{-0.304648f,0.0146689f,0.121909f}, +{-0.304853f,0.0141474f,0.121909f},{-0.303613f,0.0159666f,0.121909f},{-0.304019f,0.01559f,0.121909f}, +{-0.302651f,0.0165217f,0.121909f},{-0.302116f,0.0166864f,0.121909f},{-0.303154f,0.0162794f,0.121909f}, +{-0.301564f,0.0167695f,0.121909f},{-0.301008f,0.016769f,0.121909f},{-0.300459f,0.0166865f,0.121909f}, +{-0.29993f,0.0165233f,0.121909f},{-0.304976f,0.0136068f,0.121909f},{-0.297876f,0.00668844f,0.121909f}, +{-0.298451f,0.00768651f,0.121909f},{-0.298136f,0.00697788f,0.121909f},{-0.29833f,0.00883213f,0.121909f}, +{-0.298492f,0.00807381f,0.121909f},{-0.298451f,0.0084617f,0.121909f},{-0.297874f,0.00945932f,0.121909f}, +{-0.297559f,0.00968801f,0.121909f},{-0.298135f,0.00916954f,0.121909f},{-0.297203f,0.00984652f,0.121909f}, +{-0.296822f,0.00992735f,0.121909f},{-0.296432f,0.00992722f,0.121909f},{-0.296051f,0.00984624f,0.121909f}, +{-0.298331f,0.00731557f,0.121909f},{-0.31464f,0.0149805f,0.121909f},{-0.315148f,0.0153371f,0.121909f}, +{-0.308931f,0.0156909f,0.121909f},{-0.309396f,0.0152805f,0.121909f},{-0.308525f,0.0161593f,0.121909f}, +{-0.309911f,0.0149353f,0.121909f},{-0.308185f,0.0166773f,0.121909f},{-0.307917f,0.0172358f,0.121909f}, +{-0.307724f,0.0178252f,0.121909f},{-0.310468f,0.0146618f,0.121909f},{-0.311055f,0.0144645f,0.121909f}, +{-0.307613f,0.0184349f,0.121909f},{-0.311664f,0.0143468f,0.121909f},{-0.307584f,0.0190544f,0.121909f}, +{-0.307767f,0.0202777f,0.121909f},{-0.307636f,0.0196718f,0.121909f},{-0.312283f,0.0143109f,0.121909f}, +{-0.30798f,0.0208597f,0.121909f},{-0.312901f,0.0143575f,0.121909f},{-0.314091f,0.0146931f,0.121909f}, +{-0.313507f,0.0144856f,0.121909f},{-0.315611f,0.0157476f,0.121909f},{-0.316008f,0.0162251f,0.121909f}, +{-0.311233f,0.00305297f,0.121909f},{-0.312867f,0.00280688f,0.121909f},{-0.312312f,0.00280698f,0.121909f}, +{-0.311764f,0.00288948f,0.121909f},{-0.314459f,0.00329833f,0.121909f},{-0.313421f,0.00289017f,0.121909f}, +{-0.313957f,0.00305631f,0.121909f},{-0.315952f,0.00491125f,0.121909f},{-0.315672f,0.00442515f,0.121909f}, +{-0.315323f,0.00398713f,0.121909f},{-0.316278f,0.00597044f,0.121909f},{-0.316155f,0.00543021f,0.121909f}, +{-0.316278f,0.00708102f,0.121909f},{-0.316153f,0.00762679f,0.121909f},{-0.31632f,0.00652376f,0.121909f}, +{-0.315949f,0.0081466f,0.121909f},{-0.315671f,0.00862774f,0.121909f},{-0.315325f,0.00906124f,0.121909f}, +{-0.314919f,0.00943791f,0.121909f},{-0.314916f,0.00361021f,0.121909f},{-0.305375f,0.0062997f,0.121909f}, +{-0.306527f,0.00630037f,0.121909f},{-0.305755f,0.00621894f,0.121909f},{-0.307458f,0.0069779f,0.121909f}, +{-0.306882f,0.00645888f,0.121909f},{-0.307198f,0.0066883f,0.121909f},{-0.307773f,0.00768661f,0.121909f}, +{-0.307814f,0.00807365f,0.121909f},{-0.307653f,0.00731544f,0.121909f},{-0.307773f,0.00846171f,0.121909f}, +{-0.307652f,0.00883217f,0.121909f},{-0.307458f,0.00916947f,0.121909f},{-0.307197f,0.00945876f,0.121909f}, +{-0.306145f,0.00621907f,0.121909f},{-0.319179f,-0.0023656f,0.121909f},{-0.318901f,-0.00181168f,0.121909f}, +{-0.319529f,-0.00287783f,0.121909f},{-0.319943f,-0.00333905f,0.121909f},{-0.320415f,-0.00374099f,0.121909f}, +{-0.318698f,-0.00122583f,0.121909f},{-0.320938f,-0.00407246f,0.121909f},{-0.318576f,-0.000618365f,0.121909f}, +{-0.318534f,4.86429e-018f,0.121909f},{-0.318576f,0.000618856f,0.121909f},{-0.318699f,0.00122657f,0.121909f}, +{-0.318901f,0.00181243f,0.121909f},{-0.31918f,0.00236609f,0.121909f},{-0.319529f,0.00287783f,0.121909f}, +{-0.319944f,0.00333893f,0.121909f},{-0.320416f,0.00374048f,0.121909f},{-0.320938f,0.00407552f,0.121909f}, +{-0.321499f,0.00433883f,0.121909f},{-0.322089f,0.0045282f,0.121909f},{-0.322699f,0.00463457f,0.121909f}, +{-0.322087f,-0.00452954f,0.121909f},{-0.3215f,-0.00433369f,0.121909f},{-0.322699f,-0.00463457f,0.121909f}, +{-0.308905f,-0.00708542f,0.121909f},{-0.309508f,-0.00862355f,0.121909f},{-0.309231f,-0.0081433f,0.121909f}, +{-0.309029f,-0.00762768f,0.121909f},{-0.31073f,-0.00975654f,0.121909f},{-0.309858f,-0.00906182f,0.121909f}, +{-0.31027f,-0.00944325f,0.121909f},{-0.312873f,-0.0102431f,0.121909f},{-0.312313f,-0.0102438f,0.121909f}, +{-0.311758f,-0.0101602f,0.121909f},{-0.313954f,-0.0099962f,0.121909f},{-0.313425f,-0.0101597f,0.121909f}, +{-0.314916f,-0.00944071f,0.121909f},{-0.315326f,-0.00905963f,0.121909f},{-0.314454f,-0.00975564f,0.121909f}, +{-0.315674f,-0.00862291f,0.121909f},{-0.315951f,-0.0081413f,0.121909f},{-0.316154f,-0.00762524f,0.121909f}, +{-0.316277f,-0.00708542f,0.121909f},{-0.311229f,-0.00999655f,0.121909f},{-0.308787f,-0.000388892f,0.121909f}, +{-0.309364f,-0.0013863f,0.121909f},{-0.308908f,-0.000758756f,0.121909f},{-0.310416f,-0.00185425f,0.121909f}, +{-0.309679f,-0.00161492f,0.121909f},{-0.310035f,-0.0017734f,0.121909f},{-0.311188f,-0.00177278f,0.121909f}, +{-0.311543f,-0.0016145f,0.121909f},{-0.310806f,-0.00185398f,0.121909f},{-0.311859f,-0.00138471f,0.121909f}, +{-0.312119f,-0.00109509f,0.121909f},{-0.312314f,-0.000757801f,0.121909f},{-0.312434f,-0.000387896f,0.121909f}, +{-0.309103f,-0.00109643f,0.121909f},{-0.307586f,-0.019053f,0.121909f},{-0.307612f,-0.0184341f,0.121909f}, +{-0.316008f,-0.0162251f,0.121909f},{-0.307724f,-0.0178247f,0.121909f},{-0.307641f,-0.0196708f,0.121909f}, +{-0.307916f,-0.0172353f,0.121909f},{-0.308185f,-0.0166765f,0.121909f},{-0.308932f,-0.0156903f,0.121909f}, +{-0.309397f,-0.0152802f,0.121909f},{-0.308526f,-0.0161585f,0.121909f},{-0.311664f,-0.0143468f,0.121909f}, +{-0.312283f,-0.0143112f,0.121909f},{-0.309911f,-0.0149353f,0.121909f},{-0.310468f,-0.0146616f,0.121909f}, +{-0.31561f,-0.0157495f,0.121909f},{-0.315151f,-0.015333f,0.121909f},{-0.313508f,-0.0144863f,0.121909f}, +{-0.314092f,-0.0146944f,0.121909f},{-0.314643f,-0.0149788f,0.121909f},{-0.312901f,-0.014358f,0.121909f}, +{-0.311056f,-0.0144643f,0.121909f},{-0.307765f,-0.0202771f,0.121909f},{-0.30798f,-0.0208597f,0.121909f}, +{-0.29896f,-0.0101384f,0.121909f},{-0.29793f,-0.0114304f,0.121909f},{-0.298208f,-0.0109503f,0.121909f}, +{-0.298553f,-0.0105172f,0.121909f},{-0.29756f,-0.0130549f,0.121909f},{-0.297725f,-0.011952f,0.121909f}, +{-0.297601f,-0.0124996f,0.121909f},{-0.29821f,-0.0151544f,0.121909f},{-0.297929f,-0.0146689f,0.121909f}, +{-0.297725f,-0.0141474f,0.121909f},{-0.298964f,-0.0159666f,0.121909f},{-0.298558f,-0.01559f,0.121909f}, +{-0.299926f,-0.0165217f,0.121909f},{-0.300461f,-0.0166864f,0.121909f},{-0.299423f,-0.0162794f,0.121909f}, +{-0.301014f,-0.0167695f,0.121909f},{-0.301569f,-0.016769f,0.121909f},{-0.302118f,-0.0166865f,0.121909f}, +{-0.302647f,-0.0165233f,0.121909f},{-0.297601f,-0.0136068f,0.121909f},{-0.304701f,-0.00668858f,0.121909f}, +{-0.304126f,-0.00768692f,0.121909f},{-0.304441f,-0.00697763f,0.121909f},{-0.304247f,-0.00883211f,0.121909f}, +{-0.304085f,-0.00807384f,0.121909f},{-0.304126f,-0.00846133f,0.121909f},{-0.304703f,-0.00945929f,0.121909f}, +{-0.305018f,-0.00968796f,0.121909f},{-0.304442f,-0.00916975f,0.121909f},{-0.305375f,-0.00984651f,0.121909f}, +{-0.305756f,-0.00992734f,0.121909f},{-0.306145f,-0.00992724f,0.121909f},{-0.306525f,-0.00984636f,0.121909f}, +{-0.304246f,-0.00731545f,0.121909f},{-0.293646f,-0.0156909f,0.121909f},{-0.294052f,-0.0161593f,0.121909f}, +{-0.293181f,-0.0152805f,0.121909f},{-0.292666f,-0.0149353f,0.121909f},{-0.294392f,-0.0166773f,0.121909f}, +{-0.29466f,-0.0172358f,0.121909f},{-0.294853f,-0.0178252f,0.121909f},{-0.29211f,-0.0146618f,0.121909f}, +{-0.294964f,-0.0184349f,0.121909f},{-0.294994f,-0.0190544f,0.121909f},{-0.291522f,-0.0144645f,0.121909f}, +{-0.294941f,-0.0196718f,0.121909f},{-0.290913f,-0.0143468f,0.121909f},{-0.290295f,-0.0143109f,0.121909f}, +{-0.29481f,-0.0202777f,0.121909f},{-0.294597f,-0.0208597f,0.121909f},{-0.289676f,-0.0143575f,0.121909f}, +{-0.288486f,-0.0146931f,0.121909f},{-0.28907f,-0.0144856f,0.121909f},{-0.287937f,-0.0149805f,0.121909f}, +{-0.28743f,-0.0153371f,0.121909f},{-0.286966f,-0.0157476f,0.121909f},{-0.286569f,-0.0162251f,0.121909f}, +{-0.291344f,-0.00305297f,0.121909f},{-0.28971f,-0.00280688f,0.121909f},{-0.290265f,-0.00280698f,0.121909f}, +{-0.290813f,-0.00288948f,0.121909f},{-0.288118f,-0.00329833f,0.121909f},{-0.289156f,-0.00289017f,0.121909f}, +{-0.28862f,-0.00305631f,0.121909f},{-0.286625f,-0.00491125f,0.121909f},{-0.286905f,-0.00442515f,0.121909f}, +{-0.287255f,-0.00398713f,0.121909f},{-0.286299f,-0.00597044f,0.121909f},{-0.286422f,-0.00543021f,0.121909f}, +{-0.286299f,-0.00708102f,0.121909f},{-0.286424f,-0.00762679f,0.121909f},{-0.286257f,-0.00652376f,0.121909f}, +{-0.286628f,-0.0081466f,0.121909f},{-0.286907f,-0.00862774f,0.121909f},{-0.287252f,-0.00906124f,0.121909f}, +{-0.287658f,-0.00943791f,0.121909f},{-0.287661f,-0.00361021f,0.121909f},{-0.297203f,-0.0062997f,0.121909f}, +{-0.29605f,-0.00630037f,0.121909f},{-0.296822f,-0.00621894f,0.121909f},{-0.295119f,-0.0069779f,0.121909f}, +{-0.295695f,-0.00645888f,0.121909f},{-0.295379f,-0.0066883f,0.121909f},{-0.294804f,-0.00768661f,0.121909f}, +{-0.294763f,-0.00807365f,0.121909f},{-0.294924f,-0.00731544f,0.121909f},{-0.294804f,-0.00846171f,0.121909f}, +{-0.294925f,-0.00883217f,0.121909f},{-0.29512f,-0.00916947f,0.121909f},{-0.29538f,-0.00945876f,0.121909f}, +{-0.296432f,-0.00621907f,0.121909f},{-0.296668f,-0.000612842f,0.127503f},{-0.29725f,-0.00232777f,0.127503f}, +{-0.296787f,-0.00120978f,0.127503f},{-0.298455f,-0.00370055f,0.127503f},{-0.298961f,-0.00403832f,0.127503f}, +{-0.297993f,-0.00329584f,0.127503f},{-0.300676f,-0.00462066f,0.127503f},{-0.299505f,-0.00430621f,0.127503f}, +{-0.300079f,-0.00450141f,0.127503f},{-0.302498f,-0.00450127f,0.127503f},{-0.301289f,-0.00466102f,0.127503f}, +{-0.301901f,-0.00462052f,0.127503f},{-0.303616f,-0.00403818f,0.127503f},{-0.304123f,-0.00370041f,0.127503f}, +{-0.303072f,-0.00430621f,0.127503f},{-0.304584f,-0.00329584f,0.127503f},{-0.304989f,-0.00283386f,0.127503f}, +{-0.305327f,-0.00232743f,0.127503f},{-0.305595f,-0.00178369f,0.127503f},{-0.30579f,-0.00120944f,0.127503f}, +{-0.305909f,-0.000612502f,0.127503f},{-0.297588f,-0.0028342f,0.127503f},{-0.296982f,-0.00178369f,0.127503f}, +{-0.302686f,-0.00241971f,0.127503f},{-0.304042f,-0.000484912f,0.127503f},{-0.30371f,-0.00139723f,0.127503f}, +{-0.30343f,-0.00179629f,0.127503f},{-0.303916f,-0.000955369f,0.127503f},{-0.303085f,-0.00214016f,0.127503f}, +{-0.302245f,-0.00262702f,0.127503f},{-0.301774f,-0.00275405f,0.127503f},{-0.301289f,-0.00279661f,0.127503f}, +{-0.300333f,-0.0026284f,0.127503f},{-0.300803f,-0.00275426f,0.127503f},{-0.299894f,-0.00241949f,0.127503f}, +{-0.298533f,-0.000485989f,0.127503f},{-0.299499f,-0.00213198f,0.127503f},{-0.29866f,-0.000957231f,0.127503f}, +{-0.298866f,-0.00139896f,0.127503f},{-0.299145f,-0.0018009f,0.127503f},{-0.304044f,-0.000485989f,0.13496f}, +{-0.303917f,-0.000957231f,0.13496f},{-0.303711f,-0.00139896f,0.13496f},{-0.303432f,-0.0018009f,0.13496f}, +{-0.303078f,-0.00213198f,0.13496f},{-0.302684f,-0.00241949f,0.13496f},{-0.302244f,-0.0026284f,0.13496f}, +{-0.301774f,-0.00275426f,0.13496f},{-0.301289f,-0.00279661f,0.13496f},{-0.300803f,-0.00275405f,0.13496f}, +{-0.299492f,-0.00214016f,0.13496f},{-0.298661f,-0.000955369f,0.13496f},{-0.300332f,-0.00262702f,0.13496f}, +{-0.299891f,-0.00241971f,0.13496f},{-0.299147f,-0.00179629f,0.13496f},{-0.298867f,-0.00139723f,0.13496f}, +{-0.298535f,-0.000484912f,0.13496f},{-2.55212e-017f,0.304085f,0.127503f},{-2.89175e-017f,0.304085f,0.13496f}, +{0.000488516f,0.304042f,0.13496f},{0.000957717f,0.303916f,0.13496f},{0.00048723f,0.304042f,0.127503f}, +{0.000956449f,0.303917f,0.127503f},{0.00139564f,0.303712f,0.127503f},{0.00179504f,0.303433f,0.127503f}, +{0.00139727f,0.303711f,0.13496f},{0.00179767f,0.303431f,0.13496f},{0.00214219f,0.303086f,0.127503f}, +{0.00214411f,0.303084f,0.13496f},{0.00242266f,0.302686f,0.127503f},{0.00262748f,0.302246f,0.127503f}, +{0.00242333f,0.302684f,0.13496f},{0.00262801f,0.302245f,0.13496f},{0.00275356f,0.301777f,0.127503f}, +{0.00275356f,0.301777f,0.13496f},{0.00279661f,0.301289f,0.13496f},{0.00279661f,0.301289f,0.127503f}, +{-0.000488516f,0.304042f,0.127503f},{-0.000957717f,0.303916f,0.127503f},{-0.00048723f,0.304042f,0.13496f}, +{-0.00139564f,0.303712f,0.13496f},{-0.000956449f,0.303917f,0.13496f},{-0.00139727f,0.303711f,0.127503f}, +{-0.00179504f,0.303433f,0.13496f},{-0.00179767f,0.303431f,0.127503f},{-0.00214219f,0.303086f,0.13496f}, +{-0.00242266f,0.302686f,0.13496f},{-0.00214411f,0.303084f,0.127503f},{-0.00242333f,0.302684f,0.127503f}, +{-0.00262748f,0.302246f,0.13496f},{-0.00262801f,0.302245f,0.127503f},{-0.00275356f,0.301777f,0.13496f}, +{-0.00275356f,0.301777f,0.127503f},{-0.00279661f,0.301289f,0.127503f},{-0.00279661f,0.301289f,0.13496f}, +{-3.14626e-017f,0.30595f,0.125638f},{-2.85648e-017f,0.30595f,0.127503f},{0.000612842f,0.305909f,0.127503f}, +{0.00120978f,0.30579f,0.127503f},{0.000612502f,0.305909f,0.125638f},{0.00178369f,0.305595f,0.127503f}, +{0.00120944f,0.30579f,0.125638f},{0.00178369f,0.305595f,0.125638f},{0.00232777f,0.305327f,0.127503f}, +{0.0028342f,0.304989f,0.127503f},{0.00232743f,0.305327f,0.125638f},{0.00329584f,0.304584f,0.127503f}, +{0.00283386f,0.304989f,0.125638f},{0.00329584f,0.304584f,0.125638f},{0.00370055f,0.304122f,0.127503f}, +{0.00403832f,0.303616f,0.127503f},{0.00370041f,0.304123f,0.125638f},{0.00430621f,0.303072f,0.127503f}, +{0.00403818f,0.303616f,0.125638f},{0.00450127f,0.302498f,0.125638f},{0.00430621f,0.303072f,0.125638f}, +{0.00450141f,0.302498f,0.127503f},{0.00462052f,0.301901f,0.125638f},{0.00462066f,0.301901f,0.127503f}, +{0.00466102f,0.301289f,0.125638f},{0.00466102f,0.301289f,0.127503f},{-0.000612842f,0.305909f,0.125638f}, +{-0.00120978f,0.30579f,0.125638f},{-0.000612502f,0.305909f,0.127503f},{-0.00120944f,0.30579f,0.127503f}, +{-0.00178369f,0.305595f,0.125638f},{-0.00232777f,0.305327f,0.125638f},{-0.00178369f,0.305595f,0.127503f}, +{-0.0028342f,0.304989f,0.125638f},{-0.00232743f,0.305327f,0.127503f},{-0.00283386f,0.304989f,0.127503f}, +{-0.00329584f,0.304584f,0.125638f},{-0.00370055f,0.304122f,0.125638f},{-0.00329584f,0.304584f,0.127503f}, +{-0.00403832f,0.303616f,0.125638f},{-0.00370041f,0.304123f,0.127503f},{-0.00403818f,0.303616f,0.127503f}, +{-0.00430621f,0.303072f,0.125638f},{-0.00450127f,0.302498f,0.127503f},{-0.00430621f,0.303072f,0.127503f}, +{-0.00450141f,0.302498f,0.125638f},{-0.00462052f,0.301901f,0.127503f},{-0.00466102f,0.301289f,0.127503f}, +{-0.00462066f,0.301901f,0.125638f},{-0.00466102f,0.301289f,0.125638f},{0.00295812f,0.292456f,0.125638f}, +{0.00315337f,0.292119f,0.125638f},{0.00315227f,0.29212f,0.121909f},{0.00295749f,0.292458f,0.121909f}, +{0.0028374f,0.292827f,0.125638f},{0.00283721f,0.292829f,0.121909f},{0.00279657f,0.293216f,0.121909f}, +{0.00283728f,0.293602f,0.125638f},{0.00279668f,0.293215f,0.125638f},{0.0028377f,0.293604f,0.121909f}, +{0.00295753f,0.293973f,0.125638f},{0.00295825f,0.293975f,0.121909f},{0.0031524f,0.294311f,0.125638f}, +{0.00315303f,0.294312f,0.121909f},{0.0034126f,0.2946f,0.125638f},{0.0034133f,0.294601f,0.121909f}, +{0.00372882f,0.29483f,0.121909f},{0.00372882f,0.29483f,0.125638f},{0.00341302f,0.29183f,0.121909f}, +{0.00372824f,0.291601f,0.121909f},{0.0034143f,0.291829f,0.125638f},{0.00372908f,0.291601f,0.125638f}, +{0.00408362f,0.291443f,0.121909f},{0.00408596f,0.291442f,0.125638f},{0.00446544f,0.291361f,0.121909f}, +{0.00485544f,0.291361f,0.121909f},{0.00446705f,0.291361f,0.125638f},{0.00485646f,0.291361f,0.125638f}, +{0.00523587f,0.291442f,0.121909f},{0.00523689f,0.291442f,0.125638f},{0.00559323f,0.291601f,0.121909f}, +{0.00559323f,0.291601f,0.125638f},{0.00794301f,0.293145f,0.125638f},{0.00822403f,0.29266f,0.125638f}, +{0.00822143f,0.292663f,0.121909f},{0.00773834f,0.293667f,0.125638f},{0.00794151f,0.293149f,0.121909f}, +{0.00773817f,0.293668f,0.121909f},{0.00761523f,0.294207f,0.125638f},{0.00761511f,0.294208f,0.121909f}, +{0.00757342f,0.294761f,0.121909f},{0.00757373f,0.294759f,0.125638f},{0.00761488f,0.295314f,0.125638f}, +{0.00794445f,0.296384f,0.121909f},{0.00822146f,0.296864f,0.125638f},{0.00794412f,0.296384f,0.125638f}, +{0.00761534f,0.295319f,0.121909f},{0.00773918f,0.295862f,0.125638f},{0.00774028f,0.295864f,0.121909f}, +{0.00822277f,0.296865f,0.121909f},{0.00856678f,0.297297f,0.125638f},{0.00856839f,0.297299f,0.121909f}, +{0.00897424f,0.297676f,0.121909f},{0.00943797f,0.297992f,0.125638f},{0.00897424f,0.297676f,0.125638f}, +{0.00943797f,0.297992f,0.121909f},{0.00857075f,0.292225f,0.121909f},{0.00897738f,0.291848f,0.121909f}, +{0.00857178f,0.292224f,0.125638f},{0.00897811f,0.291847f,0.125638f},{0.00943459f,0.291536f,0.121909f}, +{0.00943645f,0.291535f,0.125638f},{0.00993607f,0.291294f,0.121909f},{0.0104724f,0.291128f,0.121909f}, +{0.00994001f,0.291292f,0.125638f},{0.0104751f,0.291128f,0.125638f},{0.0110266f,0.291045f,0.121909f}, +{0.0110274f,0.291044f,0.125638f},{0.0115811f,0.291045f,0.121909f},{0.0121288f,0.291127f,0.121909f}, +{0.0115832f,0.291045f,0.125638f},{0.0121315f,0.291128f,0.125638f},{0.0126606f,0.291291f,0.121909f}, +{0.0126606f,0.291291f,0.125638f},{0.0131668f,0.291534f,0.121909f},{0.0131668f,0.291534f,0.125638f}, +{-0.00616977f,0.294311f,0.125638f},{-0.00636455f,0.293973f,0.125638f},{-0.00636392f,0.293974f,0.121909f}, +{-0.00616867f,0.294312f,0.121909f},{-0.00590902f,0.294601f,0.125638f},{-0.00590775f,0.294602f,0.121909f}, +{-0.00559297f,0.29483f,0.121909f},{-0.00523843f,0.294988f,0.125638f},{-0.00559381f,0.29483f,0.125638f}, +{-0.00523609f,0.294989f,0.121909f},{-0.00485661f,0.29507f,0.125638f},{-0.00485499f,0.29507f,0.121909f}, +{-0.0044666f,0.29507f,0.125638f},{-0.00446558f,0.29507f,0.121909f},{-0.00408618f,0.294989f,0.125638f}, +{-0.00408515f,0.294989f,0.121909f},{-0.00372882f,0.29483f,0.121909f},{-0.00372882f,0.29483f,0.125638f}, +{-0.00648464f,0.293604f,0.121909f},{-0.00652537f,0.293216f,0.121909f},{-0.00648484f,0.293602f,0.125638f}, +{-0.00652548f,0.293215f,0.125638f},{-0.00648477f,0.292829f,0.121909f},{-0.00648435f,0.292827f,0.125638f}, +{-0.00636452f,0.292458f,0.121909f},{-0.00616965f,0.29212f,0.121909f},{-0.0063638f,0.292456f,0.125638f}, +{-0.00616901f,0.292119f,0.125638f},{-0.00590945f,0.291831f,0.121909f},{-0.00590875f,0.29183f,0.125638f}, +{-0.00559323f,0.291601f,0.121909f},{-0.00559323f,0.291601f,0.125638f},{-0.00308095f,0.290338f,0.125638f}, +{-0.00336087f,0.289852f,0.125638f},{-0.00335937f,0.289856f,0.121909f},{-0.00273163f,0.290776f,0.125638f}, +{-0.00307835f,0.290341f,0.121909f},{-0.0027306f,0.290777f,0.121909f},{-0.002325f,0.291153f,0.125638f}, +{-0.00232427f,0.291153f,0.121909f},{-0.00186593f,0.291466f,0.121909f},{-0.00186779f,0.291465f,0.125638f}, +{-0.00136631f,0.291707f,0.125638f},{-0.000274996f,0.291956f,0.121909f},{0.0002787f,0.291956f,0.125638f}, +{-0.000275788f,0.291956f,0.125638f},{-0.00136237f,0.291709f,0.121909f},{-0.000829945f,0.291873f,0.125638f}, +{-0.000827251f,0.291873f,0.121909f},{0.000280844f,0.291956f,0.121909f},{0.000826454f,0.291874f,0.125638f}, +{0.000829073f,0.291873f,0.121909f},{0.00135821f,0.29171f,0.121909f},{0.00186441f,0.291467f,0.125638f}, +{0.00135821f,0.29171f,0.125638f},{0.00186441f,0.291467f,0.121909f},{-0.00356405f,0.289334f,0.121909f}, +{-0.00368715f,0.288794f,0.121909f},{-0.00356421f,0.289333f,0.125638f},{-0.00368727f,0.288793f,0.125638f}, +{-0.00372865f,0.288242f,0.121909f},{-0.00372896f,0.288239f,0.125638f},{-0.00368751f,0.287686f,0.121909f}, +{-0.0035632f,0.287139f,0.121909f},{-0.00368704f,0.287682f,0.125638f},{-0.0035621f,0.287136f,0.125638f}, +{-0.00335826f,0.286617f,0.121909f},{-0.00335794f,0.286617f,0.125638f},{-0.00308092f,0.286137f,0.121909f}, +{-0.0027356f,0.285704f,0.121909f},{-0.00307961f,0.286135f,0.125638f},{-0.00273399f,0.285702f,0.125638f}, +{-0.00232814f,0.285325f,0.121909f},{-0.00232814f,0.285325f,0.125638f},{-0.00186441f,0.285008f,0.121909f}, +{-0.00186441f,0.285008f,0.125638f},{-0.0091279f,0.303143f,0.125638f},{-0.00951793f,0.303143f,0.125638f}, +{-0.0095162f,0.303143f,0.121909f},{-0.00912617f,0.303143f,0.121909f},{-0.00874642f,0.303062f,0.125638f}, +{-0.00874495f,0.303061f,0.121909f},{-0.00838954f,0.302903f,0.121909f},{-0.0080757f,0.302675f,0.125638f}, +{-0.00839049f,0.302903f,0.125638f},{-0.00807379f,0.302673f,0.121909f},{-0.00781413f,0.302385f,0.125638f}, +{-0.00781324f,0.302384f,0.121909f},{-0.007619f,0.302047f,0.125638f},{-0.00761862f,0.302046f,0.121909f}, +{-0.00749878f,0.301677f,0.125638f},{-0.00749845f,0.301676f,0.121909f},{-0.00745764f,0.301289f,0.121909f}, +{-0.00745764f,0.301289f,0.125638f},{-0.00989767f,0.303062f,0.121909f},{-0.0102536f,0.302903f,0.121909f}, +{-0.00989914f,0.303061f,0.125638f},{-0.0102546f,0.302903f,0.125638f},{-0.0105684f,0.302675f,0.121909f}, +{-0.0105703f,0.302673f,0.125638f},{-0.01083f,0.302385f,0.121909f},{-0.0110251f,0.302047f,0.121909f}, +{-0.0108309f,0.302384f,0.125638f},{-0.0110255f,0.302046f,0.125638f},{-0.0111453f,0.301677f,0.121909f}, +{-0.0111456f,0.301676f,0.125638f},{-0.0111865f,0.301289f,0.121909f},{-0.0111865f,0.301289f,0.125638f}, +{-0.011024f,0.298481f,0.125638f},{-0.0115849f,0.298481f,0.125638f},{-0.0115808f,0.298481f,0.121909f}, +{-0.01047f,0.298398f,0.125638f},{-0.0110199f,0.298481f,0.121909f},{-0.0104688f,0.298397f,0.121909f}, +{-0.00994023f,0.298234f,0.125638f},{-0.00993938f,0.298234f,0.121909f},{-0.00943935f,0.297993f,0.121909f}, +{-0.00944153f,0.297994f,0.125638f},{-0.00898119f,0.297681f,0.125638f},{-0.00821944f,0.296861f,0.121909f}, +{-0.00794276f,0.296381f,0.125638f},{-0.00821991f,0.296861f,0.125638f},{-0.00897771f,0.297678f,0.121909f}, +{-0.00856913f,0.297299f,0.125638f},{-0.00856753f,0.297297f,0.121909f},{-0.00794193f,0.296379f,0.121909f}, +{-0.00774033f,0.295865f,0.125638f},{-0.00773931f,0.295863f,0.121909f},{-0.00761603f,0.295323f,0.121909f}, +{-0.00757356f,0.294763f,0.125638f},{-0.00761603f,0.295323f,0.125638f},{-0.00757356f,0.294763f,0.121909f}, +{-0.0121348f,0.298398f,0.121909f},{-0.0126645f,0.298234f,0.121909f},{-0.012136f,0.298397f,0.125638f}, +{-0.0126654f,0.298234f,0.125638f},{-0.0131632f,0.297994f,0.121909f},{-0.0131654f,0.297993f,0.125638f}, +{-0.0136236f,0.297681f,0.121909f},{-0.0140356f,0.297299f,0.121909f},{-0.0136271f,0.297678f,0.125638f}, +{-0.0140372f,0.297297f,0.125638f},{-0.0143849f,0.296861f,0.121909f},{-0.0143853f,0.296861f,0.125638f}, +{-0.014662f,0.296381f,0.121909f},{-0.0148644f,0.295865f,0.121909f},{-0.0146628f,0.296379f,0.125638f}, +{-0.0148654f,0.295863f,0.125638f},{-0.0149887f,0.295323f,0.121909f},{-0.0149887f,0.295323f,0.125638f}, +{-0.0150312f,0.294763f,0.121909f},{-0.0150312f,0.294763f,0.125638f},{-0.00295812f,0.310121f,0.125638f}, +{-0.00315337f,0.310458f,0.125638f},{-0.00315227f,0.310457f,0.121909f},{-0.00295749f,0.310119f,0.121909f}, +{-0.0028374f,0.30975f,0.125638f},{-0.00283721f,0.309748f,0.121909f},{-0.00279657f,0.309361f,0.121909f}, +{-0.00283728f,0.308975f,0.125638f},{-0.00279668f,0.309362f,0.125638f},{-0.0028377f,0.308973f,0.121909f}, +{-0.00295753f,0.308604f,0.125638f},{-0.00295825f,0.308603f,0.121909f},{-0.0031524f,0.308266f,0.125638f}, +{-0.00315303f,0.308265f,0.121909f},{-0.0034126f,0.307977f,0.125638f},{-0.0034133f,0.307976f,0.121909f}, +{-0.00372882f,0.307747f,0.121909f},{-0.00372882f,0.307747f,0.125638f},{-0.00341302f,0.310747f,0.121909f}, +{-0.00372824f,0.310976f,0.121909f},{-0.0034143f,0.310748f,0.125638f},{-0.00372908f,0.310977f,0.125638f}, +{-0.00408362f,0.311134f,0.121909f},{-0.00408596f,0.311135f,0.125638f},{-0.00446544f,0.311216f,0.121909f}, +{-0.00485544f,0.311216f,0.121909f},{-0.00446705f,0.311216f,0.125638f},{-0.00485646f,0.311216f,0.125638f}, +{-0.00523587f,0.311135f,0.121909f},{-0.00523689f,0.311135f,0.125638f},{-0.00559323f,0.310976f,0.121909f}, +{-0.00559323f,0.310976f,0.125638f},{-0.00794301f,0.309432f,0.125638f},{-0.00822403f,0.309917f,0.125638f}, +{-0.00822143f,0.309914f,0.121909f},{-0.00773834f,0.30891f,0.125638f},{-0.00794151f,0.309428f,0.121909f}, +{-0.00773817f,0.308909f,0.121909f},{-0.00761523f,0.30837f,0.125638f},{-0.00761511f,0.308369f,0.121909f}, +{-0.00757342f,0.307816f,0.121909f},{-0.00757373f,0.307818f,0.125638f},{-0.00761488f,0.307263f,0.125638f}, +{-0.00794445f,0.306193f,0.121909f},{-0.00822146f,0.305713f,0.125638f},{-0.00794412f,0.306194f,0.125638f}, +{-0.00761534f,0.307258f,0.121909f},{-0.00773918f,0.306715f,0.125638f},{-0.00774028f,0.306713f,0.121909f}, +{-0.00822277f,0.305712f,0.121909f},{-0.00856678f,0.30528f,0.125638f},{-0.00856839f,0.305278f,0.121909f}, +{-0.00897424f,0.304902f,0.121909f},{-0.00943797f,0.304585f,0.125638f},{-0.00897424f,0.304902f,0.125638f}, +{-0.00943797f,0.304585f,0.121909f},{-0.00857075f,0.310352f,0.121909f},{-0.00897738f,0.310729f,0.121909f}, +{-0.00857178f,0.310353f,0.125638f},{-0.00897811f,0.31073f,0.125638f},{-0.00943459f,0.311041f,0.121909f}, +{-0.00943645f,0.311043f,0.125638f},{-0.00993607f,0.311283f,0.121909f},{-0.0104724f,0.311449f,0.121909f}, +{-0.00994001f,0.311285f,0.125638f},{-0.0104751f,0.31145f,0.125638f},{-0.0110266f,0.311533f,0.121909f}, +{-0.0110274f,0.311533f,0.125638f},{-0.0115811f,0.311532f,0.121909f},{-0.0121288f,0.31145f,0.121909f}, +{-0.0115832f,0.311532f,0.125638f},{-0.0121315f,0.31145f,0.125638f},{-0.0126606f,0.311286f,0.121909f}, +{-0.0126606f,0.311286f,0.125638f},{-0.0131668f,0.311043f,0.121909f},{-0.0131668f,0.311043f,0.125638f}, +{0.00616977f,0.308266f,0.125638f},{0.00636455f,0.308604f,0.125638f},{0.00636392f,0.308603f,0.121909f}, +{0.00616867f,0.308265f,0.121909f},{0.00590902f,0.307976f,0.125638f},{0.00590775f,0.307976f,0.121909f}, +{0.00559297f,0.307747f,0.121909f},{0.00523843f,0.307589f,0.125638f},{0.00559381f,0.307747f,0.125638f}, +{0.00523609f,0.307588f,0.121909f},{0.00485661f,0.307508f,0.125638f},{0.00485499f,0.307507f,0.121909f}, +{0.0044666f,0.307507f,0.125638f},{0.00446558f,0.307508f,0.121909f},{0.00408618f,0.307588f,0.125638f}, +{0.00408515f,0.307588f,0.121909f},{0.00372882f,0.307747f,0.121909f},{0.00372882f,0.307747f,0.125638f}, +{0.00648464f,0.308973f,0.121909f},{0.00652537f,0.309361f,0.121909f},{0.00648484f,0.308975f,0.125638f}, +{0.00652548f,0.309362f,0.125638f},{0.00648477f,0.309748f,0.121909f},{0.00648435f,0.30975f,0.125638f}, +{0.00636452f,0.310119f,0.121909f},{0.00616965f,0.310457f,0.121909f},{0.0063638f,0.310121f,0.125638f}, +{0.00616901f,0.310458f,0.125638f},{0.00590945f,0.310746f,0.121909f},{0.00590875f,0.310747f,0.125638f}, +{0.00559323f,0.310976f,0.121909f},{0.00559323f,0.310976f,0.125638f},{0.00308095f,0.312239f,0.125638f}, +{0.00336087f,0.312725f,0.125638f},{0.00335937f,0.312721f,0.121909f},{0.00273163f,0.311801f,0.125638f}, +{0.00307835f,0.312236f,0.121909f},{0.0027306f,0.3118f,0.121909f},{0.002325f,0.311424f,0.125638f}, +{0.00232427f,0.311424f,0.121909f},{0.00186593f,0.311111f,0.121909f},{0.00186779f,0.311112f,0.125638f}, +{0.00136631f,0.31087f,0.125638f},{0.000274996f,0.310621f,0.121909f},{-0.0002787f,0.310621f,0.125638f}, +{0.000275788f,0.310621f,0.125638f},{0.00136237f,0.310869f,0.121909f},{0.000829945f,0.310704f,0.125638f}, +{0.000827251f,0.310704f,0.121909f},{-0.000280844f,0.310621f,0.121909f},{-0.000826454f,0.310703f,0.125638f}, +{-0.000829073f,0.310704f,0.121909f},{-0.00135821f,0.310867f,0.121909f},{-0.00186441f,0.31111f,0.125638f}, +{-0.00135821f,0.310867f,0.125638f},{-0.00186441f,0.31111f,0.121909f},{0.00356405f,0.313243f,0.121909f}, +{0.00368715f,0.313783f,0.121909f},{0.00356421f,0.313244f,0.125638f},{0.00368727f,0.313784f,0.125638f}, +{0.00372865f,0.314335f,0.121909f},{0.00372896f,0.314338f,0.125638f},{0.00368751f,0.314891f,0.121909f}, +{0.0035632f,0.315438f,0.121909f},{0.00368704f,0.314895f,0.125638f},{0.0035621f,0.315441f,0.125638f}, +{0.00335826f,0.31596f,0.121909f},{0.00335794f,0.315961f,0.125638f},{0.00308092f,0.31644f,0.121909f}, +{0.0027356f,0.316873f,0.121909f},{0.00307961f,0.316442f,0.125638f},{0.00273399f,0.316875f,0.125638f}, +{0.00232814f,0.317252f,0.121909f},{0.00232814f,0.317252f,0.125638f},{0.00186441f,0.317569f,0.121909f}, +{0.00186441f,0.317569f,0.125638f},{0.0091279f,0.299434f,0.125638f},{0.00951793f,0.299435f,0.125638f}, +{0.0095162f,0.299434f,0.121909f},{0.00912617f,0.299435f,0.121909f},{0.00874642f,0.299515f,0.125638f}, +{0.00874495f,0.299516f,0.121909f},{0.00838954f,0.299674f,0.121909f},{0.0080757f,0.299902f,0.125638f}, +{0.00839049f,0.299674f,0.125638f},{0.00807379f,0.299904f,0.121909f},{0.00781413f,0.300192f,0.125638f}, +{0.00781324f,0.300193f,0.121909f},{0.007619f,0.30053f,0.125638f},{0.00761862f,0.300531f,0.121909f}, +{0.00749878f,0.3009f,0.125638f},{0.00749845f,0.300901f,0.121909f},{0.00745764f,0.301289f,0.121909f}, +{0.00745764f,0.301289f,0.125638f},{0.00989767f,0.299515f,0.121909f},{0.0102536f,0.299674f,0.121909f}, +{0.00989914f,0.299516f,0.125638f},{0.0102546f,0.299674f,0.125638f},{0.0105684f,0.299902f,0.121909f}, +{0.0105703f,0.299904f,0.125638f},{0.01083f,0.300192f,0.121909f},{0.0110251f,0.30053f,0.121909f}, +{0.0108309f,0.300193f,0.125638f},{0.0110255f,0.300531f,0.125638f},{0.0111453f,0.3009f,0.121909f}, +{0.0111456f,0.300901f,0.125638f},{0.0111865f,0.301289f,0.121909f},{0.0111865f,0.301289f,0.125638f}, +{0.011024f,0.304096f,0.125638f},{0.0115849f,0.304096f,0.125638f},{0.0115808f,0.304096f,0.121909f}, +{0.01047f,0.304179f,0.125638f},{0.0110199f,0.304096f,0.121909f},{0.0104688f,0.30418f,0.121909f}, +{0.00994023f,0.304343f,0.125638f},{0.00993938f,0.304343f,0.121909f},{0.00943935f,0.304584f,0.121909f}, +{0.00944153f,0.304583f,0.125638f},{0.00898119f,0.304896f,0.125638f},{0.00821944f,0.305716f,0.121909f}, +{0.00794276f,0.306196f,0.125638f},{0.00821991f,0.305716f,0.125638f},{0.00897771f,0.304899f,0.121909f}, +{0.00856913f,0.305278f,0.125638f},{0.00856753f,0.30528f,0.121909f},{0.00794193f,0.306198f,0.121909f}, +{0.00774033f,0.306712f,0.125638f},{0.00773931f,0.306714f,0.121909f},{0.00761603f,0.307254f,0.121909f}, +{0.00757356f,0.307814f,0.125638f},{0.00761603f,0.307254f,0.125638f},{0.00757356f,0.307814f,0.121909f}, +{0.0121348f,0.304179f,0.121909f},{0.0126645f,0.304343f,0.121909f},{0.012136f,0.30418f,0.125638f}, +{0.0126654f,0.304343f,0.125638f},{0.0131632f,0.304583f,0.121909f},{0.0131654f,0.304584f,0.125638f}, +{0.0136236f,0.304896f,0.121909f},{0.0140356f,0.305278f,0.121909f},{0.0136271f,0.304899f,0.125638f}, +{0.0140372f,0.30528f,0.125638f},{0.0143849f,0.305716f,0.121909f},{0.0143853f,0.305716f,0.125638f}, +{0.014662f,0.306196f,0.121909f},{0.0148644f,0.306712f,0.121909f},{0.0146628f,0.306198f,0.125638f}, +{0.0148654f,0.306714f,0.125638f},{0.0149887f,0.307254f,0.121909f},{0.0149887f,0.307254f,0.125638f}, +{0.0150312f,0.307814f,0.121909f},{0.0150312f,0.307814f,0.125638f},{-2.74685e-017f,0.304085f,0.100469f}, +{-2.69701e-017f,0.304085f,0.0986044f},{-0.000488516f,0.304042f,0.0986044f},{-0.000957717f,0.303916f,0.0986044f}, +{-0.00048723f,0.304042f,0.100469f},{-0.000956449f,0.303917f,0.100469f},{-0.00139564f,0.303712f,0.100469f}, +{-0.00179504f,0.303433f,0.100469f},{-0.00139727f,0.303711f,0.0986044f},{-0.00179767f,0.303431f,0.0986044f}, +{-0.00214219f,0.303086f,0.100469f},{-0.00214411f,0.303084f,0.0986044f},{-0.00242266f,0.302686f,0.100469f}, +{-0.00262748f,0.302246f,0.100469f},{-0.00242333f,0.302684f,0.0986044f},{-0.00262801f,0.302245f,0.0986044f}, +{-0.00275356f,0.301777f,0.100469f},{-0.00275356f,0.301777f,0.0986044f},{-0.00279661f,0.301289f,0.0986044f}, +{-0.00279661f,0.301289f,0.100469f},{0.000488516f,0.304042f,0.100469f},{0.000957717f,0.303916f,0.100469f}, +{0.00048723f,0.304042f,0.0986044f},{0.00139564f,0.303712f,0.0986044f},{0.000956449f,0.303917f,0.0986044f}, +{0.00139727f,0.303711f,0.100469f},{0.00179504f,0.303433f,0.0986044f},{0.00179767f,0.303431f,0.100469f}, +{0.00214219f,0.303086f,0.0986044f},{0.00242266f,0.302686f,0.0986044f},{0.00214411f,0.303084f,0.100469f}, +{0.00242333f,0.302684f,0.100469f},{0.00262748f,0.302246f,0.0986044f},{0.00262801f,0.302245f,0.100469f}, +{0.00275356f,0.301777f,0.0986044f},{0.00275356f,0.301777f,0.100469f},{0.00279661f,0.301289f,0.100469f}, +{0.00279661f,0.301289f,0.0986044f},{-3.06347e-017f,0.308746f,0.100469f},{-0.000737081f,0.30871f,0.100469f}, +{-2.81508e-017f,0.308746f,0.101401f},{-0.000737081f,0.30871f,0.101401f},{-0.00146169f,0.308602f,0.100469f}, +{-0.00216893f,0.308424f,0.100469f},{-0.00146169f,0.308602f,0.101401f},{-0.00285391f,0.308178f,0.100469f}, +{-0.00216893f,0.308424f,0.101401f},{-0.00285391f,0.308178f,0.101401f},{-0.00351173f,0.307868f,0.100469f}, +{-0.00413751f,0.307493f,0.100469f},{-0.00351173f,0.307868f,0.101401f},{-0.00472635f,0.307057f,0.100469f}, +{-0.00413751f,0.307493f,0.101401f},{-0.00472635f,0.307057f,0.101401f},{-0.00527335f,0.306562f,0.100469f}, +{-0.00576874f,0.306015f,0.100469f},{-0.00527335f,0.306562f,0.101401f},{-0.00620465f,0.305426f,0.100469f}, +{-0.00576874f,0.306015f,0.101401f},{-0.00620465f,0.305426f,0.101401f},{-0.00657906f,0.3048f,0.100469f}, +{-0.00688994f,0.304142f,0.100469f},{-0.00657906f,0.3048f,0.101401f},{-0.00713527f,0.303457f,0.100469f}, +{-0.00688994f,0.304142f,0.101401f},{-0.00713527f,0.303457f,0.101401f},{-0.00731301f,0.30275f,0.100469f}, +{-0.00742114f,0.302026f,0.100469f},{-0.00731301f,0.30275f,0.101401f},{-0.00745764f,0.301289f,0.100469f}, +{-0.00742114f,0.302026f,0.101401f},{-0.00745764f,0.301289f,0.101401f},{0.000737081f,0.30871f,0.101401f}, +{0.00146169f,0.308602f,0.101401f},{0.000737081f,0.30871f,0.100469f},{0.00216893f,0.308424f,0.101401f}, +{0.00146169f,0.308602f,0.100469f},{0.00216893f,0.308424f,0.100469f},{0.00285391f,0.308178f,0.101401f}, +{0.00351173f,0.307868f,0.101401f},{0.00285391f,0.308178f,0.100469f},{0.00413751f,0.307493f,0.101401f}, +{0.00351173f,0.307868f,0.100469f},{0.00413751f,0.307493f,0.100469f},{0.00472635f,0.307057f,0.101401f}, +{0.00527335f,0.306562f,0.101401f},{0.00472635f,0.307057f,0.100469f},{0.00576874f,0.306015f,0.101401f}, +{0.00527335f,0.306562f,0.100469f},{0.00576874f,0.306015f,0.100469f},{0.00620465f,0.305426f,0.101401f}, +{0.00657906f,0.3048f,0.101401f},{0.00620465f,0.305426f,0.100469f},{0.00688994f,0.304142f,0.101401f}, +{0.00657906f,0.3048f,0.100469f},{0.00688994f,0.304142f,0.100469f},{0.00713527f,0.303457f,0.101401f}, +{0.00731301f,0.30275f,0.101401f},{0.00713527f,0.303457f,0.100469f},{0.00742114f,0.302026f,0.101401f}, +{0.00731301f,0.30275f,0.100469f},{0.00742114f,0.302026f,0.100469f},{0.00745764f,0.301289f,0.101401f}, +{0.00745764f,0.301289f,0.100469f},{-0.00462052f,0.318681f,0.101401f},{-0.00462066f,0.318681f,0.104198f}, +{-0.00466102f,0.318068f,0.101401f},{-0.00462052f,0.317455f,0.104198f},{-0.00462066f,0.317456f,0.101401f}, +{-0.00466102f,0.318068f,0.104198f},{-0.00430621f,0.316285f,0.101401f},{-0.00430621f,0.316285f,0.104198f}, +{-0.00403832f,0.315741f,0.101401f},{-0.00450127f,0.316858f,0.104198f},{-0.00450141f,0.316859f,0.101401f}, +{-0.00403818f,0.31574f,0.104198f},{-0.00370041f,0.315234f,0.104198f},{-0.00370055f,0.315234f,0.101401f}, +{-0.00329584f,0.314772f,0.101401f},{-0.00329584f,0.314772f,0.104198f},{-0.00283386f,0.314368f,0.104198f}, +{-0.0028342f,0.314368f,0.101401f},{-0.00232777f,0.31403f,0.101401f},{-0.00232743f,0.31403f,0.104198f}, +{-0.00178369f,0.313762f,0.101401f},{-0.00178369f,0.313762f,0.104198f},{-0.00120944f,0.313567f,0.104198f}, +{-0.00120978f,0.313567f,0.101401f},{-2.25564e-017f,0.313407f,0.101401f},{-0.000612842f,0.313448f,0.101401f}, +{-0.000612502f,0.313448f,0.104198f},{-2.25564e-017f,0.313407f,0.104198f},{-0.00450141f,0.319278f,0.104198f}, +{-0.00450127f,0.319278f,0.101401f},{-0.00430621f,0.319852f,0.104198f},{-0.00403832f,0.320396f,0.104198f}, +{-0.00430621f,0.319852f,0.101401f},{-0.00403818f,0.320396f,0.101401f},{-0.00370055f,0.320902f,0.104198f}, +{-0.00370041f,0.320902f,0.101401f},{-0.00329584f,0.321364f,0.104198f},{-0.0028342f,0.321769f,0.104198f}, +{-0.00329584f,0.321364f,0.101401f},{-0.00283386f,0.321769f,0.101401f},{-0.00232777f,0.322106f,0.104198f}, +{-0.00232743f,0.322107f,0.101401f},{-0.00178369f,0.322374f,0.104198f},{-0.00120978f,0.322569f,0.104198f}, +{-0.00178369f,0.322374f,0.101401f},{-0.00120944f,0.32257f,0.101401f},{-0.000612842f,0.322689f,0.104198f}, +{-0.000612502f,0.322689f,0.101401f},{-2.3698e-017f,0.322729f,0.104198f},{-2.3698e-017f,0.322729f,0.101401f}, +{0.0173922f,0.305909f,0.101401f},{0.0167797f,0.30595f,0.101401f},{0.0173922f,0.305909f,0.104198f}, +{0.0161668f,0.305909f,0.104198f},{0.0167797f,0.30595f,0.104198f},{0.0161668f,0.305909f,0.101401f}, +{0.014996f,0.305595f,0.101401f},{0.0144519f,0.305327f,0.101401f},{0.014996f,0.305595f,0.104198f}, +{0.0155699f,0.30579f,0.104198f},{0.0155699f,0.30579f,0.101401f},{0.0144519f,0.305327f,0.104198f}, +{0.0139455f,0.304989f,0.101401f},{0.0139455f,0.304989f,0.104198f},{0.0134838f,0.304584f,0.101401f}, +{0.0134838f,0.304584f,0.104198f},{0.0130791f,0.304122f,0.101401f},{0.0130791f,0.304122f,0.104198f}, +{0.0127414f,0.303616f,0.101401f},{0.0124735f,0.303072f,0.101401f},{0.0127414f,0.303616f,0.104198f}, +{0.0124735f,0.303072f,0.104198f},{0.0122783f,0.302498f,0.101401f},{0.0122783f,0.302498f,0.104198f}, +{0.0121187f,0.301289f,0.101401f},{0.012159f,0.301901f,0.104198f},{0.012159f,0.301901f,0.101401f}, +{0.0121187f,0.301289f,0.104198f},{0.0179891f,0.30579f,0.104198f},{0.0185634f,0.305595f,0.104198f}, +{0.0179891f,0.30579f,0.101401f},{0.0191071f,0.305327f,0.104198f},{0.0185634f,0.305595f,0.101401f}, +{0.0191071f,0.305327f,0.101401f},{0.0196135f,0.304989f,0.104198f},{0.0200755f,0.304584f,0.104198f}, +{0.0196135f,0.304989f,0.101401f},{0.0204801f,0.304123f,0.104198f},{0.0200755f,0.304584f,0.101401f}, +{0.0204801f,0.304123f,0.101401f},{0.0208179f,0.303616f,0.104198f},{0.0210859f,0.303072f,0.104198f}, +{0.0208179f,0.303616f,0.101401f},{0.0212809f,0.302498f,0.104198f},{0.0210859f,0.303072f,0.101401f}, +{0.0212809f,0.302498f,0.101401f},{0.0214002f,0.301901f,0.104198f},{0.0214407f,0.301289f,0.104198f}, +{0.0214002f,0.301901f,0.101401f},{0.0214407f,0.301289f,0.101401f},{0.00462066f,0.283896f,0.104198f}, +{0.00466102f,0.284509f,0.104198f},{0.00464709f,0.284149f,0.101401f},{0.00458867f,0.285326f,0.101401f}, +{0.00465528f,0.28474f,0.101401f},{0.00462052f,0.285122f,0.104198f},{0.00430621f,0.286293f,0.104198f}, +{0.00403818f,0.286837f,0.104198f},{0.00423671f,0.286451f,0.101401f},{0.00444837f,0.2859f,0.101401f}, +{0.00450127f,0.285719f,0.104198f},{0.00370041f,0.287343f,0.104198f},{0.00361392f,0.287452f,0.101401f}, +{0.00395712f,0.286971f,0.101401f},{0.00329584f,0.287805f,0.104198f},{0.00283386f,0.288209f,0.104198f}, +{0.00276013f,0.288264f,0.101401f},{0.00321274f,0.287885f,0.101401f},{0.00232743f,0.288547f,0.104198f}, +{0.00178369f,0.288815f,0.104198f},{0.00226347f,0.288584f,0.101401f},{0.00120944f,0.28901f,0.104198f}, +{0.00116855f,0.289018f,0.101401f},{0.00172931f,0.288834f,0.101401f},{0.000589403f,0.289133f,0.101401f}, +{0.000612502f,0.28913f,0.104198f},{-2.78077e-017f,0.28917f,0.104198f},{-2.78077e-017f,0.28917f,0.101401f}, +{0.00456433f,0.283564f,0.101401f},{0.00440833f,0.282995f,0.101401f},{0.00450141f,0.283299f,0.104198f}, +{0.00430621f,0.282725f,0.104198f},{0.00418158f,0.282449f,0.101401f},{0.00388773f,0.281937f,0.101401f}, +{0.00403832f,0.282181f,0.104198f},{0.00353147f,0.281466f,0.101401f},{0.00370055f,0.281675f,0.104198f}, +{0.00329584f,0.281213f,0.104198f},{0.0031185f,0.281044f,0.101401f},{0.00265541f,0.280678f,0.101401f}, +{0.0028342f,0.280808f,0.104198f},{0.00214963f,0.280373f,0.101401f},{0.00232777f,0.280471f,0.104198f}, +{0.00178369f,0.280203f,0.104198f},{0.00160952f,0.280134f,0.101401f},{0.00104053f,0.279978f,0.101401f}, +{0.00120978f,0.280008f,0.104198f},{0.000461185f,0.279852f,0.101401f},{0.000612842f,0.279888f,0.104198f}, +{-2.66661e-017f,0.279848f,0.104198f},{-2.66661e-017f,0.279848f,0.101401f},{-0.0143886f,0.313813f,0.110723f}, +{-0.0143784f,0.313619f,0.101401f},{-0.0143782f,0.314009f,0.101401f},{-0.014297f,0.31439f,0.101401f}, +{-0.0143526f,0.314176f,0.110723f},{-0.0142471f,0.314526f,0.110723f},{-0.0139089f,0.315061f,0.101401f}, +{-0.014075f,0.314849f,0.110723f},{-0.0141387f,0.314745f,0.101401f},{-0.0136193f,0.315322f,0.101401f}, +{-0.0138429f,0.315132f,0.110723f},{-0.0135601f,0.315364f,0.110723f},{-0.013282f,0.315516f,0.101401f}, +{-0.0129121f,0.315636f,0.101401f},{-0.0132377f,0.315536f,0.110723f},{-0.0125242f,0.315677f,0.101401f}, +{-0.0125242f,0.315677f,0.110723f},{-0.0128879f,0.315642f,0.110723f},{-0.0143523f,0.313449f,0.110723f}, +{-0.0142976f,0.313237f,0.101401f},{-0.0142453f,0.313099f,0.110723f},{-0.0140726f,0.312777f,0.110723f}, +{-0.0141391f,0.312881f,0.101401f},{-0.0138409f,0.312495f,0.110723f},{-0.0139105f,0.312566f,0.101401f}, +{-0.0136206f,0.312305f,0.101401f},{-0.0135587f,0.312263f,0.110723f},{-0.0132367f,0.312091f,0.110723f}, +{-0.013283f,0.31211f,0.101401f},{-0.0128873f,0.311985f,0.110723f},{-0.0129131f,0.311989f,0.101401f}, +{-0.0125242f,0.311948f,0.101401f},{-0.0125242f,0.311948f,0.110723f},{-0.0125242f,0.313813f,0.111843f}, +{0.00868228f,0.311835f,0.110723f},{0.00869244f,0.311641f,0.101401f},{0.00869272f,0.312031f,0.101401f}, +{0.00877392f,0.312412f,0.101401f},{0.0087183f,0.312199f,0.110723f},{0.00882381f,0.312549f,0.110723f}, +{0.00916198f,0.313083f,0.101401f},{0.00899591f,0.312872f,0.110723f},{0.00893219f,0.312768f,0.101401f}, +{0.0094516f,0.313344f,0.101401f},{0.00922803f,0.313155f,0.110723f},{0.00951082f,0.313386f,0.110723f}, +{0.00978889f,0.313539f,0.101401f},{0.0101588f,0.313659f,0.101401f},{0.00983322f,0.313559f,0.110723f}, +{0.0105467f,0.3137f,0.101401f},{0.0105467f,0.3137f,0.110723f},{0.010183f,0.313665f,0.110723f}, +{0.00871859f,0.311471f,0.110723f},{0.00877329f,0.31126f,0.101401f},{0.00882557f,0.311121f,0.110723f}, +{0.00899828f,0.3108f,0.110723f},{0.00893177f,0.310904f,0.101401f},{0.00922999f,0.310517f,0.110723f}, +{0.00916039f,0.310589f,0.101401f},{0.00945026f,0.310327f,0.101401f},{0.00951221f,0.310286f,0.110723f}, +{0.00983423f,0.310114f,0.110723f},{0.00978794f,0.310132f,0.101401f},{0.0101836f,0.310007f,0.110723f}, +{0.0101578f,0.310012f,0.101401f},{0.0105467f,0.309971f,0.101401f},{0.0105467f,0.309971f,0.110723f}, +{0.0105467f,0.311835f,0.111843f},{0.0106598f,0.288764f,0.110723f},{0.0106699f,0.28857f,0.101401f}, +{0.0106702f,0.28896f,0.101401f},{0.0107514f,0.289341f,0.101401f},{0.0106958f,0.289128f,0.110723f}, +{0.0108013f,0.289478f,0.110723f},{0.0111395f,0.290013f,0.101401f},{0.0109734f,0.289801f,0.110723f}, +{0.0109097f,0.289697f,0.101401f},{0.0114291f,0.290273f,0.101401f},{0.0112055f,0.290084f,0.110723f}, +{0.0114883f,0.290316f,0.110723f},{0.0117664f,0.290468f,0.101401f},{0.0121363f,0.290588f,0.101401f}, +{0.0118107f,0.290488f,0.110723f},{0.0125242f,0.290629f,0.101401f},{0.0125242f,0.290629f,0.110723f}, +{0.0121605f,0.290594f,0.110723f},{0.0106961f,0.2884f,0.110723f},{0.0107508f,0.288189f,0.101401f}, +{0.0108031f,0.288051f,0.110723f},{0.0109758f,0.287729f,0.110723f},{0.0109093f,0.287833f,0.101401f}, +{0.0112075f,0.287446f,0.110723f},{0.0111379f,0.287518f,0.101401f},{0.0114278f,0.287256f,0.101401f}, +{0.0114897f,0.287215f,0.110723f},{0.0118117f,0.287043f,0.110723f},{0.0117654f,0.287061f,0.101401f}, +{0.0121611f,0.286936f,0.110723f},{0.0121353f,0.286941f,0.101401f},{0.0125242f,0.2869f,0.101401f}, +{0.0125242f,0.2869f,0.110723f},{0.0125242f,0.288764f,0.111843f},{-0.0124111f,0.290742f,0.110723f}, +{-0.0124009f,0.290548f,0.101401f},{-0.0124007f,0.290938f,0.101401f},{-0.0123195f,0.291319f,0.101401f}, +{-0.0123751f,0.291105f,0.110723f},{-0.0122696f,0.291456f,0.110723f},{-0.0119314f,0.29199f,0.101401f}, +{-0.0120975f,0.291778f,0.110723f},{-0.0121612f,0.291674f,0.101401f},{-0.0116418f,0.292251f,0.101401f}, +{-0.0118654f,0.292061f,0.110723f},{-0.0115826f,0.292293f,0.110723f},{-0.0113045f,0.292445f,0.101401f}, +{-0.0109346f,0.292565f,0.101401f},{-0.0112602f,0.292465f,0.110723f},{-0.0105467f,0.292606f,0.101401f}, +{-0.0105467f,0.292606f,0.110723f},{-0.0109104f,0.292571f,0.110723f},{-0.0123748f,0.290378f,0.110723f}, +{-0.0123201f,0.290166f,0.101401f},{-0.0122678f,0.290028f,0.110723f},{-0.0120951f,0.289706f,0.110723f}, +{-0.0121616f,0.28981f,0.101401f},{-0.0118634f,0.289424f,0.110723f},{-0.011933f,0.289496f,0.101401f}, +{-0.0116431f,0.289234f,0.101401f},{-0.0115812f,0.289192f,0.110723f},{-0.0112592f,0.28902f,0.110723f}, +{-0.0113054f,0.289039f,0.101401f},{-0.0109098f,0.288914f,0.110723f},{-0.0109356f,0.288919f,0.101401f}, +{-0.0105467f,0.288877f,0.101401f},{-0.0105467f,0.288877f,0.110723f},{-0.0105467f,0.290742f,0.111843f}, +{-0.0173925f,0.296668f,0.101401f},{-0.0173922f,0.296668f,0.104198f},{-0.0167797f,0.296628f,0.101401f}, +{-0.0161668f,0.296668f,0.104198f},{-0.0161672f,0.296668f,0.101401f},{-0.0167797f,0.296628f,0.104198f}, +{-0.014996f,0.296982f,0.101401f},{-0.014996f,0.296982f,0.104198f},{-0.0144523f,0.29725f,0.101401f}, +{-0.0155699f,0.296787f,0.104198f},{-0.0155702f,0.296787f,0.101401f},{-0.0144519f,0.29725f,0.104198f}, +{-0.0139455f,0.297588f,0.104198f},{-0.0139458f,0.297588f,0.101401f},{-0.0134838f,0.297993f,0.101401f}, +{-0.0134838f,0.297993f,0.104198f},{-0.0130791f,0.298455f,0.104198f},{-0.0130793f,0.298454f,0.101401f}, +{-0.0127415f,0.298961f,0.101401f},{-0.0127414f,0.298961f,0.104198f},{-0.0124735f,0.299505f,0.101401f}, +{-0.0124735f,0.299505f,0.104198f},{-0.0122783f,0.300079f,0.104198f},{-0.0122784f,0.300079f,0.101401f}, +{-0.0121187f,0.301289f,0.101401f},{-0.0121592f,0.300676f,0.101401f},{-0.012159f,0.300676f,0.104198f}, +{-0.0121187f,0.301289f,0.104198f},{-0.0179891f,0.296787f,0.104198f},{-0.0179895f,0.296787f,0.101401f}, +{-0.0185634f,0.296982f,0.104198f},{-0.0191071f,0.29725f,0.104198f},{-0.0185634f,0.296982f,0.101401f}, +{-0.0191075f,0.29725f,0.101401f},{-0.0196135f,0.297588f,0.104198f},{-0.0196139f,0.297588f,0.101401f}, +{-0.0200755f,0.297993f,0.104198f},{-0.0204801f,0.298454f,0.104198f},{-0.0200755f,0.297993f,0.101401f}, +{-0.0204802f,0.298455f,0.101401f},{-0.0208179f,0.298961f,0.104198f},{-0.020818f,0.298961f,0.101401f}, +{-0.0210859f,0.299505f,0.104198f},{-0.0212809f,0.300079f,0.104198f},{-0.0210859f,0.299505f,0.101401f}, +{-0.0212811f,0.300079f,0.101401f},{-0.0214002f,0.300676f,0.104198f},{-0.0214003f,0.300676f,0.101401f}, +{-0.0214407f,0.301289f,0.104198f},{-0.0214407f,0.301289f,0.101401f},{0.0254902f,0.304016f,0.121909f}, +{0.0255985f,0.302667f,0.120045f},{0.0254881f,0.304035f,0.120045f},{0.0250554f,0.306712f,0.121909f}, +{0.0250515f,0.30673f,0.120045f},{0.0247276f,0.308051f,0.120045f},{0.0255992f,0.302654f,0.121909f}, +{0.0256356f,0.301289f,0.120045f},{0.0256356f,0.301289f,0.121909f},{0.0253087f,0.305369f,0.121909f}, +{0.0253054f,0.305391f,0.120045f},{0.0241907f,0.309773f,0.121909f},{0.0246545f,0.308252f,0.121909f}, +{0.0243348f,0.309351f,0.120045f},{0.0222011f,0.314106f,0.121909f},{0.0229537f,0.312704f,0.121909f}, +{0.0227538f,0.313097f,0.120045f},{0.0236177f,0.311258f,0.121909f},{0.0238741f,0.310627f,0.120045f}, +{0.0233468f,0.311877f,0.120045f},{0.0205925f,0.316557f,0.120045f},{0.0197483f,0.317635f,0.120045f}, +{0.0204428f,0.316757f,0.121909f},{0.0220964f,0.314286f,0.120045f},{0.0213756f,0.31544f,0.120045f}, +{0.0213632f,0.315459f,0.121909f},{0.0178811f,0.319658f,0.120045f},{0.0172245f,0.320275f,0.121909f}, +{0.0183635f,0.319164f,0.121909f},{0.0188436f,0.31867f,0.120045f},{0.0194437f,0.317996f,0.121909f}, +{0.0137508f,0.322924f,0.121909f},{0.015542f,0.321676f,0.121909f},{0.014715f,0.32228f,0.120045f}, +{0.0168687f,0.320592f,0.120045f},{0.0112022f,0.324347f,0.120045f},{0.00996671f,0.324907f,0.120045f}, +{0.00988506f,0.324942f,0.121909f},{0.0124072f,0.323722f,0.120045f},{0.0118618f,0.324015f,0.121909f}, +{0.00610419f,0.326187f,0.120045f},{0.00612578f,0.326167f,0.121909f},{0.00741505f,0.325828f,0.120045f}, +{0.00783085f,0.325699f,0.121909f},{0.00870345f,0.325401f,0.120045f},{0.00264799f,0.326787f,0.121909f}, +{0.00342595f,0.326694f,0.120045f},{0.00206394f,0.326841f,0.120045f},{0.00477359f,0.326476f,0.120045f}, +{0.00439916f,0.326544f,0.121909f},{0.000884103f,0.326909f,0.121909f},{-0.000690516f,0.326915f,0.120045f}, +{-0.000883894f,0.326909f,0.121909f},{0.000689447f,0.326915f,0.120045f},{-0.00342617f,0.326694f,0.120045f}, +{-0.00477376f,0.326476f,0.120045f},{-0.00439897f,0.326544f,0.121909f},{-0.00264771f,0.326787f,0.121909f}, +{-0.00206419f,0.326841f,0.120045f},{-0.0087035f,0.325401f,0.120045f},{-0.00783085f,0.325699f,0.121909f}, +{-0.00741509f,0.325828f,0.120045f},{-0.00612769f,0.326175f,0.121909f},{-0.0061043f,0.326187f,0.120045f}, +{-0.0118616f,0.324015f,0.121909f},{-0.00988475f,0.324942f,0.121909f},{-0.0112024f,0.324347f,0.120045f}, +{-0.00996683f,0.324907f,0.120045f},{-0.0137506f,0.322924f,0.121909f},{-0.0135792f,0.323032f,0.120045f}, +{-0.0147152f,0.32228f,0.120045f},{-0.0124074f,0.323722f,0.120045f},{-0.016869f,0.320592f,0.120045f}, +{-0.0178817f,0.319658f,0.120045f},{-0.0172245f,0.320275f,0.121909f},{-0.0155417f,0.321676f,0.121909f}, +{-0.0158127f,0.321466f,0.120045f},{-0.0188441f,0.318669f,0.120045f},{-0.0197483f,0.317635f,0.120045f}, +{-0.0194435f,0.317996f,0.121909f},{-0.0183577f,0.319158f,0.121909f},{-0.0204427f,0.316757f,0.121909f}, +{-0.0205925f,0.316557f,0.120045f},{-0.0213756f,0.31544f,0.120045f},{-0.021363f,0.315459f,0.121909f}, +{-0.0220965f,0.314286f,0.120045f},{-0.0222011f,0.314106f,0.121909f},{-0.0227539f,0.313097f,0.120045f}, +{-0.0229535f,0.312704f,0.121909f},{-0.0236176f,0.311258f,0.121909f},{-0.0233469f,0.311877f,0.120045f}, +{-0.0238742f,0.310627f,0.120045f},{-0.0241907f,0.309774f,0.121909f},{-0.0243349f,0.309351f,0.120045f}, +{-0.0246619f,0.308254f,0.121909f},{-0.0250554f,0.306712f,0.121909f},{-0.0247277f,0.308051f,0.120045f}, +{-0.0253055f,0.30539f,0.120045f},{-0.0250516f,0.30673f,0.120045f},{-0.0254882f,0.304035f,0.120045f}, +{-0.0253087f,0.305369f,0.121909f},{-0.0254901f,0.304016f,0.121909f},{-0.0255986f,0.302667f,0.120045f}, +{-0.0256356f,0.301289f,0.120045f},{-0.0255992f,0.302654f,0.121909f},{-0.0256356f,0.301289f,0.121909f}, +{0.013579f,0.323032f,0.120045f},{0.0158124f,0.321467f,0.120045f},{0.0247034f,0.301289f,0.104011f}, +{0.0261017f,0.301289f,0.10513f},{0.0260447f,0.299565f,0.10513f},{0.0148773f,0.318617f,0.10252f}, +{0.0141264f,0.317418f,0.101401f},{0.0130365f,0.318311f,0.101401f},{0.0151609f,0.316449f,0.101401f}, +{0.0131883f,0.319935f,0.10252f},{0.0144813f,0.323005f,0.10513f},{0.0123517f,0.322682f,0.104011f}, +{0.0130346f,0.323903f,0.10513f},{0.0118953f,0.319127f,0.101401f},{0.0114195f,0.321068f,0.10252f}, +{0.0115354f,0.324703f,0.10513f},{0.00947527f,0.320522f,0.101401f},{0.00998868f,0.325403f,0.10513f}, +{0.00820499f,0.321097f,0.101401f},{0.0084f,0.326002f,0.10513f},{0.00689981f,0.321589f,0.101401f}, +{0.00556423f,0.321995f,0.101401f},{0.00677408f,0.326496f,0.10513f},{0.00420236f,0.322313f,0.101401f}, +{0.00511591f,0.326884f,0.10513f},{0.00343096f,0.327164f,0.10513f},{0.0028181f,0.322543f,0.101401f}, +{0.00172399f,0.327333f,0.10513f},{0.00141594f,0.322683f,0.101401f},{-2.32983e-017f,0.32739f,0.10513f}, +{0.0164604f,0.317121f,0.10252f},{0.016129f,0.315415f,0.101401f},{0.0179091f,0.315462f,0.10252f}, +{0.0170221f,0.314325f,0.101401f},{0.0178384f,0.313184f,0.101401f},{0.0192f,0.313657f,0.10252f}, +{0.018576f,0.311996f,0.101401f},{0.0203119f,0.311731f,0.10252f},{0.0192333f,0.310764f,0.101401f}, +{0.0212292f,0.309711f,0.10252f},{0.0198086f,0.309494f,0.101401f},{0.0252075f,0.308062f,0.10513f}, +{0.0255955f,0.306404f,0.10513f},{0.0242782f,0.305853f,0.104011f},{0.021942f,0.307626f,0.10252f}, +{0.0203001f,0.308189f,0.101401f},{0.0224458f,0.305508f,0.10252f},{0.0207061f,0.306853f,0.101401f}, +{0.0210249f,0.305491f,0.101401f},{0.0227423f,0.303385f,0.10252f},{0.0212547f,0.304107f,0.101401f}, +{0.0260448f,0.303012f,0.10513f},{0.022839f,0.301289f,0.10252f},{0.0213939f,0.302705f,0.101401f}, +{0.0212463f,0.298408f,0.101401f},{0.021392f,0.299845f,0.101401f},{0.0258753f,0.297858f,0.10513f}, +{0.0202358f,0.294203f,0.101401f},{0.0206669f,0.295581f,0.101401f},{0.0247131f,0.292889f,0.10513f}, +{0.0210042f,0.296985f,0.101401f},{0.0255955f,0.296173f,0.10513f},{0.0252074f,0.294514f,0.10513f}, +{0.0191008f,0.291549f,0.101401f},{0.0226142f,0.288254f,0.10513f},{0.0184019f,0.290285f,0.101401f}, +{0.0241148f,0.2913f,0.10513f},{0.0234144f,0.289753f,0.10513f},{0.019713f,0.292857f,0.101401f}, +{0.0207226f,0.285418f,0.10513f},{0.0196354f,0.284091f,0.10513f},{0.0167571f,0.287913f,0.101401f}, +{0.0176194f,0.289072f,0.101401f},{0.0217163f,0.286807f,0.10513f},{0.0158706f,0.280566f,0.10513f}, +{0.0137317f,0.284822f,0.101401f},{0.0171974f,0.281653f,0.10513f},{0.0148089f,0.285784f,0.101401f}, +{0.0158188f,0.286816f,0.101401f},{0.0184567f,0.282832f,0.10513f},{0.0101475f,0.282401f,0.101401f}, +{0.0113957f,0.283127f,0.101401f},{0.0114195f,0.281509f,0.10252f},{0.0125922f,0.283935f,0.101401f}, +{0.0123517f,0.279895f,0.104011f},{0.0130343f,0.278674f,0.10513f},{0.0109801f,0.279159f,0.104011f}, +{0.00954347f,0.278503f,0.104011f},{0.00998868f,0.277174f,0.10513f},{0.00804836f,0.277933f,0.104011f}, +{0.0115351f,0.277874f,0.10513f},{0.00650255f,0.277456f,0.104011f},{0.00677384f,0.276081f,0.10513f}, +{0.00491482f,0.277079f,0.104011f},{0.00839976f,0.276575f,0.10513f},{0.00329485f,0.276806f,0.104011f}, +{0.00511591f,0.275693f,0.10513f},{0.00343072f,0.275413f,0.10513f},{0.00172376f,0.275244f,0.10513f}, +{0.00165296f,0.276641f,0.104011f},{-2.64948e-017f,0.275187f,0.10513f},{-2.64948e-017f,0.276585f,0.104011f}, +{0.0144813f,0.279572f,0.10513f},{0.00454389f,0.278906f,0.10252f},{0.00475341f,0.280385f,0.101401f}, +{0.00601179f,0.279255f,0.10252f},{0.00304618f,0.278654f,0.10252f},{0.00333561f,0.28011f,0.101401f}, +{0.00190254f,0.279933f,0.101401f},{0.00152821f,0.278501f,0.10252f},{-2.64948e-017f,0.27845f,0.10252f}, +{0.00615037f,0.280749f,0.101401f},{0.00751875f,0.281209f,0.101401f},{0.00882321f,0.280223f,0.10252f}, +{0.00744093f,0.279696f,0.10252f},{0.00885315f,0.281761f,0.101401f},{0.0101514f,0.28083f,0.10252f}, +{0.0142636f,0.321458f,0.104011f},{0.0107068f,0.319865f,0.101401f},{0.0160914f,0.320032f,0.104011f}, +{0.0158708f,0.322011f,0.10513f},{0.0184567f,0.319745f,0.10513f},{0.0171976f,0.320924f,0.10513f}, +{0.0178031f,0.318415f,0.104011f},{0.0193705f,0.31662f,0.104011f},{0.0196355f,0.318486f,0.10513f}, +{0.0217163f,0.31577f,0.10513f},{0.0207227f,0.317159f,0.10513f},{0.0207667f,0.314668f,0.104011f}, +{0.0219695f,0.312585f,0.104011f},{0.0226143f,0.314323f,0.10513f},{0.0234145f,0.312824f,0.10513f}, +{0.0229621f,0.310399f,0.104011f},{0.0241148f,0.311277f,0.10513f},{0.0237331f,0.308145f,0.104011f}, +{0.0247132f,0.309688f,0.10513f},{0.0245992f,0.303558f,0.104011f},{0.0258754f,0.304719f,0.10513f}, +{0.0214407f,0.301289f,0.10513f},{0.0214407f,0.301289f,0.106062f},{0.0214037f,0.300029f,0.106062f}, +{0.0212935f,0.29878f,0.106062f},{0.0214037f,0.300029f,0.10513f},{0.0211114f,0.297545f,0.106062f}, +{0.0212936f,0.298781f,0.10513f},{0.0211115f,0.297545f,0.10513f},{0.0208586f,0.296326f,0.106062f}, +{0.0205363f,0.295127f,0.106062f},{0.0208587f,0.296327f,0.10513f},{0.0201457f,0.29395f,0.106062f}, +{0.0205363f,0.295127f,0.10513f},{0.0201457f,0.29395f,0.10513f},{0.0196879f,0.292798f,0.106062f}, +{0.0191643f,0.291674f,0.106062f},{0.019688f,0.292798f,0.10513f},{0.018576f,0.290582f,0.106062f}, +{0.0191643f,0.291674f,0.10513f},{0.018576f,0.290582f,0.10513f},{0.0179242f,0.289523f,0.106062f}, +{0.0172102f,0.288501f,0.106062f},{0.0179243f,0.289523f,0.10513f},{0.0164352f,0.287519f,0.106062f}, +{0.0172102f,0.288501f,0.10513f},{0.0164352f,0.287519f,0.10513f},{0.0155998f,0.28658f,0.106062f}, +{0.0147082f,0.285688f,0.106062f},{0.0156004f,0.28658f,0.10513f},{0.0137691f,0.284853f,0.106062f}, +{0.0147088f,0.285689f,0.10513f},{0.0137693f,0.284853f,0.10513f},{0.0127873f,0.284078f,0.106062f}, +{0.0117655f,0.283364f,0.106062f},{0.0127873f,0.284078f,0.10513f},{0.0107068f,0.282713f,0.106062f}, +{0.0117656f,0.283364f,0.10513f},{0.010707f,0.282713f,0.10513f},{0.00961408f,0.282124f,0.106062f}, +{0.00849036f,0.281601f,0.106062f},{0.0096143f,0.282124f,0.10513f},{0.0073385f,0.281143f,0.106062f}, +{0.00849054f,0.281601f,0.10513f},{0.00733859f,0.281143f,0.10513f},{0.00616138f,0.280752f,0.106062f}, +{0.00496191f,0.28043f,0.106062f},{0.00616144f,0.280752f,0.10513f},{0.00496208f,0.28043f,0.10513f}, +{0.00374334f,0.280177f,0.10513f},{0.00250813f,0.279995f,0.10513f},{0.00374312f,0.280177f,0.106062f}, +{0.00125925f,0.279885f,0.106062f},{0.00250793f,0.279995f,0.106062f},{-2.38691e-017f,0.279848f,0.106062f}, +{0.00125938f,0.279885f,0.10513f},{-2.38691e-017f,0.279848f,0.10513f},{0.0214037f,0.302548f,0.10513f}, +{0.0212935f,0.303797f,0.10513f},{0.0214037f,0.302548f,0.106062f},{0.0212936f,0.303796f,0.106062f}, +{0.0211114f,0.305032f,0.10513f},{0.0208586f,0.306251f,0.10513f},{0.0211115f,0.305032f,0.106062f}, +{0.0205363f,0.30745f,0.10513f},{0.0208587f,0.30625f,0.106062f},{0.0205363f,0.30745f,0.106062f}, +{0.0201457f,0.308627f,0.10513f},{0.0196879f,0.309779f,0.10513f},{0.0201457f,0.308627f,0.106062f}, +{0.0191643f,0.310903f,0.10513f},{0.019688f,0.309779f,0.106062f},{0.0191643f,0.310903f,0.106062f}, +{0.018576f,0.311996f,0.10513f},{0.0179242f,0.313054f,0.10513f},{0.018576f,0.311995f,0.106062f}, +{0.0172102f,0.314076f,0.10513f},{0.0179243f,0.313054f,0.106062f},{0.0172102f,0.314076f,0.106062f}, +{0.0164352f,0.315058f,0.10513f},{0.0155998f,0.315997f,0.10513f},{0.0164352f,0.315058f,0.106062f}, +{0.0147082f,0.316889f,0.10513f},{0.0156004f,0.315997f,0.106062f},{0.0147088f,0.316888f,0.106062f}, +{0.0137691f,0.317724f,0.10513f},{0.0127873f,0.318499f,0.10513f},{0.0137693f,0.317724f,0.106062f}, +{0.0117655f,0.319213f,0.10513f},{0.0127873f,0.318499f,0.106062f},{0.0117656f,0.319213f,0.106062f}, +{0.0107068f,0.319865f,0.10513f},{0.00961408f,0.320453f,0.10513f},{0.010707f,0.319865f,0.106062f}, +{0.00849036f,0.320976f,0.10513f},{0.0096143f,0.320453f,0.106062f},{0.00849054f,0.320976f,0.106062f}, +{0.0073385f,0.321434f,0.10513f},{0.00616138f,0.321825f,0.10513f},{0.00733859f,0.321434f,0.106062f}, +{0.00496191f,0.322147f,0.10513f},{0.00616144f,0.321825f,0.106062f},{0.00374334f,0.3224f,0.106062f}, +{0.00496208f,0.322147f,0.106062f},{0.00374312f,0.3224f,0.10513f},{0.00250813f,0.322582f,0.106062f}, +{0.00250793f,0.322582f,0.10513f},{0.00125925f,0.322692f,0.10513f},{0.00125938f,0.322692f,0.106062f}, +{-2.64948e-017f,0.322729f,0.10513f},{-2.64948e-017f,0.322729f,0.106062f},{0.0261017f,0.301289f,0.106062f}, +{0.0261017f,0.301289f,0.120045f},{0.0260652f,0.299908f,0.120045f},{0.0259565f,0.298538f,0.120045f}, +{0.0260653f,0.299908f,0.106062f},{0.0257765f,0.297181f,0.120045f},{0.0259565f,0.298538f,0.106062f}, +{0.0257766f,0.297181f,0.106062f},{0.0255265f,0.295839f,0.120045f},{0.0252074f,0.294514f,0.120045f}, +{0.0255265f,0.295839f,0.106062f},{0.0248204f,0.293211f,0.120045f},{0.0252075f,0.294515f,0.106062f}, +{0.0248205f,0.293211f,0.106062f},{0.0243664f,0.29193f,0.120045f},{0.0238467f,0.290676f,0.120045f}, +{0.0243666f,0.291931f,0.106062f},{0.0232623f,0.289449f,0.120045f},{0.0238468f,0.290676f,0.106062f}, +{0.0232624f,0.28945f,0.106062f},{0.0226142f,0.288254f,0.120045f},{0.0219036f,0.287092f,0.120045f}, +{0.0226143f,0.288254f,0.106062f},{0.0211314f,0.285966f,0.120045f},{0.0219036f,0.287092f,0.106062f}, +{0.0211315f,0.285967f,0.106062f},{0.0202988f,0.284879f,0.120045f},{0.0194069f,0.283834f,0.120045f}, +{0.0202989f,0.284879f,0.106062f},{0.0184567f,0.282832f,0.120045f},{0.0194069f,0.283834f,0.106062f}, +{0.0184567f,0.282832f,0.106062f},{0.0174549f,0.281882f,0.120045f},{0.0164091f,0.28099f,0.120045f}, +{0.0174549f,0.281882f,0.106062f},{0.015322f,0.280157f,0.120045f},{0.0164092f,0.28099f,0.106062f}, +{0.0153222f,0.280157f,0.106062f},{0.0141962f,0.279385f,0.120045f},{0.0130343f,0.278674f,0.120045f}, +{0.0141964f,0.279385f,0.106062f},{0.0118389f,0.278026f,0.120045f},{0.0130346f,0.278674f,0.106062f}, +{0.0118391f,0.278026f,0.106062f},{0.0106125f,0.277442f,0.120045f},{0.00935782f,0.276922f,0.120045f}, +{0.0106128f,0.277442f,0.106062f},{0.0080774f,0.276468f,0.120045f},{0.00935809f,0.276922f,0.106062f}, +{0.00807765f,0.276468f,0.106062f},{0.00677384f,0.276081f,0.120045f},{0.00544975f,0.275762f,0.120045f}, +{0.00677408f,0.276081f,0.106062f},{0.00410773f,0.275512f,0.120045f},{0.00544996f,0.275762f,0.106062f}, +{0.0041079f,0.275512f,0.106062f},{0.00275036f,0.275332f,0.120045f},{0.00138025f,0.275223f,0.120045f}, +{0.00275048f,0.275332f,0.106062f},{-2.32983e-017f,0.275187f,0.120045f},{0.00138032f,0.275223f,0.106062f}, +{-2.32983e-017f,0.275187f,0.106062f},{0.0260652f,0.302669f,0.106062f},{0.0259565f,0.304039f,0.106062f}, +{0.0260653f,0.302669f,0.120045f},{0.0259565f,0.304039f,0.120045f},{0.0257765f,0.305396f,0.106062f}, +{0.0255265f,0.306739f,0.106062f},{0.0257766f,0.305396f,0.120045f},{0.0252074f,0.308063f,0.106062f}, +{0.0255265f,0.306738f,0.120045f},{0.0252075f,0.308062f,0.120045f},{0.0248204f,0.309366f,0.106062f}, +{0.0243664f,0.310647f,0.106062f},{0.0248205f,0.309366f,0.120045f},{0.0238467f,0.311901f,0.106062f}, +{0.0243666f,0.310646f,0.120045f},{0.0238468f,0.311901f,0.120045f},{0.0232623f,0.313128f,0.106062f}, +{0.0226142f,0.314323f,0.106062f},{0.0232624f,0.313127f,0.120045f},{0.0219036f,0.315485f,0.106062f}, +{0.0226143f,0.314323f,0.120045f},{0.0219036f,0.315485f,0.120045f},{0.0211314f,0.316611f,0.106062f}, +{0.0202988f,0.317698f,0.106062f},{0.0211315f,0.316611f,0.120045f},{0.0194069f,0.318743f,0.106062f}, +{0.0202989f,0.317698f,0.120045f},{0.0194069f,0.318743f,0.120045f},{0.0184567f,0.319745f,0.106062f}, +{0.0174549f,0.320695f,0.106062f},{0.0184567f,0.319745f,0.120045f},{0.0164091f,0.321587f,0.106062f}, +{0.0174549f,0.320695f,0.120045f},{0.0164092f,0.321587f,0.120045f},{0.015322f,0.32242f,0.106062f}, +{0.0141962f,0.323192f,0.106062f},{0.0153222f,0.32242f,0.120045f},{0.0130343f,0.323903f,0.106062f}, +{0.0141964f,0.323192f,0.120045f},{0.0130346f,0.323903f,0.120045f},{0.0118389f,0.324551f,0.106062f}, +{0.0106125f,0.325135f,0.106062f},{0.0118391f,0.324551f,0.120045f},{0.00935782f,0.325655f,0.106062f}, +{0.0106128f,0.325135f,0.120045f},{0.00935809f,0.325655f,0.120045f},{0.0080774f,0.326109f,0.106062f}, +{0.00677384f,0.326496f,0.106062f},{0.00807765f,0.326109f,0.120045f},{0.00544975f,0.326815f,0.106062f}, +{0.00677408f,0.326496f,0.120045f},{0.00544996f,0.326815f,0.120045f},{0.00410773f,0.327065f,0.106062f}, +{0.00275036f,0.327245f,0.106062f},{0.0041079f,0.327065f,0.120045f},{0.00138025f,0.327354f,0.106062f}, +{0.00275048f,0.327245f,0.120045f},{0.00138032f,0.327354f,0.120045f},{-2.64948e-017f,0.32739f,0.106062f}, +{-2.64948e-017f,0.32739f,0.120045f},{0.0121333f,0.298398f,0.125638f},{-0.0149893f,0.307258f,0.125638f}, +{-0.0150309f,0.307814f,0.125638f},{-0.019126f,0.30503f,0.125638f},{-0.00810759f,0.286008f,0.125638f}, +{-0.00862289f,0.316224f,0.125638f},{-0.00372901f,0.31434f,0.125638f},{-0.00810797f,0.316569f,0.125638f}, +{-0.0122191f,0.315775f,0.125638f},{-0.012803f,0.315983f,0.125638f},{-0.0130106f,0.311605f,0.125638f}, +{0.00523604f,0.311135f,0.125638f},{0.00485519f,0.311216f,0.125638f},{-0.0018645f,0.317568f,0.125638f}, +{-0.00378085f,0.322866f,0.125638f},{-0.00629776f,0.320341f,0.125638f},{0.00943824f,0.311044f,0.125638f}, +{0.00917901f,0.31595f,0.125638f},{0.00862289f,0.316224f,0.125638f},{0.00897792f,0.31073f,0.125638f}, +{0.0172458f,0.301289f,0.125638f},{0.0172871f,0.301907f,0.125638f},{0.010994f,0.3156f,0.125638f}, +{0.0110243f,0.311532f,0.125638f},{0.0115815f,0.311532f,0.125638f},{0.0207988f,0.296759f,0.125638f}, +{0.0210452f,0.295205f,0.125638f},{0.021411f,0.296654f,0.125638f},{0.0174099f,0.300063f,0.125638f}, +{0.017287f,0.30067f,0.125638f},{0.0136278f,0.297678f,0.125638f},{0.019126f,0.297548f,0.125638f}, +{0.0149893f,0.295319f,0.125638f},{0.0150309f,0.294763f,0.125638f},{0.0202118f,0.296955f,0.125638f}, +{0.0149893f,0.294207f,0.125638f},{0.0148647f,0.293665f,0.125638f},{0.0200086f,0.292369f,0.125638f}, +{0.00994038f,0.298234f,0.125638f},{0.0104733f,0.298402f,0.125638f},{0.0143811f,0.292664f,0.125638f}, +{0.0185801f,0.289683f,0.125638f},{0.0193415f,0.291002f,0.125638f},{0.0205774f,0.293774f,0.125638f}, +{0.0196492f,0.297216f,0.125638f},{0.0167976f,0.287226f,0.125638f},{0.013354f,0.28631f,0.125638f}, +{0.0157911f,0.286105f,0.125638f},{0.0136271f,0.291848f,0.125638f},{0.0138626f,0.285956f,0.125638f}, +{0.0143217f,0.285539f,0.125638f},{0.0147191f,0.285063f,0.125638f},{0.0146599f,0.293146f,0.125638f}, +{0.0149896f,0.308369f,0.125638f},{0.0205772f,0.308804f,0.125638f},{0.0148655f,0.295862f,0.125638f}, +{0.0186543f,0.297949f,0.125638f},{0.0182401f,0.298411f,0.125638f},{0.0178906f,0.298923f,0.125638f}, +{0.0143836f,0.296863f,0.125638f},{0.0146621f,0.296381f,0.125638f},{0.0105684f,0.302675f,0.125638f}, +{0.01083f,0.302385f,0.125638f},{0.0174101f,0.302515f,0.125638f},{0.0102536f,0.302903f,0.125638f}, +{0.00810759f,0.316569f,0.125638f},{0.00764282f,0.316979f,0.125638f},{0.0191272f,0.305029f,0.125638f}, +{0.0133515f,0.316269f,0.125638f},{0.0157911f,0.316472f,0.125638f},{0.013859f,0.316626f,0.125638f}, +{0.0143221f,0.317036f,0.125638f},{0.0147191f,0.317514f,0.125638f},{0.0126646f,0.311285f,0.125638f}, +{0.0128028f,0.315982f,0.125638f},{0.0122189f,0.315774f,0.125638f},{0.0116123f,0.315646f,0.125638f}, +{0.0121324f,0.311449f,0.125638f},{0.014035f,0.31035f,0.125638f},{0.0177287f,0.314157f,0.125638f}, +{0.013627f,0.310729f,0.125638f},{0.0131664f,0.311043f,0.125638f},{0.0193407f,0.311577f,0.125638f}, +{0.018579f,0.312896f,0.125638f},{0.0146599f,0.309431f,0.125638f},{0.0167966f,0.315352f,0.125638f}, +{0.0196491f,0.305364f,0.125638f},{0.02021f,0.305627f,0.125638f},{0.0210452f,0.307372f,0.125638f}, +{0.0208003f,0.305817f,0.125638f},{0.021411f,0.305923f,0.125638f},{0.0143816f,0.309913f,0.125638f}, +{0.0200082f,0.31021f,0.125638f},{0.0148642f,0.308912f,0.125638f},{-0.00635281f,0.320959f,0.125638f}, +{-0.00525411f,0.322556f,0.125638f},{-0.00647672f,0.321566f,0.125638f},{0.00723674f,0.317448f,0.125638f}, +{0.00689651f,0.317966f,0.125638f},{0.018655f,0.304627f,0.125638f},{0.00632427f,0.319723f,0.125638f}, +{0.00643592f,0.319114f,0.125638f},{0.0178912f,0.303655f,0.125638f},{0.0182407f,0.304166f,0.125638f}, +{-0.010376f,0.315635f,0.125638f},{-0.0109947f,0.3156f,0.125638f},{-0.00838954f,0.299674f,0.125638f}, +{-0.00368715f,0.314896f,0.125638f},{-0.00356297f,0.315439f,0.125638f},{-0.00764334f,0.316979f,0.125638f}, +{-0.00632322f,0.319723f,0.125638f},{-0.00643547f,0.319113f,0.125638f},{-0.00232474f,0.317255f,0.125638f}, +{-0.000829763f,0.317974f,0.125638f},{-0.00227994f,0.323076f,0.125638f},{-0.00136226f,0.31781f,0.125638f}, +{-0.00662778f,0.318524f,0.125638f},{-0.00273315f,0.316876f,0.125638f},{0.00377962f,0.322867f,0.125638f}, +{0.00136248f,0.31781f,0.125638f},{0.00027877f,0.318055f,0.125638f},{0.000760576f,0.323182f,0.125638f}, +{-0.000278327f,0.318056f,0.125638f},{0.00629503f,0.320343f,0.125638f},{0.00525411f,0.322556f,0.125638f}, +{-0.00669182f,0.322148f,0.125638f},{0.00634749f,0.32096f,0.125638f},{0.0064786f,0.321566f,0.125638f}, +{0.00669182f,0.322148f,0.125638f},{-0.0030806f,0.31644f,0.125638f},{-0.00689664f,0.317965f,0.125638f}, +{-0.00335928f,0.315958f,0.125638f},{0.00227826f,0.323077f,0.125638f},{0.000829582f,0.317973f,0.125638f}, +{-0.0146621f,0.306197f,0.125638f},{-0.0178906f,0.303654f,0.125638f},{-0.0143836f,0.305714f,0.125638f}, +{0.00408395f,0.311134f,0.125638f},{0.00446533f,0.311216f,0.125638f},{-0.00917948f,0.31595f,0.125638f}, +{-0.0130106f,0.300131f,0.125638f},{-0.00632427f,0.282854f,0.125638f},{-0.00643592f,0.283463f,0.125638f}, +{-0.0097673f,0.315753f,0.125638f},{-0.0205774f,0.308803f,0.125638f},{-0.0210452f,0.307372f,0.125638f}, +{-0.0196492f,0.305361f,0.125638f},{-0.0136271f,0.310729f,0.125638f},{-0.0177299f,0.314156f,0.125638f}, +{-0.0140346f,0.310349f,0.125638f},{-0.00590935f,0.310746f,0.125638f},{-0.0207988f,0.305818f,0.125638f}, +{-0.021411f,0.305923f,0.125638f},{-0.0140362f,0.305278f,0.125638f},{-0.0174099f,0.302514f,0.125638f}, +{-0.0136278f,0.304899f,0.125638f},{-0.0182401f,0.304166f,0.125638f},{-0.0148655f,0.306715f,0.125638f}, +{-0.0186543f,0.304628f,0.125638f},{-0.0202118f,0.305622f,0.125638f},{-0.0149893f,0.30837f,0.125638f}, +{-0.0148647f,0.308913f,0.125638f},{-0.0200086f,0.310208f,0.125638f},{-0.0193415f,0.311575f,0.125638f}, +{-0.0143811f,0.309913f,0.125638f},{-0.0185801f,0.312894f,0.125638f},{-0.0146599f,0.309431f,0.125638f}, +{-0.013354f,0.316267f,0.125638f},{-0.0157911f,0.316472f,0.125638f},{-0.0167976f,0.315351f,0.125638f}, +{-0.0138626f,0.316622f,0.125638f},{-0.00976653f,0.286824f,0.125638f},{-0.00917901f,0.286627f,0.125638f}, +{-0.00994062f,0.291292f,0.125638f},{-0.0143217f,0.317038f,0.125638f},{-0.0147191f,0.317514f,0.125638f}, +{-0.00636453f,0.310119f,0.125638f},{-0.00648481f,0.309748f,0.125638f},{-0.0176127f,0.299476f,0.125638f}, +{-0.0178912f,0.298922f,0.125638f},{-0.0116126f,0.315647f,0.125638f},{-0.00862289f,0.286353f,0.125638f}, +{-0.00943824f,0.291533f,0.125638f},{-0.00315227f,0.29212f,0.125638f},{-0.00295749f,0.292458f,0.125638f}, +{-0.0104733f,0.291128f,0.125638f},{-0.0196491f,0.297213f,0.125638f},{-0.0205772f,0.293773f,0.125638f}, +{-0.0167966f,0.287225f,0.125638f},{-0.0157911f,0.286105f,0.125638f},{-0.0130106f,0.288657f,0.125638f}, +{-0.0122189f,0.286803f,0.125638f},{-0.0116123f,0.286931f,0.125638f},{-0.017287f,0.301907f,0.125638f}, +{-0.0174101f,0.300062f,0.125638f},{-0.0172458f,0.301289f,0.125638f},{-0.00723674f,0.285129f,0.125638f}, +{-0.00689651f,0.284611f,0.125638f},{-0.013859f,0.285951f,0.125638f},{-0.0133515f,0.286308f,0.125638f}, +{-0.0115815f,0.291045f,0.125638f},{-0.0121324f,0.291128f,0.125638f},{-0.014035f,0.292227f,0.125638f}, +{-0.0177287f,0.28842f,0.125638f},{-0.013627f,0.291848f,0.125638f},{-0.0143816f,0.292664f,0.125638f}, +{-0.018579f,0.289681f,0.125638f},{-0.0193407f,0.291f,0.125638f},{-0.0146599f,0.293147f,0.125638f}, +{-0.0149896f,0.294208f,0.125638f},{-0.0131664f,0.291534f,0.125638f},{-0.0126646f,0.291292f,0.125638f}, +{-0.0210452f,0.295205f,0.125638f},{-0.0143221f,0.285541f,0.125638f},{-0.02021f,0.29695f,0.125638f}, +{-0.0208003f,0.29676f,0.125638f},{-0.0147191f,0.285063f,0.125638f},{-0.021411f,0.296654f,0.125638f}, +{-0.0110243f,0.291045f,0.125638f},{0.00874495f,0.303061f,0.125638f},{0.00838954f,0.302903f,0.125638f}, +{-0.00523587f,0.291442f,0.125638f},{-0.00485544f,0.291361f,0.125638f},{0.0063639f,0.293974f,0.125638f}, +{0.00616894f,0.294312f,0.125638f},{-0.00629503f,0.282234f,0.125638f},{-0.00377962f,0.27971f,0.125638f}, +{0.0099371f,0.288657f,0.125638f},{0.0109947f,0.286977f,0.125638f},{0.0116126f,0.286931f,0.125638f}, +{0.00356297f,0.287138f,0.125638f},{0.00764334f,0.285598f,0.125638f},{0.00368715f,0.287681f,0.125638f}, +{0.0097673f,0.286824f,0.125638f},{0.00917948f,0.286627f,0.125638f},{0.00643547f,0.283464f,0.125638f}, +{0.00232474f,0.285323f,0.125638f},{0.00632322f,0.282854f,0.125638f},{0.00810797f,0.286008f,0.125638f}, +{0.00862289f,0.286353f,0.125638f},{0.00372901f,0.288237f,0.125638f},{0.00378085f,0.279711f,0.125638f}, +{0.00629776f,0.282236f,0.125638f},{0.0018645f,0.285009f,0.125638f},{0.0111453f,0.301677f,0.125638f}, +{0.0110251f,0.302047f,0.125638f},{-0.0200082f,0.292368f,0.125638f},{-0.0148642f,0.293665f,0.125638f}, +{-0.010994f,0.286978f,0.125638f},{0.00773683f,0.308915f,0.125638f},{-0.0110251f,0.30053f,0.125638f}, +{-0.0111453f,0.3009f,0.125638f},{-0.00764282f,0.285598f,0.125638f},{-0.0105684f,0.299902f,0.125638f}, +{0.00807379f,0.302673f,0.125638f},{-0.000829582f,0.284604f,0.125638f},{-0.00136248f,0.284767f,0.125638f}, +{-0.00227826f,0.2795f,0.125638f},{-0.00027877f,0.284522f,0.125638f},{-0.000760576f,0.279395f,0.125638f}, +{0.000278327f,0.284521f,0.125638f},{0.000829763f,0.284603f,0.125638f},{0.00227994f,0.279501f,0.125638f}, +{0.00136226f,0.284767f,0.125638f},{-0.00525411f,0.280021f,0.125638f},{-0.00634749f,0.281617f,0.125638f}, +{-0.0064786f,0.281011f,0.125638f},{-0.00669182f,0.280429f,0.125638f},{0.00335928f,0.286619f,0.125638f}, +{0.0030806f,0.286137f,0.125638f},{0.00689664f,0.284612f,0.125638f},{0.00273315f,0.285701f,0.125638f}, +{0.00662778f,0.284053f,0.125638f},{0.00525411f,0.280021f,0.125638f},{0.00635281f,0.281618f,0.125638f}, +{0.00669182f,0.280429f,0.125638f},{0.00647672f,0.281011f,0.125638f},{0.0176127f,0.303101f,0.125638f}, +{0.00994062f,0.311285f,0.125638f},{0.0103751f,0.315635f,0.125638f},{0.00976653f,0.315753f,0.125638f}, +{0.0104733f,0.311449f,0.125638f},{0.00912617f,0.303143f,0.125638f},{0.0095162f,0.303143f,0.125638f}, +{0.00989767f,0.303062f,0.125638f},{0.0140362f,0.297299f,0.125638f},{0.0110245f,0.298472f,0.125638f}, +{0.0177299f,0.288421f,0.125638f},{0.0140346f,0.292228f,0.125638f},{0.00822623f,0.309913f,0.125638f}, +{-0.00408474f,0.307589f,0.125638f},{-0.00446554f,0.307508f,0.125638f},{-0.018655f,0.29795f,0.125638f}, +{-0.0191272f,0.297548f,0.125638f},{0.00315227f,0.310457f,0.125638f},{0.00295755f,0.310119f,0.125638f}, +{0.00341361f,0.307976f,0.125638f},{0.00749845f,0.301676f,0.125638f},{0.00761862f,0.302046f,0.125638f}, +{0.0126655f,0.298234f,0.125638f},{0.0131672f,0.297992f,0.125638f},{0.0115822f,0.298477f,0.125638f}, +{0.0122191f,0.286802f,0.125638f},{0.012803f,0.286594f,0.125638f},{0.00590935f,0.291831f,0.125638f}, +{0.00636453f,0.292458f,0.125638f},{0.00648481f,0.292829f,0.125638f},{-0.00408362f,0.291443f,0.125638f}, +{-0.00446544f,0.291361f,0.125638f},{-0.00807379f,0.299904f,0.125638f},{-0.00430393f,0.299506f,0.125638f}, +{0.00283746f,0.29759f,0.125638f},{0.00408474f,0.294989f,0.125638f},{0.00446554f,0.29507f,0.125638f}, +{-0.00874495f,0.299516f,0.125638f},{-0.0172871f,0.30067f,0.125638f},{0.00761515f,0.30837f,0.125638f}, +{0.0085695f,0.310351f,0.125638f},{-0.00723717f,0.317447f,0.125638f},{-0.000762504f,0.323182f,0.125638f}, +{0.00662806f,0.318524f,0.125638f},{0.00341281f,0.310746f,0.125638f},{0.00372825f,0.310976f,0.125638f}, +{0.00279662f,0.309361f,0.125638f},{0.00283723f,0.309748f,0.125638f},{0.00283764f,0.308973f,0.125638f}, +{-0.00335595f,0.312725f,0.125638f},{0.00795154f,0.309428f,0.125638f},{-0.00369782f,0.298452f,0.125638f}, +{0.00295819f,0.308603f,0.125638f},{0.00315308f,0.308265f,0.125638f},{-0.00523619f,0.307588f,0.125638f}, +{-0.00616894f,0.308265f,0.125638f},{-0.0063639f,0.308603f,0.125638f},{-0.00273651f,0.311802f,0.125638f}, +{-0.00232523f,0.311424f,0.125638f},{-0.00356376f,0.313241f,0.125638f},{-0.0131672f,0.304585f,0.125638f}, +{-0.0176123f,0.3031f,0.125638f},{-0.00616972f,0.310457f,0.125638f},{-0.00648443f,0.308973f,0.125638f}, +{-0.00652539f,0.309361f,0.125638f},{-0.00559278f,0.307747f,0.125638f},{-0.00590766f,0.307976f,0.125638f}, +{-0.0048551f,0.307507f,0.125638f},{-0.00307294f,0.312244f,0.125638f},{-0.0110245f,0.304105f,0.125638f}, +{-0.0095162f,0.299434f,0.125638f},{-0.00368758f,0.313784f,0.125638f},{-0.00897792f,0.291847f,0.125638f}, +{-0.0103751f,0.286942f,0.125638f},{-0.0128028f,0.286595f,0.125638f},{-0.0182407f,0.298411f,0.125638f}, +{-0.01083f,0.300192f,0.125638f},{-0.0102536f,0.299674f,0.125638f},{-0.00912617f,0.299435f,0.125638f}, +{-0.00989767f,0.299515f,0.125638f},{-0.0115822f,0.3041f,0.125638f},{-0.0121333f,0.304179f,0.125638f}, +{-0.0104733f,0.304175f,0.125638f},{-0.00994038f,0.304343f,0.125638f},{-0.00462174f,0.30068f,0.125638f}, +{-0.00761862f,0.300531f,0.125638f},{-0.00449935f,0.300083f,0.125638f},{-0.00749845f,0.300901f,0.125638f}, +{-0.00761515f,0.294207f,0.125638f},{-0.0085695f,0.292226f,0.125638f},{-0.00822623f,0.292664f,0.125638f}, +{-0.00773683f,0.293662f,0.125638f},{-0.00403697f,0.298958f,0.125638f},{-0.0126655f,0.304343f,0.125638f}, +{0.00559278f,0.29483f,0.125638f},{0.00723717f,0.28513f,0.125638f},{0.000762504f,0.279395f,0.125638f}, +{-0.00662806f,0.284053f,0.125638f},{-0.00341302f,0.29183f,0.125638f},{-0.00372824f,0.291601f,0.125638f}, +{-0.00279657f,0.293216f,0.125638f},{-0.00283721f,0.292829f,0.125638f},{-0.0028377f,0.293604f,0.125638f}, +{0.00120604f,0.296786f,0.125638f},{-0.00795154f,0.293149f,0.125638f},{0.003698f,0.298451f,0.125638f}, +{0.00329612f,0.297992f,0.125638f},{0.0048551f,0.29507f,0.125638f},{0.00523619f,0.294989f,0.125638f}, +{0.00781324f,0.302384f,0.125638f},{0.00430606f,0.299504f,0.125638f},{0.00356376f,0.289336f,0.125638f}, +{-0.00283752f,0.297591f,0.125638f},{-0.00329569f,0.297993f,0.125638f},{0.00178338f,0.296982f,0.125638f}, +{0.000608186f,0.296667f,0.125638f},{-2.76333e-017f,0.296628f,0.125638f},{-0.0034133f,0.294601f,0.125638f}, +{-0.00233082f,0.297253f,0.125638f},{-0.00295825f,0.293975f,0.125638f},{-0.00120688f,0.296787f,0.125638f}, +{-0.00315303f,0.294312f,0.125638f},{0.0176123f,0.299477f,0.125638f},{0.010376f,0.286942f,0.125638f}, +{0.00616972f,0.29212f,0.125638f},{0.00648443f,0.293604f,0.125638f},{0.00652539f,0.293216f,0.125638f}, +{0.00449528f,0.300083f,0.125638f},{0.00590766f,0.294602f,0.125638f},{0.00273651f,0.290775f,0.125638f}, +{0.00335595f,0.289852f,0.125638f},{0.00232523f,0.291153f,0.125638f},{0.00307294f,0.290333f,0.125638f}, +{0.00461789f,0.30068f,0.125638f},{0.00403651f,0.298958f,0.125638f},{0.00368758f,0.288793f,0.125638f}, +{0.00233031f,0.297252f,0.125638f},{-0.00060875f,0.296667f,0.125638f},{-0.00178418f,0.296983f,0.125638f}, +{-0.00781324f,0.300193f,0.125638f},{0.0216239f,0.295038f,0.12559f},{0.0211432f,0.293567f,0.12559f}, +{0.0217239f,0.293355f,0.125434f},{0.0192916f,0.285138f,0.12373f},{0.0203623f,0.286511f,0.12373f}, +{0.0200519f,0.286736f,0.12429f},{0.0210134f,0.288163f,0.12429f},{0.0213388f,0.28796f,0.12373f}, +{0.0186268f,0.285695f,0.124775f},{0.0181976f,0.286054f,0.125161f},{0.0175107f,0.284451f,0.124775f}, +{0.016671f,0.285259f,0.125434f},{0.0158563f,0.28381f,0.125232f},{0.0171072f,0.284839f,0.125161f}, +{0.0151138f,0.284628f,0.125592f},{0.0154952f,0.284208f,0.125455f},{0.0162253f,0.285687f,0.12559f}, +{0.0218746f,0.289655f,0.12429f},{0.0222133f,0.289475f,0.12373f},{0.0226291f,0.291201f,0.12429f}, +{0.0215683f,0.287817f,0.123126f},{0.0217015f,0.287733f,0.122512f},{0.0224522f,0.289348f,0.123126f}, +{0.021363f,0.287118f,0.121909f},{0.0222009f,0.288471f,0.121909f},{0.0207085f,0.28626f,0.122512f}, +{0.0204426f,0.28582f,0.121909f},{0.0196196f,0.284864f,0.122512f},{0.0225908f,0.289274f,0.122512f}, +{0.0229535f,0.289873f,0.121909f},{0.0183695f,0.283407f,0.121909f},{0.0194435f,0.284581f,0.121909f}, +{0.018444f,0.283554f,0.122512f},{0.0172245f,0.282302f,0.121909f},{0.0171931f,0.282336f,0.122497f}, +{0.02337f,0.290871f,0.122512f},{0.0236175f,0.291319f,0.121909f},{0.0240343f,0.292511f,0.122512f}, +{0.0241903f,0.292804f,0.121909f},{0.024671f,0.294321f,0.121909f},{0.0245807f,0.294183f,0.122512f}, +{0.0250097f,0.295875f,0.122497f},{0.024876f,0.295904f,0.123065f},{0.0229794f,0.291045f,0.12373f}, +{0.0181357f,0.28385f,0.12373f},{0.0189975f,0.285384f,0.12429f},{0.0250554f,0.295865f,0.121909f}, +{0.0232266f,0.290935f,0.123126f},{0.0233369f,0.294543f,0.124775f},{0.0235497f,0.296191f,0.124929f}, +{0.0227992f,0.294698f,0.125161f},{0.0239879f,0.296096f,0.124546f},{0.0238014f,0.294408f,0.12429f}, +{0.0209535f,0.290145f,0.125161f},{0.0216762f,0.291626f,0.125161f},{0.0211235f,0.291872f,0.125434f}, +{0.0219851f,0.29653f,0.125592f},{0.0244299f,0.294227f,0.123126f},{0.0246584f,0.295951f,0.123602f}, +{0.0241699f,0.294302f,0.12373f},{0.0238868f,0.292565f,0.123126f},{0.0205814f,0.286352f,0.123126f}, +{0.0194991f,0.284964f,0.123126f},{0.0183308f,0.283663f,0.123126f},{0.0171019f,0.282437f,0.123062f}, +{0.02436f,0.296016f,0.1241f},{0.0236326f,0.292658f,0.12373f},{0.0169523f,0.282602f,0.1236f}, +{0.0222178f,0.294866f,0.125434f},{0.0230629f,0.296296f,0.125233f},{0.0232723f,0.29279f,0.12429f}, +{0.0196606f,0.28702f,0.124775f},{0.0178592f,0.284116f,0.12429f},{0.0167476f,0.282827f,0.124098f}, +{0.0221874f,0.291398f,0.124775f},{0.0228181f,0.292956f,0.124775f},{0.0214477f,0.289882f,0.124775f}, +{0.0206034f,0.288419f,0.124775f},{0.0164907f,0.283111f,0.124546f},{0.0222924f,0.293148f,0.125161f}, +{0.0201286f,0.288716f,0.125161f},{0.0192076f,0.287349f,0.125161f},{0.0161909f,0.283441f,0.124927f}, +{0.0225375f,0.29641f,0.125456f},{0.0204192f,0.290429f,0.125434f},{0.0196153f,0.289036f,0.125434f}, +{0.0187178f,0.287705f,0.125434f},{0.0172595f,0.286839f,0.12559f},{0.0177335f,0.286443f,0.125434f}, +{0.0205588f,0.292124f,0.12559f},{0.0198733f,0.290719f,0.12559f},{0.019091f,0.289364f,0.12559f}, +{0.0182174f,0.288068f,0.12559f},{0.000885136f,0.275874f,0.123126f},{0.00261846f,0.276266f,0.12373f}, +{0.000875717f,0.276144f,0.12373f},{0.00441602f,0.276086f,0.122512f},{0.00266296f,0.275841f,0.122512f}, +{0.00264799f,0.27579f,0.121909f},{0.00257853f,0.276647f,0.12429f},{0.000884103f,0.275668f,0.121909f}, +{0.00609912f,0.276601f,0.123126f},{0.00613678f,0.276448f,0.122512f},{0.0077748f,0.277053f,0.123065f}, +{0.00612578f,0.276411f,0.121909f},{0.00781658f,0.276923f,0.122497f},{0.00539858f,0.279436f,0.12559f}, +{0.00388481f,0.279117f,0.12559f},{0.00399151f,0.278508f,0.125434f},{0.00783085f,0.276878f,0.121909f}, +{0.00439916f,0.276033f,0.121909f},{0.00749724f,0.277918f,0.124546f},{0.00582624f,0.277705f,0.124775f}, +{0.00594221f,0.277236f,0.12429f},{0.00246996f,0.277685f,0.125161f},{0.00240697f,0.278287f,0.125434f}, +{0.000826054f,0.27757f,0.125161f},{0.005692f,0.278249f,0.125161f},{0.00736026f,0.278345f,0.124929f}, +{0.000890602f,0.275717f,0.122512f},{0.00264662f,0.275997f,0.123126f},{-0.00427461f,0.276884f,0.12429f}, +{-0.00603421f,0.276863f,0.12373f},{-0.0043408f,0.276506f,0.12373f},{0.00687127f,0.279869f,0.125592f}, +{-0.000860185f,0.276528f,0.12429f},{-0.00261652f,0.276265f,0.12373f},{-0.000873503f,0.276144f,0.12373f}, +{0.000862365f,0.276528f,0.12429f},{-0.00582624f,0.277705f,0.124775f},{-0.00419119f,0.27736f,0.124775f}, +{-0.00409462f,0.277912f,0.125161f},{-0.00554685f,0.278836f,0.125434f},{-0.00720884f,0.278817f,0.125232f}, +{-0.005692f,0.278249f,0.125161f},{-0.00257663f,0.276647f,0.12429f},{-0.00687127f,0.279869f,0.125592f}, +{-0.00704464f,0.279329f,0.125455f},{-0.00539858f,0.279436f,0.12559f},{-0.00088835f,0.275717f,0.122512f}, +{-0.000882898f,0.275874f,0.123126f},{-0.000883894f,0.275668f,0.121909f},{-0.002661f,0.27584f,0.122512f}, +{-0.00264771f,0.27579f,0.121909f},{-0.00441458f,0.276085f,0.122512f},{-0.00439897f,0.276033f,0.121909f}, +{-0.00612769f,0.276402f,0.121909f},{-0.00613678f,0.276448f,0.122512f},{-0.00783085f,0.276878f,0.121909f}, +{0.00770679f,0.277265f,0.123602f},{0.00603421f,0.276863f,0.12373f},{0.00438891f,0.27624f,0.123126f}, +{-0.00264467f,0.275996f,0.123126f},{-0.00609912f,0.276601f,0.123126f},{-0.00438748f,0.27624f,0.123126f}, +{-0.00781658f,0.276923f,0.122497f},{-0.0077751f,0.277052f,0.123062f},{0.00761353f,0.277556f,0.1241f}, +{0.00434221f,0.276507f,0.12373f},{-0.00770709f,0.277264f,0.1236f},{0.00554685f,0.278836f,0.125434f}, +{0.00720812f,0.278819f,0.125233f},{0.004276f,0.276885f,0.12429f},{-0.00252634f,0.277128f,0.124775f}, +{-0.00594221f,0.277236f,0.12429f},{-0.00761404f,0.277554f,0.124098f},{0.00252821f,0.277128f,0.124775f}, +{0.00419255f,0.277361f,0.124775f},{0.000845536f,0.277011f,0.124775f},{-0.000843398f,0.277011f,0.124775f}, +{-0.00749724f,0.277918f,0.124546f},{0.00409595f,0.277912f,0.125161f},{-0.000823965f,0.27757f,0.125161f}, +{-0.00246814f,0.277685f,0.125161f},{-0.00736095f,0.278343f,0.124927f},{0.00704393f,0.279331f,0.125456f}, +{0.000804989f,0.278175f,0.125434f},{-0.000802953f,0.278175f,0.125434f},{-0.0024052f,0.278286f,0.125434f}, +{-0.00388354f,0.279117f,0.12559f},{-0.00399021f,0.278508f,0.125434f},{0.00234263f,0.278902f,0.12559f}, +{0.00078347f,0.278793f,0.12559f},{-0.000781489f,0.278793f,0.12559f},{-0.0023409f,0.278901f,0.12559f}, +{-0.0217002f,0.287732f,0.122512f},{-0.02058f,0.286351f,0.123126f},{-0.021567f,0.287815f,0.123126f}, +{-0.0207071f,0.286258f,0.122512f},{-0.0213629f,0.287118f,0.121909f},{-0.0204426f,0.28582f,0.121909f}, +{-0.020361f,0.28651f,0.12373f},{-0.0213375f,0.287958f,0.12373f},{-0.0200505f,0.286735f,0.12429f}, +{-0.0183308f,0.283663f,0.123126f},{-0.018444f,0.283554f,0.122512f},{-0.0171015f,0.282437f,0.123063f}, +{-0.0169508f,0.282603f,0.123604f},{-0.0172584f,0.286839f,0.12559f},{-0.0177324f,0.286442f,0.125434f}, +{-0.0162253f,0.285687f,0.12559f},{-0.0171936f,0.282336f,0.122494f},{-0.0183693f,0.283407f,0.121909f}, +{-0.0172245f,0.282302f,0.121909f},{-0.0196183f,0.284863f,0.122512f},{-0.0194434f,0.284581f,0.121909f}, +{-0.0171072f,0.284839f,0.125161f},{-0.0175107f,0.284451f,0.124775f},{-0.0161913f,0.283441f,0.124927f}, +{-0.0201275f,0.288714f,0.125161f},{-0.0192063f,0.287348f,0.125161f},{-0.0187165f,0.287703f,0.125434f}, +{-0.0151117f,0.284631f,0.125592f},{-0.0178592f,0.284116f,0.12429f},{-0.0164907f,0.283111f,0.124546f}, +{-0.0232721f,0.292788f,0.12429f},{-0.0241699f,0.294302f,0.12373f},{-0.0236324f,0.292657f,0.12373f}, +{-0.0210122f,0.288161f,0.12429f},{-0.0222178f,0.294866f,0.125434f},{-0.0230652f,0.296296f,0.125232f}, +{-0.0227992f,0.294698f,0.125161f},{-0.0224512f,0.289346f,0.123126f},{-0.0225899f,0.289272f,0.122512f}, +{-0.0233369f,0.294543f,0.124775f},{-0.0228179f,0.292954f,0.124775f},{-0.0222922f,0.293146f,0.125161f}, +{-0.0229789f,0.291043f,0.12373f},{-0.0226285f,0.291199f,0.12429f},{-0.0218736f,0.289653f,0.12429f}, +{-0.0222123f,0.289473f,0.12373f},{-0.0219851f,0.29653f,0.125592f},{-0.0225398f,0.29641f,0.125455f}, +{-0.0216239f,0.295038f,0.12559f},{-0.0222011f,0.288471f,0.121909f},{-0.0233694f,0.290869f,0.122512f}, +{-0.0229536f,0.289873f,0.121909f},{-0.0240341f,0.29251f,0.122512f},{-0.0236177f,0.291319f,0.121909f}, +{-0.0241882f,0.292804f,0.121909f},{-0.0245807f,0.294183f,0.122512f},{-0.0246627f,0.294323f,0.121909f}, +{-0.0250554f,0.295865f,0.121909f},{-0.0250097f,0.295875f,0.122497f},{-0.0181357f,0.28385f,0.12373f}, +{-0.0194979f,0.284964f,0.123126f},{-0.023226f,0.290933f,0.123126f},{-0.0238866f,0.292564f,0.123126f}, +{-0.0244299f,0.294227f,0.123126f},{-0.024877f,0.295904f,0.123062f},{-0.0167454f,0.28283f,0.124102f}, +{-0.0192904f,0.285137f,0.12373f},{-0.0246594f,0.295951f,0.1236f},{-0.016671f,0.285259f,0.125434f}, +{-0.0158556f,0.283811f,0.125233f},{-0.0189963f,0.285384f,0.12429f},{-0.0221869f,0.291396f,0.124775f}, +{-0.0238014f,0.294408f,0.12429f},{-0.0243617f,0.296015f,0.124098f},{-0.0196592f,0.287019f,0.124775f}, +{-0.0186256f,0.285694f,0.124775f},{-0.0206021f,0.288418f,0.124775f},{-0.0214468f,0.28988f,0.124775f}, +{-0.0239879f,0.296096f,0.124546f},{-0.0181964f,0.286053f,0.125161f},{-0.0209526f,0.290143f,0.125161f}, +{-0.0216757f,0.291624f,0.125161f},{-0.0235519f,0.296191f,0.124927f},{-0.0154922f,0.284211f,0.125456f}, +{-0.0196142f,0.289035f,0.125434f},{-0.0204183f,0.290427f,0.125434f},{-0.0211229f,0.291871f,0.125434f}, +{-0.021143f,0.293566f,0.12559f},{-0.0217237f,0.293354f,0.125434f},{-0.0182162f,0.288066f,0.12559f}, +{-0.0190899f,0.289362f,0.12559f},{-0.0198725f,0.290718f,0.12559f},{-0.0205583f,0.292122f,0.12559f}, +{-0.0225908f,0.313303f,0.122512f},{-0.0232266f,0.311642f,0.123126f},{-0.0224522f,0.313229f,0.123126f}, +{-0.02337f,0.311706f,0.122512f},{-0.0229794f,0.311532f,0.12373f},{-0.0222133f,0.313102f,0.12373f}, +{-0.0226291f,0.311376f,0.12429f},{-0.0244299f,0.308351f,0.123126f},{-0.0245807f,0.308394f,0.122512f}, +{-0.024876f,0.306673f,0.123065f},{-0.0246584f,0.306626f,0.123602f},{-0.0211432f,0.30901f,0.12559f}, +{-0.0217239f,0.309222f,0.125434f},{-0.0216239f,0.307539f,0.12559f},{-0.0250097f,0.306702f,0.122497f}, +{-0.0240343f,0.310066f,0.122512f},{-0.0227992f,0.307879f,0.125161f},{-0.0233369f,0.308035f,0.124775f}, +{-0.0235497f,0.306386f,0.124929f},{-0.0209535f,0.312432f,0.125161f},{-0.0216762f,0.310951f,0.125161f}, +{-0.0211235f,0.310705f,0.125434f},{-0.0219851f,0.306047f,0.125592f},{-0.0238014f,0.308169f,0.12429f}, +{-0.0239879f,0.306481f,0.124546f},{-0.0189975f,0.317193f,0.12429f},{-0.0181357f,0.318727f,0.12373f}, +{-0.0192916f,0.317439f,0.12373f},{-0.0218746f,0.312922f,0.12429f},{-0.016671f,0.317318f,0.125434f}, +{-0.0158576f,0.318769f,0.125231f},{-0.0171072f,0.317738f,0.125161f},{-0.0215683f,0.31476f,0.123126f}, +{-0.0217015f,0.314844f,0.122512f},{-0.0175107f,0.318126f,0.124775f},{-0.0186268f,0.316882f,0.124775f}, +{-0.0181976f,0.316523f,0.125161f},{-0.0203623f,0.316066f,0.12373f},{-0.0200519f,0.315841f,0.12429f}, +{-0.0210134f,0.314414f,0.12429f},{-0.0213388f,0.314617f,0.12373f},{-0.0151117f,0.317946f,0.125592f}, +{-0.0154943f,0.318368f,0.125455f},{-0.0162253f,0.31689f,0.12559f},{-0.0207085f,0.316317f,0.122512f}, +{-0.0196196f,0.317713f,0.122512f},{-0.018444f,0.319023f,0.122512f},{-0.0171936f,0.320241f,0.122494f}, +{-0.0241699f,0.308275f,0.12373f},{-0.0238868f,0.310012f,0.123126f},{-0.0205814f,0.316225f,0.123126f}, +{-0.0194991f,0.317613f,0.123126f},{-0.0183308f,0.318914f,0.123126f},{-0.0171022f,0.320141f,0.12306f}, +{-0.02436f,0.306561f,0.1241f},{-0.0236326f,0.309919f,0.12373f},{-0.0169519f,0.319975f,0.123601f}, +{-0.0222178f,0.307711f,0.125434f},{-0.0230629f,0.306281f,0.125233f},{-0.0232723f,0.309787f,0.12429f}, +{-0.0196606f,0.315557f,0.124775f},{-0.0178592f,0.318461f,0.12429f},{-0.0167464f,0.319748f,0.1241f}, +{-0.0221874f,0.311179f,0.124775f},{-0.0228181f,0.309621f,0.124775f},{-0.0214477f,0.312695f,0.124775f}, +{-0.0206034f,0.314158f,0.124775f},{-0.0164907f,0.319467f,0.124546f},{-0.0222924f,0.309429f,0.125161f}, +{-0.0201286f,0.313861f,0.125161f},{-0.0192076f,0.315228f,0.125161f},{-0.0161924f,0.319138f,0.124925f}, +{-0.0225375f,0.306167f,0.125456f},{-0.0204192f,0.312148f,0.125434f},{-0.0196153f,0.313541f,0.125434f}, +{-0.0187178f,0.314873f,0.125434f},{-0.0172595f,0.315738f,0.12559f},{-0.0177335f,0.316134f,0.125434f}, +{-0.0205588f,0.310453f,0.12559f},{-0.0198733f,0.311858f,0.12559f},{-0.019091f,0.313213f,0.12559f}, +{-0.0182174f,0.314509f,0.12559f},{-0.000885136f,0.326703f,0.123126f},{-0.00261846f,0.326311f,0.12373f}, +{-0.000875717f,0.326433f,0.12373f},{-0.00441602f,0.326491f,0.122512f},{-0.00266296f,0.326736f,0.122512f}, +{-0.00257853f,0.32593f,0.12429f},{-0.00609912f,0.325976f,0.123126f},{-0.00613678f,0.326129f,0.122512f}, +{-0.0077748f,0.325524f,0.123065f},{-0.00781658f,0.325654f,0.122497f},{-0.00539858f,0.323141f,0.12559f}, +{-0.00388481f,0.32346f,0.12559f},{-0.00399151f,0.324069f,0.125434f},{-0.00749724f,0.324659f,0.124546f}, +{-0.00582624f,0.324872f,0.124775f},{-0.00594221f,0.325341f,0.12429f},{-0.00246996f,0.324892f,0.125161f}, +{-0.00240697f,0.32429f,0.125434f},{-0.000826054f,0.325007f,0.125161f},{-0.005692f,0.324329f,0.125161f}, +{-0.00736026f,0.324232f,0.124929f},{-0.000890602f,0.32686f,0.122512f},{-0.00264662f,0.32658f,0.123126f}, +{0.00427461f,0.325693f,0.12429f},{0.00603421f,0.325714f,0.12373f},{0.0043408f,0.326071f,0.12373f}, +{-0.00687127f,0.322708f,0.125592f},{0.000860185f,0.326049f,0.12429f},{0.00261652f,0.326312f,0.12373f}, +{0.000873503f,0.326433f,0.12373f},{-0.000862365f,0.326049f,0.12429f},{0.00582624f,0.324872f,0.124775f}, +{0.00419119f,0.325217f,0.124775f},{0.00409462f,0.324665f,0.125161f},{0.00554685f,0.323741f,0.125434f}, +{0.00720884f,0.32376f,0.125232f},{0.005692f,0.324329f,0.125161f},{0.00257663f,0.32593f,0.12429f}, +{0.00687127f,0.322708f,0.125592f},{0.00704464f,0.323248f,0.125455f},{0.00539858f,0.323141f,0.12559f}, +{0.00088835f,0.32686f,0.122512f},{0.000882898f,0.326703f,0.123126f},{0.002661f,0.326737f,0.122512f}, +{0.00441458f,0.326492f,0.122512f},{0.00613678f,0.326129f,0.122512f},{-0.00770679f,0.325312f,0.123602f}, +{-0.00603421f,0.325714f,0.12373f},{-0.00438891f,0.326337f,0.123126f},{0.00264467f,0.326581f,0.123126f}, +{0.00609912f,0.325976f,0.123126f},{0.00438748f,0.326337f,0.123126f},{0.00781658f,0.325654f,0.122497f}, +{0.0077751f,0.325525f,0.123062f},{-0.00761353f,0.325021f,0.1241f},{-0.00434221f,0.32607f,0.12373f}, +{0.00770709f,0.325313f,0.1236f},{-0.00554685f,0.323741f,0.125434f},{-0.00720812f,0.323758f,0.125233f}, +{-0.004276f,0.325692f,0.12429f},{0.00252634f,0.325449f,0.124775f},{0.00594221f,0.325341f,0.12429f}, +{0.00761404f,0.325023f,0.124098f},{-0.00252821f,0.325449f,0.124775f},{-0.00419255f,0.325216f,0.124775f}, +{-0.000845536f,0.325566f,0.124775f},{0.000843398f,0.325566f,0.124775f},{0.00749724f,0.324659f,0.124546f}, +{-0.00409595f,0.324665f,0.125161f},{0.000823965f,0.325007f,0.125161f},{0.00246814f,0.324892f,0.125161f}, +{0.00736095f,0.324234f,0.124927f},{-0.00704393f,0.323246f,0.125456f},{-0.000804989f,0.324402f,0.125434f}, +{0.000802953f,0.324402f,0.125434f},{0.0024052f,0.324291f,0.125434f},{0.00388354f,0.32346f,0.12559f}, +{0.00399021f,0.324069f,0.125434f},{-0.00234263f,0.323675f,0.12559f},{-0.00078347f,0.323784f,0.12559f}, +{0.000781489f,0.323784f,0.12559f},{0.0023409f,0.323676f,0.12559f},{0.0217002f,0.314846f,0.122512f}, +{0.02058f,0.316226f,0.123126f},{0.021567f,0.314762f,0.123126f},{0.0207071f,0.316319f,0.122512f}, +{0.020361f,0.316067f,0.12373f},{0.0213375f,0.314619f,0.12373f},{0.0200505f,0.315842f,0.12429f}, +{0.0183308f,0.318914f,0.123126f},{0.018444f,0.319023f,0.122512f},{0.0171012f,0.320139f,0.123065f}, +{0.0169516f,0.319975f,0.123602f},{0.0172584f,0.315738f,0.12559f},{0.0177324f,0.316135f,0.125434f}, +{0.0162253f,0.31689f,0.12559f},{0.0171931f,0.320241f,0.122497f},{0.0196183f,0.317714f,0.122512f}, +{0.0171072f,0.317738f,0.125161f},{0.0175107f,0.318126f,0.124775f},{0.0161894f,0.319134f,0.124929f}, +{0.0201275f,0.313863f,0.125161f},{0.0192063f,0.315229f,0.125161f},{0.0187165f,0.314874f,0.125434f}, +{0.0151138f,0.317949f,0.125592f},{0.0178592f,0.318461f,0.12429f},{0.0164907f,0.319467f,0.124546f}, +{0.0232721f,0.309789f,0.12429f},{0.0241699f,0.308275f,0.12373f},{0.0236324f,0.30992f,0.12373f}, +{0.0210122f,0.314416f,0.12429f},{0.0222178f,0.307711f,0.125434f},{0.0230652f,0.306281f,0.125232f}, +{0.0227992f,0.307879f,0.125161f},{0.0224512f,0.313231f,0.123126f},{0.0225899f,0.313305f,0.122512f}, +{0.0233369f,0.308035f,0.124775f},{0.0228179f,0.309623f,0.124775f},{0.0222922f,0.309431f,0.125161f}, +{0.0229789f,0.311534f,0.12373f},{0.0226285f,0.311378f,0.12429f},{0.0218736f,0.312924f,0.12429f}, +{0.0222123f,0.313104f,0.12373f},{0.0219851f,0.306047f,0.125592f},{0.0225398f,0.306167f,0.125455f}, +{0.0216239f,0.307539f,0.12559f},{0.0233694f,0.311708f,0.122512f},{0.0240341f,0.310067f,0.122512f}, +{0.0245807f,0.308394f,0.122512f},{0.0250097f,0.306702f,0.122497f},{0.0181357f,0.318727f,0.12373f}, +{0.0194979f,0.317614f,0.123126f},{0.023226f,0.311644f,0.123126f},{0.0238866f,0.310013f,0.123126f}, +{0.0244299f,0.308351f,0.123126f},{0.024877f,0.306673f,0.123062f},{0.0167465f,0.319748f,0.1241f}, +{0.0192904f,0.31744f,0.12373f},{0.0246594f,0.306626f,0.1236f},{0.016671f,0.317318f,0.125434f}, +{0.0158548f,0.318766f,0.125233f},{0.0189963f,0.317194f,0.12429f},{0.0221869f,0.311181f,0.124775f}, +{0.0238014f,0.308169f,0.12429f},{0.0243617f,0.306562f,0.124098f},{0.0196592f,0.315558f,0.124775f}, +{0.0186256f,0.316883f,0.124775f},{0.0206021f,0.31416f,0.124775f},{0.0214468f,0.312697f,0.124775f}, +{0.0239879f,0.306481f,0.124546f},{0.0181964f,0.316524f,0.125161f},{0.0209526f,0.312434f,0.125161f}, +{0.0216757f,0.310953f,0.125161f},{0.0235519f,0.306387f,0.124927f},{0.0154936f,0.318367f,0.125456f}, +{0.0196142f,0.313542f,0.125434f},{0.0204183f,0.31215f,0.125434f},{0.0211229f,0.310707f,0.125434f}, +{0.021143f,0.309011f,0.12559f},{0.0217237f,0.309223f,0.125434f},{0.0182162f,0.314511f,0.12559f}, +{0.0190899f,0.313215f,0.12559f},{0.0198725f,0.31186f,0.12559f},{0.0205583f,0.310455f,0.12559f}, +{0.00414391f,0.295088f,0.100469f},{0.00139737f,0.298869f,0.100469f},{0.00179665f,0.299148f,0.100469f}, +{0.00285439f,0.294399f,0.100469f},{0.00351607f,0.294712f,0.100469f},{0.00216513f,0.294152f,0.100469f}, +{0.000956049f,0.298662f,0.100469f},{0.0047319f,0.295524f,0.100469f},{0.00527427f,0.296015f,0.100469f}, +{0.00145499f,0.293974f,0.100469f},{0.000485772f,0.298534f,0.100469f},{0.00214182f,0.299492f,0.100469f}, +{0.00576579f,0.296558f,0.100469f},{0.000730938f,0.293867f,0.100469f},{-2.55116e-017f,0.298492f,0.100469f}, +{0.00620174f,0.297145f,0.100469f},{0.00242194f,0.299891f,0.100469f},{-2.64948e-017f,0.293831f,0.100469f}, +{-0.000731236f,0.293867f,0.100469f},{-0.00145532f,0.293975f,0.100469f},{-0.000485107f,0.298534f,0.100469f}, +{-0.00216527f,0.294153f,0.100469f},{-0.000955564f,0.29866f,0.100469f},{0.00689072f,0.298435f,0.100469f}, +{0.00657793f,0.297773f,0.100469f},{-0.00351606f,0.294712f,0.100469f},{-0.00285433f,0.294399f,0.100469f}, +{0.00713697f,0.299124f,0.100469f},{0.00262754f,0.300333f,0.100469f},{0.00275363f,0.300804f,0.100469f}, +{-0.00139499f,0.298869f,0.100469f},{0.00742217f,0.300558f,0.100469f},{0.00731456f,0.299834f,0.100469f}, +{-0.00214373f,0.299488f,0.100469f},{-0.00178917f,0.299157f,0.100469f},{-0.00527358f,0.296016f,0.100469f}, +{-0.00657692f,0.297774f,0.100469f},{-0.00688983f,0.298435f,0.100469f},{-0.00262887f,0.300331f,0.100469f}, +{-0.00275512f,0.300803f,0.100469f},{-0.00742136f,0.300558f,0.100469f},{-0.0071365f,0.299124f,0.100469f}, +{-0.00731416f,0.299834f,0.100469f},{-0.00473148f,0.295525f,0.100469f},{-0.00414378f,0.295088f,0.100469f}, +{-0.00620074f,0.297146f,0.100469f},{-0.00242212f,0.29989f,0.100469f},{-0.0057649f,0.296559f,0.100469f}, +{0.00060826f,0.31345f,0.101401f},{0.00178435f,0.313762f,0.101401f},{0.002331f,0.314032f,0.101401f}, +{0.00216527f,0.294153f,0.101401f},{0.00536018f,0.290568f,0.101401f},{0.00742136f,0.300558f,0.101401f}, +{0.0121618f,0.30068f,0.101401f},{0.0071365f,0.299124f,0.101401f},{0.0127432f,0.298958f,0.101401f}, +{0.00688983f,0.298435f,0.101401f},{0.00403701f,0.315738f,0.101401f},{0.00430572f,0.319852f,0.101401f}, +{0.014297f,0.288187f,0.101401f},{-0.00279832f,0.322545f,0.101401f},{0.0214014f,0.30068f,0.101401f}, +{-0.00689197f,0.321591f,0.101401f},{-0.00820481f,0.321097f,0.101401f},{0.021279f,0.300083f,0.101401f}, +{0.0210836f,0.299506f,0.101401f},{0.0134836f,0.297992f,0.101401f},{0.00657692f,0.297774f,0.101401f}, +{0.0130817f,0.298451f,0.101401f},{-0.00893219f,0.289809f,0.101401f},{-0.00372602f,0.28731f,0.101401f}, +{-0.00406291f,0.286794f,0.101401f},{0.0208166f,0.298958f,0.101401f},{0.0200754f,0.297993f,0.101401f}, +{0.0204775f,0.298452f,0.101401f},{0.0196172f,0.297591f,0.101401f},{0.0139105f,0.290011f,0.101401f}, +{0.0141391f,0.289696f,0.101401f},{-0.00216513f,0.294152f,0.101401f},{-0.00235358f,0.288532f,0.101401f}, +{-0.00285439f,0.294399f,0.101401f},{0.0191105f,0.297253f,0.101401f},{0.0185639f,0.296983f,0.101401f}, +{0.0167797f,0.296628f,0.101401f},{0.0173884f,0.296667f,0.101401f},{0.0179866f,0.296787f,0.101401f}, +{-0.0141364f,0.317409f,0.101401f},{-0.00948265f,0.320518f,0.101401f},{-0.00121835f,0.289001f,0.101401f}, +{-0.00145499f,0.293974f,0.101401f},{-0.000730938f,0.293867f,0.101401f},{0.0161715f,0.296667f,0.101401f}, +{-0.00180244f,0.288807f,0.101401f},{0.00620074f,0.297146f,0.101401f},{-0.00286368f,0.288187f,0.101401f}, +{0.0143784f,0.288958f,0.101401f},{-0.0107514f,0.313236f,0.101401f},{-0.0109097f,0.31288f,0.101401f}, +{-0.00140229f,0.322684f,0.101401f},{0.00329545f,0.321364f,0.101401f},{0.00369728f,0.320906f,0.101401f}, +{0.0057649f,0.296559f,0.101401f},{0.00466102f,0.318068f,0.101401f},{0.00462104f,0.318677f,0.101401f}, +{0.00731416f,0.299834f,0.101401f},{0.0124736f,0.299504f,0.101401f},{0.0121612f,0.310903f,0.101401f}, +{0.0109346f,0.310012f,0.101401f},{0.0113045f,0.310132f,0.101401f},{0.0123195f,0.311258f,0.101401f}, +{0.0116418f,0.310326f,0.101401f},{0.0119314f,0.310587f,0.101401f},{0.0136206f,0.290272f,0.101401f}, +{0.0136193f,0.287256f,0.101401f},{0.013282f,0.287061f,0.101401f},{0.013283f,0.290467f,0.101401f}, +{0.0155736f,0.296786f,0.101401f},{0.00473148f,0.295525f,0.101401f},{0.00527358f,0.296016f,0.101401f}, +{-0.0170097f,0.314341f,0.101401f},{-0.00751912f,0.281209f,0.101401f},{-0.00885348f,0.281761f,0.101401f}, +{-0.00460913f,0.283816f,0.101401f},{0.00285433f,0.294399f,0.101401f},{0.00351606f,0.294712f,0.101401f}, +{0.000731236f,0.293867f,0.101401f},{0.00145532f,0.293975f,0.101401f},{-0.0151604f,0.31645f,0.101401f}, +{-0.0161195f,0.315426f,0.101401f},{-0.0124736f,0.303073f,0.101401f},{-0.0122844f,0.302494f,0.101401f}, +{-2.64948e-017f,0.293831f,0.101401f},{-0.0043287f,0.286238f,0.101401f},{-0.00916198f,0.289494f,0.101401f}, +{-0.0107204f,0.306649f,0.101401f},{-0.00869272f,0.290546f,0.101401f},{-0.00332386f,0.287777f,0.101401f}, +{-0.017827f,0.313201f,0.101401f},{-0.00731456f,0.299834f,0.101401f},{-0.00713697f,0.299124f,0.101401f}, +{-0.00742217f,0.300558f,0.101401f},{-0.0196172f,0.304986f,0.101401f},{-0.0200754f,0.304584f,0.101401f}, +{-0.0210285f,0.305472f,0.101401f},{-0.0158194f,0.286816f,0.101401f},{-0.0167576f,0.287913f,0.101401f}, +{-0.0176198f,0.289072f,0.101401f},{-0.00462997f,0.285046f,0.101401f},{-0.0101477f,0.282401f,0.101401f}, +{-0.0125926f,0.283935f,0.101401f},{-0.013732f,0.284822f,0.101401f},{-0.00466034f,0.28443f,0.101401f}, +{-0.00426727f,0.282635f,0.101401f},{-0.00615062f,0.280749f,0.101401f},{-0.00447731f,0.283214f,0.101401f}, +{-0.00165506f,0.280155f,0.101401f},{-0.00190339f,0.27993f,0.101401f},{-0.0022162f,0.280408f,0.101401f}, +{-0.00362862f,0.281584f,0.101401f},{-0.00475417f,0.280381f,0.101401f},{-0.00398274f,0.282088f,0.101401f}, +{-0.00321095f,0.281131f,0.101401f},{-0.00273734f,0.280737f,0.101401f},{-0.00333373f,0.280122f,0.101401f}, +{-0.00106651f,0.279974f,0.101401f},{-0.000459362f,0.27987f,0.101401f},{-0.0101588f,0.288918f,0.101401f}, +{-0.011396f,0.283127f,0.101401f},{-0.0148092f,0.285784f,0.101401f},{-0.0184021f,0.290285f,0.101401f}, +{-0.0212465f,0.298409f,0.101401f},{-0.0210045f,0.296985f,0.101401f},{-0.0206672f,0.295581f,0.101401f}, +{0.0122844f,0.300083f,0.101401f},{-0.0047319f,0.295524f,0.101401f},{-0.00893177f,0.291673f,0.101401f}, +{-0.00916039f,0.291988f,0.101401f},{-0.019101f,0.291549f,0.101401f},{-0.00978889f,0.289038f,0.101401f}, +{-0.0213921f,0.299845f,0.101401f},{-0.0111395f,0.312564f,0.101401f},{-0.0114291f,0.312304f,0.101401f}, +{-0.00576579f,0.296558f,0.101401f},{-0.00527427f,0.296015f,0.101401f},{-0.00945026f,0.29225f,0.101401f}, +{-0.00978794f,0.292445f,0.101401f},{-0.0101578f,0.292565f,0.101401f},{-0.00620174f,0.297145f,0.101401f}, +{-0.00877329f,0.291317f,0.101401f},{-0.00414391f,0.295088f,0.101401f},{-0.00351607f,0.294712f,0.101401f}, +{-0.0045188f,0.285652f,0.101401f},{-0.0094516f,0.289233f,0.101401f},{-0.000614697f,0.289126f,0.101401f}, +{0.0139422f,0.29759f,0.101401f},{0.00414378f,0.295088f,0.101401f},{0.0144494f,0.297252f,0.101401f}, +{0.0124009f,0.312029f,0.101401f},{0.011933f,0.313082f,0.101401f},{0.00430656f,0.316285f,0.101401f}, +{0.00178272f,0.322372f,0.101401f},{-0.00418236f,0.322315f,0.101401f},{-0.0106702f,0.313617f,0.101401f}, +{-0.00554911f,0.321998f,0.101401f},{-0.0130817f,0.304126f,0.101401f},{-0.0134836f,0.304585f,0.101401f}, +{-0.013052f,0.318299f,0.101401f},{-0.0185679f,0.312009f,0.101401f},{-0.0203026f,0.308181f,0.101401f}, +{-0.0185639f,0.305594f,0.101401f},{-0.0207099f,0.306838f,0.101401f},{-0.00689072f,0.298435f,0.101401f}, +{-0.0119116f,0.319116f,0.101401f},{-0.0117654f,0.315516f,0.101401f},{-0.0121353f,0.315636f,0.101401f}, +{-0.0192293f,0.310772f,0.101401f},{-0.0149963f,0.305595f,0.101401f},{-0.0121618f,0.301897f,0.101401f}, +{-0.0109093f,0.314744f,0.101401f},{-0.0111379f,0.315059f,0.101401f},{-0.0106699f,0.314007f,0.101401f}, +{-0.01072f,0.319857f,0.101401f},{-0.0114278f,0.315321f,0.101401f},{0.00120563f,0.313573f,0.101401f}, +{0.0116431f,0.313343f,0.101401f},{0.0113054f,0.313538f,0.101401f},{0.0124007f,0.311639f,0.101401f}, +{0.00462115f,0.31746f,0.101401f},{0.00283787f,0.31437f,0.101401f},{0.00329614f,0.314772f,0.101401f}, +{0.00369829f,0.315231f,0.101401f},{0.0123201f,0.312411f,0.101401f},{0.0121616f,0.312767f,0.101401f}, +{0.0109356f,0.313659f,0.101401f},{0.0149963f,0.296982f,0.101401f},{0.0129131f,0.290588f,0.101401f}, +{0.0129121f,0.286941f,0.101401f},{0.0139089f,0.287516f,0.101401f},{0.0141387f,0.287832f,0.101401f}, +{0.0143782f,0.288568f,0.101401f},{0.0142976f,0.28934f,0.101401f},{-0.0202361f,0.294203f,0.101401f}, +{-0.0197133f,0.292857f,0.101401f},{-0.00869244f,0.290936f,0.101401f},{-0.00877392f,0.290165f,0.101401f}, +{-0.00657793f,0.297773f,0.101401f},{-0.0107508f,0.314388f,0.101401f},{0.00450236f,0.316862f,0.101401f}, +{0.00450189f,0.319275f,0.101401f},{0.00403597f,0.320399f,0.101401f},{0.00283697f,0.321766f,0.101401f}, +{0.00233026f,0.322105f,0.101401f},{0.0006084f,0.32269f,0.101401f},{0.00120559f,0.322568f,0.101401f}, +{-0.0210836f,0.303071f,0.101401f},{-0.0213948f,0.302691f,0.101401f},{-0.0212572f,0.304087f,0.101401f}, +{-0.0198084f,0.309494f,0.101401f},{-0.0167797f,0.30595f,0.101401f},{-0.0173884f,0.30591f,0.101401f}, +{-0.0161715f,0.30591f,0.101401f},{-0.0127432f,0.30362f,0.101401f},{-0.0155736f,0.305791f,0.101401f}, +{-0.0139422f,0.304987f,0.101401f},{-0.0144494f,0.305326f,0.101401f},{-0.0121363f,0.311989f,0.101401f}, +{-0.0117664f,0.312109f,0.101401f},{-0.0179866f,0.30579f,0.101401f},{-0.0191105f,0.305324f,0.101401f}, +{-0.0204775f,0.304126f,0.101401f},{-0.0208166f,0.303619f,0.101401f},{-0.0214014f,0.301897f,0.101401f}, +{-0.021279f,0.302494f,0.101401f},{0.0220868f,0.288274f,0.120045f},{0.0197356f,0.284927f,0.120045f}, +{-0.0164263f,0.321574f,0.120045f},{-0.0174654f,0.320686f,0.120045f},{0.0227481f,0.289468f,0.120045f}, +{-0.0130507f,0.323894f,0.120045f},{-0.0142159f,0.32318f,0.120045f},{0.0243386f,0.293237f,0.120045f}, +{-0.00935393f,0.325657f,0.120045f},{-0.0106164f,0.325134f,0.120045f},{0.0253094f,0.297211f,0.120045f}, +{-0.00542685f,0.32682f,0.120045f},{-0.00408328f,0.327069f,0.120045f},{-0.0067556f,0.326501f,0.120045f}, +{-0.00806585f,0.326113f,0.120045f},{-0.00136583f,0.327346f,0.120045f},{-0.00272847f,0.327247f,0.120045f}, +{0.025591f,0.299924f,0.120045f},{0.0254905f,0.298564f,0.120045f},{-0.0118498f,0.324546f,0.120045f}, +{0.0247326f,0.294544f,0.120045f},{0.0250564f,0.29587f,0.120045f},{-0.0153421f,0.322406f,0.120045f}, +{0.0233448f,0.290696f,0.120045f},{0.0238755f,0.291953f,0.120045f},{-0.0184567f,0.319746f,0.120045f}, +{-0.0193973f,0.318754f,0.120045f},{0.0213629f,0.287117f,0.120045f},{-0.0202847f,0.317715f,0.120045f}, +{-0.0211166f,0.316631f,0.120045f},{-0.0218906f,0.315505f,0.120045f},{0.0205784f,0.286f,0.120045f}, +{-0.0226048f,0.31434f,0.120045f},{-0.0232569f,0.313139f,0.120045f},{0.0188369f,0.2839f,0.120045f}, +{-0.0238452f,0.311905f,0.120045f},{0.0178847f,0.282922f,0.120045f},{-0.0243681f,0.310643f,0.120045f}, +{0.0168818f,0.281996f,0.120045f},{-0.0248242f,0.309355f,0.120045f},{0.0158311f,0.281125f,0.120045f}, +{-0.0252123f,0.308044f,0.120045f},{0.0147355f,0.280311f,0.120045f},{-0.0255314f,0.306715f,0.120045f}, +{0.0135981f,0.279557f,0.120045f},{-0.0257804f,0.305372f,0.120045f},{0.0124222f,0.278863f,0.120045f}, +{-0.0259588f,0.304017f,0.120045f},{0.011211f,0.278234f,0.120045f},{-0.0260659f,0.302655f,0.120045f}, +{0.00996802f,0.27767f,0.120045f},{-0.0261017f,0.301289f,0.120045f},{0.00869678f,0.277173f,0.120045f}, +{-0.0255903f,0.299924f,0.120045f},{-0.0260659f,0.299922f,0.120045f},{0.00740092f,0.276744f,0.120045f}, +{-0.0254908f,0.298564f,0.120045f},{-0.0259586f,0.29856f,0.120045f},{0.00608407f,0.276385f,0.120045f}, +{-0.0253091f,0.297211f,0.120045f},{-0.0257802f,0.297205f,0.120045f},{0.00474994f,0.276097f,0.120045f}, +{0.00340235f,0.27588f,0.120045f},{0.000682229f,0.275662f,0.120045f},{-0.0250563f,0.29587f,0.120045f}, +{-0.0255311f,0.295861f,0.120045f},{-0.00272834f,0.27533f,0.120045f},{-0.00340291f,0.27588f,0.120045f}, +{-0.00408304f,0.275508f,0.120045f},{-0.0238754f,0.291954f,0.120045f},{-0.0243383f,0.293238f,0.120045f}, +{-0.0243677f,0.291934f,0.120045f},{-0.00675524f,0.276076f,0.120045f},{-0.00740123f,0.276745f,0.120045f}, +{-0.00806539f,0.276464f,0.120045f},{-0.0226042f,0.288237f,0.120045f},{-0.0227481f,0.289469f,0.120045f}, +{-0.0232562f,0.289438f,0.120045f},{-0.0118493f,0.278031f,0.120045f},{-0.010616f,0.277443f,0.120045f}, +{-0.011211f,0.278235f,0.120045f},{-0.0202843f,0.284862f,0.120045f},{-0.0205783f,0.286001f,0.120045f}, +{-0.0211162f,0.285946f,0.120045f},{-0.0164256f,0.281003f,0.120045f},{-0.0168818f,0.281997f,0.120045f}, +{-0.0174647f,0.281891f,0.120045f},{-0.0130502f,0.278684f,0.120045f},{-0.0124221f,0.278864f,0.120045f}, +{-0.0188368f,0.2839f,0.120045f},{-0.0193967f,0.283823f,0.120045f},{-0.018456f,0.282831f,0.120045f}, +{-0.0178847f,0.282922f,0.120045f},{-0.0153414f,0.280172f,0.120045f},{-0.0142153f,0.279398f,0.120045f}, +{-0.0147355f,0.280311f,0.120045f},{-0.0135981f,0.279557f,0.120045f},{-0.0197355f,0.284928f,0.120045f}, +{-0.0158312f,0.281125f,0.120045f},{-0.00869705f,0.277173f,0.120045f},{-0.00935349f,0.27692f,0.120045f}, +{-0.00996818f,0.277671f,0.120045f},{-0.0220867f,0.288275f,0.120045f},{-0.0218902f,0.287072f,0.120045f}, +{-0.0213628f,0.287118f,0.120045f},{-0.00475041f,0.276097f,0.120045f},{-0.00542662f,0.275757f,0.120045f}, +{-0.00608443f,0.276386f,0.120045f},{-0.0233449f,0.290696f,0.120045f},{-0.0238446f,0.290671f,0.120045f}, +{-0.000682695f,0.275662f,0.120045f},{-0.00136576f,0.275232f,0.120045f},{-0.00204572f,0.275735f,0.120045f}, +{-0.0252122f,0.294532f,0.120045f},{-0.0247324f,0.294544f,0.120045f},{-0.024824f,0.293222f,0.120045f}, +{0.00204515f,0.275735f,0.120045f},{-0.00544975f,0.275762f,0.106062f},{-0.00410773f,0.275512f,0.106062f}, +{-0.00275036f,0.275332f,0.106062f},{-0.00935782f,0.276922f,0.106062f},{-0.00677384f,0.276081f,0.106062f}, +{-0.0141962f,0.279385f,0.106062f},{-0.0130343f,0.278674f,0.106062f},{-0.0118389f,0.278026f,0.106062f}, +{-0.0106125f,0.277442f,0.106062f},{-0.0174549f,0.281882f,0.106062f},{-0.015322f,0.280157f,0.106062f}, +{-0.0211314f,0.285966f,0.106062f},{-0.0202988f,0.284879f,0.106062f},{-0.0194069f,0.283834f,0.106062f}, +{-0.0184567f,0.282832f,0.106062f},{-0.0232623f,0.289449f,0.106062f},{-0.0219036f,0.287092f,0.106062f}, +{-0.0252074f,0.294514f,0.106062f},{-0.0248204f,0.293211f,0.106062f},{-0.0243664f,0.29193f,0.106062f}, +{-0.0238467f,0.290676f,0.106062f},{-0.0257765f,0.297181f,0.106062f},{-0.0259565f,0.298538f,0.106062f}, +{-0.0255265f,0.295839f,0.106062f},{-0.0260653f,0.302669f,0.106062f},{-0.0261017f,0.301289f,0.106062f}, +{-0.0260652f,0.299908f,0.106062f},{-0.0255265f,0.306738f,0.106062f},{-0.0257766f,0.305396f,0.106062f}, +{-0.0259565f,0.304039f,0.106062f},{-0.0248205f,0.309366f,0.106062f},{-0.0252075f,0.308062f,0.106062f}, +{-0.0238468f,0.311901f,0.106062f},{-0.0232624f,0.313127f,0.106062f},{-0.0243666f,0.310646f,0.106062f}, +{-0.0219036f,0.315485f,0.106062f},{-0.0226143f,0.314323f,0.106062f},{-0.0202989f,0.317698f,0.106062f}, +{-0.0211315f,0.316611f,0.106062f},{-0.0184567f,0.319745f,0.106062f},{-0.0194069f,0.318743f,0.106062f}, +{-0.0174549f,0.320695f,0.106062f},{-0.0164092f,0.321587f,0.106062f},{-0.0153222f,0.32242f,0.106062f}, +{-0.0141964f,0.323192f,0.106062f},{-0.0130346f,0.323903f,0.106062f},{-0.0118391f,0.324551f,0.106062f}, +{-0.0106128f,0.325135f,0.106062f},{-0.00935809f,0.325655f,0.106062f},{-0.00807765f,0.326109f,0.106062f}, +{-0.00677408f,0.326496f,0.106062f},{-0.00544996f,0.326815f,0.106062f},{-0.0041079f,0.327065f,0.106062f}, +{-0.00275048f,0.327245f,0.106062f},{-0.00138032f,0.327354f,0.106062f},{-0.0226142f,0.288254f,0.106062f}, +{-0.0164091f,0.28099f,0.106062f},{-0.0080774f,0.276468f,0.106062f},{-0.00138025f,0.275223f,0.106062f}, +{-0.0164242f,0.287507f,0.106062f},{-0.0128032f,0.28409f,0.106062f},{-0.00849194f,0.281601f,0.106062f}, +{-0.00372282f,0.280175f,0.106062f},{-0.00124674f,0.279884f,0.106062f},{-0.00248901f,0.279994f,0.106062f}, +{-0.00733302f,0.281141f,0.106062f},{-0.00962222f,0.282129f,0.106062f},{-0.01072f,0.28272f,0.106062f}, +{-0.0117816f,0.283375f,0.106062f},{-0.0155951f,0.286575f,0.106062f},{-0.0147132f,0.285693f,0.106062f}, +{-0.0137815f,0.284864f,0.106062f},{-0.0185679f,0.290568f,0.106062f},{-0.0179131f,0.289506f,0.106062f}, +{-0.0171977f,0.288485f,0.106062f},{-0.0191599f,0.291666f,0.106062f},{-0.0196869f,0.292796f,0.106062f}, +{-0.0201474f,0.293955f,0.106062f},{-0.0205397f,0.295139f,0.106062f},{-0.0208625f,0.296344f,0.106062f}, +{-0.0211148f,0.297565f,0.106062f},{-0.0212956f,0.298799f,0.106062f},{-0.0214044f,0.300042f,0.106062f}, +{-0.0214407f,0.301289f,0.106062f},{-0.0214044f,0.302535f,0.106062f},{-0.0212958f,0.303778f,0.106062f}, +{-0.021115f,0.305012f,0.106062f},{-0.0208629f,0.306233f,0.106062f},{-0.0205401f,0.307438f,0.106062f}, +{-0.0201478f,0.308622f,0.106062f},{-0.0196872f,0.309781f,0.106062f},{-0.0185682f,0.312009f,0.106062f}, +{-0.00248899f,0.322581f,0.106062f},{-0.00124708f,0.322694f,0.106062f},{-0.0164246f,0.315071f,0.106062f}, +{-0.00494506f,0.322151f,0.106062f},{-0.00614966f,0.321828f,0.106062f},{-0.0137818f,0.317713f,0.106062f}, +{-0.0147135f,0.316884f,0.106062f},{-0.0107205f,0.319857f,0.106062f},{-0.0117819f,0.319202f,0.106062f}, +{-0.0128035f,0.318487f,0.106062f},{-0.00849255f,0.320976f,0.106062f},{-0.00733349f,0.321436f,0.106062f}, +{-0.00962282f,0.320449f,0.106062f},{-0.00372197f,0.322394f,0.106062f},{-0.0155954f,0.316002f,0.106062f}, +{-0.0179135f,0.313071f,0.106062f},{-0.0171982f,0.314092f,0.106062f},{-0.0191601f,0.310911f,0.106062f}, +{-0.00494408f,0.280428f,0.106062f},{-0.00614928f,0.280748f,0.106062f},{-0.00496191f,0.28043f,0.10513f}, +{-0.00374312f,0.280177f,0.10513f},{-0.00250793f,0.279995f,0.10513f},{-0.00849036f,0.281601f,0.10513f}, +{-0.00616138f,0.280752f,0.10513f},{-0.0127873f,0.284078f,0.10513f},{-0.0117655f,0.283364f,0.10513f}, +{-0.0107068f,0.282713f,0.10513f},{-0.00961408f,0.282124f,0.10513f},{-0.0155998f,0.28658f,0.10513f}, +{-0.0137691f,0.284853f,0.10513f},{-0.018576f,0.290582f,0.10513f},{-0.0179242f,0.289523f,0.10513f}, +{-0.0172102f,0.288501f,0.10513f},{-0.0201457f,0.29395f,0.10513f},{-0.0196879f,0.292798f,0.10513f}, +{-0.0191643f,0.291674f,0.10513f},{-0.0212935f,0.29878f,0.10513f},{-0.0211114f,0.297545f,0.10513f}, +{-0.0208586f,0.296326f,0.10513f},{-0.0205363f,0.295127f,0.10513f},{-0.0214407f,0.301289f,0.10513f}, +{-0.0214037f,0.302548f,0.10513f},{-0.0214037f,0.300029f,0.10513f},{-0.0211115f,0.305032f,0.10513f}, +{-0.0212936f,0.303796f,0.10513f},{-0.0201457f,0.308627f,0.10513f},{-0.0205363f,0.30745f,0.10513f}, +{-0.0208587f,0.30625f,0.10513f},{-0.0191643f,0.310903f,0.10513f},{-0.019688f,0.309779f,0.10513f}, +{-0.0172102f,0.314076f,0.10513f},{-0.0179243f,0.313054f,0.10513f},{-0.018576f,0.311995f,0.10513f}, +{-0.0156004f,0.315997f,0.10513f},{-0.0164352f,0.315058f,0.10513f},{-0.0147088f,0.316888f,0.10513f}, +{-0.0137693f,0.317724f,0.10513f},{-0.0127873f,0.318499f,0.10513f},{-0.0117656f,0.319213f,0.10513f}, +{-0.010707f,0.319865f,0.10513f},{-0.0096143f,0.320453f,0.10513f},{-0.00849054f,0.320976f,0.10513f}, +{-0.00733859f,0.321434f,0.10513f},{-0.00616144f,0.321825f,0.10513f},{-0.00374334f,0.3224f,0.10513f}, +{-0.00496208f,0.322147f,0.10513f},{-0.00250813f,0.322582f,0.10513f},{-0.00125938f,0.322692f,0.10513f}, +{-0.0164352f,0.287519f,0.10513f},{-0.0147082f,0.285688f,0.10513f},{-0.0073385f,0.281143f,0.10513f}, +{-0.00125925f,0.279885f,0.10513f},{-0.015889f,0.28058f,0.10513f},{-0.0261017f,0.301289f,0.10513f}, +{-0.0260458f,0.299581f,0.10513f},{-0.0241144f,0.291299f,0.10513f},{-0.0256f,0.296196f,0.10513f}, +{-0.0252122f,0.294532f,0.10513f},{-0.0234094f,0.289744f,0.10513f},{-0.0217023f,0.286787f,0.10513f}, +{-0.0207075f,0.285398f,0.10513f},{-0.00675524f,0.276076f,0.10513f},{-0.00509193f,0.275688f,0.10513f}, +{-0.00170673f,0.275251f,0.10513f},{-0.0130502f,0.278684f,0.10513f},{-0.011544f,0.277878f,0.10513f}, +{-0.00998811f,0.277174f,0.10513f},{-0.00838954f,0.276572f,0.10513f},{-0.0145006f,0.279585f,0.10513f}, +{-0.018456f,0.282831f,0.10513f},{-0.0172093f,0.281664f,0.10513f},{-0.00340673f,0.275409f,0.10513f}, +{-0.0196237f,0.284078f,0.10513f},{-0.0226042f,0.288237f,0.10513f},{-0.0247162f,0.292898f,0.10513f}, +{-0.0258783f,0.297881f,0.10513f},{-0.0260458f,0.302996f,0.10513f},{-0.0258785f,0.304695f,0.10513f}, +{-0.0247166f,0.309679f,0.10513f},{-0.0252123f,0.308044f,0.10513f},{-0.0256002f,0.306381f,0.10513f}, +{-0.024115f,0.311277f,0.10513f},{-0.02341f,0.312833f,0.10513f},{-0.0226048f,0.31434f,0.10513f}, +{-0.0207077f,0.317179f,0.10513f},{-0.0217027f,0.31579f,0.10513f},{-0.0196242f,0.318499f,0.10513f}, +{-0.01721f,0.320913f,0.10513f},{-0.0145012f,0.322992f,0.10513f},{-0.0158895f,0.321997f,0.10513f}, +{-0.0130507f,0.323894f,0.10513f},{-0.0115442f,0.324699f,0.10513f},{-0.00340717f,0.327167f,0.10513f}, +{-0.00170718f,0.327329f,0.10513f},{-0.00509216f,0.326889f,0.10513f},{-0.0067556f,0.326501f,0.10513f}, +{-0.00839014f,0.326005f,0.10513f},{-0.0184567f,0.319746f,0.10513f},{-0.00998851f,0.325404f,0.10513f}, +{-0.0114195f,0.321068f,0.10252f},{-0.0131871f,0.319936f,0.10252f},{-0.0123517f,0.322682f,0.104011f}, +{-0.0179085f,0.315462f,0.10252f},{-0.0164595f,0.317122f,0.10252f},{-0.0148769f,0.318617f,0.10252f}, +{-0.0224459f,0.305508f,0.10252f},{-0.0219419f,0.307627f,0.10252f},{-0.0212291f,0.309712f,0.10252f}, +{-0.022839f,0.301289f,0.10252f},{-0.0227427f,0.303387f,0.10252f},{-0.0123517f,0.279895f,0.104011f}, +{-0.0114195f,0.281509f,0.10252f},{-0.0101514f,0.28083f,0.10252f},{-0.00882321f,0.280223f,0.10252f}, +{-0.00744093f,0.279696f,0.10252f},{-0.00601179f,0.279255f,0.10252f},{-0.00454389f,0.278906f,0.10252f}, +{-0.00304618f,0.278654f,0.10252f},{-0.00152821f,0.278501f,0.10252f},{-0.00650255f,0.277456f,0.104011f}, +{-0.00491482f,0.277079f,0.104011f},{-0.0109801f,0.279159f,0.104011f},{-0.00329485f,0.276806f,0.104011f}, +{-0.00165296f,0.276641f,0.104011f},{-0.00804836f,0.277933f,0.104011f},{-0.00954347f,0.278503f,0.104011f}, +{-0.0191994f,0.313658f,0.10252f},{-0.0203114f,0.311732f,0.10252f},{-0.0160918f,0.320032f,0.104011f}, +{-0.0247034f,0.301289f,0.104011f},{-0.0245988f,0.303557f,0.104011f},{-0.0242781f,0.305852f,0.104011f}, +{-0.0237331f,0.308143f,0.104011f},{-0.0229622f,0.310398f,0.104011f},{-0.02197f,0.312584f,0.104011f}, +{-0.0207674f,0.314667f,0.104011f},{-0.0193711f,0.316619f,0.104011f},{-0.0178041f,0.318414f,0.104011f}, +{-0.0142649f,0.321457f,0.104011f},{0.0255992f,0.299923f,0.121909f},{0.0254901f,0.298561f,0.121909f}, +{0.0137506f,0.279653f,0.121909f},{0.0155417f,0.280901f,0.121909f},{0.0118616f,0.278562f,0.121909f}, +{0.00988475f,0.277635f,0.121909f},{-0.00988506f,0.277635f,0.121909f},{-0.0118618f,0.278562f,0.121909f}, +{-0.015542f,0.280901f,0.121909f},{-0.0137508f,0.279653f,0.121909f},{-0.0253087f,0.297208f,0.121909f}, +{-0.0254902f,0.298561f,0.121909f},{-0.0255992f,0.299923f,0.121909f},{0.0253087f,0.297208f,0.121909f}, +{-0.0121592f,0.301901f,0.104198f},{-0.0127415f,0.303616f,0.104198f},{-0.0124735f,0.303072f,0.104198f}, +{-0.0122784f,0.302498f,0.104198f},{-0.0139458f,0.304989f,0.104198f},{-0.0130793f,0.304123f,0.104198f}, +{-0.0134838f,0.304584f,0.104198f},{-0.0161672f,0.305909f,0.104198f},{-0.0155702f,0.30579f,0.104198f}, +{-0.014996f,0.305595f,0.104198f},{-0.0173925f,0.305909f,0.104198f},{-0.0179895f,0.30579f,0.104198f}, +{-0.0167797f,0.30595f,0.104198f},{-0.0191075f,0.305327f,0.104198f},{-0.0185634f,0.305595f,0.104198f}, +{-0.0200755f,0.304584f,0.104198f},{-0.0196139f,0.304989f,0.104198f},{-0.0204802f,0.304122f,0.104198f}, +{-0.020818f,0.303616f,0.104198f},{-0.0210859f,0.303072f,0.104198f},{-0.0212811f,0.302498f,0.104198f}, +{-0.0214003f,0.301901f,0.104198f},{-0.0144523f,0.305327f,0.104198f},{-0.00978795f,0.292446f,0.110723f}, +{-0.00945021f,0.292251f,0.110723f},{-0.0101588f,0.292566f,0.110723f},{-0.00916026f,0.29199f,0.110723f}, +{-0.00893114f,0.291674f,0.110723f},{-0.00877327f,0.291317f,0.110723f},{-0.00869249f,0.290936f,0.110723f}, +{-0.00869285f,0.290546f,0.110723f},{-0.00893415f,0.289809f,0.110723f},{-0.00877489f,0.290165f,0.110723f}, +{-0.00945258f,0.289234f,0.110723f},{-0.00916327f,0.289494f,0.110723f},{-0.0101599f,0.288919f,0.110723f}, +{-0.00978972f,0.289039f,0.110723f},{0.0132829f,0.290468f,0.110723f},{0.0136207f,0.290273f,0.110723f}, +{0.0129121f,0.290589f,0.110723f},{0.0139106f,0.290012f,0.110723f},{0.0141397f,0.289696f,0.110723f}, +{0.0142976f,0.28934f,0.110723f},{0.0143784f,0.288958f,0.110723f},{0.014378f,0.288568f,0.110723f}, +{0.0141367f,0.287831f,0.110723f},{0.014296f,0.288187f,0.110723f},{0.0136183f,0.287256f,0.110723f}, +{0.0139076f,0.287517f,0.110723f},{0.012911f,0.286941f,0.110723f},{0.0132812f,0.287062f,0.110723f}, +{0.0113054f,0.313539f,0.110723f},{0.0116432f,0.313344f,0.110723f},{0.0109345f,0.31366f,0.110723f}, +{0.0119331f,0.313083f,0.110723f},{0.0121622f,0.312767f,0.110723f},{0.0123201f,0.312411f,0.110723f}, +{0.0124009f,0.312029f,0.110723f},{0.0124005f,0.311639f,0.110723f},{0.0121592f,0.310902f,0.110723f}, +{0.0123185f,0.311258f,0.110723f},{0.0116408f,0.310327f,0.110723f},{0.0119301f,0.310588f,0.110723f}, +{0.0109335f,0.310012f,0.110723f},{0.0113037f,0.310133f,0.110723f},{-0.0117655f,0.315517f,0.110723f}, +{-0.0114277f,0.315322f,0.110723f},{-0.0121363f,0.315637f,0.110723f},{-0.0111378f,0.315061f,0.110723f}, +{-0.0109086f,0.314745f,0.110723f},{-0.0107508f,0.314388f,0.110723f},{-0.01067f,0.314007f,0.110723f}, +{-0.0106704f,0.313617f,0.110723f},{-0.0109117f,0.31288f,0.110723f},{-0.0107524f,0.313235f,0.110723f}, +{-0.0114301f,0.312305f,0.110723f},{-0.0111408f,0.312565f,0.110723f},{-0.0121374f,0.31199f,0.110723f}, +{-0.0117672f,0.31211f,0.110723f},{-0.000612842f,0.289129f,0.104198f},{-0.00232777f,0.288547f,0.104198f}, +{-0.00120978f,0.28901f,0.104198f},{-0.00178369f,0.288815f,0.104198f},{-0.00370055f,0.287343f,0.104198f}, +{-0.00403832f,0.286836f,0.104198f},{-0.00329584f,0.287805f,0.104198f},{-0.00462066f,0.285121f,0.104198f}, +{-0.00430621f,0.286293f,0.104198f},{-0.00450141f,0.285718f,0.104198f},{-0.00450127f,0.283299f,0.104198f}, +{-0.00466102f,0.284509f,0.104198f},{-0.00462052f,0.283896f,0.104198f},{-0.00403818f,0.282181f,0.104198f}, +{-0.00370041f,0.281675f,0.104198f},{-0.00430621f,0.282725f,0.104198f},{-0.00329584f,0.281213f,0.104198f}, +{-0.00283386f,0.280808f,0.104198f},{-0.00232743f,0.280471f,0.104198f},{-0.00178369f,0.280203f,0.104198f}, +{-0.00120944f,0.280007f,0.104198f},{-0.000612502f,0.279888f,0.104198f},{-0.0028342f,0.288209f,0.104198f}, +{0.0121592f,0.300676f,0.104198f},{0.0127415f,0.298961f,0.104198f},{0.0124735f,0.299505f,0.104198f}, +{0.0122784f,0.300079f,0.104198f},{0.0139458f,0.297588f,0.104198f},{0.0130793f,0.298454f,0.104198f}, +{0.0134838f,0.297993f,0.104198f},{0.0161672f,0.296668f,0.104198f},{0.0155702f,0.296787f,0.104198f}, +{0.014996f,0.296982f,0.104198f},{0.0179895f,0.296787f,0.104198f},{0.0173925f,0.296668f,0.104198f}, +{0.0167797f,0.296628f,0.104198f},{0.0191075f,0.29725f,0.104198f},{0.0185634f,0.296982f,0.104198f}, +{0.0200755f,0.297993f,0.104198f},{0.0196139f,0.297588f,0.104198f},{0.0204802f,0.298455f,0.104198f}, +{0.020818f,0.298961f,0.104198f},{0.0210859f,0.299505f,0.104198f},{0.0212811f,0.300079f,0.104198f}, +{0.0214003f,0.300676f,0.104198f},{0.0144523f,0.29725f,0.104198f},{0.000612842f,0.313448f,0.104198f}, +{0.00232777f,0.31403f,0.104198f},{0.00178369f,0.313762f,0.104198f},{0.00120978f,0.313567f,0.104198f}, +{0.00370055f,0.315234f,0.104198f},{0.0028342f,0.314368f,0.104198f},{0.00329584f,0.314772f,0.104198f}, +{0.00462066f,0.317456f,0.104198f},{0.00450141f,0.316859f,0.104198f},{0.00430621f,0.316285f,0.104198f}, +{0.00462052f,0.318681f,0.104198f},{0.00450127f,0.319278f,0.104198f},{0.00466102f,0.318068f,0.104198f}, +{0.00403818f,0.320396f,0.104198f},{0.00430621f,0.319852f,0.104198f},{0.00329584f,0.321364f,0.104198f}, +{0.00370041f,0.320902f,0.104198f},{0.00283386f,0.321769f,0.104198f},{0.00232743f,0.322107f,0.104198f}, +{0.00178369f,0.322374f,0.104198f},{0.00120944f,0.32257f,0.104198f},{0.000612502f,0.322689f,0.104198f}, +{0.00403832f,0.315741f,0.104198f},{0.0114195f,0.281509f,0.104198f},{0.00948155f,0.280511f,0.104198f}, +{0.0032562f,0.278683f,0.104198f},{0.00746583f,0.279704f,0.104198f},{-0.00325654f,0.278683f,0.104198f}, +{0.00109039f,0.278476f,0.104198f},{-0.00109151f,0.278476f,0.104198f},{-0.00746603f,0.279704f,0.104198f}, +{-0.00538621f,0.279094f,0.104198f},{-0.00948213f,0.280511f,0.104198f},{-0.0114195f,0.281509f,0.104198f}, +{0.00538567f,0.279094f,0.104198f},{0.0123517f,0.279895f,0.104198f},{-0.0123517f,0.279895f,0.104198f}, +{-0.0102556f,0.278815f,0.104198f},{-0.00352201f,0.276837f,0.104198f},{-0.00807529f,0.277942f,0.104198f}, +{0.00352238f,0.276838f,0.104198f},{-0.00117941f,0.276613f,0.104198f},{0.00118061f,0.276613f,0.104198f}, +{0.0080755f,0.277942f,0.104198f},{0.0102562f,0.278815f,0.104198f},{0.0058259f,0.277282f,0.104198f}, +{-0.00582532f,0.277282f,0.104198f},{0.0132534f,0.319889f,0.104198f},{0.0114195f,0.321068f,0.104198f}, +{0.017949f,0.315411f,0.104198f},{0.0165285f,0.31705f,0.104198f},{0.0149596f,0.318546f,0.104198f}, +{0.0203023f,0.31175f,0.104198f},{0.0212053f,0.309771f,0.104198f},{0.0192114f,0.313639f,0.104198f}, +{0.0224255f,0.305615f,0.104198f},{0.0219143f,0.307721f,0.104198f},{0.0227351f,0.303466f,0.104198f}, +{0.022839f,0.301289f,0.104198f},{0.0123517f,0.322682f,0.104198f},{0.0247034f,0.301289f,0.104198f}, +{0.0245908f,0.303644f,0.104198f},{0.0229363f,0.310464f,0.104198f},{0.0237031f,0.308247f,0.104198f}, +{0.0242561f,0.305968f,0.104198f},{0.020779f,0.314649f,0.104198f},{0.019414f,0.316565f,0.104198f}, +{0.0219591f,0.312605f,0.104198f},{0.0178774f,0.318337f,0.104198f},{0.0161807f,0.319955f,0.104198f}, +{0.0143348f,0.321408f,0.104198f},{-0.0227349f,0.303466f,0.104198f},{-0.022839f,0.301289f,0.104198f}, +{-0.0212052f,0.309771f,0.104198f},{-0.0219142f,0.307722f,0.104198f},{-0.0224254f,0.305615f,0.104198f}, +{-0.0192108f,0.31364f,0.104198f},{-0.0179488f,0.315412f,0.104198f},{-0.0203018f,0.311751f,0.104198f}, +{-0.0149595f,0.318546f,0.104198f},{-0.0165281f,0.317051f,0.104198f},{-0.0132529f,0.319889f,0.104198f}, +{-0.0114195f,0.321068f,0.104198f},{-0.0247034f,0.301289f,0.104198f},{-0.0123517f,0.322682f,0.104198f}, +{-0.0143353f,0.321407f,0.104198f},{-0.0194142f,0.316564f,0.104198f},{-0.0178778f,0.318337f,0.104198f}, +{-0.0161808f,0.319955f,0.104198f},{-0.0219596f,0.312604f,0.104198f},{-0.0229364f,0.310464f,0.104198f}, +{-0.0207797f,0.314648f,0.104198f},{-0.0237033f,0.308246f,0.104198f},{-0.0242561f,0.305968f,0.104198f}, +{-0.024591f,0.303643f,0.104198f},{-0.00275356f,0.3008f,0.0986044f},{-0.00214219f,0.299491f,0.0986044f}, +{-0.00242266f,0.299891f,0.0986044f},{-0.00262748f,0.300331f,0.0986044f},{-0.000956449f,0.298661f,0.0986044f}, +{-0.00048723f,0.298535f,0.0986044f},{-0.00179504f,0.299144f,0.0986044f},{-0.00139564f,0.298865f,0.0986044f}, +{0.000957717f,0.298661f,0.0986044f},{0.000488516f,0.298535f,0.0986044f},{-2.66406e-017f,0.298492f,0.0986044f}, +{0.00179767f,0.299146f,0.0986044f},{0.00139727f,0.298866f,0.0986044f},{0.00214411f,0.299493f,0.0986044f}, +{0.00242333f,0.299893f,0.0986044f},{0.00262801f,0.300332f,0.0986044f},{0.00275356f,0.3008f,0.0986044f}, +{0.0174099f,0.300063f,0.121909f},{0.0172871f,0.300669f,0.121909f},{0.0172458f,0.301289f,0.121909f}, +{0.0176121f,0.299477f,0.121909f},{0.0182409f,0.29841f,0.121909f},{0.0178912f,0.298922f,0.121909f}, +{0.0186544f,0.29795f,0.121909f},{0.0191262f,0.297548f,0.121909f},{0.0196487f,0.297211f,0.121909f}, +{0.0202093f,0.296948f,0.121909f},{0.0207991f,0.296761f,0.121909f},{0.021411f,0.296654f,0.121909f}, +{0.0172872f,0.301908f,0.121909f},{0.0174099f,0.302515f,0.121909f},{0.0176122f,0.3031f,0.121909f}, +{0.0178915f,0.303655f,0.121909f},{0.0182411f,0.304167f,0.121909f},{0.0186545f,0.304627f,0.121909f}, +{0.0191266f,0.30503f,0.121909f},{0.0196491f,0.305366f,0.121909f},{0.0202094f,0.305629f,0.121909f}, +{0.0207994f,0.305816f,0.121909f},{0.021411f,0.305923f,0.121909f},{0.00761603f,0.308374f,0.121909f}, +{0.00821991f,0.309912f,0.121909f},{0.00794276f,0.309432f,0.121909f},{0.00774033f,0.308916f,0.121909f}, +{0.00944153f,0.311045f,0.121909f},{0.00856913f,0.31035f,0.121909f},{0.00898119f,0.310732f,0.121909f}, +{0.0115849f,0.311532f,0.121909f},{0.011024f,0.311532f,0.121909f},{0.01047f,0.311449f,0.121909f}, +{0.0126654f,0.311285f,0.121909f},{0.012136f,0.311448f,0.121909f},{0.0136271f,0.310729f,0.121909f}, +{0.0140372f,0.310348f,0.121909f},{0.0131654f,0.311044f,0.121909f},{0.0143853f,0.309911f,0.121909f}, +{0.0146628f,0.30943f,0.121909f},{0.0148654f,0.308914f,0.121909f},{0.0149887f,0.308374f,0.121909f}, +{0.00994023f,0.311285f,0.121909f},{0.00749878f,0.301677f,0.121909f},{0.0080757f,0.302675f,0.121909f}, +{0.007619f,0.302047f,0.121909f},{0.0091279f,0.303143f,0.121909f},{0.00839049f,0.302903f,0.121909f}, +{0.00874642f,0.303062f,0.121909f},{0.00989914f,0.303061f,0.121909f},{0.0102546f,0.302903f,0.121909f}, +{0.00951793f,0.303143f,0.121909f},{0.0105703f,0.302673f,0.121909f},{0.0108309f,0.302384f,0.121909f}, +{0.0110255f,0.302046f,0.121909f},{0.0111456f,0.301676f,0.121909f},{0.00781413f,0.302385f,0.121909f}, +{0.00632322f,0.319723f,0.121909f},{0.00629776f,0.320341f,0.121909f},{0.00635281f,0.320959f,0.121909f}, +{0.00643547f,0.319113f,0.121909f},{0.00662778f,0.318524f,0.121909f},{0.00689664f,0.317965f,0.121909f}, +{0.00723717f,0.317447f,0.121909f},{0.00862289f,0.316224f,0.121909f},{0.00917948f,0.31595f,0.121909f}, +{0.00764334f,0.316979f,0.121909f},{0.00810797f,0.316569f,0.121909f},{0.010376f,0.315635f,0.121909f}, +{0.0109947f,0.3156f,0.121909f},{0.0143217f,0.317038f,0.121909f},{0.0138626f,0.316622f,0.121909f}, +{0.0122191f,0.315775f,0.121909f},{0.012803f,0.315983f,0.121909f},{0.013354f,0.316267f,0.121909f}, +{0.0147191f,0.317514f,0.121909f},{0.0116126f,0.315647f,0.121909f},{0.0097673f,0.315753f,0.121909f}, +{0.00647672f,0.321566f,0.121909f},{0.00669182f,0.322148f,0.121909f},{-0.00232814f,0.311427f,0.121909f}, +{-0.00335826f,0.312719f,0.121909f},{-0.00308092f,0.312239f,0.121909f},{-0.0027356f,0.311806f,0.121909f}, +{-0.00372865f,0.314343f,0.121909f},{-0.0035632f,0.313241f,0.121909f},{-0.00368751f,0.313788f,0.121909f}, +{-0.00307835f,0.316443f,0.121909f},{-0.00335937f,0.315957f,0.121909f},{-0.00356405f,0.315436f,0.121909f}, +{-0.00232427f,0.317255f,0.121909f},{-0.0027306f,0.316878f,0.121909f},{-0.00136237f,0.31781f,0.121909f}, +{-0.000827251f,0.317975f,0.121909f},{-0.00186593f,0.317568f,0.121909f},{-0.000274996f,0.318058f,0.121909f}, +{0.000280844f,0.318058f,0.121909f},{0.000829073f,0.317975f,0.121909f},{0.00135821f,0.317812f,0.121909f}, +{-0.00368715f,0.314895f,0.121909f},{0.0034127f,0.307977f,0.121909f},{0.00283723f,0.308975f,0.121909f}, +{0.00315233f,0.308266f,0.121909f},{0.00295815f,0.310121f,0.121909f},{0.00279666f,0.309362f,0.121909f}, +{0.00283762f,0.30975f,0.121909f},{0.00341439f,0.310748f,0.121909f},{0.00372927f,0.310977f,0.121909f}, +{0.00315311f,0.310458f,0.121909f},{0.00408585f,0.311135f,0.121909f},{0.00446695f,0.311216f,0.121909f}, +{0.0048565f,0.311216f,0.121909f},{0.00523731f,0.311135f,0.121909f},{0.00295751f,0.308604f,0.121909f}, +{-0.0133515f,0.316269f,0.121909f},{-0.013859f,0.316626f,0.121909f},{-0.00764282f,0.316979f,0.121909f}, +{-0.00810759f,0.316569f,0.121909f},{-0.00723674f,0.317448f,0.121909f},{-0.00862289f,0.316224f,0.121909f}, +{-0.00689651f,0.317966f,0.121909f},{-0.00662806f,0.318524f,0.121909f},{-0.00643592f,0.319114f,0.121909f}, +{-0.00917901f,0.31595f,0.121909f},{-0.00976653f,0.315753f,0.121909f},{-0.00632427f,0.319723f,0.121909f}, +{-0.0103751f,0.315635f,0.121909f},{-0.00629503f,0.320343f,0.121909f},{-0.0064786f,0.321566f,0.121909f}, +{-0.00634749f,0.32096f,0.121909f},{-0.010994f,0.3156f,0.121909f},{-0.00669182f,0.322148f,0.121909f}, +{-0.0116123f,0.315646f,0.121909f},{-0.0128028f,0.315982f,0.121909f},{-0.0122189f,0.315774f,0.121909f}, +{-0.0143221f,0.317036f,0.121909f},{-0.0147191f,0.317514f,0.121909f},{-0.00994417f,0.304342f,0.121909f}, +{-0.0115782f,0.304095f,0.121909f},{-0.0110237f,0.304096f,0.121909f},{-0.0104759f,0.304178f,0.121909f}, +{-0.0131702f,0.304587f,0.121909f},{-0.0121323f,0.304179f,0.121909f},{-0.0126687f,0.304345f,0.121909f}, +{-0.0146632f,0.3062f,0.121909f},{-0.0143833f,0.305714f,0.121909f},{-0.014034f,0.305276f,0.121909f}, +{-0.0149897f,0.307259f,0.121909f},{-0.0148666f,0.306719f,0.121909f},{-0.0149894f,0.30837f,0.121909f}, +{-0.0148645f,0.308915f,0.121909f},{-0.0150313f,0.307812f,0.121909f},{-0.0146603f,0.309435f,0.121909f}, +{-0.014382f,0.309916f,0.121909f},{-0.0140364f,0.31035f,0.121909f},{-0.0136305f,0.310726f,0.121909f}, +{-0.0136274f,0.304899f,0.121909f},{-0.00408601f,0.307588f,0.121909f},{-0.0052381f,0.307589f,0.121909f}, +{-0.00446686f,0.307507f,0.121909f},{-0.00616977f,0.308266f,0.121909f},{-0.00559379f,0.307747f,0.121909f}, +{-0.00590924f,0.307977f,0.121909f},{-0.00648482f,0.308975f,0.121909f},{-0.00652543f,0.309362f,0.121909f}, +{-0.0063645f,0.308604f,0.121909f},{-0.00648441f,0.30975f,0.121909f},{-0.00636386f,0.310121f,0.121909f}, +{-0.00616897f,0.310458f,0.121909f},{-0.00590844f,0.310747f,0.121909f},{-0.00485671f,0.307508f,0.121909f}, +{-0.0178906f,0.298923f,0.121909f},{-0.0176123f,0.299477f,0.121909f},{-0.0182401f,0.298411f,0.121909f}, +{-0.0186543f,0.297949f,0.121909f},{-0.019126f,0.297548f,0.121909f},{-0.0174099f,0.300063f,0.121909f}, +{-0.0196492f,0.297216f,0.121909f},{-0.017287f,0.30067f,0.121909f},{-0.0172458f,0.301289f,0.121909f}, +{-0.0172871f,0.301907f,0.121909f},{-0.0174101f,0.302515f,0.121909f},{-0.0176127f,0.303101f,0.121909f}, +{-0.0178912f,0.303655f,0.121909f},{-0.0182407f,0.304166f,0.121909f},{-0.018655f,0.304627f,0.121909f}, +{-0.0191272f,0.305029f,0.121909f},{-0.0196491f,0.305364f,0.121909f},{-0.02021f,0.305627f,0.121909f}, +{-0.0208003f,0.305817f,0.121909f},{-0.021411f,0.305923f,0.121909f},{-0.0207988f,0.296759f,0.121909f}, +{-0.0202118f,0.296955f,0.121909f},{-0.021411f,0.296654f,0.121909f},{-0.00761603f,0.294203f,0.121909f}, +{-0.00821991f,0.292665f,0.121909f},{-0.00794276f,0.293145f,0.121909f},{-0.00774033f,0.293661f,0.121909f}, +{-0.00944153f,0.291532f,0.121909f},{-0.00856913f,0.292227f,0.121909f},{-0.00898119f,0.291845f,0.121909f}, +{-0.0115849f,0.291045f,0.121909f},{-0.011024f,0.291045f,0.121909f},{-0.01047f,0.291128f,0.121909f}, +{-0.0126654f,0.291292f,0.121909f},{-0.012136f,0.291129f,0.121909f},{-0.0136271f,0.291848f,0.121909f}, +{-0.0140372f,0.292229f,0.121909f},{-0.0131654f,0.291533f,0.121909f},{-0.0143853f,0.292666f,0.121909f}, +{-0.0146628f,0.293147f,0.121909f},{-0.0148654f,0.293663f,0.121909f},{-0.0149887f,0.294203f,0.121909f}, +{-0.00994023f,0.291292f,0.121909f},{-0.00749878f,0.3009f,0.121909f},{-0.0080757f,0.299902f,0.121909f}, +{-0.007619f,0.30053f,0.121909f},{-0.0091279f,0.299434f,0.121909f},{-0.00839049f,0.299674f,0.121909f}, +{-0.00874642f,0.299515f,0.121909f},{-0.00989914f,0.299516f,0.121909f},{-0.0102546f,0.299674f,0.121909f}, +{-0.00951793f,0.299435f,0.121909f},{-0.0105703f,0.299904f,0.121909f},{-0.0108309f,0.300193f,0.121909f}, +{-0.0110255f,0.300531f,0.121909f},{-0.0111456f,0.300901f,0.121909f},{-0.00781413f,0.300192f,0.121909f}, +{-0.00629776f,0.282236f,0.121909f},{-0.00632322f,0.282854f,0.121909f},{-0.0147191f,0.285063f,0.121909f}, +{-0.00643547f,0.283464f,0.121909f},{-0.00635281f,0.281618f,0.121909f},{-0.00662778f,0.284053f,0.121909f}, +{-0.00689664f,0.284612f,0.121909f},{-0.00764334f,0.285598f,0.121909f},{-0.00810797f,0.286008f,0.121909f}, +{-0.00723717f,0.28513f,0.121909f},{-0.010376f,0.286942f,0.121909f},{-0.0109947f,0.286977f,0.121909f}, +{-0.00862289f,0.286353f,0.121909f},{-0.00917948f,0.286627f,0.121909f},{-0.0143217f,0.285539f,0.121909f}, +{-0.0138626f,0.285956f,0.121909f},{-0.0122191f,0.286802f,0.121909f},{-0.012803f,0.286594f,0.121909f}, +{-0.013354f,0.28631f,0.121909f},{-0.0116126f,0.286931f,0.121909f},{-0.0097673f,0.286824f,0.121909f}, +{-0.00647672f,0.281011f,0.121909f},{-0.00669182f,0.280429f,0.121909f},{0.00232814f,0.29115f,0.121909f}, +{0.00335826f,0.289858f,0.121909f},{0.00308092f,0.290338f,0.121909f},{0.0027356f,0.290771f,0.121909f}, +{0.00372865f,0.288234f,0.121909f},{0.0035632f,0.289337f,0.121909f},{0.00368751f,0.288789f,0.121909f}, +{0.00307835f,0.286134f,0.121909f},{0.00335937f,0.28662f,0.121909f},{0.00356405f,0.287141f,0.121909f}, +{0.00232427f,0.285322f,0.121909f},{0.0027306f,0.285699f,0.121909f},{0.00136237f,0.284767f,0.121909f}, +{0.000827251f,0.284602f,0.121909f},{0.00186593f,0.285009f,0.121909f},{0.000274996f,0.284519f,0.121909f}, +{-0.000280844f,0.284519f,0.121909f},{-0.000829073f,0.284602f,0.121909f},{-0.00135821f,0.284765f,0.121909f}, +{0.00368715f,0.287682f,0.121909f},{-0.0034126f,0.2946f,0.121909f},{-0.00283728f,0.293602f,0.121909f}, +{-0.0031524f,0.294311f,0.121909f},{-0.00295812f,0.292456f,0.121909f},{-0.00279668f,0.293215f,0.121909f}, +{-0.0028374f,0.292827f,0.121909f},{-0.0034143f,0.291829f,0.121909f},{-0.00372908f,0.291601f,0.121909f}, +{-0.00315337f,0.292119f,0.121909f},{-0.00408596f,0.291442f,0.121909f},{-0.00446705f,0.291361f,0.121909f}, +{-0.00485646f,0.291361f,0.121909f},{-0.00523689f,0.291442f,0.121909f},{-0.00295753f,0.293973f,0.121909f}, +{0.00764282f,0.285598f,0.121909f},{0.00723674f,0.285129f,0.121909f},{0.00810759f,0.286008f,0.121909f}, +{0.00862289f,0.286353f,0.121909f},{0.00689651f,0.284611f,0.121909f},{0.00662806f,0.284053f,0.121909f}, +{0.00643592f,0.283463f,0.121909f},{0.00917901f,0.286627f,0.121909f},{0.00632427f,0.282854f,0.121909f}, +{0.00629503f,0.282234f,0.121909f},{0.00976653f,0.286824f,0.121909f},{0.00634749f,0.281617f,0.121909f}, +{0.0103751f,0.286942f,0.121909f},{0.010994f,0.286978f,0.121909f},{0.0064786f,0.281011f,0.121909f}, +{0.00669182f,0.280429f,0.121909f},{0.0116123f,0.286931f,0.121909f},{0.0128028f,0.286595f,0.121909f}, +{0.0122189f,0.286803f,0.121909f},{0.0133515f,0.286308f,0.121909f},{0.013859f,0.285951f,0.121909f}, +{0.0143221f,0.285541f,0.121909f},{0.0147191f,0.285063f,0.121909f},{0.00994417f,0.298236f,0.121909f}, +{0.0115782f,0.298482f,0.121909f},{0.0110237f,0.298482f,0.121909f},{0.0104759f,0.298399f,0.121909f}, +{0.0131702f,0.29799f,0.121909f},{0.0121323f,0.298398f,0.121909f},{0.0126687f,0.298232f,0.121909f}, +{0.0146632f,0.296377f,0.121909f},{0.0143833f,0.296863f,0.121909f},{0.014034f,0.297301f,0.121909f}, +{0.0149897f,0.295318f,0.121909f},{0.0148666f,0.295858f,0.121909f},{0.0149894f,0.294208f,0.121909f}, +{0.0148645f,0.293662f,0.121909f},{0.0150313f,0.294765f,0.121909f},{0.0146603f,0.293142f,0.121909f}, +{0.014382f,0.292661f,0.121909f},{0.0140364f,0.292227f,0.121909f},{0.0136305f,0.291851f,0.121909f}, +{0.0136274f,0.297678f,0.121909f},{0.00408601f,0.294989f,0.121909f},{0.0052381f,0.294988f,0.121909f}, +{0.00446686f,0.29507f,0.121909f},{0.00616977f,0.294311f,0.121909f},{0.00559379f,0.29483f,0.121909f}, +{0.00590924f,0.2946f,0.121909f},{0.00648482f,0.293602f,0.121909f},{0.00652543f,0.293215f,0.121909f}, +{0.0063645f,0.293973f,0.121909f},{0.00648441f,0.292827f,0.121909f},{0.00636386f,0.292456f,0.121909f}, +{0.00616897f,0.292119f,0.121909f},{0.00590844f,0.29183f,0.121909f},{0.00485671f,0.295069f,0.121909f}, +{0.00462052f,0.300676f,0.127503f},{0.00403818f,0.298961f,0.127503f},{0.00450127f,0.300079f,0.127503f}, +{0.00283386f,0.297588f,0.127503f},{0.00232743f,0.29725f,0.127503f},{0.00329584f,0.297993f,0.127503f}, +{0.000612502f,0.296668f,0.127503f},{0.00178369f,0.296982f,0.127503f},{0.00120944f,0.296787f,0.127503f}, +{-0.00120978f,0.296787f,0.127503f},{-2.48389e-017f,0.296628f,0.127503f},{-0.000612842f,0.296668f,0.127503f}, +{-0.00232777f,0.29725f,0.127503f},{-0.0028342f,0.297588f,0.127503f},{-0.00178369f,0.296982f,0.127503f}, +{-0.00329584f,0.297993f,0.127503f},{-0.00370055f,0.298455f,0.127503f},{-0.00403832f,0.298961f,0.127503f}, +{-0.00430621f,0.299505f,0.127503f},{-0.00450141f,0.300079f,0.127503f},{-0.00462066f,0.300676f,0.127503f}, +{0.00370041f,0.298454f,0.127503f},{0.00430621f,0.299505f,0.127503f},{-0.00139737f,0.298869f,0.127503f}, +{-0.00275363f,0.300804f,0.127503f},{-0.00242194f,0.299891f,0.127503f},{-0.00214182f,0.299492f,0.127503f}, +{-0.00262754f,0.300333f,0.127503f},{-0.00179665f,0.299148f,0.127503f},{-0.000956049f,0.298662f,0.127503f}, +{-0.000485772f,0.298534f,0.127503f},{-2.74781e-017f,0.298492f,0.127503f},{0.000955564f,0.29866f,0.127503f}, +{0.000485107f,0.298534f,0.127503f},{0.00139499f,0.298869f,0.127503f},{0.00275512f,0.300803f,0.127503f}, +{0.00178917f,0.299157f,0.127503f},{0.00262887f,0.300331f,0.127503f},{0.00242212f,0.29989f,0.127503f}, +{0.00214373f,0.299488f,0.127503f},{-0.00275512f,0.300803f,0.13496f},{-0.00262887f,0.300331f,0.13496f}, +{-0.00242212f,0.29989f,0.13496f},{-0.00214373f,0.299488f,0.13496f},{-0.00178917f,0.299157f,0.13496f}, +{-0.00139499f,0.298869f,0.13496f},{-0.000955564f,0.29866f,0.13496f},{-0.000485107f,0.298534f,0.13496f}, +{-2.71676e-017f,0.298492f,0.13496f},{0.000485772f,0.298534f,0.13496f},{0.00179665f,0.299148f,0.13496f}, +{0.00262754f,0.300333f,0.13496f},{0.000956049f,0.298662f,0.13496f},{0.00139737f,0.298869f,0.13496f}, +{0.00214182f,0.299492f,0.13496f},{0.00242194f,0.299891f,0.13496f},{0.00275363f,0.300804f,0.13496f}, +{0.301289f,0.00279661f,0.126571f},{0.301289f,0.00279661f,0.134028f},{0.301777f,0.00275356f,0.134028f}, +{0.302246f,0.00262748f,0.134028f},{0.301776f,0.00275376f,0.126571f},{0.302245f,0.00262801f,0.126571f}, +{0.302684f,0.00242333f,0.126571f},{0.303084f,0.00214411f,0.126571f},{0.302686f,0.00242266f,0.134028f}, +{0.303086f,0.00214219f,0.134028f},{0.303431f,0.00179767f,0.126571f},{0.303433f,0.00179504f,0.134028f}, +{0.303711f,0.00139727f,0.126571f},{0.303916f,0.000957717f,0.126571f},{0.303712f,0.00139564f,0.134028f}, +{0.303917f,0.000956449f,0.134028f},{0.304042f,0.000488516f,0.126571f},{0.304042f,0.000488516f,0.134028f}, +{0.304085f,2.50765e-018f,0.134028f},{0.304085f,2.50765e-018f,0.126571f},{0.3008f,0.00275356f,0.126571f}, +{0.300331f,0.00262748f,0.126571f},{0.300801f,0.00275376f,0.134028f},{0.299893f,0.00242333f,0.134028f}, +{0.300332f,0.00262801f,0.134028f},{0.299891f,0.00242266f,0.126571f},{0.299493f,0.00214411f,0.134028f}, +{0.299491f,0.00214219f,0.126571f},{0.299146f,0.00179767f,0.134028f},{0.298866f,0.00139727f,0.134028f}, +{0.299144f,0.00179504f,0.126571f},{0.298865f,0.00139564f,0.126571f},{0.298661f,0.000957717f,0.134028f}, +{0.298661f,0.000956449f,0.126571f},{0.298535f,0.000488516f,0.134028f},{0.298535f,0.000488516f,0.126571f}, +{0.298492f,2.16517e-018f,0.126571f},{0.298492f,2.16517e-018f,0.134028f},{0.301289f,0.00466102f,0.124706f}, +{0.301289f,0.00466102f,0.126571f},{0.301901f,0.00462052f,0.126571f},{0.302498f,0.00450127f,0.126571f}, +{0.301901f,0.00462066f,0.124706f},{0.303072f,0.00430621f,0.126571f},{0.302498f,0.00450141f,0.124706f}, +{0.303072f,0.00430621f,0.124706f},{0.303616f,0.00403818f,0.126571f},{0.304123f,0.00370041f,0.126571f}, +{0.303616f,0.00403832f,0.124706f},{0.304584f,0.00329584f,0.126571f},{0.304122f,0.00370055f,0.124706f}, +{0.304584f,0.00329584f,0.124706f},{0.304989f,0.00283386f,0.126571f},{0.305327f,0.00232743f,0.126571f}, +{0.304989f,0.0028342f,0.124706f},{0.305595f,0.00178369f,0.126571f},{0.305327f,0.00232777f,0.124706f}, +{0.30579f,0.00120978f,0.124706f},{0.305595f,0.00178369f,0.124706f},{0.30579f,0.00120944f,0.126571f}, +{0.305909f,0.000612842f,0.124706f},{0.305909f,0.000612502f,0.126571f},{0.30595f,2.73598e-018f,0.124706f}, +{0.30595f,2.73598e-018f,0.126571f},{0.300676f,0.00462052f,0.124706f},{0.300079f,0.00450127f,0.124706f}, +{0.300676f,0.00462066f,0.126571f},{0.300079f,0.00450141f,0.126571f},{0.299505f,0.00430621f,0.124706f}, +{0.298961f,0.00403818f,0.124706f},{0.299505f,0.00430621f,0.126571f},{0.298454f,0.00370041f,0.124706f}, +{0.298961f,0.00403832f,0.126571f},{0.298455f,0.00370055f,0.126571f},{0.297993f,0.00329584f,0.124706f}, +{0.297588f,0.00283386f,0.124706f},{0.297993f,0.00329584f,0.126571f},{0.29725f,0.00232743f,0.124706f}, +{0.297588f,0.0028342f,0.126571f},{0.29725f,0.00232777f,0.126571f},{0.296982f,0.00178369f,0.124706f}, +{0.296787f,0.00120978f,0.126571f},{0.296982f,0.00178369f,0.126571f},{0.296787f,0.00120944f,0.124706f}, +{0.296668f,0.000612842f,0.126571f},{0.296628f,2.16517e-018f,0.126571f},{0.296668f,0.000612502f,0.124706f}, +{0.296628f,2.16517e-018f,0.124706f},{0.304247f,-0.00883211f,0.124706f},{0.304442f,-0.00916975f,0.124706f}, +{0.304441f,-0.00916839f,0.120977f},{0.304246f,-0.00883048f,0.120977f},{0.304126f,-0.00846133f,0.124706f}, +{0.304126f,-0.00845974f,0.120977f},{0.304085f,-0.0080728f,0.120977f},{0.304126f,-0.00768692f,0.124706f}, +{0.304085f,-0.00807384f,0.124706f},{0.304126f,-0.00768446f,0.120977f},{0.304246f,-0.00731545f,0.124706f}, +{0.304247f,-0.00731401f,0.120977f},{0.304441f,-0.00697763f,0.124706f},{0.304442f,-0.00697682f,0.120977f}, +{0.304701f,-0.00668858f,0.124706f},{0.304702f,-0.0066878f,0.120977f},{0.305017f,-0.0064585f,0.120977f}, +{0.305017f,-0.0064585f,0.124706f},{0.304702f,-0.00945833f,0.120977f},{0.305017f,-0.00968734f,0.120977f}, +{0.304703f,-0.00945929f,0.124706f},{0.305018f,-0.00968796f,0.124706f},{0.305372f,-0.00984564f,0.120977f}, +{0.305375f,-0.00984651f,0.124706f},{0.305754f,-0.00992724f,0.120977f},{0.306144f,-0.00992738f,0.120977f}, +{0.305756f,-0.00992734f,0.124706f},{0.306145f,-0.00992724f,0.124706f},{0.306524f,-0.00984657f,0.120977f}, +{0.306525f,-0.00984636f,0.124706f},{0.306882f,-0.00968775f,0.120977f},{0.306882f,-0.00968775f,0.124706f}, +{0.309232f,-0.00814348f,0.124706f},{0.309513f,-0.00862894f,0.124706f},{0.30951f,-0.00862571f,0.120977f}, +{0.309027f,-0.00762194f,0.124706f},{0.30923f,-0.00813961f,0.120977f},{0.309027f,-0.00762066f,0.120977f}, +{0.308904f,-0.00708133f,0.124706f},{0.308904f,-0.00708043f,0.120977f},{0.308862f,-0.0065271f,0.120977f}, +{0.308862f,-0.00652944f,0.124706f},{0.308903f,-0.00597413f,0.124706f},{0.309233f,-0.00490426f,0.120977f}, +{0.30951f,-0.00442484f,0.124706f},{0.309233f,-0.00490499f,0.124706f},{0.308904f,-0.00596985f,0.120977f}, +{0.309028f,-0.00542656f,0.124706f},{0.309029f,-0.00542408f,0.120977f},{0.309511f,-0.00442313f,0.120977f}, +{0.309855f,-0.00399173f,0.124706f},{0.309857f,-0.00398963f,0.120977f},{0.310263f,-0.00361295f,0.120977f}, +{0.310726f,-0.00329618f,0.124706f},{0.310263f,-0.00361295f,0.124706f},{0.310726f,-0.00329618f,0.120977f}, +{0.309859f,-0.00906373f,0.120977f},{0.310266f,-0.00944065f,0.120977f},{0.30986f,-0.00906452f,0.124706f}, +{0.310267f,-0.00944121f,0.124706f},{0.310723f,-0.00975253f,0.120977f},{0.310725f,-0.00975397f,0.124706f}, +{0.311225f,-0.00999456f,0.120977f},{0.311761f,-0.0101607f,0.120977f},{0.311229f,-0.0099963f,0.124706f}, +{0.311764f,-0.010161f,0.124706f},{0.312315f,-0.010244f,0.120977f},{0.312316f,-0.0102441f,0.124706f}, +{0.31287f,-0.0102439f,0.120977f},{0.313417f,-0.0101614f,0.120977f},{0.312872f,-0.0102436f,0.124706f}, +{0.31342f,-0.010161f,0.124706f},{0.313949f,-0.0099979f,0.120977f},{0.313949f,-0.0099979f,0.124706f}, +{0.314455f,-0.00975468f,0.120977f},{0.314455f,-0.00975468f,0.124706f},{0.295119f,-0.00697787f,0.124706f}, +{0.294924f,-0.00731578f,0.124706f},{0.294925f,-0.00731414f,0.120977f},{0.29512f,-0.0069765f,0.120977f}, +{0.29538f,-0.00668793f,0.124706f},{0.295381f,-0.00668696f,0.120977f},{0.295696f,-0.0064583f,0.120977f}, +{0.29605f,-0.00630061f,0.124706f},{0.295695f,-0.00645891f,0.124706f},{0.296052f,-0.00629975f,0.120977f}, +{0.296432f,-0.00621902f,0.124706f},{0.296434f,-0.00621892f,0.120977f},{0.296822f,-0.00621887f,0.124706f}, +{0.296823f,-0.00621902f,0.120977f},{0.297202f,-0.00629969f,0.124706f},{0.297203f,-0.0062999f,0.120977f}, +{0.29756f,-0.0064585f,0.120977f},{0.29756f,-0.0064585f,0.124706f},{0.294804f,-0.00768493f,0.120977f}, +{0.294763f,-0.00807242f,0.120977f},{0.294804f,-0.00768652f,0.124706f},{0.294763f,-0.00807346f,0.124706f}, +{0.294804f,-0.00845934f,0.120977f},{0.294804f,-0.0084618f,0.124706f},{0.294924f,-0.0088308f,0.120977f}, +{0.295119f,-0.00916863f,0.120977f},{0.294925f,-0.00883225f,0.124706f},{0.29512f,-0.00916944f,0.124706f}, +{0.295379f,-0.00945768f,0.120977f},{0.29538f,-0.00945846f,0.124706f},{0.295695f,-0.00968775f,0.120977f}, +{0.295695f,-0.00968775f,0.124706f},{0.298208f,-0.0109506f,0.124706f},{0.297928f,-0.0114367f,0.124706f}, +{0.297929f,-0.0114328f,0.120977f},{0.298557f,-0.0105126f,0.124706f},{0.29821f,-0.0109474f,0.120977f}, +{0.298558f,-0.0105118f,0.120977f},{0.298964f,-0.0101356f,0.124706f},{0.298964f,-0.0101351f,0.120977f}, +{0.299423f,-0.00982233f,0.120977f},{0.299421f,-0.00982376f,0.124706f},{0.299922f,-0.00958174f,0.124706f}, +{0.301014f,-0.00933222f,0.120977f},{0.301567f,-0.00933241f,0.124706f},{0.301013f,-0.00933231f,0.124706f}, +{0.299926f,-0.00958f,0.120977f},{0.300459f,-0.00941561f,0.124706f},{0.300461f,-0.00941532f,0.120977f}, +{0.301569f,-0.0093327f,0.120977f},{0.302115f,-0.00941491f,0.124706f},{0.302118f,-0.00941526f,0.120977f}, +{0.302647f,-0.0095784f,0.120977f},{0.303153f,-0.00982161f,0.124706f},{0.302647f,-0.0095784f,0.124706f}, +{0.303153f,-0.00982161f,0.120977f},{0.297725f,-0.0119544f,0.120977f},{0.297601f,-0.012495f,0.120977f}, +{0.297724f,-0.0119556f,0.124706f},{0.297601f,-0.0124959f,0.124706f},{0.29756f,-0.0130469f,0.120977f}, +{0.29756f,-0.0130492f,0.124706f},{0.297601f,-0.0136022f,0.120977f},{0.297725f,-0.0141497f,0.120977f}, +{0.297601f,-0.0136064f,0.124706f},{0.297726f,-0.0141522f,0.124706f},{0.29793f,-0.0146713f,0.120977f}, +{0.297931f,-0.014672f,0.124706f},{0.298208f,-0.0151515f,0.120977f},{0.298553f,-0.0155846f,0.120977f}, +{0.298209f,-0.0151532f,0.124706f},{0.298555f,-0.0155867f,0.124706f},{0.29896f,-0.0159633f,0.120977f}, +{0.29896f,-0.0159633f,0.124706f},{0.299424f,-0.0162801f,0.120977f},{0.299424f,-0.0162801f,0.124706f}, +{0.292161f,0.00185425f,0.124706f},{0.291771f,0.00185398f,0.124706f},{0.291772f,0.00185425f,0.120977f}, +{0.292162f,0.00185398f,0.120977f},{0.292542f,0.0017734f,0.124706f},{0.292544f,0.00177278f,0.120977f}, +{0.292899f,0.0016145f,0.120977f},{0.293213f,0.0013863f,0.124706f},{0.292898f,0.00161492f,0.124706f}, +{0.293215f,0.00138471f,0.120977f},{0.293474f,0.00109643f,0.124706f},{0.293475f,0.00109509f,0.120977f}, +{0.29367f,0.000758756f,0.124706f},{0.29367f,0.000757801f,0.120977f},{0.29379f,0.000388892f,0.124706f}, +{0.29379f,0.000387896f,0.120977f},{0.293831f,5.86186e-018f,0.120977f},{0.293831f,5.86186e-018f,0.124706f}, +{0.291391f,0.0017734f,0.120977f},{0.291035f,0.00161492f,0.120977f},{0.291389f,0.00177278f,0.124706f}, +{0.291034f,0.0016145f,0.124706f},{0.29072f,0.0013863f,0.120977f},{0.290718f,0.00138471f,0.124706f}, +{0.290459f,0.00109643f,0.120977f},{0.290263f,0.000758756f,0.120977f},{0.290458f,0.00109509f,0.124706f}, +{0.290263f,0.000757801f,0.124706f},{0.290143f,0.000388892f,0.120977f},{0.290143f,0.000387896f,0.124706f}, +{0.290102f,6.91815e-018f,0.120977f},{0.290102f,6.91815e-018f,0.124706f},{0.290265f,-0.00280711f,0.124706f}, +{0.289704f,-0.00280775f,0.124706f},{0.289708f,-0.00280711f,0.120977f},{0.290819f,-0.00289062f,0.124706f}, +{0.290269f,-0.00280775f,0.120977f},{0.29082f,-0.00289112f,0.120977f},{0.291348f,-0.00305432f,0.124706f}, +{0.291349f,-0.00305467f,0.120977f},{0.291849f,-0.00329522f,0.120977f},{0.291847f,-0.00329432f,0.124706f}, +{0.292307f,-0.00360761f,0.124706f},{0.293069f,-0.00442796f,0.120977f},{0.293346f,-0.00490757f,0.124706f}, +{0.293069f,-0.00442732f,0.124706f},{0.292311f,-0.00361015f,0.120977f},{0.292719f,-0.00398905f,0.124706f}, +{0.292721f,-0.00399124f,0.120977f},{0.293347f,-0.00490957f,0.120977f},{0.293548f,-0.00542319f,0.124706f}, +{0.293549f,-0.00542563f,0.120977f},{0.293673f,-0.00596545f,0.120977f},{0.293715f,-0.00652543f,0.124706f}, +{0.293673f,-0.00596545f,0.124706f},{0.293715f,-0.00652543f,0.120977f},{0.289154f,-0.00289062f,0.120977f}, +{0.288624f,-0.00305432f,0.120977f},{0.289153f,-0.00289112f,0.124706f},{0.288623f,-0.00305467f,0.124706f}, +{0.288125f,-0.00329432f,0.120977f},{0.288123f,-0.00329522f,0.124706f},{0.287665f,-0.00360761f,0.120977f}, +{0.287253f,-0.00398905f,0.120977f},{0.287661f,-0.00361015f,0.124706f},{0.287251f,-0.00399124f,0.124706f}, +{0.286904f,-0.00442732f,0.120977f},{0.286903f,-0.00442796f,0.124706f},{0.286627f,-0.00490757f,0.120977f}, +{0.286424f,-0.00542319f,0.120977f},{0.286626f,-0.00490957f,0.124706f},{0.286423f,-0.00542563f,0.124706f}, +{0.2863f,-0.00596545f,0.120977f},{0.2863f,-0.00596545f,0.124706f},{0.286257f,-0.00652543f,0.120977f}, +{0.286257f,-0.00652543f,0.124706f},{0.29833f,0.00883211f,0.124706f},{0.298135f,0.00916975f,0.124706f}, +{0.298136f,0.00916839f,0.120977f},{0.298331f,0.00883048f,0.120977f},{0.298451f,0.00846133f,0.124706f}, +{0.298451f,0.00845974f,0.120977f},{0.298492f,0.0080728f,0.120977f},{0.298451f,0.00768692f,0.124706f}, +{0.298492f,0.00807384f,0.124706f},{0.298451f,0.00768446f,0.120977f},{0.298331f,0.00731545f,0.124706f}, +{0.29833f,0.00731401f,0.120977f},{0.298136f,0.00697763f,0.124706f},{0.298136f,0.00697682f,0.120977f}, +{0.297876f,0.00668858f,0.124706f},{0.297875f,0.0066878f,0.120977f},{0.29756f,0.0064585f,0.120977f}, +{0.29756f,0.0064585f,0.124706f},{0.297876f,0.00945833f,0.120977f},{0.29756f,0.00968734f,0.120977f}, +{0.297874f,0.00945929f,0.124706f},{0.297559f,0.00968796f,0.124706f},{0.297205f,0.00984564f,0.120977f}, +{0.297203f,0.00984651f,0.124706f},{0.296823f,0.00992724f,0.120977f},{0.296433f,0.00992738f,0.120977f}, +{0.296822f,0.00992734f,0.124706f},{0.296432f,0.00992724f,0.124706f},{0.296053f,0.00984657f,0.120977f}, +{0.296052f,0.00984636f,0.124706f},{0.295695f,0.00968775f,0.120977f},{0.295695f,0.00968775f,0.124706f}, +{0.293346f,0.00814348f,0.124706f},{0.293065f,0.00862894f,0.124706f},{0.293067f,0.00862571f,0.120977f}, +{0.29355f,0.00762194f,0.124706f},{0.293347f,0.00813961f,0.120977f},{0.29355f,0.00762066f,0.120977f}, +{0.293673f,0.00708133f,0.124706f},{0.293673f,0.00708043f,0.120977f},{0.293715f,0.0065271f,0.120977f}, +{0.293715f,0.00652944f,0.124706f},{0.293674f,0.00597413f,0.124706f},{0.293344f,0.00490426f,0.120977f}, +{0.293067f,0.00442484f,0.124706f},{0.293344f,0.00490499f,0.124706f},{0.293673f,0.00596985f,0.120977f}, +{0.293549f,0.00542656f,0.124706f},{0.293548f,0.00542408f,0.120977f},{0.293066f,0.00442313f,0.120977f}, +{0.292722f,0.00399173f,0.124706f},{0.29272f,0.00398963f,0.120977f},{0.292314f,0.00361295f,0.120977f}, +{0.291851f,0.00329618f,0.124706f},{0.292314f,0.00361295f,0.124706f},{0.291851f,0.00329618f,0.120977f}, +{0.292718f,0.00906373f,0.120977f},{0.292311f,0.00944065f,0.120977f},{0.292717f,0.00906452f,0.124706f}, +{0.29231f,0.00944121f,0.124706f},{0.291854f,0.00975253f,0.120977f},{0.291852f,0.00975397f,0.124706f}, +{0.291352f,0.00999456f,0.120977f},{0.290816f,0.0101607f,0.120977f},{0.291349f,0.0099963f,0.124706f}, +{0.290813f,0.010161f,0.124706f},{0.290262f,0.010244f,0.120977f},{0.290261f,0.0102441f,0.124706f}, +{0.289707f,0.0102439f,0.120977f},{0.28916f,0.0101614f,0.120977f},{0.289705f,0.0102436f,0.124706f}, +{0.289157f,0.010161f,0.124706f},{0.288628f,0.0099979f,0.120977f},{0.288628f,0.0099979f,0.124706f}, +{0.288122f,0.00975468f,0.120977f},{0.288122f,0.00975468f,0.124706f},{0.307458f,0.00697787f,0.124706f}, +{0.307653f,0.00731578f,0.124706f},{0.307652f,0.00731414f,0.120977f},{0.307457f,0.0069765f,0.120977f}, +{0.307198f,0.00668793f,0.124706f},{0.307196f,0.00668696f,0.120977f},{0.306881f,0.0064583f,0.120977f}, +{0.306527f,0.00630061f,0.124706f},{0.306882f,0.00645891f,0.124706f},{0.306525f,0.00629975f,0.120977f}, +{0.306145f,0.00621902f,0.124706f},{0.306144f,0.00621892f,0.120977f},{0.305755f,0.00621887f,0.124706f}, +{0.305754f,0.00621902f,0.120977f},{0.305375f,0.00629969f,0.124706f},{0.305374f,0.0062999f,0.120977f}, +{0.305017f,0.0064585f,0.120977f},{0.305017f,0.0064585f,0.124706f},{0.307773f,0.00768493f,0.120977f}, +{0.307814f,0.00807242f,0.120977f},{0.307773f,0.00768652f,0.124706f},{0.307814f,0.00807346f,0.124706f}, +{0.307773f,0.00845934f,0.120977f},{0.307773f,0.0084618f,0.124706f},{0.307653f,0.0088308f,0.120977f}, +{0.307458f,0.00916863f,0.120977f},{0.307652f,0.00883225f,0.124706f},{0.307458f,0.00916944f,0.124706f}, +{0.307198f,0.00945768f,0.120977f},{0.307197f,0.00945846f,0.124706f},{0.306882f,0.00968775f,0.120977f}, +{0.306882f,0.00968775f,0.124706f},{0.304369f,0.0109506f,0.124706f},{0.304649f,0.0114367f,0.124706f}, +{0.304648f,0.0114328f,0.120977f},{0.30402f,0.0105126f,0.124706f},{0.304367f,0.0109474f,0.120977f}, +{0.304019f,0.0105118f,0.120977f},{0.303614f,0.0101356f,0.124706f},{0.303613f,0.0101351f,0.120977f}, +{0.303154f,0.00982233f,0.120977f},{0.303156f,0.00982376f,0.124706f},{0.302655f,0.00958174f,0.124706f}, +{0.301564f,0.00933222f,0.120977f},{0.30101f,0.00933241f,0.124706f},{0.301564f,0.00933231f,0.124706f}, +{0.302651f,0.00958f,0.120977f},{0.302118f,0.00941561f,0.124706f},{0.302116f,0.00941532f,0.120977f}, +{0.301008f,0.0093327f,0.120977f},{0.300462f,0.00941491f,0.124706f},{0.300459f,0.00941526f,0.120977f}, +{0.29993f,0.0095784f,0.120977f},{0.299424f,0.00982161f,0.124706f},{0.29993f,0.0095784f,0.124706f}, +{0.299424f,0.00982161f,0.120977f},{0.304853f,0.0119544f,0.120977f},{0.304976f,0.012495f,0.120977f}, +{0.304853f,0.0119556f,0.124706f},{0.304976f,0.0124959f,0.124706f},{0.305017f,0.0130469f,0.120977f}, +{0.305017f,0.0130492f,0.124706f},{0.304976f,0.0136022f,0.120977f},{0.304852f,0.0141497f,0.120977f}, +{0.304976f,0.0136064f,0.124706f},{0.304851f,0.0141522f,0.124706f},{0.304647f,0.0146713f,0.120977f}, +{0.304646f,0.014672f,0.124706f},{0.304369f,0.0151515f,0.120977f},{0.304024f,0.0155846f,0.120977f}, +{0.304368f,0.0151532f,0.124706f},{0.304023f,0.0155867f,0.124706f},{0.303617f,0.0159633f,0.120977f}, +{0.303617f,0.0159633f,0.124706f},{0.303153f,0.0162801f,0.120977f},{0.303153f,0.0162801f,0.124706f}, +{0.310416f,-0.00185425f,0.124706f},{0.310806f,-0.00185398f,0.124706f},{0.310805f,-0.00185425f,0.120977f}, +{0.310415f,-0.00185398f,0.120977f},{0.310035f,-0.0017734f,0.124706f},{0.310034f,-0.00177278f,0.120977f}, +{0.309678f,-0.0016145f,0.120977f},{0.309364f,-0.0013863f,0.124706f},{0.309679f,-0.00161492f,0.124706f}, +{0.309362f,-0.00138471f,0.120977f},{0.309103f,-0.00109643f,0.124706f},{0.309102f,-0.00109509f,0.120977f}, +{0.308908f,-0.000758756f,0.124706f},{0.308907f,-0.000757801f,0.120977f},{0.308787f,-0.000388892f,0.124706f}, +{0.308787f,-0.000387896f,0.120977f},{0.308746f,2.31914e-018f,0.120977f},{0.308746f,2.31914e-018f,0.124706f}, +{0.311186f,-0.0017734f,0.120977f},{0.311542f,-0.00161492f,0.120977f},{0.311188f,-0.00177278f,0.124706f}, +{0.311543f,-0.0016145f,0.124706f},{0.311857f,-0.0013863f,0.120977f},{0.311859f,-0.00138471f,0.124706f}, +{0.312119f,-0.00109643f,0.120977f},{0.312314f,-0.000758756f,0.120977f},{0.312119f,-0.00109509f,0.124706f}, +{0.312314f,-0.000757801f,0.124706f},{0.312434f,-0.000388892f,0.120977f},{0.312434f,-0.000387896f,0.124706f}, +{0.312475f,2.09082e-018f,0.120977f},{0.312475f,2.09082e-018f,0.124706f},{0.312313f,0.00280711f,0.124706f}, +{0.312873f,0.00280775f,0.124706f},{0.312869f,0.00280711f,0.120977f},{0.311758f,0.00289062f,0.124706f}, +{0.312308f,0.00280775f,0.120977f},{0.311757f,0.00289112f,0.120977f},{0.311229f,0.00305432f,0.124706f}, +{0.311228f,0.00305467f,0.120977f},{0.310728f,0.00329522f,0.120977f},{0.31073f,0.00329432f,0.124706f}, +{0.31027f,0.00360761f,0.124706f},{0.309508f,0.00442796f,0.120977f},{0.309231f,0.00490757f,0.124706f}, +{0.309508f,0.00442732f,0.124706f},{0.310266f,0.00361015f,0.120977f},{0.309858f,0.00398905f,0.124706f}, +{0.309856f,0.00399124f,0.120977f},{0.30923f,0.00490957f,0.120977f},{0.309029f,0.00542319f,0.124706f}, +{0.309028f,0.00542563f,0.120977f},{0.308905f,0.00596545f,0.120977f},{0.308862f,0.00652543f,0.124706f}, +{0.308905f,0.00596545f,0.124706f},{0.308862f,0.00652543f,0.120977f},{0.313423f,0.00289062f,0.120977f}, +{0.313953f,0.00305432f,0.120977f},{0.313425f,0.00289112f,0.124706f},{0.313954f,0.00305467f,0.124706f}, +{0.314452f,0.00329432f,0.120977f},{0.314454f,0.00329522f,0.124706f},{0.314912f,0.00360761f,0.120977f}, +{0.315324f,0.00398905f,0.120977f},{0.314916f,0.00361015f,0.124706f},{0.315326f,0.00399124f,0.124706f}, +{0.315673f,0.00442732f,0.120977f},{0.315674f,0.00442796f,0.124706f},{0.315951f,0.00490757f,0.120977f}, +{0.316153f,0.00542319f,0.120977f},{0.315951f,0.00490957f,0.124706f},{0.316154f,0.00542563f,0.124706f}, +{0.316277f,0.00596545f,0.120977f},{0.316277f,0.00596545f,0.124706f},{0.31632f,0.00652543f,0.120977f}, +{0.31632f,0.00652543f,0.124706f},{0.301289f,0.00279661f,0.0995366f},{0.301289f,0.00279661f,0.0976722f}, +{0.3008f,0.00275356f,0.0976722f},{0.300331f,0.00262748f,0.0976722f},{0.300801f,0.00275376f,0.0995366f}, +{0.300332f,0.00262801f,0.0995366f},{0.299893f,0.00242333f,0.0995366f},{0.299493f,0.00214411f,0.0995366f}, +{0.299891f,0.00242266f,0.0976722f},{0.299491f,0.00214219f,0.0976722f},{0.299146f,0.00179767f,0.0995366f}, +{0.299144f,0.00179504f,0.0976722f},{0.298866f,0.00139727f,0.0995366f},{0.298661f,0.000957717f,0.0995366f}, +{0.298865f,0.00139564f,0.0976722f},{0.298661f,0.000956449f,0.0976722f},{0.298535f,0.000488516f,0.0995366f}, +{0.298535f,0.000488516f,0.0976722f},{0.298492f,2.50765e-018f,0.0976722f},{0.298492f,2.50765e-018f,0.0995366f}, +{0.301777f,0.00275356f,0.0995366f},{0.302246f,0.00262748f,0.0995366f},{0.301776f,0.00275376f,0.0976722f}, +{0.302684f,0.00242333f,0.0976722f},{0.302245f,0.00262801f,0.0976722f},{0.302686f,0.00242266f,0.0995366f}, +{0.303084f,0.00214411f,0.0976722f},{0.303086f,0.00214219f,0.0995366f},{0.303431f,0.00179767f,0.0976722f}, +{0.303711f,0.00139727f,0.0976722f},{0.303433f,0.00179504f,0.0995366f},{0.303712f,0.00139564f,0.0995366f}, +{0.303916f,0.000957717f,0.0976722f},{0.303917f,0.000956449f,0.0995366f},{0.304042f,0.000488516f,0.0976722f}, +{0.304042f,0.000488516f,0.0995366f},{0.304085f,2.16517e-018f,0.0995366f},{0.304085f,2.16517e-018f,0.0976722f}, +{0.301289f,0.00745764f,0.0995366f},{0.300551f,0.00742114f,0.0995366f},{0.301289f,0.00745764f,0.100469f}, +{0.300551f,0.00742114f,0.100469f},{0.299827f,0.00731301f,0.0995366f},{0.29912f,0.00713527f,0.0995366f}, +{0.299827f,0.00731301f,0.100469f},{0.298435f,0.00688994f,0.0995366f},{0.29912f,0.00713527f,0.100469f}, +{0.298435f,0.00688994f,0.100469f},{0.297777f,0.00657906f,0.0995366f},{0.297151f,0.00620465f,0.0995366f}, +{0.297777f,0.00657906f,0.100469f},{0.296562f,0.00576874f,0.0995366f},{0.297151f,0.00620465f,0.100469f}, +{0.296562f,0.00576874f,0.100469f},{0.296015f,0.00527335f,0.0995366f},{0.29552f,0.00472635f,0.0995366f}, +{0.296015f,0.00527335f,0.100469f},{0.295084f,0.00413751f,0.0995366f},{0.29552f,0.00472635f,0.100469f}, +{0.295084f,0.00413751f,0.100469f},{0.294709f,0.00351173f,0.0995366f},{0.294399f,0.00285391f,0.0995366f}, +{0.294709f,0.00351173f,0.100469f},{0.294153f,0.00216893f,0.0995366f},{0.294399f,0.00285391f,0.100469f}, +{0.294153f,0.00216893f,0.100469f},{0.293976f,0.00146169f,0.0995366f},{0.293867f,0.000737081f,0.0995366f}, +{0.293976f,0.00146169f,0.100469f},{0.293831f,3.07846e-018f,0.0995366f},{0.293867f,0.000737081f,0.100469f}, +{0.293831f,3.07846e-018f,0.100469f},{0.302026f,0.00742114f,0.100469f},{0.30275f,0.00731301f,0.100469f}, +{0.302026f,0.00742114f,0.0995366f},{0.303457f,0.00713527f,0.100469f},{0.30275f,0.00731301f,0.0995366f}, +{0.303457f,0.00713527f,0.0995366f},{0.304142f,0.00688994f,0.100469f},{0.3048f,0.00657906f,0.100469f}, +{0.304142f,0.00688994f,0.0995366f},{0.305426f,0.00620465f,0.100469f},{0.3048f,0.00657906f,0.0995366f}, +{0.305426f,0.00620465f,0.0995366f},{0.306015f,0.00576874f,0.100469f},{0.306562f,0.00527335f,0.100469f}, +{0.306015f,0.00576874f,0.0995366f},{0.307057f,0.00472635f,0.100469f},{0.306562f,0.00527335f,0.0995366f}, +{0.307057f,0.00472635f,0.0995366f},{0.307493f,0.00413751f,0.100469f},{0.307868f,0.00351173f,0.100469f}, +{0.307493f,0.00413751f,0.0995366f},{0.308178f,0.00285391f,0.100469f},{0.307868f,0.00351173f,0.0995366f}, +{0.308178f,0.00285391f,0.0995366f},{0.308424f,0.00216893f,0.100469f},{0.308602f,0.00146169f,0.100469f}, +{0.308424f,0.00216893f,0.0995366f},{0.30871f,0.000737081f,0.100469f},{0.308602f,0.00146169f,0.0995366f}, +{0.30871f,0.000737081f,0.0995366f},{0.308746f,2.16517e-018f,0.100469f},{0.308746f,2.16517e-018f,0.0995366f}, +{0.296668f,0.0173925f,0.100469f},{0.296668f,0.0173922f,0.103265f},{0.296628f,0.0167797f,0.100469f}, +{0.296668f,0.0161668f,0.103265f},{0.296668f,0.0161672f,0.100469f},{0.296628f,0.0167797f,0.103265f}, +{0.296982f,0.014996f,0.100469f},{0.296982f,0.014996f,0.103265f},{0.29725f,0.0144523f,0.100469f}, +{0.296787f,0.0155699f,0.103265f},{0.296787f,0.0155702f,0.100469f},{0.29725f,0.0144519f,0.103265f}, +{0.297588f,0.0139455f,0.103265f},{0.297588f,0.0139458f,0.100469f},{0.297993f,0.0134838f,0.100469f}, +{0.297993f,0.0134838f,0.103265f},{0.298455f,0.0130791f,0.103265f},{0.298454f,0.0130793f,0.100469f}, +{0.298961f,0.0127415f,0.100469f},{0.298961f,0.0127414f,0.103265f},{0.299505f,0.0124735f,0.100469f}, +{0.299505f,0.0124735f,0.103265f},{0.300079f,0.0122783f,0.103265f},{0.300079f,0.0122784f,0.100469f}, +{0.301289f,0.0121187f,0.100469f},{0.300676f,0.0121592f,0.100469f},{0.300676f,0.012159f,0.103265f}, +{0.301289f,0.0121187f,0.103265f},{0.296787f,0.0179891f,0.103265f},{0.296787f,0.0179895f,0.100469f}, +{0.296982f,0.0185634f,0.103265f},{0.29725f,0.0191071f,0.103265f},{0.296982f,0.0185634f,0.100469f}, +{0.29725f,0.0191075f,0.100469f},{0.297588f,0.0196135f,0.103265f},{0.297588f,0.0196139f,0.100469f}, +{0.297993f,0.0200755f,0.103265f},{0.298454f,0.0204801f,0.103265f},{0.297993f,0.0200755f,0.100469f}, +{0.298455f,0.0204802f,0.100469f},{0.298961f,0.0208179f,0.103265f},{0.298961f,0.020818f,0.100469f}, +{0.299505f,0.0210859f,0.103265f},{0.300079f,0.0212809f,0.103265f},{0.299505f,0.0210859f,0.100469f}, +{0.300079f,0.0212811f,0.100469f},{0.300676f,0.0214002f,0.103265f},{0.300676f,0.0214003f,0.100469f}, +{0.301289f,0.0214407f,0.103265f},{0.301289f,0.0214407f,0.100469f},{0.318681f,0.00462066f,0.100469f}, +{0.318068f,0.00466102f,0.100469f},{0.318681f,0.00462066f,0.103265f},{0.317455f,0.00462052f,0.103265f}, +{0.318068f,0.00466102f,0.103265f},{0.317455f,0.00462052f,0.100469f},{0.316285f,0.00430621f,0.100469f}, +{0.31574f,0.00403818f,0.100469f},{0.316285f,0.00430621f,0.103265f},{0.316858f,0.00450127f,0.103265f}, +{0.316858f,0.00450127f,0.100469f},{0.31574f,0.00403818f,0.103265f},{0.315234f,0.00370041f,0.100469f}, +{0.315234f,0.00370041f,0.103265f},{0.314772f,0.00329584f,0.100469f},{0.314772f,0.00329584f,0.103265f}, +{0.314368f,0.00283386f,0.100469f},{0.314368f,0.00283386f,0.103265f},{0.31403f,0.00232743f,0.100469f}, +{0.313762f,0.00178369f,0.100469f},{0.31403f,0.00232743f,0.103265f},{0.313762f,0.00178369f,0.103265f}, +{0.313567f,0.00120944f,0.100469f},{0.313567f,0.00120944f,0.103265f},{0.313407f,1.10315e-019f,0.100469f}, +{0.313448f,0.000612502f,0.103265f},{0.313448f,0.000612502f,0.100469f},{0.313407f,1.10315e-019f,0.103265f}, +{0.319278f,0.00450141f,0.103265f},{0.319852f,0.00430621f,0.103265f},{0.319278f,0.00450141f,0.100469f}, +{0.320396f,0.00403832f,0.103265f},{0.319852f,0.00430621f,0.100469f},{0.320396f,0.00403832f,0.100469f}, +{0.320902f,0.00370055f,0.103265f},{0.321364f,0.00329584f,0.103265f},{0.320902f,0.00370055f,0.100469f}, +{0.321769f,0.0028342f,0.103265f},{0.321364f,0.00329584f,0.100469f},{0.321769f,0.0028342f,0.100469f}, +{0.322106f,0.00232777f,0.103265f},{0.322374f,0.00178369f,0.103265f},{0.322106f,0.00232777f,0.100469f}, +{0.322569f,0.00120978f,0.103265f},{0.322374f,0.00178369f,0.100469f},{0.322569f,0.00120978f,0.100469f}, +{0.322689f,0.000612842f,0.103265f},{0.322729f,6.81126e-019f,0.103265f},{0.322689f,0.000612842f,0.100469f}, +{0.322729f,6.81126e-019f,0.100469f},{0.305909f,-0.0173922f,0.103265f},{0.30595f,-0.0167797f,0.103265f}, +{0.305936f,-0.0171394f,0.100469f},{0.305877f,-0.0159621f,0.100469f},{0.305944f,-0.0165489f,0.100469f}, +{0.305909f,-0.0161668f,0.103265f},{0.305595f,-0.014996f,0.103265f},{0.305327f,-0.0144519f,0.103265f}, +{0.305525f,-0.0148373f,0.100469f},{0.305737f,-0.0153885f,0.100469f},{0.30579f,-0.0155699f,0.103265f}, +{0.304989f,-0.0139455f,0.103265f},{0.304902f,-0.0138368f,0.100469f},{0.305246f,-0.0143174f,0.100469f}, +{0.304584f,-0.0134838f,0.103265f},{0.304122f,-0.0130791f,0.103265f},{0.304049f,-0.0130241f,0.100469f}, +{0.304501f,-0.0134033f,0.100469f},{0.303616f,-0.0127414f,0.103265f},{0.303072f,-0.0124735f,0.103265f}, +{0.303552f,-0.0127048f,0.100469f},{0.302498f,-0.0122783f,0.103265f},{0.302457f,-0.0122704f,0.100469f}, +{0.303018f,-0.0124544f,0.100469f},{0.301878f,-0.0121554f,0.100469f},{0.301901f,-0.012159f,0.103265f}, +{0.301289f,-0.0121187f,0.103265f},{0.301289f,-0.0121187f,0.100469f},{0.305853f,-0.0177242f,0.100469f}, +{0.305697f,-0.018294f,0.100469f},{0.30579f,-0.0179891f,0.103265f},{0.305595f,-0.0185634f,0.103265f}, +{0.30547f,-0.0188393f,0.100469f},{0.305176f,-0.0193514f,0.100469f},{0.305327f,-0.0191071f,0.103265f}, +{0.30482f,-0.0198223f,0.100469f},{0.304989f,-0.0196135f,0.103265f},{0.304584f,-0.0200755f,0.103265f}, +{0.304407f,-0.0202443f,0.100469f},{0.303944f,-0.0206107f,0.100469f},{0.304123f,-0.0204801f,0.103265f}, +{0.303438f,-0.0209155f,0.100469f},{0.303616f,-0.0208179f,0.103265f},{0.303072f,-0.0210859f,0.103265f}, +{0.302898f,-0.0211542f,0.100469f},{0.302329f,-0.0213103f,0.100469f},{0.302498f,-0.0212809f,0.103265f}, +{0.30175f,-0.0214362f,0.100469f},{0.301901f,-0.0214002f,0.103265f},{0.301289f,-0.0214407f,0.103265f}, +{0.301289f,-0.0214407f,0.100469f},{0.2869f,0.0125242f,0.109791f},{0.28691f,0.01233f,0.100469f}, +{0.28691f,0.0127201f,0.100469f},{0.286992f,0.0131013f,0.100469f},{0.286936f,0.0128878f,0.109791f}, +{0.287041f,0.0132379f,0.109791f},{0.28738f,0.0137725f,0.100469f},{0.287214f,0.0135608f,0.109791f}, +{0.28715f,0.0134567f,0.100469f},{0.287669f,0.014033f,0.100469f},{0.287446f,0.0138436f,0.109791f}, +{0.287728f,0.0140755f,0.109791f},{0.288007f,0.0142276f,0.100469f},{0.288376f,0.0143478f,0.100469f}, +{0.288051f,0.0142478f,0.109791f},{0.288764f,0.0143886f,0.100469f},{0.288764f,0.0143886f,0.109791f}, +{0.288401f,0.0143539f,0.109791f},{0.286936f,0.01216f,0.109791f},{0.286991f,0.0119486f,0.100469f}, +{0.287043f,0.0118103f,0.109791f},{0.287216f,0.0114885f,0.109791f},{0.287149f,0.0115926f,0.100469f}, +{0.287448f,0.0112063f,0.109791f},{0.287378f,0.0112779f,0.100469f},{0.287668f,0.0110163f,0.100469f}, +{0.28773f,0.0109746f,0.109791f},{0.288052f,0.0108025f,0.109791f},{0.288006f,0.0108212f,0.100469f}, +{0.288401f,0.0106963f,0.109791f},{0.288375f,0.0107009f,0.100469f},{0.288764f,0.0106598f,0.100469f}, +{0.288764f,0.0106598f,0.109791f},{0.288764f,0.0125242f,0.110911f},{0.309971f,0.0105467f,0.109791f}, +{0.309981f,0.0103525f,0.100469f},{0.309981f,0.0107426f,0.100469f},{0.310062f,0.0111238f,0.100469f}, +{0.310007f,0.0109103f,0.109791f},{0.310112f,0.0112604f,0.109791f},{0.310451f,0.011795f,0.100469f}, +{0.310284f,0.0115833f,0.109791f},{0.310221f,0.0114792f,0.100469f},{0.31074f,0.0120555f,0.100469f}, +{0.310517f,0.0118661f,0.109791f},{0.310799f,0.012098f,0.109791f},{0.311077f,0.0122501f,0.100469f}, +{0.311447f,0.0123703f,0.100469f},{0.311122f,0.0122703f,0.109791f},{0.311835f,0.0124111f,0.100469f}, +{0.311835f,0.0124111f,0.109791f},{0.311472f,0.0123763f,0.109791f},{0.310007f,0.0101825f,0.109791f}, +{0.310062f,0.00997107f,0.100469f},{0.310114f,0.00983283f,0.109791f},{0.310287f,0.00951095f,0.109791f}, +{0.31022f,0.00961513f,0.100469f},{0.310519f,0.00922876f,0.109791f},{0.310449f,0.00930035f,0.100469f}, +{0.310739f,0.00903878f,0.100469f},{0.310801f,0.0089971f,0.109791f},{0.311123f,0.008825f,0.109791f}, +{0.311076f,0.00884365f,0.100469f},{0.311472f,0.00871884f,0.109791f},{0.311446f,0.00872342f,0.100469f}, +{0.311835f,0.00868228f,0.100469f},{0.311835f,0.00868228f,0.109791f},{0.311835f,0.0105467f,0.110911f}, +{0.311948f,-0.0125242f,0.109791f},{0.311958f,-0.0127183f,0.100469f},{0.311959f,-0.0123283f,0.100469f}, +{0.31204f,-0.0119471f,0.100469f},{0.311984f,-0.0121606f,0.109791f},{0.31209f,-0.0118105f,0.109791f}, +{0.312428f,-0.0112759f,0.100469f},{0.312262f,-0.0114876f,0.109791f},{0.312198f,-0.0115917f,0.100469f}, +{0.312718f,-0.0110154f,0.100469f},{0.312494f,-0.0112048f,0.109791f},{0.312777f,-0.0109729f,0.109791f}, +{0.313055f,-0.0108208f,0.100469f},{0.313425f,-0.0107006f,0.100469f},{0.313099f,-0.0108006f,0.109791f}, +{0.313813f,-0.0106598f,0.100469f},{0.313813f,-0.0106598f,0.109791f},{0.313449f,-0.0106945f,0.109791f}, +{0.311985f,-0.0128884f,0.109791f},{0.312039f,-0.0130998f,0.100469f},{0.312092f,-0.0132381f,0.109791f}, +{0.312264f,-0.0135599f,0.109791f},{0.312198f,-0.0134558f,0.100469f},{0.312496f,-0.0138421f,0.109791f}, +{0.312426f,-0.0137705f,0.100469f},{0.312716f,-0.0140321f,0.100469f},{0.312778f,-0.0140738f,0.109791f}, +{0.3131f,-0.0142459f,0.109791f},{0.313054f,-0.0142272f,0.100469f},{0.31345f,-0.0143521f,0.109791f}, +{0.313424f,-0.0143475f,0.100469f},{0.313813f,-0.0143886f,0.100469f},{0.313813f,-0.0143886f,0.109791f}, +{0.313813f,-0.0125242f,0.110911f},{0.288877f,-0.0105467f,0.109791f},{0.288888f,-0.0107408f,0.100469f}, +{0.288888f,-0.0103508f,0.100469f},{0.288969f,-0.0099696f,0.100469f},{0.288913f,-0.010183f,0.109791f}, +{0.289019f,-0.00983297f,0.109791f},{0.289357f,-0.00929843f,0.100469f},{0.289191f,-0.00951009f,0.109791f}, +{0.289127f,-0.00961418f,0.100469f},{0.289647f,-0.00903788f,0.100469f},{0.289423f,-0.0092273f,0.109791f}, +{0.289706f,-0.00899543f,0.109791f},{0.289984f,-0.00884326f,0.100469f},{0.290354f,-0.0087231f,0.100469f}, +{0.290028f,-0.00882313f,0.109791f},{0.290742f,-0.00868228f,0.100469f},{0.290742f,-0.00868228f,0.109791f}, +{0.290378f,-0.00871703f,0.109791f},{0.288914f,-0.0109109f,0.109791f},{0.288968f,-0.0111223f,0.100469f}, +{0.289021f,-0.0112606f,0.109791f},{0.289193f,-0.0115824f,0.109791f},{0.289127f,-0.0114782f,0.100469f}, +{0.289425f,-0.0118646f,0.109791f},{0.289356f,-0.011793f,0.100469f},{0.289645f,-0.0120546f,0.100469f}, +{0.289707f,-0.0120963f,0.109791f},{0.290029f,-0.0122684f,0.109791f},{0.289983f,-0.0122497f,0.100469f}, +{0.290379f,-0.0123745f,0.109791f},{0.290353f,-0.01237f,0.100469f},{0.290742f,-0.0124111f,0.100469f}, +{0.290742f,-0.0124111f,0.109791f},{0.290742f,-0.0105467f,0.110911f},{0.283896f,-0.00462052f,0.100469f}, +{0.283896f,-0.00462066f,0.103265f},{0.284509f,-0.00466102f,0.100469f},{0.285122f,-0.00462052f,0.103265f}, +{0.285121f,-0.00462066f,0.100469f},{0.284509f,-0.00466102f,0.103265f},{0.286293f,-0.00430621f,0.100469f}, +{0.286293f,-0.00430621f,0.103265f},{0.286836f,-0.00403832f,0.100469f},{0.285719f,-0.00450127f,0.103265f}, +{0.285718f,-0.00450141f,0.100469f},{0.286837f,-0.00403818f,0.103265f},{0.287343f,-0.00370041f,0.103265f}, +{0.287343f,-0.00370055f,0.100469f},{0.287805f,-0.00329584f,0.100469f},{0.287805f,-0.00329584f,0.103265f}, +{0.288209f,-0.00283386f,0.103265f},{0.288209f,-0.0028342f,0.100469f},{0.288547f,-0.00232777f,0.100469f}, +{0.288547f,-0.00232743f,0.103265f},{0.288815f,-0.00178369f,0.100469f},{0.288815f,-0.00178369f,0.103265f}, +{0.28901f,-0.00120944f,0.103265f},{0.28901f,-0.00120978f,0.100469f},{0.28917f,2.73598e-018f,0.100469f}, +{0.289129f,-0.000612842f,0.100469f},{0.28913f,-0.000612502f,0.103265f},{0.28917f,2.73598e-018f,0.103265f}, +{0.283299f,-0.00450141f,0.103265f},{0.283299f,-0.00450127f,0.100469f},{0.282725f,-0.00430621f,0.103265f}, +{0.282181f,-0.00403832f,0.103265f},{0.282725f,-0.00430621f,0.100469f},{0.282181f,-0.00403818f,0.100469f}, +{0.281675f,-0.00370055f,0.103265f},{0.281675f,-0.00370041f,0.100469f},{0.281213f,-0.00329584f,0.103265f}, +{0.280808f,-0.0028342f,0.103265f},{0.281213f,-0.00329584f,0.100469f},{0.280808f,-0.00283386f,0.100469f}, +{0.280471f,-0.00232777f,0.103265f},{0.280471f,-0.00232743f,0.100469f},{0.280203f,-0.00178369f,0.103265f}, +{0.280008f,-0.00120978f,0.103265f},{0.280203f,-0.00178369f,0.100469f},{0.280007f,-0.00120944f,0.100469f}, +{0.279888f,-0.000612842f,0.103265f},{0.279888f,-0.000612502f,0.100469f},{0.279848f,2.16517e-018f,0.103265f}, +{0.279848f,2.16517e-018f,0.100469f},{0.326779f,0.00272711f,0.120977f},{0.326887f,0.00137858f,0.119113f}, +{0.326777f,0.00274679f,0.119113f},{0.326344f,0.00542344f,0.120977f},{0.32634f,0.00544141f,0.119113f}, +{0.326016f,0.00676244f,0.119113f},{0.326888f,0.00136573f,0.120977f},{0.326924f,5.30462e-018f,0.119113f}, +{0.326924f,1.3464e-013f,0.120977f},{0.326597f,0.0040808f,0.120977f},{0.326594f,0.00410196f,0.119113f}, +{0.325479f,0.00848488f,0.120977f},{0.325943f,0.00696342f,0.120977f},{0.325623f,0.00806238f,0.119113f}, +{0.32349f,0.0128178f,0.120977f},{0.324242f,0.0114155f,0.120977f},{0.324042f,0.0118088f,0.119113f}, +{0.324906f,0.00996949f,0.120977f},{0.325163f,0.00933854f,0.119113f},{0.324635f,0.0105882f,0.119113f}, +{0.321881f,0.0152688f,0.119113f},{0.321037f,0.0163461f,0.119113f},{0.321731f,0.0154686f,0.120977f}, +{0.323385f,0.0129975f,0.119113f},{0.322664f,0.0141518f,0.119113f},{0.322652f,0.0141704f,0.120977f}, +{0.31917f,0.0183698f,0.119113f},{0.318513f,0.0189869f,0.120977f},{0.319652f,0.017875f,0.120977f}, +{0.320132f,0.0173811f,0.119113f},{0.320732f,0.0167072f,0.120977f},{0.315039f,0.0216356f,0.120977f}, +{0.316831f,0.0203871f,0.120977f},{0.316004f,0.0209918f,0.119113f},{0.318157f,0.0193037f,0.119113f}, +{0.312491f,0.0230585f,0.119113f},{0.311255f,0.0236188f,0.119113f},{0.311174f,0.0236531f,0.120977f}, +{0.313696f,0.0224332f,0.119113f},{0.31315f,0.0227263f,0.120977f},{0.307393f,0.0248983f,0.119113f}, +{0.307414f,0.024878f,0.120977f},{0.308704f,0.0245398f,0.119113f},{0.309119f,0.0244103f,0.120977f}, +{0.309992f,0.0241129f,0.119113f},{0.303937f,0.0254985f,0.120977f},{0.304714f,0.0254058f,0.119113f}, +{0.303352f,0.0255525f,0.119113f},{0.306062f,0.0251874f,0.119113f},{0.305688f,0.0252555f,0.120977f}, +{0.302173f,0.0256204f,0.120977f},{0.300598f,0.0256263f,0.119113f},{0.300405f,0.0256204f,0.120977f}, +{0.301978f,0.0256264f,0.119113f},{0.297862f,0.0254057f,0.119113f},{0.296515f,0.0251873f,0.119113f}, +{0.29689f,0.0252554f,0.120977f},{0.298641f,0.0254985f,0.120977f},{0.299224f,0.0255524f,0.119113f}, +{0.292585f,0.0241129f,0.119113f},{0.293458f,0.0244103f,0.120977f},{0.293873f,0.0245398f,0.119113f}, +{0.295161f,0.0248864f,0.120977f},{0.295184f,0.0248983f,0.119113f},{0.289427f,0.0227264f,0.120977f}, +{0.291404f,0.0236533f,0.120977f},{0.290086f,0.0230584f,0.119113f},{0.291322f,0.0236187f,0.119113f}, +{0.287538f,0.0216357f,0.120977f},{0.287709f,0.0217438f,0.119113f},{0.286573f,0.0209917f,0.119113f}, +{0.288881f,0.0224331f,0.119113f},{0.28442f,0.0193036f,0.119113f},{0.283407f,0.0183692f,0.119113f}, +{0.284064f,0.0189869f,0.120977f},{0.285747f,0.0203873f,0.120977f},{0.285476f,0.020178f,0.119113f}, +{0.282444f,0.0173806f,0.119113f},{0.28154f,0.016346f,0.119113f},{0.281845f,0.0167073f,0.120977f}, +{0.282931f,0.0178697f,0.120977f},{0.280846f,0.0154687f,0.120977f},{0.280696f,0.0152688f,0.119113f}, +{0.279913f,0.0141517f,0.119113f},{0.279926f,0.0141707f,0.120977f},{0.279192f,0.0129974f,0.119113f}, +{0.279087f,0.0128178f,0.120977f},{0.278535f,0.0118086f,0.119113f},{0.278335f,0.0114158f,0.120977f}, +{0.277671f,0.0099697f,0.120977f},{0.277942f,0.010588f,0.119113f},{0.277414f,0.00933828f,0.119113f}, +{0.277098f,0.00848516f,0.120977f},{0.276954f,0.00806211f,0.119113f},{0.276627f,0.00696571f,0.120977f}, +{0.276233f,0.00542344f,0.120977f},{0.276561f,0.00676218f,0.119113f},{0.275983f,0.00410176f,0.119113f}, +{0.276237f,0.00544117f,0.119113f},{0.2758f,0.00274665f,0.119113f},{0.27598f,0.00408095f,0.120977f}, +{0.275798f,0.00272732f,0.120977f},{0.27569f,0.0013785f,0.119113f},{0.275653f,2.16517e-018f,0.119113f}, +{0.275689f,0.00136552f,0.120977f},{0.275653f,-1.34633e-013f,0.120977f},{0.314868f,0.0217439f,0.119113f}, +{0.317101f,0.0201781f,0.119113f},{0.325992f,-3.74266e-017f,0.103079f},{0.32739f,-6.52846e-018f,0.104198f}, +{0.327333f,-0.00172399f,0.104198f},{0.316166f,0.0173288f,0.101587f},{0.315415f,0.0161291f,0.100469f}, +{0.314325f,0.0170222f,0.100469f},{0.316449f,0.0151609f,0.100469f},{0.314477f,0.0186467f,0.101587f}, +{0.31577f,0.0217163f,0.104198f},{0.31364f,0.0213938f,0.103079f},{0.314323f,0.0226142f,0.104198f}, +{0.313184f,0.0178384f,0.100469f},{0.312708f,0.0197792f,0.101587f},{0.312824f,0.0234144f,0.104198f}, +{0.310764f,0.0192333f,0.100469f},{0.311277f,0.0241148f,0.104198f},{0.309494f,0.0198086f,0.100469f}, +{0.309689f,0.0247131f,0.104198f},{0.308188f,0.0203001f,0.100469f},{0.306853f,0.0207061f,0.100469f}, +{0.308063f,0.0252074f,0.104198f},{0.305491f,0.0210249f,0.100469f},{0.306404f,0.0255955f,0.104198f}, +{0.30472f,0.0258753f,0.104198f},{0.304107f,0.0212548f,0.100469f},{0.303013f,0.0260447f,0.104198f}, +{0.302704f,0.021394f,0.100469f},{0.301289f,0.0261017f,0.104198f},{0.317749f,0.0158329f,0.101587f}, +{0.317418f,0.0141266f,0.100469f},{0.319198f,0.0141734f,0.101587f},{0.318311f,0.0130367f,0.100469f}, +{0.319127f,0.0118953f,0.100469f},{0.320489f,0.0123685f,0.101587f},{0.319865f,0.010707f,0.100469f}, +{0.3216f,0.0104425f,0.101587f},{0.320522f,0.00947547f,0.100469f},{0.322518f,0.00842229f,0.101587f}, +{0.321097f,0.00820499f,0.100469f},{0.326496f,0.00677384f,0.104198f},{0.326884f,0.00511591f,0.104198f}, +{0.325567f,0.0045642f,0.103079f},{0.323231f,0.00633756f,0.101587f},{0.321589f,0.0069f,0.100469f}, +{0.323734f,0.00421935f,0.101587f},{0.321995f,0.00556442f,0.100469f},{0.322313f,0.00420236f,0.100469f}, +{0.324031f,0.00209692f,0.101587f},{0.322543f,0.00281829f,0.100469f},{0.327333f,0.00172376f,0.104198f}, +{0.324128f,-3.56201e-017f,0.101587f},{0.322682f,0.00141614f,0.100469f},{0.322535f,-0.00288015f,0.100469f}, +{0.322681f,-0.00144343f,0.100469f},{0.327164f,-0.00343096f,0.104198f},{0.321524f,-0.00708591f,0.100469f}, +{0.321955f,-0.00570761f,0.100469f},{0.326002f,-0.0084f,0.104198f},{0.322293f,-0.00430368f,0.100469f}, +{0.326884f,-0.00511591f,0.104198f},{0.326496f,-0.00677408f,0.104198f},{0.320389f,-0.00973971f,0.100469f}, +{0.323903f,-0.0130346f,0.104198f},{0.31969f,-0.0110032f,0.100469f},{0.325403f,-0.00998868f,0.104198f}, +{0.324703f,-0.0115354f,0.104198f},{0.321002f,-0.00843197f,0.100469f},{0.322011f,-0.0158708f,0.104198f}, +{0.320924f,-0.0171976f,0.104198f},{0.318046f,-0.0133753f,0.100469f},{0.318908f,-0.012217f,0.100469f}, +{0.323005f,-0.0144813f,0.104198f},{0.317159f,-0.0207227f,0.104198f},{0.31502f,-0.0164663f,0.100469f}, +{0.318486f,-0.0196355f,0.104198f},{0.316097f,-0.0155046f,0.100469f},{0.317107f,-0.0144728f,0.100469f}, +{0.319745f,-0.0184567f,0.104198f},{0.311436f,-0.0188871f,0.100469f},{0.312684f,-0.0181615f,0.100469f}, +{0.312708f,-0.0197792f,0.101587f},{0.313881f,-0.0173533f,0.100469f},{0.31364f,-0.0213938f,0.103079f}, +{0.314323f,-0.0226143f,0.104198f},{0.312269f,-0.0221291f,0.103079f},{0.310832f,-0.0227855f,0.103079f}, +{0.311277f,-0.0241148f,0.104198f},{0.309337f,-0.0233556f,0.103079f},{0.312824f,-0.0234145f,0.104198f}, +{0.307791f,-0.0238322f,0.103079f},{0.308062f,-0.0252075f,0.104198f},{0.306203f,-0.0242096f,0.103079f}, +{0.309688f,-0.0247132f,0.104198f},{0.304583f,-0.0244827f,0.103079f},{0.306404f,-0.0255955f,0.104198f}, +{0.304719f,-0.0258754f,0.104198f},{0.303012f,-0.0260448f,0.104198f},{0.302942f,-0.0246481f,0.103079f}, +{0.301289f,-0.0261017f,0.104198f},{0.301289f,-0.0247034f,0.103079f},{0.31577f,-0.0217163f,0.104198f}, +{0.305832f,-0.0223824f,0.101587f},{0.306042f,-0.0209041f,0.100469f},{0.3073f,-0.0220336f,0.101587f}, +{0.304335f,-0.022635f,0.101587f},{0.304624f,-0.0211784f,0.100469f},{0.303191f,-0.0213558f,0.100469f}, +{0.302817f,-0.0227878f,0.101587f},{0.301289f,-0.022839f,0.101587f},{0.307439f,-0.0205399f,0.100469f}, +{0.308807f,-0.0200791f,0.100469f},{0.310112f,-0.0210659f,0.101587f},{0.308729f,-0.0215929f,0.101587f}, +{0.310142f,-0.0195273f,0.100469f},{0.31144f,-0.0204589f,0.101587f},{0.315552f,0.0201691f,0.103079f}, +{0.311995f,0.018576f,0.100469f},{0.31738f,0.0187435f,0.103079f},{0.317159f,0.0207226f,0.104198f}, +{0.319745f,0.0184567f,0.104198f},{0.318486f,0.0196354f,0.104198f},{0.319092f,0.017126f,0.103079f}, +{0.320659f,0.015331f,0.103079f},{0.320924f,0.0171974f,0.104198f},{0.323005f,0.0144813f,0.104198f}, +{0.322011f,0.0158706f,0.104198f},{0.322055f,0.0133791f,0.103079f},{0.323258f,0.011296f,0.103079f}, +{0.323903f,0.0130343f,0.104198f},{0.324703f,0.0115351f,0.104198f},{0.324251f,0.00911062f,0.103079f}, +{0.325403f,0.00998868f,0.104198f},{0.325022f,0.00685616f,0.103079f},{0.326002f,0.00839976f,0.104198f}, +{0.325888f,0.00226928f,0.103079f},{0.327164f,0.00343072f,0.104198f},{0.322729f,3.81816e-017f,0.104198f}, +{0.322729f,-7.35642e-018f,0.10513f},{0.322692f,-0.00125938f,0.10513f},{0.322582f,-0.00250813f,0.10513f}, +{0.322692f,-0.00125925f,0.104198f},{0.3224f,-0.00374334f,0.10513f},{0.322582f,-0.00250793f,0.104198f}, +{0.3224f,-0.00374312f,0.104198f},{0.322147f,-0.00496208f,0.10513f},{0.321825f,-0.00616144f,0.10513f}, +{0.322147f,-0.00496191f,0.104198f},{0.321434f,-0.00733859f,0.10513f},{0.321825f,-0.00616138f,0.104198f}, +{0.321434f,-0.0073385f,0.104198f},{0.320976f,-0.00849054f,0.10513f},{0.320453f,-0.0096143f,0.10513f}, +{0.320976f,-0.00849036f,0.104198f},{0.319865f,-0.010707f,0.10513f},{0.320453f,-0.00961408f,0.104198f}, +{0.319865f,-0.0107068f,0.104198f},{0.319213f,-0.0117656f,0.10513f},{0.318499f,-0.0127873f,0.10513f}, +{0.319213f,-0.0117655f,0.104198f},{0.317724f,-0.0137693f,0.10513f},{0.318499f,-0.0127873f,0.104198f}, +{0.317724f,-0.0137691f,0.104198f},{0.316888f,-0.0147088f,0.10513f},{0.315997f,-0.0156004f,0.10513f}, +{0.316889f,-0.0147082f,0.104198f},{0.315058f,-0.0164352f,0.10513f},{0.315997f,-0.0155998f,0.104198f}, +{0.315058f,-0.0164352f,0.104198f},{0.314076f,-0.0172102f,0.10513f},{0.313054f,-0.0179243f,0.10513f}, +{0.314076f,-0.0172102f,0.104198f},{0.311995f,-0.018576f,0.10513f},{0.313054f,-0.0179242f,0.104198f}, +{0.311996f,-0.018576f,0.104198f},{0.310903f,-0.0191643f,0.10513f},{0.309779f,-0.019688f,0.10513f}, +{0.310903f,-0.0191643f,0.104198f},{0.308627f,-0.0201457f,0.10513f},{0.309779f,-0.0196879f,0.104198f}, +{0.308627f,-0.0201457f,0.104198f},{0.30745f,-0.0205363f,0.10513f},{0.30625f,-0.0208587f,0.10513f}, +{0.30745f,-0.0205363f,0.104198f},{0.306251f,-0.0208586f,0.104198f},{0.305032f,-0.0211114f,0.104198f}, +{0.303797f,-0.0212935f,0.104198f},{0.305032f,-0.0211115f,0.10513f},{0.302548f,-0.0214037f,0.10513f}, +{0.303796f,-0.0212936f,0.10513f},{0.301289f,-0.0214407f,0.10513f},{0.302548f,-0.0214037f,0.104198f}, +{0.301289f,-0.0214407f,0.104198f},{0.322692f,0.00125938f,0.104198f},{0.322582f,0.00250813f,0.104198f}, +{0.322692f,0.00125925f,0.10513f},{0.322582f,0.00250793f,0.10513f},{0.3224f,0.00374334f,0.104198f}, +{0.322147f,0.00496208f,0.104198f},{0.3224f,0.00374312f,0.10513f},{0.321825f,0.00616144f,0.104198f}, +{0.322147f,0.00496191f,0.10513f},{0.321825f,0.00616138f,0.10513f},{0.321434f,0.00733859f,0.104198f}, +{0.320976f,0.00849054f,0.104198f},{0.321434f,0.0073385f,0.10513f},{0.320453f,0.0096143f,0.104198f}, +{0.320976f,0.00849036f,0.10513f},{0.320453f,0.00961408f,0.10513f},{0.319865f,0.010707f,0.104198f}, +{0.319213f,0.0117656f,0.104198f},{0.319865f,0.0107068f,0.10513f},{0.318499f,0.0127873f,0.104198f}, +{0.319213f,0.0117655f,0.10513f},{0.318499f,0.0127873f,0.10513f},{0.317724f,0.0137693f,0.104198f}, +{0.316888f,0.0147088f,0.104198f},{0.317724f,0.0137691f,0.10513f},{0.315997f,0.0156004f,0.104198f}, +{0.316889f,0.0147082f,0.10513f},{0.315997f,0.0155998f,0.10513f},{0.315058f,0.0164352f,0.104198f}, +{0.314076f,0.0172102f,0.104198f},{0.315058f,0.0164352f,0.10513f},{0.313054f,0.0179243f,0.104198f}, +{0.314076f,0.0172102f,0.10513f},{0.313054f,0.0179242f,0.10513f},{0.311995f,0.018576f,0.104198f}, +{0.310903f,0.0191643f,0.104198f},{0.311996f,0.018576f,0.10513f},{0.309779f,0.019688f,0.104198f}, +{0.310903f,0.0191643f,0.10513f},{0.309779f,0.0196879f,0.10513f},{0.308627f,0.0201457f,0.104198f}, +{0.30745f,0.0205363f,0.104198f},{0.308627f,0.0201457f,0.10513f},{0.30625f,0.0208587f,0.104198f}, +{0.30745f,0.0205363f,0.10513f},{0.305032f,0.0211114f,0.10513f},{0.306251f,0.0208586f,0.10513f}, +{0.305032f,0.0211115f,0.104198f},{0.303797f,0.0212935f,0.10513f},{0.303796f,0.0212936f,0.104198f}, +{0.302548f,0.0214037f,0.104198f},{0.302548f,0.0214037f,0.10513f},{0.301289f,0.0214407f,0.104198f}, +{0.301289f,0.0214407f,0.10513f},{0.32739f,1.99664e-017f,0.10513f},{0.32739f,2.41062e-017f,0.119113f}, +{0.327354f,-0.00138032f,0.119113f},{0.327245f,-0.00275048f,0.119113f},{0.327354f,-0.00138025f,0.10513f}, +{0.327065f,-0.0041079f,0.119113f},{0.327245f,-0.00275036f,0.10513f},{0.327065f,-0.00410773f,0.10513f}, +{0.326815f,-0.00544996f,0.119113f},{0.326496f,-0.00677408f,0.119113f},{0.326815f,-0.00544975f,0.10513f}, +{0.326109f,-0.00807765f,0.119113f},{0.326496f,-0.00677384f,0.10513f},{0.326109f,-0.0080774f,0.10513f}, +{0.325655f,-0.00935809f,0.119113f},{0.325135f,-0.0106128f,0.119113f},{0.325655f,-0.00935782f,0.10513f}, +{0.324551f,-0.0118391f,0.119113f},{0.325135f,-0.0106125f,0.10513f},{0.324551f,-0.0118389f,0.10513f}, +{0.323903f,-0.0130346f,0.119113f},{0.323192f,-0.0141964f,0.119113f},{0.323903f,-0.0130343f,0.10513f}, +{0.32242f,-0.0153222f,0.119113f},{0.323192f,-0.0141962f,0.10513f},{0.32242f,-0.015322f,0.10513f}, +{0.321587f,-0.0164092f,0.119113f},{0.320695f,-0.0174549f,0.119113f},{0.321587f,-0.0164091f,0.10513f}, +{0.319745f,-0.0184567f,0.119113f},{0.320695f,-0.0174549f,0.10513f},{0.319745f,-0.0184567f,0.10513f}, +{0.318743f,-0.0194069f,0.119113f},{0.317698f,-0.0202989f,0.119113f},{0.318743f,-0.0194069f,0.10513f}, +{0.316611f,-0.0211315f,0.119113f},{0.317698f,-0.0202988f,0.10513f},{0.316611f,-0.0211314f,0.10513f}, +{0.315485f,-0.0219036f,0.119113f},{0.314323f,-0.0226143f,0.119113f},{0.315485f,-0.0219036f,0.10513f}, +{0.313127f,-0.0232624f,0.119113f},{0.314323f,-0.0226142f,0.10513f},{0.313128f,-0.0232623f,0.10513f}, +{0.311901f,-0.0238468f,0.119113f},{0.310646f,-0.0243666f,0.119113f},{0.311901f,-0.0238467f,0.10513f}, +{0.309366f,-0.0248205f,0.119113f},{0.310647f,-0.0243664f,0.10513f},{0.309366f,-0.0248204f,0.10513f}, +{0.308062f,-0.0252075f,0.119113f},{0.306738f,-0.0255265f,0.119113f},{0.308063f,-0.0252074f,0.10513f}, +{0.305396f,-0.0257766f,0.119113f},{0.306739f,-0.0255265f,0.10513f},{0.305396f,-0.0257765f,0.10513f}, +{0.304039f,-0.0259565f,0.119113f},{0.302669f,-0.0260653f,0.119113f},{0.304039f,-0.0259565f,0.10513f}, +{0.301289f,-0.0261017f,0.119113f},{0.302669f,-0.0260652f,0.10513f},{0.301289f,-0.0261017f,0.10513f}, +{0.327354f,0.00138032f,0.10513f},{0.327245f,0.00275048f,0.10513f},{0.327354f,0.00138025f,0.119113f}, +{0.327245f,0.00275036f,0.119113f},{0.327065f,0.0041079f,0.10513f},{0.326815f,0.00544996f,0.10513f}, +{0.327065f,0.00410773f,0.119113f},{0.326496f,0.00677408f,0.10513f},{0.326815f,0.00544975f,0.119113f}, +{0.326496f,0.00677384f,0.119113f},{0.326109f,0.00807765f,0.10513f},{0.325655f,0.00935809f,0.10513f}, +{0.326109f,0.0080774f,0.119113f},{0.325135f,0.0106128f,0.10513f},{0.325655f,0.00935782f,0.119113f}, +{0.325135f,0.0106125f,0.119113f},{0.324551f,0.0118391f,0.10513f},{0.323903f,0.0130346f,0.10513f}, +{0.324551f,0.0118389f,0.119113f},{0.323192f,0.0141964f,0.10513f},{0.323903f,0.0130343f,0.119113f}, +{0.323192f,0.0141962f,0.119113f},{0.32242f,0.0153222f,0.10513f},{0.321587f,0.0164092f,0.10513f}, +{0.32242f,0.015322f,0.119113f},{0.320695f,0.0174549f,0.10513f},{0.321587f,0.0164091f,0.119113f}, +{0.320695f,0.0174549f,0.119113f},{0.319745f,0.0184567f,0.10513f},{0.318743f,0.0194069f,0.10513f}, +{0.319745f,0.0184567f,0.119113f},{0.317698f,0.0202989f,0.10513f},{0.318743f,0.0194069f,0.119113f}, +{0.317698f,0.0202988f,0.119113f},{0.316611f,0.0211315f,0.10513f},{0.315485f,0.0219036f,0.10513f}, +{0.316611f,0.0211314f,0.119113f},{0.314323f,0.0226143f,0.10513f},{0.315485f,0.0219036f,0.119113f}, +{0.314323f,0.0226142f,0.119113f},{0.313127f,0.0232624f,0.10513f},{0.311901f,0.0238468f,0.10513f}, +{0.313128f,0.0232623f,0.119113f},{0.310646f,0.0243666f,0.10513f},{0.311901f,0.0238467f,0.119113f}, +{0.310647f,0.0243664f,0.119113f},{0.309366f,0.0248205f,0.10513f},{0.308062f,0.0252075f,0.10513f}, +{0.309366f,0.0248204f,0.119113f},{0.306738f,0.0255265f,0.10513f},{0.308063f,0.0252074f,0.119113f}, +{0.306739f,0.0255265f,0.119113f},{0.305396f,0.0257766f,0.10513f},{0.304039f,0.0259565f,0.10513f}, +{0.305396f,0.0257765f,0.119113f},{0.302669f,0.0260653f,0.10513f},{0.304039f,0.0259565f,0.119113f}, +{0.302669f,0.0260652f,0.119113f},{0.301289f,0.0261017f,0.10513f},{0.301289f,0.0261017f,0.119113f}, +{0.313422f,-0.00289006f,0.124706f},{0.286299f,0.00596973f,0.124706f},{0.286258f,0.00652514f,0.124706f}, +{0.282163f,0.00374099f,0.124706f},{0.293181f,-0.0152805f,0.124706f},{0.292666f,0.0149353f,0.124706f}, +{0.29756f,0.0130513f,0.124706f},{0.293181f,0.0152802f,0.124706f},{0.289069f,0.0144863f,0.124706f}, +{0.288486f,0.0146944f,0.124706f},{0.288278f,0.0103166f,0.124706f},{0.306525f,0.00984656f,0.124706f}, +{0.306144f,0.00992732f,0.124706f},{0.299424f,0.0162797f,0.124706f},{0.297508f,0.0215779f,0.124706f}, +{0.294991f,0.019053f,0.124706f},{0.310727f,0.00975506f,0.124706f},{0.310468f,0.0146618f,0.124706f}, +{0.309911f,0.0149353f,0.124706f},{0.310266f,0.00944145f,0.124706f},{0.318534f,3.09663e-018f,0.124706f}, +{0.318576f,0.000618856f,0.124706f},{0.312283f,0.0143109f,0.124706f},{0.312313f,0.0102438f,0.124706f}, +{0.31287f,0.0102437f,0.124706f},{0.322087f,-0.00452954f,0.124706f},{0.322334f,-0.00608354f,0.124706f}, +{0.322699f,-0.00463457f,0.124706f},{0.318698f,-0.00122583f,0.124706f},{0.318576f,-0.000618365f,0.124706f}, +{0.314916f,-0.00361044f,0.124706f},{0.320415f,-0.00374099f,0.124706f},{0.316278f,-0.00596973f,0.124706f}, +{0.316319f,-0.00652514f,0.124706f},{0.3215f,-0.00433369f,0.124706f},{0.316278f,-0.00708106f,0.124706f}, +{0.316153f,-0.00762403f,0.124706f},{0.321297f,-0.00891935f,0.124706f},{0.311229f,-0.00305413f,0.124706f}, +{0.311762f,-0.00288693f,0.124706f},{0.31567f,-0.00862484f,0.124706f},{0.319869f,-0.0116055f,0.124706f}, +{0.32063f,-0.0102864f,0.124706f},{0.321866f,-0.00751463f,0.124706f},{0.320938f,-0.00407246f,0.124706f}, +{0.318086f,-0.0140624f,0.124706f},{0.314643f,-0.0149788f,0.124706f},{0.31708f,-0.0151839f,0.124706f}, +{0.314916f,-0.00944085f,0.124706f},{0.315151f,-0.015333f,0.124706f},{0.31561f,-0.0157495f,0.124706f}, +{0.316008f,-0.0162251f,0.124706f},{0.315948f,-0.00814252f,0.124706f},{0.316278f,0.00708097f,0.124706f}, +{0.321866f,0.00751594f,0.124706f},{0.316154f,-0.00542663f,0.124706f},{0.319943f,-0.00333905f,0.124706f}, +{0.319529f,-0.00287783f,0.124706f},{0.319179f,-0.0023656f,0.124706f},{0.315672f,-0.00442541f,0.124706f}, +{0.315951f,-0.00490799f,0.124706f},{0.311857f,0.0013863f,0.124706f},{0.312119f,0.00109643f,0.124706f}, +{0.318699f,0.00122657f,0.124706f},{0.311542f,0.00161492f,0.124706f},{0.309396f,0.0152805f,0.124706f}, +{0.308931f,0.0156909f,0.124706f},{0.320416f,0.00374048f,0.124706f},{0.31464f,0.0149805f,0.124706f}, +{0.31708f,0.0151839f,0.124706f},{0.315148f,0.0153371f,0.124706f},{0.315611f,0.0157476f,0.124706f}, +{0.316008f,0.0162251f,0.124706f},{0.313953f,0.00999629f,0.124706f},{0.314091f,0.0146931f,0.124706f}, +{0.313507f,0.0144856f,0.124706f},{0.312901f,0.0143575f,0.124706f},{0.313421f,0.0101606f,0.124706f}, +{0.315324f,0.00906122f,0.124706f},{0.319017f,0.0128683f,0.124706f},{0.314916f,0.00944057f,0.124706f}, +{0.314455f,0.00975455f,0.124706f},{0.320629f,0.0102881f,0.124706f},{0.319868f,0.0116071f,0.124706f}, +{0.315948f,0.00814199f,0.124706f},{0.318085f,0.0140632f,0.124706f},{0.320938f,0.00407552f,0.124706f}, +{0.321499f,0.00433883f,0.124706f},{0.322334f,0.00608354f,0.124706f},{0.322089f,0.0045282f,0.124706f}, +{0.322699f,0.00463457f,0.124706f},{0.31567f,0.00862459f,0.124706f},{0.321297f,0.008921f,0.124706f}, +{0.316153f,0.00762395f,0.124706f},{0.294936f,0.0196708f,0.124706f},{0.296034f,0.0212675f,0.124706f}, +{0.294812f,0.0202771f,0.124706f},{0.308525f,0.0161593f,0.124706f},{0.308185f,0.0166773f,0.124706f}, +{0.319944f,0.00333893f,0.124706f},{0.307613f,0.0184349f,0.124706f},{0.307724f,0.0178252f,0.124706f}, +{0.31918f,0.00236609f,0.124706f},{0.319529f,0.00287783f,0.124706f},{0.290913f,0.0143468f,0.124706f}, +{0.290294f,0.0143112f,0.124706f},{0.292899f,-0.0016145f,0.124706f},{0.297601f,0.0136072f,0.124706f}, +{0.297726f,0.0141506f,0.124706f},{0.293645f,0.0156903f,0.124706f},{0.294965f,0.0184341f,0.124706f}, +{0.294853f,0.0178247f,0.124706f},{0.298964f,0.015966f,0.124706f},{0.300459f,0.0166853f,0.124706f}, +{0.299009f,0.0217877f,0.124706f},{0.299926f,0.0165216f,0.124706f},{0.294661f,0.0172353f,0.124706f}, +{0.298555f,0.0155872f,0.124706f},{0.305068f,0.0215784f,0.124706f},{0.302651f,0.0165218f,0.124706f}, +{0.301567f,0.0167668f,0.124706f},{0.302049f,0.0218936f,0.124706f},{0.30101f,0.0167671f,0.124706f}, +{0.307584f,0.0190544f,0.124706f},{0.306543f,0.0212675f,0.124706f},{0.294597f,0.0208597f,0.124706f}, +{0.307636f,0.0196718f,0.124706f},{0.307767f,0.0202777f,0.124706f},{0.30798f,0.0208597f,0.124706f}, +{0.298208f,0.0151517f,0.124706f},{0.294392f,0.0166765f,0.124706f},{0.297929f,0.0146693f,0.124706f}, +{0.303567f,0.0217881f,0.124706f},{0.302118f,0.0166848f,0.124706f},{0.286626f,0.00490799f,0.124706f}, +{0.283398f,0.0023656f,0.124706f},{0.286905f,0.00442541f,0.124706f},{0.305373f,0.00984589f,0.124706f}, +{0.305754f,0.00992719f,0.124706f},{0.292109f,0.0146616f,0.124706f},{0.288278f,-0.00115727f,0.124706f}, +{0.294964f,-0.0184349f,0.124706f},{0.294853f,-0.0178252f,0.124706f},{0.291521f,0.0144643f,0.124706f}, +{0.280711f,0.00751463f,0.124706f},{0.280243f,0.00608354f,0.124706f},{0.281639f,0.00407246f,0.124706f}, +{0.287661f,0.00944085f,0.124706f},{0.283559f,0.0128671f,0.124706f},{0.287254f,0.00906082f,0.124706f}, +{0.295379f,0.00945782f,0.124706f},{0.28049f,0.00452954f,0.124706f},{0.279878f,0.00463457f,0.124706f}, +{0.287252f,0.00398966f,0.124706f},{0.283879f,0.00122583f,0.124706f},{0.287661f,0.00361044f,0.124706f}, +{0.283048f,0.00287783f,0.124706f},{0.286423f,0.00542663f,0.124706f},{0.282634f,0.00333905f,0.124706f}, +{0.281077f,0.00433369f,0.124706f},{0.286299f,0.00708106f,0.124706f},{0.286424f,0.00762403f,0.124706f}, +{0.28128f,0.00891935f,0.124706f},{0.281947f,0.0102864f,0.124706f},{0.286907f,0.00862484f,0.124706f}, +{0.282708f,0.0116055f,0.124706f},{0.286629f,0.00814252f,0.124706f},{0.287935f,0.0149788f,0.124706f}, +{0.285497f,0.0151839f,0.124706f},{0.284491f,0.0140624f,0.124706f},{0.287426f,0.015333f,0.124706f}, +{0.291522f,-0.0144645f,0.124706f},{0.29211f,-0.0146618f,0.124706f},{0.291348f,-0.00999677f,0.124706f}, +{0.286967f,0.0157495f,0.124706f},{0.286569f,0.0162251f,0.124706f},{0.294924f,0.00883069f,0.124706f}, +{0.294804f,0.00845974f,0.124706f},{0.283676f,-0.00181243f,0.124706f},{0.283397f,-0.00236609f,0.124706f}, +{0.289676f,0.014358f,0.124706f},{0.292666f,-0.0149353f,0.124706f},{0.29185f,-0.00975506f,0.124706f}, +{0.298136f,-0.00916839f,0.124706f},{0.298331f,-0.00883048f,0.124706f},{0.290815f,-0.0101609f,0.124706f}, +{0.281639f,-0.00407552f,0.124706f},{0.280711f,-0.00751594f,0.124706f},{0.284492f,-0.0140632f,0.124706f}, +{0.285497f,-0.0151839f,0.124706f},{0.288278f,-0.0126311f,0.124706f},{0.28907f,-0.0144856f,0.124706f}, +{0.289676f,-0.0143575f,0.124706f},{0.284002f,0.000618365f,0.124706f},{0.283878f,-0.00122657f,0.124706f}, +{0.284043f,7.02122e-018f,0.124706f},{0.294052f,-0.0161593f,0.124706f},{0.294392f,-0.0166773f,0.124706f}, +{0.28743f,-0.0153371f,0.124706f},{0.287937f,-0.0149805f,0.124706f},{0.289707f,-0.0102437f,0.124706f}, +{0.289156f,-0.0101606f,0.124706f},{0.287254f,-0.00906122f,0.124706f},{0.28356f,-0.0128683f,0.124706f}, +{0.287662f,-0.00944057f,0.124706f},{0.286907f,-0.00862459f,0.124706f},{0.28271f,-0.0116071f,0.124706f}, +{0.281948f,-0.0102881f,0.124706f},{0.286629f,-0.00814199f,0.124706f},{0.286299f,-0.00708097f,0.124706f}, +{0.288122f,-0.00975455f,0.124706f},{0.288624f,-0.00999629f,0.124706f},{0.280243f,-0.00608354f,0.124706f}, +{0.286966f,-0.0157476f,0.124706f},{0.281079f,-0.00433883f,0.124706f},{0.280488f,-0.0045282f,0.124706f}, +{0.286569f,-0.0162251f,0.124706f},{0.279878f,-0.00463457f,0.124706f},{0.290264f,-0.0102438f,0.124706f}, +{0.310034f,0.00177278f,0.124706f},{0.309678f,0.0016145f,0.124706f},{0.296053f,-0.00984657f,0.124706f}, +{0.296433f,-0.00992738f,0.124706f},{0.307652f,-0.00731413f,0.124706f},{0.307457f,-0.00697672f,0.124706f}, +{0.294994f,-0.0190544f,0.124706f},{0.297509f,-0.0215784f,0.124706f},{0.311226f,-0.0126311f,0.124706f}, +{0.312283f,-0.0143112f,0.124706f},{0.312901f,-0.014358f,0.124706f},{0.304852f,-0.0141506f,0.124706f}, +{0.308932f,-0.0156903f,0.124706f},{0.304976f,-0.0136072f,0.124706f},{0.311056f,-0.0144643f,0.124706f}, +{0.310468f,-0.0146616f,0.124706f},{0.307724f,-0.0178247f,0.124706f},{0.303613f,-0.015966f,0.124706f}, +{0.307612f,-0.0184341f,0.124706f},{0.309397f,-0.0152802f,0.124706f},{0.309911f,-0.0149353f,0.124706f}, +{0.305018f,-0.0130513f,0.124706f},{0.305069f,-0.0215779f,0.124706f},{0.307586f,-0.019053f,0.124706f}, +{0.303153f,-0.0162797f,0.124706f},{0.312434f,0.000388892f,0.124706f},{0.312314f,0.000758756f,0.124706f}, +{0.28128f,-0.008921f,0.124706f},{0.286424f,-0.00762395f,0.124706f},{0.290295f,-0.0143109f,0.124706f}, +{0.309025f,0.00762671f,0.124706f},{0.290263f,-0.000758756f,0.124706f},{0.290143f,-0.000388892f,0.124706f}, +{0.293646f,-0.0156909f,0.124706f},{0.29072f,-0.0013863f,0.124706f},{0.309362f,0.00138471f,0.124706f}, +{0.300459f,-0.0166848f,0.124706f},{0.299926f,-0.0165218f,0.124706f},{0.29901f,-0.0217881f,0.124706f}, +{0.30101f,-0.0167668f,0.124706f},{0.300528f,-0.0218936f,0.124706f},{0.301567f,-0.0167671f,0.124706f}, +{0.302118f,-0.0166853f,0.124706f},{0.303568f,-0.0217877f,0.124706f},{0.302651f,-0.0165216f,0.124706f}, +{0.296034f,-0.0212675f,0.124706f},{0.294941f,-0.0196718f,0.124706f},{0.29481f,-0.0202777f,0.124706f}, +{0.294597f,-0.0208597f,0.124706f},{0.304648f,-0.0146693f,0.124706f},{0.304369f,-0.0151517f,0.124706f}, +{0.308185f,-0.0166765f,0.124706f},{0.304022f,-0.0155872f,0.124706f},{0.307916f,-0.0172353f,0.124706f}, +{0.306543f,-0.0212675f,0.124706f},{0.307641f,-0.0196708f,0.124706f},{0.30798f,-0.0208597f,0.124706f}, +{0.307765f,-0.0202771f,0.124706f},{0.318901f,0.00181243f,0.124706f},{0.311229f,0.00999677f,0.124706f}, +{0.311664f,0.0143468f,0.124706f},{0.311055f,0.0144645f,0.124706f},{0.311762f,0.0101609f,0.124706f}, +{0.310415f,0.00185398f,0.124706f},{0.310805f,0.00185425f,0.124706f},{0.311186f,0.0017734f,0.124706f}, +{0.315325f,-0.00398966f,0.124706f},{0.312313f,-0.00281666f,0.124706f},{0.319018f,-0.0128671f,0.124706f}, +{0.315323f,-0.00906082f,0.124706f},{0.309515f,0.00862453f,0.124706f},{0.297204f,0.00630002f,0.124706f}, +{0.296823f,0.00621904f,0.124706f},{0.282634f,-0.00333893f,0.124706f},{0.282161f,-0.00374048f,0.124706f}, +{0.304441f,0.00916836f,0.124706f},{0.304246f,0.00883081f,0.124706f},{0.304702f,0.0066875f,0.124706f}, +{0.308787f,0.000387896f,0.124706f},{0.308907f,0.000757801f,0.124706f},{0.313954f,-0.00305438f,0.124706f}, +{0.314456f,-0.00329623f,0.124706f},{0.312871f,-0.00281186f,0.124706f},{0.313508f,-0.0144863f,0.124706f}, +{0.314092f,-0.0146944f,0.124706f},{0.307198f,-0.00945782f,0.124706f},{0.307653f,-0.00883069f,0.124706f}, +{0.307773f,-0.00845974f,0.124706f},{0.297205f,-0.00984564f,0.124706f},{0.296823f,-0.00992724f,0.124706f}, +{0.293215f,-0.00138471f,0.124706f},{0.296985f,-0.00178272f,0.124706f},{0.304126f,-0.00369829f,0.124706f}, +{0.305373f,-0.00630002f,0.124706f},{0.305754f,-0.00621904f,0.124706f},{0.292544f,-0.00177278f,0.124706f}, +{0.284001f,-0.000618856f,0.124706f},{0.308904f,0.00708155f,0.124706f},{0.309858f,0.00906268f,0.124706f}, +{0.294051f,0.0161585f,0.124706f},{0.300526f,0.0218934f,0.124706f},{0.307917f,0.0172358f,0.124706f}, +{0.304701f,0.00945796f,0.124706f},{0.305017f,0.00968738f,0.124706f},{0.304085f,0.00807261f,0.124706f}, +{0.304126f,0.00845965f,0.124706f},{0.304126f,0.00768455f,0.124706f},{0.297933f,0.0114364f,0.124706f}, +{0.30924f,0.00813915f,0.124706f},{0.297591f,-0.00283697f,0.124706f},{0.304247f,0.00731409f,0.124706f}, +{0.304442f,0.00697679f,0.124706f},{0.296052f,0.00629974f,0.124706f},{0.29512f,0.00697672f,0.124706f}, +{0.294925f,0.00731413f,0.124706f},{0.298552f,0.0105136f,0.124706f},{0.298963f,0.0101357f,0.124706f}, +{0.297725f,0.0119527f,0.124706f},{0.288121f,0.00329623f,0.124706f},{0.283676f,0.00181168f,0.124706f}, +{0.295119f,0.00916838f,0.124706f},{0.294804f,0.00768456f,0.124706f},{0.294763f,0.00807245f,0.124706f}, +{0.295696f,0.00645825f,0.124706f},{0.295381f,0.00668694f,0.124706f},{0.296433f,0.00621891f,0.124706f}, +{0.298216f,0.0109558f,0.124706f},{0.290264f,0.00281666f,0.124706f},{0.291772f,-0.00185425f,0.124706f}, +{0.297601f,0.0124958f,0.124706f},{0.292311f,-0.00944145f,0.124706f},{0.290913f,-0.0143468f,0.124706f}, +{0.288486f,-0.0146931f,0.124706f},{0.283048f,-0.00287783f,0.124706f},{0.290459f,-0.00109643f,0.124706f}, +{0.291035f,-0.00161492f,0.124706f},{0.292162f,-0.00185398f,0.124706f},{0.291391f,-0.0017734f,0.124706f}, +{0.289706f,0.00281186f,0.124706f},{0.289155f,0.00289006f,0.124706f},{0.290815f,0.00288693f,0.124706f}, +{0.291348f,0.00305413f,0.124706f},{0.296667f,-0.0006084f,0.124706f},{0.29367f,-0.000757801f,0.124706f}, +{0.296789f,-0.00120559f,0.124706f},{0.29379f,-0.000387896f,0.124706f},{0.293673f,-0.00708155f,0.124706f}, +{0.292719f,-0.00906268f,0.124706f},{0.293062f,-0.00862453f,0.124706f},{0.293552f,-0.00762671f,0.124706f}, +{0.297252f,-0.00233026f,0.124706f},{0.288623f,0.00305438f,0.124706f},{0.306881f,-0.00645825f,0.124706f}, +{0.308526f,-0.0161585f,0.124706f},{0.302051f,-0.0218934f,0.124706f},{0.29466f,-0.0172358f,0.124706f}, +{0.297876f,-0.00945833f,0.124706f},{0.29756f,-0.00968734f,0.124706f},{0.298492f,-0.0080728f,0.124706f}, +{0.298451f,-0.00845974f,0.124706f},{0.298451f,-0.00768446f,0.124706f},{0.302495f,-0.00450236f,0.124706f}, +{0.293337f,-0.00813915f,0.124706f},{0.304987f,-0.00283787f,0.124706f},{0.304585f,-0.00329614f,0.124706f}, +{0.306144f,-0.00621891f,0.124706f},{0.306525f,-0.00629974f,0.124706f},{0.309102f,0.00109509f,0.124706f}, +{0.305595f,-0.00178435f,0.124706f},{0.304852f,-0.0119527f,0.124706f},{0.298451f,-0.00369728f,0.124706f}, +{0.297993f,-0.00329545f,0.124706f},{0.303072f,-0.00430656f,0.124706f},{0.301897f,-0.00462115f,0.124706f}, +{0.301289f,-0.00466102f,0.124706f},{0.297875f,-0.0066878f,0.124706f},{0.298958f,-0.00403597f,0.124706f}, +{0.29833f,-0.00731401f,0.124706f},{0.300082f,-0.00450189f,0.124706f},{0.298136f,-0.00697682f,0.124706f}, +{0.318901f,-0.00181168f,0.124706f},{0.311664f,-0.0143468f,0.124706f},{0.307458f,-0.00916838f,0.124706f}, +{0.307773f,-0.00768456f,0.124706f},{0.307814f,-0.00807245f,0.124706f},{0.305784f,-0.00120563f,0.124706f}, +{0.307196f,-0.00668694f,0.124706f},{0.304025f,-0.0105136f,0.124706f},{0.304644f,-0.0114364f,0.124706f}, +{0.303614f,-0.0101357f,0.124706f},{0.304361f,-0.0109558f,0.124706f},{0.305906f,-0.00060826f,0.124706f}, +{0.305325f,-0.002331f,0.124706f},{0.304976f,-0.0124958f,0.124706f},{0.303619f,-0.00403701f,0.124706f}, +{0.30068f,-0.00462104f,0.124706f},{0.299504f,-0.00430572f,0.124706f},{0.293475f,-0.00109509f,0.124706f}, +{0.322912f,-0.00625082f,0.124658f},{0.322432f,-0.00772125f,0.124658f},{0.323012f,-0.00793332f,0.124501f}, +{0.32058f,-0.0161504f,0.122798f},{0.321651f,-0.0147775f,0.122798f},{0.32134f,-0.0145522f,0.123358f}, +{0.322302f,-0.0131254f,0.123358f},{0.322627f,-0.0133286f,0.122798f},{0.319915f,-0.0155937f,0.123843f}, +{0.319486f,-0.0152344f,0.124229f},{0.318799f,-0.0168374f,0.123843f},{0.31796f,-0.0160299f,0.124501f}, +{0.317145f,-0.0174787f,0.1243f},{0.318396f,-0.0164494f,0.124229f},{0.316402f,-0.0166602f,0.124659f}, +{0.316784f,-0.0170806f,0.124523f},{0.317514f,-0.0156014f,0.124658f},{0.323163f,-0.0116335f,0.123358f}, +{0.323502f,-0.0118136f,0.122798f},{0.323918f,-0.0100875f,0.123358f},{0.322857f,-0.013472f,0.122194f}, +{0.32299f,-0.0135551f,0.12158f},{0.323741f,-0.0119407f,0.122194f},{0.322652f,-0.0141705f,0.120977f}, +{0.323489f,-0.0128179f,0.120977f},{0.321997f,-0.0150287f,0.12158f},{0.321731f,-0.0154687f,0.120977f}, +{0.320908f,-0.0164249f,0.12158f},{0.323879f,-0.0120144f,0.12158f},{0.324242f,-0.0114156f,0.120977f}, +{0.319658f,-0.0178815f,0.120977f},{0.320732f,-0.0167073f,0.120977f},{0.319733f,-0.0177348f,0.12158f}, +{0.318513f,-0.0189869f,0.120977f},{0.318482f,-0.0189523f,0.121565f},{0.324659f,-0.0104178f,0.12158f}, +{0.324906f,-0.00996957f,0.120977f},{0.325323f,-0.00877706f,0.12158f},{0.325479f,-0.00848485f,0.120977f}, +{0.32596f,-0.0069676f,0.120977f},{0.325869f,-0.00710556f,0.12158f},{0.326298f,-0.00541355f,0.121565f}, +{0.326165f,-0.00538462f,0.122132f},{0.324268f,-0.0102436f,0.122798f},{0.319424f,-0.0174384f,0.122798f}, +{0.320286f,-0.0159041f,0.123358f},{0.326344f,-0.00542344f,0.120977f},{0.324515f,-0.0103538f,0.122194f}, +{0.324625f,-0.006746f,0.123843f},{0.324838f,-0.00509752f,0.123996f},{0.324088f,-0.00659057f,0.124229f}, +{0.325276f,-0.00519238f,0.123614f},{0.32509f,-0.00688027f,0.123358f},{0.322242f,-0.0111437f,0.124229f}, +{0.322965f,-0.00966271f,0.124229f},{0.322412f,-0.00941631f,0.124501f},{0.323274f,-0.00475885f,0.124659f}, +{0.325718f,-0.00706195f,0.122194f},{0.325947f,-0.00533751f,0.12267f},{0.325458f,-0.0069868f,0.122798f}, +{0.325175f,-0.00872319f,0.122194f},{0.32187f,-0.0149364f,0.122194f},{0.320788f,-0.0163241f,0.122194f}, +{0.319619f,-0.0176259f,0.122194f},{0.31839f,-0.0188517f,0.12213f},{0.325649f,-0.00527292f,0.123168f}, +{0.324921f,-0.00863036f,0.122798f},{0.318241f,-0.0186868f,0.122667f},{0.323506f,-0.0064225f,0.124501f}, +{0.324351f,-0.00499215f,0.124301f},{0.324561f,-0.00849877f,0.123358f},{0.320949f,-0.0142682f,0.123843f}, +{0.319148f,-0.0171725f,0.123358f},{0.318036f,-0.0184612f,0.123166f},{0.323476f,-0.0098906f,0.123843f}, +{0.324107f,-0.00833292f,0.123843f},{0.322736f,-0.0114065f,0.123843f},{0.321892f,-0.0128692f,0.123843f}, +{0.317779f,-0.018178f,0.123614f},{0.323581f,-0.00814092f,0.124229f},{0.321417f,-0.0125727f,0.124229f}, +{0.320496f,-0.0139394f,0.124229f},{0.317479f,-0.0178475f,0.123995f},{0.323826f,-0.00487843f,0.124524f}, +{0.321708f,-0.0108595f,0.124501f},{0.320904f,-0.0122521f,0.124501f},{0.320006f,-0.013584f,0.124501f}, +{0.318548f,-0.0144491f,0.124658f},{0.319022f,-0.014846f,0.124501f},{0.321847f,-0.00916459f,0.124658f}, +{0.321162f,-0.0105692f,0.124658f},{0.32038f,-0.0119246f,0.124658f},{0.319506f,-0.0132209f,0.124658f}, +{0.302174f,-0.0254145f,0.122194f},{0.303907f,-0.0250226f,0.122798f},{0.302164f,-0.0251441f,0.122798f}, +{0.305705f,-0.0252029f,0.12158f},{0.303952f,-0.0254479f,0.12158f},{0.303937f,-0.0254985f,0.120977f}, +{0.303867f,-0.0246411f,0.123358f},{0.302173f,-0.0256204f,0.120977f},{0.307388f,-0.0246879f,0.122194f}, +{0.307425f,-0.0248403f,0.12158f},{0.309063f,-0.0242356f,0.122132f},{0.307414f,-0.024878f,0.120977f}, +{0.309105f,-0.0243658f,0.121565f},{0.306687f,-0.0218522f,0.124658f},{0.305173f,-0.0221712f,0.124658f}, +{0.30528f,-0.0227801f,0.124501f},{0.309119f,-0.0244103f,0.120977f},{0.305688f,-0.0252555f,0.120977f}, +{0.308786f,-0.0233704f,0.123614f},{0.307115f,-0.0235834f,0.123843f},{0.307231f,-0.0240528f,0.123358f}, +{0.303759f,-0.0236035f,0.124229f},{0.303695f,-0.0230016f,0.124501f},{0.302115f,-0.0237181f,0.124229f}, +{0.306981f,-0.02304f,0.124229f},{0.308649f,-0.0229434f,0.123996f},{0.302179f,-0.0255715f,0.12158f}, +{0.303935f,-0.0252917f,0.122194f},{0.297014f,-0.0244044f,0.123358f},{0.295254f,-0.0244252f,0.122798f}, +{0.296948f,-0.0247822f,0.122798f},{0.30816f,-0.0214191f,0.124659f},{0.300428f,-0.0247609f,0.123358f}, +{0.298672f,-0.0250231f,0.122798f},{0.300415f,-0.0251442f,0.122798f},{0.302151f,-0.0247607f,0.123358f}, +{0.295462f,-0.0235834f,0.123843f},{0.297097f,-0.0239281f,0.123843f},{0.297194f,-0.0233768f,0.124229f}, +{0.295742f,-0.0224524f,0.124501f},{0.29408f,-0.0224714f,0.1243f},{0.295597f,-0.02304f,0.124229f}, +{0.298712f,-0.0246415f,0.123358f},{0.294417f,-0.0214191f,0.124659f},{0.294244f,-0.0219595f,0.124523f}, +{0.29589f,-0.0218522f,0.124658f},{0.3004f,-0.0255716f,0.12158f},{0.300406f,-0.0254147f,0.122194f}, +{0.300405f,-0.0256204f,0.120977f},{0.298628f,-0.0254484f,0.12158f},{0.298641f,-0.0254985f,0.120977f}, +{0.296874f,-0.0252035f,0.12158f},{0.29689f,-0.0252554f,0.120977f},{0.295161f,-0.0248864f,0.120977f}, +{0.295152f,-0.0248403f,0.12158f},{0.293458f,-0.0244103f,0.120977f},{0.308995f,-0.0240236f,0.12267f}, +{0.307323f,-0.0244252f,0.122798f},{0.305677f,-0.0250482f,0.122194f},{0.298644f,-0.0252922f,0.122194f}, +{0.295189f,-0.0246879f,0.122194f},{0.296901f,-0.0250488f,0.122194f},{0.293472f,-0.0243658f,0.121565f}, +{0.293513f,-0.0242365f,0.12213f},{0.308902f,-0.0237329f,0.123168f},{0.305631f,-0.0247816f,0.122798f}, +{0.293581f,-0.0240245f,0.122667f},{0.306835f,-0.0224524f,0.124501f},{0.308497f,-0.0224691f,0.124301f}, +{0.305565f,-0.0244038f,0.123358f},{0.298762f,-0.0241606f,0.123843f},{0.295346f,-0.0240528f,0.123358f}, +{0.293674f,-0.0237345f,0.123166f},{0.303817f,-0.0241602f,0.123843f},{0.305481f,-0.0239275f,0.123843f}, +{0.302134f,-0.0242775f,0.123843f},{0.300445f,-0.0242776f,0.123843f},{0.293791f,-0.0233704f,0.123614f}, +{0.305384f,-0.0233762f,0.124229f},{0.300465f,-0.0237183f,0.124229f},{0.29882f,-0.023604f,0.124229f}, +{0.293928f,-0.0229455f,0.123995f},{0.308332f,-0.0219573f,0.124524f},{0.302094f,-0.0231133f,0.124501f}, +{0.300486f,-0.0231134f,0.124501f},{0.298883f,-0.023002f,0.124501f},{0.297405f,-0.0221717f,0.124658f}, +{0.297298f,-0.0227807f,0.124501f},{0.303631f,-0.0223867f,0.124658f},{0.302072f,-0.0224954f,0.124658f}, +{0.300507f,-0.0224956f,0.124658f},{0.298948f,-0.0223872f,0.124658f},{0.279588f,-0.013557f,0.12158f}, +{0.280709f,-0.0149379f,0.122194f},{0.279721f,-0.0134738f,0.122194f},{0.280581f,-0.0150302f,0.12158f}, +{0.279926f,-0.0141709f,0.120977f},{0.280846f,-0.0154689f,0.120977f},{0.280928f,-0.0147789f,0.122798f}, +{0.279951f,-0.0133304f,0.122798f},{0.281238f,-0.0145536f,0.123358f},{0.282958f,-0.0176259f,0.122194f}, +{0.282845f,-0.0177348f,0.12158f},{0.284187f,-0.0188513f,0.122131f},{0.284338f,-0.0186852f,0.122672f}, +{0.28403f,-0.0144499f,0.124658f},{0.283556f,-0.0148468f,0.124501f},{0.285063f,-0.0156014f,0.124658f}, +{0.284095f,-0.0189527f,0.121561f},{0.282919f,-0.0178817f,0.120977f},{0.284064f,-0.0189869f,0.120977f}, +{0.28167f,-0.0164258f,0.12158f},{0.281845f,-0.0167075f,0.120977f},{0.284181f,-0.0164494f,0.124229f}, +{0.283778f,-0.0168374f,0.123843f},{0.285097f,-0.0178479f,0.123994f},{0.281161f,-0.0125744f,0.124229f}, +{0.282082f,-0.0139408f,0.124229f},{0.282572f,-0.0135853f,0.124501f},{0.286177f,-0.0166578f,0.12466f}, +{0.283429f,-0.0171725f,0.123358f},{0.284798f,-0.018178f,0.123614f},{0.278016f,-0.00850026f,0.123358f}, +{0.277119f,-0.0069868f,0.122798f},{0.277656f,-0.00863187f,0.122798f},{0.280276f,-0.0131272f,0.123358f}, +{0.279071f,-0.0064225f,0.124501f},{0.278223f,-0.00499264f,0.1243f},{0.278489f,-0.00659057f,0.124229f}, +{0.278837f,-0.0119427f,0.122194f},{0.278699f,-0.0120165f,0.12158f},{0.277952f,-0.006746f,0.123843f}, +{0.278471f,-0.00833438f,0.123843f},{0.278996f,-0.00814234f,0.124229f},{0.27831f,-0.0102456f,0.122798f}, +{0.27866f,-0.0100893f,0.123358f},{0.279415f,-0.0116355f,0.123358f},{0.279076f,-0.0118156f,0.122798f}, +{0.279303f,-0.00475885f,0.124659f},{0.278749f,-0.00487893f,0.124523f},{0.279665f,-0.00625082f,0.124658f}, +{0.279087f,-0.012818f,0.120977f},{0.277919f,-0.0104197f,0.12158f},{0.278335f,-0.011416f,0.120977f}, +{0.277254f,-0.0087786f,0.12158f},{0.277671f,-0.00996985f,0.120977f},{0.2771f,-0.00848443f,0.120977f}, +{0.276708f,-0.00710556f,0.12158f},{0.276626f,-0.00696541f,0.120977f},{0.276233f,-0.00542344f,0.120977f}, +{0.276279f,-0.00541355f,0.121565f},{0.283153f,-0.0174384f,0.122798f},{0.281791f,-0.016325f,0.122194f}, +{0.278063f,-0.0103558f,0.122194f},{0.277402f,-0.00872472f,0.122194f},{0.276859f,-0.00706195f,0.122194f}, +{0.276412f,-0.00538482f,0.12213f},{0.284543f,-0.0184588f,0.12317f},{0.281998f,-0.0161513f,0.122798f}, +{0.276629f,-0.00533772f,0.122667f},{0.284618f,-0.0160299f,0.124501f},{0.285433f,-0.0174779f,0.1243f}, +{0.282292f,-0.015905f,0.123358f},{0.279102f,-0.00989244f,0.123843f},{0.277487f,-0.00688027f,0.123358f}, +{0.276927f,-0.00527328f,0.123166f},{0.281629f,-0.0142696f,0.123843f},{0.282663f,-0.0155946f,0.123843f}, +{0.280686f,-0.012871f,0.123843f},{0.279842f,-0.0114084f,0.123843f},{0.277301f,-0.00519238f,0.123614f}, +{0.283092f,-0.0152353f,0.124229f},{0.280336f,-0.0111456f,0.124229f},{0.279613f,-0.00966451f,0.124229f}, +{0.277737f,-0.005098f,0.123995f},{0.285796f,-0.0170773f,0.124524f},{0.281674f,-0.0122538f,0.124501f}, +{0.28087f,-0.0108613f,0.124501f},{0.280166f,-0.00941806f,0.124501f},{0.280146f,-0.0077226f,0.124658f}, +{0.279565f,-0.00793471f,0.124501f},{0.283072f,-0.0132221f,0.124658f},{0.282199f,-0.0119262f,0.124658f}, +{0.281416f,-0.010571f,0.124658f},{0.28073f,-0.0091663f,0.124658f},{0.278698f,0.0120144f,0.12158f}, +{0.278062f,0.0103538f,0.122194f},{0.278836f,0.0119407f,0.122194f},{0.277919f,0.0104178f,0.12158f}, +{0.278309f,0.0102436f,0.122798f},{0.279075f,0.0118136f,0.122798f},{0.278659f,0.0100875f,0.123358f}, +{0.276859f,0.00706195f,0.122194f},{0.276708f,0.00710556f,0.12158f},{0.276413f,0.00538462f,0.122132f}, +{0.27663f,0.00533751f,0.12267f},{0.280145f,0.00772125f,0.124658f},{0.279565f,0.00793332f,0.124501f}, +{0.279665f,0.00625082f,0.124658f},{0.276279f,0.00541355f,0.121565f},{0.277254f,0.00877706f,0.12158f}, +{0.278489f,0.00659057f,0.124229f},{0.277952f,0.006746f,0.123843f},{0.277739f,0.00509752f,0.123996f}, +{0.280335f,0.0111437f,0.124229f},{0.279612f,0.00966271f,0.124229f},{0.280165f,0.00941631f,0.124501f}, +{0.279303f,0.00475885f,0.124659f},{0.277487f,0.00688027f,0.123358f},{0.277301f,0.00519238f,0.123614f}, +{0.282291f,0.0159041f,0.123358f},{0.283153f,0.0174384f,0.122798f},{0.281997f,0.0161504f,0.122798f}, +{0.279414f,0.0116335f,0.123358f},{0.284618f,0.0160299f,0.124501f},{0.285431f,0.0174801f,0.124299f}, +{0.284181f,0.0164494f,0.124229f},{0.27972f,0.013472f,0.122194f},{0.279587f,0.0135551f,0.12158f}, +{0.283778f,0.0168374f,0.123843f},{0.282662f,0.0155937f,0.123843f},{0.283091f,0.0152344f,0.124229f}, +{0.280926f,0.0147775f,0.122798f},{0.281237f,0.0145522f,0.123358f},{0.280275f,0.0131254f,0.123358f}, +{0.27995f,0.0133286f,0.122798f},{0.286177f,0.0166578f,0.12466f},{0.285794f,0.0170797f,0.124523f}, +{0.285063f,0.0156014f,0.124658f},{0.28058f,0.0150287f,0.12158f},{0.281669f,0.0164249f,0.12158f}, +{0.282845f,0.0177348f,0.12158f},{0.284095f,0.0189527f,0.121561f},{0.277119f,0.0069868f,0.122798f}, +{0.277402f,0.00872319f,0.122194f},{0.280707f,0.0149364f,0.122194f},{0.281789f,0.0163241f,0.122194f}, +{0.282958f,0.0176259f,0.122194f},{0.284186f,0.018852f,0.122128f},{0.276929f,0.00527292f,0.123168f}, +{0.277656f,0.00863036f,0.122798f},{0.284337f,0.0186863f,0.122669f},{0.279071f,0.0064225f,0.124501f}, +{0.278226f,0.00499215f,0.124301f},{0.278016f,0.00849877f,0.123358f},{0.281628f,0.0142682f,0.123843f}, +{0.283429f,0.0171725f,0.123358f},{0.284542f,0.0184598f,0.123168f},{0.279101f,0.0098906f,0.123843f}, +{0.27847f,0.00833292f,0.123843f},{0.279841f,0.0114065f,0.123843f},{0.280685f,0.0128692f,0.123843f}, +{0.284798f,0.018178f,0.123614f},{0.278996f,0.00814092f,0.124229f},{0.28116f,0.0125727f,0.124229f}, +{0.282081f,0.0139394f,0.124229f},{0.285096f,0.0178492f,0.123993f},{0.278751f,0.00487843f,0.124524f}, +{0.280869f,0.0108595f,0.124501f},{0.281673f,0.0122521f,0.124501f},{0.282571f,0.013584f,0.124501f}, +{0.284029f,0.0144491f,0.124658f},{0.283555f,0.014846f,0.124501f},{0.28073f,0.00916459f,0.124658f}, +{0.281415f,0.0105692f,0.124658f},{0.282198f,0.0119246f,0.124658f},{0.283071f,0.0132209f,0.124658f}, +{0.300403f,0.0254145f,0.122194f},{0.29867f,0.0250226f,0.122798f},{0.300413f,0.0251441f,0.122798f}, +{0.296873f,0.0252029f,0.12158f},{0.298626f,0.0254479f,0.12158f},{0.29871f,0.0246411f,0.123358f}, +{0.295189f,0.0246879f,0.122194f},{0.295152f,0.0248403f,0.12158f},{0.293514f,0.0242356f,0.122132f}, +{0.293472f,0.0243658f,0.121565f},{0.29589f,0.0218522f,0.124658f},{0.297404f,0.0221712f,0.124658f}, +{0.297297f,0.0227801f,0.124501f},{0.293791f,0.0233704f,0.123614f},{0.295462f,0.0235834f,0.123843f}, +{0.295346f,0.0240528f,0.123358f},{0.298819f,0.0236035f,0.124229f},{0.298882f,0.0230016f,0.124501f}, +{0.300462f,0.0237181f,0.124229f},{0.295597f,0.02304f,0.124229f},{0.293928f,0.0229434f,0.123996f}, +{0.300398f,0.0255715f,0.12158f},{0.298642f,0.0252917f,0.122194f},{0.305563f,0.0244044f,0.123358f}, +{0.307323f,0.0244252f,0.122798f},{0.305629f,0.0247822f,0.122798f},{0.294417f,0.0214191f,0.124659f}, +{0.302149f,0.0247609f,0.123358f},{0.303905f,0.0250231f,0.122798f},{0.302162f,0.0251442f,0.122798f}, +{0.300426f,0.0247607f,0.123358f},{0.307115f,0.0235834f,0.123843f},{0.30548f,0.0239281f,0.123843f}, +{0.305383f,0.0233768f,0.124229f},{0.306835f,0.0224524f,0.124501f},{0.308497f,0.0224714f,0.1243f}, +{0.306981f,0.02304f,0.124229f},{0.303865f,0.0246415f,0.123358f},{0.30816f,0.0214191f,0.124659f}, +{0.308333f,0.0219595f,0.124523f},{0.306687f,0.0218522f,0.124658f},{0.302177f,0.0255716f,0.12158f}, +{0.302171f,0.0254147f,0.122194f},{0.30395f,0.0254484f,0.12158f},{0.305703f,0.0252035f,0.12158f}, +{0.307425f,0.0248403f,0.12158f},{0.293582f,0.0240236f,0.12267f},{0.295254f,0.0244252f,0.122798f}, +{0.2969f,0.0250482f,0.122194f},{0.303933f,0.0252922f,0.122194f},{0.307388f,0.0246879f,0.122194f}, +{0.305676f,0.0250488f,0.122194f},{0.309105f,0.0243658f,0.121565f},{0.309064f,0.0242365f,0.12213f}, +{0.293675f,0.0237329f,0.123168f},{0.296946f,0.0247816f,0.122798f},{0.308996f,0.0240245f,0.122667f}, +{0.295742f,0.0224524f,0.124501f},{0.29408f,0.0224691f,0.124301f},{0.297013f,0.0244038f,0.123358f}, +{0.303815f,0.0241606f,0.123843f},{0.307231f,0.0240528f,0.123358f},{0.308903f,0.0237345f,0.123166f}, +{0.29876f,0.0241602f,0.123843f},{0.297096f,0.0239275f,0.123843f},{0.300443f,0.0242775f,0.123843f}, +{0.302132f,0.0242776f,0.123843f},{0.308786f,0.0233704f,0.123614f},{0.297193f,0.0233762f,0.124229f}, +{0.302113f,0.0237183f,0.124229f},{0.303757f,0.023604f,0.124229f},{0.308649f,0.0229455f,0.123995f}, +{0.294245f,0.0219573f,0.124524f},{0.300484f,0.0231133f,0.124501f},{0.302091f,0.0231134f,0.124501f}, +{0.303694f,0.023002f,0.124501f},{0.305172f,0.0221717f,0.124658f},{0.305279f,0.0227807f,0.124501f}, +{0.298946f,0.0223867f,0.124658f},{0.300505f,0.0224954f,0.124658f},{0.30207f,0.0224956f,0.124658f}, +{0.303629f,0.0223872f,0.124658f},{0.322989f,0.013557f,0.12158f},{0.321869f,0.0149379f,0.122194f}, +{0.322856f,0.0134738f,0.122194f},{0.321996f,0.0150302f,0.12158f},{0.32165f,0.0147789f,0.122798f}, +{0.322626f,0.0133304f,0.122798f},{0.321339f,0.0145536f,0.123358f},{0.319619f,0.0176259f,0.122194f}, +{0.319733f,0.0177348f,0.12158f},{0.31839f,0.018851f,0.122132f},{0.31824f,0.0186861f,0.12267f}, +{0.318547f,0.0144499f,0.124658f},{0.319021f,0.0148468f,0.124501f},{0.317514f,0.0156014f,0.124658f}, +{0.318482f,0.0189523f,0.121565f},{0.320907f,0.0164258f,0.12158f},{0.318396f,0.0164494f,0.124229f}, +{0.318799f,0.0168374f,0.123843f},{0.317478f,0.0178459f,0.123996f},{0.321416f,0.0125744f,0.124229f}, +{0.320495f,0.0139408f,0.124229f},{0.320005f,0.0135853f,0.124501f},{0.316402f,0.0166602f,0.124659f}, +{0.319148f,0.0171725f,0.123358f},{0.317779f,0.018178f,0.123614f},{0.324561f,0.00850026f,0.123358f}, +{0.325458f,0.0069868f,0.122798f},{0.324921f,0.00863187f,0.122798f},{0.322301f,0.0131272f,0.123358f}, +{0.323506f,0.0064225f,0.124501f},{0.324354f,0.00499264f,0.1243f},{0.324088f,0.00659057f,0.124229f}, +{0.32374f,0.0119427f,0.122194f},{0.323878f,0.0120165f,0.12158f},{0.324625f,0.006746f,0.123843f}, +{0.324106f,0.00833438f,0.123843f},{0.323581f,0.00814234f,0.124229f},{0.324267f,0.0102456f,0.122798f}, +{0.323917f,0.0100893f,0.123358f},{0.323162f,0.0116355f,0.123358f},{0.323501f,0.0118156f,0.122798f}, +{0.323274f,0.00475885f,0.124659f},{0.323828f,0.00487893f,0.124523f},{0.322912f,0.00625082f,0.124658f}, +{0.324658f,0.0104197f,0.12158f},{0.325323f,0.0087786f,0.12158f},{0.325869f,0.00710556f,0.12158f}, +{0.326298f,0.00541355f,0.121565f},{0.319424f,0.0174384f,0.122798f},{0.320786f,0.016325f,0.122194f}, +{0.324515f,0.0103558f,0.122194f},{0.325175f,0.00872472f,0.122194f},{0.325718f,0.00706195f,0.122194f}, +{0.326165f,0.00538482f,0.12213f},{0.318035f,0.0184599f,0.123168f},{0.320579f,0.0161513f,0.122798f}, +{0.325948f,0.00533772f,0.122667f},{0.31796f,0.0160299f,0.124501f},{0.317143f,0.017477f,0.124301f}, +{0.320285f,0.015905f,0.123358f},{0.323475f,0.00989244f,0.123843f},{0.32509f,0.00688027f,0.123358f}, +{0.32565f,0.00527328f,0.123166f},{0.320948f,0.0142696f,0.123843f},{0.319914f,0.0155946f,0.123843f}, +{0.321891f,0.012871f,0.123843f},{0.322735f,0.0114084f,0.123843f},{0.325276f,0.00519238f,0.123614f}, +{0.319485f,0.0152353f,0.124229f},{0.322241f,0.0111456f,0.124229f},{0.322964f,0.00966451f,0.124229f}, +{0.32484f,0.005098f,0.123995f},{0.316782f,0.0170789f,0.124524f},{0.320903f,0.0122538f,0.124501f}, +{0.321707f,0.0108613f,0.124501f},{0.322411f,0.00941806f,0.124501f},{0.322432f,0.0077226f,0.124658f}, +{0.323012f,0.00793471f,0.124501f},{0.319505f,0.0132221f,0.124658f},{0.320378f,0.0119262f,0.124658f}, +{0.321161f,0.010571f,0.124658f},{0.321847f,0.0091663f,0.124658f},{0.305432f,-0.00620072f,0.0995366f}, +{0.302686f,-0.00241971f,0.0995366f},{0.303085f,-0.00214016f,0.0995366f},{0.304143f,-0.00688999f,0.0995366f}, +{0.304805f,-0.00657676f,0.0995366f},{0.303454f,-0.00713669f,0.0995366f},{0.302245f,-0.00262702f,0.0995366f}, +{0.30602f,-0.00576486f,0.0995366f},{0.306563f,-0.00527335f,0.0995366f},{0.302744f,-0.00731445f,0.0995366f}, +{0.301774f,-0.00275405f,0.0995366f},{0.30343f,-0.00179629f,0.0995366f},{0.307054f,-0.004731f,0.0995366f}, +{0.302019f,-0.00742168f,0.0995366f},{0.301289f,-0.00279661f,0.0995366f},{0.30749f,-0.00414307f,0.0995366f}, +{0.30371f,-0.00139723f,0.0995366f},{0.301289f,-0.00745764f,0.0995366f},{0.300557f,-0.0074216f,0.0995366f}, +{0.299833f,-0.00731392f,0.0995366f},{0.300803f,-0.00275426f,0.0995366f},{0.299123f,-0.00713585f,0.0995366f}, +{0.300333f,-0.0026284f,0.0995366f},{0.308179f,-0.0028536f,0.0995366f},{0.307866f,-0.00351526f,0.0995366f}, +{0.297772f,-0.00657672f,0.0995366f},{0.298434f,-0.0068893f,0.0995366f},{0.308426f,-0.00216444f,0.0995366f}, +{0.303916f,-0.000955369f,0.0995366f},{0.304042f,-0.000484912f,0.0995366f},{0.299894f,-0.00241949f,0.0995366f}, +{0.308711f,-0.000730865f,0.0995366f},{0.308603f,-0.00145464f,0.0995366f},{0.299145f,-0.0018009f,0.0995366f}, +{0.299499f,-0.00213198f,0.0995366f},{0.296015f,-0.00527224f,0.0995366f},{0.294712f,-0.00351451f,0.0995366f}, +{0.294399f,-0.00285307f,0.0995366f},{0.29866f,-0.000957231f,0.0995366f},{0.298533f,-0.000485989f,0.0995366f}, +{0.293867f,-0.000730708f,0.0995366f},{0.294152f,-0.00216422f,0.0995366f},{0.293974f,-0.00145452f,0.0995366f}, +{0.296557f,-0.00576389f,0.0995366f},{0.297145f,-0.00620014f,0.0995366f},{0.295088f,-0.00414214f,0.0995366f}, +{0.298866f,-0.00139896f,0.0995366f},{0.295524f,-0.00472993f,0.0995366f},{0.301897f,0.0121618f,0.100469f}, +{0.303073f,0.0124736f,0.100469f},{0.30362f,0.0127432f,0.100469f},{0.303454f,-0.00713585f,0.100469f}, +{0.306649f,-0.0107204f,0.100469f},{0.30871f,-0.000730708f,0.100469f},{0.31345f,-0.00060826f,0.100469f}, +{0.308425f,-0.00216422f,0.100469f},{0.314032f,-0.002331f,0.100469f},{0.308178f,-0.00285307f,0.100469f}, +{0.305326f,0.0144494f,0.100469f},{0.305594f,0.0185639f,0.100469f},{0.315586f,-0.0131013f,0.100469f}, +{0.29849f,0.021256f,0.100469f},{0.32269f,-0.0006084f,0.100469f},{0.294397f,0.0203028f,0.100469f}, +{0.293084f,0.0198085f,0.100469f},{0.322568f,-0.00120559f,0.100469f},{0.322372f,-0.00178272f,0.100469f}, +{0.314772f,-0.00329614f,0.100469f},{0.307865f,-0.00351451f,0.100469f},{0.31437f,-0.00283787f,0.100469f}, +{0.292356f,-0.0114792f,0.100469f},{0.297563f,-0.0139787f,0.100469f},{0.297226f,-0.0144948f,0.100469f}, +{0.322105f,-0.00233026f,0.100469f},{0.321364f,-0.00329545f,0.100469f},{0.321766f,-0.00283697f,0.100469f}, +{0.320906f,-0.00369728f,0.100469f},{0.315199f,-0.0112779f,0.100469f},{0.315428f,-0.0115926f,0.100469f}, +{0.299123f,-0.00713669f,0.100469f},{0.298935f,-0.0127563f,0.100469f},{0.298434f,-0.00688999f,0.100469f}, +{0.320399f,-0.00403597f,0.100469f},{0.319852f,-0.00430572f,0.100469f},{0.318068f,-0.00466102f,0.100469f}, +{0.318677f,-0.00462104f,0.100469f},{0.319275f,-0.00450189f,0.100469f},{0.287152f,0.0161201f,0.100469f}, +{0.291806f,0.0192295f,0.100469f},{0.30007f,-0.0122874f,0.100469f},{0.299834f,-0.00731445f,0.100469f}, +{0.300558f,-0.00742168f,0.100469f},{0.31746f,-0.00462115f,0.100469f},{0.299486f,-0.0124812f,0.100469f}, +{0.307489f,-0.00414214f,0.100469f},{0.298425f,-0.0131016f,0.100469f},{0.315667f,-0.01233f,0.100469f}, +{0.290537f,0.0119471f,0.100469f},{0.290379f,0.0115917f,0.100469f},{0.299886f,0.0213951f,0.100469f}, +{0.304584f,0.0200754f,0.100469f},{0.304986f,0.0196172f,0.100469f},{0.307053f,-0.00472993f,0.100469f}, +{0.30595f,0.0167797f,0.100469f},{0.30591f,0.0173884f,0.100469f},{0.308603f,-0.00145452f,0.100469f}, +{0.313762f,-0.00178435f,0.100469f},{0.31345f,0.00961418f,0.100469f},{0.312223f,0.0087231f,0.100469f}, +{0.312593f,0.00884326f,0.100469f},{0.313608f,0.0099696f,0.100469f},{0.31293f,0.00903788f,0.100469f}, +{0.31322f,0.00929843f,0.100469f},{0.314909f,-0.0110163f,0.100469f},{0.314908f,-0.014033f,0.100469f}, +{0.314571f,-0.0142276f,0.100469f},{0.314571f,-0.0108212f,0.100469f},{0.316862f,-0.00450236f,0.100469f}, +{0.30602f,-0.00576389f,0.100469f},{0.306562f,-0.00527224f,0.100469f},{0.284279f,0.0130525f,0.100469f}, +{0.293769f,-0.0200792f,0.100469f},{0.292435f,-0.0195277f,0.100469f},{0.296679f,-0.0174727f,0.100469f}, +{0.304143f,-0.0068893f,0.100469f},{0.304805f,-0.00657672f,0.100469f},{0.30202f,-0.0074216f,0.100469f}, +{0.302744f,-0.00731392f,0.100469f},{0.286128f,0.0151611f,0.100469f},{0.285169f,0.0141371f,0.100469f}, +{0.288815f,0.00178435f,0.100469f},{0.289004f,0.00120563f,0.100469f},{0.301289f,-0.00745764f,0.100469f}, +{0.29696f,-0.0150508f,0.100469f},{0.292127f,-0.011795f,0.100469f},{0.290568f,0.00536018f,0.100469f}, +{0.292596f,-0.0107426f,0.100469f},{0.297965f,-0.0135115f,0.100469f},{0.283462f,0.0119121f,0.100469f}, +{0.293974f,-0.00145464f,0.100469f},{0.294152f,-0.00216444f,0.100469f},{0.293866f,-0.000730865f,0.100469f}, +{0.281671f,0.00369728f,0.100469f},{0.281213f,0.00329545f,0.100469f},{0.28026f,0.00418323f,0.100469f}, +{0.285469f,-0.0144727f,0.100469f},{0.284531f,-0.0133751f,0.100469f},{0.283669f,-0.0122169f,0.100469f}, +{0.296659f,-0.0162427f,0.100469f},{0.291141f,-0.0188874f,0.100469f},{0.288696f,-0.0173532f,0.100469f}, +{0.287556f,-0.0164664f,0.100469f},{0.296628f,-0.0168584f,0.100469f},{0.297021f,-0.018654f,0.100469f}, +{0.295138f,-0.0205396f,0.100469f},{0.296811f,-0.0180747f,0.100469f},{0.299634f,-0.0211335f,0.100469f}, +{0.299385f,-0.0213586f,0.100469f},{0.299072f,-0.0208805f,0.100469f},{0.29766f,-0.0197045f,0.100469f}, +{0.296534f,-0.0209071f,0.100469f},{0.297306f,-0.0192003f,0.100469f},{0.298078f,-0.0201577f,0.100469f}, +{0.298551f,-0.0205519f,0.100469f},{0.297955f,-0.0211663f,0.100469f},{0.300222f,-0.0213146f,0.100469f}, +{0.300829f,-0.021419f,0.100469f},{0.29113f,-0.0123703f,0.100469f},{0.289893f,-0.0181614f,0.100469f}, +{0.286479f,-0.0155048f,0.100469f},{0.282886f,-0.0110032f,0.100469f},{0.280042f,-0.00287961f,0.100469f}, +{0.280284f,-0.00430325f,0.100469f},{0.280621f,-0.00570752f,0.100469f},{0.313573f,-0.00120563f,0.100469f}, +{0.296557f,-0.00576486f,0.100469f},{0.292357f,-0.00961513f,0.100469f},{0.292128f,-0.00930035f,0.100469f}, +{0.282188f,-0.00973944f,0.100469f},{0.2915f,-0.0122501f,0.100469f},{0.279896f,-0.00144304f,0.100469f}, +{0.290149f,0.0112759f,0.100469f},{0.289859f,0.0110154f,0.100469f},{0.295523f,-0.004731f,0.100469f}, +{0.296014f,-0.00527335f,0.100469f},{0.291838f,-0.00903878f,0.100469f},{0.291501f,-0.00884365f,0.100469f}, +{0.291131f,-0.00872342f,0.100469f},{0.295087f,-0.00414307f,0.100469f},{0.292515f,-0.00997107f,0.100469f}, +{0.297145f,-0.00620072f,0.100469f},{0.297772f,-0.00657676f,0.100469f},{0.29677f,-0.0156368f,0.100469f}, +{0.291837f,-0.0120555f,0.100469f},{0.300674f,-0.0121629f,0.100469f},{0.315231f,-0.00369829f,0.100469f}, +{0.305432f,-0.00620014f,0.100469f},{0.315738f,-0.00403701f,0.100469f},{0.313689f,0.0107408f,0.100469f}, +{0.313222f,0.011793f,0.100469f},{0.305595f,0.0149963f,0.100469f},{0.303071f,0.0210836f,0.100469f}, +{0.297106f,0.0210266f,0.100469f},{0.290618f,0.0123283f,0.100469f},{0.295739f,0.0207091f,0.100469f}, +{0.288207f,0.00283787f,0.100469f},{0.287805f,0.00329614f,0.100469f},{0.288237f,0.0170101f,0.100469f}, +{0.282721f,0.0107207f,0.100469f},{0.280986f,0.00689212f,0.100469f},{0.282725f,0.00430572f,0.100469f}, +{0.280579f,0.00554954f,0.100469f},{0.294398f,-0.0028536f,0.100469f},{0.289377f,0.0178274f,0.100469f}, +{0.289523f,0.0142272f,0.100469f},{0.289153f,0.0143475f,0.100469f},{0.282059f,0.00948339f,0.100469f}, +{0.286292f,0.00430656f,0.100469f},{0.289127f,0.00060826f,0.100469f},{0.290379f,0.0134558f,0.100469f}, +{0.290151f,0.0137705f,0.100469f},{0.290619f,0.0127183f,0.100469f},{0.290569f,0.0185682f,0.100469f}, +{0.289861f,0.0140321f,0.100469f},{0.302494f,0.0122844f,0.100469f},{0.312932f,0.0120546f,0.100469f}, +{0.312594f,0.0122497f,0.100469f},{0.313689f,0.0103508f,0.100469f},{0.30591f,0.0161715f,0.100469f}, +{0.304126f,0.0130817f,0.100469f},{0.304585f,0.0134836f,0.100469f},{0.304987f,0.0139422f,0.100469f}, +{0.313609f,0.0111223f,0.100469f},{0.31345f,0.0114782f,0.100469f},{0.312224f,0.01237f,0.100469f}, +{0.316285f,-0.00430656f,0.100469f},{0.314202f,-0.0107009f,0.100469f},{0.314201f,-0.0143478f,0.100469f}, +{0.315197f,-0.0137725f,0.100469f},{0.315427f,-0.0134567f,0.100469f},{0.315667f,-0.0127201f,0.100469f}, +{0.315586f,-0.0119486f,0.100469f},{0.281052f,-0.00708565f,0.100469f},{0.281575f,-0.00843163f,0.100469f}, +{0.292596f,-0.0103525f,0.100469f},{0.292515f,-0.0111238f,0.100469f},{0.294711f,-0.00351526f,0.100469f}, +{0.290538f,0.0130998f,0.100469f},{0.305791f,0.0155736f,0.100469f},{0.30579f,0.0179866f,0.100469f}, +{0.305324f,0.0191105f,0.100469f},{0.304126f,0.0204775f,0.100469f},{0.303619f,0.0208166f,0.100469f}, +{0.301897f,0.0214014f,0.100469f},{0.302494f,0.021279f,0.100469f},{0.280205f,0.00178272f,0.100469f}, +{0.279894f,0.00140253f,0.100469f},{0.280031f,0.00279893f,0.100469f},{0.28148f,0.00820537f,0.100469f}, +{0.284509f,0.00466102f,0.100469f},{0.2839f,0.00462104f,0.100469f},{0.285117f,0.00462115f,0.100469f}, +{0.288545f,0.002331f,0.100469f},{0.285715f,0.00450236f,0.100469f},{0.287346f,0.00369829f,0.100469f}, +{0.286839f,0.00403701f,0.100469f},{0.289152f,0.0107006f,0.100469f},{0.289522f,0.0108208f,0.100469f}, +{0.283302f,0.00450189f,0.100469f},{0.282178f,0.00403597f,0.100469f},{0.280811f,0.00283697f,0.100469f}, +{0.280472f,0.00233026f,0.100469f},{0.279887f,0.0006084f,0.100469f},{0.280009f,0.00120559f,0.100469f}, +{0.323375f,-0.0130142f,0.119113f},{0.321024f,-0.0163617f,0.119113f},{0.284862f,0.0202853f,0.119113f}, +{0.283823f,0.0193978f,0.119113f},{0.324037f,-0.0118202f,0.119113f},{0.288238f,0.0226051f,0.119113f}, +{0.287073f,0.0218911f,0.119113f},{0.325627f,-0.00805156f,0.119113f},{0.291935f,0.0243682f,0.119113f}, +{0.290672f,0.0238452f,0.119113f},{0.326598f,-0.0040778f,0.119113f},{0.295862f,0.0255314f,0.119113f}, +{0.297205f,0.0257805f,0.119113f},{0.294533f,0.0252126f,0.119113f},{0.293223f,0.0248245f,0.119113f}, +{0.299923f,0.0260573f,0.119113f},{0.29856f,0.0259588f,0.119113f},{0.32688f,-0.00136419f,0.119113f}, +{0.326779f,-0.00272502f,0.119113f},{0.289439f,0.023257f,0.119113f},{0.326021f,-0.00674482f,0.119113f}, +{0.326345f,-0.00541896f,0.119113f},{0.285946f,0.0211172f,0.119113f},{0.324633f,-0.0105928f,0.119113f}, +{0.325164f,-0.00933541f,0.119113f},{0.282832f,0.0184571f,0.119113f},{0.281891f,0.0174659f,0.119113f}, +{0.322651f,-0.0141713f,0.119113f},{0.281004f,0.0164267f,0.119113f},{0.280172f,0.0153425f,0.119113f}, +{0.279398f,0.0142163f,0.119113f},{0.321867f,-0.0152881f,0.119113f},{0.278684f,0.0130512f,0.119113f}, +{0.278032f,0.0118502f,0.119113f},{0.320125f,-0.0173888f,0.119113f},{0.277443f,0.0106168f,0.119113f}, +{0.319173f,-0.0183667f,0.119113f},{0.27692f,0.00935425f,0.119113f},{0.31817f,-0.0192925f,0.119113f}, +{0.276464f,0.00806608f,0.119113f},{0.31712f,-0.0201635f,0.119113f},{0.276076f,0.00675581f,0.119113f}, +{0.316024f,-0.0209774f,0.119113f},{0.275757f,0.00542697f,0.119113f},{0.314887f,-0.021732f,0.119113f}, +{0.275508f,0.00408325f,0.119113f},{0.313711f,-0.022425f,0.119113f},{0.27533f,0.00272836f,0.119113f}, +{0.3125f,-0.0230545f,0.119113f},{0.275223f,0.00136603f,0.119113f},{0.311257f,-0.0236185f,0.119113f}, +{0.275187f,5.40871e-017f,0.119113f},{0.309985f,-0.0241155f,0.119113f},{0.275698f,-0.00136408f,0.119113f}, +{0.275223f,-0.0013662f,0.119113f},{0.308689f,-0.0245441f,0.119113f},{0.275798f,-0.00272485f,0.119113f}, +{0.27533f,-0.00272864f,0.119113f},{0.307373f,-0.0249032f,0.119113f},{0.275979f,-0.0040775f,0.119113f}, +{0.275508f,-0.00408356f,0.119113f},{0.306038f,-0.0251918f,0.119113f},{0.304691f,-0.0254089f,0.119113f}, +{0.301971f,-0.0256265f,0.119113f},{0.276232f,-0.00541865f,0.119113f},{0.275757f,-0.00542725f,0.119113f}, +{0.29856f,-0.025959f,0.119113f},{0.297886f,-0.0254087f,0.119113f},{0.297205f,-0.0257802f,0.119113f}, +{0.277413f,-0.00933492f,0.119113f},{0.27695f,-0.00805103f,0.119113f},{0.276921f,-0.00935456f,0.119113f}, +{0.294533f,-0.0252123f,0.119113f},{0.293887f,-0.0245439f,0.119113f},{0.293223f,-0.0248241f,0.119113f}, +{0.278684f,-0.0130514f,0.119113f},{0.27854f,-0.0118198f,0.119113f},{0.278032f,-0.0118505f,0.119113f}, +{0.289439f,-0.0232571f,0.119113f},{0.290673f,-0.0238453f,0.119113f},{0.290077f,-0.0230539f,0.119113f}, +{0.281004f,-0.0164269f,0.119113f},{0.28071f,-0.0152875f,0.119113f},{0.280172f,-0.0153428f,0.119113f}, +{0.284863f,-0.0202852f,0.119113f},{0.284407f,-0.019292f,0.119113f},{0.283824f,-0.0193978f,0.119113f}, +{0.288238f,-0.022605f,0.119113f},{0.288866f,-0.0224246f,0.119113f},{0.282452f,-0.0173882f,0.119113f}, +{0.281892f,-0.017466f,0.119113f},{0.282833f,-0.0184572f,0.119113f},{0.283404f,-0.0183661f,0.119113f}, +{0.285947f,-0.021117f,0.119113f},{0.287073f,-0.021891f,0.119113f},{0.286553f,-0.0209773f,0.119113f}, +{0.28769f,-0.0217317f,0.119113f},{0.281553f,-0.016361f,0.119113f},{0.285457f,-0.0201633f,0.119113f}, +{0.292591f,-0.0241152f,0.119113f},{0.291935f,-0.024368f,0.119113f},{0.29132f,-0.023618f,0.119113f}, +{0.279202f,-0.0130136f,0.119113f},{0.279398f,-0.0142166f,0.119113f},{0.279926f,-0.0141706f,0.119113f}, +{0.296538f,-0.0251915f,0.119113f},{0.295862f,-0.0255313f,0.119113f},{0.295204f,-0.024903f,0.119113f}, +{0.277944f,-0.0105924f,0.119113f},{0.277444f,-0.0106171f,0.119113f},{0.300606f,-0.0256265f,0.119113f}, +{0.299923f,-0.0260568f,0.119113f},{0.299243f,-0.0255538f,0.119113f},{0.276076f,-0.00675606f,0.119113f}, +{0.276556f,-0.00674437f,0.119113f},{0.276465f,-0.00806637f,0.119113f},{0.303334f,-0.0255539f,0.119113f}, +{0.295839f,-0.0255265f,0.10513f},{0.297181f,-0.0257766f,0.10513f},{0.298538f,-0.0259565f,0.10513f}, +{0.291931f,-0.0243666f,0.10513f},{0.294515f,-0.0252075f,0.10513f},{0.287092f,-0.0219036f,0.10513f}, +{0.288254f,-0.0226143f,0.10513f},{0.28945f,-0.0232624f,0.10513f},{0.290676f,-0.0238468f,0.10513f}, +{0.283834f,-0.0194069f,0.10513f},{0.285967f,-0.0211315f,0.10513f},{0.280157f,-0.0153222f,0.10513f}, +{0.28099f,-0.0164092f,0.10513f},{0.281882f,-0.0174549f,0.10513f},{0.282832f,-0.0184567f,0.10513f}, +{0.278026f,-0.0118391f,0.10513f},{0.279385f,-0.0141964f,0.10513f},{0.276081f,-0.00677408f,0.10513f}, +{0.276468f,-0.00807765f,0.10513f},{0.276922f,-0.00935809f,0.10513f},{0.277442f,-0.0106128f,0.10513f}, +{0.275512f,-0.0041079f,0.10513f},{0.275332f,-0.00275048f,0.10513f},{0.275762f,-0.00544996f,0.10513f}, +{0.275223f,0.00138025f,0.10513f},{0.275187f,4.23508e-018f,0.10513f},{0.275223f,-0.00138032f,0.10513f}, +{0.275762f,0.00544975f,0.10513f},{0.275512f,0.00410773f,0.10513f},{0.275332f,0.00275036f,0.10513f}, +{0.276468f,0.0080774f,0.10513f},{0.276081f,0.00677384f,0.10513f},{0.277442f,0.0106125f,0.10513f}, +{0.278026f,0.0118389f,0.10513f},{0.276922f,0.00935782f,0.10513f},{0.279385f,0.0141962f,0.10513f}, +{0.278674f,0.0130343f,0.10513f},{0.28099f,0.0164091f,0.10513f},{0.280157f,0.015322f,0.10513f}, +{0.282832f,0.0184567f,0.10513f},{0.281882f,0.0174549f,0.10513f},{0.283834f,0.0194069f,0.10513f}, +{0.284879f,0.0202988f,0.10513f},{0.285966f,0.0211314f,0.10513f},{0.287092f,0.0219036f,0.10513f}, +{0.288254f,0.0226142f,0.10513f},{0.289449f,0.0232623f,0.10513f},{0.290676f,0.0238467f,0.10513f}, +{0.29193f,0.0243664f,0.10513f},{0.293211f,0.0248204f,0.10513f},{0.294514f,0.0252074f,0.10513f}, +{0.295839f,0.0255265f,0.10513f},{0.297181f,0.0257765f,0.10513f},{0.298538f,0.0259565f,0.10513f}, +{0.299908f,0.0260652f,0.10513f},{0.278674f,-0.0130346f,0.10513f},{0.284879f,-0.0202989f,0.10513f}, +{0.293211f,-0.0248205f,0.10513f},{0.299908f,-0.0260653f,0.10513f},{0.284864f,-0.013782f,0.10513f}, +{0.288485f,-0.0171983f,0.10513f},{0.292797f,-0.0196871f,0.10513f},{0.297566f,-0.0211136f,0.10513f}, +{0.300042f,-0.0214048f,0.10513f},{0.2988f,-0.0212945f,0.10513f},{0.293956f,-0.0201477f,0.10513f}, +{0.291666f,-0.01916f,0.10513f},{0.290569f,-0.0185682f,0.10513f},{0.289507f,-0.0179136f,0.10513f}, +{0.285693f,-0.0147136f,0.10513f},{0.286575f,-0.0155955f,0.10513f},{0.287507f,-0.0164247f,0.10513f}, +{0.282721f,-0.0107207f,0.10513f},{0.283375f,-0.0117822f,0.10513f},{0.284091f,-0.0128038f,0.10513f}, +{0.282129f,-0.00962296f,0.10513f},{0.281602f,-0.00849262f,0.10513f},{0.281141f,-0.00733354f,0.10513f}, +{0.280749f,-0.00614966f,0.10513f},{0.280426f,-0.00494495f,0.10513f},{0.280174f,-0.00372348f,0.10513f}, +{0.279993f,-0.00248937f,0.10513f},{0.279884f,-0.00124681f,0.10513f},{0.279848f,-1.52221e-017f,0.10513f}, +{0.279884f,0.00124661f,0.10513f},{0.279993f,0.00248903f,0.10513f},{0.280174f,0.00372306f,0.10513f}, +{0.280426f,0.0049445f,0.10513f},{0.280748f,0.00614923f,0.10513f},{0.281141f,0.00733314f,0.10513f}, +{0.281601f,0.00849224f,0.10513f},{0.28272f,0.0107204f,0.10513f},{0.2988f,0.0212927f,0.10513f}, +{0.300041f,0.0214054f,0.10513f},{0.284864f,0.013782f,0.10513f},{0.296343f,0.0208628f,0.10513f}, +{0.295139f,0.0205399f,0.10513f},{0.287507f,0.0164248f,0.10513f},{0.286575f,0.0155957f,0.10513f}, +{0.290568f,0.0185682f,0.10513f},{0.289507f,0.0179135f,0.10513f},{0.288485f,0.0171982f,0.10513f}, +{0.292796f,0.0196873f,0.10513f},{0.293955f,0.0201477f,0.10513f},{0.291666f,0.0191602f,0.10513f}, +{0.297567f,0.0211056f,0.10513f},{0.285693f,0.0147138f,0.10513f},{0.283375f,0.011782f,0.10513f}, +{0.28409f,0.0128037f,0.10513f},{0.282128f,0.0096226f,0.10513f},{0.296344f,-0.02086f,0.10513f}, +{0.295139f,-0.0205402f,0.10513f},{0.296327f,-0.0208587f,0.104198f},{0.297545f,-0.0211115f,0.104198f}, +{0.298781f,-0.0212936f,0.104198f},{0.292798f,-0.019688f,0.104198f},{0.295127f,-0.0205363f,0.104198f}, +{0.288501f,-0.0172102f,0.104198f},{0.289523f,-0.0179243f,0.104198f},{0.290582f,-0.018576f,0.104198f}, +{0.291674f,-0.0191643f,0.104198f},{0.285689f,-0.0147088f,0.104198f},{0.287519f,-0.0164352f,0.104198f}, +{0.282713f,-0.010707f,0.104198f},{0.283364f,-0.0117656f,0.104198f},{0.284078f,-0.0127873f,0.104198f}, +{0.281143f,-0.00733859f,0.104198f},{0.281601f,-0.00849054f,0.104198f},{0.282124f,-0.0096143f,0.104198f}, +{0.279995f,-0.00250813f,0.104198f},{0.280177f,-0.00374334f,0.104198f},{0.28043f,-0.00496208f,0.104198f}, +{0.280752f,-0.00616144f,0.104198f},{0.279848f,-2.06038e-017f,0.104198f},{0.279885f,0.00125925f,0.104198f}, +{0.279885f,-0.00125938f,0.104198f},{0.280177f,0.00374312f,0.104198f},{0.279995f,0.00250793f,0.104198f}, +{0.281143f,0.0073385f,0.104198f},{0.280752f,0.00616138f,0.104198f},{0.28043f,0.00496191f,0.104198f}, +{0.282124f,0.00961408f,0.104198f},{0.281601f,0.00849036f,0.104198f},{0.284078f,0.0127873f,0.104198f}, +{0.283364f,0.0117655f,0.104198f},{0.282713f,0.0107068f,0.104198f},{0.285688f,0.0147082f,0.104198f}, +{0.284853f,0.0137691f,0.104198f},{0.28658f,0.0155998f,0.104198f},{0.287519f,0.0164352f,0.104198f}, +{0.288501f,0.0172102f,0.104198f},{0.289523f,0.0179242f,0.104198f},{0.290582f,0.018576f,0.104198f}, +{0.291674f,0.0191643f,0.104198f},{0.292798f,0.0196879f,0.104198f},{0.29395f,0.0201457f,0.104198f}, +{0.295127f,0.0205363f,0.104198f},{0.297545f,0.0211114f,0.104198f},{0.296326f,0.0208586f,0.104198f}, +{0.29878f,0.0212935f,0.104198f},{0.300029f,0.0214037f,0.104198f},{0.284853f,-0.0137693f,0.104198f}, +{0.28658f,-0.0156004f,0.104198f},{0.29395f,-0.0201457f,0.104198f},{0.300029f,-0.0214037f,0.104198f}, +{0.285399f,-0.0207081f,0.104198f},{0.275187f,2.47615e-017f,0.104198f},{0.275243f,-0.00170747f,0.104198f}, +{0.277174f,-0.0099892f,0.104198f},{0.275689f,-0.00509254f,0.104198f},{0.276076f,-0.00675606f,0.104198f}, +{0.277879f,-0.0115449f,0.104198f},{0.279586f,-0.0145019f,0.104198f},{0.280581f,-0.0158902f,0.104198f}, +{0.294533f,-0.0252123f,0.104198f},{0.296197f,-0.0256001f,0.104198f},{0.299582f,-0.0260375f,0.104198f}, +{0.288238f,-0.022605f,0.104198f},{0.289744f,-0.0234101f,0.104198f},{0.2913f,-0.0241149f,0.104198f}, +{0.292899f,-0.0247164f,0.104198f},{0.286788f,-0.0217031f,0.104198f},{0.282833f,-0.0184572f,0.104198f}, +{0.284079f,-0.0196247f,0.104198f},{0.297882f,-0.0258794f,0.104198f},{0.281665f,-0.0172106f,0.104198f}, +{0.278684f,-0.0130514f,0.104198f},{0.276572f,-0.00839068f,0.104198f},{0.27541f,-0.00340738f,0.104198f}, +{0.275243f,0.00170697f,0.104198f},{0.27541f,0.0034068f,0.104198f},{0.276572f,0.00839024f,0.104198f}, +{0.276076f,0.00675581f,0.104198f},{0.275688f,0.00509225f,0.104198f},{0.277174f,0.00998889f,0.104198f}, +{0.277879f,0.0115449f,0.104198f},{0.278684f,0.0130512f,0.104198f},{0.280581f,0.0158901f,0.104198f}, +{0.279586f,0.0145016f,0.104198f},{0.281664f,0.0172105f,0.104198f},{0.284079f,0.0196248f,0.104198f}, +{0.286787f,0.0217032f,0.104198f},{0.285399f,0.0207084f,0.104198f},{0.288238f,0.0226051f,0.104198f}, +{0.289744f,0.0234102f,0.104198f},{0.297881f,0.0258786f,0.104198f},{0.299581f,0.0260403f,0.104198f}, +{0.296196f,0.0256003f,0.104198f},{0.294533f,0.0252126f,0.104198f},{0.292898f,0.0247167f,0.104198f}, +{0.282832f,0.0184571f,0.104198f},{0.2913f,0.024115f,0.104198f},{0.289869f,0.0197792f,0.101587f}, +{0.288101f,0.0186469f,0.101587f},{0.288937f,0.0213938f,0.103079f},{0.28338f,0.0141739f,0.101587f}, +{0.284829f,0.0158335f,0.101587f},{0.286412f,0.0173289f,0.101587f},{0.278843f,0.00421973f,0.101587f}, +{0.279347f,0.00633871f,0.101587f},{0.280059f,0.00842303f,0.101587f},{0.27845f,6.45552e-018f,0.101587f}, +{0.278546f,0.00209801f,0.101587f},{0.288937f,-0.0213938f,0.103079f},{0.289869f,-0.0197792f,0.101587f}, +{0.291137f,-0.0204589f,0.101587f},{0.292465f,-0.0210659f,0.101587f},{0.293848f,-0.0215929f,0.101587f}, +{0.295277f,-0.0220336f,0.101587f},{0.296745f,-0.0223824f,0.101587f},{0.298242f,-0.022635f,0.101587f}, +{0.29976f,-0.0227878f,0.101587f},{0.294786f,-0.0238322f,0.103079f},{0.296374f,-0.0242096f,0.103079f}, +{0.290308f,-0.0221291f,0.103079f},{0.297994f,-0.0244827f,0.103079f},{0.299636f,-0.0246481f,0.103079f}, +{0.29324f,-0.0233556f,0.103079f},{0.291745f,-0.0227855f,0.103079f},{0.282089f,0.0123693f,0.101587f}, +{0.280977f,0.0104434f,0.101587f},{0.285197f,0.0187434f,0.103079f},{0.276585f,8.86415e-018f,0.103079f}, +{0.27669f,0.00226809f,0.103079f},{0.27701f,0.00456378f,0.103079f},{0.277555f,0.00685491f,0.103079f}, +{0.278326f,0.00910982f,0.103079f},{0.279319f,0.011295f,0.103079f},{0.280521f,0.0133782f,0.103079f}, +{0.281917f,0.0153304f,0.103079f},{0.283484f,0.0171254f,0.103079f},{0.287024f,0.0201689f,0.103079f}, +{0.326888f,-0.00136552f,0.120977f},{0.326779f,-0.00272732f,0.120977f},{0.315039f,-0.0216357f,0.120977f}, +{0.31683f,-0.0203873f,0.120977f},{0.31315f,-0.0227264f,0.120977f},{0.311173f,-0.0236533f,0.120977f}, +{0.291403f,-0.0236531f,0.120977f},{0.289427f,-0.0227263f,0.120977f},{0.285747f,-0.0203871f,0.120977f}, +{0.287538f,-0.0216356f,0.120977f},{0.27598f,-0.0040808f,0.120977f},{0.275798f,-0.00272711f,0.120977f}, +{0.275689f,-0.00136573f,0.120977f},{0.326597f,-0.00408095f,0.120977f},{0.289129f,0.000612842f,0.103265f}, +{0.288547f,0.00232777f,0.103265f},{0.288815f,0.00178369f,0.103265f},{0.28901f,0.00120978f,0.103265f}, +{0.287343f,0.00370055f,0.103265f},{0.288209f,0.0028342f,0.103265f},{0.287805f,0.00329584f,0.103265f}, +{0.285121f,0.00462066f,0.103265f},{0.285718f,0.00450141f,0.103265f},{0.286293f,0.00430621f,0.103265f}, +{0.283896f,0.00462052f,0.103265f},{0.283299f,0.00450127f,0.103265f},{0.284509f,0.00466102f,0.103265f}, +{0.282181f,0.00403818f,0.103265f},{0.282725f,0.00430621f,0.103265f},{0.281213f,0.00329584f,0.103265f}, +{0.281675f,0.00370041f,0.103265f},{0.280808f,0.00283386f,0.103265f},{0.280471f,0.00232743f,0.103265f}, +{0.280203f,0.00178369f,0.103265f},{0.280007f,0.00120944f,0.103265f},{0.279888f,0.000612502f,0.103265f}, +{0.286836f,0.00403832f,0.103265f},{0.291501f,-0.00884266f,0.109791f},{0.291838f,-0.00903773f,0.109791f}, +{0.29113f,-0.00872205f,0.109791f},{0.292128f,-0.00929879f,0.109791f},{0.292357f,-0.00961469f,0.109791f}, +{0.292515f,-0.00997137f,0.109791f},{0.292596f,-0.0103527f,0.109791f},{0.292596f,-0.0107427f,0.109791f}, +{0.292354f,-0.0114796f,0.109791f},{0.292514f,-0.011124f,0.109791f},{0.291836f,-0.0120547f,0.109791f}, +{0.292125f,-0.0117943f,0.109791f},{0.291129f,-0.0123696f,0.109791f},{0.291499f,-0.0122492f,0.109791f}, +{0.314571f,-0.0108202f,0.109791f},{0.314909f,-0.0110152f,0.109791f},{0.314201f,-0.0106996f,0.109791f}, +{0.315199f,-0.0112763f,0.109791f},{0.315428f,-0.0115922f,0.109791f},{0.315586f,-0.0119489f,0.109791f}, +{0.315667f,-0.0123302f,0.109791f},{0.315667f,-0.0127202f,0.109791f},{0.315425f,-0.0134571f,0.109791f}, +{0.315585f,-0.0131015f,0.109791f},{0.314907f,-0.0140322f,0.109791f},{0.315196f,-0.0137718f,0.109791f}, +{0.3142f,-0.0143471f,0.109791f},{0.31457f,-0.0142268f,0.109791f},{0.312594f,0.0122507f,0.109791f}, +{0.312932f,0.0120557f,0.109791f},{0.312223f,0.0123713f,0.109791f},{0.313222f,0.0117946f,0.109791f}, +{0.313451f,0.0114787f,0.109791f},{0.313609f,0.011122f,0.109791f},{0.313689f,0.0107407f,0.109791f}, +{0.313689f,0.0103507f,0.109791f},{0.313448f,0.00961383f,0.109791f},{0.313607f,0.00996936f,0.109791f}, +{0.312929f,0.00903866f,0.109791f},{0.313219f,0.00929907f,0.109791f},{0.312222f,0.00872375f,0.109791f}, +{0.312592f,0.00884413f,0.109791f},{0.289523f,0.0142282f,0.109791f},{0.289861f,0.0140332f,0.109791f}, +{0.289152f,0.0143488f,0.109791f},{0.290151f,0.0137721f,0.109791f},{0.29038f,0.0134562f,0.109791f}, +{0.290538f,0.0130995f,0.109791f},{0.290619f,0.0127182f,0.109791f},{0.290618f,0.0123282f,0.109791f}, +{0.290377f,0.0115913f,0.109791f},{0.290536f,0.0119469f,0.109791f},{0.289858f,0.0110162f,0.109791f}, +{0.290148f,0.0112766f,0.109791f},{0.289151f,0.0107013f,0.109791f},{0.289521f,0.0108216f,0.109791f}, +{0.300676f,-0.0121592f,0.103265f},{0.298961f,-0.0127415f,0.103265f},{0.300079f,-0.0122784f,0.103265f}, +{0.299505f,-0.0124735f,0.103265f},{0.297588f,-0.0139458f,0.103265f},{0.29725f,-0.0144523f,0.103265f}, +{0.297993f,-0.0134838f,0.103265f},{0.296668f,-0.0161672f,0.103265f},{0.296982f,-0.014996f,0.103265f}, +{0.296787f,-0.0155702f,0.103265f},{0.296787f,-0.0179895f,0.103265f},{0.296628f,-0.0167797f,0.103265f}, +{0.296668f,-0.0173925f,0.103265f},{0.29725f,-0.0191075f,0.103265f},{0.297588f,-0.0196139f,0.103265f}, +{0.296982f,-0.0185634f,0.103265f},{0.297993f,-0.0200755f,0.103265f},{0.298455f,-0.0204802f,0.103265f}, +{0.298961f,-0.020818f,0.103265f},{0.299505f,-0.0210859f,0.103265f},{0.300079f,-0.0212811f,0.103265f}, +{0.300676f,-0.0214003f,0.103265f},{0.298454f,-0.0130793f,0.103265f},{0.313448f,-0.000612842f,0.103265f}, +{0.31403f,-0.00232777f,0.103265f},{0.313762f,-0.00178369f,0.103265f},{0.313567f,-0.00120978f,0.103265f}, +{0.315234f,-0.00370055f,0.103265f},{0.314368f,-0.0028342f,0.103265f},{0.314772f,-0.00329584f,0.103265f}, +{0.317456f,-0.00462066f,0.103265f},{0.316859f,-0.00450141f,0.103265f},{0.316285f,-0.00430621f,0.103265f}, +{0.319278f,-0.00450127f,0.103265f},{0.318681f,-0.00462052f,0.103265f},{0.318068f,-0.00466102f,0.103265f}, +{0.320396f,-0.00403818f,0.103265f},{0.319852f,-0.00430621f,0.103265f},{0.321364f,-0.00329584f,0.103265f}, +{0.320902f,-0.00370041f,0.103265f},{0.321769f,-0.00283386f,0.103265f},{0.322107f,-0.00232743f,0.103265f}, +{0.322374f,-0.00178369f,0.103265f},{0.32257f,-0.00120944f,0.103265f},{0.322689f,-0.000612502f,0.103265f}, +{0.315741f,-0.00403832f,0.103265f},{0.301901f,0.0121592f,0.103265f},{0.303616f,0.0127415f,0.103265f}, +{0.303072f,0.0124735f,0.103265f},{0.302498f,0.0122784f,0.103265f},{0.304989f,0.0139458f,0.103265f}, +{0.304123f,0.0130793f,0.103265f},{0.304584f,0.0134838f,0.103265f},{0.305909f,0.0161672f,0.103265f}, +{0.30579f,0.0155702f,0.103265f},{0.305595f,0.014996f,0.103265f},{0.305909f,0.0173925f,0.103265f}, +{0.30579f,0.0179895f,0.103265f},{0.30595f,0.0167797f,0.103265f},{0.305327f,0.0191075f,0.103265f}, +{0.305595f,0.0185634f,0.103265f},{0.304584f,0.0200755f,0.103265f},{0.304989f,0.0196139f,0.103265f}, +{0.304122f,0.0204802f,0.103265f},{0.303616f,0.020818f,0.103265f},{0.303072f,0.0210859f,0.103265f}, +{0.302498f,0.0212811f,0.103265f},{0.301901f,0.0214003f,0.103265f},{0.305327f,0.0144523f,0.103265f}, +{0.312708f,-0.0197792f,0.103265f},{0.31077f,-0.0207778f,0.103265f},{0.304545f,-0.0226057f,0.103265f}, +{0.308754f,-0.0215843f,0.103265f},{0.298032f,-0.0226056f,0.103265f},{0.302379f,-0.022813f,0.103265f}, +{0.300197f,-0.0228129f,0.103265f},{0.293823f,-0.0215842f,0.103265f},{0.295902f,-0.0221948f,0.103265f}, +{0.291806f,-0.0207777f,0.103265f},{0.289869f,-0.0197792f,0.103265f},{0.306674f,-0.0221949f,0.103265f}, +{0.31364f,-0.0213938f,0.103265f},{0.288937f,-0.0213938f,0.103265f},{0.291033f,-0.022474f,0.103265f}, +{0.297767f,-0.0244511f,0.103265f},{0.293213f,-0.0233463f,0.103265f},{0.304811f,-0.024451f,0.103265f}, +{0.300109f,-0.0246752f,0.103265f},{0.302469f,-0.0246752f,0.103265f},{0.309364f,-0.0233462f,0.103265f}, +{0.311545f,-0.0224738f,0.103265f},{0.307114f,-0.0240066f,0.103265f},{0.295463f,-0.0240067f,0.103265f}, +{0.314542f,0.0186002f,0.103265f},{0.312708f,0.0197792f,0.103265f},{0.319238f,0.0141228f,0.103265f}, +{0.317817f,0.0157616f,0.103265f},{0.316248f,0.0172577f,0.103265f},{0.321591f,0.0104612f,0.103265f}, +{0.322494f,0.00848256f,0.103265f},{0.3205f,0.0123508f,0.103265f},{0.323714f,0.00432634f,0.103265f}, +{0.323203f,0.00643279f,0.103265f},{0.324024f,0.00217707f,0.103265f},{0.324128f,-1.5323e-017f,0.103265f}, +{0.31364f,0.0213938f,0.103265f},{0.325992f,-1.67506e-017f,0.103265f},{0.325879f,0.00235542f,0.103265f}, +{0.324225f,0.00917539f,0.103265f},{0.324992f,0.0069585f,0.103265f},{0.325545f,0.00467972f,0.103265f}, +{0.322068f,0.01336f,0.103265f},{0.320703f,0.015276f,0.103265f},{0.323248f,0.0113162f,0.103265f}, +{0.319166f,0.0170487f,0.103265f},{0.317469f,0.0186667f,0.103265f},{0.315623f,0.020119f,0.103265f}, +{0.278554f,0.00217765f,0.103265f},{0.27845f,2.16517e-018f,0.103265f},{0.280083f,0.00848291f,0.103265f}, +{0.279374f,0.00643333f,0.103265f},{0.278863f,0.00432654f,0.103265f},{0.282078f,0.0123517f,0.103265f}, +{0.28334f,0.0141231f,0.103265f},{0.280987f,0.0104622f,0.103265f},{0.286329f,0.0172579f,0.103265f}, +{0.28476f,0.015762f,0.103265f},{0.288036f,0.0186006f,0.103265f},{0.289869f,0.0197792f,0.103265f}, +{0.276585f,1.02508e-017f,0.103265f},{0.288937f,0.0213938f,0.103265f},{0.286953f,0.0201186f,0.103265f}, +{0.281874f,0.0152757f,0.103265f},{0.283411f,0.0170482f,0.103265f},{0.285108f,0.0186665f,0.103265f}, +{0.279329f,0.0113151f,0.103265f},{0.278352f,0.00917501f,0.103265f},{0.280509f,0.013359f,0.103265f}, +{0.277585f,0.00695792f,0.103265f},{0.277032f,0.00467951f,0.103265f},{0.276698f,0.00235479f,0.103265f}, +{0.298535f,-0.000488516f,0.0976722f},{0.299146f,-0.00179767f,0.0976722f},{0.298866f,-0.00139727f,0.0976722f}, +{0.298661f,-0.000957717f,0.0976722f},{0.300332f,-0.00262801f,0.0976722f},{0.300801f,-0.00275376f,0.0976722f}, +{0.299493f,-0.00214411f,0.0976722f},{0.299893f,-0.00242333f,0.0976722f},{0.302246f,-0.00262748f,0.0976722f}, +{0.301777f,-0.00275356f,0.0976722f},{0.301289f,-0.00279661f,0.0976722f},{0.303086f,-0.00214219f,0.0976722f}, +{0.302686f,-0.00242266f,0.0976722f},{0.303433f,-0.00179504f,0.0976722f},{0.303712f,-0.00139564f,0.0976722f}, +{0.303917f,-0.000956449f,0.0976722f},{0.304042f,-0.000488516f,0.0976722f},{0.318698f,-0.00122594f,0.120977f}, +{0.318576f,-0.00061944f,0.120977f},{0.318534f,2.3413e-019f,0.120977f},{0.318901f,-0.0018111f,0.120977f}, +{0.319529f,-0.00287862f,0.120977f},{0.31918f,-0.00236645f,0.120977f},{0.319943f,-0.00333866f,0.120977f}, +{0.320415f,-0.00374077f,0.120977f},{0.320937f,-0.00407752f,0.120977f},{0.321498f,-0.00434093f,0.120977f}, +{0.322088f,-0.00452747f,0.120977f},{0.322699f,-0.00463457f,0.120977f},{0.318576f,0.000619763f,0.120977f}, +{0.318698f,0.00122605f,0.120977f},{0.318901f,0.00181151f,0.120977f},{0.31918f,0.00236685f,0.120977f}, +{0.31953f,0.00287881f,0.120977f},{0.319943f,0.00333885f,0.120977f},{0.320415f,0.00374104f,0.120977f}, +{0.320938f,0.00407771f,0.120977f},{0.321498f,0.00434097f,0.120977f},{0.322088f,0.00452758f,0.120977f}, +{0.322699f,0.00463457f,0.120977f},{0.308905f,0.00708542f,0.120977f},{0.309508f,0.00862355f,0.120977f}, +{0.309231f,0.0081433f,0.120977f},{0.309029f,0.00762768f,0.120977f},{0.31073f,0.00975654f,0.120977f}, +{0.309858f,0.00906182f,0.120977f},{0.31027f,0.00944325f,0.120977f},{0.312873f,0.0102431f,0.120977f}, +{0.312313f,0.0102438f,0.120977f},{0.311758f,0.0101602f,0.120977f},{0.313954f,0.0099962f,0.120977f}, +{0.313425f,0.0101597f,0.120977f},{0.314916f,0.00944071f,0.120977f},{0.315326f,0.00905963f,0.120977f}, +{0.314454f,0.00975564f,0.120977f},{0.315674f,0.00862291f,0.120977f},{0.315951f,0.0081413f,0.120977f}, +{0.316154f,0.00762524f,0.120977f},{0.316277f,0.00708542f,0.120977f},{0.311229f,0.00999655f,0.120977f}, +{0.308787f,0.000388892f,0.120977f},{0.309364f,0.0013863f,0.120977f},{0.308908f,0.000758756f,0.120977f}, +{0.310416f,0.00185425f,0.120977f},{0.309679f,0.00161492f,0.120977f},{0.310035f,0.0017734f,0.120977f}, +{0.311188f,0.00177278f,0.120977f},{0.311543f,0.0016145f,0.120977f},{0.310806f,0.00185398f,0.120977f}, +{0.311859f,0.00138471f,0.120977f},{0.312119f,0.00109509f,0.120977f},{0.312314f,0.000757801f,0.120977f}, +{0.312434f,0.000387896f,0.120977f},{0.309103f,0.00109643f,0.120977f},{0.307612f,0.0184341f,0.120977f}, +{0.307586f,0.019053f,0.120977f},{0.307641f,0.0196708f,0.120977f},{0.307724f,0.0178247f,0.120977f}, +{0.307916f,0.0172353f,0.120977f},{0.308185f,0.0166765f,0.120977f},{0.308526f,0.0161585f,0.120977f}, +{0.309911f,0.0149353f,0.120977f},{0.310468f,0.0146616f,0.120977f},{0.308932f,0.0156903f,0.120977f}, +{0.309397f,0.0152802f,0.120977f},{0.311664f,0.0143468f,0.120977f},{0.312283f,0.0143112f,0.120977f}, +{0.31561f,0.0157495f,0.120977f},{0.315151f,0.015333f,0.120977f},{0.313508f,0.0144863f,0.120977f}, +{0.314092f,0.0146944f,0.120977f},{0.314643f,0.0149788f,0.120977f},{0.316008f,0.0162251f,0.120977f}, +{0.312901f,0.014358f,0.120977f},{0.311056f,0.0144643f,0.120977f},{0.307765f,0.0202771f,0.120977f}, +{0.30798f,0.0208597f,0.120977f},{0.29896f,0.0101384f,0.120977f},{0.29793f,0.0114304f,0.120977f}, +{0.298208f,0.0109503f,0.120977f},{0.298553f,0.0105172f,0.120977f},{0.29756f,0.0130549f,0.120977f}, +{0.297725f,0.011952f,0.120977f},{0.297601f,0.0124996f,0.120977f},{0.29821f,0.0151544f,0.120977f}, +{0.297929f,0.0146689f,0.120977f},{0.297725f,0.0141474f,0.120977f},{0.298964f,0.0159666f,0.120977f}, +{0.298558f,0.01559f,0.120977f},{0.299926f,0.0165217f,0.120977f},{0.300461f,0.0166864f,0.120977f}, +{0.299423f,0.0162794f,0.120977f},{0.301014f,0.0167695f,0.120977f},{0.301569f,0.016769f,0.120977f}, +{0.302118f,0.0166865f,0.120977f},{0.302647f,0.0165233f,0.120977f},{0.297601f,0.0136068f,0.120977f}, +{0.304701f,0.00668844f,0.120977f},{0.304126f,0.00768651f,0.120977f},{0.304441f,0.00697788f,0.120977f}, +{0.304247f,0.00883213f,0.120977f},{0.304085f,0.00807381f,0.120977f},{0.304126f,0.0084617f,0.120977f}, +{0.304703f,0.00945932f,0.120977f},{0.305018f,0.00968801f,0.120977f},{0.304442f,0.00916954f,0.120977f}, +{0.305374f,0.00984652f,0.120977f},{0.305755f,0.00992735f,0.120977f},{0.306145f,0.00992722f,0.120977f}, +{0.306526f,0.00984624f,0.120977f},{0.304246f,0.00731557f,0.120977f},{0.287937f,0.0149805f,0.120977f}, +{0.28743f,0.0153371f,0.120977f},{0.293646f,0.0156909f,0.120977f},{0.293181f,0.0152805f,0.120977f}, +{0.294052f,0.0161593f,0.120977f},{0.292666f,0.0149353f,0.120977f},{0.294392f,0.0166773f,0.120977f}, +{0.29466f,0.0172358f,0.120977f},{0.294853f,0.0178252f,0.120977f},{0.29211f,0.0146618f,0.120977f}, +{0.291522f,0.0144645f,0.120977f},{0.294964f,0.0184349f,0.120977f},{0.290913f,0.0143468f,0.120977f}, +{0.294994f,0.0190544f,0.120977f},{0.29481f,0.0202777f,0.120977f},{0.294941f,0.0196718f,0.120977f}, +{0.290295f,0.0143109f,0.120977f},{0.294597f,0.0208597f,0.120977f},{0.289676f,0.0143575f,0.120977f}, +{0.288486f,0.0146931f,0.120977f},{0.28907f,0.0144856f,0.120977f},{0.286966f,0.0157476f,0.120977f}, +{0.286569f,0.0162251f,0.120977f},{0.291344f,0.00305297f,0.120977f},{0.28971f,0.00280688f,0.120977f}, +{0.290265f,0.00280698f,0.120977f},{0.290813f,0.00288948f,0.120977f},{0.288118f,0.00329833f,0.120977f}, +{0.289156f,0.00289017f,0.120977f},{0.28862f,0.00305631f,0.120977f},{0.286625f,0.00491125f,0.120977f}, +{0.286905f,0.00442515f,0.120977f},{0.287255f,0.00398713f,0.120977f},{0.286299f,0.00597044f,0.120977f}, +{0.286422f,0.00543021f,0.120977f},{0.286299f,0.00708102f,0.120977f},{0.286424f,0.00762679f,0.120977f}, +{0.286257f,0.00652376f,0.120977f},{0.286628f,0.0081466f,0.120977f},{0.286907f,0.00862774f,0.120977f}, +{0.287252f,0.00906124f,0.120977f},{0.287658f,0.00943791f,0.120977f},{0.287661f,0.00361021f,0.120977f}, +{0.297203f,0.0062997f,0.120977f},{0.29605f,0.00630037f,0.120977f},{0.296822f,0.00621894f,0.120977f}, +{0.295119f,0.0069779f,0.120977f},{0.295695f,0.00645888f,0.120977f},{0.295379f,0.0066883f,0.120977f}, +{0.294804f,0.00768661f,0.120977f},{0.294763f,0.00807365f,0.120977f},{0.294924f,0.00731544f,0.120977f}, +{0.294804f,0.00846171f,0.120977f},{0.294925f,0.00883217f,0.120977f},{0.29512f,0.00916947f,0.120977f}, +{0.29538f,0.00945876f,0.120977f},{0.296432f,0.00621907f,0.120977f},{0.283398f,-0.0023656f,0.120977f}, +{0.283676f,-0.00181168f,0.120977f},{0.283048f,-0.00287783f,0.120977f},{0.282634f,-0.00333905f,0.120977f}, +{0.282163f,-0.00374099f,0.120977f},{0.283879f,-0.00122583f,0.120977f},{0.281639f,-0.00407246f,0.120977f}, +{0.284002f,-0.000618365f,0.120977f},{0.284043f,7.02945e-018f,0.120977f},{0.284001f,0.000618856f,0.120977f}, +{0.283878f,0.00122657f,0.120977f},{0.283676f,0.00181243f,0.120977f},{0.283397f,0.00236609f,0.120977f}, +{0.283048f,0.00287783f,0.120977f},{0.282634f,0.00333893f,0.120977f},{0.282161f,0.00374048f,0.120977f}, +{0.281639f,0.00407552f,0.120977f},{0.281079f,0.00433883f,0.120977f},{0.280488f,0.0045282f,0.120977f}, +{0.279878f,0.00463457f,0.120977f},{0.28049f,-0.00452954f,0.120977f},{0.281077f,-0.00433369f,0.120977f}, +{0.279878f,-0.00463457f,0.120977f},{0.293673f,-0.00708542f,0.120977f},{0.293069f,-0.00862355f,0.120977f}, +{0.293346f,-0.0081433f,0.120977f},{0.293548f,-0.00762768f,0.120977f},{0.291847f,-0.00975654f,0.120977f}, +{0.292719f,-0.00906182f,0.120977f},{0.292307f,-0.00944325f,0.120977f},{0.289704f,-0.0102431f,0.120977f}, +{0.290265f,-0.0102438f,0.120977f},{0.290819f,-0.0101602f,0.120977f},{0.288623f,-0.0099962f,0.120977f}, +{0.289153f,-0.0101597f,0.120977f},{0.287661f,-0.00944071f,0.120977f},{0.287251f,-0.00905963f,0.120977f}, +{0.288123f,-0.00975564f,0.120977f},{0.286903f,-0.00862291f,0.120977f},{0.286626f,-0.0081413f,0.120977f}, +{0.286423f,-0.00762524f,0.120977f},{0.2863f,-0.00708542f,0.120977f},{0.291348f,-0.00999655f,0.120977f}, +{0.29379f,-0.000388892f,0.120977f},{0.293213f,-0.0013863f,0.120977f},{0.29367f,-0.000758756f,0.120977f}, +{0.292161f,-0.00185425f,0.120977f},{0.292898f,-0.00161492f,0.120977f},{0.292542f,-0.0017734f,0.120977f}, +{0.291389f,-0.00177278f,0.120977f},{0.291034f,-0.0016145f,0.120977f},{0.291771f,-0.00185398f,0.120977f}, +{0.290718f,-0.00138471f,0.120977f},{0.290458f,-0.00109509f,0.120977f},{0.290263f,-0.000757801f,0.120977f}, +{0.290143f,-0.000387896f,0.120977f},{0.293474f,-0.00109643f,0.120977f},{0.294991f,-0.019053f,0.120977f}, +{0.294965f,-0.0184341f,0.120977f},{0.286569f,-0.0162251f,0.120977f},{0.294853f,-0.0178247f,0.120977f}, +{0.294936f,-0.0196708f,0.120977f},{0.294661f,-0.0172353f,0.120977f},{0.294392f,-0.0166765f,0.120977f}, +{0.293645f,-0.0156903f,0.120977f},{0.293181f,-0.0152802f,0.120977f},{0.294051f,-0.0161585f,0.120977f}, +{0.290913f,-0.0143468f,0.120977f},{0.290294f,-0.0143112f,0.120977f},{0.292666f,-0.0149353f,0.120977f}, +{0.292109f,-0.0146616f,0.120977f},{0.286967f,-0.0157495f,0.120977f},{0.287426f,-0.015333f,0.120977f}, +{0.289069f,-0.0144863f,0.120977f},{0.288486f,-0.0146944f,0.120977f},{0.287935f,-0.0149788f,0.120977f}, +{0.289676f,-0.014358f,0.120977f},{0.291521f,-0.0144643f,0.120977f},{0.294812f,-0.0202771f,0.120977f}, +{0.294597f,-0.0208597f,0.120977f},{0.303617f,-0.0101384f,0.120977f},{0.304647f,-0.0114304f,0.120977f}, +{0.304369f,-0.0109503f,0.120977f},{0.304024f,-0.0105172f,0.120977f},{0.305017f,-0.0130549f,0.120977f}, +{0.304852f,-0.011952f,0.120977f},{0.304976f,-0.0124996f,0.120977f},{0.304367f,-0.0151544f,0.120977f}, +{0.304648f,-0.0146689f,0.120977f},{0.304853f,-0.0141474f,0.120977f},{0.303613f,-0.0159666f,0.120977f}, +{0.304019f,-0.01559f,0.120977f},{0.302651f,-0.0165217f,0.120977f},{0.302116f,-0.0166864f,0.120977f}, +{0.303154f,-0.0162794f,0.120977f},{0.301564f,-0.0167695f,0.120977f},{0.301008f,-0.016769f,0.120977f}, +{0.300459f,-0.0166865f,0.120977f},{0.29993f,-0.0165233f,0.120977f},{0.304976f,-0.0136068f,0.120977f}, +{0.297876f,-0.00668858f,0.120977f},{0.298451f,-0.00768692f,0.120977f},{0.298136f,-0.00697763f,0.120977f}, +{0.29833f,-0.00883211f,0.120977f},{0.298492f,-0.00807384f,0.120977f},{0.298451f,-0.00846133f,0.120977f}, +{0.297874f,-0.00945929f,0.120977f},{0.297559f,-0.00968796f,0.120977f},{0.298135f,-0.00916975f,0.120977f}, +{0.297203f,-0.00984651f,0.120977f},{0.296822f,-0.00992734f,0.120977f},{0.296432f,-0.00992724f,0.120977f}, +{0.296052f,-0.00984636f,0.120977f},{0.298331f,-0.00731545f,0.120977f},{0.308931f,-0.0156909f,0.120977f}, +{0.308525f,-0.0161593f,0.120977f},{0.309396f,-0.0152805f,0.120977f},{0.309911f,-0.0149353f,0.120977f}, +{0.308185f,-0.0166773f,0.120977f},{0.307917f,-0.0172358f,0.120977f},{0.307724f,-0.0178252f,0.120977f}, +{0.310468f,-0.0146618f,0.120977f},{0.307613f,-0.0184349f,0.120977f},{0.307584f,-0.0190544f,0.120977f}, +{0.311055f,-0.0144645f,0.120977f},{0.307636f,-0.0196718f,0.120977f},{0.311664f,-0.0143468f,0.120977f}, +{0.312283f,-0.0143109f,0.120977f},{0.307767f,-0.0202777f,0.120977f},{0.30798f,-0.0208597f,0.120977f}, +{0.312901f,-0.0143575f,0.120977f},{0.314091f,-0.0146931f,0.120977f},{0.313507f,-0.0144856f,0.120977f}, +{0.31464f,-0.0149805f,0.120977f},{0.315148f,-0.0153371f,0.120977f},{0.315611f,-0.0157476f,0.120977f}, +{0.316008f,-0.0162251f,0.120977f},{0.311233f,-0.00305297f,0.120977f},{0.312867f,-0.00280688f,0.120977f}, +{0.312312f,-0.00280698f,0.120977f},{0.311764f,-0.00288948f,0.120977f},{0.314459f,-0.00329833f,0.120977f}, +{0.313421f,-0.00289017f,0.120977f},{0.313957f,-0.00305631f,0.120977f},{0.315952f,-0.00491125f,0.120977f}, +{0.315672f,-0.00442515f,0.120977f},{0.315323f,-0.00398713f,0.120977f},{0.316278f,-0.00597044f,0.120977f}, +{0.316155f,-0.00543021f,0.120977f},{0.316278f,-0.00708102f,0.120977f},{0.316153f,-0.00762679f,0.120977f}, +{0.31632f,-0.00652376f,0.120977f},{0.315949f,-0.0081466f,0.120977f},{0.315671f,-0.00862774f,0.120977f}, +{0.315325f,-0.00906124f,0.120977f},{0.314919f,-0.00943791f,0.120977f},{0.314916f,-0.00361021f,0.120977f}, +{0.305375f,-0.0062997f,0.120977f},{0.306527f,-0.00630037f,0.120977f},{0.305755f,-0.00621894f,0.120977f}, +{0.307458f,-0.0069779f,0.120977f},{0.306882f,-0.00645888f,0.120977f},{0.307198f,-0.0066883f,0.120977f}, +{0.307773f,-0.00768661f,0.120977f},{0.307814f,-0.00807365f,0.120977f},{0.307653f,-0.00731544f,0.120977f}, +{0.307773f,-0.00846171f,0.120977f},{0.307652f,-0.00883217f,0.120977f},{0.307458f,-0.00916947f,0.120977f}, +{0.307197f,-0.00945876f,0.120977f},{0.306145f,-0.00621907f,0.120977f},{0.305909f,-0.000612842f,0.126571f}, +{0.305327f,-0.00232777f,0.126571f},{0.30579f,-0.00120978f,0.126571f},{0.304122f,-0.00370055f,0.126571f}, +{0.303616f,-0.00403832f,0.126571f},{0.304584f,-0.00329584f,0.126571f},{0.301901f,-0.00462066f,0.126571f}, +{0.303072f,-0.00430621f,0.126571f},{0.302498f,-0.00450141f,0.126571f},{0.300079f,-0.00450127f,0.126571f}, +{0.301289f,-0.00466102f,0.126571f},{0.300676f,-0.00462052f,0.126571f},{0.298961f,-0.00403818f,0.126571f}, +{0.298454f,-0.00370041f,0.126571f},{0.299505f,-0.00430621f,0.126571f},{0.297993f,-0.00329584f,0.126571f}, +{0.297588f,-0.00283386f,0.126571f},{0.29725f,-0.00232743f,0.126571f},{0.296982f,-0.00178369f,0.126571f}, +{0.296787f,-0.00120944f,0.126571f},{0.296668f,-0.000612502f,0.126571f},{0.304989f,-0.0028342f,0.126571f}, +{0.305595f,-0.00178369f,0.126571f},{0.299891f,-0.00241971f,0.126571f},{0.298535f,-0.000484912f,0.126571f}, +{0.298867f,-0.00139723f,0.126571f},{0.299147f,-0.00179629f,0.126571f},{0.298661f,-0.000955369f,0.126571f}, +{0.299492f,-0.00214016f,0.126571f},{0.300332f,-0.00262702f,0.126571f},{0.300803f,-0.00275405f,0.126571f}, +{0.301289f,-0.00279661f,0.126571f},{0.302244f,-0.0026284f,0.126571f},{0.301774f,-0.00275426f,0.126571f}, +{0.302684f,-0.00241949f,0.126571f},{0.304044f,-0.000485989f,0.126571f},{0.303078f,-0.00213198f,0.126571f}, +{0.303917f,-0.000957231f,0.126571f},{0.303711f,-0.00139896f,0.126571f},{0.303432f,-0.0018009f,0.126571f}, +{0.298533f,-0.000485989f,0.134028f},{0.29866f,-0.000957231f,0.134028f},{0.298866f,-0.00139896f,0.134028f}, +{0.299145f,-0.0018009f,0.134028f},{0.299499f,-0.00213198f,0.134028f},{0.299894f,-0.00241949f,0.134028f}, +{0.300333f,-0.0026284f,0.134028f},{0.300803f,-0.00275426f,0.134028f},{0.301289f,-0.00279661f,0.134028f}, +{0.301774f,-0.00275405f,0.134028f},{0.303085f,-0.00214016f,0.134028f},{0.303916f,-0.000955369f,0.134028f}, +{0.302245f,-0.00262702f,0.134028f},{0.302686f,-0.00241971f,0.134028f},{0.30343f,-0.00179629f,0.134028f}, +{0.30371f,-0.00139723f,0.134028f},{0.304042f,-0.000484912f,0.134028f},{5.39634e-017f,-0.298492f,0.127503f}, +{5.05671e-017f,-0.298492f,0.13496f},{0.000488516f,-0.298535f,0.13496f},{0.000957717f,-0.298661f,0.13496f}, +{0.00048723f,-0.298535f,0.127503f},{0.000956449f,-0.298661f,0.127503f},{0.00139564f,-0.298865f,0.127503f}, +{0.00179504f,-0.299144f,0.127503f},{0.00139727f,-0.298866f,0.13496f},{0.00179767f,-0.299146f,0.13496f}, +{0.00214219f,-0.299491f,0.127503f},{0.00214411f,-0.299493f,0.13496f},{0.00242266f,-0.299891f,0.127503f}, +{0.00262748f,-0.300331f,0.127503f},{0.00242333f,-0.299893f,0.13496f},{0.00262801f,-0.300332f,0.13496f}, +{0.00275356f,-0.3008f,0.127503f},{0.00275356f,-0.3008f,0.13496f},{0.00279661f,-0.301289f,0.13496f}, +{0.00279661f,-0.301289f,0.127503f},{-0.000488516f,-0.298535f,0.127503f},{-0.000957717f,-0.298661f,0.127503f}, +{-0.00048723f,-0.298535f,0.13496f},{-0.00139564f,-0.298865f,0.13496f},{-0.000956449f,-0.298661f,0.13496f}, +{-0.00139727f,-0.298866f,0.127503f},{-0.00179504f,-0.299144f,0.13496f},{-0.00179767f,-0.299146f,0.127503f}, +{-0.00214219f,-0.299491f,0.13496f},{-0.00242266f,-0.299891f,0.13496f},{-0.00214411f,-0.299493f,0.127503f}, +{-0.00242333f,-0.299893f,0.127503f},{-0.00262748f,-0.300331f,0.13496f},{-0.00262801f,-0.300332f,0.127503f}, +{-0.00275356f,-0.3008f,0.13496f},{-0.00275356f,-0.3008f,0.127503f},{-0.00279661f,-0.301289f,0.127503f}, +{-0.00279661f,-0.301289f,0.13496f},{4.80219e-017f,-0.296628f,0.125638f},{5.09198e-017f,-0.296628f,0.127503f}, +{0.000612842f,-0.296668f,0.127503f},{0.00120978f,-0.296787f,0.127503f},{0.000612502f,-0.296668f,0.125638f}, +{0.00178369f,-0.296982f,0.127503f},{0.00120944f,-0.296787f,0.125638f},{0.00178369f,-0.296982f,0.125638f}, +{0.00232777f,-0.29725f,0.127503f},{0.0028342f,-0.297588f,0.127503f},{0.00232743f,-0.29725f,0.125638f}, +{0.00329584f,-0.297993f,0.127503f},{0.00283386f,-0.297588f,0.125638f},{0.00329584f,-0.297993f,0.125638f}, +{0.00370055f,-0.298455f,0.127503f},{0.00403832f,-0.298961f,0.127503f},{0.00370041f,-0.298454f,0.125638f}, +{0.00430621f,-0.299505f,0.127503f},{0.00403818f,-0.298961f,0.125638f},{0.00450127f,-0.300079f,0.125638f}, +{0.00430621f,-0.299505f,0.125638f},{0.00450141f,-0.300079f,0.127503f},{0.00462052f,-0.300676f,0.125638f}, +{0.00462066f,-0.300676f,0.127503f},{0.00466102f,-0.301289f,0.125638f},{0.00466102f,-0.301289f,0.127503f}, +{-0.000612842f,-0.296668f,0.125638f},{-0.00120978f,-0.296787f,0.125638f},{-0.000612502f,-0.296668f,0.127503f}, +{-0.00120944f,-0.296787f,0.127503f},{-0.00178369f,-0.296982f,0.125638f},{-0.00232777f,-0.29725f,0.125638f}, +{-0.00178369f,-0.296982f,0.127503f},{-0.0028342f,-0.297588f,0.125638f},{-0.00232743f,-0.29725f,0.127503f}, +{-0.00283386f,-0.297588f,0.127503f},{-0.00329584f,-0.297993f,0.125638f},{-0.00370055f,-0.298455f,0.125638f}, +{-0.00329584f,-0.297993f,0.127503f},{-0.00403832f,-0.298961f,0.125638f},{-0.00370041f,-0.298454f,0.127503f}, +{-0.00403818f,-0.298961f,0.127503f},{-0.00430621f,-0.299505f,0.125638f},{-0.00450127f,-0.300079f,0.127503f}, +{-0.00430621f,-0.299505f,0.127503f},{-0.00450141f,-0.300079f,0.125638f},{-0.00462052f,-0.300676f,0.127503f}, +{-0.00466102f,-0.301289f,0.127503f},{-0.00462066f,-0.300676f,0.125638f},{-0.00466102f,-0.301289f,0.125638f}, +{0.00295812f,-0.310121f,0.125638f},{0.00315337f,-0.310458f,0.125638f},{0.00315227f,-0.310457f,0.121909f}, +{0.00295749f,-0.310119f,0.121909f},{0.0028374f,-0.30975f,0.125638f},{0.00283721f,-0.309748f,0.121909f}, +{0.00279657f,-0.309361f,0.121909f},{0.00283728f,-0.308975f,0.125638f},{0.00279668f,-0.309362f,0.125638f}, +{0.0028377f,-0.308973f,0.121909f},{0.00295753f,-0.308604f,0.125638f},{0.00295825f,-0.308603f,0.121909f}, +{0.0031524f,-0.308266f,0.125638f},{0.00315303f,-0.308265f,0.121909f},{0.0034126f,-0.307977f,0.125638f}, +{0.0034133f,-0.307976f,0.121909f},{0.00372882f,-0.307747f,0.121909f},{0.00372882f,-0.307747f,0.125638f}, +{0.00341302f,-0.310747f,0.121909f},{0.00372824f,-0.310976f,0.121909f},{0.0034143f,-0.310748f,0.125638f}, +{0.00372908f,-0.310977f,0.125638f},{0.00408362f,-0.311134f,0.121909f},{0.00408596f,-0.311135f,0.125638f}, +{0.00446544f,-0.311216f,0.121909f},{0.00485544f,-0.311216f,0.121909f},{0.00446705f,-0.311216f,0.125638f}, +{0.00485646f,-0.311216f,0.125638f},{0.00523587f,-0.311135f,0.121909f},{0.00523689f,-0.311135f,0.125638f}, +{0.00559323f,-0.310976f,0.121909f},{0.00559323f,-0.310976f,0.125638f},{0.00794301f,-0.309432f,0.125638f}, +{0.00822403f,-0.309917f,0.125638f},{0.00822143f,-0.309914f,0.121909f},{0.00773834f,-0.30891f,0.125638f}, +{0.00794151f,-0.309428f,0.121909f},{0.00773817f,-0.308909f,0.121909f},{0.00761523f,-0.30837f,0.125638f}, +{0.00761511f,-0.308369f,0.121909f},{0.00757342f,-0.307816f,0.121909f},{0.00757373f,-0.307818f,0.125638f}, +{0.00761488f,-0.307263f,0.125638f},{0.00794445f,-0.306193f,0.121909f},{0.00822146f,-0.305713f,0.125638f}, +{0.00794412f,-0.306194f,0.125638f},{0.00761534f,-0.307258f,0.121909f},{0.00773918f,-0.306715f,0.125638f}, +{0.00774028f,-0.306713f,0.121909f},{0.00822277f,-0.305712f,0.121909f},{0.00856678f,-0.30528f,0.125638f}, +{0.00856839f,-0.305278f,0.121909f},{0.00897424f,-0.304902f,0.121909f},{0.00943797f,-0.304585f,0.125638f}, +{0.00897424f,-0.304902f,0.125638f},{0.00943797f,-0.304585f,0.121909f},{0.00857075f,-0.310352f,0.121909f}, +{0.00897738f,-0.310729f,0.121909f},{0.00857178f,-0.310353f,0.125638f},{0.00897811f,-0.31073f,0.125638f}, +{0.00943459f,-0.311041f,0.121909f},{0.00943645f,-0.311043f,0.125638f},{0.00993607f,-0.311283f,0.121909f}, +{0.0104724f,-0.311449f,0.121909f},{0.00994001f,-0.311285f,0.125638f},{0.0104751f,-0.31145f,0.125638f}, +{0.0110266f,-0.311533f,0.121909f},{0.0110274f,-0.311533f,0.125638f},{0.0115811f,-0.311532f,0.121909f}, +{0.0121288f,-0.31145f,0.121909f},{0.0115832f,-0.311532f,0.125638f},{0.0121315f,-0.31145f,0.125638f}, +{0.0126606f,-0.311286f,0.121909f},{0.0126606f,-0.311286f,0.125638f},{0.0131668f,-0.311043f,0.121909f}, +{0.0131668f,-0.311043f,0.125638f},{-0.00616977f,-0.308266f,0.125638f},{-0.00636455f,-0.308604f,0.125638f}, +{-0.00636392f,-0.308603f,0.121909f},{-0.00616867f,-0.308265f,0.121909f},{-0.00590902f,-0.307976f,0.125638f}, +{-0.00590775f,-0.307976f,0.121909f},{-0.00559297f,-0.307747f,0.121909f},{-0.00523843f,-0.307589f,0.125638f}, +{-0.00559381f,-0.307747f,0.125638f},{-0.00523609f,-0.307588f,0.121909f},{-0.00485661f,-0.307508f,0.125638f}, +{-0.00485499f,-0.307507f,0.121909f},{-0.0044666f,-0.307507f,0.125638f},{-0.00446558f,-0.307508f,0.121909f}, +{-0.00408618f,-0.307588f,0.125638f},{-0.00408515f,-0.307588f,0.121909f},{-0.00372882f,-0.307747f,0.121909f}, +{-0.00372882f,-0.307747f,0.125638f},{-0.00648464f,-0.308973f,0.121909f},{-0.00652537f,-0.309361f,0.121909f}, +{-0.00648484f,-0.308975f,0.125638f},{-0.00652548f,-0.309362f,0.125638f},{-0.00648477f,-0.309748f,0.121909f}, +{-0.00648435f,-0.30975f,0.125638f},{-0.00636452f,-0.310119f,0.121909f},{-0.00616965f,-0.310457f,0.121909f}, +{-0.0063638f,-0.310121f,0.125638f},{-0.00616901f,-0.310458f,0.125638f},{-0.00590945f,-0.310746f,0.121909f}, +{-0.00590875f,-0.310747f,0.125638f},{-0.00559323f,-0.310976f,0.121909f},{-0.00559323f,-0.310976f,0.125638f}, +{-0.00308095f,-0.312239f,0.125638f},{-0.00336087f,-0.312725f,0.125638f},{-0.00335937f,-0.312721f,0.121909f}, +{-0.00273163f,-0.311801f,0.125638f},{-0.00307835f,-0.312236f,0.121909f},{-0.0027306f,-0.3118f,0.121909f}, +{-0.002325f,-0.311424f,0.125638f},{-0.00232427f,-0.311424f,0.121909f},{-0.00186593f,-0.311111f,0.121909f}, +{-0.00186779f,-0.311112f,0.125638f},{-0.00136631f,-0.31087f,0.125638f},{-0.000274996f,-0.310621f,0.121909f}, +{0.0002787f,-0.310621f,0.125638f},{-0.000275788f,-0.310621f,0.125638f},{-0.00136237f,-0.310869f,0.121909f}, +{-0.000829945f,-0.310704f,0.125638f},{-0.000827251f,-0.310704f,0.121909f},{0.000280844f,-0.310621f,0.121909f}, +{0.000826454f,-0.310703f,0.125638f},{0.000829073f,-0.310704f,0.121909f},{0.00135821f,-0.310867f,0.121909f}, +{0.00186441f,-0.31111f,0.125638f},{0.00135821f,-0.310867f,0.125638f},{0.00186441f,-0.31111f,0.121909f}, +{-0.00356405f,-0.313243f,0.121909f},{-0.00368715f,-0.313783f,0.121909f},{-0.00356421f,-0.313244f,0.125638f}, +{-0.00368727f,-0.313784f,0.125638f},{-0.00372865f,-0.314335f,0.121909f},{-0.00372896f,-0.314338f,0.125638f}, +{-0.00368751f,-0.314891f,0.121909f},{-0.0035632f,-0.315438f,0.121909f},{-0.00368704f,-0.314895f,0.125638f}, +{-0.0035621f,-0.315441f,0.125638f},{-0.00335826f,-0.31596f,0.121909f},{-0.00335794f,-0.315961f,0.125638f}, +{-0.00308092f,-0.31644f,0.121909f},{-0.0027356f,-0.316873f,0.121909f},{-0.00307961f,-0.316442f,0.125638f}, +{-0.00273399f,-0.316875f,0.125638f},{-0.00232814f,-0.317252f,0.121909f},{-0.00232814f,-0.317252f,0.125638f}, +{-0.00186441f,-0.317569f,0.121909f},{-0.00186441f,-0.317569f,0.125638f},{-0.0091279f,-0.299434f,0.125638f}, +{-0.00951793f,-0.299435f,0.125638f},{-0.0095162f,-0.299434f,0.121909f},{-0.00912617f,-0.299435f,0.121909f}, +{-0.00874642f,-0.299515f,0.125638f},{-0.00874495f,-0.299516f,0.121909f},{-0.00838954f,-0.299674f,0.121909f}, +{-0.0080757f,-0.299902f,0.125638f},{-0.00839049f,-0.299674f,0.125638f},{-0.00807379f,-0.299904f,0.121909f}, +{-0.00781413f,-0.300192f,0.125638f},{-0.00781324f,-0.300193f,0.121909f},{-0.007619f,-0.30053f,0.125638f}, +{-0.00761862f,-0.300531f,0.121909f},{-0.00749878f,-0.3009f,0.125638f},{-0.00749845f,-0.300901f,0.121909f}, +{-0.00745764f,-0.301289f,0.121909f},{-0.00745764f,-0.301289f,0.125638f},{-0.00989767f,-0.299515f,0.121909f}, +{-0.0102536f,-0.299674f,0.121909f},{-0.00989914f,-0.299516f,0.125638f},{-0.0102546f,-0.299674f,0.125638f}, +{-0.0105684f,-0.299902f,0.121909f},{-0.0105703f,-0.299904f,0.125638f},{-0.01083f,-0.300192f,0.121909f}, +{-0.0110251f,-0.30053f,0.121909f},{-0.0108309f,-0.300193f,0.125638f},{-0.0110255f,-0.300531f,0.125638f}, +{-0.0111453f,-0.3009f,0.121909f},{-0.0111456f,-0.300901f,0.125638f},{-0.0111865f,-0.301289f,0.121909f}, +{-0.0111865f,-0.301289f,0.125638f},{-0.011024f,-0.304096f,0.125638f},{-0.0115849f,-0.304096f,0.125638f}, +{-0.0115808f,-0.304096f,0.121909f},{-0.01047f,-0.304179f,0.125638f},{-0.0110199f,-0.304096f,0.121909f}, +{-0.0104688f,-0.30418f,0.121909f},{-0.00994023f,-0.304343f,0.125638f},{-0.00993938f,-0.304343f,0.121909f}, +{-0.00943935f,-0.304584f,0.121909f},{-0.00944153f,-0.304583f,0.125638f},{-0.00898119f,-0.304896f,0.125638f}, +{-0.00821944f,-0.305716f,0.121909f},{-0.00794276f,-0.306196f,0.125638f},{-0.00821991f,-0.305716f,0.125638f}, +{-0.00897771f,-0.304899f,0.121909f},{-0.00856913f,-0.305278f,0.125638f},{-0.00856753f,-0.30528f,0.121909f}, +{-0.00794193f,-0.306198f,0.121909f},{-0.00774033f,-0.306712f,0.125638f},{-0.00773931f,-0.306714f,0.121909f}, +{-0.00761603f,-0.307254f,0.121909f},{-0.00757356f,-0.307814f,0.125638f},{-0.00761603f,-0.307254f,0.125638f}, +{-0.00757356f,-0.307814f,0.121909f},{-0.0121348f,-0.304179f,0.121909f},{-0.0126645f,-0.304343f,0.121909f}, +{-0.012136f,-0.30418f,0.125638f},{-0.0126654f,-0.304343f,0.125638f},{-0.0131632f,-0.304583f,0.121909f}, +{-0.0131654f,-0.304584f,0.125638f},{-0.0136236f,-0.304896f,0.121909f},{-0.0140356f,-0.305278f,0.121909f}, +{-0.0136271f,-0.304899f,0.125638f},{-0.0140372f,-0.30528f,0.125638f},{-0.0143849f,-0.305716f,0.121909f}, +{-0.0143853f,-0.305716f,0.125638f},{-0.014662f,-0.306196f,0.121909f},{-0.0148644f,-0.306712f,0.121909f}, +{-0.0146628f,-0.306198f,0.125638f},{-0.0148654f,-0.306714f,0.125638f},{-0.0149887f,-0.307254f,0.121909f}, +{-0.0149887f,-0.307254f,0.125638f},{-0.0150312f,-0.307814f,0.121909f},{-0.0150312f,-0.307814f,0.125638f}, +{-0.00295812f,-0.292456f,0.125638f},{-0.00315337f,-0.292119f,0.125638f},{-0.00315227f,-0.29212f,0.121909f}, +{-0.00295749f,-0.292458f,0.121909f},{-0.0028374f,-0.292827f,0.125638f},{-0.00283721f,-0.292829f,0.121909f}, +{-0.00279657f,-0.293216f,0.121909f},{-0.00283728f,-0.293602f,0.125638f},{-0.00279668f,-0.293215f,0.125638f}, +{-0.0028377f,-0.293604f,0.121909f},{-0.00295753f,-0.293973f,0.125638f},{-0.00295825f,-0.293975f,0.121909f}, +{-0.0031524f,-0.294311f,0.125638f},{-0.00315303f,-0.294312f,0.121909f},{-0.0034126f,-0.2946f,0.125638f}, +{-0.0034133f,-0.294601f,0.121909f},{-0.00372882f,-0.29483f,0.121909f},{-0.00372882f,-0.29483f,0.125638f}, +{-0.00341302f,-0.29183f,0.121909f},{-0.00372824f,-0.291601f,0.121909f},{-0.0034143f,-0.291829f,0.125638f}, +{-0.00372908f,-0.291601f,0.125638f},{-0.00408362f,-0.291443f,0.121909f},{-0.00408596f,-0.291442f,0.125638f}, +{-0.00446544f,-0.291361f,0.121909f},{-0.00485544f,-0.291361f,0.121909f},{-0.00446705f,-0.291361f,0.125638f}, +{-0.00485646f,-0.291361f,0.125638f},{-0.00523587f,-0.291442f,0.121909f},{-0.00523689f,-0.291442f,0.125638f}, +{-0.00559323f,-0.291601f,0.121909f},{-0.00559323f,-0.291601f,0.125638f},{-0.00794301f,-0.293145f,0.125638f}, +{-0.00822403f,-0.29266f,0.125638f},{-0.00822143f,-0.292663f,0.121909f},{-0.00773834f,-0.293667f,0.125638f}, +{-0.00794151f,-0.293149f,0.121909f},{-0.00773817f,-0.293668f,0.121909f},{-0.00761523f,-0.294207f,0.125638f}, +{-0.00761511f,-0.294208f,0.121909f},{-0.00757342f,-0.294761f,0.121909f},{-0.00757373f,-0.294759f,0.125638f}, +{-0.00761488f,-0.295314f,0.125638f},{-0.00794445f,-0.296384f,0.121909f},{-0.00822146f,-0.296864f,0.125638f}, +{-0.00794412f,-0.296384f,0.125638f},{-0.00761534f,-0.295319f,0.121909f},{-0.00773918f,-0.295862f,0.125638f}, +{-0.00774028f,-0.295864f,0.121909f},{-0.00822277f,-0.296865f,0.121909f},{-0.00856678f,-0.297297f,0.125638f}, +{-0.00856839f,-0.297299f,0.121909f},{-0.00897424f,-0.297676f,0.121909f},{-0.00943797f,-0.297992f,0.125638f}, +{-0.00897424f,-0.297676f,0.125638f},{-0.00943797f,-0.297992f,0.121909f},{-0.00857075f,-0.292225f,0.121909f}, +{-0.00897738f,-0.291848f,0.121909f},{-0.00857178f,-0.292224f,0.125638f},{-0.00897811f,-0.291847f,0.125638f}, +{-0.00943459f,-0.291536f,0.121909f},{-0.00943645f,-0.291535f,0.125638f},{-0.00993607f,-0.291294f,0.121909f}, +{-0.0104724f,-0.291128f,0.121909f},{-0.00994001f,-0.291292f,0.125638f},{-0.0104751f,-0.291128f,0.125638f}, +{-0.0110266f,-0.291045f,0.121909f},{-0.0110274f,-0.291044f,0.125638f},{-0.0115811f,-0.291045f,0.121909f}, +{-0.0121288f,-0.291127f,0.121909f},{-0.0115832f,-0.291045f,0.125638f},{-0.0121315f,-0.291128f,0.125638f}, +{-0.0126606f,-0.291291f,0.121909f},{-0.0126606f,-0.291291f,0.125638f},{-0.0131668f,-0.291534f,0.121909f}, +{-0.0131668f,-0.291534f,0.125638f},{0.00616977f,-0.294311f,0.125638f},{0.00636455f,-0.293973f,0.125638f}, +{0.00636392f,-0.293974f,0.121909f},{0.00616867f,-0.294312f,0.121909f},{0.00590902f,-0.294601f,0.125638f}, +{0.00590775f,-0.294602f,0.121909f},{0.00559297f,-0.29483f,0.121909f},{0.00523843f,-0.294988f,0.125638f}, +{0.00559381f,-0.29483f,0.125638f},{0.00523609f,-0.294989f,0.121909f},{0.00485661f,-0.29507f,0.125638f}, +{0.00485499f,-0.29507f,0.121909f},{0.0044666f,-0.29507f,0.125638f},{0.00446558f,-0.29507f,0.121909f}, +{0.00408618f,-0.294989f,0.125638f},{0.00408515f,-0.294989f,0.121909f},{0.00372882f,-0.29483f,0.121909f}, +{0.00372882f,-0.29483f,0.125638f},{0.00648464f,-0.293604f,0.121909f},{0.00652537f,-0.293216f,0.121909f}, +{0.00648484f,-0.293602f,0.125638f},{0.00652548f,-0.293215f,0.125638f},{0.00648477f,-0.292829f,0.121909f}, +{0.00648435f,-0.292827f,0.125638f},{0.00636452f,-0.292458f,0.121909f},{0.00616965f,-0.29212f,0.121909f}, +{0.0063638f,-0.292456f,0.125638f},{0.00616901f,-0.292119f,0.125638f},{0.00590945f,-0.291831f,0.121909f}, +{0.00590875f,-0.29183f,0.125638f},{0.00559323f,-0.291601f,0.121909f},{0.00559323f,-0.291601f,0.125638f}, +{0.00308095f,-0.290338f,0.125638f},{0.00336087f,-0.289852f,0.125638f},{0.00335937f,-0.289856f,0.121909f}, +{0.00273163f,-0.290776f,0.125638f},{0.00307835f,-0.290341f,0.121909f},{0.0027306f,-0.290777f,0.121909f}, +{0.002325f,-0.291153f,0.125638f},{0.00232427f,-0.291153f,0.121909f},{0.00186593f,-0.291466f,0.121909f}, +{0.00186779f,-0.291465f,0.125638f},{0.00136631f,-0.291707f,0.125638f},{0.000274996f,-0.291956f,0.121909f}, +{-0.0002787f,-0.291956f,0.125638f},{0.000275788f,-0.291956f,0.125638f},{0.00136237f,-0.291709f,0.121909f}, +{0.000829945f,-0.291873f,0.125638f},{0.000827251f,-0.291873f,0.121909f},{-0.000280844f,-0.291956f,0.121909f}, +{-0.000826454f,-0.291874f,0.125638f},{-0.000829073f,-0.291873f,0.121909f},{-0.00135821f,-0.29171f,0.121909f}, +{-0.00186441f,-0.291467f,0.125638f},{-0.00135821f,-0.29171f,0.125638f},{-0.00186441f,-0.291467f,0.121909f}, +{0.00356405f,-0.289334f,0.121909f},{0.00368715f,-0.288794f,0.121909f},{0.00356421f,-0.289333f,0.125638f}, +{0.00368727f,-0.288793f,0.125638f},{0.00372865f,-0.288242f,0.121909f},{0.00372896f,-0.288239f,0.125638f}, +{0.00368751f,-0.287686f,0.121909f},{0.0035632f,-0.287139f,0.121909f},{0.00368704f,-0.287682f,0.125638f}, +{0.0035621f,-0.287136f,0.125638f},{0.00335826f,-0.286617f,0.121909f},{0.00335794f,-0.286617f,0.125638f}, +{0.00308092f,-0.286137f,0.121909f},{0.0027356f,-0.285704f,0.121909f},{0.00307961f,-0.286135f,0.125638f}, +{0.00273399f,-0.285702f,0.125638f},{0.00232814f,-0.285325f,0.121909f},{0.00232814f,-0.285325f,0.125638f}, +{0.00186441f,-0.285008f,0.121909f},{0.00186441f,-0.285008f,0.125638f},{0.0091279f,-0.303143f,0.125638f}, +{0.00951793f,-0.303143f,0.125638f},{0.0095162f,-0.303143f,0.121909f},{0.00912617f,-0.303143f,0.121909f}, +{0.00874642f,-0.303062f,0.125638f},{0.00874495f,-0.303061f,0.121909f},{0.00838954f,-0.302903f,0.121909f}, +{0.0080757f,-0.302675f,0.125638f},{0.00839049f,-0.302903f,0.125638f},{0.00807379f,-0.302673f,0.121909f}, +{0.00781413f,-0.302385f,0.125638f},{0.00781324f,-0.302384f,0.121909f},{0.007619f,-0.302047f,0.125638f}, +{0.00761862f,-0.302046f,0.121909f},{0.00749878f,-0.301677f,0.125638f},{0.00749845f,-0.301676f,0.121909f}, +{0.00745764f,-0.301289f,0.121909f},{0.00745764f,-0.301289f,0.125638f},{0.00989767f,-0.303062f,0.121909f}, +{0.0102536f,-0.302903f,0.121909f},{0.00989914f,-0.303061f,0.125638f},{0.0102546f,-0.302903f,0.125638f}, +{0.0105684f,-0.302675f,0.121909f},{0.0105703f,-0.302673f,0.125638f},{0.01083f,-0.302385f,0.121909f}, +{0.0110251f,-0.302047f,0.121909f},{0.0108309f,-0.302384f,0.125638f},{0.0110255f,-0.302046f,0.125638f}, +{0.0111453f,-0.301677f,0.121909f},{0.0111456f,-0.301676f,0.125638f},{0.0111865f,-0.301289f,0.121909f}, +{0.0111865f,-0.301289f,0.125638f},{0.011024f,-0.298481f,0.125638f},{0.0115849f,-0.298481f,0.125638f}, +{0.0115808f,-0.298481f,0.121909f},{0.01047f,-0.298398f,0.125638f},{0.0110199f,-0.298481f,0.121909f}, +{0.0104688f,-0.298397f,0.121909f},{0.00994023f,-0.298234f,0.125638f},{0.00993938f,-0.298234f,0.121909f}, +{0.00943935f,-0.297993f,0.121909f},{0.00944153f,-0.297994f,0.125638f},{0.00898119f,-0.297681f,0.125638f}, +{0.00821944f,-0.296861f,0.121909f},{0.00794276f,-0.296381f,0.125638f},{0.00821991f,-0.296861f,0.125638f}, +{0.00897771f,-0.297678f,0.121909f},{0.00856913f,-0.297299f,0.125638f},{0.00856753f,-0.297297f,0.121909f}, +{0.00794193f,-0.296379f,0.121909f},{0.00774033f,-0.295865f,0.125638f},{0.00773931f,-0.295863f,0.121909f}, +{0.00761603f,-0.295323f,0.121909f},{0.00757356f,-0.294763f,0.125638f},{0.00761603f,-0.295323f,0.125638f}, +{0.00757356f,-0.294763f,0.121909f},{0.0121348f,-0.298398f,0.121909f},{0.0126645f,-0.298234f,0.121909f}, +{0.012136f,-0.298397f,0.125638f},{0.0126654f,-0.298234f,0.125638f},{0.0131632f,-0.297994f,0.121909f}, +{0.0131654f,-0.297993f,0.125638f},{0.0136236f,-0.297681f,0.121909f},{0.0140356f,-0.297299f,0.121909f}, +{0.0136271f,-0.297678f,0.125638f},{0.0140372f,-0.297297f,0.125638f},{0.0143849f,-0.296861f,0.121909f}, +{0.0143853f,-0.296861f,0.125638f},{0.014662f,-0.296381f,0.121909f},{0.0148644f,-0.295865f,0.121909f}, +{0.0146628f,-0.296379f,0.125638f},{0.0148654f,-0.295863f,0.125638f},{0.0149887f,-0.295323f,0.121909f}, +{0.0149887f,-0.295323f,0.125638f},{0.0150312f,-0.294763f,0.121909f},{0.0150312f,-0.294763f,0.125638f}, +{5.2016e-017f,-0.298492f,0.100469f},{5.25144e-017f,-0.298492f,0.0986044f},{-0.000488516f,-0.298535f,0.0986044f}, +{-0.000957717f,-0.298661f,0.0986044f},{-0.00048723f,-0.298535f,0.100469f},{-0.000956449f,-0.298661f,0.100469f}, +{-0.00139564f,-0.298865f,0.100469f},{-0.00179504f,-0.299144f,0.100469f},{-0.00139727f,-0.298866f,0.0986044f}, +{-0.00179767f,-0.299146f,0.0986044f},{-0.00214219f,-0.299491f,0.100469f},{-0.00214411f,-0.299493f,0.0986044f}, +{-0.00242266f,-0.299891f,0.100469f},{-0.00262748f,-0.300331f,0.100469f},{-0.00242333f,-0.299893f,0.0986044f}, +{-0.00262801f,-0.300332f,0.0986044f},{-0.00275356f,-0.3008f,0.100469f},{-0.00275356f,-0.3008f,0.0986044f}, +{-0.00279661f,-0.301289f,0.0986044f},{-0.00279661f,-0.301289f,0.100469f},{0.000488516f,-0.298535f,0.100469f}, +{0.000957717f,-0.298661f,0.100469f},{0.00048723f,-0.298535f,0.0986044f},{0.00139564f,-0.298865f,0.0986044f}, +{0.000956449f,-0.298661f,0.0986044f},{0.00139727f,-0.298866f,0.100469f},{0.00179504f,-0.299144f,0.0986044f}, +{0.00179767f,-0.299146f,0.100469f},{0.00214219f,-0.299491f,0.0986044f},{0.00242266f,-0.299891f,0.0986044f}, +{0.00214411f,-0.299493f,0.100469f},{0.00242333f,-0.299893f,0.100469f},{0.00262748f,-0.300331f,0.0986044f}, +{0.00262801f,-0.300332f,0.100469f},{0.00275356f,-0.3008f,0.0986044f},{0.00275356f,-0.3008f,0.100469f}, +{0.00279661f,-0.301289f,0.100469f},{0.00279661f,-0.301289f,0.0986044f},{4.88499e-017f,-0.293831f,0.100469f}, +{-0.000737081f,-0.293867f,0.100469f},{5.13338e-017f,-0.293831f,0.101401f},{-0.000737081f,-0.293867f,0.101401f}, +{-0.00146169f,-0.293976f,0.100469f},{-0.00216893f,-0.294153f,0.100469f},{-0.00146169f,-0.293976f,0.101401f}, +{-0.00285391f,-0.294399f,0.100469f},{-0.00216893f,-0.294153f,0.101401f},{-0.00285391f,-0.294399f,0.101401f}, +{-0.00351173f,-0.294709f,0.100469f},{-0.00413751f,-0.295084f,0.100469f},{-0.00351173f,-0.294709f,0.101401f}, +{-0.00472635f,-0.29552f,0.100469f},{-0.00413751f,-0.295084f,0.101401f},{-0.00472635f,-0.29552f,0.101401f}, +{-0.00527335f,-0.296015f,0.100469f},{-0.00576874f,-0.296562f,0.100469f},{-0.00527335f,-0.296015f,0.101401f}, +{-0.00620465f,-0.297151f,0.100469f},{-0.00576874f,-0.296562f,0.101401f},{-0.00620465f,-0.297151f,0.101401f}, +{-0.00657906f,-0.297777f,0.100469f},{-0.00688994f,-0.298435f,0.100469f},{-0.00657906f,-0.297777f,0.101401f}, +{-0.00713527f,-0.29912f,0.100469f},{-0.00688994f,-0.298435f,0.101401f},{-0.00713527f,-0.29912f,0.101401f}, +{-0.00731301f,-0.299827f,0.100469f},{-0.00742114f,-0.300551f,0.100469f},{-0.00731301f,-0.299827f,0.101401f}, +{-0.00745764f,-0.301289f,0.100469f},{-0.00742114f,-0.300551f,0.101401f},{-0.00745764f,-0.301289f,0.101401f}, +{0.000737081f,-0.293867f,0.101401f},{0.00146169f,-0.293976f,0.101401f},{0.000737081f,-0.293867f,0.100469f}, +{0.00216893f,-0.294153f,0.101401f},{0.00146169f,-0.293976f,0.100469f},{0.00216893f,-0.294153f,0.100469f}, +{0.00285391f,-0.294399f,0.101401f},{0.00351173f,-0.294709f,0.101401f},{0.00285391f,-0.294399f,0.100469f}, +{0.00413751f,-0.295084f,0.101401f},{0.00351173f,-0.294709f,0.100469f},{0.00413751f,-0.295084f,0.100469f}, +{0.00472635f,-0.29552f,0.101401f},{0.00527335f,-0.296015f,0.101401f},{0.00472635f,-0.29552f,0.100469f}, +{0.00576874f,-0.296562f,0.101401f},{0.00527335f,-0.296015f,0.100469f},{0.00576874f,-0.296562f,0.100469f}, +{0.00620465f,-0.297151f,0.101401f},{0.00657906f,-0.297777f,0.101401f},{0.00620465f,-0.297151f,0.100469f}, +{0.00688994f,-0.298435f,0.101401f},{0.00657906f,-0.297777f,0.100469f},{0.00688994f,-0.298435f,0.100469f}, +{0.00713527f,-0.29912f,0.101401f},{0.00731301f,-0.299827f,0.101401f},{0.00713527f,-0.29912f,0.100469f}, +{0.00742114f,-0.300551f,0.101401f},{0.00731301f,-0.299827f,0.100469f},{0.00742114f,-0.300551f,0.100469f}, +{0.00745764f,-0.301289f,0.101401f},{0.00745764f,-0.301289f,0.100469f},{-0.00462052f,-0.283896f,0.101401f}, +{-0.00462066f,-0.283896f,0.104198f},{-0.00466102f,-0.284509f,0.101401f},{-0.00462052f,-0.285122f,0.104198f}, +{-0.00462066f,-0.285121f,0.101401f},{-0.00466102f,-0.284509f,0.104198f},{-0.00430621f,-0.286293f,0.101401f}, +{-0.00430621f,-0.286293f,0.104198f},{-0.00403832f,-0.286836f,0.101401f},{-0.00450127f,-0.285719f,0.104198f}, +{-0.00450141f,-0.285718f,0.101401f},{-0.00403818f,-0.286837f,0.104198f},{-0.00370041f,-0.287343f,0.104198f}, +{-0.00370055f,-0.287343f,0.101401f},{-0.00329584f,-0.287805f,0.101401f},{-0.00329584f,-0.287805f,0.104198f}, +{-0.00283386f,-0.288209f,0.104198f},{-0.0028342f,-0.288209f,0.101401f},{-0.00232777f,-0.288547f,0.101401f}, +{-0.00232743f,-0.288547f,0.104198f},{-0.00178369f,-0.288815f,0.101401f},{-0.00178369f,-0.288815f,0.104198f}, +{-0.00120944f,-0.28901f,0.104198f},{-0.00120978f,-0.28901f,0.101401f},{5.69282e-017f,-0.28917f,0.101401f}, +{-0.000612842f,-0.289129f,0.101401f},{-0.000612502f,-0.28913f,0.104198f},{5.69282e-017f,-0.28917f,0.104198f}, +{-0.00450141f,-0.283299f,0.104198f},{-0.00450127f,-0.283299f,0.101401f},{-0.00430621f,-0.282725f,0.104198f}, +{-0.00403832f,-0.282181f,0.104198f},{-0.00430621f,-0.282725f,0.101401f},{-0.00403818f,-0.282181f,0.101401f}, +{-0.00370055f,-0.281675f,0.104198f},{-0.00370041f,-0.281675f,0.101401f},{-0.00329584f,-0.281213f,0.104198f}, +{-0.0028342f,-0.280808f,0.104198f},{-0.00329584f,-0.281213f,0.101401f},{-0.00283386f,-0.280808f,0.101401f}, +{-0.00232777f,-0.280471f,0.104198f},{-0.00232743f,-0.280471f,0.101401f},{-0.00178369f,-0.280203f,0.104198f}, +{-0.00120978f,-0.280008f,0.104198f},{-0.00178369f,-0.280203f,0.101401f},{-0.00120944f,-0.280007f,0.101401f}, +{-0.000612842f,-0.279888f,0.104198f},{-0.000612502f,-0.279888f,0.101401f},{5.57866e-017f,-0.279848f,0.104198f}, +{5.57866e-017f,-0.279848f,0.101401f},{0.0173922f,-0.296668f,0.101401f},{0.0167797f,-0.296628f,0.101401f}, +{0.0173922f,-0.296668f,0.104198f},{0.0161668f,-0.296668f,0.104198f},{0.0167797f,-0.296628f,0.104198f}, +{0.0161668f,-0.296668f,0.101401f},{0.014996f,-0.296982f,0.101401f},{0.0144519f,-0.29725f,0.101401f}, +{0.014996f,-0.296982f,0.104198f},{0.0155699f,-0.296787f,0.104198f},{0.0155699f,-0.296787f,0.101401f}, +{0.0144519f,-0.29725f,0.104198f},{0.0139455f,-0.297588f,0.101401f},{0.0139455f,-0.297588f,0.104198f}, +{0.0134838f,-0.297993f,0.101401f},{0.0134838f,-0.297993f,0.104198f},{0.0130791f,-0.298455f,0.101401f}, +{0.0130791f,-0.298455f,0.104198f},{0.0127414f,-0.298961f,0.101401f},{0.0124735f,-0.299505f,0.101401f}, +{0.0127414f,-0.298961f,0.104198f},{0.0124735f,-0.299505f,0.104198f},{0.0122783f,-0.300079f,0.101401f}, +{0.0122783f,-0.300079f,0.104198f},{0.0121187f,-0.301289f,0.101401f},{0.012159f,-0.300676f,0.104198f}, +{0.012159f,-0.300676f,0.101401f},{0.0121187f,-0.301289f,0.104198f},{0.0179891f,-0.296787f,0.104198f}, +{0.0185634f,-0.296982f,0.104198f},{0.0179891f,-0.296787f,0.101401f},{0.0191071f,-0.29725f,0.104198f}, +{0.0185634f,-0.296982f,0.101401f},{0.0191071f,-0.29725f,0.101401f},{0.0196135f,-0.297588f,0.104198f}, +{0.0200755f,-0.297993f,0.104198f},{0.0196135f,-0.297588f,0.101401f},{0.0204801f,-0.298454f,0.104198f}, +{0.0200755f,-0.297993f,0.101401f},{0.0204801f,-0.298454f,0.101401f},{0.0208179f,-0.298961f,0.104198f}, +{0.0210859f,-0.299505f,0.104198f},{0.0208179f,-0.298961f,0.101401f},{0.0212809f,-0.300079f,0.104198f}, +{0.0210859f,-0.299505f,0.101401f},{0.0212809f,-0.300079f,0.101401f},{0.0214002f,-0.300676f,0.104198f}, +{0.0214407f,-0.301289f,0.104198f},{0.0214002f,-0.300676f,0.101401f},{0.0214407f,-0.301289f,0.101401f}, +{0.00462066f,-0.318681f,0.104198f},{0.00466102f,-0.318068f,0.104198f},{0.00464709f,-0.318428f,0.101401f}, +{0.00458867f,-0.317251f,0.101401f},{0.00465528f,-0.317837f,0.101401f},{0.00462052f,-0.317455f,0.104198f}, +{0.00430621f,-0.316285f,0.104198f},{0.00403818f,-0.31574f,0.104198f},{0.00423671f,-0.316126f,0.101401f}, +{0.00444837f,-0.316677f,0.101401f},{0.00450127f,-0.316858f,0.104198f},{0.00370041f,-0.315234f,0.104198f}, +{0.00361392f,-0.315125f,0.101401f},{0.00395712f,-0.315606f,0.101401f},{0.00329584f,-0.314772f,0.104198f}, +{0.00283386f,-0.314368f,0.104198f},{0.00276013f,-0.314313f,0.101401f},{0.00321274f,-0.314692f,0.101401f}, +{0.00232743f,-0.31403f,0.104198f},{0.00178369f,-0.313762f,0.104198f},{0.00226347f,-0.313993f,0.101401f}, +{0.00120944f,-0.313567f,0.104198f},{0.00116855f,-0.313559f,0.101401f},{0.00172931f,-0.313743f,0.101401f}, +{0.000589403f,-0.313444f,0.101401f},{0.000612502f,-0.313448f,0.104198f},{5.16769e-017f,-0.313407f,0.104198f}, +{5.16769e-017f,-0.313407f,0.101401f},{0.00456433f,-0.319013f,0.101401f},{0.00440833f,-0.319582f,0.101401f}, +{0.00450141f,-0.319278f,0.104198f},{0.00430621f,-0.319852f,0.104198f},{0.00418158f,-0.320128f,0.101401f}, +{0.00388773f,-0.32064f,0.101401f},{0.00403832f,-0.320396f,0.104198f},{0.00353147f,-0.321111f,0.101401f}, +{0.00370055f,-0.320902f,0.104198f},{0.00329584f,-0.321364f,0.104198f},{0.0031185f,-0.321533f,0.101401f}, +{0.00265541f,-0.321899f,0.101401f},{0.0028342f,-0.321769f,0.104198f},{0.00214963f,-0.322204f,0.101401f}, +{0.00232777f,-0.322106f,0.104198f},{0.00178369f,-0.322374f,0.104198f},{0.00160952f,-0.322443f,0.101401f}, +{0.00104053f,-0.322599f,0.101401f},{0.00120978f,-0.322569f,0.104198f},{0.000461185f,-0.322725f,0.101401f}, +{0.000612842f,-0.322689f,0.104198f},{5.28185e-017f,-0.322729f,0.104198f},{5.28185e-017f,-0.322729f,0.101401f}, +{-0.0143886f,-0.288764f,0.110723f},{-0.0143784f,-0.288958f,0.101401f},{-0.0143782f,-0.288568f,0.101401f}, +{-0.014297f,-0.288187f,0.101401f},{-0.0143526f,-0.288401f,0.110723f},{-0.0142471f,-0.288051f,0.110723f}, +{-0.0139089f,-0.287516f,0.101401f},{-0.014075f,-0.287728f,0.110723f},{-0.0141387f,-0.287832f,0.101401f}, +{-0.0136193f,-0.287256f,0.101401f},{-0.0138429f,-0.287445f,0.110723f},{-0.0135601f,-0.287213f,0.110723f}, +{-0.013282f,-0.287061f,0.101401f},{-0.0129121f,-0.286941f,0.101401f},{-0.0132377f,-0.287041f,0.110723f}, +{-0.0125242f,-0.2869f,0.101401f},{-0.0125242f,-0.2869f,0.110723f},{-0.0128879f,-0.286935f,0.110723f}, +{-0.0143523f,-0.289129f,0.110723f},{-0.0142976f,-0.28934f,0.101401f},{-0.0142453f,-0.289478f,0.110723f}, +{-0.0140726f,-0.2898f,0.110723f},{-0.0141391f,-0.289696f,0.101401f},{-0.0138409f,-0.290082f,0.110723f}, +{-0.0139105f,-0.290011f,0.101401f},{-0.0136206f,-0.290272f,0.101401f},{-0.0135587f,-0.290314f,0.110723f}, +{-0.0132367f,-0.290486f,0.110723f},{-0.013283f,-0.290467f,0.101401f},{-0.0128873f,-0.290592f,0.110723f}, +{-0.0129131f,-0.290588f,0.101401f},{-0.0125242f,-0.290629f,0.101401f},{-0.0125242f,-0.290629f,0.110723f}, +{-0.0125242f,-0.288764f,0.111843f},{0.00868228f,-0.290742f,0.110723f},{0.00869244f,-0.290936f,0.101401f}, +{0.00869272f,-0.290546f,0.101401f},{0.00877392f,-0.290165f,0.101401f},{0.0087183f,-0.290378f,0.110723f}, +{0.00882381f,-0.290028f,0.110723f},{0.00916198f,-0.289494f,0.101401f},{0.00899591f,-0.289705f,0.110723f}, +{0.00893219f,-0.289809f,0.101401f},{0.0094516f,-0.289233f,0.101401f},{0.00922803f,-0.289422f,0.110723f}, +{0.00951082f,-0.289191f,0.110723f},{0.00978889f,-0.289038f,0.101401f},{0.0101588f,-0.288918f,0.101401f}, +{0.00983322f,-0.289018f,0.110723f},{0.0105467f,-0.288877f,0.101401f},{0.0105467f,-0.288877f,0.110723f}, +{0.010183f,-0.288912f,0.110723f},{0.00871859f,-0.291106f,0.110723f},{0.00877329f,-0.291317f,0.101401f}, +{0.00882557f,-0.291456f,0.110723f},{0.00899828f,-0.291778f,0.110723f},{0.00893177f,-0.291673f,0.101401f}, +{0.00922999f,-0.29206f,0.110723f},{0.00916039f,-0.291988f,0.101401f},{0.00945026f,-0.29225f,0.101401f}, +{0.00951221f,-0.292291f,0.110723f},{0.00983423f,-0.292464f,0.110723f},{0.00978794f,-0.292445f,0.101401f}, +{0.0101836f,-0.29257f,0.110723f},{0.0101578f,-0.292565f,0.101401f},{0.0105467f,-0.292606f,0.101401f}, +{0.0105467f,-0.292606f,0.110723f},{0.0105467f,-0.290742f,0.111843f},{0.0106598f,-0.313813f,0.110723f}, +{0.0106699f,-0.314007f,0.101401f},{0.0106702f,-0.313617f,0.101401f},{0.0107514f,-0.313236f,0.101401f}, +{0.0106958f,-0.313449f,0.110723f},{0.0108013f,-0.313099f,0.110723f},{0.0111395f,-0.312564f,0.101401f}, +{0.0109734f,-0.312776f,0.110723f},{0.0109097f,-0.31288f,0.101401f},{0.0114291f,-0.312304f,0.101401f}, +{0.0112055f,-0.312493f,0.110723f},{0.0114883f,-0.312261f,0.110723f},{0.0117664f,-0.312109f,0.101401f}, +{0.0121363f,-0.311989f,0.101401f},{0.0118107f,-0.312089f,0.110723f},{0.0125242f,-0.311948f,0.101401f}, +{0.0125242f,-0.311948f,0.110723f},{0.0121605f,-0.311983f,0.110723f},{0.0106961f,-0.314177f,0.110723f}, +{0.0107508f,-0.314388f,0.101401f},{0.0108031f,-0.314527f,0.110723f},{0.0109758f,-0.314848f,0.110723f}, +{0.0109093f,-0.314744f,0.101401f},{0.0112075f,-0.315131f,0.110723f},{0.0111379f,-0.315059f,0.101401f}, +{0.0114278f,-0.315321f,0.101401f},{0.0114897f,-0.315362f,0.110723f},{0.0118117f,-0.315534f,0.110723f}, +{0.0117654f,-0.315516f,0.101401f},{0.0121611f,-0.315641f,0.110723f},{0.0121353f,-0.315636f,0.101401f}, +{0.0125242f,-0.315677f,0.101401f},{0.0125242f,-0.315677f,0.110723f},{0.0125242f,-0.313813f,0.111843f}, +{-0.0124111f,-0.311835f,0.110723f},{-0.0124009f,-0.312029f,0.101401f},{-0.0124007f,-0.311639f,0.101401f}, +{-0.0123195f,-0.311258f,0.101401f},{-0.0123751f,-0.311472f,0.110723f},{-0.0122696f,-0.311121f,0.110723f}, +{-0.0119314f,-0.310587f,0.101401f},{-0.0120975f,-0.310799f,0.110723f},{-0.0121612f,-0.310903f,0.101401f}, +{-0.0116418f,-0.310326f,0.101401f},{-0.0118654f,-0.310516f,0.110723f},{-0.0115826f,-0.310284f,0.110723f}, +{-0.0113045f,-0.310132f,0.101401f},{-0.0109346f,-0.310012f,0.101401f},{-0.0112602f,-0.310112f,0.110723f}, +{-0.0105467f,-0.309971f,0.101401f},{-0.0105467f,-0.309971f,0.110723f},{-0.0109104f,-0.310006f,0.110723f}, +{-0.0123748f,-0.312199f,0.110723f},{-0.0123201f,-0.312411f,0.101401f},{-0.0122678f,-0.312549f,0.110723f}, +{-0.0120951f,-0.312871f,0.110723f},{-0.0121616f,-0.312767f,0.101401f},{-0.0118634f,-0.313153f,0.110723f}, +{-0.011933f,-0.313082f,0.101401f},{-0.0116431f,-0.313343f,0.101401f},{-0.0115812f,-0.313385f,0.110723f}, +{-0.0112592f,-0.313557f,0.110723f},{-0.0113054f,-0.313538f,0.101401f},{-0.0109098f,-0.313663f,0.110723f}, +{-0.0109356f,-0.313659f,0.101401f},{-0.0105467f,-0.3137f,0.101401f},{-0.0105467f,-0.3137f,0.110723f}, +{-0.0105467f,-0.311835f,0.111843f},{-0.0173925f,-0.305909f,0.101401f},{-0.0173922f,-0.305909f,0.104198f}, +{-0.0167797f,-0.30595f,0.101401f},{-0.0161668f,-0.305909f,0.104198f},{-0.0161672f,-0.305909f,0.101401f}, +{-0.0167797f,-0.30595f,0.104198f},{-0.014996f,-0.305595f,0.101401f},{-0.014996f,-0.305595f,0.104198f}, +{-0.0144523f,-0.305327f,0.101401f},{-0.0155699f,-0.30579f,0.104198f},{-0.0155702f,-0.30579f,0.101401f}, +{-0.0144519f,-0.305327f,0.104198f},{-0.0139455f,-0.304989f,0.104198f},{-0.0139458f,-0.304989f,0.101401f}, +{-0.0134838f,-0.304584f,0.101401f},{-0.0134838f,-0.304584f,0.104198f},{-0.0130791f,-0.304122f,0.104198f}, +{-0.0130793f,-0.304123f,0.101401f},{-0.0127415f,-0.303616f,0.101401f},{-0.0127414f,-0.303616f,0.104198f}, +{-0.0124735f,-0.303072f,0.101401f},{-0.0124735f,-0.303072f,0.104198f},{-0.0122783f,-0.302498f,0.104198f}, +{-0.0122784f,-0.302498f,0.101401f},{-0.0121187f,-0.301289f,0.101401f},{-0.0121592f,-0.301901f,0.101401f}, +{-0.012159f,-0.301901f,0.104198f},{-0.0121187f,-0.301289f,0.104198f},{-0.0179891f,-0.30579f,0.104198f}, +{-0.0179895f,-0.30579f,0.101401f},{-0.0185634f,-0.305595f,0.104198f},{-0.0191071f,-0.305327f,0.104198f}, +{-0.0185634f,-0.305595f,0.101401f},{-0.0191075f,-0.305327f,0.101401f},{-0.0196135f,-0.304989f,0.104198f}, +{-0.0196139f,-0.304989f,0.101401f},{-0.0200755f,-0.304584f,0.104198f},{-0.0204801f,-0.304123f,0.104198f}, +{-0.0200755f,-0.304584f,0.101401f},{-0.0204802f,-0.304122f,0.101401f},{-0.0208179f,-0.303616f,0.104198f}, +{-0.020818f,-0.303616f,0.101401f},{-0.0210859f,-0.303072f,0.104198f},{-0.0212809f,-0.302498f,0.104198f}, +{-0.0210859f,-0.303072f,0.101401f},{-0.0212811f,-0.302498f,0.101401f},{-0.0214002f,-0.301901f,0.104198f}, +{-0.0214003f,-0.301901f,0.101401f},{-0.0214407f,-0.301289f,0.104198f},{-0.0214407f,-0.301289f,0.101401f}, +{0.0254902f,-0.298561f,0.121909f},{0.0255985f,-0.29991f,0.120045f},{0.0254881f,-0.298542f,0.120045f}, +{0.0250554f,-0.295865f,0.121909f},{0.0250515f,-0.295847f,0.120045f},{0.0247276f,-0.294526f,0.120045f}, +{0.0255992f,-0.299923f,0.121909f},{0.0256356f,-0.301289f,0.120045f},{0.0256356f,-0.301289f,0.121909f}, +{0.0253087f,-0.297208f,0.121909f},{0.0253054f,-0.297187f,0.120045f},{0.0241907f,-0.292804f,0.121909f}, +{0.0246545f,-0.294325f,0.121909f},{0.0243348f,-0.293226f,0.120045f},{0.0222011f,-0.288471f,0.121909f}, +{0.0229537f,-0.289873f,0.121909f},{0.0227538f,-0.28948f,0.120045f},{0.0236177f,-0.291319f,0.121909f}, +{0.0238741f,-0.29195f,0.120045f},{0.0233468f,-0.2907f,0.120045f},{0.0205925f,-0.28602f,0.120045f}, +{0.0197483f,-0.284942f,0.120045f},{0.0204428f,-0.28582f,0.121909f},{0.0220964f,-0.288291f,0.120045f}, +{0.0213756f,-0.287137f,0.120045f},{0.0213632f,-0.287118f,0.121909f},{0.0178811f,-0.282919f,0.120045f}, +{0.0172245f,-0.282302f,0.121909f},{0.0183635f,-0.283414f,0.121909f},{0.0188436f,-0.283907f,0.120045f}, +{0.0194437f,-0.284581f,0.121909f},{0.0137508f,-0.279653f,0.121909f},{0.015542f,-0.280901f,0.121909f}, +{0.014715f,-0.280297f,0.120045f},{0.0168687f,-0.281985f,0.120045f},{0.0112022f,-0.27823f,0.120045f}, +{0.00996671f,-0.27767f,0.120045f},{0.00988506f,-0.277635f,0.121909f},{0.0124072f,-0.278855f,0.120045f}, +{0.0118618f,-0.278562f,0.121909f},{0.00610419f,-0.27639f,0.120045f},{0.00612578f,-0.276411f,0.121909f}, +{0.00741505f,-0.276749f,0.120045f},{0.00783085f,-0.276878f,0.121909f},{0.00870345f,-0.277176f,0.120045f}, +{0.00264799f,-0.27579f,0.121909f},{0.00342595f,-0.275883f,0.120045f},{0.00206394f,-0.275736f,0.120045f}, +{0.00477359f,-0.276101f,0.120045f},{0.00439916f,-0.276033f,0.121909f},{0.000884103f,-0.275668f,0.121909f}, +{-0.000690516f,-0.275662f,0.120045f},{-0.000883894f,-0.275668f,0.121909f},{0.000689447f,-0.275662f,0.120045f}, +{-0.00342617f,-0.275883f,0.120045f},{-0.00477376f,-0.276101f,0.120045f},{-0.00439897f,-0.276033f,0.121909f}, +{-0.00264771f,-0.27579f,0.121909f},{-0.00206419f,-0.275736f,0.120045f},{-0.0087035f,-0.277176f,0.120045f}, +{-0.00783085f,-0.276878f,0.121909f},{-0.00741509f,-0.276749f,0.120045f},{-0.00612769f,-0.276402f,0.121909f}, +{-0.0061043f,-0.27639f,0.120045f},{-0.0118616f,-0.278562f,0.121909f},{-0.00988475f,-0.277635f,0.121909f}, +{-0.0112024f,-0.27823f,0.120045f},{-0.00996683f,-0.27767f,0.120045f},{-0.0137506f,-0.279653f,0.121909f}, +{-0.0135792f,-0.279545f,0.120045f},{-0.0147152f,-0.280297f,0.120045f},{-0.0124074f,-0.278855f,0.120045f}, +{-0.016869f,-0.281985f,0.120045f},{-0.0178817f,-0.282919f,0.120045f},{-0.0172245f,-0.282302f,0.121909f}, +{-0.0155417f,-0.280901f,0.121909f},{-0.0158127f,-0.281111f,0.120045f},{-0.0188441f,-0.283908f,0.120045f}, +{-0.0197483f,-0.284943f,0.120045f},{-0.0194435f,-0.284581f,0.121909f},{-0.0183577f,-0.283419f,0.121909f}, +{-0.0204427f,-0.28582f,0.121909f},{-0.0205925f,-0.28602f,0.120045f},{-0.0213756f,-0.287137f,0.120045f}, +{-0.021363f,-0.287118f,0.121909f},{-0.0220965f,-0.288291f,0.120045f},{-0.0222011f,-0.288471f,0.121909f}, +{-0.0227539f,-0.28948f,0.120045f},{-0.0229535f,-0.289873f,0.121909f},{-0.0236176f,-0.291319f,0.121909f}, +{-0.0233469f,-0.290701f,0.120045f},{-0.0238742f,-0.29195f,0.120045f},{-0.0241907f,-0.292803f,0.121909f}, +{-0.0243349f,-0.293226f,0.120045f},{-0.0246619f,-0.294323f,0.121909f},{-0.0250554f,-0.295865f,0.121909f}, +{-0.0247277f,-0.294526f,0.120045f},{-0.0253055f,-0.297187f,0.120045f},{-0.0250516f,-0.295847f,0.120045f}, +{-0.0254882f,-0.298542f,0.120045f},{-0.0253087f,-0.297208f,0.121909f},{-0.0254901f,-0.298561f,0.121909f}, +{-0.0255986f,-0.29991f,0.120045f},{-0.0256356f,-0.301289f,0.120045f},{-0.0255992f,-0.299923f,0.121909f}, +{-0.0256356f,-0.301289f,0.121909f},{0.013579f,-0.279545f,0.120045f},{0.0158124f,-0.28111f,0.120045f}, +{0.0247034f,-0.301289f,0.104011f},{0.0261017f,-0.301289f,0.10513f},{0.0260447f,-0.303013f,0.10513f}, +{0.0148773f,-0.28396f,0.10252f},{0.0141264f,-0.285159f,0.101401f},{0.0130365f,-0.284266f,0.101401f}, +{0.0151609f,-0.286128f,0.101401f},{0.0131883f,-0.282642f,0.10252f},{0.0144813f,-0.279572f,0.10513f}, +{0.0123517f,-0.279895f,0.104011f},{0.0130346f,-0.278674f,0.10513f},{0.0118953f,-0.28345f,0.101401f}, +{0.0114195f,-0.281509f,0.10252f},{0.0115354f,-0.277874f,0.10513f},{0.00947527f,-0.282055f,0.101401f}, +{0.00998868f,-0.277174f,0.10513f},{0.00820499f,-0.28148f,0.101401f},{0.0084f,-0.276575f,0.10513f}, +{0.00689981f,-0.280988f,0.101401f},{0.00556423f,-0.280582f,0.101401f},{0.00677408f,-0.276081f,0.10513f}, +{0.00420236f,-0.280264f,0.101401f},{0.00511591f,-0.275693f,0.10513f},{0.00343096f,-0.275413f,0.10513f}, +{0.0028181f,-0.280034f,0.101401f},{0.00172399f,-0.275244f,0.10513f},{0.00141594f,-0.279895f,0.101401f}, +{5.61862e-017f,-0.275187f,0.10513f},{0.0164604f,-0.285456f,0.10252f},{0.016129f,-0.287162f,0.101401f}, +{0.0179091f,-0.287115f,0.10252f},{0.0170221f,-0.288252f,0.101401f},{0.0178384f,-0.289393f,0.101401f}, +{0.0192f,-0.28892f,0.10252f},{0.018576f,-0.290582f,0.101401f},{0.0203119f,-0.290846f,0.10252f}, +{0.0192333f,-0.291813f,0.101401f},{0.0212292f,-0.292866f,0.10252f},{0.0198086f,-0.293084f,0.101401f}, +{0.0252075f,-0.294515f,0.10513f},{0.0255955f,-0.296173f,0.10513f},{0.0242782f,-0.296724f,0.104011f}, +{0.021942f,-0.294951f,0.10252f},{0.0203001f,-0.294389f,0.101401f},{0.0224458f,-0.297069f,0.10252f}, +{0.0207061f,-0.295724f,0.101401f},{0.0210249f,-0.297086f,0.101401f},{0.0227423f,-0.299192f,0.10252f}, +{0.0212547f,-0.29847f,0.101401f},{0.0260448f,-0.299565f,0.10513f},{0.022839f,-0.301289f,0.10252f}, +{0.0213939f,-0.299872f,0.101401f},{0.0212463f,-0.304169f,0.101401f},{0.021392f,-0.302732f,0.101401f}, +{0.0258753f,-0.30472f,0.10513f},{0.0202358f,-0.308374f,0.101401f},{0.0206669f,-0.306996f,0.101401f}, +{0.0247131f,-0.309689f,0.10513f},{0.0210042f,-0.305592f,0.101401f},{0.0255955f,-0.306404f,0.10513f}, +{0.0252074f,-0.308063f,0.10513f},{0.0191008f,-0.311028f,0.101401f},{0.0226142f,-0.314323f,0.10513f}, +{0.0184019f,-0.312292f,0.101401f},{0.0241148f,-0.311277f,0.10513f},{0.0234144f,-0.312824f,0.10513f}, +{0.019713f,-0.309721f,0.101401f},{0.0207226f,-0.317159f,0.10513f},{0.0196354f,-0.318486f,0.10513f}, +{0.0167571f,-0.314664f,0.101401f},{0.0176194f,-0.313506f,0.101401f},{0.0217163f,-0.31577f,0.10513f}, +{0.0158706f,-0.322011f,0.10513f},{0.0137317f,-0.317755f,0.101401f},{0.0171974f,-0.320924f,0.10513f}, +{0.0148089f,-0.316793f,0.101401f},{0.0158188f,-0.315761f,0.101401f},{0.0184567f,-0.319745f,0.10513f}, +{0.0101475f,-0.320176f,0.101401f},{0.0113957f,-0.31945f,0.101401f},{0.0114195f,-0.321068f,0.10252f}, +{0.0125922f,-0.318642f,0.101401f},{0.0123517f,-0.322682f,0.104011f},{0.0130343f,-0.323903f,0.10513f}, +{0.0109801f,-0.323418f,0.104011f},{0.00954347f,-0.324074f,0.104011f},{0.00998868f,-0.325403f,0.10513f}, +{0.00804836f,-0.324644f,0.104011f},{0.0115351f,-0.324703f,0.10513f},{0.00650255f,-0.325121f,0.104011f}, +{0.00677384f,-0.326496f,0.10513f},{0.00491482f,-0.325498f,0.104011f},{0.00839976f,-0.326002f,0.10513f}, +{0.00329485f,-0.325771f,0.104011f},{0.00511591f,-0.326884f,0.10513f},{0.00343072f,-0.327164f,0.10513f}, +{0.00172376f,-0.327333f,0.10513f},{0.00165296f,-0.325937f,0.104011f},{5.29897e-017f,-0.32739f,0.10513f}, +{5.29897e-017f,-0.325992f,0.104011f},{0.0144813f,-0.323005f,0.10513f},{0.00454389f,-0.323671f,0.10252f}, +{0.00475341f,-0.322193f,0.101401f},{0.00601179f,-0.323322f,0.10252f},{0.00304618f,-0.323923f,0.10252f}, +{0.00333561f,-0.322467f,0.101401f},{0.00190254f,-0.322644f,0.101401f},{0.00152821f,-0.324076f,0.10252f}, +{5.29897e-017f,-0.324128f,0.10252f},{0.00615037f,-0.321828f,0.101401f},{0.00751875f,-0.321368f,0.101401f}, +{0.00882321f,-0.322354f,0.10252f},{0.00744093f,-0.322881f,0.10252f},{0.00885315f,-0.320816f,0.101401f}, +{0.0101514f,-0.321748f,0.10252f},{0.0142636f,-0.281119f,0.104011f},{0.0107068f,-0.282713f,0.101401f}, +{0.0160914f,-0.282545f,0.104011f},{0.0158708f,-0.280566f,0.10513f},{0.0184567f,-0.282832f,0.10513f}, +{0.0171976f,-0.281653f,0.10513f},{0.0178031f,-0.284163f,0.104011f},{0.0193705f,-0.285958f,0.104011f}, +{0.0196355f,-0.284091f,0.10513f},{0.0217163f,-0.286807f,0.10513f},{0.0207227f,-0.285418f,0.10513f}, +{0.0207667f,-0.287909f,0.104011f},{0.0219695f,-0.289993f,0.104011f},{0.0226143f,-0.288254f,0.10513f}, +{0.0234145f,-0.289753f,0.10513f},{0.0229621f,-0.292178f,0.104011f},{0.0241148f,-0.2913f,0.10513f}, +{0.0237331f,-0.294432f,0.104011f},{0.0247132f,-0.292889f,0.10513f},{0.0245992f,-0.299019f,0.104011f}, +{0.0258754f,-0.297858f,0.10513f},{0.0214407f,-0.301289f,0.10513f},{0.0214407f,-0.301289f,0.106062f}, +{0.0214037f,-0.302548f,0.106062f},{0.0212935f,-0.303797f,0.106062f},{0.0214037f,-0.302548f,0.10513f}, +{0.0211114f,-0.305032f,0.106062f},{0.0212936f,-0.303796f,0.10513f},{0.0211115f,-0.305032f,0.10513f}, +{0.0208586f,-0.306251f,0.106062f},{0.0205363f,-0.30745f,0.106062f},{0.0208587f,-0.30625f,0.10513f}, +{0.0201457f,-0.308627f,0.106062f},{0.0205363f,-0.30745f,0.10513f},{0.0201457f,-0.308627f,0.10513f}, +{0.0196879f,-0.309779f,0.106062f},{0.0191643f,-0.310903f,0.106062f},{0.019688f,-0.309779f,0.10513f}, +{0.018576f,-0.311996f,0.106062f},{0.0191643f,-0.310903f,0.10513f},{0.018576f,-0.311995f,0.10513f}, +{0.0179242f,-0.313054f,0.106062f},{0.0172102f,-0.314076f,0.106062f},{0.0179243f,-0.313054f,0.10513f}, +{0.0164352f,-0.315058f,0.106062f},{0.0172102f,-0.314076f,0.10513f},{0.0164352f,-0.315058f,0.10513f}, +{0.0155998f,-0.315997f,0.106062f},{0.0147082f,-0.316889f,0.106062f},{0.0156004f,-0.315997f,0.10513f}, +{0.0137691f,-0.317724f,0.106062f},{0.0147088f,-0.316888f,0.10513f},{0.0137693f,-0.317724f,0.10513f}, +{0.0127873f,-0.318499f,0.106062f},{0.0117655f,-0.319213f,0.106062f},{0.0127873f,-0.318499f,0.10513f}, +{0.0107068f,-0.319865f,0.106062f},{0.0117656f,-0.319213f,0.10513f},{0.010707f,-0.319865f,0.10513f}, +{0.00961408f,-0.320453f,0.106062f},{0.00849036f,-0.320976f,0.106062f},{0.0096143f,-0.320453f,0.10513f}, +{0.0073385f,-0.321434f,0.106062f},{0.00849054f,-0.320976f,0.10513f},{0.00733859f,-0.321434f,0.10513f}, +{0.00616138f,-0.321825f,0.106062f},{0.00496191f,-0.322147f,0.106062f},{0.00616144f,-0.321825f,0.10513f}, +{0.00496208f,-0.322147f,0.10513f},{0.00374334f,-0.3224f,0.10513f},{0.00250813f,-0.322582f,0.10513f}, +{0.00374312f,-0.3224f,0.106062f},{0.00125925f,-0.322692f,0.106062f},{0.00250793f,-0.322582f,0.106062f}, +{5.56154e-017f,-0.322729f,0.106062f},{0.00125938f,-0.322692f,0.10513f},{5.56154e-017f,-0.322729f,0.10513f}, +{0.0214037f,-0.300029f,0.10513f},{0.0212935f,-0.29878f,0.10513f},{0.0214037f,-0.300029f,0.106062f}, +{0.0212936f,-0.298781f,0.106062f},{0.0211114f,-0.297545f,0.10513f},{0.0208586f,-0.296326f,0.10513f}, +{0.0211115f,-0.297545f,0.106062f},{0.0205363f,-0.295127f,0.10513f},{0.0208587f,-0.296327f,0.106062f}, +{0.0205363f,-0.295127f,0.106062f},{0.0201457f,-0.29395f,0.10513f},{0.0196879f,-0.292798f,0.10513f}, +{0.0201457f,-0.29395f,0.106062f},{0.0191643f,-0.291674f,0.10513f},{0.019688f,-0.292798f,0.106062f}, +{0.0191643f,-0.291674f,0.106062f},{0.018576f,-0.290582f,0.10513f},{0.0179242f,-0.289523f,0.10513f}, +{0.018576f,-0.290582f,0.106062f},{0.0172102f,-0.288501f,0.10513f},{0.0179243f,-0.289523f,0.106062f}, +{0.0172102f,-0.288501f,0.106062f},{0.0164352f,-0.287519f,0.10513f},{0.0155998f,-0.28658f,0.10513f}, +{0.0164352f,-0.287519f,0.106062f},{0.0147082f,-0.285688f,0.10513f},{0.0156004f,-0.28658f,0.106062f}, +{0.0147088f,-0.285689f,0.106062f},{0.0137691f,-0.284853f,0.10513f},{0.0127873f,-0.284078f,0.10513f}, +{0.0137693f,-0.284853f,0.106062f},{0.0117655f,-0.283364f,0.10513f},{0.0127873f,-0.284078f,0.106062f}, +{0.0117656f,-0.283364f,0.106062f},{0.0107068f,-0.282713f,0.10513f},{0.00961408f,-0.282124f,0.10513f}, +{0.010707f,-0.282713f,0.106062f},{0.00849036f,-0.281601f,0.10513f},{0.0096143f,-0.282124f,0.106062f}, +{0.00849054f,-0.281601f,0.106062f},{0.0073385f,-0.281143f,0.10513f},{0.00616138f,-0.280752f,0.10513f}, +{0.00733859f,-0.281143f,0.106062f},{0.00496191f,-0.28043f,0.10513f},{0.00616144f,-0.280752f,0.106062f}, +{0.00374334f,-0.280177f,0.106062f},{0.00496208f,-0.28043f,0.106062f},{0.00374312f,-0.280177f,0.10513f}, +{0.00250813f,-0.279995f,0.106062f},{0.00250793f,-0.279995f,0.10513f},{0.00125925f,-0.279885f,0.10513f}, +{0.00125938f,-0.279885f,0.106062f},{5.29897e-017f,-0.279848f,0.10513f},{5.29897e-017f,-0.279848f,0.106062f}, +{0.0261017f,-0.301289f,0.106062f},{0.0261017f,-0.301289f,0.120045f},{0.0260652f,-0.302669f,0.120045f}, +{0.0259565f,-0.304039f,0.120045f},{0.0260653f,-0.302669f,0.106062f},{0.0257765f,-0.305396f,0.120045f}, +{0.0259565f,-0.304039f,0.106062f},{0.0257766f,-0.305396f,0.106062f},{0.0255265f,-0.306739f,0.120045f}, +{0.0252074f,-0.308063f,0.120045f},{0.0255265f,-0.306738f,0.106062f},{0.0248204f,-0.309366f,0.120045f}, +{0.0252075f,-0.308062f,0.106062f},{0.0248205f,-0.309366f,0.106062f},{0.0243664f,-0.310647f,0.120045f}, +{0.0238467f,-0.311901f,0.120045f},{0.0243666f,-0.310646f,0.106062f},{0.0232623f,-0.313128f,0.120045f}, +{0.0238468f,-0.311901f,0.106062f},{0.0232624f,-0.313127f,0.106062f},{0.0226142f,-0.314323f,0.120045f}, +{0.0219036f,-0.315485f,0.120045f},{0.0226143f,-0.314323f,0.106062f},{0.0211314f,-0.316611f,0.120045f}, +{0.0219036f,-0.315485f,0.106062f},{0.0211315f,-0.316611f,0.106062f},{0.0202988f,-0.317698f,0.120045f}, +{0.0194069f,-0.318743f,0.120045f},{0.0202989f,-0.317698f,0.106062f},{0.0184567f,-0.319745f,0.120045f}, +{0.0194069f,-0.318743f,0.106062f},{0.0184567f,-0.319745f,0.106062f},{0.0174549f,-0.320695f,0.120045f}, +{0.0164091f,-0.321587f,0.120045f},{0.0174549f,-0.320695f,0.106062f},{0.015322f,-0.32242f,0.120045f}, +{0.0164092f,-0.321587f,0.106062f},{0.0153222f,-0.32242f,0.106062f},{0.0141962f,-0.323192f,0.120045f}, +{0.0130343f,-0.323903f,0.120045f},{0.0141964f,-0.323192f,0.106062f},{0.0118389f,-0.324551f,0.120045f}, +{0.0130346f,-0.323903f,0.106062f},{0.0118391f,-0.324551f,0.106062f},{0.0106125f,-0.325135f,0.120045f}, +{0.00935782f,-0.325655f,0.120045f},{0.0106128f,-0.325135f,0.106062f},{0.0080774f,-0.326109f,0.120045f}, +{0.00935809f,-0.325655f,0.106062f},{0.00807765f,-0.326109f,0.106062f},{0.00677384f,-0.326496f,0.120045f}, +{0.00544975f,-0.326815f,0.120045f},{0.00677408f,-0.326496f,0.106062f},{0.00410773f,-0.327065f,0.120045f}, +{0.00544996f,-0.326815f,0.106062f},{0.0041079f,-0.327065f,0.106062f},{0.00275036f,-0.327245f,0.120045f}, +{0.00138025f,-0.327354f,0.120045f},{0.00275048f,-0.327245f,0.106062f},{5.61862e-017f,-0.32739f,0.120045f}, +{0.00138032f,-0.327354f,0.106062f},{5.61862e-017f,-0.32739f,0.106062f},{0.0260652f,-0.299908f,0.106062f}, +{0.0259565f,-0.298538f,0.106062f},{0.0260653f,-0.299908f,0.120045f},{0.0259565f,-0.298538f,0.120045f}, +{0.0257765f,-0.297181f,0.106062f},{0.0255265f,-0.295839f,0.106062f},{0.0257766f,-0.297181f,0.120045f}, +{0.0252074f,-0.294514f,0.106062f},{0.0255265f,-0.295839f,0.120045f},{0.0252075f,-0.294515f,0.120045f}, +{0.0248204f,-0.293211f,0.106062f},{0.0243664f,-0.29193f,0.106062f},{0.0248205f,-0.293211f,0.120045f}, +{0.0238467f,-0.290676f,0.106062f},{0.0243666f,-0.291931f,0.120045f},{0.0238468f,-0.290676f,0.120045f}, +{0.0232623f,-0.289449f,0.106062f},{0.0226142f,-0.288254f,0.106062f},{0.0232624f,-0.28945f,0.120045f}, +{0.0219036f,-0.287092f,0.106062f},{0.0226143f,-0.288254f,0.120045f},{0.0219036f,-0.287092f,0.120045f}, +{0.0211314f,-0.285966f,0.106062f},{0.0202988f,-0.284879f,0.106062f},{0.0211315f,-0.285967f,0.120045f}, +{0.0194069f,-0.283834f,0.106062f},{0.0202989f,-0.284879f,0.120045f},{0.0194069f,-0.283834f,0.120045f}, +{0.0184567f,-0.282832f,0.106062f},{0.0174549f,-0.281882f,0.106062f},{0.0184567f,-0.282832f,0.120045f}, +{0.0164091f,-0.28099f,0.106062f},{0.0174549f,-0.281882f,0.120045f},{0.0164092f,-0.28099f,0.120045f}, +{0.015322f,-0.280157f,0.106062f},{0.0141962f,-0.279385f,0.106062f},{0.0153222f,-0.280157f,0.120045f}, +{0.0130343f,-0.278674f,0.106062f},{0.0141964f,-0.279385f,0.120045f},{0.0130346f,-0.278674f,0.120045f}, +{0.0118389f,-0.278026f,0.106062f},{0.0106125f,-0.277442f,0.106062f},{0.0118391f,-0.278026f,0.120045f}, +{0.00935782f,-0.276922f,0.106062f},{0.0106128f,-0.277442f,0.120045f},{0.00935809f,-0.276922f,0.120045f}, +{0.0080774f,-0.276468f,0.106062f},{0.00677384f,-0.276081f,0.106062f},{0.00807765f,-0.276468f,0.120045f}, +{0.00544975f,-0.275762f,0.106062f},{0.00677408f,-0.276081f,0.120045f},{0.00544996f,-0.275762f,0.120045f}, +{0.00410773f,-0.275512f,0.106062f},{0.00275036f,-0.275332f,0.106062f},{0.0041079f,-0.275512f,0.120045f}, +{0.00138025f,-0.275223f,0.106062f},{0.00275048f,-0.275332f,0.120045f},{0.00138032f,-0.275223f,0.120045f}, +{5.29897e-017f,-0.275187f,0.106062f},{5.29897e-017f,-0.275187f,0.120045f},{0.0121333f,-0.304179f,0.125638f}, +{-0.0149893f,-0.295319f,0.125638f},{-0.0150309f,-0.294763f,0.125638f},{-0.019126f,-0.297548f,0.125638f}, +{-0.00810759f,-0.316569f,0.125638f},{-0.00862289f,-0.286353f,0.125638f},{-0.00372901f,-0.288237f,0.125638f}, +{-0.00810797f,-0.286008f,0.125638f},{-0.0122191f,-0.286802f,0.125638f},{-0.012803f,-0.286594f,0.125638f}, +{-0.0130106f,-0.290972f,0.125638f},{0.00523604f,-0.291442f,0.125638f},{0.00485519f,-0.291361f,0.125638f}, +{-0.0018645f,-0.285009f,0.125638f},{-0.00378085f,-0.279711f,0.125638f},{-0.00629776f,-0.282236f,0.125638f}, +{0.00943824f,-0.291533f,0.125638f},{0.00917901f,-0.286627f,0.125638f},{0.00862289f,-0.286353f,0.125638f}, +{0.00897792f,-0.291847f,0.125638f},{0.0172458f,-0.301289f,0.125638f},{0.0172871f,-0.30067f,0.125638f}, +{0.010994f,-0.286978f,0.125638f},{0.0110243f,-0.291045f,0.125638f},{0.0115815f,-0.291045f,0.125638f}, +{0.0207988f,-0.305818f,0.125638f},{0.0210452f,-0.307372f,0.125638f},{0.021411f,-0.305923f,0.125638f}, +{0.0174099f,-0.302514f,0.125638f},{0.017287f,-0.301907f,0.125638f},{0.0136278f,-0.304899f,0.125638f}, +{0.019126f,-0.30503f,0.125638f},{0.0149893f,-0.307258f,0.125638f},{0.0150309f,-0.307814f,0.125638f}, +{0.0202118f,-0.305622f,0.125638f},{0.0149893f,-0.30837f,0.125638f},{0.0148647f,-0.308913f,0.125638f}, +{0.0200086f,-0.310208f,0.125638f},{0.00994038f,-0.304343f,0.125638f},{0.0104733f,-0.304175f,0.125638f}, +{0.0143811f,-0.309913f,0.125638f},{0.0185801f,-0.312894f,0.125638f},{0.0193415f,-0.311575f,0.125638f}, +{0.0205774f,-0.308803f,0.125638f},{0.0196492f,-0.305361f,0.125638f},{0.0167976f,-0.315351f,0.125638f}, +{0.013354f,-0.316267f,0.125638f},{0.0157911f,-0.316472f,0.125638f},{0.0136271f,-0.310729f,0.125638f}, +{0.0138626f,-0.316622f,0.125638f},{0.0143217f,-0.317038f,0.125638f},{0.0147191f,-0.317514f,0.125638f}, +{0.0146599f,-0.309431f,0.125638f},{0.0149896f,-0.294208f,0.125638f},{0.0205772f,-0.293773f,0.125638f}, +{0.0148655f,-0.306715f,0.125638f},{0.0186543f,-0.304628f,0.125638f},{0.0182401f,-0.304166f,0.125638f}, +{0.0178906f,-0.303654f,0.125638f},{0.0143836f,-0.305714f,0.125638f},{0.0146621f,-0.306197f,0.125638f}, +{0.0105684f,-0.299902f,0.125638f},{0.01083f,-0.300192f,0.125638f},{0.0174101f,-0.300062f,0.125638f}, +{0.0102536f,-0.299674f,0.125638f},{0.00810759f,-0.286008f,0.125638f},{0.00764282f,-0.285598f,0.125638f}, +{0.0191272f,-0.297548f,0.125638f},{0.0133515f,-0.286308f,0.125638f},{0.0157911f,-0.286105f,0.125638f}, +{0.013859f,-0.285951f,0.125638f},{0.0143221f,-0.285541f,0.125638f},{0.0147191f,-0.285063f,0.125638f}, +{0.0126646f,-0.291292f,0.125638f},{0.0128028f,-0.286595f,0.125638f},{0.0122189f,-0.286803f,0.125638f}, +{0.0116123f,-0.286931f,0.125638f},{0.0121324f,-0.291128f,0.125638f},{0.014035f,-0.292227f,0.125638f}, +{0.0177287f,-0.28842f,0.125638f},{0.013627f,-0.291848f,0.125638f},{0.0131664f,-0.291534f,0.125638f}, +{0.0193407f,-0.291f,0.125638f},{0.018579f,-0.289681f,0.125638f},{0.0146599f,-0.293147f,0.125638f}, +{0.0167966f,-0.287225f,0.125638f},{0.0196491f,-0.297213f,0.125638f},{0.02021f,-0.29695f,0.125638f}, +{0.0210452f,-0.295205f,0.125638f},{0.0208003f,-0.29676f,0.125638f},{0.021411f,-0.296654f,0.125638f}, +{0.0143816f,-0.292664f,0.125638f},{0.0200082f,-0.292368f,0.125638f},{0.0148642f,-0.293665f,0.125638f}, +{-0.00635281f,-0.281618f,0.125638f},{-0.00525411f,-0.280021f,0.125638f},{-0.00647672f,-0.281011f,0.125638f}, +{0.00723674f,-0.285129f,0.125638f},{0.00689651f,-0.284611f,0.125638f},{0.018655f,-0.29795f,0.125638f}, +{0.00632427f,-0.282854f,0.125638f},{0.00643592f,-0.283463f,0.125638f},{0.0178912f,-0.298922f,0.125638f}, +{0.0182407f,-0.298411f,0.125638f},{-0.010376f,-0.286942f,0.125638f},{-0.0109947f,-0.286977f,0.125638f}, +{-0.00838954f,-0.302903f,0.125638f},{-0.00368715f,-0.287681f,0.125638f},{-0.00356297f,-0.287138f,0.125638f}, +{-0.00764334f,-0.285598f,0.125638f},{-0.00632322f,-0.282854f,0.125638f},{-0.00643547f,-0.283464f,0.125638f}, +{-0.00232474f,-0.285323f,0.125638f},{-0.000829763f,-0.284603f,0.125638f},{-0.00227994f,-0.279501f,0.125638f}, +{-0.00136226f,-0.284767f,0.125638f},{-0.00662778f,-0.284053f,0.125638f},{-0.00273315f,-0.285701f,0.125638f}, +{0.00377962f,-0.27971f,0.125638f},{0.00136248f,-0.284767f,0.125638f},{0.00027877f,-0.284522f,0.125638f}, +{0.000760576f,-0.279395f,0.125638f},{-0.000278327f,-0.284521f,0.125638f},{0.00629503f,-0.282234f,0.125638f}, +{0.00525411f,-0.280021f,0.125638f},{-0.00669182f,-0.280429f,0.125638f},{0.00634749f,-0.281617f,0.125638f}, +{0.0064786f,-0.281011f,0.125638f},{0.00669182f,-0.280429f,0.125638f},{-0.0030806f,-0.286137f,0.125638f}, +{-0.00689664f,-0.284612f,0.125638f},{-0.00335928f,-0.286619f,0.125638f},{0.00227826f,-0.2795f,0.125638f}, +{0.000829582f,-0.284604f,0.125638f},{-0.0146621f,-0.296381f,0.125638f},{-0.0178906f,-0.298923f,0.125638f}, +{-0.0143836f,-0.296863f,0.125638f},{0.00408395f,-0.291443f,0.125638f},{0.00446533f,-0.291361f,0.125638f}, +{-0.00917948f,-0.286627f,0.125638f},{-0.0130106f,-0.302446f,0.125638f},{-0.00632427f,-0.319723f,0.125638f}, +{-0.00643592f,-0.319114f,0.125638f},{-0.0097673f,-0.286824f,0.125638f},{-0.0205774f,-0.293774f,0.125638f}, +{-0.0210452f,-0.295205f,0.125638f},{-0.0196492f,-0.297216f,0.125638f},{-0.0136271f,-0.291848f,0.125638f}, +{-0.0177299f,-0.288421f,0.125638f},{-0.0140346f,-0.292228f,0.125638f},{-0.00590935f,-0.291831f,0.125638f}, +{-0.0207988f,-0.296759f,0.125638f},{-0.021411f,-0.296654f,0.125638f},{-0.0140362f,-0.297299f,0.125638f}, +{-0.0174099f,-0.300063f,0.125638f},{-0.0136278f,-0.297678f,0.125638f},{-0.0182401f,-0.298411f,0.125638f}, +{-0.0148655f,-0.295862f,0.125638f},{-0.0186543f,-0.297949f,0.125638f},{-0.0202118f,-0.296955f,0.125638f}, +{-0.0149893f,-0.294207f,0.125638f},{-0.0148647f,-0.293665f,0.125638f},{-0.0200086f,-0.292369f,0.125638f}, +{-0.0193415f,-0.291002f,0.125638f},{-0.0143811f,-0.292664f,0.125638f},{-0.0185801f,-0.289683f,0.125638f}, +{-0.0146599f,-0.293146f,0.125638f},{-0.013354f,-0.28631f,0.125638f},{-0.0157911f,-0.286105f,0.125638f}, +{-0.0167976f,-0.287226f,0.125638f},{-0.0138626f,-0.285956f,0.125638f},{-0.00976653f,-0.315753f,0.125638f}, +{-0.00917901f,-0.31595f,0.125638f},{-0.00994062f,-0.311285f,0.125638f},{-0.0143217f,-0.285539f,0.125638f}, +{-0.0147191f,-0.285063f,0.125638f},{-0.00636453f,-0.292458f,0.125638f},{-0.00648481f,-0.292829f,0.125638f}, +{-0.0176127f,-0.303101f,0.125638f},{-0.0178912f,-0.303655f,0.125638f},{-0.0116126f,-0.286931f,0.125638f}, +{-0.00862289f,-0.316224f,0.125638f},{-0.00943824f,-0.311044f,0.125638f},{-0.00315227f,-0.310457f,0.125638f}, +{-0.00295749f,-0.310119f,0.125638f},{-0.0104733f,-0.311449f,0.125638f},{-0.0196491f,-0.305364f,0.125638f}, +{-0.0205772f,-0.308804f,0.125638f},{-0.0167966f,-0.315352f,0.125638f},{-0.0157911f,-0.316472f,0.125638f}, +{-0.0130106f,-0.31392f,0.125638f},{-0.0122189f,-0.315774f,0.125638f},{-0.0116123f,-0.315646f,0.125638f}, +{-0.017287f,-0.30067f,0.125638f},{-0.0174101f,-0.302515f,0.125638f},{-0.0172458f,-0.301289f,0.125638f}, +{-0.00723674f,-0.317448f,0.125638f},{-0.00689651f,-0.317966f,0.125638f},{-0.013859f,-0.316626f,0.125638f}, +{-0.0133515f,-0.316269f,0.125638f},{-0.0115815f,-0.311532f,0.125638f},{-0.0121324f,-0.311449f,0.125638f}, +{-0.014035f,-0.31035f,0.125638f},{-0.0177287f,-0.314157f,0.125638f},{-0.013627f,-0.310729f,0.125638f}, +{-0.0143816f,-0.309913f,0.125638f},{-0.018579f,-0.312896f,0.125638f},{-0.0193407f,-0.311577f,0.125638f}, +{-0.0146599f,-0.309431f,0.125638f},{-0.0149896f,-0.308369f,0.125638f},{-0.0131664f,-0.311043f,0.125638f}, +{-0.0126646f,-0.311285f,0.125638f},{-0.0210452f,-0.307372f,0.125638f},{-0.0143221f,-0.317036f,0.125638f}, +{-0.02021f,-0.305627f,0.125638f},{-0.0208003f,-0.305817f,0.125638f},{-0.0147191f,-0.317514f,0.125638f}, +{-0.021411f,-0.305923f,0.125638f},{-0.0110243f,-0.311532f,0.125638f},{0.00874495f,-0.299516f,0.125638f}, +{0.00838954f,-0.299674f,0.125638f},{-0.00523587f,-0.311135f,0.125638f},{-0.00485544f,-0.311216f,0.125638f}, +{0.0063639f,-0.308603f,0.125638f},{0.00616894f,-0.308265f,0.125638f},{-0.00629503f,-0.320343f,0.125638f}, +{-0.00377962f,-0.322867f,0.125638f},{0.0099371f,-0.31392f,0.125638f},{0.0109947f,-0.3156f,0.125638f}, +{0.0116126f,-0.315647f,0.125638f},{0.00356297f,-0.315439f,0.125638f},{0.00764334f,-0.316979f,0.125638f}, +{0.00368715f,-0.314896f,0.125638f},{0.0097673f,-0.315753f,0.125638f},{0.00917948f,-0.31595f,0.125638f}, +{0.00643547f,-0.319113f,0.125638f},{0.00232474f,-0.317255f,0.125638f},{0.00632322f,-0.319723f,0.125638f}, +{0.00810797f,-0.316569f,0.125638f},{0.00862289f,-0.316224f,0.125638f},{0.00372901f,-0.31434f,0.125638f}, +{0.00378085f,-0.322866f,0.125638f},{0.00629776f,-0.320341f,0.125638f},{0.0018645f,-0.317568f,0.125638f}, +{0.0111453f,-0.3009f,0.125638f},{0.0110251f,-0.30053f,0.125638f},{-0.0200082f,-0.31021f,0.125638f}, +{-0.0148642f,-0.308912f,0.125638f},{-0.010994f,-0.3156f,0.125638f},{0.00773683f,-0.293662f,0.125638f}, +{-0.0110251f,-0.302047f,0.125638f},{-0.0111453f,-0.301677f,0.125638f},{-0.00764282f,-0.316979f,0.125638f}, +{-0.0105684f,-0.302675f,0.125638f},{0.00807379f,-0.299904f,0.125638f},{-0.000829582f,-0.317973f,0.125638f}, +{-0.00136248f,-0.31781f,0.125638f},{-0.00227826f,-0.323077f,0.125638f},{-0.00027877f,-0.318055f,0.125638f}, +{-0.000760576f,-0.323182f,0.125638f},{0.000278327f,-0.318056f,0.125638f},{0.000829763f,-0.317974f,0.125638f}, +{0.00227994f,-0.323076f,0.125638f},{0.00136226f,-0.31781f,0.125638f},{-0.00525411f,-0.322556f,0.125638f}, +{-0.00634749f,-0.32096f,0.125638f},{-0.0064786f,-0.321566f,0.125638f},{-0.00669182f,-0.322148f,0.125638f}, +{0.00335928f,-0.315958f,0.125638f},{0.0030806f,-0.31644f,0.125638f},{0.00689664f,-0.317965f,0.125638f}, +{0.00273315f,-0.316876f,0.125638f},{0.00662778f,-0.318524f,0.125638f},{0.00525411f,-0.322556f,0.125638f}, +{0.00635281f,-0.320959f,0.125638f},{0.00669182f,-0.322148f,0.125638f},{0.00647672f,-0.321566f,0.125638f}, +{0.0176127f,-0.299476f,0.125638f},{0.00994062f,-0.291292f,0.125638f},{0.0103751f,-0.286942f,0.125638f}, +{0.00976653f,-0.286824f,0.125638f},{0.0104733f,-0.291128f,0.125638f},{0.00912617f,-0.299435f,0.125638f}, +{0.0095162f,-0.299434f,0.125638f},{0.00989767f,-0.299515f,0.125638f},{0.0140362f,-0.305278f,0.125638f}, +{0.0110245f,-0.304105f,0.125638f},{0.0177299f,-0.314156f,0.125638f},{0.0140346f,-0.310349f,0.125638f}, +{0.00822623f,-0.292664f,0.125638f},{-0.00408474f,-0.294989f,0.125638f},{-0.00446554f,-0.29507f,0.125638f}, +{-0.018655f,-0.304627f,0.125638f},{-0.0191272f,-0.305029f,0.125638f},{0.00315227f,-0.29212f,0.125638f}, +{0.00295755f,-0.292458f,0.125638f},{0.00341361f,-0.294601f,0.125638f},{0.00749845f,-0.300901f,0.125638f}, +{0.00761862f,-0.300531f,0.125638f},{0.0126655f,-0.304343f,0.125638f},{0.0131672f,-0.304585f,0.125638f}, +{0.0115822f,-0.3041f,0.125638f},{0.0122191f,-0.315775f,0.125638f},{0.012803f,-0.315983f,0.125638f}, +{0.00590935f,-0.310746f,0.125638f},{0.00636453f,-0.310119f,0.125638f},{0.00648481f,-0.309748f,0.125638f}, +{-0.00408362f,-0.311134f,0.125638f},{-0.00446544f,-0.311216f,0.125638f},{-0.00807379f,-0.302673f,0.125638f}, +{-0.00430393f,-0.303071f,0.125638f},{0.00283746f,-0.304987f,0.125638f},{0.00408474f,-0.307589f,0.125638f}, +{0.00446554f,-0.307508f,0.125638f},{-0.00874495f,-0.303061f,0.125638f},{-0.0172871f,-0.301907f,0.125638f}, +{0.00761515f,-0.294207f,0.125638f},{0.0085695f,-0.292226f,0.125638f},{-0.00723717f,-0.28513f,0.125638f}, +{-0.000762504f,-0.279395f,0.125638f},{0.00662806f,-0.284053f,0.125638f},{0.00341281f,-0.291831f,0.125638f}, +{0.00372825f,-0.291601f,0.125638f},{0.00279662f,-0.293216f,0.125638f},{0.00283723f,-0.292829f,0.125638f}, +{0.00283764f,-0.293604f,0.125638f},{-0.00335595f,-0.289852f,0.125638f},{0.00795154f,-0.293149f,0.125638f}, +{-0.00369782f,-0.304126f,0.125638f},{0.00295819f,-0.293974f,0.125638f},{0.00315308f,-0.294312f,0.125638f}, +{-0.00523619f,-0.294989f,0.125638f},{-0.00616894f,-0.294312f,0.125638f},{-0.0063639f,-0.293974f,0.125638f}, +{-0.00273651f,-0.290775f,0.125638f},{-0.00232523f,-0.291153f,0.125638f},{-0.00356376f,-0.289336f,0.125638f}, +{-0.0131672f,-0.297992f,0.125638f},{-0.0176123f,-0.299477f,0.125638f},{-0.00616972f,-0.29212f,0.125638f}, +{-0.00648443f,-0.293604f,0.125638f},{-0.00652539f,-0.293216f,0.125638f},{-0.00559278f,-0.29483f,0.125638f}, +{-0.00590766f,-0.294602f,0.125638f},{-0.0048551f,-0.29507f,0.125638f},{-0.00307294f,-0.290333f,0.125638f}, +{-0.0110245f,-0.298472f,0.125638f},{-0.0095162f,-0.303143f,0.125638f},{-0.00368758f,-0.288793f,0.125638f}, +{-0.00897792f,-0.31073f,0.125638f},{-0.0103751f,-0.315635f,0.125638f},{-0.0128028f,-0.315982f,0.125638f}, +{-0.0182407f,-0.304166f,0.125638f},{-0.01083f,-0.302385f,0.125638f},{-0.0102536f,-0.302903f,0.125638f}, +{-0.00912617f,-0.303143f,0.125638f},{-0.00989767f,-0.303062f,0.125638f},{-0.0115822f,-0.298477f,0.125638f}, +{-0.0121333f,-0.298398f,0.125638f},{-0.0104733f,-0.298402f,0.125638f},{-0.00994038f,-0.298234f,0.125638f}, +{-0.00462174f,-0.301897f,0.125638f},{-0.00761862f,-0.302046f,0.125638f},{-0.00449935f,-0.302494f,0.125638f}, +{-0.00749845f,-0.301676f,0.125638f},{-0.00761515f,-0.30837f,0.125638f},{-0.0085695f,-0.310351f,0.125638f}, +{-0.00822623f,-0.309913f,0.125638f},{-0.00773683f,-0.308915f,0.125638f},{-0.00403697f,-0.303619f,0.125638f}, +{-0.0126655f,-0.298234f,0.125638f},{0.00559278f,-0.307747f,0.125638f},{0.00723717f,-0.317447f,0.125638f}, +{0.000762504f,-0.323182f,0.125638f},{-0.00662806f,-0.318524f,0.125638f},{-0.00341302f,-0.310747f,0.125638f}, +{-0.00372824f,-0.310976f,0.125638f},{-0.00279657f,-0.309361f,0.125638f},{-0.00283721f,-0.309748f,0.125638f}, +{-0.0028377f,-0.308973f,0.125638f},{0.00120604f,-0.305791f,0.125638f},{-0.00795154f,-0.309428f,0.125638f}, +{0.003698f,-0.304126f,0.125638f},{0.00329612f,-0.304585f,0.125638f},{0.0048551f,-0.307507f,0.125638f}, +{0.00523619f,-0.307588f,0.125638f},{0.00781324f,-0.300193f,0.125638f},{0.00430606f,-0.303073f,0.125638f}, +{0.00356376f,-0.313241f,0.125638f},{-0.00283752f,-0.304986f,0.125638f},{-0.00329569f,-0.304584f,0.125638f}, +{0.00178338f,-0.305595f,0.125638f},{0.000608186f,-0.30591f,0.125638f},{5.18512e-017f,-0.30595f,0.125638f}, +{-0.0034133f,-0.307976f,0.125638f},{-0.00233082f,-0.305324f,0.125638f},{-0.00295825f,-0.308603f,0.125638f}, +{-0.00120688f,-0.30579f,0.125638f},{-0.00315303f,-0.308265f,0.125638f},{0.0176123f,-0.3031f,0.125638f}, +{0.010376f,-0.315635f,0.125638f},{0.00616972f,-0.310457f,0.125638f},{0.00648443f,-0.308973f,0.125638f}, +{0.00652539f,-0.309361f,0.125638f},{0.00449528f,-0.302494f,0.125638f},{0.00590766f,-0.307976f,0.125638f}, +{0.00273651f,-0.311802f,0.125638f},{0.00335595f,-0.312725f,0.125638f},{0.00232523f,-0.311424f,0.125638f}, +{0.00307294f,-0.312244f,0.125638f},{0.00461789f,-0.301897f,0.125638f},{0.00403651f,-0.30362f,0.125638f}, +{0.00368758f,-0.313784f,0.125638f},{0.00233031f,-0.305326f,0.125638f},{-0.00060875f,-0.30591f,0.125638f}, +{-0.00178418f,-0.305594f,0.125638f},{-0.00781324f,-0.302384f,0.125638f},{0.0216239f,-0.307539f,0.12559f}, +{0.0211432f,-0.30901f,0.12559f},{0.0217239f,-0.309222f,0.125434f},{0.0192916f,-0.317439f,0.12373f}, +{0.0203623f,-0.316066f,0.12373f},{0.0200519f,-0.315841f,0.12429f},{0.0210134f,-0.314414f,0.12429f}, +{0.0213388f,-0.314617f,0.12373f},{0.0186268f,-0.316882f,0.124775f},{0.0181976f,-0.316523f,0.125161f}, +{0.0175107f,-0.318126f,0.124775f},{0.016671f,-0.317318f,0.125434f},{0.0158563f,-0.318767f,0.125232f}, +{0.0171072f,-0.317738f,0.125161f},{0.0151138f,-0.317949f,0.125592f},{0.0154952f,-0.318369f,0.125455f}, +{0.0162253f,-0.31689f,0.12559f},{0.0218746f,-0.312922f,0.12429f},{0.0222133f,-0.313102f,0.12373f}, +{0.0226291f,-0.311376f,0.12429f},{0.0215683f,-0.31476f,0.123126f},{0.0217015f,-0.314844f,0.122512f}, +{0.0224522f,-0.313229f,0.123126f},{0.021363f,-0.315459f,0.121909f},{0.0222009f,-0.314106f,0.121909f}, +{0.0207085f,-0.316317f,0.122512f},{0.0204426f,-0.316757f,0.121909f},{0.0196196f,-0.317713f,0.122512f}, +{0.0225908f,-0.313303f,0.122512f},{0.0229535f,-0.312704f,0.121909f},{0.0183695f,-0.31917f,0.121909f}, +{0.0194435f,-0.317996f,0.121909f},{0.018444f,-0.319023f,0.122512f},{0.0172245f,-0.320275f,0.121909f}, +{0.0171931f,-0.320241f,0.122497f},{0.02337f,-0.311706f,0.122512f},{0.0236175f,-0.311258f,0.121909f}, +{0.0240343f,-0.310066f,0.122512f},{0.0241903f,-0.309773f,0.121909f},{0.024671f,-0.308256f,0.121909f}, +{0.0245807f,-0.308394f,0.122512f},{0.0250097f,-0.306702f,0.122497f},{0.024876f,-0.306673f,0.123065f}, +{0.0229794f,-0.311532f,0.12373f},{0.0181357f,-0.318727f,0.12373f},{0.0189975f,-0.317193f,0.12429f}, +{0.0250554f,-0.306712f,0.121909f},{0.0232266f,-0.311642f,0.123126f},{0.0233369f,-0.308035f,0.124775f}, +{0.0235497f,-0.306386f,0.124929f},{0.0227992f,-0.307879f,0.125161f},{0.0239879f,-0.306481f,0.124546f}, +{0.0238014f,-0.308169f,0.12429f},{0.0209535f,-0.312432f,0.125161f},{0.0216762f,-0.310951f,0.125161f}, +{0.0211235f,-0.310705f,0.125434f},{0.0219851f,-0.306047f,0.125592f},{0.0244299f,-0.308351f,0.123126f}, +{0.0246584f,-0.306626f,0.123602f},{0.0241699f,-0.308275f,0.12373f},{0.0238868f,-0.310012f,0.123126f}, +{0.0205814f,-0.316225f,0.123126f},{0.0194991f,-0.317613f,0.123126f},{0.0183308f,-0.318914f,0.123126f}, +{0.0171019f,-0.32014f,0.123062f},{0.02436f,-0.306561f,0.1241f},{0.0236326f,-0.309919f,0.12373f}, +{0.0169523f,-0.319975f,0.1236f},{0.0222178f,-0.307711f,0.125434f},{0.0230629f,-0.306281f,0.125233f}, +{0.0232723f,-0.309787f,0.12429f},{0.0196606f,-0.315557f,0.124775f},{0.0178592f,-0.318461f,0.12429f}, +{0.0167476f,-0.31975f,0.124098f},{0.0221874f,-0.311179f,0.124775f},{0.0228181f,-0.309621f,0.124775f}, +{0.0214477f,-0.312695f,0.124775f},{0.0206034f,-0.314158f,0.124775f},{0.0164907f,-0.319467f,0.124546f}, +{0.0222924f,-0.309429f,0.125161f},{0.0201286f,-0.313861f,0.125161f},{0.0192076f,-0.315228f,0.125161f}, +{0.0161909f,-0.319136f,0.124927f},{0.0225375f,-0.306167f,0.125456f},{0.0204192f,-0.312148f,0.125434f}, +{0.0196153f,-0.313541f,0.125434f},{0.0187178f,-0.314873f,0.125434f},{0.0172595f,-0.315738f,0.12559f}, +{0.0177335f,-0.316134f,0.125434f},{0.0205588f,-0.310453f,0.12559f},{0.0198733f,-0.311858f,0.12559f}, +{0.019091f,-0.313213f,0.12559f},{0.0182174f,-0.314509f,0.12559f},{0.000885136f,-0.326703f,0.123126f}, +{0.00261846f,-0.326311f,0.12373f},{0.000875717f,-0.326433f,0.12373f},{0.00441602f,-0.326491f,0.122512f}, +{0.00266296f,-0.326736f,0.122512f},{0.00264799f,-0.326787f,0.121909f},{0.00257853f,-0.32593f,0.12429f}, +{0.000884103f,-0.326909f,0.121909f},{0.00609912f,-0.325976f,0.123126f},{0.00613678f,-0.326129f,0.122512f}, +{0.0077748f,-0.325524f,0.123065f},{0.00612578f,-0.326167f,0.121909f},{0.00781658f,-0.325654f,0.122497f}, +{0.00539858f,-0.323141f,0.12559f},{0.00388481f,-0.32346f,0.12559f},{0.00399151f,-0.324069f,0.125434f}, +{0.00783085f,-0.325699f,0.121909f},{0.00439916f,-0.326544f,0.121909f},{0.00749724f,-0.324659f,0.124546f}, +{0.00582624f,-0.324872f,0.124775f},{0.00594221f,-0.325341f,0.12429f},{0.00246996f,-0.324892f,0.125161f}, +{0.00240697f,-0.32429f,0.125434f},{0.000826054f,-0.325007f,0.125161f},{0.005692f,-0.324329f,0.125161f}, +{0.00736026f,-0.324232f,0.124929f},{0.000890602f,-0.32686f,0.122512f},{0.00264662f,-0.32658f,0.123126f}, +{-0.00427461f,-0.325693f,0.12429f},{-0.00603421f,-0.325714f,0.12373f},{-0.0043408f,-0.326071f,0.12373f}, +{0.00687127f,-0.322708f,0.125592f},{-0.000860185f,-0.326049f,0.12429f},{-0.00261652f,-0.326312f,0.12373f}, +{-0.000873503f,-0.326433f,0.12373f},{0.000862365f,-0.326049f,0.12429f},{-0.00582624f,-0.324872f,0.124775f}, +{-0.00419119f,-0.325217f,0.124775f},{-0.00409462f,-0.324665f,0.125161f},{-0.00554685f,-0.323741f,0.125434f}, +{-0.00720884f,-0.32376f,0.125232f},{-0.005692f,-0.324329f,0.125161f},{-0.00257663f,-0.32593f,0.12429f}, +{-0.00687127f,-0.322708f,0.125592f},{-0.00704464f,-0.323248f,0.125455f},{-0.00539858f,-0.323141f,0.12559f}, +{-0.00088835f,-0.32686f,0.122512f},{-0.000882898f,-0.326703f,0.123126f},{-0.000883894f,-0.326909f,0.121909f}, +{-0.002661f,-0.326737f,0.122512f},{-0.00264771f,-0.326787f,0.121909f},{-0.00441458f,-0.326492f,0.122512f}, +{-0.00439897f,-0.326544f,0.121909f},{-0.00612769f,-0.326175f,0.121909f},{-0.00613678f,-0.326129f,0.122512f}, +{-0.00783085f,-0.325699f,0.121909f},{0.00770679f,-0.325312f,0.123602f},{0.00603421f,-0.325714f,0.12373f}, +{0.00438891f,-0.326337f,0.123126f},{-0.00264467f,-0.326581f,0.123126f},{-0.00609912f,-0.325976f,0.123126f}, +{-0.00438748f,-0.326337f,0.123126f},{-0.00781658f,-0.325654f,0.122497f},{-0.0077751f,-0.325525f,0.123062f}, +{0.00761353f,-0.325021f,0.1241f},{0.00434221f,-0.32607f,0.12373f},{-0.00770709f,-0.325313f,0.1236f}, +{0.00554685f,-0.323741f,0.125434f},{0.00720812f,-0.323758f,0.125233f},{0.004276f,-0.325692f,0.12429f}, +{-0.00252634f,-0.325449f,0.124775f},{-0.00594221f,-0.325341f,0.12429f},{-0.00761404f,-0.325023f,0.124098f}, +{0.00252821f,-0.325449f,0.124775f},{0.00419255f,-0.325216f,0.124775f},{0.000845536f,-0.325566f,0.124775f}, +{-0.000843398f,-0.325566f,0.124775f},{-0.00749724f,-0.324659f,0.124546f},{0.00409595f,-0.324665f,0.125161f}, +{-0.000823965f,-0.325007f,0.125161f},{-0.00246814f,-0.324892f,0.125161f},{-0.00736095f,-0.324234f,0.124927f}, +{0.00704393f,-0.323246f,0.125456f},{0.000804989f,-0.324402f,0.125434f},{-0.000802953f,-0.324402f,0.125434f}, +{-0.0024052f,-0.324291f,0.125434f},{-0.00388354f,-0.32346f,0.12559f},{-0.00399021f,-0.324069f,0.125434f}, +{0.00234263f,-0.323675f,0.12559f},{0.00078347f,-0.323784f,0.12559f},{-0.000781489f,-0.323784f,0.12559f}, +{-0.0023409f,-0.323676f,0.12559f},{-0.0217002f,-0.314846f,0.122512f},{-0.02058f,-0.316226f,0.123126f}, +{-0.021567f,-0.314762f,0.123126f},{-0.0207071f,-0.316319f,0.122512f},{-0.0213629f,-0.315459f,0.121909f}, +{-0.0204426f,-0.316757f,0.121909f},{-0.020361f,-0.316067f,0.12373f},{-0.0213375f,-0.314619f,0.12373f}, +{-0.0200505f,-0.315842f,0.12429f},{-0.0183308f,-0.318914f,0.123126f},{-0.018444f,-0.319023f,0.122512f}, +{-0.0171015f,-0.32014f,0.123063f},{-0.0169508f,-0.319974f,0.123604f},{-0.0172584f,-0.315738f,0.12559f}, +{-0.0177324f,-0.316135f,0.125434f},{-0.0162253f,-0.31689f,0.12559f},{-0.0171936f,-0.320241f,0.122494f}, +{-0.0183693f,-0.31917f,0.121909f},{-0.0172245f,-0.320275f,0.121909f},{-0.0196183f,-0.317714f,0.122512f}, +{-0.0194434f,-0.317996f,0.121909f},{-0.0171072f,-0.317738f,0.125161f},{-0.0175107f,-0.318126f,0.124775f}, +{-0.0161913f,-0.319136f,0.124927f},{-0.0201275f,-0.313863f,0.125161f},{-0.0192063f,-0.315229f,0.125161f}, +{-0.0187165f,-0.314874f,0.125434f},{-0.0151117f,-0.317946f,0.125592f},{-0.0178592f,-0.318461f,0.12429f}, +{-0.0164907f,-0.319467f,0.124546f},{-0.0232721f,-0.309789f,0.12429f},{-0.0241699f,-0.308275f,0.12373f}, +{-0.0236324f,-0.30992f,0.12373f},{-0.0210122f,-0.314416f,0.12429f},{-0.0222178f,-0.307711f,0.125434f}, +{-0.0230652f,-0.306281f,0.125232f},{-0.0227992f,-0.307879f,0.125161f},{-0.0224512f,-0.313231f,0.123126f}, +{-0.0225899f,-0.313305f,0.122512f},{-0.0233369f,-0.308035f,0.124775f},{-0.0228179f,-0.309623f,0.124775f}, +{-0.0222922f,-0.309431f,0.125161f},{-0.0229789f,-0.311534f,0.12373f},{-0.0226285f,-0.311378f,0.12429f}, +{-0.0218736f,-0.312924f,0.12429f},{-0.0222123f,-0.313104f,0.12373f},{-0.0219851f,-0.306047f,0.125592f}, +{-0.0225398f,-0.306167f,0.125455f},{-0.0216239f,-0.307539f,0.12559f},{-0.0222011f,-0.314107f,0.121909f}, +{-0.0233694f,-0.311708f,0.122512f},{-0.0229536f,-0.312705f,0.121909f},{-0.0240341f,-0.310067f,0.122512f}, +{-0.0236177f,-0.311258f,0.121909f},{-0.0241882f,-0.309773f,0.121909f},{-0.0245807f,-0.308394f,0.122512f}, +{-0.0246627f,-0.308254f,0.121909f},{-0.0250554f,-0.306712f,0.121909f},{-0.0250097f,-0.306702f,0.122497f}, +{-0.0181357f,-0.318727f,0.12373f},{-0.0194979f,-0.317614f,0.123126f},{-0.023226f,-0.311644f,0.123126f}, +{-0.0238866f,-0.310013f,0.123126f},{-0.0244299f,-0.308351f,0.123126f},{-0.024877f,-0.306673f,0.123062f}, +{-0.0167454f,-0.319747f,0.124102f},{-0.0192904f,-0.31744f,0.12373f},{-0.0246594f,-0.306626f,0.1236f}, +{-0.016671f,-0.317318f,0.125434f},{-0.0158556f,-0.318766f,0.125233f},{-0.0189963f,-0.317194f,0.12429f}, +{-0.0221869f,-0.311181f,0.124775f},{-0.0238014f,-0.308169f,0.12429f},{-0.0243617f,-0.306562f,0.124098f}, +{-0.0196592f,-0.315558f,0.124775f},{-0.0186256f,-0.316883f,0.124775f},{-0.0206021f,-0.31416f,0.124775f}, +{-0.0214468f,-0.312697f,0.124775f},{-0.0239879f,-0.306481f,0.124546f},{-0.0181964f,-0.316524f,0.125161f}, +{-0.0209526f,-0.312434f,0.125161f},{-0.0216757f,-0.310953f,0.125161f},{-0.0235519f,-0.306387f,0.124927f}, +{-0.0154922f,-0.318366f,0.125456f},{-0.0196142f,-0.313542f,0.125434f},{-0.0204183f,-0.31215f,0.125434f}, +{-0.0211229f,-0.310707f,0.125434f},{-0.021143f,-0.309011f,0.12559f},{-0.0217237f,-0.309223f,0.125434f}, +{-0.0182162f,-0.314511f,0.12559f},{-0.0190899f,-0.313215f,0.12559f},{-0.0198725f,-0.31186f,0.12559f}, +{-0.0205583f,-0.310455f,0.12559f},{-0.0225908f,-0.289274f,0.122512f},{-0.0232266f,-0.290935f,0.123126f}, +{-0.0224522f,-0.289348f,0.123126f},{-0.02337f,-0.290871f,0.122512f},{-0.0229794f,-0.291045f,0.12373f}, +{-0.0222133f,-0.289475f,0.12373f},{-0.0226291f,-0.291201f,0.12429f},{-0.0244299f,-0.294227f,0.123126f}, +{-0.0245807f,-0.294183f,0.122512f},{-0.024876f,-0.295904f,0.123065f},{-0.0246584f,-0.295951f,0.123602f}, +{-0.0211432f,-0.293567f,0.12559f},{-0.0217239f,-0.293355f,0.125434f},{-0.0216239f,-0.295038f,0.12559f}, +{-0.0250097f,-0.295875f,0.122497f},{-0.0240343f,-0.292511f,0.122512f},{-0.0227992f,-0.294698f,0.125161f}, +{-0.0233369f,-0.294543f,0.124775f},{-0.0235497f,-0.296191f,0.124929f},{-0.0209535f,-0.290145f,0.125161f}, +{-0.0216762f,-0.291626f,0.125161f},{-0.0211235f,-0.291872f,0.125434f},{-0.0219851f,-0.29653f,0.125592f}, +{-0.0238014f,-0.294408f,0.12429f},{-0.0239879f,-0.296096f,0.124546f},{-0.0189975f,-0.285384f,0.12429f}, +{-0.0181357f,-0.28385f,0.12373f},{-0.0192916f,-0.285138f,0.12373f},{-0.0218746f,-0.289655f,0.12429f}, +{-0.016671f,-0.285259f,0.125434f},{-0.0158576f,-0.283808f,0.125231f},{-0.0171072f,-0.284839f,0.125161f}, +{-0.0215683f,-0.287817f,0.123126f},{-0.0217015f,-0.287733f,0.122512f},{-0.0175107f,-0.284451f,0.124775f}, +{-0.0186268f,-0.285695f,0.124775f},{-0.0181976f,-0.286054f,0.125161f},{-0.0203623f,-0.286511f,0.12373f}, +{-0.0200519f,-0.286736f,0.12429f},{-0.0210134f,-0.288163f,0.12429f},{-0.0213388f,-0.28796f,0.12373f}, +{-0.0151117f,-0.284631f,0.125592f},{-0.0154943f,-0.284209f,0.125455f},{-0.0162253f,-0.285687f,0.12559f}, +{-0.0207085f,-0.28626f,0.122512f},{-0.0196196f,-0.284864f,0.122512f},{-0.018444f,-0.283554f,0.122512f}, +{-0.0171936f,-0.282336f,0.122494f},{-0.0241699f,-0.294302f,0.12373f},{-0.0238868f,-0.292565f,0.123126f}, +{-0.0205814f,-0.286352f,0.123126f},{-0.0194991f,-0.284964f,0.123126f},{-0.0183308f,-0.283663f,0.123126f}, +{-0.0171022f,-0.282437f,0.12306f},{-0.02436f,-0.296016f,0.1241f},{-0.0236326f,-0.292658f,0.12373f}, +{-0.0169519f,-0.282602f,0.123601f},{-0.0222178f,-0.294866f,0.125434f},{-0.0230629f,-0.296296f,0.125233f}, +{-0.0232723f,-0.29279f,0.12429f},{-0.0196606f,-0.28702f,0.124775f},{-0.0178592f,-0.284116f,0.12429f}, +{-0.0167464f,-0.282829f,0.1241f},{-0.0221874f,-0.291398f,0.124775f},{-0.0228181f,-0.292956f,0.124775f}, +{-0.0214477f,-0.289882f,0.124775f},{-0.0206034f,-0.288419f,0.124775f},{-0.0164907f,-0.283111f,0.124546f}, +{-0.0222924f,-0.293148f,0.125161f},{-0.0201286f,-0.288716f,0.125161f},{-0.0192076f,-0.287349f,0.125161f}, +{-0.0161924f,-0.283439f,0.124925f},{-0.0225375f,-0.29641f,0.125456f},{-0.0204192f,-0.290429f,0.125434f}, +{-0.0196153f,-0.289036f,0.125434f},{-0.0187178f,-0.287705f,0.125434f},{-0.0172595f,-0.286839f,0.12559f}, +{-0.0177335f,-0.286443f,0.125434f},{-0.0205588f,-0.292124f,0.12559f},{-0.0198733f,-0.290719f,0.12559f}, +{-0.019091f,-0.289364f,0.12559f},{-0.0182174f,-0.288068f,0.12559f},{-0.000885136f,-0.275874f,0.123126f}, +{-0.00261846f,-0.276266f,0.12373f},{-0.000875717f,-0.276144f,0.12373f},{-0.00441602f,-0.276086f,0.122512f}, +{-0.00266296f,-0.275841f,0.122512f},{-0.00257853f,-0.276647f,0.12429f},{-0.00609912f,-0.276601f,0.123126f}, +{-0.00613678f,-0.276448f,0.122512f},{-0.0077748f,-0.277053f,0.123065f},{-0.00781658f,-0.276923f,0.122497f}, +{-0.00539858f,-0.279436f,0.12559f},{-0.00388481f,-0.279117f,0.12559f},{-0.00399151f,-0.278508f,0.125434f}, +{-0.00749724f,-0.277918f,0.124546f},{-0.00582624f,-0.277705f,0.124775f},{-0.00594221f,-0.277236f,0.12429f}, +{-0.00246996f,-0.277685f,0.125161f},{-0.00240697f,-0.278287f,0.125434f},{-0.000826054f,-0.27757f,0.125161f}, +{-0.005692f,-0.278249f,0.125161f},{-0.00736026f,-0.278345f,0.124929f},{-0.000890602f,-0.275717f,0.122512f}, +{-0.00264662f,-0.275997f,0.123126f},{0.00427461f,-0.276884f,0.12429f},{0.00603421f,-0.276863f,0.12373f}, +{0.0043408f,-0.276506f,0.12373f},{-0.00687127f,-0.279869f,0.125592f},{0.000860185f,-0.276528f,0.12429f}, +{0.00261652f,-0.276265f,0.12373f},{0.000873503f,-0.276144f,0.12373f},{-0.000862365f,-0.276528f,0.12429f}, +{0.00582624f,-0.277705f,0.124775f},{0.00419119f,-0.27736f,0.124775f},{0.00409462f,-0.277912f,0.125161f}, +{0.00554685f,-0.278836f,0.125434f},{0.00720884f,-0.278817f,0.125232f},{0.005692f,-0.278249f,0.125161f}, +{0.00257663f,-0.276647f,0.12429f},{0.00687127f,-0.279869f,0.125592f},{0.00704464f,-0.279329f,0.125455f}, +{0.00539858f,-0.279436f,0.12559f},{0.00088835f,-0.275717f,0.122512f},{0.000882898f,-0.275874f,0.123126f}, +{0.002661f,-0.27584f,0.122512f},{0.00441458f,-0.276085f,0.122512f},{0.00613678f,-0.276448f,0.122512f}, +{-0.00770679f,-0.277265f,0.123602f},{-0.00603421f,-0.276863f,0.12373f},{-0.00438891f,-0.27624f,0.123126f}, +{0.00264467f,-0.275996f,0.123126f},{0.00609912f,-0.276601f,0.123126f},{0.00438748f,-0.27624f,0.123126f}, +{0.00781658f,-0.276923f,0.122497f},{0.0077751f,-0.277052f,0.123062f},{-0.00761353f,-0.277556f,0.1241f}, +{-0.00434221f,-0.276507f,0.12373f},{0.00770709f,-0.277264f,0.1236f},{-0.00554685f,-0.278836f,0.125434f}, +{-0.00720812f,-0.278819f,0.125233f},{-0.004276f,-0.276885f,0.12429f},{0.00252634f,-0.277128f,0.124775f}, +{0.00594221f,-0.277236f,0.12429f},{0.00761404f,-0.277554f,0.124098f},{-0.00252821f,-0.277128f,0.124775f}, +{-0.00419255f,-0.277361f,0.124775f},{-0.000845536f,-0.277011f,0.124775f},{0.000843398f,-0.277011f,0.124775f}, +{0.00749724f,-0.277918f,0.124546f},{-0.00409595f,-0.277912f,0.125161f},{0.000823965f,-0.27757f,0.125161f}, +{0.00246814f,-0.277685f,0.125161f},{0.00736095f,-0.278343f,0.124927f},{-0.00704393f,-0.279331f,0.125456f}, +{-0.000804989f,-0.278175f,0.125434f},{0.000802953f,-0.278175f,0.125434f},{0.0024052f,-0.278286f,0.125434f}, +{0.00388354f,-0.279117f,0.12559f},{0.00399021f,-0.278508f,0.125434f},{-0.00234263f,-0.278902f,0.12559f}, +{-0.00078347f,-0.278793f,0.12559f},{0.000781489f,-0.278793f,0.12559f},{0.0023409f,-0.278901f,0.12559f}, +{0.0217002f,-0.287732f,0.122512f},{0.02058f,-0.286351f,0.123126f},{0.021567f,-0.287815f,0.123126f}, +{0.0207071f,-0.286258f,0.122512f},{0.020361f,-0.28651f,0.12373f},{0.0213375f,-0.287958f,0.12373f}, +{0.0200505f,-0.286735f,0.12429f},{0.0183308f,-0.283663f,0.123126f},{0.018444f,-0.283554f,0.122512f}, +{0.0171012f,-0.282438f,0.123065f},{0.0169516f,-0.282602f,0.123602f},{0.0172584f,-0.286839f,0.12559f}, +{0.0177324f,-0.286442f,0.125434f},{0.0162253f,-0.285687f,0.12559f},{0.0171931f,-0.282336f,0.122497f}, +{0.0196183f,-0.284863f,0.122512f},{0.0171072f,-0.284839f,0.125161f},{0.0175107f,-0.284451f,0.124775f}, +{0.0161894f,-0.283443f,0.124929f},{0.0201275f,-0.288714f,0.125161f},{0.0192063f,-0.287348f,0.125161f}, +{0.0187165f,-0.287703f,0.125434f},{0.0151138f,-0.284628f,0.125592f},{0.0178592f,-0.284116f,0.12429f}, +{0.0164907f,-0.283111f,0.124546f},{0.0232721f,-0.292788f,0.12429f},{0.0241699f,-0.294302f,0.12373f}, +{0.0236324f,-0.292657f,0.12373f},{0.0210122f,-0.288161f,0.12429f},{0.0222178f,-0.294866f,0.125434f}, +{0.0230652f,-0.296296f,0.125232f},{0.0227992f,-0.294698f,0.125161f},{0.0224512f,-0.289346f,0.123126f}, +{0.0225899f,-0.289272f,0.122512f},{0.0233369f,-0.294543f,0.124775f},{0.0228179f,-0.292954f,0.124775f}, +{0.0222922f,-0.293146f,0.125161f},{0.0229789f,-0.291043f,0.12373f},{0.0226285f,-0.291199f,0.12429f}, +{0.0218736f,-0.289653f,0.12429f},{0.0222123f,-0.289473f,0.12373f},{0.0219851f,-0.29653f,0.125592f}, +{0.0225398f,-0.29641f,0.125455f},{0.0216239f,-0.295038f,0.12559f},{0.0233694f,-0.290869f,0.122512f}, +{0.0240341f,-0.29251f,0.122512f},{0.0245807f,-0.294183f,0.122512f},{0.0250097f,-0.295875f,0.122497f}, +{0.0181357f,-0.28385f,0.12373f},{0.0194979f,-0.284964f,0.123126f},{0.023226f,-0.290933f,0.123126f}, +{0.0238866f,-0.292564f,0.123126f},{0.0244299f,-0.294227f,0.123126f},{0.024877f,-0.295904f,0.123062f}, +{0.0167465f,-0.282829f,0.1241f},{0.0192904f,-0.285137f,0.12373f},{0.0246594f,-0.295951f,0.1236f}, +{0.016671f,-0.285259f,0.125434f},{0.0158548f,-0.283812f,0.125233f},{0.0189963f,-0.285384f,0.12429f}, +{0.0221869f,-0.291396f,0.124775f},{0.0238014f,-0.294408f,0.12429f},{0.0243617f,-0.296015f,0.124098f}, +{0.0196592f,-0.287019f,0.124775f},{0.0186256f,-0.285694f,0.124775f},{0.0206021f,-0.288418f,0.124775f}, +{0.0214468f,-0.28988f,0.124775f},{0.0239879f,-0.296096f,0.124546f},{0.0181964f,-0.286053f,0.125161f}, +{0.0209526f,-0.290143f,0.125161f},{0.0216757f,-0.291624f,0.125161f},{0.0235519f,-0.296191f,0.124927f}, +{0.0154936f,-0.28421f,0.125456f},{0.0196142f,-0.289035f,0.125434f},{0.0204183f,-0.290427f,0.125434f}, +{0.0211229f,-0.291871f,0.125434f},{0.021143f,-0.293566f,0.12559f},{0.0217237f,-0.293354f,0.125434f}, +{0.0182162f,-0.288066f,0.12559f},{0.0190899f,-0.289362f,0.12559f},{0.0198725f,-0.290718f,0.12559f}, +{0.0205583f,-0.292122f,0.12559f},{0.00414391f,-0.307489f,0.100469f},{0.00139737f,-0.303708f,0.100469f}, +{0.00179665f,-0.303429f,0.100469f},{0.00285439f,-0.308179f,0.100469f},{0.00351607f,-0.307865f,0.100469f}, +{0.00216513f,-0.308425f,0.100469f},{0.000956049f,-0.303916f,0.100469f},{0.0047319f,-0.307053f,0.100469f}, +{0.00527427f,-0.306562f,0.100469f},{0.00145499f,-0.308603f,0.100469f},{0.000485772f,-0.304043f,0.100469f}, +{0.00214182f,-0.303085f,0.100469f},{0.00576579f,-0.30602f,0.100469f},{0.000730938f,-0.30871f,0.100469f}, +{5.39729e-017f,-0.304085f,0.100469f},{0.00620174f,-0.305432f,0.100469f},{0.00242194f,-0.302686f,0.100469f}, +{5.29897e-017f,-0.308746f,0.100469f},{-0.000731236f,-0.30871f,0.100469f},{-0.00145532f,-0.308602f,0.100469f}, +{-0.000485107f,-0.304043f,0.100469f},{-0.00216527f,-0.308424f,0.100469f},{-0.000955564f,-0.303917f,0.100469f}, +{0.00689072f,-0.304142f,0.100469f},{0.00657793f,-0.304804f,0.100469f},{-0.00351606f,-0.307865f,0.100469f}, +{-0.00285433f,-0.308178f,0.100469f},{0.00713697f,-0.303453f,0.100469f},{0.00262754f,-0.302244f,0.100469f}, +{0.00275363f,-0.301773f,0.100469f},{-0.00139499f,-0.303708f,0.100469f},{0.00742217f,-0.302019f,0.100469f}, +{0.00731456f,-0.302743f,0.100469f},{-0.00214373f,-0.303089f,0.100469f},{-0.00178917f,-0.303421f,0.100469f}, +{-0.00527358f,-0.306561f,0.100469f},{-0.00657692f,-0.304803f,0.100469f},{-0.00688983f,-0.304142f,0.100469f}, +{-0.00262887f,-0.302246f,0.100469f},{-0.00275512f,-0.301775f,0.100469f},{-0.00742136f,-0.302019f,0.100469f}, +{-0.0071365f,-0.303453f,0.100469f},{-0.00731416f,-0.302743f,0.100469f},{-0.00473148f,-0.307052f,0.100469f}, +{-0.00414378f,-0.307489f,0.100469f},{-0.00620074f,-0.305431f,0.100469f},{-0.00242212f,-0.302687f,0.100469f}, +{-0.0057649f,-0.306018f,0.100469f},{0.00060826f,-0.289127f,0.101401f},{0.00178435f,-0.288815f,0.101401f}, +{0.002331f,-0.288545f,0.101401f},{0.00216527f,-0.308424f,0.101401f},{0.00536018f,-0.312009f,0.101401f}, +{0.00742136f,-0.302019f,0.101401f},{0.0121618f,-0.301897f,0.101401f},{0.0071365f,-0.303453f,0.101401f}, +{0.0127432f,-0.30362f,0.101401f},{0.00688983f,-0.304142f,0.101401f},{0.00403701f,-0.286839f,0.101401f}, +{0.00430572f,-0.282725f,0.101401f},{0.014297f,-0.31439f,0.101401f},{-0.00279832f,-0.280033f,0.101401f}, +{0.0214014f,-0.301897f,0.101401f},{-0.00689197f,-0.280986f,0.101401f},{-0.00820481f,-0.28148f,0.101401f}, +{0.021279f,-0.302494f,0.101401f},{0.0210836f,-0.303071f,0.101401f},{0.0134836f,-0.304585f,0.101401f}, +{0.00657692f,-0.304803f,0.101401f},{0.0130817f,-0.304126f,0.101401f},{-0.00893219f,-0.312768f,0.101401f}, +{-0.00372602f,-0.315267f,0.101401f},{-0.00406291f,-0.315783f,0.101401f},{0.0208166f,-0.303619f,0.101401f}, +{0.0200754f,-0.304584f,0.101401f},{0.0204775f,-0.304126f,0.101401f},{0.0196172f,-0.304986f,0.101401f}, +{0.0139105f,-0.312566f,0.101401f},{0.0141391f,-0.312881f,0.101401f},{-0.00216513f,-0.308425f,0.101401f}, +{-0.00235358f,-0.314045f,0.101401f},{-0.00285439f,-0.308179f,0.101401f},{0.0191105f,-0.305324f,0.101401f}, +{0.0185639f,-0.305594f,0.101401f},{0.0167797f,-0.30595f,0.101401f},{0.0173884f,-0.30591f,0.101401f}, +{0.0179866f,-0.30579f,0.101401f},{-0.0141364f,-0.285168f,0.101401f},{-0.00948265f,-0.282059f,0.101401f}, +{-0.00121835f,-0.313576f,0.101401f},{-0.00145499f,-0.308603f,0.101401f},{-0.000730938f,-0.30871f,0.101401f}, +{0.0161715f,-0.30591f,0.101401f},{-0.00180244f,-0.31377f,0.101401f},{0.00620074f,-0.305431f,0.101401f}, +{-0.00286368f,-0.31439f,0.101401f},{0.0143784f,-0.313619f,0.101401f},{-0.0107514f,-0.289341f,0.101401f}, +{-0.0109097f,-0.289697f,0.101401f},{-0.00140229f,-0.279893f,0.101401f},{0.00329545f,-0.281213f,0.101401f}, +{0.00369728f,-0.281671f,0.101401f},{0.0057649f,-0.306018f,0.101401f},{0.00466102f,-0.284509f,0.101401f}, +{0.00462104f,-0.2839f,0.101401f},{0.00731416f,-0.302743f,0.101401f},{0.0124736f,-0.303073f,0.101401f}, +{0.0121612f,-0.291674f,0.101401f},{0.0109346f,-0.292565f,0.101401f},{0.0113045f,-0.292445f,0.101401f}, +{0.0123195f,-0.291319f,0.101401f},{0.0116418f,-0.292251f,0.101401f},{0.0119314f,-0.29199f,0.101401f}, +{0.0136206f,-0.312305f,0.101401f},{0.0136193f,-0.315322f,0.101401f},{0.013282f,-0.315516f,0.101401f}, +{0.013283f,-0.31211f,0.101401f},{0.0155736f,-0.305791f,0.101401f},{0.00473148f,-0.307052f,0.101401f}, +{0.00527358f,-0.306561f,0.101401f},{-0.0170097f,-0.288236f,0.101401f},{-0.00751912f,-0.321368f,0.101401f}, +{-0.00885348f,-0.320816f,0.101401f},{-0.00460913f,-0.318761f,0.101401f},{0.00285433f,-0.308178f,0.101401f}, +{0.00351606f,-0.307865f,0.101401f},{0.000731236f,-0.30871f,0.101401f},{0.00145532f,-0.308602f,0.101401f}, +{-0.0151604f,-0.286127f,0.101401f},{-0.0161195f,-0.287151f,0.101401f},{-0.0124736f,-0.299504f,0.101401f}, +{-0.0122844f,-0.300083f,0.101401f},{5.29897e-017f,-0.308746f,0.101401f},{-0.0043287f,-0.316339f,0.101401f}, +{-0.00916198f,-0.313083f,0.101401f},{-0.0107204f,-0.295928f,0.101401f},{-0.00869272f,-0.312031f,0.101401f}, +{-0.00332386f,-0.3148f,0.101401f},{-0.017827f,-0.289376f,0.101401f},{-0.00731456f,-0.302743f,0.101401f}, +{-0.00713697f,-0.303453f,0.101401f},{-0.00742217f,-0.302019f,0.101401f},{-0.0196172f,-0.297591f,0.101401f}, +{-0.0200754f,-0.297993f,0.101401f},{-0.0210285f,-0.297105f,0.101401f},{-0.0158194f,-0.315761f,0.101401f}, +{-0.0167576f,-0.314664f,0.101401f},{-0.0176198f,-0.313505f,0.101401f},{-0.00462997f,-0.317531f,0.101401f}, +{-0.0101477f,-0.320176f,0.101401f},{-0.0125926f,-0.318642f,0.101401f},{-0.013732f,-0.317755f,0.101401f}, +{-0.00466034f,-0.318147f,0.101401f},{-0.00426727f,-0.319943f,0.101401f},{-0.00615062f,-0.321828f,0.101401f}, +{-0.00447731f,-0.319363f,0.101401f},{-0.00165506f,-0.322422f,0.101401f},{-0.00190339f,-0.322647f,0.101401f}, +{-0.0022162f,-0.322169f,0.101401f},{-0.00362862f,-0.320993f,0.101401f},{-0.00475417f,-0.322196f,0.101401f}, +{-0.00398274f,-0.320489f,0.101401f},{-0.00321095f,-0.321446f,0.101401f},{-0.00273734f,-0.32184f,0.101401f}, +{-0.00333373f,-0.322455f,0.101401f},{-0.00106651f,-0.322603f,0.101401f},{-0.000459362f,-0.322708f,0.101401f}, +{-0.0101588f,-0.313659f,0.101401f},{-0.011396f,-0.31945f,0.101401f},{-0.0148092f,-0.316793f,0.101401f}, +{-0.0184021f,-0.312292f,0.101401f},{-0.0212465f,-0.304168f,0.101401f},{-0.0210045f,-0.305592f,0.101401f}, +{-0.0206672f,-0.306996f,0.101401f},{0.0122844f,-0.302494f,0.101401f},{-0.0047319f,-0.307053f,0.101401f}, +{-0.00893177f,-0.310904f,0.101401f},{-0.00916039f,-0.310589f,0.101401f},{-0.019101f,-0.311028f,0.101401f}, +{-0.00978889f,-0.313539f,0.101401f},{-0.0213921f,-0.302732f,0.101401f},{-0.0111395f,-0.290013f,0.101401f}, +{-0.0114291f,-0.290273f,0.101401f},{-0.00576579f,-0.30602f,0.101401f},{-0.00527427f,-0.306562f,0.101401f}, +{-0.00945026f,-0.310327f,0.101401f},{-0.00978794f,-0.310132f,0.101401f},{-0.0101578f,-0.310012f,0.101401f}, +{-0.00620174f,-0.305432f,0.101401f},{-0.00877329f,-0.31126f,0.101401f},{-0.00414391f,-0.307489f,0.101401f}, +{-0.00351607f,-0.307865f,0.101401f},{-0.0045188f,-0.316925f,0.101401f},{-0.0094516f,-0.313344f,0.101401f}, +{-0.000614697f,-0.313451f,0.101401f},{0.0139422f,-0.304987f,0.101401f},{0.00414378f,-0.307489f,0.101401f}, +{0.0144494f,-0.305326f,0.101401f},{0.0124009f,-0.290548f,0.101401f},{0.011933f,-0.289496f,0.101401f}, +{0.00430656f,-0.286292f,0.101401f},{0.00178272f,-0.280205f,0.101401f},{-0.00418236f,-0.280262f,0.101401f}, +{-0.0106702f,-0.28896f,0.101401f},{-0.00554911f,-0.280579f,0.101401f},{-0.0130817f,-0.298451f,0.101401f}, +{-0.0134836f,-0.297992f,0.101401f},{-0.013052f,-0.284278f,0.101401f},{-0.0185679f,-0.290568f,0.101401f}, +{-0.0203026f,-0.294396f,0.101401f},{-0.0185639f,-0.296983f,0.101401f},{-0.0207099f,-0.295739f,0.101401f}, +{-0.00689072f,-0.304142f,0.101401f},{-0.0119116f,-0.283461f,0.101401f},{-0.0117654f,-0.287061f,0.101401f}, +{-0.0121353f,-0.286941f,0.101401f},{-0.0192293f,-0.291805f,0.101401f},{-0.0149963f,-0.296982f,0.101401f}, +{-0.0121618f,-0.30068f,0.101401f},{-0.0109093f,-0.287833f,0.101401f},{-0.0111379f,-0.287518f,0.101401f}, +{-0.0106699f,-0.28857f,0.101401f},{-0.01072f,-0.28272f,0.101401f},{-0.0114278f,-0.287256f,0.101401f}, +{0.00120563f,-0.289004f,0.101401f},{0.0116431f,-0.289234f,0.101401f},{0.0113054f,-0.289039f,0.101401f}, +{0.0124007f,-0.290938f,0.101401f},{0.00462115f,-0.285117f,0.101401f},{0.00283787f,-0.288207f,0.101401f}, +{0.00329614f,-0.287805f,0.101401f},{0.00369829f,-0.287346f,0.101401f},{0.0123201f,-0.290166f,0.101401f}, +{0.0121616f,-0.28981f,0.101401f},{0.0109356f,-0.288919f,0.101401f},{0.0149963f,-0.305595f,0.101401f}, +{0.0129131f,-0.311989f,0.101401f},{0.0129121f,-0.315636f,0.101401f},{0.0139089f,-0.315061f,0.101401f}, +{0.0141387f,-0.314745f,0.101401f},{0.0143782f,-0.314009f,0.101401f},{0.0142976f,-0.313237f,0.101401f}, +{-0.0202361f,-0.308374f,0.101401f},{-0.0197133f,-0.30972f,0.101401f},{-0.00869244f,-0.311641f,0.101401f}, +{-0.00877392f,-0.312412f,0.101401f},{-0.00657793f,-0.304804f,0.101401f},{-0.0107508f,-0.288189f,0.101401f}, +{0.00450236f,-0.285715f,0.101401f},{0.00450189f,-0.283302f,0.101401f},{0.00403597f,-0.282178f,0.101401f}, +{0.00283697f,-0.280811f,0.101401f},{0.00233026f,-0.280472f,0.101401f},{0.0006084f,-0.279887f,0.101401f}, +{0.00120559f,-0.280009f,0.101401f},{-0.0210836f,-0.299506f,0.101401f},{-0.0213948f,-0.299886f,0.101401f}, +{-0.0212572f,-0.29849f,0.101401f},{-0.0198084f,-0.293083f,0.101401f},{-0.0167797f,-0.296628f,0.101401f}, +{-0.0173884f,-0.296667f,0.101401f},{-0.0161715f,-0.296667f,0.101401f},{-0.0127432f,-0.298958f,0.101401f}, +{-0.0155736f,-0.296786f,0.101401f},{-0.0139422f,-0.29759f,0.101401f},{-0.0144494f,-0.297252f,0.101401f}, +{-0.0121363f,-0.290588f,0.101401f},{-0.0117664f,-0.290468f,0.101401f},{-0.0179866f,-0.296787f,0.101401f}, +{-0.0191105f,-0.297253f,0.101401f},{-0.0204775f,-0.298452f,0.101401f},{-0.0208166f,-0.298958f,0.101401f}, +{-0.0214014f,-0.30068f,0.101401f},{-0.021279f,-0.300083f,0.101401f},{0.0220868f,-0.314303f,0.120045f}, +{0.0197356f,-0.31765f,0.120045f},{-0.0164263f,-0.281003f,0.120045f},{-0.0174654f,-0.281891f,0.120045f}, +{0.0227481f,-0.313109f,0.120045f},{-0.0130507f,-0.278683f,0.120045f},{-0.0142159f,-0.279397f,0.120045f}, +{0.0243386f,-0.30934f,0.120045f},{-0.00935393f,-0.27692f,0.120045f},{-0.0106164f,-0.277443f,0.120045f}, +{0.0253094f,-0.305366f,0.120045f},{-0.00542685f,-0.275757f,0.120045f},{-0.00408328f,-0.275508f,0.120045f}, +{-0.0067556f,-0.276076f,0.120045f},{-0.00806585f,-0.276464f,0.120045f},{-0.00136583f,-0.275231f,0.120045f}, +{-0.00272847f,-0.27533f,0.120045f},{0.025591f,-0.302653f,0.120045f},{0.0254905f,-0.304014f,0.120045f}, +{-0.0118498f,-0.278032f,0.120045f},{0.0247326f,-0.308033f,0.120045f},{0.0250564f,-0.306708f,0.120045f}, +{-0.0153421f,-0.280171f,0.120045f},{0.0233448f,-0.311881f,0.120045f},{0.0238755f,-0.310624f,0.120045f}, +{-0.0184567f,-0.282831f,0.120045f},{-0.0193973f,-0.283823f,0.120045f},{0.0213629f,-0.31546f,0.120045f}, +{-0.0202847f,-0.284862f,0.120045f},{-0.0211166f,-0.285946f,0.120045f},{-0.0218906f,-0.287072f,0.120045f}, +{0.0205784f,-0.316577f,0.120045f},{-0.0226048f,-0.288237f,0.120045f},{-0.0232569f,-0.289438f,0.120045f}, +{0.0188369f,-0.318677f,0.120045f},{-0.0238452f,-0.290672f,0.120045f},{0.0178847f,-0.319655f,0.120045f}, +{-0.0243681f,-0.291934f,0.120045f},{0.0168818f,-0.320581f,0.120045f},{-0.0248242f,-0.293222f,0.120045f}, +{0.0158311f,-0.321452f,0.120045f},{-0.0252123f,-0.294533f,0.120045f},{0.0147355f,-0.322266f,0.120045f}, +{-0.0255314f,-0.295862f,0.120045f},{0.0135981f,-0.323021f,0.120045f},{-0.0257804f,-0.297205f,0.120045f}, +{0.0124222f,-0.323714f,0.120045f},{-0.0259588f,-0.29856f,0.120045f},{0.011211f,-0.324343f,0.120045f}, +{-0.0260659f,-0.299922f,0.120045f},{0.00996802f,-0.324907f,0.120045f},{-0.0261017f,-0.301289f,0.120045f}, +{0.00869678f,-0.325404f,0.120045f},{-0.0255903f,-0.302653f,0.120045f},{-0.0260659f,-0.302655f,0.120045f}, +{0.00740092f,-0.325833f,0.120045f},{-0.0254908f,-0.304013f,0.120045f},{-0.0259586f,-0.304017f,0.120045f}, +{0.00608407f,-0.326192f,0.120045f},{-0.0253091f,-0.305366f,0.120045f},{-0.0257802f,-0.305372f,0.120045f}, +{0.00474994f,-0.32648f,0.120045f},{0.00340235f,-0.326697f,0.120045f},{0.000682229f,-0.326915f,0.120045f}, +{-0.0250563f,-0.306707f,0.120045f},{-0.0255311f,-0.306716f,0.120045f},{-0.00272834f,-0.327248f,0.120045f}, +{-0.00340291f,-0.326697f,0.120045f},{-0.00408304f,-0.327069f,0.120045f},{-0.0238754f,-0.310623f,0.120045f}, +{-0.0243383f,-0.30934f,0.120045f},{-0.0243677f,-0.310643f,0.120045f},{-0.00675524f,-0.326501f,0.120045f}, +{-0.00740123f,-0.325832f,0.120045f},{-0.00806539f,-0.326113f,0.120045f},{-0.0226042f,-0.31434f,0.120045f}, +{-0.0227481f,-0.313108f,0.120045f},{-0.0232562f,-0.313139f,0.120045f},{-0.0118493f,-0.324546f,0.120045f}, +{-0.010616f,-0.325134f,0.120045f},{-0.011211f,-0.324342f,0.120045f},{-0.0202843f,-0.317715f,0.120045f}, +{-0.0205783f,-0.316576f,0.120045f},{-0.0211162f,-0.316631f,0.120045f},{-0.0164256f,-0.321574f,0.120045f}, +{-0.0168818f,-0.320581f,0.120045f},{-0.0174647f,-0.320686f,0.120045f},{-0.0130502f,-0.323894f,0.120045f}, +{-0.0124221f,-0.323713f,0.120045f},{-0.0188368f,-0.318677f,0.120045f},{-0.0193967f,-0.318755f,0.120045f}, +{-0.018456f,-0.319746f,0.120045f},{-0.0178847f,-0.319655f,0.120045f},{-0.0153414f,-0.322406f,0.120045f}, +{-0.0142153f,-0.32318f,0.120045f},{-0.0147355f,-0.322266f,0.120045f},{-0.0135981f,-0.32302f,0.120045f}, +{-0.0197355f,-0.31765f,0.120045f},{-0.0158312f,-0.321452f,0.120045f},{-0.00869705f,-0.325404f,0.120045f}, +{-0.00935349f,-0.325657f,0.120045f},{-0.00996818f,-0.324907f,0.120045f},{-0.0220867f,-0.314302f,0.120045f}, +{-0.0218902f,-0.315505f,0.120045f},{-0.0213628f,-0.315459f,0.120045f},{-0.00475041f,-0.32648f,0.120045f}, +{-0.00542662f,-0.32682f,0.120045f},{-0.00608443f,-0.326192f,0.120045f},{-0.0233449f,-0.311881f,0.120045f}, +{-0.0238446f,-0.311906f,0.120045f},{-0.000682695f,-0.326915f,0.120045f},{-0.00136576f,-0.327345f,0.120045f}, +{-0.00204572f,-0.326842f,0.120045f},{-0.0252122f,-0.308045f,0.120045f},{-0.0247324f,-0.308033f,0.120045f}, +{-0.024824f,-0.309355f,0.120045f},{0.00204515f,-0.326842f,0.120045f},{-0.00544975f,-0.326815f,0.106062f}, +{-0.00410773f,-0.327065f,0.106062f},{-0.00275036f,-0.327245f,0.106062f},{-0.00935782f,-0.325655f,0.106062f}, +{-0.00677384f,-0.326496f,0.106062f},{-0.0141962f,-0.323192f,0.106062f},{-0.0130343f,-0.323903f,0.106062f}, +{-0.0118389f,-0.324551f,0.106062f},{-0.0106125f,-0.325135f,0.106062f},{-0.0174549f,-0.320695f,0.106062f}, +{-0.015322f,-0.32242f,0.106062f},{-0.0211314f,-0.316611f,0.106062f},{-0.0202988f,-0.317698f,0.106062f}, +{-0.0194069f,-0.318743f,0.106062f},{-0.0184567f,-0.319745f,0.106062f},{-0.0232623f,-0.313128f,0.106062f}, +{-0.0219036f,-0.315485f,0.106062f},{-0.0252074f,-0.308063f,0.106062f},{-0.0248204f,-0.309366f,0.106062f}, +{-0.0243664f,-0.310647f,0.106062f},{-0.0238467f,-0.311901f,0.106062f},{-0.0257765f,-0.305396f,0.106062f}, +{-0.0259565f,-0.304039f,0.106062f},{-0.0255265f,-0.306739f,0.106062f},{-0.0260653f,-0.299908f,0.106062f}, +{-0.0261017f,-0.301289f,0.106062f},{-0.0260652f,-0.302669f,0.106062f},{-0.0255265f,-0.295839f,0.106062f}, +{-0.0257766f,-0.297181f,0.106062f},{-0.0259565f,-0.298538f,0.106062f},{-0.0248205f,-0.293211f,0.106062f}, +{-0.0252075f,-0.294515f,0.106062f},{-0.0238468f,-0.290676f,0.106062f},{-0.0232624f,-0.28945f,0.106062f}, +{-0.0243666f,-0.291931f,0.106062f},{-0.0219036f,-0.287092f,0.106062f},{-0.0226143f,-0.288254f,0.106062f}, +{-0.0202989f,-0.284879f,0.106062f},{-0.0211315f,-0.285967f,0.106062f},{-0.0184567f,-0.282832f,0.106062f}, +{-0.0194069f,-0.283834f,0.106062f},{-0.0174549f,-0.281882f,0.106062f},{-0.0164092f,-0.28099f,0.106062f}, +{-0.0153222f,-0.280157f,0.106062f},{-0.0141964f,-0.279385f,0.106062f},{-0.0130346f,-0.278674f,0.106062f}, +{-0.0118391f,-0.278026f,0.106062f},{-0.0106128f,-0.277442f,0.106062f},{-0.00935809f,-0.276922f,0.106062f}, +{-0.00807765f,-0.276468f,0.106062f},{-0.00677408f,-0.276081f,0.106062f},{-0.00544996f,-0.275762f,0.106062f}, +{-0.0041079f,-0.275512f,0.106062f},{-0.00275048f,-0.275332f,0.106062f},{-0.00138032f,-0.275223f,0.106062f}, +{-0.0226142f,-0.314323f,0.106062f},{-0.0164091f,-0.321587f,0.106062f},{-0.0080774f,-0.326109f,0.106062f}, +{-0.00138025f,-0.327354f,0.106062f},{-0.0164242f,-0.315071f,0.106062f},{-0.0128032f,-0.318487f,0.106062f}, +{-0.00849194f,-0.320976f,0.106062f},{-0.00372282f,-0.322402f,0.106062f},{-0.00124674f,-0.322693f,0.106062f}, +{-0.00248901f,-0.322583f,0.106062f},{-0.00733302f,-0.321436f,0.106062f},{-0.00962222f,-0.320449f,0.106062f}, +{-0.01072f,-0.319857f,0.106062f},{-0.0117816f,-0.319202f,0.106062f},{-0.0155951f,-0.316002f,0.106062f}, +{-0.0147132f,-0.316884f,0.106062f},{-0.0137815f,-0.317713f,0.106062f},{-0.0185679f,-0.312009f,0.106062f}, +{-0.0179131f,-0.313071f,0.106062f},{-0.0171977f,-0.314092f,0.106062f},{-0.0191599f,-0.310912f,0.106062f}, +{-0.0196869f,-0.309781f,0.106062f},{-0.0201474f,-0.308622f,0.106062f},{-0.0205397f,-0.307438f,0.106062f}, +{-0.0208625f,-0.306233f,0.106062f},{-0.0211148f,-0.305012f,0.106062f},{-0.0212956f,-0.303778f,0.106062f}, +{-0.0214044f,-0.302535f,0.106062f},{-0.0214407f,-0.301289f,0.106062f},{-0.0214044f,-0.300042f,0.106062f}, +{-0.0212958f,-0.298799f,0.106062f},{-0.021115f,-0.297565f,0.106062f},{-0.0208629f,-0.296344f,0.106062f}, +{-0.0205401f,-0.295139f,0.106062f},{-0.0201478f,-0.293955f,0.106062f},{-0.0196872f,-0.292796f,0.106062f}, +{-0.0185682f,-0.290568f,0.106062f},{-0.00248899f,-0.279996f,0.106062f},{-0.00124708f,-0.279883f,0.106062f}, +{-0.0164246f,-0.287506f,0.106062f},{-0.00494506f,-0.280426f,0.106062f},{-0.00614966f,-0.280749f,0.106062f}, +{-0.0137818f,-0.284864f,0.106062f},{-0.0147135f,-0.285693f,0.106062f},{-0.0107205f,-0.28272f,0.106062f}, +{-0.0117819f,-0.283375f,0.106062f},{-0.0128035f,-0.28409f,0.106062f},{-0.00849255f,-0.281601f,0.106062f}, +{-0.00733349f,-0.281141f,0.106062f},{-0.00962282f,-0.282128f,0.106062f},{-0.00372197f,-0.280183f,0.106062f}, +{-0.0155954f,-0.286575f,0.106062f},{-0.0179135f,-0.289507f,0.106062f},{-0.0171982f,-0.288485f,0.106062f}, +{-0.0191601f,-0.291666f,0.106062f},{-0.00494408f,-0.322149f,0.106062f},{-0.00614928f,-0.321829f,0.106062f}, +{-0.00496191f,-0.322147f,0.10513f},{-0.00374312f,-0.3224f,0.10513f},{-0.00250793f,-0.322582f,0.10513f}, +{-0.00849036f,-0.320976f,0.10513f},{-0.00616138f,-0.321825f,0.10513f},{-0.0127873f,-0.318499f,0.10513f}, +{-0.0117655f,-0.319213f,0.10513f},{-0.0107068f,-0.319865f,0.10513f},{-0.00961408f,-0.320453f,0.10513f}, +{-0.0155998f,-0.315997f,0.10513f},{-0.0137691f,-0.317724f,0.10513f},{-0.018576f,-0.311996f,0.10513f}, +{-0.0179242f,-0.313054f,0.10513f},{-0.0172102f,-0.314076f,0.10513f},{-0.0201457f,-0.308627f,0.10513f}, +{-0.0196879f,-0.309779f,0.10513f},{-0.0191643f,-0.310903f,0.10513f},{-0.0212935f,-0.303797f,0.10513f}, +{-0.0211114f,-0.305032f,0.10513f},{-0.0208586f,-0.306251f,0.10513f},{-0.0205363f,-0.30745f,0.10513f}, +{-0.0214407f,-0.301289f,0.10513f},{-0.0214037f,-0.300029f,0.10513f},{-0.0214037f,-0.302548f,0.10513f}, +{-0.0211115f,-0.297545f,0.10513f},{-0.0212936f,-0.298781f,0.10513f},{-0.0201457f,-0.29395f,0.10513f}, +{-0.0205363f,-0.295127f,0.10513f},{-0.0208587f,-0.296327f,0.10513f},{-0.0191643f,-0.291674f,0.10513f}, +{-0.019688f,-0.292798f,0.10513f},{-0.0172102f,-0.288501f,0.10513f},{-0.0179243f,-0.289523f,0.10513f}, +{-0.018576f,-0.290582f,0.10513f},{-0.0156004f,-0.28658f,0.10513f},{-0.0164352f,-0.287519f,0.10513f}, +{-0.0147088f,-0.285689f,0.10513f},{-0.0137693f,-0.284853f,0.10513f},{-0.0127873f,-0.284078f,0.10513f}, +{-0.0117656f,-0.283364f,0.10513f},{-0.010707f,-0.282713f,0.10513f},{-0.0096143f,-0.282124f,0.10513f}, +{-0.00849054f,-0.281601f,0.10513f},{-0.00733859f,-0.281143f,0.10513f},{-0.00616144f,-0.280752f,0.10513f}, +{-0.00374334f,-0.280177f,0.10513f},{-0.00496208f,-0.28043f,0.10513f},{-0.00250813f,-0.279995f,0.10513f}, +{-0.00125938f,-0.279885f,0.10513f},{-0.0164352f,-0.315058f,0.10513f},{-0.0147082f,-0.316889f,0.10513f}, +{-0.0073385f,-0.321434f,0.10513f},{-0.00125925f,-0.322692f,0.10513f},{-0.015889f,-0.321997f,0.10513f}, +{-0.0261017f,-0.301289f,0.10513f},{-0.0260458f,-0.302996f,0.10513f},{-0.0241144f,-0.311278f,0.10513f}, +{-0.0256f,-0.306381f,0.10513f},{-0.0252122f,-0.308045f,0.10513f},{-0.0234094f,-0.312833f,0.10513f}, +{-0.0217023f,-0.31579f,0.10513f},{-0.0207075f,-0.317179f,0.10513f},{-0.00675524f,-0.326501f,0.10513f}, +{-0.00509193f,-0.326889f,0.10513f},{-0.00170673f,-0.327326f,0.10513f},{-0.0130502f,-0.323894f,0.10513f}, +{-0.011544f,-0.324699f,0.10513f},{-0.00998811f,-0.325403f,0.10513f},{-0.00838954f,-0.326005f,0.10513f}, +{-0.0145006f,-0.322992f,0.10513f},{-0.018456f,-0.319746f,0.10513f},{-0.0172093f,-0.320913f,0.10513f}, +{-0.00340673f,-0.327168f,0.10513f},{-0.0196237f,-0.318499f,0.10513f},{-0.0226042f,-0.31434f,0.10513f}, +{-0.0247162f,-0.309679f,0.10513f},{-0.0258783f,-0.304696f,0.10513f},{-0.0260458f,-0.299582f,0.10513f}, +{-0.0258785f,-0.297882f,0.10513f},{-0.0247166f,-0.292898f,0.10513f},{-0.0252123f,-0.294533f,0.10513f}, +{-0.0256002f,-0.296196f,0.10513f},{-0.024115f,-0.2913f,0.10513f},{-0.02341f,-0.289744f,0.10513f}, +{-0.0226048f,-0.288237f,0.10513f},{-0.0207077f,-0.285398f,0.10513f},{-0.0217027f,-0.286787f,0.10513f}, +{-0.0196242f,-0.284078f,0.10513f},{-0.01721f,-0.281664f,0.10513f},{-0.0145012f,-0.279585f,0.10513f}, +{-0.0158895f,-0.28058f,0.10513f},{-0.0130507f,-0.278683f,0.10513f},{-0.0115442f,-0.277878f,0.10513f}, +{-0.00340717f,-0.27541f,0.10513f},{-0.00170718f,-0.275248f,0.10513f},{-0.00509216f,-0.275688f,0.10513f}, +{-0.0067556f,-0.276076f,0.10513f},{-0.00839014f,-0.276572f,0.10513f},{-0.0184567f,-0.282831f,0.10513f}, +{-0.00998851f,-0.277174f,0.10513f},{-0.0114195f,-0.281509f,0.10252f},{-0.0131871f,-0.282642f,0.10252f}, +{-0.0123517f,-0.279895f,0.104011f},{-0.0179085f,-0.287115f,0.10252f},{-0.0164595f,-0.285455f,0.10252f}, +{-0.0148769f,-0.28396f,0.10252f},{-0.0224459f,-0.297069f,0.10252f},{-0.0219419f,-0.29495f,0.10252f}, +{-0.0212291f,-0.292866f,0.10252f},{-0.022839f,-0.301289f,0.10252f},{-0.0227427f,-0.299191f,0.10252f}, +{-0.0123517f,-0.322682f,0.104011f},{-0.0114195f,-0.321068f,0.10252f},{-0.0101514f,-0.321748f,0.10252f}, +{-0.00882321f,-0.322354f,0.10252f},{-0.00744093f,-0.322881f,0.10252f},{-0.00601179f,-0.323322f,0.10252f}, +{-0.00454389f,-0.323671f,0.10252f},{-0.00304618f,-0.323923f,0.10252f},{-0.00152821f,-0.324076f,0.10252f}, +{-0.00650255f,-0.325121f,0.104011f},{-0.00491482f,-0.325498f,0.104011f},{-0.0109801f,-0.323418f,0.104011f}, +{-0.00329485f,-0.325771f,0.104011f},{-0.00165296f,-0.325937f,0.104011f},{-0.00804836f,-0.324644f,0.104011f}, +{-0.00954347f,-0.324074f,0.104011f},{-0.0191994f,-0.288919f,0.10252f},{-0.0203114f,-0.290845f,0.10252f}, +{-0.0160918f,-0.282545f,0.104011f},{-0.0247034f,-0.301289f,0.104011f},{-0.0245988f,-0.29902f,0.104011f}, +{-0.0242781f,-0.296725f,0.104011f},{-0.0237331f,-0.294434f,0.104011f},{-0.0229622f,-0.292179f,0.104011f}, +{-0.02197f,-0.289994f,0.104011f},{-0.0207674f,-0.28791f,0.104011f},{-0.0193711f,-0.285958f,0.104011f}, +{-0.0178041f,-0.284163f,0.104011f},{-0.0142649f,-0.28112f,0.104011f},{0.0255992f,-0.302654f,0.121909f}, +{0.0254901f,-0.304016f,0.121909f},{0.0137506f,-0.322924f,0.121909f},{0.0155417f,-0.321676f,0.121909f}, +{0.0118616f,-0.324015f,0.121909f},{0.00988475f,-0.324942f,0.121909f},{-0.00988506f,-0.324942f,0.121909f}, +{-0.0118618f,-0.324015f,0.121909f},{-0.015542f,-0.321676f,0.121909f},{-0.0137508f,-0.322924f,0.121909f}, +{-0.0253087f,-0.305369f,0.121909f},{-0.0254902f,-0.304016f,0.121909f},{-0.0255992f,-0.302654f,0.121909f}, +{0.0253087f,-0.305369f,0.121909f},{-0.0121592f,-0.300676f,0.104198f},{-0.0127415f,-0.298961f,0.104198f}, +{-0.0124735f,-0.299505f,0.104198f},{-0.0122784f,-0.300079f,0.104198f},{-0.0139458f,-0.297588f,0.104198f}, +{-0.0130793f,-0.298454f,0.104198f},{-0.0134838f,-0.297993f,0.104198f},{-0.0161672f,-0.296668f,0.104198f}, +{-0.0155702f,-0.296787f,0.104198f},{-0.014996f,-0.296982f,0.104198f},{-0.0173925f,-0.296668f,0.104198f}, +{-0.0179895f,-0.296787f,0.104198f},{-0.0167797f,-0.296628f,0.104198f},{-0.0191075f,-0.29725f,0.104198f}, +{-0.0185634f,-0.296982f,0.104198f},{-0.0200755f,-0.297993f,0.104198f},{-0.0196139f,-0.297588f,0.104198f}, +{-0.0204802f,-0.298455f,0.104198f},{-0.020818f,-0.298961f,0.104198f},{-0.0210859f,-0.299505f,0.104198f}, +{-0.0212811f,-0.300079f,0.104198f},{-0.0214003f,-0.300676f,0.104198f},{-0.0144523f,-0.29725f,0.104198f}, +{-0.00978795f,-0.310131f,0.110723f},{-0.00945021f,-0.310326f,0.110723f},{-0.0101588f,-0.310011f,0.110723f}, +{-0.00916026f,-0.310587f,0.110723f},{-0.00893114f,-0.310903f,0.110723f},{-0.00877327f,-0.31126f,0.110723f}, +{-0.00869249f,-0.311641f,0.110723f},{-0.00869285f,-0.312031f,0.110723f},{-0.00893415f,-0.312768f,0.110723f}, +{-0.00877489f,-0.312413f,0.110723f},{-0.00945258f,-0.313343f,0.110723f},{-0.00916327f,-0.313083f,0.110723f}, +{-0.0101599f,-0.313658f,0.110723f},{-0.00978972f,-0.313538f,0.110723f},{0.0132829f,-0.312109f,0.110723f}, +{0.0136207f,-0.312304f,0.110723f},{0.0129121f,-0.311988f,0.110723f},{0.0139106f,-0.312565f,0.110723f}, +{0.0141397f,-0.312881f,0.110723f},{0.0142976f,-0.313237f,0.110723f},{0.0143784f,-0.313619f,0.110723f}, +{0.014378f,-0.314009f,0.110723f},{0.0141367f,-0.314746f,0.110723f},{0.014296f,-0.31439f,0.110723f}, +{0.0136183f,-0.315321f,0.110723f},{0.0139076f,-0.31506f,0.110723f},{0.012911f,-0.315636f,0.110723f}, +{0.0132812f,-0.315515f,0.110723f},{0.0113054f,-0.289038f,0.110723f},{0.0116432f,-0.289233f,0.110723f}, +{0.0109345f,-0.288917f,0.110723f},{0.0119331f,-0.289494f,0.110723f},{0.0121622f,-0.28981f,0.110723f}, +{0.0123201f,-0.290167f,0.110723f},{0.0124009f,-0.290548f,0.110723f},{0.0124005f,-0.290938f,0.110723f}, +{0.0121592f,-0.291675f,0.110723f},{0.0123185f,-0.291319f,0.110723f},{0.0116408f,-0.29225f,0.110723f}, +{0.0119301f,-0.291989f,0.110723f},{0.0109335f,-0.292565f,0.110723f},{0.0113037f,-0.292444f,0.110723f}, +{-0.0117655f,-0.28706f,0.110723f},{-0.0114277f,-0.287255f,0.110723f},{-0.0121363f,-0.28694f,0.110723f}, +{-0.0111378f,-0.287516f,0.110723f},{-0.0109086f,-0.287832f,0.110723f},{-0.0107508f,-0.288189f,0.110723f}, +{-0.01067f,-0.28857f,0.110723f},{-0.0106704f,-0.28896f,0.110723f},{-0.0109117f,-0.289697f,0.110723f}, +{-0.0107524f,-0.289342f,0.110723f},{-0.0114301f,-0.290272f,0.110723f},{-0.0111408f,-0.290012f,0.110723f}, +{-0.0121374f,-0.290587f,0.110723f},{-0.0117672f,-0.290467f,0.110723f},{-0.000612842f,-0.313448f,0.104198f}, +{-0.00232777f,-0.31403f,0.104198f},{-0.00120978f,-0.313567f,0.104198f},{-0.00178369f,-0.313762f,0.104198f}, +{-0.00370055f,-0.315234f,0.104198f},{-0.00403832f,-0.315741f,0.104198f},{-0.00329584f,-0.314772f,0.104198f}, +{-0.00462066f,-0.317456f,0.104198f},{-0.00430621f,-0.316285f,0.104198f},{-0.00450141f,-0.316859f,0.104198f}, +{-0.00450127f,-0.319278f,0.104198f},{-0.00466102f,-0.318068f,0.104198f},{-0.00462052f,-0.318681f,0.104198f}, +{-0.00403818f,-0.320396f,0.104198f},{-0.00370041f,-0.320902f,0.104198f},{-0.00430621f,-0.319852f,0.104198f}, +{-0.00329584f,-0.321364f,0.104198f},{-0.00283386f,-0.321769f,0.104198f},{-0.00232743f,-0.322107f,0.104198f}, +{-0.00178369f,-0.322374f,0.104198f},{-0.00120944f,-0.32257f,0.104198f},{-0.000612502f,-0.322689f,0.104198f}, +{-0.0028342f,-0.314368f,0.104198f},{0.0121592f,-0.301901f,0.104198f},{0.0127415f,-0.303616f,0.104198f}, +{0.0124735f,-0.303072f,0.104198f},{0.0122784f,-0.302498f,0.104198f},{0.0139458f,-0.304989f,0.104198f}, +{0.0130793f,-0.304123f,0.104198f},{0.0134838f,-0.304584f,0.104198f},{0.0161672f,-0.305909f,0.104198f}, +{0.0155702f,-0.30579f,0.104198f},{0.014996f,-0.305595f,0.104198f},{0.0179895f,-0.30579f,0.104198f}, +{0.0173925f,-0.305909f,0.104198f},{0.0167797f,-0.30595f,0.104198f},{0.0191075f,-0.305327f,0.104198f}, +{0.0185634f,-0.305595f,0.104198f},{0.0200755f,-0.304584f,0.104198f},{0.0196139f,-0.304989f,0.104198f}, +{0.0204802f,-0.304122f,0.104198f},{0.020818f,-0.303616f,0.104198f},{0.0210859f,-0.303072f,0.104198f}, +{0.0212811f,-0.302498f,0.104198f},{0.0214003f,-0.301901f,0.104198f},{0.0144523f,-0.305327f,0.104198f}, +{0.000612842f,-0.289129f,0.104198f},{0.00232777f,-0.288547f,0.104198f},{0.00178369f,-0.288815f,0.104198f}, +{0.00120978f,-0.28901f,0.104198f},{0.00370055f,-0.287343f,0.104198f},{0.0028342f,-0.288209f,0.104198f}, +{0.00329584f,-0.287805f,0.104198f},{0.00462066f,-0.285121f,0.104198f},{0.00450141f,-0.285718f,0.104198f}, +{0.00430621f,-0.286293f,0.104198f},{0.00462052f,-0.283896f,0.104198f},{0.00450127f,-0.283299f,0.104198f}, +{0.00466102f,-0.284509f,0.104198f},{0.00403818f,-0.282181f,0.104198f},{0.00430621f,-0.282725f,0.104198f}, +{0.00329584f,-0.281213f,0.104198f},{0.00370041f,-0.281675f,0.104198f},{0.00283386f,-0.280808f,0.104198f}, +{0.00232743f,-0.280471f,0.104198f},{0.00178369f,-0.280203f,0.104198f},{0.00120944f,-0.280007f,0.104198f}, +{0.000612502f,-0.279888f,0.104198f},{0.00403832f,-0.286836f,0.104198f},{0.0114195f,-0.321068f,0.104198f}, +{0.00948155f,-0.322066f,0.104198f},{0.0032562f,-0.323894f,0.104198f},{0.00746583f,-0.322873f,0.104198f}, +{-0.00325654f,-0.323894f,0.104198f},{0.00109039f,-0.324102f,0.104198f},{-0.00109151f,-0.324101f,0.104198f}, +{-0.00746603f,-0.322873f,0.104198f},{-0.00538621f,-0.323483f,0.104198f},{-0.00948213f,-0.322066f,0.104198f}, +{-0.0114195f,-0.321068f,0.104198f},{0.00538567f,-0.323483f,0.104198f},{0.0123517f,-0.322682f,0.104198f}, +{-0.0123517f,-0.322682f,0.104198f},{-0.0102556f,-0.323763f,0.104198f},{-0.00352201f,-0.32574f,0.104198f}, +{-0.00807529f,-0.324635f,0.104198f},{0.00352238f,-0.32574f,0.104198f},{-0.00117941f,-0.325964f,0.104198f}, +{0.00118061f,-0.325964f,0.104198f},{0.0080755f,-0.324635f,0.104198f},{0.0102562f,-0.323762f,0.104198f}, +{0.0058259f,-0.325295f,0.104198f},{-0.00582532f,-0.325295f,0.104198f},{0.0132534f,-0.282688f,0.104198f}, +{0.0114195f,-0.281509f,0.104198f},{0.017949f,-0.287166f,0.104198f},{0.0165285f,-0.285527f,0.104198f}, +{0.0149596f,-0.284031f,0.104198f},{0.0203023f,-0.290827f,0.104198f},{0.0212053f,-0.292806f,0.104198f}, +{0.0192114f,-0.288938f,0.104198f},{0.0224255f,-0.296962f,0.104198f},{0.0219143f,-0.294856f,0.104198f}, +{0.0227351f,-0.299111f,0.104198f},{0.022839f,-0.301289f,0.104198f},{0.0123517f,-0.279895f,0.104198f}, +{0.0247034f,-0.301289f,0.104198f},{0.0245908f,-0.298933f,0.104198f},{0.0229363f,-0.292113f,0.104198f}, +{0.0237031f,-0.29433f,0.104198f},{0.0242561f,-0.296609f,0.104198f},{0.020779f,-0.287929f,0.104198f}, +{0.019414f,-0.286013f,0.104198f},{0.0219591f,-0.289972f,0.104198f},{0.0178774f,-0.28424f,0.104198f}, +{0.0161807f,-0.282622f,0.104198f},{0.0143348f,-0.28117f,0.104198f},{-0.0227349f,-0.299111f,0.104198f}, +{-0.022839f,-0.301289f,0.104198f},{-0.0212052f,-0.292806f,0.104198f},{-0.0219142f,-0.294855f,0.104198f}, +{-0.0224254f,-0.296962f,0.104198f},{-0.0192108f,-0.288937f,0.104198f},{-0.0179488f,-0.287165f,0.104198f}, +{-0.0203018f,-0.290826f,0.104198f},{-0.0149595f,-0.284031f,0.104198f},{-0.0165281f,-0.285527f,0.104198f}, +{-0.0132529f,-0.282688f,0.104198f},{-0.0114195f,-0.281509f,0.104198f},{-0.0247034f,-0.301289f,0.104198f}, +{-0.0123517f,-0.279895f,0.104198f},{-0.0143353f,-0.28117f,0.104198f},{-0.0194142f,-0.286013f,0.104198f}, +{-0.0178778f,-0.28424f,0.104198f},{-0.0161808f,-0.282622f,0.104198f},{-0.0219596f,-0.289973f,0.104198f}, +{-0.0229364f,-0.292114f,0.104198f},{-0.0207797f,-0.28793f,0.104198f},{-0.0237033f,-0.294331f,0.104198f}, +{-0.0242561f,-0.296609f,0.104198f},{-0.024591f,-0.298934f,0.104198f},{-0.00275356f,-0.301777f,0.0986044f}, +{-0.00214219f,-0.303086f,0.0986044f},{-0.00242266f,-0.302686f,0.0986044f},{-0.00262748f,-0.302246f,0.0986044f}, +{-0.000956449f,-0.303917f,0.0986044f},{-0.00048723f,-0.304042f,0.0986044f},{-0.00179504f,-0.303433f,0.0986044f}, +{-0.00139564f,-0.303712f,0.0986044f},{0.000957717f,-0.303916f,0.0986044f},{0.000488516f,-0.304042f,0.0986044f}, +{5.2844e-017f,-0.304085f,0.0986044f},{0.00179767f,-0.303431f,0.0986044f},{0.00139727f,-0.303711f,0.0986044f}, +{0.00214411f,-0.303084f,0.0986044f},{0.00242333f,-0.302684f,0.0986044f},{0.00262801f,-0.302245f,0.0986044f}, +{0.00275356f,-0.301777f,0.0986044f},{0.0174099f,-0.302514f,0.121909f},{0.0172871f,-0.301908f,0.121909f}, +{0.0172458f,-0.301289f,0.121909f},{0.0176121f,-0.3031f,0.121909f},{0.0182409f,-0.304167f,0.121909f}, +{0.0178912f,-0.303655f,0.121909f},{0.0186544f,-0.304627f,0.121909f},{0.0191262f,-0.305029f,0.121909f}, +{0.0196487f,-0.305366f,0.121909f},{0.0202093f,-0.305629f,0.121909f},{0.0207991f,-0.305816f,0.121909f}, +{0.021411f,-0.305923f,0.121909f},{0.0172872f,-0.300669f,0.121909f},{0.0174099f,-0.300063f,0.121909f}, +{0.0176122f,-0.299477f,0.121909f},{0.0178915f,-0.298922f,0.121909f},{0.0182411f,-0.29841f,0.121909f}, +{0.0186545f,-0.29795f,0.121909f},{0.0191266f,-0.297547f,0.121909f},{0.0196491f,-0.297211f,0.121909f}, +{0.0202094f,-0.296948f,0.121909f},{0.0207994f,-0.296761f,0.121909f},{0.021411f,-0.296654f,0.121909f}, +{0.00761603f,-0.294203f,0.121909f},{0.00821991f,-0.292665f,0.121909f},{0.00794276f,-0.293145f,0.121909f}, +{0.00774033f,-0.293661f,0.121909f},{0.00944153f,-0.291532f,0.121909f},{0.00856913f,-0.292227f,0.121909f}, +{0.00898119f,-0.291845f,0.121909f},{0.0115849f,-0.291045f,0.121909f},{0.011024f,-0.291045f,0.121909f}, +{0.01047f,-0.291128f,0.121909f},{0.0126654f,-0.291292f,0.121909f},{0.012136f,-0.291129f,0.121909f}, +{0.0136271f,-0.291848f,0.121909f},{0.0140372f,-0.292229f,0.121909f},{0.0131654f,-0.291533f,0.121909f}, +{0.0143853f,-0.292666f,0.121909f},{0.0146628f,-0.293147f,0.121909f},{0.0148654f,-0.293663f,0.121909f}, +{0.0149887f,-0.294203f,0.121909f},{0.00994023f,-0.291292f,0.121909f},{0.00749878f,-0.3009f,0.121909f}, +{0.0080757f,-0.299902f,0.121909f},{0.007619f,-0.30053f,0.121909f},{0.0091279f,-0.299434f,0.121909f}, +{0.00839049f,-0.299674f,0.121909f},{0.00874642f,-0.299515f,0.121909f},{0.00989914f,-0.299516f,0.121909f}, +{0.0102546f,-0.299674f,0.121909f},{0.00951793f,-0.299435f,0.121909f},{0.0105703f,-0.299904f,0.121909f}, +{0.0108309f,-0.300193f,0.121909f},{0.0110255f,-0.300531f,0.121909f},{0.0111456f,-0.300901f,0.121909f}, +{0.00781413f,-0.300192f,0.121909f},{0.00632322f,-0.282854f,0.121909f},{0.00629776f,-0.282236f,0.121909f}, +{0.00635281f,-0.281618f,0.121909f},{0.00643547f,-0.283464f,0.121909f},{0.00662778f,-0.284053f,0.121909f}, +{0.00689664f,-0.284612f,0.121909f},{0.00723717f,-0.28513f,0.121909f},{0.00862289f,-0.286353f,0.121909f}, +{0.00917948f,-0.286627f,0.121909f},{0.00764334f,-0.285598f,0.121909f},{0.00810797f,-0.286008f,0.121909f}, +{0.010376f,-0.286942f,0.121909f},{0.0109947f,-0.286977f,0.121909f},{0.0143217f,-0.285539f,0.121909f}, +{0.0138626f,-0.285956f,0.121909f},{0.0122191f,-0.286802f,0.121909f},{0.012803f,-0.286594f,0.121909f}, +{0.013354f,-0.28631f,0.121909f},{0.0147191f,-0.285063f,0.121909f},{0.0116126f,-0.286931f,0.121909f}, +{0.0097673f,-0.286824f,0.121909f},{0.00647672f,-0.281011f,0.121909f},{0.00669182f,-0.280429f,0.121909f}, +{-0.00232814f,-0.29115f,0.121909f},{-0.00335826f,-0.289858f,0.121909f},{-0.00308092f,-0.290338f,0.121909f}, +{-0.0027356f,-0.290771f,0.121909f},{-0.00372865f,-0.288234f,0.121909f},{-0.0035632f,-0.289337f,0.121909f}, +{-0.00368751f,-0.288789f,0.121909f},{-0.00307835f,-0.286134f,0.121909f},{-0.00335937f,-0.28662f,0.121909f}, +{-0.00356405f,-0.287141f,0.121909f},{-0.00232427f,-0.285322f,0.121909f},{-0.0027306f,-0.285699f,0.121909f}, +{-0.00136237f,-0.284767f,0.121909f},{-0.000827251f,-0.284602f,0.121909f},{-0.00186593f,-0.285009f,0.121909f}, +{-0.000274996f,-0.284519f,0.121909f},{0.000280844f,-0.284519f,0.121909f},{0.000829073f,-0.284602f,0.121909f}, +{0.00135821f,-0.284765f,0.121909f},{-0.00368715f,-0.287682f,0.121909f},{0.0034127f,-0.2946f,0.121909f}, +{0.00283723f,-0.293602f,0.121909f},{0.00315233f,-0.294311f,0.121909f},{0.00295815f,-0.292456f,0.121909f}, +{0.00279666f,-0.293215f,0.121909f},{0.00283762f,-0.292827f,0.121909f},{0.00341439f,-0.291829f,0.121909f}, +{0.00372927f,-0.291601f,0.121909f},{0.00315311f,-0.292119f,0.121909f},{0.00408585f,-0.291442f,0.121909f}, +{0.00446695f,-0.291361f,0.121909f},{0.0048565f,-0.291361f,0.121909f},{0.00523731f,-0.291442f,0.121909f}, +{0.00295751f,-0.293973f,0.121909f},{-0.0133515f,-0.286308f,0.121909f},{-0.013859f,-0.285951f,0.121909f}, +{-0.00764282f,-0.285598f,0.121909f},{-0.00810759f,-0.286008f,0.121909f},{-0.00723674f,-0.285129f,0.121909f}, +{-0.00862289f,-0.286353f,0.121909f},{-0.00689651f,-0.284611f,0.121909f},{-0.00662806f,-0.284053f,0.121909f}, +{-0.00643592f,-0.283463f,0.121909f},{-0.00917901f,-0.286627f,0.121909f},{-0.00976653f,-0.286824f,0.121909f}, +{-0.00632427f,-0.282854f,0.121909f},{-0.0103751f,-0.286942f,0.121909f},{-0.00629503f,-0.282234f,0.121909f}, +{-0.0064786f,-0.281011f,0.121909f},{-0.00634749f,-0.281617f,0.121909f},{-0.010994f,-0.286978f,0.121909f}, +{-0.00669182f,-0.280429f,0.121909f},{-0.0116123f,-0.286931f,0.121909f},{-0.0128028f,-0.286595f,0.121909f}, +{-0.0122189f,-0.286803f,0.121909f},{-0.0143221f,-0.285541f,0.121909f},{-0.0147191f,-0.285063f,0.121909f}, +{-0.00994417f,-0.298236f,0.121909f},{-0.0115782f,-0.298482f,0.121909f},{-0.0110237f,-0.298482f,0.121909f}, +{-0.0104759f,-0.298399f,0.121909f},{-0.0131702f,-0.29799f,0.121909f},{-0.0121323f,-0.298398f,0.121909f}, +{-0.0126687f,-0.298232f,0.121909f},{-0.0146632f,-0.296377f,0.121909f},{-0.0143833f,-0.296863f,0.121909f}, +{-0.014034f,-0.297301f,0.121909f},{-0.0149897f,-0.295318f,0.121909f},{-0.0148666f,-0.295858f,0.121909f}, +{-0.0149894f,-0.294208f,0.121909f},{-0.0148645f,-0.293662f,0.121909f},{-0.0150313f,-0.294765f,0.121909f}, +{-0.0146603f,-0.293142f,0.121909f},{-0.014382f,-0.292661f,0.121909f},{-0.0140364f,-0.292227f,0.121909f}, +{-0.0136305f,-0.291851f,0.121909f},{-0.0136274f,-0.297678f,0.121909f},{-0.00408601f,-0.294989f,0.121909f}, +{-0.0052381f,-0.294988f,0.121909f},{-0.00446686f,-0.29507f,0.121909f},{-0.00616977f,-0.294311f,0.121909f}, +{-0.00559379f,-0.29483f,0.121909f},{-0.00590924f,-0.2946f,0.121909f},{-0.00648482f,-0.293602f,0.121909f}, +{-0.00652543f,-0.293215f,0.121909f},{-0.0063645f,-0.293973f,0.121909f},{-0.00648441f,-0.292827f,0.121909f}, +{-0.00636386f,-0.292456f,0.121909f},{-0.00616897f,-0.292119f,0.121909f},{-0.00590844f,-0.29183f,0.121909f}, +{-0.00485671f,-0.295069f,0.121909f},{-0.0178906f,-0.303654f,0.121909f},{-0.0176123f,-0.3031f,0.121909f}, +{-0.0182401f,-0.304166f,0.121909f},{-0.0186543f,-0.304628f,0.121909f},{-0.019126f,-0.30503f,0.121909f}, +{-0.0174099f,-0.302514f,0.121909f},{-0.0196492f,-0.305361f,0.121909f},{-0.017287f,-0.301907f,0.121909f}, +{-0.0172458f,-0.301289f,0.121909f},{-0.0172871f,-0.30067f,0.121909f},{-0.0174101f,-0.300062f,0.121909f}, +{-0.0176127f,-0.299476f,0.121909f},{-0.0178912f,-0.298922f,0.121909f},{-0.0182407f,-0.298411f,0.121909f}, +{-0.018655f,-0.29795f,0.121909f},{-0.0191272f,-0.297548f,0.121909f},{-0.0196491f,-0.297213f,0.121909f}, +{-0.02021f,-0.29695f,0.121909f},{-0.0208003f,-0.29676f,0.121909f},{-0.021411f,-0.296654f,0.121909f}, +{-0.0207988f,-0.305818f,0.121909f},{-0.0202118f,-0.305622f,0.121909f},{-0.021411f,-0.305923f,0.121909f}, +{-0.00761603f,-0.308374f,0.121909f},{-0.00821991f,-0.309912f,0.121909f},{-0.00794276f,-0.309432f,0.121909f}, +{-0.00774033f,-0.308916f,0.121909f},{-0.00944153f,-0.311045f,0.121909f},{-0.00856913f,-0.31035f,0.121909f}, +{-0.00898119f,-0.310732f,0.121909f},{-0.0115849f,-0.311532f,0.121909f},{-0.011024f,-0.311532f,0.121909f}, +{-0.01047f,-0.311449f,0.121909f},{-0.0126654f,-0.311285f,0.121909f},{-0.012136f,-0.311448f,0.121909f}, +{-0.0136271f,-0.310729f,0.121909f},{-0.0140372f,-0.310348f,0.121909f},{-0.0131654f,-0.311044f,0.121909f}, +{-0.0143853f,-0.309911f,0.121909f},{-0.0146628f,-0.30943f,0.121909f},{-0.0148654f,-0.308914f,0.121909f}, +{-0.0149887f,-0.308374f,0.121909f},{-0.00994023f,-0.311285f,0.121909f},{-0.00749878f,-0.301677f,0.121909f}, +{-0.0080757f,-0.302675f,0.121909f},{-0.007619f,-0.302047f,0.121909f},{-0.0091279f,-0.303143f,0.121909f}, +{-0.00839049f,-0.302903f,0.121909f},{-0.00874642f,-0.303062f,0.121909f},{-0.00989914f,-0.303061f,0.121909f}, +{-0.0102546f,-0.302903f,0.121909f},{-0.00951793f,-0.303143f,0.121909f},{-0.0105703f,-0.302673f,0.121909f}, +{-0.0108309f,-0.302384f,0.121909f},{-0.0110255f,-0.302046f,0.121909f},{-0.0111456f,-0.301676f,0.121909f}, +{-0.00781413f,-0.302385f,0.121909f},{-0.00629776f,-0.320341f,0.121909f},{-0.00632322f,-0.319723f,0.121909f}, +{-0.0147191f,-0.317514f,0.121909f},{-0.00643547f,-0.319113f,0.121909f},{-0.00635281f,-0.320959f,0.121909f}, +{-0.00662778f,-0.318524f,0.121909f},{-0.00689664f,-0.317965f,0.121909f},{-0.00764334f,-0.316979f,0.121909f}, +{-0.00810797f,-0.316569f,0.121909f},{-0.00723717f,-0.317447f,0.121909f},{-0.010376f,-0.315635f,0.121909f}, +{-0.0109947f,-0.3156f,0.121909f},{-0.00862289f,-0.316224f,0.121909f},{-0.00917948f,-0.31595f,0.121909f}, +{-0.0143217f,-0.317038f,0.121909f},{-0.0138626f,-0.316622f,0.121909f},{-0.0122191f,-0.315775f,0.121909f}, +{-0.012803f,-0.315983f,0.121909f},{-0.013354f,-0.316267f,0.121909f},{-0.0116126f,-0.315647f,0.121909f}, +{-0.0097673f,-0.315753f,0.121909f},{-0.00647672f,-0.321566f,0.121909f},{-0.00669182f,-0.322148f,0.121909f}, +{0.00232814f,-0.311427f,0.121909f},{0.00335826f,-0.312719f,0.121909f},{0.00308092f,-0.312239f,0.121909f}, +{0.0027356f,-0.311806f,0.121909f},{0.00372865f,-0.314343f,0.121909f},{0.0035632f,-0.313241f,0.121909f}, +{0.00368751f,-0.313788f,0.121909f},{0.00307835f,-0.316443f,0.121909f},{0.00335937f,-0.315957f,0.121909f}, +{0.00356405f,-0.315436f,0.121909f},{0.00232427f,-0.317255f,0.121909f},{0.0027306f,-0.316878f,0.121909f}, +{0.00136237f,-0.31781f,0.121909f},{0.000827251f,-0.317975f,0.121909f},{0.00186593f,-0.317568f,0.121909f}, +{0.000274996f,-0.318058f,0.121909f},{-0.000280844f,-0.318058f,0.121909f},{-0.000829073f,-0.317975f,0.121909f}, +{-0.00135821f,-0.317812f,0.121909f},{0.00368715f,-0.314895f,0.121909f},{-0.0034126f,-0.307977f,0.121909f}, +{-0.00283728f,-0.308975f,0.121909f},{-0.0031524f,-0.308266f,0.121909f},{-0.00295812f,-0.310121f,0.121909f}, +{-0.00279668f,-0.309362f,0.121909f},{-0.0028374f,-0.30975f,0.121909f},{-0.0034143f,-0.310748f,0.121909f}, +{-0.00372908f,-0.310977f,0.121909f},{-0.00315337f,-0.310458f,0.121909f},{-0.00408596f,-0.311135f,0.121909f}, +{-0.00446705f,-0.311216f,0.121909f},{-0.00485646f,-0.311216f,0.121909f},{-0.00523689f,-0.311135f,0.121909f}, +{-0.00295753f,-0.308604f,0.121909f},{0.00764282f,-0.316979f,0.121909f},{0.00723674f,-0.317448f,0.121909f}, +{0.00810759f,-0.316569f,0.121909f},{0.00862289f,-0.316224f,0.121909f},{0.00689651f,-0.317966f,0.121909f}, +{0.00662806f,-0.318524f,0.121909f},{0.00643592f,-0.319114f,0.121909f},{0.00917901f,-0.31595f,0.121909f}, +{0.00632427f,-0.319723f,0.121909f},{0.00629503f,-0.320343f,0.121909f},{0.00976653f,-0.315753f,0.121909f}, +{0.00634749f,-0.32096f,0.121909f},{0.0103751f,-0.315635f,0.121909f},{0.010994f,-0.3156f,0.121909f}, +{0.0064786f,-0.321566f,0.121909f},{0.00669182f,-0.322148f,0.121909f},{0.0116123f,-0.315646f,0.121909f}, +{0.0128028f,-0.315982f,0.121909f},{0.0122189f,-0.315774f,0.121909f},{0.0133515f,-0.316269f,0.121909f}, +{0.013859f,-0.316626f,0.121909f},{0.0143221f,-0.317036f,0.121909f},{0.0147191f,-0.317514f,0.121909f}, +{0.00994417f,-0.304342f,0.121909f},{0.0115782f,-0.304095f,0.121909f},{0.0110237f,-0.304096f,0.121909f}, +{0.0104759f,-0.304178f,0.121909f},{0.0131702f,-0.304587f,0.121909f},{0.0121323f,-0.304179f,0.121909f}, +{0.0126687f,-0.304345f,0.121909f},{0.0146632f,-0.3062f,0.121909f},{0.0143833f,-0.305714f,0.121909f}, +{0.014034f,-0.305276f,0.121909f},{0.0149897f,-0.307259f,0.121909f},{0.0148666f,-0.306719f,0.121909f}, +{0.0149894f,-0.30837f,0.121909f},{0.0148645f,-0.308915f,0.121909f},{0.0150313f,-0.307812f,0.121909f}, +{0.0146603f,-0.309435f,0.121909f},{0.014382f,-0.309916f,0.121909f},{0.0140364f,-0.31035f,0.121909f}, +{0.0136305f,-0.310726f,0.121909f},{0.0136274f,-0.304899f,0.121909f},{0.00408601f,-0.307588f,0.121909f}, +{0.0052381f,-0.307589f,0.121909f},{0.00446686f,-0.307507f,0.121909f},{0.00616977f,-0.308266f,0.121909f}, +{0.00559379f,-0.307747f,0.121909f},{0.00590924f,-0.307977f,0.121909f},{0.00648482f,-0.308975f,0.121909f}, +{0.00652543f,-0.309362f,0.121909f},{0.0063645f,-0.308604f,0.121909f},{0.00648441f,-0.30975f,0.121909f}, +{0.00636386f,-0.310121f,0.121909f},{0.00616897f,-0.310458f,0.121909f},{0.00590844f,-0.310747f,0.121909f}, +{0.00485671f,-0.307508f,0.121909f},{0.00462052f,-0.301901f,0.127503f},{0.00403818f,-0.303616f,0.127503f}, +{0.00450127f,-0.302498f,0.127503f},{0.00283386f,-0.304989f,0.127503f},{0.00232743f,-0.305327f,0.127503f}, +{0.00329584f,-0.304584f,0.127503f},{0.000612502f,-0.305909f,0.127503f},{0.00178369f,-0.305595f,0.127503f}, +{0.00120944f,-0.30579f,0.127503f},{-0.00120978f,-0.30579f,0.127503f},{5.46456e-017f,-0.30595f,0.127503f}, +{-0.000612842f,-0.305909f,0.127503f},{-0.00232777f,-0.305327f,0.127503f},{-0.0028342f,-0.304989f,0.127503f}, +{-0.00178369f,-0.305595f,0.127503f},{-0.00329584f,-0.304584f,0.127503f},{-0.00370055f,-0.304122f,0.127503f}, +{-0.00403832f,-0.303616f,0.127503f},{-0.00430621f,-0.303072f,0.127503f},{-0.00450141f,-0.302498f,0.127503f}, +{-0.00462066f,-0.301901f,0.127503f},{0.00370041f,-0.304123f,0.127503f},{0.00430621f,-0.303072f,0.127503f}, +{-0.00139737f,-0.303708f,0.127503f},{-0.00275363f,-0.301773f,0.127503f},{-0.00242194f,-0.302686f,0.127503f}, +{-0.00214182f,-0.303085f,0.127503f},{-0.00262754f,-0.302244f,0.127503f},{-0.00179665f,-0.303429f,0.127503f}, +{-0.000956049f,-0.303916f,0.127503f},{-0.000485772f,-0.304043f,0.127503f},{5.20065e-017f,-0.304085f,0.127503f}, +{0.000955564f,-0.303917f,0.127503f},{0.000485107f,-0.304043f,0.127503f},{0.00139499f,-0.303708f,0.127503f}, +{0.00275512f,-0.301775f,0.127503f},{0.00178917f,-0.303421f,0.127503f},{0.00262887f,-0.302246f,0.127503f}, +{0.00242212f,-0.302687f,0.127503f},{0.00214373f,-0.303089f,0.127503f},{-0.00275512f,-0.301775f,0.13496f}, +{-0.00262887f,-0.302246f,0.13496f},{-0.00242212f,-0.302687f,0.13496f},{-0.00214373f,-0.303089f,0.13496f}, +{-0.00178917f,-0.303421f,0.13496f},{-0.00139499f,-0.303708f,0.13496f},{-0.000955564f,-0.303917f,0.13496f}, +{-0.000485107f,-0.304043f,0.13496f},{5.2317e-017f,-0.304085f,0.13496f},{0.000485772f,-0.304043f,0.13496f}, +{0.00179665f,-0.303429f,0.13496f},{0.00262754f,-0.302244f,0.13496f},{0.000956049f,-0.303916f,0.13496f}, +{0.00139737f,-0.303708f,0.13496f},{0.00214182f,-0.303085f,0.13496f},{0.00242194f,-0.302686f,0.13496f}, +{0.00275363f,-0.301773f,0.13496f},{-0.278876f,0.0027207f,0.141016f},{-0.279289f,0.00279661f,0.127503f}, +{-0.279666f,0.00276223f,0.140921f},{-0.278101f,0.00254178f,0.141133f},{-0.278432f,0.00266037f,0.127503f}, +{-0.277654f,0.00226719f,0.127503f},{-0.277449f,0.00210085f,0.141283f},{-0.276631f,0.000869207f,0.127503f}, +{-0.277032f,0.00165072f,0.127503f},{-0.276921f,0.00149803f,0.141448f},{-0.276599f,0.000793813f,0.141604f}, +{-0.276492f,-8.9946e-019f,0.127503f},{-0.276492f,-2.12873e-008f,0.141748f},{-0.280158f,0.00265777f,0.127503f}, +{-0.280438f,0.00255964f,0.140869f},{-0.280939f,0.00225612f,0.127503f},{-0.281556f,0.00163414f,0.127503f}, +{-0.28111f,0.00212367f,0.140862f},{-0.281946f,0.000869207f,0.127503f},{-0.281644f,0.00151779f,0.140892f}, +{-0.281979f,0.000793595f,0.140955f},{-0.282085f,0.0f,0.127503f},{-0.282085f,0.0f,0.141048f}, +{-0.321654f,0.00226719f,0.127503f},{-0.32241f,0.00266113f,0.141631f},{-0.321628f,0.00225617f,0.141475f}, +{-0.322432f,0.00266037f,0.127503f},{-0.321032f,0.00165072f,0.127503f},{-0.321061f,0.00161123f,0.141322f}, +{-0.320631f,0.000869207f,0.127503f},{-0.320624f,0.000861428f,0.141174f},{-0.323269f,0.00279699f,0.141768f}, +{-0.320492f,2.26626e-008f,0.141048f},{-0.320492f,9.24713e-018f,0.127503f},{-0.323289f,0.00279661f,0.127503f}, +{-0.324142f,0.00267244f,0.141876f},{-0.324922f,0.00227523f,0.141932f},{-0.324158f,0.00265777f,0.127503f}, +{-0.324939f,0.00225612f,0.127503f},{-0.325551f,0.00164828f,0.14193f},{-0.325556f,0.00163414f,0.127503f}, +{-0.325946f,0.000869207f,0.127503f},{-0.325955f,0.000867575f,0.141868f},{-0.326085f,8.90465e-018f,0.127503f}, +{-0.326085f,8.90465e-018f,0.141748f},{-0.301289f,-0.00279661f,0.136825f},{-0.300432f,-0.00266037f,0.127503f}, +{-0.302923f,-0.00226719f,0.136825f},{-0.302158f,-0.00265777f,0.127503f},{-0.302939f,-0.00225612f,0.127503f}, +{-0.302145f,-0.00266037f,0.136825f},{-0.303545f,-0.00165072f,0.136825f},{-0.303946f,-0.000869207f,0.127503f}, +{-0.304085f,3.42486e-019f,0.136825f},{-0.303946f,-0.000869207f,0.136825f},{-0.303556f,-0.00163414f,0.127503f}, +{-0.304085f,3.42486e-019f,0.127503f},{-0.300419f,-0.00265777f,0.136825f},{-0.299654f,-0.00226719f,0.127503f}, +{-0.299638f,-0.00225612f,0.136825f},{-0.299021f,-0.00163414f,0.136825f},{-0.299032f,-0.00165072f,0.127503f}, +{-0.298631f,-0.000869207f,0.136825f},{-0.298631f,-0.000869207f,0.127503f},{-0.298492f,0.0f,0.127503f}, +{-0.298492f,0.0f,0.136825f},{-0.298637f,0.00383933f,0.140336f},{-0.299639f,0.00435933f,0.127503f}, +{-0.299629f,0.00437081f,0.140342f},{-0.30073f,0.00462728f,0.127503f},{-0.298643f,0.00383758f,0.127503f}, +{-0.30072f,0.00463064f,0.140371f},{-0.297804f,0.00309444f,0.127503f},{-0.297795f,0.00308762f,0.140354f}, +{-0.297163f,0.00216892f,0.127503f},{-0.30185f,0.00463006f,0.140416f},{-0.297147f,0.00216891f,0.14039f}, +{-0.296764f,0.00111911f,0.127503f},{-0.296628f,5.60046e-014f,0.140488f},{-0.296628f,3.35892e-010f,0.127503f}, +{-0.296754f,0.00112174f,0.140439f},{-0.301853f,0.00462657f,0.127503f},{-0.302944f,0.00435716f,0.127503f}, +{-0.302946f,0.00437228f,0.140465f},{-0.303934f,0.00384698f,0.140509f},{-0.303939f,0.0038338f,0.127503f}, +{-0.304779f,0.00308862f,0.127503f},{-0.304777f,0.00309221f,0.140537f},{-0.305417f,0.00216381f,0.127503f}, +{-0.305426f,0.00217168f,0.140543f},{-0.305823f,0.00112329f,0.140525f},{-0.305814f,0.00111503f,0.127503f}, +{-0.30595f,0.0f,0.140488f},{-0.268793f,0.0031834f,0.141919f},{-0.268706f,-0.0034311f,0.143258f}, +{-0.273216f,0.00348389f,0.141453f},{-0.280744f,-0.013311f,0.142108f},{-0.281094f,-0.00749864f,0.141891f}, +{-0.27672f,-0.01447f,0.142985f},{-0.26798f,-0.0237151f,0.145107f},{-0.268531f,-0.0168317f,0.144795f}, +{-0.264f,-0.0250351f,0.14612f},{-0.2978f,-0.00309212f,0.140537f},{-0.293788f,-0.00980991f,0.140443f}, +{-0.298643f,-0.00384705f,0.140509f},{-0.281979f,-0.000788852f,0.141161f},{-0.281606f,-0.00148198f,0.141294f}, +{-0.285735f,-0.00113058f,0.140739f},{-0.302948f,-0.00437081f,0.140342f},{-0.301857f,-0.00463066f,0.140371f}, +{-0.302709f,-0.00734722f,0.140099f},{-0.308774f,0.00981015f,0.140456f},{-0.30394f,-0.00383936f,0.140336f}, +{-0.304783f,-0.0030876f,0.140354f},{-0.307737f,-0.000835134f,0.140403f},{-0.312842f,0.00565577f,0.140706f}, +{-0.308256f,0.00448849f,0.140582f},{-0.320599f,-0.000794809f,0.140955f},{-0.316415f,-0.00431412f,0.139973f}, +{-0.320936f,-0.00152033f,0.140892f},{-0.334055f,0.0168309f,0.144796f},{-0.338577f,0.0250351f,0.14612f}, +{-0.334598f,0.0237151f,0.145107f},{-0.313348f,0.0110109f,0.140705f},{-0.329718f,0.00922726f,0.143432f}, +{-0.330654f,0.0222833f,0.144104f},{-0.329893f,0.0156491f,0.143876f},{-0.329371f,-0.00348559f,0.141452f}, +{-0.329543f,0.00283697f,0.142622f},{-0.325978f,-0.000793378f,0.141605f},{-0.333794f,-0.00318417f,0.141918f}, +{-0.33388f,0.00342276f,0.143256f},{-0.334267f,-0.00969325f,0.140239f},{-0.338577f,-0.00290707f,0.142335f}, +{-0.338577f,0.00398877f,0.143878f},{-0.338577f,-0.00968775f,0.140407f},{-0.325081f,-0.00378729f,0.140965f}, +{-0.325129f,-0.00209478f,0.141284f},{-0.324474f,-0.00253473f,0.141134f},{-0.333967f,0.010107f,0.144218f}, +{-0.323703f,-0.00272118f,0.141016f},{-0.321359f,-0.00973119f,0.139327f},{-0.320799f,-0.00404127f,0.140452f}, +{-0.298312f,-0.00858894f,0.140271f},{-0.290225f,-0.000322559f,0.140392f},{-0.29535f,0.00611166f,0.139905f}, +{-0.290725f,0.0049946f,0.139783f},{-0.299868f,0.00734676f,0.140099f},{-0.299631f,-0.0043723f,0.140465f}, +{-0.281789f,0.00405908f,0.140464f},{-0.286166f,0.00435339f,0.139998f},{-0.297151f,-0.00217165f,0.140543f}, +{-0.294309f,-0.00450063f,0.140568f},{-0.280465f,-0.00253786f,0.141575f},{-0.279704f,-0.00276739f,0.141709f}, +{-0.276982f,-0.00835592f,0.14266f},{-0.278136f,-0.00255847f,0.141903f},{-0.277464f,-0.00212169f,0.141937f}, +{-0.275858f,-0.0208182f,0.143118f},{-0.264f,-0.00398877f,0.143878f},{-0.272694f,-0.0156505f,0.143875f}, +{-0.264f,0.00968775f,0.140407f},{-0.264f,0.00290707f,0.142335f},{-0.268311f,0.00969325f,0.140239f}, +{-0.281218f,0.00973122f,0.139327f},{-0.276917f,0.00972934f,0.139659f},{-0.277503f,0.00378494f,0.140965f}, +{-0.284865f,-0.0121774f,0.141276f},{-0.2853f,-0.00665136f,0.141165f},{-0.294831f,0.000816648f,0.140389f}, +{-0.278905f,-0.0027728f,0.141822f},{-0.268619f,-0.0101155f,0.144218f},{-0.264f,-0.0179944f,0.145774f}, +{-0.271923f,-0.0222833f,0.144104f},{-0.264f,-0.0109671f,0.145026f},{-0.272615f,0.0097173f,0.139971f}, +{-0.285519f,0.0097497f,0.139013f},{-0.304264f,0.00858896f,0.140271f},{-0.307222f,-0.00613049f,0.139921f}, +{-0.316849f,0.00115281f,0.140712f},{-0.311834f,-0.00500873f,0.139791f},{-0.304385f,-0.0120097f,0.13929f}, +{-0.308539f,-0.0108714f,0.138995f},{-0.300727f,-0.00463004f,0.140416f},{-0.300237f,-0.0131607f,0.139564f}, +{-0.296096f,-0.0143354f,0.139836f},{-0.289722f,-0.00566917f,0.140697f},{-0.289219f,-0.0110148f,0.140695f}, +{-0.289811f,0.0100181f,0.138847f},{-0.294038f,0.0108714f,0.138995f},{-0.298192f,0.0120097f,0.13929f}, +{-0.30234f,0.0131607f,0.139564f},{-0.306481f,0.0143354f,0.139836f},{-0.317286f,0.00666271f,0.14114f}, +{-0.321494f,0.00749967f,0.141879f},{-0.322913f,-0.00277232f,0.14092f},{-0.32566f,-0.00972932f,0.139659f}, +{-0.325656f,-0.00149718f,0.141448f},{-0.317723f,0.0121843f,0.141251f},{-0.32214f,-0.00255887f,0.140869f}, +{-0.321467f,-0.00212359f,0.140862f},{-0.312336f,0.000305779f,0.140401f},{-0.305823f,-0.00112176f,0.140439f}, +{-0.30543f,-0.00216894f,0.14039f},{-0.321845f,0.0133136f,0.142096f},{-0.325602f,0.00834704f,0.14266f}, +{-0.325864f,0.0144683f,0.142986f},{-0.273043f,-0.0028458f,0.142624f},{-0.272869f,-0.0092361f,0.143432f}, +{-0.276934f,-0.00151619f,0.141923f},{-0.276599f,-0.00079021f,0.141859f},{-0.279796f,-0.019351f,0.142144f}, +{-0.28376f,-0.0179262f,0.14121f},{-0.287806f,-0.0166178f,0.140509f},{-0.281123f,-0.00210151f,0.141433f}, +{-0.296754f,-0.00112326f,0.140525f},{-0.291943f,-0.0154659f,0.14012f},{-0.312766f,-0.0100181f,0.138847f}, +{-0.310634f,0.0154659f,0.14012f},{-0.317058f,-0.00974966f,0.139013f},{-0.318817f,0.0179262f,0.14121f}, +{-0.314771f,0.0166178f,0.140509f},{-0.322781f,0.0193511f,0.142144f},{-0.326719f,0.0208182f,0.143118f}, +{-0.329962f,-0.00971729f,0.139971f},{-0.338577f,0.0179944f,0.145774f},{-0.338577f,0.0109671f,0.145026f}, +{-0.264f,-0.0262081f,0.148238f},{-0.267733f,-0.0248064f,0.147199f},{-0.267738f,-0.0250058f,0.146766f}, +{-0.271434f,-0.0233183f,0.146165f},{-0.271439f,-0.0235291f,0.145739f},{-0.282552f,-0.0188229f,0.143165f}, +{-0.282558f,-0.0190695f,0.142766f},{-0.278832f,-0.0203019f,0.144139f},{-0.278837f,-0.0205368f,0.143731f}, +{-0.275137f,-0.022035f,0.14473f},{-0.275132f,-0.0218112f,0.145147f},{-0.29417f,-0.015307f,0.141119f}, +{-0.294165f,-0.0150041f,0.141517f},{-0.298107f,-0.0141429f,0.140834f},{-0.286329f,-0.0174212f,0.1423f}, +{-0.290221f,-0.0161629f,0.141811f},{-0.290226f,-0.0164424f,0.141416f},{-0.305963f,-0.0114006f,0.14071f}, +{-0.309927f,-0.0106866f,0.140011f},{-0.30597f,-0.0117799f,0.140283f},{-0.302024f,-0.0125814f,0.14098f}, +{-0.302035f,-0.0129503f,0.14056f},{-0.298097f,-0.0138012f,0.141246f},{-0.322165f,-0.00963024f,0.140526f}, +{-0.318066f,-0.00968708f,0.140168f},{-0.318055f,-0.0091952f,0.140649f},{-0.313966f,-0.0099197f,0.139934f}, +{-0.309914f,-0.0102596f,0.140442f},{-0.313954f,-0.00946264f,0.140382f},{-0.322157f,-0.00907526f,0.141031f}, +{-0.326264f,-0.0095489f,0.140876f},{-0.326258f,-0.00894343f,0.141413f},{-0.330364f,-0.00945311f,0.141203f}, +{-0.334468f,-0.00933687f,0.14148f},{-0.33036f,-0.00879579f,0.141773f},{-0.334465f,-0.0086246f,0.142088f}, +{-0.338577f,-0.00922107f,0.141665f},{-0.338577f,-0.00845004f,0.142301f},{-0.286338f,-0.0176856f,0.141921f}, +{-0.264f,-0.0263793f,0.147802f},{-0.264f,-0.0259023f,0.148593f},{-0.267734f,-0.0244885f,0.147557f}, +{-0.271437f,-0.0229936f,0.146522f},{-0.282562f,-0.0184899f,0.143511f},{-0.275137f,-0.0214828f,0.145501f}, +{-0.294177f,-0.0146321f,0.14188f},{-0.286341f,-0.0170843f,0.142644f},{-0.290234f,-0.0158117f,0.142162f}, +{-0.305972f,-0.010968f,0.141112f},{-0.302034f,-0.0121699f,0.141368f},{-0.298108f,-0.0134094f,0.141622f}, +{-0.31806f,-0.0086637f,0.141107f},{-0.309921f,-0.00980481f,0.140857f},{-0.31396f,-0.00897481f,0.140813f}, +{-0.32216f,-0.00849863f,0.141523f},{-0.32626f,-0.00832061f,0.14194f},{-0.330362f,-0.00812583f,0.142335f}, +{-0.334466f,-0.00790535f,0.142688f},{-0.338577f,-0.00767878f,0.142938f},{-0.278839f,-0.0199715f,0.144489f}, +{-0.264f,-0.0254953f,0.148828f},{-0.267945f,-0.0239945f,0.147747f},{-0.271858f,-0.0224149f,0.146665f}, +{-0.283628f,-0.0176882f,0.143502f},{-0.275768f,-0.0208215f,0.145592f},{-0.279683f,-0.0192329f,0.144529f}, +{-0.295955f,-0.0136618f,0.142081f},{-0.287664f,-0.0162503f,0.14274f},{-0.2918f,-0.0149457f,0.142346f}, +{-0.31263f,-0.00869072f,0.141186f},{-0.308401f,-0.00973903f,0.141305f},{-0.304248f,-0.0110356f,0.141581f}, +{-0.321265f,-0.00795144f,0.141896f},{-0.316941f,-0.0081943f,0.14144f},{-0.325589f,-0.00772122f,0.142378f}, +{-0.329914f,-0.00747253f,0.142842f},{-0.334241f,-0.00719397f,0.143263f},{-0.338577f,-0.00690556f,0.143577f}, +{-0.300098f,-0.0123399f,0.141831f},{-0.264f,-0.0250324f,0.148916f},{-0.267971f,-0.0235306f,0.147857f}, +{-0.271889f,-0.0219498f,0.146794f},{-0.283688f,-0.0172517f,0.143711f},{-0.275809f,-0.0203651f,0.14574f}, +{-0.296012f,-0.0132021f,0.142332f},{-0.287719f,-0.0158114f,0.142927f},{-0.291851f,-0.0144807f,0.142544f}, +{-0.308457f,-0.0092687f,0.141666f},{-0.304299f,-0.0105497f,0.141886f},{-0.300157f,-0.0118813f,0.142106f}, +{-0.321297f,-0.0073368f,0.142324f},{-0.316973f,-0.00759572f,0.141811f},{-0.312673f,-0.00819435f,0.141567f}, +{-0.325613f,-0.00708183f,0.142866f},{-0.32993f,-0.00678804f,0.143377f},{-0.334249f,-0.00646507f,0.143843f}, +{-0.338577f,-0.00613003f,0.144218f},{-0.279733f,-0.0187868f,0.144697f},{-0.326294f,-0.00696068f,0.143005f}, +{-0.330384f,-0.00667554f,0.143491f},{-0.334476f,-0.00636198f,0.143939f},{-0.318115f,-0.00748015f,0.141999f}, +{-0.314024f,-0.00786981f,0.141631f},{-0.322205f,-0.00722771f,0.1425f},{-0.302112f,-0.0111819f,0.142035f}, +{-0.309993f,-0.00875236f,0.14162f},{-0.290321f,-0.014914f,0.142686f},{-0.298189f,-0.0124511f,0.142242f}, +{-0.294261f,-0.0137038f,0.142453f},{-0.282633f,-0.0175985f,0.143972f},{-0.278896f,-0.0190677f,0.144928f}, +{-0.286425f,-0.0162018f,0.143129f},{-0.275179f,-0.0205663f,0.145919f},{-0.271464f,-0.022067f,0.146916f}, +{-0.267747f,-0.0235578f,0.14792f},{-0.306047f,-0.00994863f,0.141826f},{-0.338577f,-0.00603944f,0.144293f}, +{-0.272455f,-0.00744254f,0.145994f},{-0.268304f,-0.015865f,0.147531f},{-0.268397f,-0.0083666f,0.146789f}, +{-0.272638f,-0.000311244f,0.144934f},{-0.268488f,-0.000930332f,0.145573f},{-0.272193f,0.00667554f,0.143491f}, +{-0.264f,-0.00158091f,0.146182f},{-0.268101f,0.0063617f,0.143935f},{-0.264f,-0.00932143f,0.147589f}, +{-0.264f,0.00603944f,0.144293f},{-0.276379f,-0.00654234f,0.145204f},{-0.28029f,-0.00567271f,0.144415f}, +{-0.276103f,-0.0134133f,0.14569f},{-0.287869f,-0.00989537f,0.143217f},{-0.283807f,-0.0110779f,0.143908f}, +{-0.28841f,-0.00388505f,0.143059f},{-0.279922f,-0.0122295f,0.144789f},{-0.296503f,-0.0072715f,0.142814f}, +{-0.301301f,-1.23849e-006f,0.142893f},{-0.300722f,-0.00593214f,0.142703f},{-0.292161f,-0.00860427f,0.142918f}, +{-0.30924f,-0.00327255f,0.142485f},{-0.31361f,-0.00211647f,0.14253f},{-0.305494f,0.00133631f,0.142894f}, +{-0.304916f,-0.00459153f,0.142593f},{-0.334185f,0.00836678f,0.146789f},{-0.334094f,0.00093054f,0.145573f}, +{-0.329944f,0.000310969f,0.144934f},{-0.317858f,-0.00135717f,0.142953f},{-0.318318f,0.00485039f,0.143617f}, +{-0.338577f,0.00158091f,0.146182f},{-0.325928f,-0.000284983f,0.144284f},{-0.330127f,0.00744232f,0.145994f}, +{-0.338577f,0.0171357f,0.148501f},{-0.334277f,0.0158652f,0.147532f},{-0.321928f,-0.000835711f,0.143615f}, +{-0.326203f,0.00654153f,0.145205f},{-0.322295f,0.00568021f,0.144405f},{-0.309815f,0.00265603f,0.142905f}, +{-0.314151f,0.00387587f,0.143071f},{-0.292745f,-0.00267273f,0.142876f},{-0.297082f,-0.00133739f,0.142892f}, +{-0.284266f,-0.00483092f,0.143642f},{-0.272271f,-0.0146267f,0.1466f},{-0.264f,-0.0171357f,0.148501f}, +{-0.276283f,0.0069607f,0.143005f},{-0.276654f,0.000284018f,0.144284f},{-0.280372f,0.00722775f,0.1425f}, +{-0.280656f,0.000847135f,0.143625f},{-0.284462f,0.00746803f,0.141989f},{-0.284723f,0.00138663f,0.142978f}, +{-0.288553f,0.00787057f,0.141632f},{-0.288949f,0.00210321f,0.142519f},{-0.292582f,0.00875939f,0.141625f}, +{-0.293326f,0.00324421f,0.142456f},{-0.296532f,0.00994211f,0.141827f},{-0.334828f,0.023562f,0.147921f}, +{-0.338577f,0.0249766f,0.148916f},{-0.29766f,0.00458966f,0.142591f},{-0.300462f,0.0111906f,0.142034f}, +{-0.304385f,0.0124586f,0.142239f},{-0.30188f,0.00592971f,0.142704f},{-0.308317f,0.0136985f,0.142455f}, +{-0.306073f,0.00727121f,0.142816f},{-0.312257f,0.0149126f,0.142682f},{-0.310392f,0.00859914f,0.142945f}, +{-0.316149f,0.0162055f,0.143141f},{-0.314695f,0.0098903f,0.143228f},{-0.319944f,0.0175985f,0.143972f}, +{-0.31878f,0.0110874f,0.143884f},{-0.323681f,0.0190677f,0.144928f},{-0.322664f,0.012233f,0.144779f}, +{-0.327398f,0.0205663f,0.145919f},{-0.326479f,0.0134127f,0.14569f},{-0.331113f,0.0220671f,0.146916f}, +{-0.330311f,0.0146265f,0.1466f},{-0.338577f,0.00932143f,0.147589f},{-0.264f,0.00690312f,0.143579f}, +{-0.268335f,0.00719191f,0.143259f},{-0.272663f,0.00746979f,0.142843f},{-0.285643f,0.00814762f,0.141414f}, +{-0.276988f,0.0077197f,0.142379f},{-0.281312f,0.00793083f,0.141883f},{-0.298329f,0.0110361f,0.141582f}, +{-0.302474f,0.0123542f,0.141829f},{-0.289949f,0.00871456f,0.141206f},{-0.294168f,0.00976951f,0.141335f}, +{-0.314917f,0.0162476f,0.14273f},{-0.310786f,0.0149252f,0.142321f},{-0.306622f,0.0136614f,0.142081f}, +{-0.322891f,0.0192347f,0.144536f},{-0.318943f,0.0176916f,0.143534f},{-0.326807f,0.0208212f,0.145595f}, +{-0.330719f,0.022413f,0.146665f},{-0.33463f,0.0239981f,0.147749f},{-0.338577f,0.0254927f,0.148829f}, +{-0.264f,0.00767576f,0.142941f},{-0.268111f,0.00790232f,0.142685f},{-0.272215f,0.00812312f,0.142338f}, +{-0.284517f,0.00864847f,0.1411f},{-0.276317f,0.00831807f,0.141942f},{-0.280417f,0.00849626f,0.141525f}, +{-0.296607f,0.0109591f,0.141114f},{-0.288618f,0.00897354f,0.140816f},{-0.292654f,0.00981108f,0.140864f}, +{-0.308402f,0.0146249f,0.141884f},{-0.304467f,0.0134151f,0.141621f},{-0.30054f,0.0121769f,0.141369f}, +{-0.320015f,0.0184881f,0.143513f},{-0.312344f,0.0158082f,0.142159f},{-0.316233f,0.0170869f,0.142657f}, +{-0.323738f,0.0199696f,0.144491f},{-0.32744f,0.0214809f,0.145503f},{-0.33114f,0.0229915f,0.146524f}, +{-0.334841f,0.0244911f,0.147559f},{-0.338577f,0.0259001f,0.148595f},{-0.264f,0.00844643f,0.142304f}, +{-0.268112f,0.0086212f,0.142086f},{-0.272217f,0.00879266f,0.141776f},{-0.284522f,0.00917932f,0.140643f}, +{-0.27632f,0.00894054f,0.141415f},{-0.296616f,0.0113914f,0.140713f},{-0.288623f,0.00946126f,0.140385f}, +{-0.292661f,0.0102671f,0.14045f},{-0.308414f,0.0149971f,0.141521f},{-0.304478f,0.0138071f,0.141245f}, +{-0.30055f,0.0125887f,0.140981f},{-0.320025f,0.0188214f,0.143167f},{-0.312357f,0.0161597f,0.14181f}, +{-0.316245f,0.0174245f,0.142314f},{-0.323745f,0.0203004f,0.144141f},{-0.327445f,0.0218097f,0.145149f}, +{-0.331143f,0.0233168f,0.146167f},{-0.334842f,0.0248099f,0.147201f},{-0.338577f,0.0262067f,0.148241f}, +{-0.280421f,0.0090726f,0.141033f},{-0.264f,0.00921688f,0.141668f},{-0.268109f,0.00933302f,0.141483f}, +{-0.272213f,0.00944958f,0.141206f},{-0.284511f,0.00968445f,0.140171f},{-0.276314f,0.00954568f,0.140879f}, +{-0.296607f,0.0117779f,0.140285f},{-0.288611f,0.00991732f,0.139936f},{-0.29265f,0.0106844f,0.140013f}, +{-0.308407f,0.0153055f,0.141121f},{-0.304471f,0.0141412f,0.140836f},{-0.300542f,0.0129485f,0.140562f}, +{-0.320019f,0.0190685f,0.142768f},{-0.316239f,0.0176844f,0.141924f},{-0.312351f,0.016441f,0.141419f}, +{-0.32374f,0.0205358f,0.143733f},{-0.32744f,0.0220341f,0.144732f},{-0.331138f,0.0235282f,0.145742f}, +{-0.334839f,0.0250051f,0.146769f},{-0.338577f,0.0263788f,0.147805f},{-0.280413f,0.00962732f,0.140529f}, +{-0.268106f,0.00976429f,0.141114f},{-0.264f,0.00968775f,0.141279f},{-0.280402f,0.00995451f,0.140217f}, +{-0.276306f,0.00990606f,0.140549f},{-0.272207f,0.00984421f,0.140856f},{-0.292635f,0.0109184f,0.13974f}, +{-0.284498f,0.00997907f,0.139878f},{-0.304457f,0.0143137f,0.140577f},{-0.300528f,0.01314f,0.140298f}, +{-0.296593f,0.0119892f,0.140016f},{-0.316228f,0.0178005f,0.141673f},{-0.312338f,0.0165744f,0.141169f}, +{-0.308394f,0.015459f,0.140867f},{-0.323731f,0.0206269f,0.143469f},{-0.320009f,0.0191718f,0.142511f}, +{-0.327432f,0.0221132f,0.144461f},{-0.331132f,0.0235942f,0.145464f},{-0.334836f,0.0250554f,0.146485f}, +{-0.338577f,0.0264087f,0.147518f},{-0.288596f,0.0101788f,0.139657f},{-0.302478f,0.0137161f,0.140288f}, +{-0.298329f,0.0124851f,0.140002f},{-0.294164f,0.0113146f,0.139715f},{-0.28994f,0.0103804f,0.139538f}, +{-0.285632f,0.00997452f,0.139665f},{-0.281304f,0.00994023f,0.140012f},{-0.276982f,0.00991203f,0.140375f}, +{-0.272659f,0.009849f,0.140706f},{-0.268332f,0.00976769f,0.140986f},{-0.264f,0.00968775f,0.141169f}, +{-0.306628f,0.014938f,0.140581f},{-0.310795f,0.0161103f,0.140863f},{-0.314927f,0.0173564f,0.141293f}, +{-0.318949f,0.0187613f,0.142077f},{-0.322893f,0.0202782f,0.143048f},{-0.326806f,0.021842f,0.144073f}, +{-0.330714f,0.0234057f,0.145113f},{-0.334625f,0.024951f,0.146173f},{-0.338577f,0.0263814f,0.147244f}, +{-0.268582f,0.00976336f,0.140775f},{-0.264f,0.00968775f,0.140979f},{-0.282301f,0.00990978f,0.139723f}, +{-0.27773f,0.00989796f,0.140113f},{-0.273158f,0.00983969f,0.140469f},{-0.291415f,0.0106101f,0.139359f}, +{-0.295853f,0.0117247f,0.139609f},{-0.286881f,0.00998742f,0.139387f},{-0.304641f,0.0142908f,0.140193f}, +{-0.309044f,0.0155467f,0.140484f},{-0.300252f,0.0129908f,0.139902f},{-0.321941f,0.0197978f,0.142487f}, +{-0.317743f,0.0182285f,0.141521f},{-0.313441f,0.0168071f,0.140836f},{-0.326094f,0.0214356f,0.143538f}, +{-0.330239f,0.0230806f,0.14461f},{-0.334386f,0.0247084f,0.145702f},{-0.338577f,0.0262125f,0.146805f}, +{-0.268576f,0.00974593f,0.140582f},{-0.264f,0.00968775f,0.140788f},{-0.282277f,0.00985594f,0.139537f}, +{-0.277712f,0.00985469f,0.139924f},{-0.273146f,0.00980831f,0.140278f},{-0.295818f,0.0116247f,0.13941f}, +{-0.28685f,0.00992109f,0.139202f},{-0.304602f,0.0141594f,0.139977f},{-0.309003f,0.0154002f,0.140259f}, +{-0.300215f,0.0128748f,0.139695f},{-0.321909f,0.0195912f,0.142214f},{-0.317704f,0.0180446f,0.141269f}, +{-0.3134f,0.0166436f,0.140601f},{-0.326069f,0.021206f,0.143245f},{-0.330222f,0.0228275f,0.144296f}, +{-0.334378f,0.0244304f,0.145365f},{-0.338577f,0.0259067f,0.146446f},{-0.291381f,0.0105278f,0.139169f}, +{-0.268569f,0.00972275f,0.140397f},{-0.264f,0.00968775f,0.140597f},{-0.282252f,0.00978412f,0.139372f}, +{-0.277693f,0.0097971f,0.139752f},{-0.273133f,0.00976655f,0.140099f},{-0.291345f,0.0104201f,0.139009f}, +{-0.295781f,0.0114944f,0.139248f},{-0.286819f,0.00983335f,0.139043f},{-0.304563f,0.013988f,0.139811f}, +{-0.308962f,0.0152086f,0.14009f},{-0.300177f,0.0127235f,0.13953f},{-0.321876f,0.01932f,0.142022f}, +{-0.317666f,0.017804f,0.141087f},{-0.313358f,0.0164298f,0.140429f},{-0.326044f,0.0209031f,0.143041f}, +{-0.330205f,0.0224922f,0.144081f},{-0.334369f,0.0240607f,0.145139f},{-0.338577f,0.0254987f,0.146209f}, +{-0.268205f,-0.0240512f,0.145139f},{-0.264f,-0.0254987f,0.146209f},{-0.276531f,-0.0208987f,0.143038f}, +{-0.272372f,-0.0224907f,0.144081f},{-0.289223f,-0.0164319f,0.14044f},{-0.29362f,-0.015224f,0.140101f}, +{-0.284903f,-0.0177924f,0.141053f},{-0.302398f,-0.0127141f,0.139531f},{-0.306793f,-0.0114783f,0.139232f}, +{-0.298012f,-0.0139803f,0.139813f},{-0.320325f,-0.00981234f,0.139389f},{-0.315765f,-0.00988648f,0.139069f}, +{-0.311233f,-0.0103884f,0.138993f},{-0.324884f,-0.00979575f,0.139753f},{-0.329444f,-0.00976673f,0.1401f}, +{-0.334007f,-0.00972076f,0.140404f},{-0.338577f,-0.00968775f,0.140597f},{-0.280697f,-0.0193145f,0.142013f}, +{-0.268196f,-0.0244211f,0.145365f},{-0.264f,-0.0259067f,0.146446f},{-0.280665f,-0.0195856f,0.142206f}, +{-0.276506f,-0.0212016f,0.143242f},{-0.272354f,-0.0228261f,0.144296f},{-0.289182f,-0.016646f,0.140613f}, +{-0.29358f,-0.0154158f,0.14027f},{-0.284865f,-0.0180326f,0.141234f},{-0.306756f,-0.0116084f,0.139394f}, +{-0.30236f,-0.0128655f,0.139695f},{-0.297973f,-0.0141518f,0.13998f},{-0.320299f,-0.0098846f,0.139554f}, +{-0.315733f,-0.0099743f,0.139229f},{-0.311197f,-0.0104962f,0.139152f},{-0.324865f,-0.00985341f,0.139926f}, +{-0.329431f,-0.00980859f,0.140279f},{-0.334001f,-0.0097442f,0.140589f},{-0.338577f,-0.00968775f,0.140788f}, +{-0.268187f,-0.0246992f,0.145701f},{-0.264f,-0.0262125f,0.146805f},{-0.280632f,-0.019792f,0.142478f}, +{-0.276481f,-0.0214312f,0.143536f},{-0.272337f,-0.0230793f,0.144611f},{-0.293539f,-0.0155626f,0.140495f}, +{-0.284826f,-0.0182163f,0.141486f},{-0.30672f,-0.0117083f,0.139593f},{-0.302322f,-0.0129816f,0.139903f}, +{-0.297934f,-0.0142832f,0.140196f},{-0.320275f,-0.00993888f,0.139741f},{-0.315703f,-0.0100406f,0.139415f}, +{-0.311163f,-0.0105787f,0.139342f},{-0.324847f,-0.00989672f,0.140115f},{-0.329419f,-0.00984006f,0.140471f}, +{-0.333995f,-0.00976183f,0.140782f},{-0.338577f,-0.00968775f,0.140979f},{-0.289141f,-0.0168098f,0.140849f}, +{-0.264f,-0.0264087f,0.147518f},{-0.275145f,-0.0221132f,0.144461f},{-0.271445f,-0.0235942f,0.145464f}, +{-0.267741f,-0.0250554f,0.146485f},{-0.28635f,-0.0178005f,0.141673f},{-0.290239f,-0.0165745f,0.141169f}, +{-0.278846f,-0.0206269f,0.143469f},{-0.282568f,-0.0191717f,0.142511f},{-0.302049f,-0.01314f,0.140298f}, +{-0.29812f,-0.0143137f,0.140577f},{-0.294183f,-0.015459f,0.140867f},{-0.313981f,-0.0101788f,0.139657f}, +{-0.309942f,-0.0109184f,0.13974f},{-0.305984f,-0.0119892f,0.140016f},{-0.322175f,-0.00995447f,0.140217f}, +{-0.318079f,-0.00997902f,0.139878f},{-0.326272f,-0.00990604f,0.140549f},{-0.33037f,-0.0098442f,0.140856f}, +{-0.334471f,-0.00976429f,0.141114f},{-0.338577f,-0.00968775f,0.141279f},{-0.267949f,-0.0249437f,0.146173f}, +{-0.264f,-0.0263814f,0.147244f},{-0.279681f,-0.0202741f,0.143041f},{-0.27577f,-0.0218394f,0.144071f}, +{-0.271862f,-0.023405f,0.145114f},{-0.287654f,-0.0173571f,0.141303f},{-0.291791f,-0.0161317f,0.140885f}, +{-0.283621f,-0.0187523f,0.14205f},{-0.300094f,-0.0136985f,0.140292f},{-0.304247f,-0.0124827f,0.140001f}, +{-0.295948f,-0.0149357f,0.140582f},{-0.31264f,-0.010352f,0.139523f},{-0.308404f,-0.0112762f,0.139687f}, +{-0.321273f,-0.00995919f,0.140024f},{-0.31695f,-0.010024f,0.139691f},{-0.325595f,-0.00991129f,0.140376f}, +{-0.329918f,-0.00984923f,0.140707f},{-0.338577f,-0.00968775f,0.141169f},{-0.334244f,-0.00976681f,0.140992f}, +{-0.113384f,0.00379135f,0.144903f},{-0.113745f,0.00496458f,0.14459f},{-0.113263f,-0.00742307f,0.147291f}, +{-0.113263f,0.00257039f,0.145216f},{-0.114327f,0.00603944f,0.144293f},{-0.113263f,-0.00240499f,0.146356f}, +{-0.215517f,-0.0211541f,0.148776f},{-0.167133f,-0.0173396f,0.148518f},{-0.118851f,-0.013533f,0.148143f}, +{-0.117569f,-0.0132893f,0.148115f},{-0.116377f,-0.0127783f,0.148054f},{-0.115321f,-0.0120253f,0.147961f}, +{-0.114448f,-0.0110634f,0.147836f},{-0.113799f,-0.00994277f,0.14768f},{-0.113398f,-0.00870927f,0.147496f}, +{-0.113525f,-0.0123416f,0.145204f},{-0.112615f,-0.0109102f,0.145018f},{-0.114734f,-0.0135295f,0.145346f}, +{-0.15205f,-0.0164058f,0.14564f},{-0.189366f,-0.0192822f,0.145867f},{-0.226683f,-0.0221586f,0.146027f}, +{-0.112054f,-0.00932212f,0.144792f},{-0.111865f,-0.00765064f,0.144531f},{-0.119322f,0.00968775f,0.140407f}, +{-0.117633f,0.00949318f,0.140468f},{-0.112587f,0.00543154f,0.141666f},{-0.112048f,0.00387196f,0.142086f}, +{-0.116038f,0.00892517f,0.140645f},{-0.114625f,0.0080214f,0.14092f},{-0.113456f,0.00683431f,0.141269f}, +{-0.111865f,0.00223012f,0.142505f},{-0.119322f,0.00968775f,0.141279f},{-0.111865f,-0.00268915f,0.144987f}, +{-0.111865f,0.00223012f,0.14386f},{-0.111865f,-0.00765064f,0.145911f},{-0.116009f,-0.0143331f,0.145639f}, +{-0.117166f,-0.0147899f,0.146726f},{-0.117347f,-0.0148426f,0.146158f},{-0.118743f,-0.0150857f,0.146754f}, +{-0.115703f,-0.014171f,0.146666f},{-0.1144f,-0.0132538f,0.146574f},{-0.113328f,-0.0120868f,0.14645f}, +{-0.112525f,-0.0107201f,0.146296f},{-0.112032f,-0.00921907f,0.146114f},{-0.114787f,0.00815064f,0.142549f}, +{-0.113553f,0.00695586f,0.14283f},{-0.112058f,0.00391721f,0.143508f},{-0.112631f,0.00552233f,0.143157f}, +{-0.116176f,0.0089918f,0.141854f},{-0.117706f,0.00951028f,0.141426f},{-0.113829f,0.00632699f,0.144055f}, +{-0.113789f,0.0068323f,0.143638f},{-0.114001f,0.00732043f,0.143234f},{-0.114347f,0.00776225f,0.14287f}, +{-0.227685f,-0.0235779f,0.147426f},{-0.216179f,-0.0219204f,0.148625f},{-0.216137f,-0.0224876f,0.148085f}, +{-0.155057f,-0.0179164f,0.147043f},{-0.118746f,-0.0149745f,0.1473f},{-0.167425f,-0.0186837f,0.147841f}, +{-0.118809f,-0.0140869f,0.148094f},{-0.167468f,-0.0180963f,0.148384f},{-0.11877f,-0.0146193f,0.147797f}, +{-0.191371f,-0.0207472f,0.147267f},{-0.112274f,-0.00748972f,0.146886f},{-0.112435f,-0.00897658f,0.147115f}, +{-0.112116f,-0.00911758f,0.146645f},{-0.112887f,-0.0103998f,0.147311f},{-0.113376f,-0.0119652f,0.146998f}, +{-0.112592f,-0.0106014f,0.146835f},{-0.114648f,-0.0128307f,0.147613f},{-0.11572f,-0.0140507f,0.147224f}, +{-0.114435f,-0.0131339f,0.147128f},{-0.117179f,-0.0146743f,0.147286f},{-0.114951f,-0.0124497f,0.147903f}, +{-0.114003f,-0.0113986f,0.14777f},{-0.117405f,-0.0138348f,0.148064f},{-0.117272f,-0.0143101f,0.147775f}, +{-0.116101f,-0.013274f,0.148f},{-0.112748f,-0.00743905f,0.147194f},{-0.112873f,-0.00883688f,0.14741f}, +{-0.111963f,-0.00756687f,0.146419f},{-0.1133f,-0.0101719f,0.147604f},{-0.115877f,-0.0137111f,0.147711f}, +{-0.113636f,-0.0117086f,0.147479f},{-0.112073f,-0.00254212f,0.145696f},{-0.112539f,-0.0024474f,0.146152f}, +{-0.112048f,0.00239822f,0.14453f},{-0.112586f,0.00252701f,0.145044f},{-0.11229f,0.00405957f,0.14418f}, +{-0.113281f,0.00550952f,0.144258f},{-0.112863f,0.00559184f,0.143809f},{-0.112743f,0.00407172f,0.14463f}, +{-0.227099f,-0.022887f,0.146255f},{-0.227063f,-0.0233314f,0.14672f},{-0.151481f,-0.0174497f,0.14634f}, +{-0.189252f,-0.0203893f,0.146565f},{-0.189288f,-0.0199559f,0.146102f},{-0.151517f,-0.0170273f,0.145879f}, +{-0.489052f,0.0123416f,0.145204f},{-0.489962f,0.0109102f,0.145018f},{-0.487844f,0.0135295f,0.145346f}, +{-0.450527f,0.0164058f,0.14564f},{-0.413211f,0.0192822f,0.145867f},{-0.375894f,0.0221586f,0.146027f}, +{-0.490523f,0.00932212f,0.144792f},{-0.490713f,0.00765064f,0.144531f},{-0.483255f,-0.00968775f,0.140407f}, +{-0.484944f,-0.00949318f,0.140468f},{-0.48999f,-0.00543154f,0.141666f},{-0.49053f,-0.00387196f,0.142086f}, +{-0.486539f,-0.00892517f,0.140645f},{-0.487952f,-0.0080214f,0.14092f},{-0.489121f,-0.00683431f,0.141269f}, +{-0.490713f,-0.00223012f,0.142505f},{-0.489193f,-0.00379135f,0.144903f},{-0.488833f,-0.00496458f,0.14459f}, +{-0.489314f,0.00742307f,0.147291f},{-0.489314f,-0.00257039f,0.145216f},{-0.48825f,-0.00603944f,0.144293f}, +{-0.489314f,0.00240499f,0.146356f},{-0.387061f,0.0211541f,0.148776f},{-0.435444f,0.0173396f,0.148518f}, +{-0.483726f,0.013533f,0.148143f},{-0.485001f,0.0132913f,0.148115f},{-0.486194f,0.0127821f,0.148055f}, +{-0.487252f,0.0120287f,0.147962f},{-0.488124f,0.0110706f,0.147837f},{-0.488776f,0.00994698f,0.14768f}, +{-0.489178f,0.00871793f,0.147497f},{-0.483255f,-0.00968775f,0.141279f},{-0.490713f,0.00268915f,0.144987f}, +{-0.490713f,0.00765064f,0.145911f},{-0.490713f,-0.00223012f,0.14386f},{-0.486568f,0.0143331f,0.145639f}, +{-0.4854f,0.014793f,0.146726f},{-0.48523f,0.0148426f,0.146158f},{-0.483834f,0.0150857f,0.146754f}, +{-0.486869f,0.014174f,0.146667f},{-0.488168f,0.0132606f,0.146575f},{-0.489246f,0.0120925f,0.146451f}, +{-0.490048f,0.0107278f,0.146297f},{-0.490544f,0.00922792f,0.146115f},{-0.48779f,-0.00815064f,0.142549f}, +{-0.489024f,-0.00695586f,0.14283f},{-0.489946f,-0.00552233f,0.143157f},{-0.490519f,-0.00391721f,0.143508f}, +{-0.486401f,-0.0089918f,0.141854f},{-0.484871f,-0.00951028f,0.141426f},{-0.488788f,-0.0068323f,0.143638f}, +{-0.488748f,-0.00632699f,0.144055f},{-0.488576f,-0.00732043f,0.143234f},{-0.48823f,-0.00776225f,0.14287f}, +{-0.374892f,0.0235779f,0.147426f},{-0.386398f,0.0219204f,0.148625f},{-0.38644f,0.0224876f,0.148085f}, +{-0.447521f,0.0179164f,0.147043f},{-0.483831f,0.0149745f,0.1473f},{-0.435152f,0.0186837f,0.147841f}, +{-0.483769f,0.0140869f,0.148094f},{-0.435109f,0.0180963f,0.148384f},{-0.483807f,0.0146193f,0.147797f}, +{-0.411206f,0.0207472f,0.147267f},{-0.486695f,0.0137517f,0.147682f},{-0.485162f,0.013838f,0.148064f}, +{-0.485304f,0.0143462f,0.147745f},{-0.488127f,0.0131473f,0.147128f},{-0.486836f,0.0140617f,0.147224f}, +{-0.485388f,0.0146779f,0.147286f},{-0.48927f,0.0101903f,0.147606f},{-0.488565f,0.0114133f,0.147771f}, +{-0.490167f,0.00899738f,0.147089f},{-0.490614f,0.00756687f,0.146419f},{-0.490303f,0.00748972f,0.146886f}, +{-0.489978f,0.0106218f,0.146837f},{-0.489191f,0.0119815f,0.146999f},{-0.490458f,0.00912889f,0.146646f}, +{-0.489708f,0.0104352f,0.147285f},{-0.489702f,0.00884706f,0.147411f},{-0.487935f,0.0128697f,0.147584f}, +{-0.486458f,0.0132839f,0.148001f},{-0.489829f,0.00743905f,0.147194f},{-0.487613f,0.0124617f,0.147903f}, +{-0.488955f,0.0117456f,0.147451f},{-0.490504f,0.00254212f,0.145696f},{-0.490038f,0.0024474f,0.146152f}, +{-0.490529f,-0.00239822f,0.14453f},{-0.489991f,-0.00252701f,0.145044f},{-0.490287f,-0.00405957f,0.14418f}, +{-0.489296f,-0.00550952f,0.144258f},{-0.489714f,-0.00559184f,0.143809f},{-0.489834f,-0.00407172f,0.14463f}, +{-0.375514f,0.0233314f,0.14672f},{-0.375478f,0.022887f,0.146255f},{-0.45106f,0.0170273f,0.145879f}, +{-0.451096f,0.0174497f,0.14634f},{-0.413325f,0.0203893f,0.146565f},{-0.413289f,0.0199559f,0.146102f}, +{-0.299632f,-0.0043568f,0.127503f},{-0.298639f,-0.00383438f,0.127503f},{-0.297796f,-0.00308638f,0.127503f}, +{-0.29716f,-0.00216232f,0.127503f},{-0.301848f,-0.00462734f,0.127503f},{-0.300722f,-0.00462608f,0.127503f}, +{-0.303933f,-0.00383806f,0.127503f},{-0.302939f,-0.00435903f,0.127503f},{-0.304776f,-0.00309213f,0.127503f}, +{-0.305415f,-0.00216808f,0.127503f},{-0.305813f,-0.00111857f,0.127503f},{-0.296762f,-0.0011128f,0.127503f}, +{-0.298964f,0.00150163f,0.127503f},{-0.29861f,0.000787374f,0.127503f},{-0.29946f,0.00211724f,0.127503f}, +{-0.30013f,0.00254559f,0.127503f},{-0.300894f,0.00276842f,0.127503f},{-0.301689f,0.00276723f,0.127503f}, +{-0.302452f,0.00254283f,0.127503f},{-0.303112f,0.00210508f,0.127503f},{-0.303628f,0.00150519f,0.127503f}, +{-0.303974f,0.00078745f,0.127503f},{-0.302447f,0.00254559f,0.136825f},{-0.301683f,0.00276842f,0.136825f}, +{-0.298949f,0.00150519f,0.136825f},{-0.300888f,0.00276723f,0.136825f},{-0.299465f,0.00210508f,0.136825f}, +{-0.298603f,0.00078745f,0.136825f},{-0.300125f,0.00254283f,0.136825f},{-0.303117f,0.00211724f,0.136825f}, +{-0.303613f,0.00150163f,0.136825f},{-0.303967f,0.000787374f,0.136825f},{-0.322419f,-0.00265777f,0.127503f}, +{-0.321638f,-0.00225612f,0.127503f},{-0.321021f,-0.00163414f,0.127503f},{-0.324145f,-0.00266037f,0.127503f}, +{-0.324923f,-0.00226719f,0.127503f},{-0.323289f,-0.00279661f,0.127503f},{-0.325545f,-0.00165072f,0.127503f}, +{-0.325946f,-0.000869207f,0.127503f},{-0.320631f,-0.000869207f,0.127503f},{-0.278419f,-0.00265777f,0.127503f}, +{-0.277638f,-0.00225612f,0.127503f},{-0.277021f,-0.00163414f,0.127503f},{-0.280145f,-0.00266037f,0.127503f}, +{-0.279289f,-0.00279661f,0.127503f},{-0.281545f,-0.00165072f,0.127503f},{-0.280923f,-0.00226719f,0.127503f}, +{-0.281946f,-0.000869207f,0.127503f},{-0.276631f,-0.000869207f,0.127503f},{-0.0027207f,0.323702f,0.141016f}, +{-0.00279661f,0.323289f,0.127503f},{-0.00276223f,0.322911f,0.140921f},{-0.00254178f,0.324476f,0.141133f}, +{-0.00266037f,0.324145f,0.127503f},{-0.00226719f,0.324923f,0.127503f},{-0.00210085f,0.325128f,0.141283f}, +{-0.000869207f,0.325946f,0.127503f},{-0.00165072f,0.325545f,0.127503f},{-0.00149803f,0.325656f,0.141448f}, +{-0.000793813f,0.325978f,0.141604f},{-2.68373e-017f,0.326085f,0.127503f},{2.12873e-008f,0.326085f,0.141748f}, +{-0.00265777f,0.322419f,0.127503f},{-0.00255964f,0.322139f,0.140869f},{-0.00225612f,0.321638f,0.127503f}, +{-0.00163414f,0.321021f,0.127503f},{-0.00212367f,0.321467f,0.140862f},{-0.000869207f,0.320631f,0.127503f}, +{-0.00151779f,0.320933f,0.140892f},{-0.000793595f,0.320598f,0.140955f},{-2.77368e-017f,0.320492f,0.127503f}, +{-2.77368e-017f,0.320492f,0.141048f},{-0.00226719f,0.280923f,0.127503f},{-0.00266113f,0.280167f,0.141631f}, +{-0.00225617f,0.280949f,0.141475f},{-0.00266037f,0.280145f,0.127503f},{-0.00165072f,0.281545f,0.127503f}, +{-0.00161123f,0.281516f,0.141322f},{-0.000869207f,0.281946f,0.127503f},{-0.000861428f,0.281954f,0.141174f}, +{-0.00279699f,0.279308f,0.141768f},{-2.26626e-008f,0.282085f,0.141048f},{-3.69839e-017f,0.282085f,0.127503f}, +{-0.00279661f,0.279289f,0.127503f},{-0.00267244f,0.278435f,0.141876f},{-0.00227523f,0.277655f,0.141932f}, +{-0.00265777f,0.278419f,0.127503f},{-0.00225612f,0.277638f,0.127503f},{-0.00164828f,0.277026f,0.14193f}, +{-0.00163414f,0.277021f,0.127503f},{-0.000869207f,0.276631f,0.127503f},{-0.000867575f,0.276622f,0.141868f}, +{-3.66414e-017f,0.276492f,0.127503f},{-3.66414e-017f,0.276492f,0.141748f},{0.00279661f,0.301289f,0.136825f}, +{0.00266037f,0.302145f,0.127503f},{0.00226719f,0.299654f,0.136825f},{0.00265777f,0.300419f,0.127503f}, +{0.00225612f,0.299638f,0.127503f},{0.00266037f,0.300432f,0.136825f},{0.00165072f,0.299032f,0.136825f}, +{0.000869207f,0.298631f,0.127503f},{-2.80793e-017f,0.298492f,0.136825f},{0.000869207f,0.298631f,0.136825f}, +{0.00163414f,0.299021f,0.127503f},{-2.80793e-017f,0.298492f,0.127503f},{0.00265777f,0.302158f,0.136825f}, +{0.00226719f,0.302923f,0.127503f},{0.00225612f,0.302939f,0.136825f},{0.00163414f,0.303556f,0.136825f}, +{0.00165072f,0.303545f,0.127503f},{0.000869207f,0.303946f,0.136825f},{0.000869207f,0.303946f,0.127503f}, +{-2.77368e-017f,0.304085f,0.127503f},{-2.77368e-017f,0.304085f,0.136825f},{-0.00383933f,0.303941f,0.140336f}, +{-0.00435933f,0.302938f,0.127503f},{-0.00437081f,0.302948f,0.140342f},{-0.00462728f,0.301847f,0.127503f}, +{-0.00383758f,0.303934f,0.127503f},{-0.00463064f,0.301857f,0.140371f},{-0.00309444f,0.304774f,0.127503f}, +{-0.00308762f,0.304783f,0.140354f},{-0.00216892f,0.305414f,0.127503f},{-0.00463006f,0.300727f,0.140416f}, +{-0.00216891f,0.30543f,0.14039f},{-0.00111911f,0.305813f,0.127503f},{-5.60324e-014f,0.30595f,0.140488f}, +{-3.35892e-010f,0.305949f,0.127503f},{-0.00112174f,0.305823f,0.140439f},{-0.00462657f,0.300724f,0.127503f}, +{-0.00435716f,0.299633f,0.127503f},{-0.00437228f,0.299631f,0.140465f},{-0.00384698f,0.298643f,0.140509f}, +{-0.0038338f,0.298638f,0.127503f},{-0.00308862f,0.297798f,0.127503f},{-0.00309221f,0.2978f,0.140537f}, +{-0.00216381f,0.29716f,0.127503f},{-0.00217168f,0.297151f,0.140543f},{-0.00112329f,0.296754f,0.140525f}, +{-0.00111503f,0.296763f,0.127503f},{-2.77368e-017f,0.296628f,0.140488f},{-2.77368e-017f,0.296628f,0.127503f}, +{-0.0031834f,0.333784f,0.141919f},{0.0034311f,0.333871f,0.143258f},{-0.00348389f,0.329361f,0.141453f}, +{0.013311f,0.321833f,0.142108f},{0.00749864f,0.321483f,0.141891f},{0.01447f,0.325857f,0.142985f}, +{0.0237151f,0.334598f,0.145107f},{0.0168317f,0.334046f,0.144795f},{0.0250351f,0.338577f,0.14612f}, +{0.00309212f,0.304777f,0.140537f},{0.00980991f,0.308789f,0.140443f},{0.00384705f,0.303935f,0.140509f}, +{0.000788852f,0.320598f,0.141161f},{0.00148198f,0.320971f,0.141294f},{0.00113058f,0.316843f,0.140739f}, +{0.00437081f,0.299629f,0.140342f},{0.00463066f,0.30072f,0.140371f},{0.00734722f,0.299868f,0.140099f}, +{-0.00981015f,0.293803f,0.140456f},{0.00383936f,0.298637f,0.140336f},{0.0030876f,0.297795f,0.140354f}, +{0.000835134f,0.29484f,0.140403f},{-0.00565577f,0.289735f,0.140706f},{-0.00448849f,0.294321f,0.140582f}, +{0.000794809f,0.281978f,0.140955f},{0.00431412f,0.286162f,0.139973f},{0.00152033f,0.281642f,0.140892f}, +{-0.0168309f,0.268522f,0.144796f},{-0.0250351f,0.264f,0.14612f},{-0.0237151f,0.26798f,0.145107f}, +{-0.0110109f,0.289229f,0.140705f},{-0.00922726f,0.272859f,0.143432f},{-0.0222833f,0.271923f,0.144104f}, +{-0.0156491f,0.272684f,0.143876f},{0.00348559f,0.273206f,0.141452f},{-0.00283697f,0.273034f,0.142622f}, +{0.000793378f,0.276599f,0.141605f},{0.00318417f,0.268783f,0.141918f},{-0.00342276f,0.268697f,0.143256f}, +{0.00969325f,0.268311f,0.140239f},{0.00290707f,0.264f,0.142335f},{-0.00398877f,0.264f,0.143878f}, +{0.00968775f,0.264f,0.140407f},{0.00378729f,0.277496f,0.140965f},{0.00209478f,0.277448f,0.141284f}, +{0.00253473f,0.278103f,0.141134f},{-0.010107f,0.26861f,0.144218f},{0.00272118f,0.278874f,0.141016f}, +{0.00973119f,0.281218f,0.139327f},{0.00404127f,0.281779f,0.140452f},{0.00858894f,0.304265f,0.140271f}, +{0.000322559f,0.312352f,0.140392f},{-0.00611166f,0.307227f,0.139905f},{-0.0049946f,0.311852f,0.139783f}, +{-0.00734676f,0.30271f,0.140099f},{0.0043723f,0.302947f,0.140465f},{-0.00405908f,0.320788f,0.140464f}, +{-0.00435339f,0.316411f,0.139998f},{0.00217165f,0.305426f,0.140543f},{0.00450063f,0.308268f,0.140568f}, +{0.00253786f,0.322112f,0.141575f},{0.00276739f,0.322873f,0.141709f},{0.00835592f,0.325595f,0.14266f}, +{0.00255847f,0.324441f,0.141903f},{0.00212169f,0.325113f,0.141937f},{0.0208182f,0.326719f,0.143118f}, +{0.00398877f,0.338577f,0.143878f},{0.0156505f,0.329883f,0.143875f},{-0.00968775f,0.338577f,0.140407f}, +{-0.00290707f,0.338577f,0.142335f},{-0.00969325f,0.334267f,0.140239f},{-0.00973122f,0.321359f,0.139327f}, +{-0.00972934f,0.32566f,0.139659f},{-0.00378494f,0.325074f,0.140965f},{0.0121774f,0.317712f,0.141276f}, +{0.00665136f,0.317277f,0.141165f},{-0.000816648f,0.307746f,0.140389f},{0.0027728f,0.323672f,0.141822f}, +{0.0101155f,0.333958f,0.144218f},{0.0179944f,0.338577f,0.145774f},{0.0222833f,0.330654f,0.144104f}, +{0.0109671f,0.338577f,0.145026f},{-0.0097173f,0.329962f,0.139971f},{-0.0097497f,0.317058f,0.139013f}, +{-0.00858896f,0.298313f,0.140271f},{0.00613049f,0.295355f,0.139921f},{-0.00115281f,0.285728f,0.140712f}, +{0.00500873f,0.290743f,0.139791f},{0.0120097f,0.298192f,0.13929f},{0.0108714f,0.294038f,0.138995f}, +{0.00463004f,0.30185f,0.140416f},{0.0131607f,0.30234f,0.139564f},{0.0143354f,0.306481f,0.139836f}, +{0.00566917f,0.312855f,0.140697f},{0.0110148f,0.313358f,0.140695f},{-0.0100181f,0.312766f,0.138847f}, +{-0.0108714f,0.308539f,0.138995f},{-0.0120097f,0.304385f,0.13929f},{-0.0131607f,0.300237f,0.139564f}, +{-0.0143354f,0.296096f,0.139836f},{-0.00666271f,0.285291f,0.14114f},{-0.00749967f,0.281083f,0.141879f}, +{0.00277232f,0.279664f,0.14092f},{0.00972932f,0.276917f,0.139659f},{0.00149718f,0.276921f,0.141448f}, +{-0.0121843f,0.284854f,0.141251f},{0.00255887f,0.280437f,0.140869f},{0.00212359f,0.28111f,0.140862f}, +{-0.000305779f,0.290241f,0.140401f},{0.00112176f,0.296754f,0.140439f},{0.00216894f,0.297147f,0.14039f}, +{-0.0133136f,0.280732f,0.142096f},{-0.00834704f,0.276975f,0.14266f},{-0.0144683f,0.276713f,0.142986f}, +{0.0028458f,0.329534f,0.142624f},{0.0092361f,0.329708f,0.143432f},{0.00151619f,0.325643f,0.141923f}, +{0.00079021f,0.325978f,0.141859f},{0.019351f,0.322781f,0.142144f},{0.0179262f,0.318817f,0.14121f}, +{0.0166178f,0.314771f,0.140509f},{0.00210151f,0.321454f,0.141433f},{0.00112326f,0.305823f,0.140525f}, +{0.0154659f,0.310634f,0.14012f},{0.0100181f,0.289811f,0.138847f},{-0.0154659f,0.291943f,0.14012f}, +{0.00974966f,0.285519f,0.139013f},{-0.0179262f,0.28376f,0.14121f},{-0.0166178f,0.287806f,0.140509f}, +{-0.0193511f,0.279796f,0.142144f},{-0.0208182f,0.275858f,0.143118f},{0.00971729f,0.272615f,0.139971f}, +{-0.0179944f,0.264f,0.145774f},{-0.0109671f,0.264f,0.145026f},{0.0262081f,0.338577f,0.148238f}, +{0.0248064f,0.334844f,0.147199f},{0.0250058f,0.334839f,0.146766f},{0.0233183f,0.331143f,0.146165f}, +{0.0235291f,0.331138f,0.145739f},{0.0188229f,0.320025f,0.143165f},{0.0190695f,0.320019f,0.142766f}, +{0.0203019f,0.323745f,0.144139f},{0.0205368f,0.32374f,0.143731f},{0.022035f,0.32744f,0.14473f}, +{0.0218112f,0.327445f,0.145147f},{0.015307f,0.308407f,0.141119f},{0.0150041f,0.308412f,0.141517f}, +{0.0141429f,0.304471f,0.140834f},{0.0174212f,0.316248f,0.1423f},{0.0161629f,0.312356f,0.141811f}, +{0.0164424f,0.312351f,0.141416f},{0.0114006f,0.296614f,0.14071f},{0.0106866f,0.29265f,0.140011f}, +{0.0117799f,0.296607f,0.140283f},{0.0125814f,0.300553f,0.14098f},{0.0129503f,0.300542f,0.14056f}, +{0.0138012f,0.30448f,0.141246f},{0.00963024f,0.280413f,0.140526f},{0.00968708f,0.284511f,0.140168f}, +{0.0091952f,0.284522f,0.140649f},{0.0099197f,0.288611f,0.139934f},{0.0102596f,0.292663f,0.140442f}, +{0.00946264f,0.288623f,0.140382f},{0.00907526f,0.280421f,0.141031f},{0.0095489f,0.276313f,0.140876f}, +{0.00894343f,0.27632f,0.141413f},{0.00945311f,0.272213f,0.141203f},{0.00933687f,0.268109f,0.14148f}, +{0.00879579f,0.272217f,0.141773f},{0.0086246f,0.268112f,0.142088f},{0.00922107f,0.264f,0.141665f}, +{0.00845004f,0.264f,0.142301f},{0.0176856f,0.316239f,0.141921f},{0.0263793f,0.338577f,0.147802f}, +{0.0259023f,0.338577f,0.148593f},{0.0244885f,0.334843f,0.147557f},{0.0229936f,0.33114f,0.146522f}, +{0.0184899f,0.320015f,0.143511f},{0.0214828f,0.32744f,0.145501f},{0.0146321f,0.3084f,0.14188f}, +{0.0170843f,0.316236f,0.142644f},{0.0158117f,0.312343f,0.142162f},{0.010968f,0.296605f,0.141112f}, +{0.0121699f,0.300543f,0.141368f},{0.0134094f,0.304469f,0.141622f},{0.0086637f,0.284517f,0.141107f}, +{0.00980481f,0.292656f,0.140857f},{0.00897481f,0.288617f,0.140813f},{0.00849863f,0.280417f,0.141523f}, +{0.00832061f,0.276317f,0.14194f},{0.00812583f,0.272215f,0.142335f},{0.00790535f,0.268111f,0.142688f}, +{0.00767878f,0.264f,0.142938f},{0.0199715f,0.323738f,0.144489f},{0.0254953f,0.338577f,0.148828f}, +{0.0239945f,0.334632f,0.147747f},{0.0224149f,0.330719f,0.146665f},{0.0176882f,0.318949f,0.143502f}, +{0.0208215f,0.326809f,0.145592f},{0.0192329f,0.322894f,0.144529f},{0.0136618f,0.306623f,0.142081f}, +{0.0162503f,0.314913f,0.14274f},{0.0149457f,0.310777f,0.142346f},{0.00869072f,0.289947f,0.141186f}, +{0.00973903f,0.294176f,0.141305f},{0.0110356f,0.29833f,0.141581f},{0.00795144f,0.281312f,0.141896f}, +{0.0081943f,0.285636f,0.14144f},{0.00772122f,0.276988f,0.142378f},{0.00747253f,0.272663f,0.142842f}, +{0.00719397f,0.268336f,0.143263f},{0.00690556f,0.264f,0.143577f},{0.0123399f,0.302479f,0.141831f}, +{0.0250324f,0.338577f,0.148916f},{0.0235306f,0.334606f,0.147857f},{0.0219498f,0.330688f,0.146794f}, +{0.0172517f,0.318889f,0.143711f},{0.0203651f,0.326769f,0.14574f},{0.0132021f,0.306566f,0.142332f}, +{0.0158114f,0.314858f,0.142927f},{0.0144807f,0.310726f,0.142544f},{0.0092687f,0.29412f,0.141666f}, +{0.0105497f,0.298278f,0.141886f},{0.0118813f,0.30242f,0.142106f},{0.0073368f,0.28128f,0.142324f}, +{0.00759572f,0.285604f,0.141811f},{0.00819435f,0.289904f,0.141567f},{0.00708183f,0.276964f,0.142866f}, +{0.00678804f,0.272648f,0.143377f},{0.00646507f,0.268328f,0.143843f},{0.00613003f,0.264f,0.144218f}, +{0.0187868f,0.322844f,0.144697f},{0.00696068f,0.276283f,0.143005f},{0.00667554f,0.272193f,0.143491f}, +{0.00636198f,0.268101f,0.143939f},{0.00748015f,0.284462f,0.141999f},{0.00786981f,0.288553f,0.141631f}, +{0.00722771f,0.280372f,0.1425f},{0.0111819f,0.300465f,0.142035f},{0.00875236f,0.292584f,0.14162f}, +{0.014914f,0.312256f,0.142686f},{0.0124511f,0.304388f,0.142242f},{0.0137038f,0.308316f,0.142453f}, +{0.0175985f,0.319944f,0.143972f},{0.0190677f,0.323681f,0.144928f},{0.0162018f,0.316153f,0.143129f}, +{0.0205663f,0.327398f,0.145919f},{0.022067f,0.331113f,0.146916f},{0.0235578f,0.33483f,0.14792f}, +{0.00994863f,0.29653f,0.141826f},{0.00603944f,0.264f,0.144293f},{0.00744254f,0.330122f,0.145994f}, +{0.015865f,0.334273f,0.147531f},{0.0083666f,0.334181f,0.146789f},{0.000311244f,0.329939f,0.144934f}, +{0.000930332f,0.334089f,0.145573f},{-0.00667554f,0.330384f,0.143491f},{0.00158091f,0.338577f,0.146182f}, +{-0.0063617f,0.334477f,0.143935f},{0.00932143f,0.338577f,0.147589f},{-0.00603944f,0.338577f,0.144293f}, +{0.00654234f,0.326198f,0.145204f},{0.00567271f,0.322287f,0.144415f},{0.0134133f,0.326474f,0.14569f}, +{0.00989537f,0.314708f,0.143217f},{0.0110779f,0.318771f,0.143908f},{0.00388505f,0.314167f,0.143059f}, +{0.0122295f,0.322655f,0.144789f},{0.0072715f,0.306074f,0.142814f},{1.23849e-006f,0.301276f,0.142893f}, +{0.00593214f,0.301855f,0.142703f},{0.00860427f,0.310416f,0.142918f},{0.00327255f,0.293337f,0.142485f}, +{0.00211647f,0.288967f,0.14253f},{-0.00133631f,0.297083f,0.142894f},{0.00459153f,0.297661f,0.142593f}, +{-0.00836678f,0.268392f,0.146789f},{-0.00093054f,0.268483f,0.145573f},{-0.000310969f,0.272633f,0.144934f}, +{0.00135717f,0.284719f,0.142953f},{-0.00485039f,0.284259f,0.143617f},{-0.00158091f,0.264f,0.146182f}, +{0.000284983f,0.276649f,0.144284f},{-0.00744232f,0.27245f,0.145994f},{-0.0171357f,0.264f,0.148501f}, +{-0.0158652f,0.2683f,0.147532f},{0.000835711f,0.280649f,0.143615f},{-0.00654153f,0.276375f,0.145205f}, +{-0.00568021f,0.280282f,0.144405f},{-0.00265603f,0.292762f,0.142905f},{-0.00387587f,0.288426f,0.143071f}, +{0.00267273f,0.309833f,0.142876f},{0.00133739f,0.305495f,0.142892f},{0.00483092f,0.318311f,0.143642f}, +{0.0146267f,0.330306f,0.1466f},{0.0171357f,0.338577f,0.148501f},{-0.0069607f,0.326294f,0.143005f}, +{-0.000284018f,0.325924f,0.144284f},{-0.00722775f,0.322205f,0.1425f},{-0.000847135f,0.321921f,0.143625f}, +{-0.00746803f,0.318116f,0.141989f},{-0.00138663f,0.317854f,0.142978f},{-0.00787057f,0.314024f,0.141632f}, +{-0.00210321f,0.313628f,0.142519f},{-0.00875939f,0.309995f,0.141625f},{-0.00324421f,0.309251f,0.142456f}, +{-0.00994211f,0.306045f,0.141827f},{-0.023562f,0.267749f,0.147921f},{-0.0249766f,0.264f,0.148916f}, +{-0.00458966f,0.304917f,0.142591f},{-0.0111906f,0.302115f,0.142034f},{-0.0124586f,0.298192f,0.142239f}, +{-0.00592971f,0.300697f,0.142704f},{-0.0136985f,0.29426f,0.142455f},{-0.00727121f,0.296504f,0.142816f}, +{-0.0149126f,0.29032f,0.142682f},{-0.00859914f,0.292185f,0.142945f},{-0.0162055f,0.286428f,0.143141f}, +{-0.0098903f,0.287882f,0.143228f},{-0.0175985f,0.282633f,0.143972f},{-0.0110874f,0.283798f,0.143884f}, +{-0.0190677f,0.278896f,0.144928f},{-0.012233f,0.279914f,0.144779f},{-0.0205663f,0.275179f,0.145919f}, +{-0.0134127f,0.276098f,0.14569f},{-0.0220671f,0.271464f,0.146916f},{-0.0146265f,0.272266f,0.1466f}, +{-0.00932143f,0.264f,0.147589f},{-0.00690312f,0.338577f,0.143579f},{-0.00719191f,0.334242f,0.143259f}, +{-0.00746979f,0.329914f,0.142843f},{-0.00814762f,0.316934f,0.141414f},{-0.0077197f,0.325589f,0.142379f}, +{-0.00793083f,0.321266f,0.141883f},{-0.0110361f,0.304248f,0.141582f},{-0.0123542f,0.300103f,0.141829f}, +{-0.00871456f,0.312628f,0.141206f},{-0.00976951f,0.308409f,0.141335f},{-0.0162476f,0.28766f,0.14273f}, +{-0.0149252f,0.291792f,0.142321f},{-0.0136614f,0.295955f,0.142081f},{-0.0192347f,0.279686f,0.144536f}, +{-0.0176916f,0.283634f,0.143534f},{-0.0208212f,0.27577f,0.145595f},{-0.022413f,0.271858f,0.146665f}, +{-0.0239981f,0.267947f,0.147749f},{-0.0254927f,0.264f,0.148829f},{-0.00767576f,0.338577f,0.142941f}, +{-0.00790232f,0.334466f,0.142685f},{-0.00812312f,0.330362f,0.142338f},{-0.00864847f,0.31806f,0.1411f}, +{-0.00831807f,0.32626f,0.141942f},{-0.00849626f,0.32216f,0.141525f},{-0.0109591f,0.30597f,0.141114f}, +{-0.00897354f,0.313959f,0.140816f},{-0.00981108f,0.309923f,0.140864f},{-0.0146249f,0.294175f,0.141884f}, +{-0.0134151f,0.29811f,0.141621f},{-0.0121769f,0.302037f,0.141369f},{-0.0184881f,0.282562f,0.143513f}, +{-0.0158082f,0.290233f,0.142159f},{-0.0170869f,0.286345f,0.142657f},{-0.0199696f,0.278839f,0.144491f}, +{-0.0214809f,0.275137f,0.145503f},{-0.0229915f,0.271437f,0.146524f},{-0.0244911f,0.267736f,0.147559f}, +{-0.0259001f,0.264f,0.148595f},{-0.00844643f,0.338577f,0.142304f},{-0.0086212f,0.334465f,0.142086f}, +{-0.00879266f,0.33036f,0.141776f},{-0.00917932f,0.318055f,0.140643f},{-0.00894054f,0.326258f,0.141415f}, +{-0.0113914f,0.305961f,0.140713f},{-0.00946126f,0.313954f,0.140385f},{-0.0102671f,0.309916f,0.14045f}, +{-0.0149971f,0.294163f,0.141521f},{-0.0138071f,0.298099f,0.141245f},{-0.0125887f,0.302027f,0.140981f}, +{-0.0188214f,0.282552f,0.143167f},{-0.0161597f,0.29022f,0.14181f},{-0.0174245f,0.286332f,0.142314f}, +{-0.0203004f,0.278832f,0.144141f},{-0.0218097f,0.275132f,0.145149f},{-0.0233168f,0.271434f,0.146167f}, +{-0.0248099f,0.267735f,0.147201f},{-0.0262067f,0.264f,0.148241f},{-0.0090726f,0.322157f,0.141033f}, +{-0.00921688f,0.338577f,0.141668f},{-0.00933302f,0.334468f,0.141483f},{-0.00944958f,0.330364f,0.141206f}, +{-0.00968445f,0.318066f,0.140171f},{-0.00954568f,0.326264f,0.140879f},{-0.0117779f,0.30597f,0.140285f}, +{-0.00991732f,0.313966f,0.139936f},{-0.0106844f,0.309927f,0.140013f},{-0.0153055f,0.29417f,0.141121f}, +{-0.0141412f,0.298106f,0.140836f},{-0.0129485f,0.302035f,0.140562f},{-0.0190685f,0.282558f,0.142768f}, +{-0.0176844f,0.286338f,0.141924f},{-0.016441f,0.290226f,0.141419f},{-0.0205358f,0.278837f,0.143733f}, +{-0.0220341f,0.275137f,0.144732f},{-0.0235282f,0.271439f,0.145742f},{-0.0250051f,0.267738f,0.146769f}, +{-0.0263788f,0.264f,0.147805f},{-0.00962732f,0.322165f,0.140529f},{-0.00976429f,0.334471f,0.141114f}, +{-0.00968775f,0.338577f,0.141279f},{-0.00995451f,0.322175f,0.140217f},{-0.00990606f,0.326272f,0.140549f}, +{-0.00984421f,0.33037f,0.140856f},{-0.0109184f,0.309942f,0.13974f},{-0.00997907f,0.318079f,0.139878f}, +{-0.0143137f,0.29812f,0.140577f},{-0.01314f,0.302049f,0.140298f},{-0.0119892f,0.305984f,0.140016f}, +{-0.0178005f,0.28635f,0.141673f},{-0.0165744f,0.290239f,0.141169f},{-0.015459f,0.294183f,0.140867f}, +{-0.0206269f,0.278846f,0.143469f},{-0.0191718f,0.282568f,0.142511f},{-0.0221132f,0.275145f,0.144461f}, +{-0.0235942f,0.271445f,0.145464f},{-0.0250554f,0.267741f,0.146485f},{-0.0264087f,0.264f,0.147518f}, +{-0.0101788f,0.313981f,0.139657f},{-0.0137161f,0.300099f,0.140288f},{-0.0124851f,0.304248f,0.140002f}, +{-0.0113146f,0.308413f,0.139715f},{-0.0103804f,0.312637f,0.139538f},{-0.00997452f,0.316945f,0.139665f}, +{-0.00994023f,0.321273f,0.140012f},{-0.00991203f,0.325595f,0.140375f},{-0.009849f,0.329918f,0.140706f}, +{-0.00976769f,0.334245f,0.140986f},{-0.00968775f,0.338577f,0.141169f},{-0.014938f,0.295949f,0.140581f}, +{-0.0161103f,0.291782f,0.140863f},{-0.0173564f,0.28765f,0.141293f},{-0.0187613f,0.283628f,0.142077f}, +{-0.0202782f,0.279684f,0.143048f},{-0.021842f,0.275771f,0.144073f},{-0.0234057f,0.271863f,0.145113f}, +{-0.024951f,0.267952f,0.146173f},{-0.0263814f,0.264f,0.147244f},{-0.00976336f,0.333995f,0.140775f}, +{-0.00968775f,0.338577f,0.140979f},{-0.00990978f,0.320276f,0.139723f},{-0.00989796f,0.324847f,0.140113f}, +{-0.00983969f,0.329419f,0.140469f},{-0.0106101f,0.311162f,0.139359f},{-0.0117247f,0.306724f,0.139609f}, +{-0.00998742f,0.315696f,0.139387f},{-0.0142908f,0.297936f,0.140193f},{-0.0155467f,0.293533f,0.140484f}, +{-0.0129908f,0.302325f,0.139902f},{-0.0197978f,0.280636f,0.142487f},{-0.0182285f,0.284834f,0.141521f}, +{-0.0168071f,0.289136f,0.140836f},{-0.0214356f,0.276483f,0.143538f},{-0.0230806f,0.272338f,0.14461f}, +{-0.0247084f,0.268191f,0.145702f},{-0.0262125f,0.264f,0.146805f},{-0.00974593f,0.334001f,0.140582f}, +{-0.00968775f,0.338577f,0.140788f},{-0.00985594f,0.3203f,0.139537f},{-0.00985469f,0.324865f,0.139924f}, +{-0.00980831f,0.329431f,0.140278f},{-0.0116247f,0.30676f,0.13941f},{-0.00992109f,0.315727f,0.139202f}, +{-0.0141594f,0.297975f,0.139977f},{-0.0154002f,0.293574f,0.140259f},{-0.0128748f,0.302362f,0.139695f}, +{-0.0195912f,0.280668f,0.142214f},{-0.0180446f,0.284873f,0.141269f},{-0.0166436f,0.289177f,0.140601f}, +{-0.021206f,0.276508f,0.143245f},{-0.0228275f,0.272355f,0.144296f},{-0.0244304f,0.268199f,0.145365f}, +{-0.0259067f,0.264f,0.146446f},{-0.0105278f,0.311196f,0.139169f},{-0.00972275f,0.334008f,0.140397f}, +{-0.00968775f,0.338577f,0.140597f},{-0.00978412f,0.320325f,0.139372f},{-0.0097971f,0.324884f,0.139752f}, +{-0.00976655f,0.329444f,0.140099f},{-0.0104201f,0.311232f,0.139009f},{-0.0114944f,0.306797f,0.139248f}, +{-0.00983335f,0.315758f,0.139043f},{-0.013988f,0.298014f,0.139811f},{-0.0152086f,0.293615f,0.14009f}, +{-0.0127235f,0.3024f,0.13953f},{-0.01932f,0.280701f,0.142022f},{-0.017804f,0.284911f,0.141087f}, +{-0.0164298f,0.289219f,0.140429f},{-0.0209031f,0.276533f,0.143041f},{-0.0224922f,0.272372f,0.144081f}, +{-0.0240607f,0.268208f,0.145139f},{-0.0254987f,0.264f,0.146209f},{0.0240512f,0.334373f,0.145139f}, +{0.0254987f,0.338577f,0.146209f},{0.0208987f,0.326047f,0.143038f},{0.0224907f,0.330206f,0.144081f}, +{0.0164319f,0.313354f,0.14044f},{0.015224f,0.308957f,0.140101f},{0.0177924f,0.317674f,0.141053f}, +{0.0127141f,0.300179f,0.139531f},{0.0114783f,0.295784f,0.139232f},{0.0139803f,0.304565f,0.139813f}, +{0.00981234f,0.282253f,0.139389f},{0.00988648f,0.286812f,0.139069f},{0.0103884f,0.291345f,0.138993f}, +{0.00979575f,0.277693f,0.139753f},{0.00976673f,0.273133f,0.1401f},{0.00972076f,0.26857f,0.140404f}, +{0.00968775f,0.264f,0.140597f},{0.0193145f,0.32188f,0.142013f},{0.0244211f,0.334381f,0.145365f}, +{0.0259067f,0.338577f,0.146446f},{0.0195856f,0.321913f,0.142206f},{0.0212016f,0.326071f,0.143242f}, +{0.0228261f,0.330223f,0.144296f},{0.016646f,0.313395f,0.140613f},{0.0154158f,0.308997f,0.14027f}, +{0.0180326f,0.317712f,0.141234f},{0.0116084f,0.295821f,0.139394f},{0.0128655f,0.300217f,0.139695f}, +{0.0141518f,0.304604f,0.13998f},{0.0098846f,0.282278f,0.139554f},{0.0099743f,0.286844f,0.139229f}, +{0.0104962f,0.29138f,0.139152f},{0.00985341f,0.277712f,0.139926f},{0.00980859f,0.273146f,0.140279f}, +{0.0097442f,0.268576f,0.140589f},{0.00968775f,0.264f,0.140788f},{0.0246992f,0.33439f,0.145701f}, +{0.0262125f,0.338577f,0.146805f},{0.019792f,0.321945f,0.142478f},{0.0214312f,0.326096f,0.143536f}, +{0.0230793f,0.33024f,0.144611f},{0.0155626f,0.309038f,0.140495f},{0.0182163f,0.317751f,0.141486f}, +{0.0117083f,0.295857f,0.139593f},{0.0129816f,0.300255f,0.139903f},{0.0142832f,0.304643f,0.140196f}, +{0.00993888f,0.282302f,0.139741f},{0.0100406f,0.286874f,0.139415f},{0.0105787f,0.291414f,0.139342f}, +{0.00989672f,0.27773f,0.140115f},{0.00984006f,0.273158f,0.140471f},{0.00976183f,0.268582f,0.140782f}, +{0.00968775f,0.264f,0.140979f},{0.0168098f,0.313436f,0.140849f},{0.0264087f,0.338577f,0.147518f}, +{0.0221132f,0.327432f,0.144461f},{0.0235942f,0.331132f,0.145464f},{0.0250554f,0.334836f,0.146485f}, +{0.0178005f,0.316228f,0.141673f},{0.0165745f,0.312338f,0.141169f},{0.0206269f,0.323731f,0.143469f}, +{0.0191717f,0.320009f,0.142511f},{0.01314f,0.300528f,0.140298f},{0.0143137f,0.304457f,0.140577f}, +{0.015459f,0.308394f,0.140867f},{0.0101788f,0.288596f,0.139657f},{0.0109184f,0.292635f,0.13974f}, +{0.0119892f,0.296593f,0.140016f},{0.00995447f,0.280402f,0.140217f},{0.00997902f,0.284498f,0.139878f}, +{0.00990604f,0.276306f,0.140549f},{0.0098442f,0.272207f,0.140856f},{0.00976429f,0.268106f,0.141114f}, +{0.00968775f,0.264f,0.141279f},{0.0249437f,0.334628f,0.146173f},{0.0263814f,0.338577f,0.147244f}, +{0.0202741f,0.322896f,0.143041f},{0.0218394f,0.326807f,0.144071f},{0.023405f,0.330715f,0.145114f}, +{0.0173571f,0.314923f,0.141303f},{0.0161317f,0.310786f,0.140885f},{0.0187523f,0.318956f,0.14205f}, +{0.0136985f,0.302483f,0.140292f},{0.0124827f,0.29833f,0.140001f},{0.0149357f,0.306629f,0.140582f}, +{0.010352f,0.289937f,0.139523f},{0.0112762f,0.294173f,0.139687f},{0.00995919f,0.281305f,0.140024f}, +{0.010024f,0.285627f,0.139691f},{0.00991129f,0.276982f,0.140376f},{0.00984923f,0.272659f,0.140707f}, +{0.00968775f,0.264f,0.141169f},{0.00976681f,0.268333f,0.140992f},{-0.00379135f,0.489193f,0.144903f}, +{-0.00496458f,0.488833f,0.14459f},{0.00742307f,0.489314f,0.147291f},{-0.00257039f,0.489314f,0.145216f}, +{-0.00603944f,0.48825f,0.144293f},{0.00240499f,0.489314f,0.146356f},{0.0211541f,0.387061f,0.148776f}, +{0.0173396f,0.435444f,0.148518f},{0.013533f,0.483726f,0.148143f},{0.0132893f,0.485008f,0.148115f}, +{0.0127783f,0.4862f,0.148054f},{0.0120253f,0.487256f,0.147961f},{0.0110634f,0.488129f,0.147836f}, +{0.00994277f,0.488778f,0.14768f},{0.00870927f,0.489179f,0.147496f},{0.0123416f,0.489052f,0.145204f}, +{0.0109102f,0.489962f,0.145018f},{0.0135295f,0.487844f,0.145346f},{0.0164058f,0.450527f,0.14564f}, +{0.0192822f,0.413211f,0.145867f},{0.0221586f,0.375894f,0.146027f},{0.00932212f,0.490523f,0.144792f}, +{0.00765064f,0.490713f,0.144531f},{-0.00968775f,0.483255f,0.140407f},{-0.00949318f,0.484944f,0.140468f}, +{-0.00543154f,0.48999f,0.141666f},{-0.00387196f,0.49053f,0.142086f},{-0.00892517f,0.486539f,0.140645f}, +{-0.0080214f,0.487952f,0.14092f},{-0.00683431f,0.489121f,0.141269f},{-0.00223012f,0.490713f,0.142505f}, +{-0.00968775f,0.483255f,0.141279f},{0.00268915f,0.490713f,0.144987f},{-0.00223012f,0.490713f,0.14386f}, +{0.00765064f,0.490713f,0.145911f},{0.0143331f,0.486568f,0.145639f},{0.0147899f,0.485411f,0.146726f}, +{0.0148426f,0.48523f,0.146158f},{0.0150857f,0.483834f,0.146754f},{0.014171f,0.486874f,0.146666f}, +{0.0132538f,0.488177f,0.146574f},{0.0120868f,0.489249f,0.14645f},{0.0107201f,0.490052f,0.146296f}, +{0.00921907f,0.490545f,0.146114f},{-0.00815064f,0.48779f,0.142549f},{-0.00695586f,0.489024f,0.14283f}, +{-0.00391721f,0.490519f,0.143508f},{-0.00552233f,0.489946f,0.143157f},{-0.0089918f,0.486401f,0.141854f}, +{-0.00951028f,0.484871f,0.141426f},{-0.00632699f,0.488748f,0.144055f},{-0.0068323f,0.488788f,0.143638f}, +{-0.00732043f,0.488576f,0.143234f},{-0.00776225f,0.48823f,0.14287f},{0.0235779f,0.374892f,0.147426f}, +{0.0219204f,0.386398f,0.148625f},{0.0224876f,0.38644f,0.148085f},{0.0179164f,0.44752f,0.147043f}, +{0.0149745f,0.483831f,0.1473f},{0.0186837f,0.435152f,0.147841f},{0.0140869f,0.483769f,0.148094f}, +{0.0180963f,0.435109f,0.148384f},{0.0146193f,0.483807f,0.147797f},{0.0207472f,0.411206f,0.147267f}, +{0.00748972f,0.490303f,0.146886f},{0.00897658f,0.490142f,0.147115f},{0.00911758f,0.490461f,0.146645f}, +{0.0103998f,0.48969f,0.147311f},{0.0119652f,0.489201f,0.146998f},{0.0106014f,0.489986f,0.146835f}, +{0.0128307f,0.48793f,0.147613f},{0.0140507f,0.486857f,0.147224f},{0.0131339f,0.488142f,0.147128f}, +{0.0146743f,0.485398f,0.147286f},{0.0124497f,0.487626f,0.147903f},{0.0113986f,0.488574f,0.14777f}, +{0.0138348f,0.485172f,0.148064f},{0.0143101f,0.485306f,0.147775f},{0.013274f,0.486476f,0.148f}, +{0.00743905f,0.489829f,0.147194f},{0.00883688f,0.489704f,0.14741f},{0.00756687f,0.490614f,0.146419f}, +{0.0101719f,0.489277f,0.147604f},{0.0137111f,0.486701f,0.147711f},{0.0117086f,0.488941f,0.147479f}, +{0.00254212f,0.490504f,0.145696f},{0.0024474f,0.490038f,0.146152f},{-0.00239822f,0.490529f,0.14453f}, +{-0.00252701f,0.489991f,0.145044f},{-0.00405957f,0.490287f,0.14418f},{-0.00550952f,0.489296f,0.144258f}, +{-0.00559184f,0.489714f,0.143809f},{-0.00407172f,0.489834f,0.14463f},{0.022887f,0.375478f,0.146255f}, +{0.0233314f,0.375514f,0.14672f},{0.0174497f,0.451096f,0.14634f},{0.0203893f,0.413325f,0.146565f}, +{0.0199559f,0.413289f,0.146102f},{0.0170273f,0.45106f,0.145879f},{-0.0123416f,0.113525f,0.145204f}, +{-0.0109102f,0.112615f,0.145018f},{-0.0135295f,0.114734f,0.145346f},{-0.0164058f,0.15205f,0.14564f}, +{-0.0192822f,0.189366f,0.145867f},{-0.0221586f,0.226683f,0.146027f},{-0.00932212f,0.112054f,0.144792f}, +{-0.00765064f,0.111865f,0.144531f},{0.00968775f,0.119322f,0.140407f},{0.00949318f,0.117633f,0.140468f}, +{0.00543154f,0.112587f,0.141666f},{0.00387196f,0.112048f,0.142086f},{0.00892517f,0.116038f,0.140645f}, +{0.0080214f,0.114625f,0.14092f},{0.00683431f,0.113456f,0.141269f},{0.00223012f,0.111865f,0.142505f}, +{0.00379135f,0.113384f,0.144903f},{0.00496458f,0.113745f,0.14459f},{-0.00742307f,0.113263f,0.147291f}, +{0.00257039f,0.113263f,0.145216f},{0.00603944f,0.114327f,0.144293f},{-0.00240499f,0.113263f,0.146356f}, +{-0.0211541f,0.215517f,0.148776f},{-0.0173396f,0.167133f,0.148518f},{-0.013533f,0.118851f,0.148143f}, +{-0.0132913f,0.117576f,0.148115f},{-0.0127821f,0.116383f,0.148055f},{-0.0120287f,0.115326f,0.147962f}, +{-0.0110706f,0.114453f,0.147837f},{-0.00994698f,0.113801f,0.14768f},{-0.00871793f,0.1134f,0.147497f}, +{0.00968775f,0.119322f,0.141279f},{-0.00268915f,0.111865f,0.144987f},{-0.00765064f,0.111865f,0.145911f}, +{0.00223012f,0.111865f,0.14386f},{-0.0143331f,0.116009f,0.145639f},{-0.014793f,0.117177f,0.146726f}, +{-0.0148426f,0.117347f,0.146158f},{-0.0150857f,0.118743f,0.146754f},{-0.014174f,0.115708f,0.146667f}, +{-0.0132606f,0.114409f,0.146575f},{-0.0120925f,0.113332f,0.146451f},{-0.0107278f,0.112529f,0.146297f}, +{-0.00922792f,0.112033f,0.146115f},{0.00815064f,0.114787f,0.142549f},{0.00695586f,0.113553f,0.14283f}, +{0.00552233f,0.112631f,0.143157f},{0.00391721f,0.112058f,0.143508f},{0.0089918f,0.116176f,0.141854f}, +{0.00951028f,0.117706f,0.141426f},{0.0068323f,0.113789f,0.143638f},{0.00632699f,0.113829f,0.144055f}, +{0.00732043f,0.114001f,0.143234f},{0.00776225f,0.114347f,0.14287f},{-0.0235779f,0.227685f,0.147426f}, +{-0.0219204f,0.216179f,0.148625f},{-0.0224876f,0.216137f,0.148085f},{-0.0179164f,0.155057f,0.147043f}, +{-0.0149745f,0.118746f,0.1473f},{-0.0186837f,0.167425f,0.147841f},{-0.0140869f,0.118809f,0.148094f}, +{-0.0180963f,0.167468f,0.148384f},{-0.0146193f,0.11877f,0.147797f},{-0.0207472f,0.191371f,0.147267f}, +{-0.0137517f,0.115882f,0.147682f},{-0.013838f,0.117415f,0.148064f},{-0.0143462f,0.117273f,0.147745f}, +{-0.0131473f,0.11445f,0.147128f},{-0.0140617f,0.115741f,0.147224f},{-0.0146779f,0.11719f,0.147286f}, +{-0.0101903f,0.113307f,0.147606f},{-0.0114133f,0.114012f,0.147771f},{-0.00899738f,0.11241f,0.147089f}, +{-0.00756687f,0.111963f,0.146419f},{-0.00748972f,0.112274f,0.146886f},{-0.0106218f,0.112599f,0.146837f}, +{-0.0119815f,0.113386f,0.146999f},{-0.00912889f,0.112119f,0.146646f},{-0.0104352f,0.112869f,0.147285f}, +{-0.00884706f,0.112875f,0.147411f},{-0.0128697f,0.114643f,0.147584f},{-0.0132839f,0.116119f,0.148001f}, +{-0.00743905f,0.112748f,0.147194f},{-0.0124617f,0.114964f,0.147903f},{-0.0117456f,0.113623f,0.147451f}, +{-0.00254212f,0.112073f,0.145696f},{-0.0024474f,0.112539f,0.146152f},{0.00239822f,0.112048f,0.14453f}, +{0.00252701f,0.112586f,0.145044f},{0.00405957f,0.11229f,0.14418f},{0.00550952f,0.113281f,0.144258f}, +{0.00559184f,0.112863f,0.143809f},{0.00407172f,0.112743f,0.14463f},{-0.0233314f,0.227063f,0.14672f}, +{-0.022887f,0.227099f,0.146255f},{-0.0170273f,0.151517f,0.145879f},{-0.0174497f,0.151481f,0.14634f}, +{-0.0203893f,0.189252f,0.146565f},{-0.0199559f,0.189288f,0.146102f},{0.0043568f,0.302945f,0.127503f}, +{0.00383438f,0.303939f,0.127503f},{0.00308638f,0.304781f,0.127503f},{0.00216232f,0.305417f,0.127503f}, +{0.00462734f,0.300729f,0.127503f},{0.00462608f,0.301855f,0.127503f},{0.00383806f,0.298645f,0.127503f}, +{0.00435903f,0.299638f,0.127503f},{0.00309213f,0.297801f,0.127503f},{0.00216808f,0.297163f,0.127503f}, +{0.00111857f,0.296764f,0.127503f},{0.0011128f,0.305815f,0.127503f},{-0.00150163f,0.303613f,0.127503f}, +{-0.000787374f,0.303967f,0.127503f},{-0.00211724f,0.303117f,0.127503f},{-0.00254559f,0.302447f,0.127503f}, +{-0.00276842f,0.301683f,0.127503f},{-0.00276723f,0.300888f,0.127503f},{-0.00254283f,0.300125f,0.127503f}, +{-0.00210508f,0.299465f,0.127503f},{-0.00150519f,0.298949f,0.127503f},{-0.00078745f,0.298603f,0.127503f}, +{-0.00254559f,0.30013f,0.136825f},{-0.00276842f,0.300894f,0.136825f},{-0.00150519f,0.303628f,0.136825f}, +{-0.00276723f,0.301689f,0.136825f},{-0.00210508f,0.303112f,0.136825f},{-0.00078745f,0.303974f,0.136825f}, +{-0.00254283f,0.302452f,0.136825f},{-0.00211724f,0.29946f,0.136825f},{-0.00150163f,0.298964f,0.136825f}, +{-0.000787374f,0.29861f,0.136825f},{0.00265777f,0.280158f,0.127503f},{0.00225612f,0.280939f,0.127503f}, +{0.00163414f,0.281556f,0.127503f},{0.00266037f,0.278432f,0.127503f},{0.00226719f,0.277654f,0.127503f}, +{0.00279661f,0.279289f,0.127503f},{0.00165072f,0.277032f,0.127503f},{0.000869207f,0.276631f,0.127503f}, +{0.000869207f,0.281946f,0.127503f},{0.00265777f,0.324158f,0.127503f},{0.00225612f,0.324939f,0.127503f}, +{0.00163414f,0.325556f,0.127503f},{0.00266037f,0.322432f,0.127503f},{0.00279661f,0.323289f,0.127503f}, +{0.00165072f,0.321032f,0.127503f},{0.00226719f,0.321654f,0.127503f},{0.000869207f,0.320631f,0.127503f}, +{0.000869207f,0.325946f,0.127503f},{0.323702f,0.0027207f,0.140084f},{0.323289f,0.00279661f,0.126571f}, +{0.322911f,0.00276223f,0.139989f},{0.324476f,0.00254178f,0.140201f},{0.324145f,0.00266037f,0.126571f}, +{0.324923f,0.00226719f,0.126571f},{0.325128f,0.00210085f,0.140351f},{0.325946f,0.000869207f,0.126571f}, +{0.325545f,0.00165072f,0.126571f},{0.325656f,0.00149803f,0.140516f},{0.325978f,0.000793813f,0.140672f}, +{0.326085f,1.80082e-018f,0.126571f},{0.326085f,-2.12873e-008f,0.140816f},{0.322419f,0.00265777f,0.126571f}, +{0.322139f,0.00255964f,0.139937f},{0.321638f,0.00225612f,0.126571f},{0.321021f,0.00163414f,0.126571f}, +{0.321467f,0.00212367f,0.13993f},{0.320631f,0.000869207f,0.126571f},{0.320933f,0.00151779f,0.13996f}, +{0.320598f,0.000793595f,0.140023f},{0.320492f,2.70028e-018f,0.126571f},{0.320492f,2.70028e-018f,0.140116f}, +{0.280923f,0.00226719f,0.126571f},{0.280167f,0.00266113f,0.140699f},{0.280949f,0.00225617f,0.140543f}, +{0.280145f,0.00266037f,0.126571f},{0.281545f,0.00165072f,0.126571f},{0.281516f,0.00161123f,0.140389f}, +{0.281946f,0.000869207f,0.126571f},{0.281954f,0.000861428f,0.140241f},{0.279308f,0.00279699f,0.140836f}, +{0.282085f,2.26626e-008f,0.140116f},{0.282085f,1.19474e-017f,0.126571f},{0.279289f,0.00279661f,0.126571f}, +{0.278435f,0.00267244f,0.140943f},{0.277655f,0.00227523f,0.141f},{0.278419f,0.00265777f,0.126571f}, +{0.277638f,0.00225612f,0.126571f},{0.277026f,0.00164828f,0.140998f},{0.277021f,0.00163414f,0.126571f}, +{0.276631f,0.000869207f,0.126571f},{0.276622f,0.000867575f,0.140935f},{0.276492f,1.16049e-017f,0.126571f}, +{0.276492f,1.16049e-017f,0.140816f},{0.301289f,-0.00279661f,0.135893f},{0.302145f,-0.00266037f,0.126571f}, +{0.299654f,-0.00226719f,0.135893f},{0.300419f,-0.00265777f,0.126571f},{0.299638f,-0.00225612f,0.126571f}, +{0.300432f,-0.00266037f,0.135893f},{0.299032f,-0.00165072f,0.135893f},{0.298631f,-0.000869207f,0.126571f}, +{0.298492f,3.04276e-018f,0.135893f},{0.298631f,-0.000869207f,0.135893f},{0.299021f,-0.00163414f,0.126571f}, +{0.298492f,3.04276e-018f,0.126571f},{0.302158f,-0.00265777f,0.135893f},{0.302923f,-0.00226719f,0.126571f}, +{0.302939f,-0.00225612f,0.135893f},{0.303556f,-0.00163414f,0.135893f},{0.303545f,-0.00165072f,0.126571f}, +{0.303946f,-0.000869207f,0.135893f},{0.303946f,-0.000869207f,0.126571f},{0.304085f,2.70028e-018f,0.126571f}, +{0.304085f,2.70028e-018f,0.135893f},{0.303941f,0.00383933f,0.139404f},{0.302938f,0.00435933f,0.126571f}, +{0.302948f,0.00437081f,0.13941f},{0.301847f,0.00462728f,0.126571f},{0.303934f,0.00383758f,0.126571f}, +{0.301857f,0.00463064f,0.139439f},{0.304774f,0.00309444f,0.126571f},{0.304783f,0.00308762f,0.139422f}, +{0.305414f,0.00216892f,0.126571f},{0.300727f,0.00463006f,0.139484f},{0.30543f,0.00216891f,0.139458f}, +{0.305813f,0.00111911f,0.126571f},{0.30595f,5.60073e-014f,0.139555f},{0.305949f,3.35892e-010f,0.126571f}, +{0.305823f,0.00112174f,0.139506f},{0.300724f,0.00462657f,0.126571f},{0.299633f,0.00435716f,0.126571f}, +{0.299631f,0.00437228f,0.139533f},{0.298643f,0.00384698f,0.139577f},{0.298638f,0.0038338f,0.126571f}, +{0.297798f,0.00308862f,0.126571f},{0.2978f,0.00309221f,0.139605f},{0.29716f,0.00216381f,0.126571f}, +{0.297151f,0.00217168f,0.139611f},{0.296754f,0.00112329f,0.139593f},{0.296763f,0.00111503f,0.126571f}, +{0.296628f,2.70028e-018f,0.139555f},{0.296628f,2.70028e-018f,0.126571f},{0.333784f,0.0031834f,0.140987f}, +{0.333871f,-0.0034311f,0.142326f},{0.329361f,0.00348389f,0.140521f},{0.321833f,-0.013311f,0.141175f}, +{0.321483f,-0.00749864f,0.140959f},{0.325857f,-0.01447f,0.142053f},{0.334598f,-0.0237151f,0.144174f}, +{0.334046f,-0.0168317f,0.143863f},{0.338577f,-0.0250351f,0.145188f},{0.304777f,-0.00309212f,0.139605f}, +{0.308789f,-0.00980991f,0.139511f},{0.303935f,-0.00384705f,0.139577f},{0.320598f,-0.000788852f,0.140229f}, +{0.320971f,-0.00148198f,0.140362f},{0.316843f,-0.00113058f,0.139807f},{0.299629f,-0.00437081f,0.13941f}, +{0.30072f,-0.00463066f,0.139439f},{0.299868f,-0.00734722f,0.139167f},{0.293803f,0.00981015f,0.139524f}, +{0.298637f,-0.00383936f,0.139404f},{0.297795f,-0.0030876f,0.139422f},{0.29484f,-0.000835134f,0.139471f}, +{0.289735f,0.00565577f,0.139774f},{0.294321f,0.00448849f,0.13965f},{0.281978f,-0.000794809f,0.140023f}, +{0.286162f,-0.00431412f,0.13904f},{0.281642f,-0.00152033f,0.13996f},{0.268522f,0.0168309f,0.143864f}, +{0.264f,0.0250351f,0.145188f},{0.26798f,0.0237151f,0.144174f},{0.289229f,0.0110109f,0.139773f}, +{0.272859f,0.00922726f,0.1425f},{0.271923f,0.0222833f,0.143172f},{0.272684f,0.0156491f,0.142944f}, +{0.273206f,-0.00348559f,0.14052f},{0.273034f,0.00283697f,0.14169f},{0.276599f,-0.000793378f,0.140672f}, +{0.268783f,-0.00318417f,0.140986f},{0.268697f,0.00342276f,0.142324f},{0.268311f,-0.00969325f,0.139307f}, +{0.264f,-0.00290707f,0.141403f},{0.264f,0.00398877f,0.142946f},{0.264f,-0.00968775f,0.139474f}, +{0.277496f,-0.00378729f,0.140033f},{0.277448f,-0.00209478f,0.140352f},{0.278103f,-0.00253473f,0.140202f}, +{0.26861f,0.010107f,0.143286f},{0.278874f,-0.00272118f,0.140084f},{0.281218f,-0.00973119f,0.138395f}, +{0.281779f,-0.00404127f,0.13952f},{0.304265f,-0.00858894f,0.139339f},{0.312352f,-0.000322559f,0.13946f}, +{0.307227f,0.00611166f,0.138973f},{0.311852f,0.0049946f,0.138851f},{0.30271f,0.00734676f,0.139167f}, +{0.302947f,-0.0043723f,0.139533f},{0.320788f,0.00405908f,0.139532f},{0.316411f,0.00435339f,0.139066f}, +{0.305426f,-0.00217165f,0.139611f},{0.308268f,-0.00450063f,0.139635f},{0.322112f,-0.00253786f,0.140643f}, +{0.322873f,-0.00276739f,0.140776f},{0.325595f,-0.00835592f,0.141728f},{0.324441f,-0.00255847f,0.140971f}, +{0.325113f,-0.00212169f,0.141005f},{0.326719f,-0.0208182f,0.142186f},{0.338577f,-0.00398877f,0.142946f}, +{0.329883f,-0.0156505f,0.142943f},{0.338577f,0.00968775f,0.139474f},{0.338577f,0.00290707f,0.141403f}, +{0.334267f,0.00969325f,0.139307f},{0.321359f,0.00973122f,0.138395f},{0.32566f,0.00972934f,0.138727f}, +{0.325074f,0.00378494f,0.140033f},{0.317712f,-0.0121774f,0.140344f},{0.317277f,-0.00665136f,0.140233f}, +{0.307746f,0.000816648f,0.139456f},{0.323672f,-0.0027728f,0.14089f},{0.333958f,-0.0101155f,0.143286f}, +{0.338577f,-0.0179944f,0.144842f},{0.330654f,-0.0222833f,0.143172f},{0.338577f,-0.0109671f,0.144094f}, +{0.329962f,0.0097173f,0.139038f},{0.317058f,0.0097497f,0.138081f},{0.298313f,0.00858896f,0.139339f}, +{0.295355f,-0.00613049f,0.138989f},{0.285728f,0.00115281f,0.13978f},{0.290743f,-0.00500873f,0.138859f}, +{0.298192f,-0.0120097f,0.138358f},{0.294038f,-0.0108714f,0.138063f},{0.30185f,-0.00463004f,0.139484f}, +{0.30234f,-0.0131607f,0.138632f},{0.306481f,-0.0143354f,0.138904f},{0.312855f,-0.00566917f,0.139765f}, +{0.313358f,-0.0110148f,0.139763f},{0.312766f,0.0100181f,0.137915f},{0.308539f,0.0108714f,0.138063f}, +{0.304385f,0.0120097f,0.138358f},{0.300237f,0.0131607f,0.138632f},{0.296096f,0.0143354f,0.138904f}, +{0.285291f,0.00666271f,0.140207f},{0.281083f,0.00749967f,0.140947f},{0.279664f,-0.00277232f,0.139987f}, +{0.276917f,-0.00972932f,0.138727f},{0.276921f,-0.00149718f,0.140516f},{0.284854f,0.0121843f,0.140319f}, +{0.280437f,-0.00255887f,0.139937f},{0.28111f,-0.00212359f,0.13993f},{0.290241f,0.000305779f,0.139469f}, +{0.296754f,-0.00112176f,0.139506f},{0.297147f,-0.00216894f,0.139458f},{0.280732f,0.0133136f,0.141164f}, +{0.276975f,0.00834704f,0.141728f},{0.276713f,0.0144683f,0.142054f},{0.329534f,-0.0028458f,0.141692f}, +{0.329708f,-0.0092361f,0.1425f},{0.325643f,-0.00151619f,0.140991f},{0.325978f,-0.00079021f,0.140927f}, +{0.322781f,-0.019351f,0.141212f},{0.318817f,-0.0179262f,0.140278f},{0.314771f,-0.0166178f,0.139577f}, +{0.321454f,-0.00210151f,0.140501f},{0.305823f,-0.00112326f,0.139593f},{0.310634f,-0.0154659f,0.139188f}, +{0.289811f,-0.0100181f,0.137915f},{0.291943f,0.0154659f,0.139188f},{0.285519f,-0.00974966f,0.138081f}, +{0.28376f,0.0179262f,0.140277f},{0.287806f,0.0166178f,0.139577f},{0.279796f,0.0193511f,0.141212f}, +{0.275858f,0.0208182f,0.142186f},{0.272615f,-0.00971729f,0.139038f},{0.264f,0.0179944f,0.144842f}, +{0.264f,0.0109671f,0.144094f},{0.338577f,-0.0262081f,0.147306f},{0.334844f,-0.0248064f,0.146267f}, +{0.334839f,-0.0250058f,0.145834f},{0.331143f,-0.0233183f,0.145233f},{0.331138f,-0.0235291f,0.144807f}, +{0.320025f,-0.0188229f,0.142233f},{0.320019f,-0.0190695f,0.141834f},{0.323745f,-0.0203019f,0.143206f}, +{0.32374f,-0.0205368f,0.142798f},{0.32744f,-0.022035f,0.143797f},{0.327445f,-0.0218112f,0.144215f}, +{0.308407f,-0.015307f,0.140187f},{0.308412f,-0.0150041f,0.140585f},{0.304471f,-0.0141429f,0.139901f}, +{0.316248f,-0.0174212f,0.141368f},{0.312356f,-0.0161629f,0.140879f},{0.312351f,-0.0164424f,0.140484f}, +{0.296614f,-0.0114006f,0.139778f},{0.29265f,-0.0106866f,0.139078f},{0.296607f,-0.0117799f,0.13935f}, +{0.300553f,-0.0125814f,0.140047f},{0.300542f,-0.0129503f,0.139627f},{0.30448f,-0.0138012f,0.140314f}, +{0.280413f,-0.00963024f,0.139594f},{0.284511f,-0.00968708f,0.139236f},{0.284522f,-0.0091952f,0.139717f}, +{0.288611f,-0.0099197f,0.139001f},{0.292663f,-0.0102596f,0.139509f},{0.288623f,-0.00946264f,0.13945f}, +{0.280421f,-0.00907526f,0.140098f},{0.276313f,-0.0095489f,0.139944f},{0.27632f,-0.00894343f,0.140481f}, +{0.272213f,-0.00945311f,0.140271f},{0.268109f,-0.00933687f,0.140548f},{0.272217f,-0.00879579f,0.140841f}, +{0.268112f,-0.0086246f,0.141156f},{0.264f,-0.00922107f,0.140732f},{0.264f,-0.00845004f,0.141369f}, +{0.316239f,-0.0176856f,0.140989f},{0.338577f,-0.0263793f,0.14687f},{0.338577f,-0.0259023f,0.147661f}, +{0.334843f,-0.0244885f,0.146625f},{0.33114f,-0.0229936f,0.14559f},{0.320015f,-0.0184899f,0.142579f}, +{0.32744f,-0.0214828f,0.144569f},{0.3084f,-0.0146321f,0.140948f},{0.316236f,-0.0170843f,0.141711f}, +{0.312343f,-0.0158117f,0.14123f},{0.296605f,-0.010968f,0.14018f},{0.300543f,-0.0121699f,0.140436f}, +{0.304469f,-0.0134094f,0.140689f},{0.284517f,-0.0086637f,0.140175f},{0.292656f,-0.00980481f,0.139924f}, +{0.288617f,-0.00897481f,0.139881f},{0.280417f,-0.00849863f,0.14059f},{0.276317f,-0.00832061f,0.141007f}, +{0.272215f,-0.00812583f,0.141403f},{0.268111f,-0.00790535f,0.141755f},{0.264f,-0.00767878f,0.142006f}, +{0.323738f,-0.0199715f,0.143557f},{0.338577f,-0.0254953f,0.147896f},{0.334632f,-0.0239945f,0.146815f}, +{0.330719f,-0.0224149f,0.145732f},{0.318949f,-0.0176882f,0.14257f},{0.326809f,-0.0208215f,0.14466f}, +{0.322894f,-0.0192329f,0.143596f},{0.306623f,-0.0136618f,0.141149f},{0.314913f,-0.0162503f,0.141808f}, +{0.310777f,-0.0149457f,0.141414f},{0.289947f,-0.00869072f,0.140254f},{0.294176f,-0.00973903f,0.140373f}, +{0.29833f,-0.0110356f,0.140649f},{0.281312f,-0.00795144f,0.140963f},{0.285636f,-0.0081943f,0.140508f}, +{0.276988f,-0.00772122f,0.141446f},{0.272663f,-0.00747253f,0.14191f},{0.268336f,-0.00719397f,0.142331f}, +{0.264f,-0.00690556f,0.142645f},{0.302479f,-0.0123399f,0.140899f},{0.338577f,-0.0250324f,0.147984f}, +{0.334606f,-0.0235306f,0.146925f},{0.330688f,-0.0219498f,0.145862f},{0.318889f,-0.0172517f,0.142779f}, +{0.326769f,-0.0203651f,0.144808f},{0.306566f,-0.0132021f,0.1414f},{0.314858f,-0.0158114f,0.141995f}, +{0.310726f,-0.0144807f,0.141612f},{0.29412f,-0.0092687f,0.140734f},{0.298278f,-0.0105497f,0.140954f}, +{0.30242f,-0.0118813f,0.141174f},{0.28128f,-0.0073368f,0.141392f},{0.285604f,-0.00759572f,0.140879f}, +{0.289904f,-0.00819435f,0.140634f},{0.276964f,-0.00708183f,0.141934f},{0.272648f,-0.00678804f,0.142445f}, +{0.268328f,-0.00646507f,0.142911f},{0.264f,-0.00613003f,0.143285f},{0.322844f,-0.0187868f,0.143765f}, +{0.276283f,-0.00696068f,0.142073f},{0.272193f,-0.00667554f,0.142559f},{0.268101f,-0.00636198f,0.143007f}, +{0.284462f,-0.00748015f,0.141066f},{0.288553f,-0.00786981f,0.140699f},{0.280372f,-0.00722771f,0.141568f}, +{0.300465f,-0.0111819f,0.141102f},{0.292584f,-0.00875236f,0.140687f},{0.312256f,-0.014914f,0.141754f}, +{0.304388f,-0.0124511f,0.141309f},{0.308316f,-0.0137038f,0.141521f},{0.319944f,-0.0175985f,0.14304f}, +{0.323681f,-0.0190677f,0.143996f},{0.316153f,-0.0162018f,0.142196f},{0.327398f,-0.0205663f,0.144987f}, +{0.331113f,-0.022067f,0.145984f},{0.33483f,-0.0235578f,0.146988f},{0.29653f,-0.00994863f,0.140894f}, +{0.264f,-0.00603944f,0.14336f},{0.330122f,-0.00744254f,0.145062f},{0.334273f,-0.015865f,0.146599f}, +{0.334181f,-0.0083666f,0.145857f},{0.329939f,-0.000311244f,0.144002f},{0.334089f,-0.000930332f,0.144641f}, +{0.330384f,0.00667554f,0.142559f},{0.338577f,-0.00158091f,0.14525f},{0.334477f,0.0063617f,0.143002f}, +{0.338577f,-0.00932143f,0.146656f},{0.338577f,0.00603944f,0.14336f},{0.326198f,-0.00654234f,0.144272f}, +{0.322287f,-0.00567271f,0.143483f},{0.326474f,-0.0134133f,0.144758f},{0.314708f,-0.00989537f,0.142284f}, +{0.318771f,-0.0110779f,0.142976f},{0.314167f,-0.00388505f,0.142127f},{0.322655f,-0.0122295f,0.143857f}, +{0.306074f,-0.0072715f,0.141882f},{0.301276f,-1.23849e-006f,0.14196f},{0.301855f,-0.00593214f,0.141771f}, +{0.310416f,-0.00860427f,0.141986f},{0.293337f,-0.00327255f,0.141553f},{0.288967f,-0.00211647f,0.141598f}, +{0.297083f,0.00133631f,0.141962f},{0.297661f,-0.00459153f,0.141661f},{0.268392f,0.00836678f,0.145857f}, +{0.268483f,0.00093054f,0.144641f},{0.272633f,0.000310969f,0.144002f},{0.284719f,-0.00135717f,0.142021f}, +{0.284259f,0.00485039f,0.142684f},{0.264f,0.00158091f,0.14525f},{0.276649f,-0.000284983f,0.143352f}, +{0.27245f,0.00744232f,0.145062f},{0.264f,0.0171357f,0.147569f},{0.2683f,0.0158652f,0.1466f}, +{0.280649f,-0.000835711f,0.142683f},{0.276375f,0.00654153f,0.144272f},{0.280282f,0.00568021f,0.143473f}, +{0.292762f,0.00265603f,0.141973f},{0.288426f,0.00387587f,0.142138f},{0.309833f,-0.00267273f,0.141944f}, +{0.305495f,-0.00133739f,0.14196f},{0.318311f,-0.00483092f,0.14271f},{0.330306f,-0.0146267f,0.145667f}, +{0.338577f,-0.0171357f,0.147569f},{0.326294f,0.0069607f,0.142073f},{0.325924f,0.000284018f,0.143351f}, +{0.322205f,0.00722775f,0.141568f},{0.321921f,0.000847135f,0.142693f},{0.318116f,0.00746803f,0.141057f}, +{0.317854f,0.00138663f,0.142046f},{0.314024f,0.00787057f,0.1407f},{0.313628f,0.00210321f,0.141587f}, +{0.309995f,0.00875939f,0.140692f},{0.309251f,0.00324421f,0.141524f},{0.306045f,0.00994211f,0.140894f}, +{0.267749f,0.023562f,0.146989f},{0.264f,0.0249766f,0.147983f},{0.304917f,0.00458966f,0.141659f}, +{0.302115f,0.0111906f,0.141102f},{0.298192f,0.0124586f,0.141307f},{0.300697f,0.00592971f,0.141772f}, +{0.29426f,0.0136985f,0.141523f},{0.296504f,0.00727121f,0.141884f},{0.29032f,0.0149126f,0.14175f}, +{0.292185f,0.00859914f,0.142013f},{0.286428f,0.0162055f,0.142209f},{0.287882f,0.0098903f,0.142296f}, +{0.282633f,0.0175985f,0.14304f},{0.283798f,0.0110874f,0.142952f},{0.278896f,0.0190677f,0.143996f}, +{0.279914f,0.012233f,0.143847f},{0.275179f,0.0205663f,0.144987f},{0.276098f,0.0134127f,0.144758f}, +{0.271464f,0.0220671f,0.145984f},{0.272266f,0.0146265f,0.145668f},{0.264f,0.00932143f,0.146656f}, +{0.338577f,0.00690312f,0.142647f},{0.334242f,0.00719191f,0.142327f},{0.329914f,0.00746979f,0.14191f}, +{0.316934f,0.00814762f,0.140482f},{0.325589f,0.0077197f,0.141447f},{0.321266f,0.00793083f,0.14095f}, +{0.304248f,0.0110361f,0.14065f},{0.300103f,0.0123542f,0.140896f},{0.312628f,0.00871456f,0.140273f}, +{0.308409f,0.00976951f,0.140403f},{0.28766f,0.0162476f,0.141798f},{0.291792f,0.0149252f,0.141389f}, +{0.295955f,0.0136614f,0.141149f},{0.279686f,0.0192347f,0.143604f},{0.283634f,0.0176916f,0.142602f}, +{0.27577f,0.0208212f,0.144662f},{0.271858f,0.022413f,0.145733f},{0.267947f,0.0239981f,0.146816f}, +{0.264f,0.0254927f,0.147897f},{0.338577f,0.00767576f,0.142009f},{0.334466f,0.00790232f,0.141753f}, +{0.330362f,0.00812312f,0.141405f},{0.31806f,0.00864847f,0.140168f},{0.32626f,0.00831807f,0.14101f}, +{0.32216f,0.00849626f,0.140592f},{0.30597f,0.0109591f,0.140182f},{0.313959f,0.00897354f,0.139884f}, +{0.309923f,0.00981108f,0.139931f},{0.294175f,0.0146249f,0.140952f},{0.29811f,0.0134151f,0.140688f}, +{0.302037f,0.0121769f,0.140437f},{0.282562f,0.0184881f,0.142581f},{0.290233f,0.0158082f,0.141227f}, +{0.286345f,0.0170869f,0.141725f},{0.278839f,0.0199696f,0.143558f},{0.275137f,0.0214809f,0.14457f}, +{0.271437f,0.0229915f,0.145592f},{0.267736f,0.0244911f,0.146626f},{0.264f,0.0259001f,0.147663f}, +{0.338577f,0.00844643f,0.141372f},{0.334465f,0.0086212f,0.141154f},{0.33036f,0.00879266f,0.140843f}, +{0.318055f,0.00917932f,0.139711f},{0.326258f,0.00894054f,0.140483f},{0.305961f,0.0113914f,0.139781f}, +{0.313954f,0.00946126f,0.139453f},{0.309916f,0.0102671f,0.139517f},{0.294163f,0.0149971f,0.140589f}, +{0.298099f,0.0138071f,0.140313f},{0.302027f,0.0125887f,0.140048f},{0.282552f,0.0188214f,0.142234f}, +{0.29022f,0.0161597f,0.140877f},{0.286332f,0.0174245f,0.141382f},{0.278832f,0.0203004f,0.143209f}, +{0.275132f,0.0218097f,0.144217f},{0.271434f,0.0233168f,0.145235f},{0.267735f,0.0248099f,0.146269f}, +{0.264f,0.0262067f,0.147309f},{0.322157f,0.0090726f,0.140101f},{0.338577f,0.00921688f,0.140736f}, +{0.334468f,0.00933302f,0.140551f},{0.330364f,0.00944958f,0.140274f},{0.318066f,0.00968445f,0.139239f}, +{0.326264f,0.00954568f,0.139947f},{0.30597f,0.0117779f,0.139353f},{0.313966f,0.00991732f,0.139004f}, +{0.309927f,0.0106844f,0.139081f},{0.29417f,0.0153055f,0.140189f},{0.298106f,0.0141412f,0.139904f}, +{0.302035f,0.0129485f,0.13963f},{0.282558f,0.0190685f,0.141836f},{0.286338f,0.0176844f,0.140992f}, +{0.290226f,0.016441f,0.140486f},{0.278837f,0.0205358f,0.142801f},{0.275137f,0.0220341f,0.1438f}, +{0.271439f,0.0235282f,0.14481f},{0.267738f,0.0250051f,0.145837f},{0.264f,0.0263788f,0.146873f}, +{0.322165f,0.00962732f,0.139597f},{0.334471f,0.00976429f,0.140182f},{0.338577f,0.00968775f,0.140347f}, +{0.322175f,0.00995451f,0.139285f},{0.326272f,0.00990606f,0.139616f},{0.33037f,0.00984421f,0.139924f}, +{0.309942f,0.0109184f,0.138808f},{0.318079f,0.00997907f,0.138946f},{0.29812f,0.0143137f,0.139645f}, +{0.302049f,0.01314f,0.139366f},{0.305984f,0.0119892f,0.139084f},{0.28635f,0.0178005f,0.140741f}, +{0.290239f,0.0165744f,0.140236f},{0.294183f,0.015459f,0.139935f},{0.278846f,0.0206269f,0.142536f}, +{0.282568f,0.0191718f,0.141579f},{0.275145f,0.0221132f,0.143529f},{0.271445f,0.0235942f,0.144532f}, +{0.267741f,0.0250554f,0.145553f},{0.264f,0.0264087f,0.146586f},{0.313981f,0.0101788f,0.138724f}, +{0.300099f,0.0137161f,0.139356f},{0.304248f,0.0124851f,0.13907f},{0.308413f,0.0113146f,0.138783f}, +{0.312637f,0.0103804f,0.138606f},{0.316945f,0.00997452f,0.138733f},{0.321273f,0.00994023f,0.13908f}, +{0.325595f,0.00991203f,0.139443f},{0.329918f,0.009849f,0.139773f},{0.334245f,0.00976769f,0.140054f}, +{0.338577f,0.00968775f,0.140237f},{0.295949f,0.014938f,0.139648f},{0.291782f,0.0161103f,0.139931f}, +{0.28765f,0.0173564f,0.140361f},{0.283628f,0.0187613f,0.141145f},{0.279684f,0.0202782f,0.142115f}, +{0.275771f,0.021842f,0.143141f},{0.271863f,0.0234057f,0.144181f},{0.267952f,0.024951f,0.14524f}, +{0.264f,0.0263814f,0.146312f},{0.333995f,0.00976336f,0.139842f},{0.338577f,0.00968775f,0.140047f}, +{0.320276f,0.00990978f,0.138791f},{0.324847f,0.00989796f,0.139181f},{0.329419f,0.00983969f,0.139537f}, +{0.311162f,0.0106101f,0.138427f},{0.306724f,0.0117247f,0.138676f},{0.315696f,0.00998742f,0.138455f}, +{0.297936f,0.0142908f,0.139261f},{0.293533f,0.0155467f,0.139552f},{0.302325f,0.0129908f,0.13897f}, +{0.280636f,0.0197978f,0.141555f},{0.284834f,0.0182285f,0.140588f},{0.289136f,0.0168071f,0.139904f}, +{0.276483f,0.0214356f,0.142606f},{0.272338f,0.0230806f,0.143678f},{0.268191f,0.0247084f,0.144769f}, +{0.264f,0.0262125f,0.145873f},{0.334001f,0.00974593f,0.13965f},{0.338577f,0.00968775f,0.139856f}, +{0.3203f,0.00985594f,0.138605f},{0.324865f,0.00985469f,0.138992f},{0.329431f,0.00980831f,0.139346f}, +{0.30676f,0.0116247f,0.138477f},{0.315727f,0.00992109f,0.13827f},{0.297975f,0.0141594f,0.139045f}, +{0.293574f,0.0154002f,0.139327f},{0.302362f,0.0128748f,0.138762f},{0.280668f,0.0195912f,0.141282f}, +{0.284873f,0.0180446f,0.140336f},{0.289177f,0.0166436f,0.139669f},{0.276508f,0.021206f,0.142313f}, +{0.272355f,0.0228275f,0.143363f},{0.268199f,0.0244304f,0.144433f},{0.264f,0.0259067f,0.145514f}, +{0.311196f,0.0105278f,0.138237f},{0.334008f,0.00972275f,0.139465f},{0.338577f,0.00968775f,0.139665f}, +{0.320325f,0.00978412f,0.13844f},{0.324884f,0.0097971f,0.13882f},{0.329444f,0.00976655f,0.139166f}, +{0.311232f,0.0104201f,0.138077f},{0.306797f,0.0114944f,0.138315f},{0.315758f,0.00983335f,0.13811f}, +{0.298014f,0.013988f,0.138879f},{0.293615f,0.0152086f,0.139158f},{0.3024f,0.0127235f,0.138598f}, +{0.280701f,0.01932f,0.14109f},{0.284911f,0.017804f,0.140155f},{0.289219f,0.0164298f,0.139496f}, +{0.276533f,0.0209031f,0.142109f},{0.272372f,0.0224922f,0.143148f},{0.268208f,0.0240607f,0.144207f}, +{0.264f,0.0254987f,0.145277f},{0.334373f,-0.0240512f,0.144207f},{0.338577f,-0.0254987f,0.145277f}, +{0.326047f,-0.0208987f,0.142106f},{0.330206f,-0.0224907f,0.143149f},{0.313354f,-0.0164319f,0.139508f}, +{0.308957f,-0.015224f,0.139169f},{0.317674f,-0.0177924f,0.140121f},{0.300179f,-0.0127141f,0.138599f}, +{0.295784f,-0.0114783f,0.1383f},{0.304565f,-0.0139803f,0.138881f},{0.282253f,-0.00981234f,0.138457f}, +{0.286812f,-0.00988648f,0.138137f},{0.291345f,-0.0103884f,0.138061f},{0.277693f,-0.00979575f,0.138821f}, +{0.273133f,-0.00976673f,0.139168f},{0.26857f,-0.00972076f,0.139471f},{0.264f,-0.00968775f,0.139665f}, +{0.32188f,-0.0193145f,0.141081f},{0.334381f,-0.0244211f,0.144433f},{0.338577f,-0.0259067f,0.145514f}, +{0.321913f,-0.0195856f,0.141274f},{0.326071f,-0.0212016f,0.14231f},{0.330223f,-0.0228261f,0.143364f}, +{0.313395f,-0.016646f,0.139681f},{0.308997f,-0.0154158f,0.139338f},{0.317712f,-0.0180326f,0.140302f}, +{0.295821f,-0.0116084f,0.138462f},{0.300217f,-0.0128655f,0.138763f},{0.304604f,-0.0141518f,0.139047f}, +{0.282278f,-0.0098846f,0.138622f},{0.286844f,-0.0099743f,0.138297f},{0.29138f,-0.0104962f,0.13822f}, +{0.277712f,-0.00985341f,0.138994f},{0.273146f,-0.00980859f,0.139347f},{0.268576f,-0.0097442f,0.139657f}, +{0.264f,-0.00968775f,0.139856f},{0.33439f,-0.0246992f,0.144769f},{0.338577f,-0.0262125f,0.145873f}, +{0.321945f,-0.019792f,0.141546f},{0.326096f,-0.0214312f,0.142603f},{0.33024f,-0.0230793f,0.143679f}, +{0.309038f,-0.0155626f,0.139563f},{0.317751f,-0.0182163f,0.140554f},{0.295857f,-0.0117083f,0.13866f}, +{0.300255f,-0.0129816f,0.138971f},{0.304643f,-0.0142832f,0.139263f},{0.282302f,-0.00993888f,0.138809f}, +{0.286874f,-0.0100406f,0.138482f},{0.291414f,-0.0105787f,0.13841f},{0.27773f,-0.00989672f,0.139183f}, +{0.273158f,-0.00984006f,0.139539f},{0.268582f,-0.00976183f,0.139849f},{0.264f,-0.00968775f,0.140047f}, +{0.313436f,-0.0168098f,0.139917f},{0.338577f,-0.0264087f,0.146586f},{0.327432f,-0.0221132f,0.143529f}, +{0.331132f,-0.0235942f,0.144532f},{0.334836f,-0.0250554f,0.145553f},{0.316228f,-0.0178005f,0.140741f}, +{0.312338f,-0.0165745f,0.140236f},{0.323731f,-0.0206269f,0.142536f},{0.320009f,-0.0191717f,0.141579f}, +{0.300528f,-0.01314f,0.139366f},{0.304457f,-0.0143137f,0.139645f},{0.308394f,-0.015459f,0.139935f}, +{0.288596f,-0.0101788f,0.138724f},{0.292635f,-0.0109184f,0.138808f},{0.296593f,-0.0119892f,0.139084f}, +{0.280402f,-0.00995447f,0.139285f},{0.284498f,-0.00997902f,0.138946f},{0.276306f,-0.00990604f,0.139616f}, +{0.272207f,-0.0098442f,0.139924f},{0.268106f,-0.00976429f,0.140182f},{0.264f,-0.00968775f,0.140347f}, +{0.334628f,-0.0249437f,0.145241f},{0.338577f,-0.0263814f,0.146312f},{0.322896f,-0.0202741f,0.142109f}, +{0.326807f,-0.0218394f,0.143139f},{0.330715f,-0.023405f,0.144181f},{0.314923f,-0.0173571f,0.14037f}, +{0.310786f,-0.0161317f,0.139953f},{0.318956f,-0.0187523f,0.141118f},{0.302483f,-0.0136985f,0.13936f}, +{0.29833f,-0.0124827f,0.139069f},{0.306629f,-0.0149357f,0.139649f},{0.289937f,-0.010352f,0.138591f}, +{0.294173f,-0.0112762f,0.138755f},{0.281305f,-0.00995919f,0.139092f},{0.285627f,-0.010024f,0.138759f}, +{0.276982f,-0.00991129f,0.139444f},{0.272659f,-0.00984923f,0.139775f},{0.264f,-0.00968775f,0.140237f}, +{0.268333f,-0.00976681f,0.14006f},{0.489193f,0.00379135f,0.143971f},{0.488833f,0.00496458f,0.143658f}, +{0.489314f,-0.00742307f,0.146358f},{0.489314f,0.00257039f,0.144284f},{0.48825f,0.00603944f,0.14336f}, +{0.489314f,-0.00240499f,0.145424f},{0.387061f,-0.0211541f,0.147844f},{0.435444f,-0.0173396f,0.147586f}, +{0.483726f,-0.013533f,0.147211f},{0.485008f,-0.0132893f,0.147183f},{0.4862f,-0.0127783f,0.147122f}, +{0.487256f,-0.0120253f,0.147029f},{0.488129f,-0.0110634f,0.146904f},{0.488778f,-0.00994277f,0.146747f}, +{0.489179f,-0.00870927f,0.146564f},{0.489052f,-0.0123416f,0.144272f},{0.489962f,-0.0109102f,0.144086f}, +{0.487844f,-0.0135295f,0.144414f},{0.450527f,-0.0164058f,0.144708f},{0.413211f,-0.0192822f,0.144935f}, +{0.375894f,-0.0221586f,0.145095f},{0.490523f,-0.00932212f,0.14386f},{0.490713f,-0.00765064f,0.143599f}, +{0.483255f,0.00968775f,0.139474f},{0.484944f,0.00949318f,0.139536f},{0.48999f,0.00543154f,0.140734f}, +{0.49053f,0.00387196f,0.141154f},{0.486539f,0.00892517f,0.139713f},{0.487952f,0.0080214f,0.139987f}, +{0.489121f,0.00683431f,0.140337f},{0.490713f,0.00223012f,0.141572f},{0.483255f,0.00968775f,0.140347f}, +{0.490713f,-0.00268915f,0.144055f},{0.490713f,0.00223012f,0.142928f},{0.490713f,-0.00765064f,0.144979f}, +{0.486568f,-0.0143331f,0.144707f},{0.485411f,-0.0147899f,0.145794f},{0.48523f,-0.0148426f,0.145225f}, +{0.483834f,-0.0150857f,0.145821f},{0.486874f,-0.014171f,0.145734f},{0.488177f,-0.0132538f,0.145642f}, +{0.489249f,-0.0120868f,0.145518f},{0.490052f,-0.0107201f,0.145364f},{0.490545f,-0.00921907f,0.145182f}, +{0.48779f,0.00815064f,0.141617f},{0.489024f,0.00695586f,0.141898f},{0.490519f,0.00391721f,0.142576f}, +{0.489946f,0.00552233f,0.142225f},{0.486401f,0.0089918f,0.140922f},{0.484871f,0.00951028f,0.140494f}, +{0.488748f,0.00632699f,0.143123f},{0.488788f,0.0068323f,0.142705f},{0.488576f,0.00732043f,0.142302f}, +{0.48823f,0.00776225f,0.141937f},{0.374892f,-0.0235779f,0.146493f},{0.386398f,-0.0219204f,0.147693f}, +{0.38644f,-0.0224876f,0.147153f},{0.44752f,-0.0179164f,0.146111f},{0.483831f,-0.0149745f,0.146368f}, +{0.435152f,-0.0186837f,0.146909f},{0.483769f,-0.0140869f,0.147162f},{0.435109f,-0.0180963f,0.147451f}, +{0.483807f,-0.0146193f,0.146864f},{0.411206f,-0.0207472f,0.146335f},{0.490303f,-0.00748972f,0.145954f}, +{0.490142f,-0.00897658f,0.146183f},{0.490461f,-0.00911758f,0.145712f},{0.48969f,-0.0103998f,0.146379f}, +{0.489201f,-0.0119652f,0.146066f},{0.489986f,-0.0106014f,0.145903f},{0.48793f,-0.0128307f,0.14668f}, +{0.486857f,-0.0140507f,0.146292f},{0.488142f,-0.0131339f,0.146196f},{0.485398f,-0.0146743f,0.146354f}, +{0.487626f,-0.0124497f,0.14697f},{0.488574f,-0.0113986f,0.146838f},{0.485172f,-0.0138348f,0.147131f}, +{0.485306f,-0.0143101f,0.146843f},{0.486476f,-0.013274f,0.147068f},{0.489829f,-0.00743905f,0.146261f}, +{0.489704f,-0.00883688f,0.146478f},{0.490614f,-0.00756687f,0.145487f},{0.489277f,-0.0101719f,0.146672f}, +{0.486701f,-0.0137111f,0.146779f},{0.488941f,-0.0117086f,0.146547f},{0.490504f,-0.00254212f,0.144763f}, +{0.490038f,-0.0024474f,0.14522f},{0.490529f,0.00239822f,0.143598f},{0.489991f,0.00252701f,0.144111f}, +{0.490287f,0.00405957f,0.143247f},{0.489296f,0.00550952f,0.143326f},{0.489714f,0.00559184f,0.142876f}, +{0.489834f,0.00407172f,0.143698f},{0.375478f,-0.022887f,0.145323f},{0.375514f,-0.0233314f,0.145788f}, +{0.451096f,-0.0174497f,0.145407f},{0.413325f,-0.0203893f,0.145633f},{0.413289f,-0.0199559f,0.14517f}, +{0.45106f,-0.0170273f,0.144947f},{0.113525f,0.0123416f,0.144272f},{0.112615f,0.0109102f,0.144086f}, +{0.114734f,0.0135295f,0.144414f},{0.15205f,0.0164058f,0.144708f},{0.189366f,0.0192822f,0.144935f}, +{0.226683f,0.0221586f,0.145095f},{0.112054f,0.00932212f,0.14386f},{0.111865f,0.00765064f,0.143599f}, +{0.119322f,-0.00968775f,0.139474f},{0.117633f,-0.00949318f,0.139536f},{0.112587f,-0.00543154f,0.140734f}, +{0.112048f,-0.00387196f,0.141154f},{0.116038f,-0.00892517f,0.139713f},{0.114625f,-0.0080214f,0.139987f}, +{0.113456f,-0.00683431f,0.140337f},{0.111865f,-0.00223012f,0.141572f},{0.113384f,-0.00379135f,0.143971f}, +{0.113745f,-0.00496458f,0.143658f},{0.113263f,0.00742307f,0.146358f},{0.113263f,-0.00257039f,0.144284f}, +{0.114327f,-0.00603944f,0.14336f},{0.113263f,0.00240499f,0.145424f},{0.215517f,0.0211541f,0.147844f}, +{0.167133f,0.0173396f,0.147586f},{0.118851f,0.013533f,0.147211f},{0.117576f,0.0132913f,0.147183f}, +{0.116383f,0.0127821f,0.147123f},{0.115326f,0.0120287f,0.14703f},{0.114453f,0.0110706f,0.146905f}, +{0.113801f,0.00994698f,0.146748f},{0.1134f,0.00871793f,0.146565f},{0.119322f,-0.00968775f,0.140347f}, +{0.111865f,0.00268915f,0.144055f},{0.111865f,0.00765064f,0.144979f},{0.111865f,-0.00223012f,0.142928f}, +{0.116009f,0.0143331f,0.144707f},{0.117177f,0.014793f,0.145794f},{0.117347f,0.0148426f,0.145225f}, +{0.118743f,0.0150857f,0.145821f},{0.115708f,0.014174f,0.145734f},{0.114409f,0.0132606f,0.145643f}, +{0.113332f,0.0120925f,0.145519f},{0.112529f,0.0107278f,0.145364f},{0.112033f,0.00922792f,0.145183f}, +{0.114787f,-0.00815064f,0.141617f},{0.113553f,-0.00695586f,0.141898f},{0.112631f,-0.00552233f,0.142225f}, +{0.112058f,-0.00391721f,0.142576f},{0.116176f,-0.0089918f,0.140922f},{0.117706f,-0.00951028f,0.140494f}, +{0.113789f,-0.0068323f,0.142705f},{0.113829f,-0.00632699f,0.143123f},{0.114001f,-0.00732043f,0.142302f}, +{0.114347f,-0.00776225f,0.141937f},{0.227685f,0.0235779f,0.146493f},{0.216179f,0.0219204f,0.147693f}, +{0.216137f,0.0224876f,0.147153f},{0.155057f,0.0179164f,0.146111f},{0.118746f,0.0149745f,0.146368f}, +{0.167425f,0.0186837f,0.146909f},{0.118809f,0.0140869f,0.147162f},{0.167468f,0.0180963f,0.147451f}, +{0.11877f,0.0146193f,0.146864f},{0.191371f,0.0207472f,0.146335f},{0.115882f,0.0137517f,0.146749f}, +{0.117415f,0.013838f,0.147132f},{0.117273f,0.0143462f,0.146813f},{0.11445f,0.0131473f,0.146196f}, +{0.115741f,0.0140617f,0.146292f},{0.11719f,0.0146779f,0.146354f},{0.113307f,0.0101903f,0.146674f}, +{0.114012f,0.0114133f,0.146839f},{0.11241f,0.00899738f,0.146157f},{0.111963f,0.00756687f,0.145487f}, +{0.112274f,0.00748972f,0.145954f},{0.112599f,0.0106218f,0.145905f},{0.113386f,0.0119815f,0.146067f}, +{0.112119f,0.00912889f,0.145714f},{0.112869f,0.0104352f,0.146353f},{0.112875f,0.00884706f,0.146479f}, +{0.114643f,0.0128697f,0.146651f},{0.116119f,0.0132839f,0.147069f},{0.112748f,0.00743905f,0.146261f}, +{0.114964f,0.0124617f,0.146971f},{0.113623f,0.0117456f,0.146519f},{0.112073f,0.00254212f,0.144763f}, +{0.112539f,0.0024474f,0.14522f},{0.112048f,-0.00239822f,0.143598f},{0.112586f,-0.00252701f,0.144111f}, +{0.11229f,-0.00405957f,0.143247f},{0.113281f,-0.00550952f,0.143326f},{0.112863f,-0.00559184f,0.142876f}, +{0.112743f,-0.00407172f,0.143698f},{0.227063f,0.0233314f,0.145788f},{0.227099f,0.022887f,0.145323f}, +{0.151517f,0.0170273f,0.144947f},{0.151481f,0.0174497f,0.145407f},{0.189252f,0.0203893f,0.145633f}, +{0.189288f,0.0199559f,0.14517f},{0.302945f,-0.0043568f,0.126571f},{0.303939f,-0.00383438f,0.126571f}, +{0.304781f,-0.00308638f,0.126571f},{0.305417f,-0.00216232f,0.126571f},{0.300729f,-0.00462734f,0.126571f}, +{0.301855f,-0.00462608f,0.126571f},{0.298645f,-0.00383806f,0.126571f},{0.299638f,-0.00435903f,0.126571f}, +{0.297801f,-0.00309213f,0.126571f},{0.297163f,-0.00216808f,0.126571f},{0.296764f,-0.00111857f,0.126571f}, +{0.305815f,-0.0011128f,0.126571f},{0.303613f,0.00150163f,0.126571f},{0.303967f,0.000787374f,0.126571f}, +{0.303117f,0.00211724f,0.126571f},{0.302447f,0.00254559f,0.126571f},{0.301683f,0.00276842f,0.126571f}, +{0.300888f,0.00276723f,0.126571f},{0.300125f,0.00254283f,0.126571f},{0.299465f,0.00210508f,0.126571f}, +{0.298949f,0.00150519f,0.126571f},{0.298603f,0.00078745f,0.126571f},{0.30013f,0.00254559f,0.135893f}, +{0.300894f,0.00276842f,0.135893f},{0.303628f,0.00150519f,0.135893f},{0.301689f,0.00276723f,0.135893f}, +{0.303112f,0.00210508f,0.135893f},{0.303974f,0.00078745f,0.135893f},{0.302452f,0.00254283f,0.135893f}, +{0.29946f,0.00211724f,0.135893f},{0.298964f,0.00150163f,0.135893f},{0.29861f,0.000787374f,0.135893f}, +{0.280158f,-0.00265777f,0.126571f},{0.280939f,-0.00225612f,0.126571f},{0.281556f,-0.00163414f,0.126571f}, +{0.278432f,-0.00266037f,0.126571f},{0.277654f,-0.00226719f,0.126571f},{0.279289f,-0.00279661f,0.126571f}, +{0.277032f,-0.00165072f,0.126571f},{0.276631f,-0.000869207f,0.126571f},{0.281946f,-0.000869207f,0.126571f}, +{0.324158f,-0.00265777f,0.126571f},{0.324939f,-0.00225612f,0.126571f},{0.325556f,-0.00163414f,0.126571f}, +{0.322432f,-0.00266037f,0.126571f},{0.323289f,-0.00279661f,0.126571f},{0.321032f,-0.00165072f,0.126571f}, +{0.321654f,-0.00226719f,0.126571f},{0.320631f,-0.000869207f,0.126571f},{0.325946f,-0.000869207f,0.126571f}, +{-0.0027207f,-0.278876f,0.141016f},{-0.00279661f,-0.279289f,0.127503f},{-0.00276223f,-0.279666f,0.140921f}, +{-0.00254178f,-0.278101f,0.141133f},{-0.00266037f,-0.278432f,0.127503f},{-0.00226719f,-0.277654f,0.127503f}, +{-0.00210085f,-0.277449f,0.141283f},{-0.000869207f,-0.276631f,0.127503f},{-0.00165072f,-0.277032f,0.127503f}, +{-0.00149803f,-0.276921f,0.141448f},{-0.000793813f,-0.276599f,0.141604f},{8.0384e-017f,-0.276492f,0.127503f}, +{2.12873e-008f,-0.276492f,0.141748f},{-0.00265777f,-0.280158f,0.127503f},{-0.00255964f,-0.280438f,0.140869f}, +{-0.00225612f,-0.280939f,0.127503f},{-0.00163414f,-0.281556f,0.127503f},{-0.00212367f,-0.28111f,0.140862f}, +{-0.000869207f,-0.281946f,0.127503f},{-0.00151779f,-0.281644f,0.140892f},{-0.000793595f,-0.281979f,0.140955f}, +{7.94845e-017f,-0.282085f,0.127503f},{7.94845e-017f,-0.282085f,0.141048f},{-0.00226719f,-0.321654f,0.127503f}, +{-0.00266113f,-0.32241f,0.141631f},{-0.00225617f,-0.321628f,0.141475f},{-0.00266037f,-0.322432f,0.127503f}, +{-0.00165072f,-0.321032f,0.127503f},{-0.00161123f,-0.321061f,0.141322f},{-0.000869207f,-0.320631f,0.127503f}, +{-0.000861428f,-0.320624f,0.141174f},{-0.00279699f,-0.323269f,0.141768f},{-2.26626e-008f,-0.320492f,0.141048f}, +{7.02374e-017f,-0.320492f,0.127503f},{-0.00279661f,-0.323289f,0.127503f},{-0.00267244f,-0.324142f,0.141876f}, +{-0.00227523f,-0.324922f,0.141932f},{-0.00265777f,-0.324158f,0.127503f},{-0.00225612f,-0.324939f,0.127503f}, +{-0.00164828f,-0.325551f,0.14193f},{-0.00163414f,-0.325556f,0.127503f},{-0.000869207f,-0.325946f,0.127503f}, +{-0.000867575f,-0.325955f,0.141868f},{7.05799e-017f,-0.326085f,0.127503f},{7.05799e-017f,-0.326085f,0.141748f}, +{0.00279661f,-0.301289f,0.136825f},{0.00266037f,-0.300432f,0.127503f},{0.00226719f,-0.302923f,0.136825f}, +{0.00265777f,-0.302158f,0.127503f},{0.00225612f,-0.302939f,0.127503f},{0.00266037f,-0.302145f,0.136825f}, +{0.00165072f,-0.303545f,0.136825f},{0.000869207f,-0.303946f,0.127503f},{7.91421e-017f,-0.304085f,0.136825f}, +{0.000869207f,-0.303946f,0.136825f},{0.00163414f,-0.303556f,0.127503f},{7.91421e-017f,-0.304085f,0.127503f}, +{0.00265777f,-0.300419f,0.136825f},{0.00226719f,-0.299654f,0.127503f},{0.00225612f,-0.299638f,0.136825f}, +{0.00163414f,-0.299021f,0.136825f},{0.00165072f,-0.299032f,0.127503f},{0.000869207f,-0.298631f,0.136825f}, +{0.000869207f,-0.298631f,0.127503f},{7.94845e-017f,-0.298492f,0.127503f},{7.94845e-017f,-0.298492f,0.136825f}, +{-0.00383933f,-0.298637f,0.140336f},{-0.00435933f,-0.299639f,0.127503f},{-0.00437081f,-0.299629f,0.140342f}, +{-0.00462728f,-0.30073f,0.127503f},{-0.00383758f,-0.298643f,0.127503f},{-0.00463064f,-0.30072f,0.140371f}, +{-0.00309444f,-0.297804f,0.127503f},{-0.00308762f,-0.297795f,0.140354f},{-0.00216892f,-0.297163f,0.127503f}, +{-0.00463006f,-0.30185f,0.140416f},{-0.00216891f,-0.297147f,0.14039f},{-0.00111911f,-0.296764f,0.127503f}, +{-5.59251e-014f,-0.296628f,0.140488f},{-3.35892e-010f,-0.296628f,0.127503f},{-0.00112174f,-0.296754f,0.140439f}, +{-0.00462657f,-0.301853f,0.127503f},{-0.00435716f,-0.302944f,0.127503f},{-0.00437228f,-0.302946f,0.140465f}, +{-0.00384698f,-0.303934f,0.140509f},{-0.0038338f,-0.303939f,0.127503f},{-0.00308862f,-0.304779f,0.127503f}, +{-0.00309221f,-0.304777f,0.140537f},{-0.00216381f,-0.305417f,0.127503f},{-0.00217168f,-0.305426f,0.140543f}, +{-0.00112329f,-0.305823f,0.140525f},{-0.00111503f,-0.305814f,0.127503f},{7.94845e-017f,-0.30595f,0.140488f}, +{7.94845e-017f,-0.30595f,0.127503f},{-0.0031834f,-0.268793f,0.141919f},{0.0034311f,-0.268706f,0.143258f}, +{-0.00348389f,-0.273216f,0.141453f},{0.013311f,-0.280744f,0.142108f},{0.00749864f,-0.281094f,0.141891f}, +{0.01447f,-0.27672f,0.142985f},{0.0237151f,-0.26798f,0.145107f},{0.0168317f,-0.268531f,0.144795f}, +{0.0250351f,-0.264f,0.14612f},{0.00309212f,-0.2978f,0.140537f},{0.00980991f,-0.293788f,0.140443f}, +{0.00384705f,-0.298643f,0.140509f},{0.000788852f,-0.281979f,0.141161f},{0.00148198f,-0.281606f,0.141294f}, +{0.00113058f,-0.285735f,0.140739f},{0.00437081f,-0.302948f,0.140342f},{0.00463066f,-0.301857f,0.140371f}, +{0.00734722f,-0.302709f,0.140099f},{-0.00981015f,-0.308774f,0.140456f},{0.00383936f,-0.30394f,0.140336f}, +{0.0030876f,-0.304783f,0.140354f},{0.000835134f,-0.307737f,0.140403f},{-0.00565577f,-0.312842f,0.140706f}, +{-0.00448849f,-0.308256f,0.140582f},{0.000794809f,-0.320599f,0.140955f},{0.00431412f,-0.316415f,0.139973f}, +{0.00152033f,-0.320936f,0.140892f},{-0.0168309f,-0.334055f,0.144796f},{-0.0250351f,-0.338577f,0.14612f}, +{-0.0237151f,-0.334598f,0.145107f},{-0.0110109f,-0.313348f,0.140705f},{-0.00922726f,-0.329718f,0.143432f}, +{-0.0222833f,-0.330654f,0.144104f},{-0.0156491f,-0.329893f,0.143876f},{0.00348559f,-0.329371f,0.141452f}, +{-0.00283697f,-0.329543f,0.142622f},{0.000793378f,-0.325978f,0.141605f},{0.00318417f,-0.333794f,0.141918f}, +{-0.00342276f,-0.33388f,0.143256f},{0.00969325f,-0.334267f,0.140239f},{0.00290707f,-0.338577f,0.142335f}, +{-0.00398877f,-0.338577f,0.143878f},{0.00968775f,-0.338577f,0.140407f},{0.00378729f,-0.325081f,0.140965f}, +{0.00209478f,-0.325129f,0.141284f},{0.00253473f,-0.324474f,0.141134f},{-0.010107f,-0.333967f,0.144218f}, +{0.00272118f,-0.323703f,0.141016f},{0.00973119f,-0.321359f,0.139327f},{0.00404127f,-0.320799f,0.140452f}, +{0.00858894f,-0.298312f,0.140271f},{0.000322559f,-0.290225f,0.140392f},{-0.00611166f,-0.29535f,0.139905f}, +{-0.0049946f,-0.290725f,0.139783f},{-0.00734676f,-0.299868f,0.140099f},{0.0043723f,-0.299631f,0.140465f}, +{-0.00405908f,-0.281789f,0.140464f},{-0.00435339f,-0.286166f,0.139998f},{0.00217165f,-0.297151f,0.140543f}, +{0.00450063f,-0.294309f,0.140568f},{0.00253786f,-0.280465f,0.141575f},{0.00276739f,-0.279704f,0.141709f}, +{0.00835592f,-0.276982f,0.14266f},{0.00255847f,-0.278136f,0.141903f},{0.00212169f,-0.277464f,0.141937f}, +{0.0208182f,-0.275858f,0.143118f},{0.00398877f,-0.264f,0.143878f},{0.0156505f,-0.272694f,0.143875f}, +{-0.00968775f,-0.264f,0.140407f},{-0.00290707f,-0.264f,0.142335f},{-0.00969325f,-0.268311f,0.140239f}, +{-0.00973122f,-0.281218f,0.139327f},{-0.00972934f,-0.276917f,0.139659f},{-0.00378494f,-0.277503f,0.140965f}, +{0.0121774f,-0.284865f,0.141276f},{0.00665136f,-0.2853f,0.141165f},{-0.000816648f,-0.294831f,0.140389f}, +{0.0027728f,-0.278905f,0.141822f},{0.0101155f,-0.268619f,0.144218f},{0.0179944f,-0.264f,0.145774f}, +{0.0222833f,-0.271923f,0.144104f},{0.0109671f,-0.264f,0.145026f},{-0.0097173f,-0.272615f,0.139971f}, +{-0.0097497f,-0.285519f,0.139013f},{-0.00858896f,-0.304264f,0.140271f},{0.00613049f,-0.307222f,0.139921f}, +{-0.00115281f,-0.316849f,0.140712f},{0.00500873f,-0.311834f,0.139791f},{0.0120097f,-0.304385f,0.13929f}, +{0.0108714f,-0.308539f,0.138995f},{0.00463004f,-0.300727f,0.140416f},{0.0131607f,-0.300237f,0.139564f}, +{0.0143354f,-0.296096f,0.139836f},{0.00566917f,-0.289722f,0.140697f},{0.0110148f,-0.289219f,0.140695f}, +{-0.0100181f,-0.289811f,0.138847f},{-0.0108714f,-0.294038f,0.138995f},{-0.0120097f,-0.298192f,0.13929f}, +{-0.0131607f,-0.30234f,0.139564f},{-0.0143354f,-0.306481f,0.139836f},{-0.00666271f,-0.317286f,0.14114f}, +{-0.00749967f,-0.321494f,0.141879f},{0.00277232f,-0.322913f,0.14092f},{0.00972932f,-0.32566f,0.139659f}, +{0.00149718f,-0.325656f,0.141448f},{-0.0121843f,-0.317723f,0.141251f},{0.00255887f,-0.32214f,0.140869f}, +{0.00212359f,-0.321467f,0.140862f},{-0.000305779f,-0.312336f,0.140401f},{0.00112176f,-0.305823f,0.140439f}, +{0.00216894f,-0.30543f,0.14039f},{-0.0133136f,-0.321845f,0.142096f},{-0.00834704f,-0.325602f,0.14266f}, +{-0.0144683f,-0.325864f,0.142986f},{0.0028458f,-0.273043f,0.142624f},{0.0092361f,-0.272869f,0.143432f}, +{0.00151619f,-0.276934f,0.141923f},{0.00079021f,-0.276599f,0.141859f},{0.019351f,-0.279796f,0.142144f}, +{0.0179262f,-0.28376f,0.14121f},{0.0166178f,-0.287806f,0.140509f},{0.00210151f,-0.281123f,0.141433f}, +{0.00112326f,-0.296754f,0.140525f},{0.0154659f,-0.291943f,0.14012f},{0.0100181f,-0.312766f,0.138847f}, +{-0.0154659f,-0.310634f,0.14012f},{0.00974966f,-0.317058f,0.139013f},{-0.0179262f,-0.318817f,0.14121f}, +{-0.0166178f,-0.314771f,0.140509f},{-0.0193511f,-0.322781f,0.142144f},{-0.0208182f,-0.326719f,0.143118f}, +{0.00971729f,-0.329962f,0.139971f},{-0.0179944f,-0.338577f,0.145774f},{-0.0109671f,-0.338577f,0.145026f}, +{0.0262081f,-0.264f,0.148238f},{0.0248064f,-0.267733f,0.147199f},{0.0250058f,-0.267738f,0.146766f}, +{0.0233183f,-0.271434f,0.146165f},{0.0235291f,-0.271439f,0.145739f},{0.0188229f,-0.282552f,0.143165f}, +{0.0190695f,-0.282558f,0.142766f},{0.0203019f,-0.278832f,0.144139f},{0.0205368f,-0.278837f,0.143731f}, +{0.022035f,-0.275137f,0.14473f},{0.0218112f,-0.275132f,0.145147f},{0.015307f,-0.29417f,0.141119f}, +{0.0150041f,-0.294165f,0.141517f},{0.0141429f,-0.298107f,0.140834f},{0.0174212f,-0.286329f,0.1423f}, +{0.0161629f,-0.290221f,0.141811f},{0.0164424f,-0.290226f,0.141416f},{0.0114006f,-0.305963f,0.14071f}, +{0.0106866f,-0.309927f,0.140011f},{0.0117799f,-0.30597f,0.140283f},{0.0125814f,-0.302024f,0.14098f}, +{0.0129503f,-0.302035f,0.14056f},{0.0138012f,-0.298097f,0.141246f},{0.00963024f,-0.322165f,0.140526f}, +{0.00968708f,-0.318066f,0.140168f},{0.0091952f,-0.318055f,0.140649f},{0.0099197f,-0.313966f,0.139934f}, +{0.0102596f,-0.309914f,0.140442f},{0.00946264f,-0.313954f,0.140382f},{0.00907526f,-0.322157f,0.141031f}, +{0.0095489f,-0.326264f,0.140876f},{0.00894343f,-0.326258f,0.141413f},{0.00945311f,-0.330364f,0.141203f}, +{0.00933687f,-0.334468f,0.14148f},{0.00879579f,-0.33036f,0.141773f},{0.0086246f,-0.334465f,0.142088f}, +{0.00922107f,-0.338577f,0.141665f},{0.00845004f,-0.338577f,0.142301f},{0.0176856f,-0.286338f,0.141921f}, +{0.0263793f,-0.264f,0.147802f},{0.0259023f,-0.264f,0.148593f},{0.0244885f,-0.267734f,0.147557f}, +{0.0229936f,-0.271437f,0.146522f},{0.0184899f,-0.282562f,0.143511f},{0.0214828f,-0.275137f,0.145501f}, +{0.0146321f,-0.294177f,0.14188f},{0.0170843f,-0.286341f,0.142644f},{0.0158117f,-0.290234f,0.142162f}, +{0.010968f,-0.305972f,0.141112f},{0.0121699f,-0.302034f,0.141368f},{0.0134094f,-0.298108f,0.141622f}, +{0.0086637f,-0.31806f,0.141107f},{0.00980481f,-0.309921f,0.140857f},{0.00897481f,-0.31396f,0.140813f}, +{0.00849863f,-0.32216f,0.141523f},{0.00832061f,-0.32626f,0.14194f},{0.00812583f,-0.330362f,0.142335f}, +{0.00790535f,-0.334466f,0.142688f},{0.00767878f,-0.338577f,0.142938f},{0.0199715f,-0.278839f,0.144489f}, +{0.0254953f,-0.264f,0.148828f},{0.0239945f,-0.267945f,0.147747f},{0.0224149f,-0.271858f,0.146665f}, +{0.0176882f,-0.283628f,0.143502f},{0.0208215f,-0.275768f,0.145592f},{0.0192329f,-0.279683f,0.144529f}, +{0.0136618f,-0.295955f,0.142081f},{0.0162503f,-0.287664f,0.14274f},{0.0149457f,-0.2918f,0.142346f}, +{0.00869072f,-0.31263f,0.141186f},{0.00973903f,-0.308401f,0.141305f},{0.0110356f,-0.304248f,0.141581f}, +{0.00795144f,-0.321265f,0.141896f},{0.0081943f,-0.316941f,0.14144f},{0.00772122f,-0.325589f,0.142378f}, +{0.00747253f,-0.329914f,0.142842f},{0.00719397f,-0.334241f,0.143263f},{0.00690556f,-0.338577f,0.143577f}, +{0.0123399f,-0.300098f,0.141831f},{0.0250324f,-0.264f,0.148916f},{0.0235306f,-0.267971f,0.147857f}, +{0.0219498f,-0.271889f,0.146794f},{0.0172517f,-0.283688f,0.143711f},{0.0203651f,-0.275809f,0.14574f}, +{0.0132021f,-0.296012f,0.142332f},{0.0158114f,-0.287719f,0.142927f},{0.0144807f,-0.291851f,0.142544f}, +{0.0092687f,-0.308457f,0.141666f},{0.0105497f,-0.304299f,0.141886f},{0.0118813f,-0.300157f,0.142106f}, +{0.0073368f,-0.321297f,0.142324f},{0.00759572f,-0.316973f,0.141811f},{0.00819435f,-0.312673f,0.141567f}, +{0.00708183f,-0.325613f,0.142866f},{0.00678804f,-0.32993f,0.143377f},{0.00646507f,-0.334249f,0.143843f}, +{0.00613003f,-0.338577f,0.144218f},{0.0187868f,-0.279733f,0.144697f},{0.00696068f,-0.326294f,0.143005f}, +{0.00667554f,-0.330384f,0.143491f},{0.00636198f,-0.334476f,0.143939f},{0.00748015f,-0.318115f,0.141999f}, +{0.00786981f,-0.314024f,0.141631f},{0.00722771f,-0.322205f,0.1425f},{0.0111819f,-0.302112f,0.142035f}, +{0.00875236f,-0.309993f,0.14162f},{0.014914f,-0.290321f,0.142686f},{0.0124511f,-0.298189f,0.142242f}, +{0.0137038f,-0.294261f,0.142453f},{0.0175985f,-0.282633f,0.143972f},{0.0190677f,-0.278896f,0.144928f}, +{0.0162018f,-0.286425f,0.143129f},{0.0205663f,-0.275179f,0.145919f},{0.022067f,-0.271464f,0.146916f}, +{0.0235578f,-0.267747f,0.14792f},{0.00994863f,-0.306047f,0.141826f},{0.00603944f,-0.338577f,0.144293f}, +{0.00744254f,-0.272455f,0.145994f},{0.015865f,-0.268304f,0.147531f},{0.0083666f,-0.268397f,0.146789f}, +{0.000311244f,-0.272638f,0.144934f},{0.000930332f,-0.268488f,0.145573f},{-0.00667554f,-0.272193f,0.143491f}, +{0.00158091f,-0.264f,0.146182f},{-0.0063617f,-0.268101f,0.143935f},{0.00932143f,-0.264f,0.147589f}, +{-0.00603944f,-0.264f,0.144293f},{0.00654234f,-0.276379f,0.145204f},{0.00567271f,-0.28029f,0.144415f}, +{0.0134133f,-0.276103f,0.14569f},{0.00989537f,-0.287869f,0.143217f},{0.0110779f,-0.283807f,0.143908f}, +{0.00388505f,-0.28841f,0.143059f},{0.0122295f,-0.279922f,0.144789f},{0.0072715f,-0.296503f,0.142814f}, +{1.23849e-006f,-0.301301f,0.142893f},{0.00593214f,-0.300722f,0.142703f},{0.00860427f,-0.292161f,0.142918f}, +{0.00327255f,-0.30924f,0.142485f},{0.00211647f,-0.31361f,0.14253f},{-0.00133631f,-0.305494f,0.142894f}, +{0.00459153f,-0.304916f,0.142593f},{-0.00836678f,-0.334185f,0.146789f},{-0.00093054f,-0.334094f,0.145573f}, +{-0.000310969f,-0.329944f,0.144934f},{0.00135717f,-0.317858f,0.142953f},{-0.00485039f,-0.318318f,0.143617f}, +{-0.00158091f,-0.338577f,0.146182f},{0.000284983f,-0.325928f,0.144284f},{-0.00744232f,-0.330127f,0.145994f}, +{-0.0171357f,-0.338577f,0.148501f},{-0.0158652f,-0.334277f,0.147532f},{0.000835711f,-0.321928f,0.143615f}, +{-0.00654153f,-0.326203f,0.145205f},{-0.00568021f,-0.322295f,0.144405f},{-0.00265603f,-0.309815f,0.142905f}, +{-0.00387587f,-0.314151f,0.143071f},{0.00267273f,-0.292745f,0.142876f},{0.00133739f,-0.297082f,0.142892f}, +{0.00483092f,-0.284266f,0.143642f},{0.0146267f,-0.272271f,0.1466f},{0.0171357f,-0.264f,0.148501f}, +{-0.0069607f,-0.276283f,0.143005f},{-0.000284018f,-0.276654f,0.144284f},{-0.00722775f,-0.280372f,0.1425f}, +{-0.000847135f,-0.280656f,0.143625f},{-0.00746803f,-0.284462f,0.141989f},{-0.00138663f,-0.284723f,0.142978f}, +{-0.00787057f,-0.288553f,0.141632f},{-0.00210321f,-0.288949f,0.142519f},{-0.00875939f,-0.292582f,0.141625f}, +{-0.00324421f,-0.293326f,0.142456f},{-0.00994211f,-0.296532f,0.141827f},{-0.023562f,-0.334828f,0.147921f}, +{-0.0249766f,-0.338577f,0.148916f},{-0.00458966f,-0.29766f,0.142591f},{-0.0111906f,-0.300462f,0.142034f}, +{-0.0124586f,-0.304385f,0.142239f},{-0.00592971f,-0.30188f,0.142704f},{-0.0136985f,-0.308317f,0.142455f}, +{-0.00727121f,-0.306073f,0.142816f},{-0.0149126f,-0.312257f,0.142682f},{-0.00859914f,-0.310392f,0.142945f}, +{-0.0162055f,-0.316149f,0.143141f},{-0.0098903f,-0.314695f,0.143228f},{-0.0175985f,-0.319944f,0.143972f}, +{-0.0110874f,-0.31878f,0.143884f},{-0.0190677f,-0.323681f,0.144928f},{-0.012233f,-0.322664f,0.144779f}, +{-0.0205663f,-0.327398f,0.145919f},{-0.0134127f,-0.326479f,0.14569f},{-0.0220671f,-0.331113f,0.146916f}, +{-0.0146265f,-0.330311f,0.1466f},{-0.00932143f,-0.338577f,0.147589f},{-0.00690312f,-0.264f,0.143579f}, +{-0.00719191f,-0.268335f,0.143259f},{-0.00746979f,-0.272663f,0.142843f},{-0.00814762f,-0.285643f,0.141414f}, +{-0.0077197f,-0.276988f,0.142379f},{-0.00793083f,-0.281312f,0.141883f},{-0.0110361f,-0.298329f,0.141582f}, +{-0.0123542f,-0.302474f,0.141829f},{-0.00871456f,-0.289949f,0.141206f},{-0.00976951f,-0.294168f,0.141335f}, +{-0.0162476f,-0.314917f,0.14273f},{-0.0149252f,-0.310786f,0.142321f},{-0.0136614f,-0.306622f,0.142081f}, +{-0.0192347f,-0.322891f,0.144536f},{-0.0176916f,-0.318943f,0.143534f},{-0.0208212f,-0.326807f,0.145595f}, +{-0.022413f,-0.330719f,0.146665f},{-0.0239981f,-0.33463f,0.147749f},{-0.0254927f,-0.338577f,0.148829f}, +{-0.00767576f,-0.264f,0.142941f},{-0.00790232f,-0.268111f,0.142685f},{-0.00812312f,-0.272215f,0.142338f}, +{-0.00864847f,-0.284517f,0.1411f},{-0.00831807f,-0.276317f,0.141942f},{-0.00849626f,-0.280417f,0.141525f}, +{-0.0109591f,-0.296607f,0.141114f},{-0.00897354f,-0.288618f,0.140816f},{-0.00981108f,-0.292654f,0.140864f}, +{-0.0146249f,-0.308402f,0.141884f},{-0.0134151f,-0.304467f,0.141621f},{-0.0121769f,-0.30054f,0.141369f}, +{-0.0184881f,-0.320015f,0.143513f},{-0.0158082f,-0.312344f,0.142159f},{-0.0170869f,-0.316233f,0.142657f}, +{-0.0199696f,-0.323738f,0.144491f},{-0.0214809f,-0.32744f,0.145503f},{-0.0229915f,-0.33114f,0.146524f}, +{-0.0244911f,-0.334841f,0.147559f},{-0.0259001f,-0.338577f,0.148595f},{-0.00844643f,-0.264f,0.142304f}, +{-0.0086212f,-0.268112f,0.142086f},{-0.00879266f,-0.272217f,0.141776f},{-0.00917932f,-0.284522f,0.140643f}, +{-0.00894054f,-0.27632f,0.141415f},{-0.0113914f,-0.296616f,0.140713f},{-0.00946126f,-0.288623f,0.140385f}, +{-0.0102671f,-0.292661f,0.14045f},{-0.0149971f,-0.308414f,0.141521f},{-0.0138071f,-0.304478f,0.141245f}, +{-0.0125887f,-0.30055f,0.140981f},{-0.0188214f,-0.320025f,0.143167f},{-0.0161597f,-0.312357f,0.14181f}, +{-0.0174245f,-0.316245f,0.142314f},{-0.0203004f,-0.323745f,0.144141f},{-0.0218097f,-0.327445f,0.145149f}, +{-0.0233168f,-0.331143f,0.146167f},{-0.0248099f,-0.334842f,0.147201f},{-0.0262067f,-0.338577f,0.148241f}, +{-0.0090726f,-0.280421f,0.141033f},{-0.00921688f,-0.264f,0.141668f},{-0.00933302f,-0.268109f,0.141483f}, +{-0.00944958f,-0.272213f,0.141206f},{-0.00968445f,-0.284511f,0.140171f},{-0.00954568f,-0.276314f,0.140879f}, +{-0.0117779f,-0.296607f,0.140285f},{-0.00991732f,-0.288611f,0.139936f},{-0.0106844f,-0.29265f,0.140013f}, +{-0.0153055f,-0.308407f,0.141121f},{-0.0141412f,-0.304471f,0.140836f},{-0.0129485f,-0.300542f,0.140562f}, +{-0.0190685f,-0.320019f,0.142768f},{-0.0176844f,-0.316239f,0.141924f},{-0.016441f,-0.312351f,0.141419f}, +{-0.0205358f,-0.32374f,0.143733f},{-0.0220341f,-0.32744f,0.144732f},{-0.0235282f,-0.331138f,0.145742f}, +{-0.0250051f,-0.334839f,0.146769f},{-0.0263788f,-0.338577f,0.147805f},{-0.00962732f,-0.280413f,0.140529f}, +{-0.00976429f,-0.268106f,0.141114f},{-0.00968775f,-0.264f,0.141279f},{-0.00995451f,-0.280402f,0.140217f}, +{-0.00990606f,-0.276306f,0.140549f},{-0.00984421f,-0.272207f,0.140856f},{-0.0109184f,-0.292635f,0.13974f}, +{-0.00997907f,-0.284498f,0.139878f},{-0.0143137f,-0.304457f,0.140577f},{-0.01314f,-0.300528f,0.140298f}, +{-0.0119892f,-0.296593f,0.140016f},{-0.0178005f,-0.316228f,0.141673f},{-0.0165744f,-0.312338f,0.141169f}, +{-0.015459f,-0.308394f,0.140867f},{-0.0206269f,-0.323731f,0.143469f},{-0.0191718f,-0.320009f,0.142511f}, +{-0.0221132f,-0.327432f,0.144461f},{-0.0235942f,-0.331132f,0.145464f},{-0.0250554f,-0.334836f,0.146485f}, +{-0.0264087f,-0.338577f,0.147518f},{-0.0101788f,-0.288596f,0.139657f},{-0.0137161f,-0.302478f,0.140288f}, +{-0.0124851f,-0.298329f,0.140002f},{-0.0113146f,-0.294164f,0.139715f},{-0.0103804f,-0.28994f,0.139538f}, +{-0.00997452f,-0.285632f,0.139665f},{-0.00994023f,-0.281304f,0.140012f},{-0.00991203f,-0.276982f,0.140375f}, +{-0.009849f,-0.272659f,0.140706f},{-0.00976769f,-0.268332f,0.140986f},{-0.00968775f,-0.264f,0.141169f}, +{-0.014938f,-0.306628f,0.140581f},{-0.0161103f,-0.310795f,0.140863f},{-0.0173564f,-0.314927f,0.141293f}, +{-0.0187613f,-0.318949f,0.142077f},{-0.0202782f,-0.322893f,0.143048f},{-0.021842f,-0.326806f,0.144073f}, +{-0.0234057f,-0.330714f,0.145113f},{-0.024951f,-0.334625f,0.146173f},{-0.0263814f,-0.338577f,0.147244f}, +{-0.00976336f,-0.268582f,0.140775f},{-0.00968775f,-0.264f,0.140979f},{-0.00990978f,-0.282301f,0.139723f}, +{-0.00989796f,-0.27773f,0.140113f},{-0.00983969f,-0.273158f,0.140469f},{-0.0106101f,-0.291415f,0.139359f}, +{-0.0117247f,-0.295853f,0.139609f},{-0.00998742f,-0.286881f,0.139387f},{-0.0142908f,-0.304641f,0.140193f}, +{-0.0155467f,-0.309044f,0.140484f},{-0.0129908f,-0.300252f,0.139902f},{-0.0197978f,-0.321941f,0.142487f}, +{-0.0182285f,-0.317743f,0.141521f},{-0.0168071f,-0.313441f,0.140836f},{-0.0214356f,-0.326094f,0.143538f}, +{-0.0230806f,-0.330239f,0.14461f},{-0.0247084f,-0.334386f,0.145702f},{-0.0262125f,-0.338577f,0.146805f}, +{-0.00974593f,-0.268576f,0.140582f},{-0.00968775f,-0.264f,0.140788f},{-0.00985594f,-0.282277f,0.139537f}, +{-0.00985469f,-0.277712f,0.139924f},{-0.00980831f,-0.273146f,0.140278f},{-0.0116247f,-0.295818f,0.13941f}, +{-0.00992109f,-0.28685f,0.139202f},{-0.0141594f,-0.304602f,0.139977f},{-0.0154002f,-0.309003f,0.140259f}, +{-0.0128748f,-0.300215f,0.139695f},{-0.0195912f,-0.321909f,0.142214f},{-0.0180446f,-0.317704f,0.141269f}, +{-0.0166436f,-0.3134f,0.140601f},{-0.021206f,-0.326069f,0.143245f},{-0.0228275f,-0.330222f,0.144296f}, +{-0.0244304f,-0.334378f,0.145365f},{-0.0259067f,-0.338577f,0.146446f},{-0.0105278f,-0.291381f,0.139169f}, +{-0.00972275f,-0.268569f,0.140397f},{-0.00968775f,-0.264f,0.140597f},{-0.00978412f,-0.282252f,0.139372f}, +{-0.0097971f,-0.277693f,0.139752f},{-0.00976655f,-0.273133f,0.140099f},{-0.0104201f,-0.291345f,0.139009f}, +{-0.0114944f,-0.295781f,0.139248f},{-0.00983335f,-0.286819f,0.139043f},{-0.013988f,-0.304563f,0.139811f}, +{-0.0152086f,-0.308962f,0.14009f},{-0.0127235f,-0.300177f,0.13953f},{-0.01932f,-0.321876f,0.142022f}, +{-0.017804f,-0.317666f,0.141087f},{-0.0164298f,-0.313358f,0.140429f},{-0.0209031f,-0.326044f,0.143041f}, +{-0.0224922f,-0.330205f,0.144081f},{-0.0240607f,-0.334369f,0.145139f},{-0.0254987f,-0.338577f,0.146209f}, +{0.0240512f,-0.268205f,0.145139f},{0.0254987f,-0.264f,0.146209f},{0.0208987f,-0.276531f,0.143038f}, +{0.0224907f,-0.272372f,0.144081f},{0.0164319f,-0.289223f,0.14044f},{0.015224f,-0.29362f,0.140101f}, +{0.0177924f,-0.284903f,0.141053f},{0.0127141f,-0.302398f,0.139531f},{0.0114783f,-0.306793f,0.139232f}, +{0.0139803f,-0.298012f,0.139813f},{0.00981234f,-0.320325f,0.139389f},{0.00988648f,-0.315765f,0.139069f}, +{0.0103884f,-0.311233f,0.138993f},{0.00979575f,-0.324884f,0.139753f},{0.00976673f,-0.329444f,0.1401f}, +{0.00972076f,-0.334007f,0.140404f},{0.00968775f,-0.338577f,0.140597f},{0.0193145f,-0.280697f,0.142013f}, +{0.0244211f,-0.268196f,0.145365f},{0.0259067f,-0.264f,0.146446f},{0.0195856f,-0.280665f,0.142206f}, +{0.0212016f,-0.276506f,0.143242f},{0.0228261f,-0.272354f,0.144296f},{0.016646f,-0.289182f,0.140613f}, +{0.0154158f,-0.29358f,0.14027f},{0.0180326f,-0.284865f,0.141234f},{0.0116084f,-0.306756f,0.139394f}, +{0.0128655f,-0.30236f,0.139695f},{0.0141518f,-0.297973f,0.13998f},{0.0098846f,-0.320299f,0.139554f}, +{0.0099743f,-0.315733f,0.139229f},{0.0104962f,-0.311197f,0.139152f},{0.00985341f,-0.324865f,0.139926f}, +{0.00980859f,-0.329431f,0.140279f},{0.0097442f,-0.334001f,0.140589f},{0.00968775f,-0.338577f,0.140788f}, +{0.0246992f,-0.268187f,0.145701f},{0.0262125f,-0.264f,0.146805f},{0.019792f,-0.280632f,0.142478f}, +{0.0214312f,-0.276481f,0.143536f},{0.0230793f,-0.272337f,0.144611f},{0.0155626f,-0.293539f,0.140495f}, +{0.0182163f,-0.284826f,0.141486f},{0.0117083f,-0.30672f,0.139593f},{0.0129816f,-0.302322f,0.139903f}, +{0.0142832f,-0.297934f,0.140196f},{0.00993888f,-0.320275f,0.139741f},{0.0100406f,-0.315703f,0.139415f}, +{0.0105787f,-0.311163f,0.139342f},{0.00989672f,-0.324847f,0.140115f},{0.00984006f,-0.329419f,0.140471f}, +{0.00976183f,-0.333995f,0.140782f},{0.00968775f,-0.338577f,0.140979f},{0.0168098f,-0.289141f,0.140849f}, +{0.0264087f,-0.264f,0.147518f},{0.0221132f,-0.275145f,0.144461f},{0.0235942f,-0.271445f,0.145464f}, +{0.0250554f,-0.267741f,0.146485f},{0.0178005f,-0.28635f,0.141673f},{0.0165745f,-0.290239f,0.141169f}, +{0.0206269f,-0.278846f,0.143469f},{0.0191717f,-0.282568f,0.142511f},{0.01314f,-0.302049f,0.140298f}, +{0.0143137f,-0.29812f,0.140577f},{0.015459f,-0.294183f,0.140867f},{0.0101788f,-0.313981f,0.139657f}, +{0.0109184f,-0.309942f,0.13974f},{0.0119892f,-0.305984f,0.140016f},{0.00995447f,-0.322175f,0.140217f}, +{0.00997902f,-0.318079f,0.139878f},{0.00990604f,-0.326272f,0.140549f},{0.0098442f,-0.33037f,0.140856f}, +{0.00976429f,-0.334471f,0.141114f},{0.00968775f,-0.338577f,0.141279f},{0.0249437f,-0.267949f,0.146173f}, +{0.0263814f,-0.264f,0.147244f},{0.0202741f,-0.279681f,0.143041f},{0.0218394f,-0.27577f,0.144071f}, +{0.023405f,-0.271862f,0.145114f},{0.0173571f,-0.287654f,0.141303f},{0.0161317f,-0.291791f,0.140885f}, +{0.0187523f,-0.283621f,0.14205f},{0.0136985f,-0.300094f,0.140292f},{0.0124827f,-0.304247f,0.140001f}, +{0.0149357f,-0.295948f,0.140582f},{0.010352f,-0.31264f,0.139523f},{0.0112762f,-0.308404f,0.139687f}, +{0.00995919f,-0.321273f,0.140024f},{0.010024f,-0.31695f,0.139691f},{0.00991129f,-0.325595f,0.140376f}, +{0.00984923f,-0.329918f,0.140707f},{0.00968775f,-0.338577f,0.141169f},{0.00976681f,-0.334244f,0.140992f}, +{-0.00379135f,-0.113384f,0.144903f},{-0.00496458f,-0.113745f,0.14459f},{0.00742307f,-0.113263f,0.147291f}, +{-0.00257039f,-0.113263f,0.145216f},{-0.00603944f,-0.114327f,0.144293f},{0.00240499f,-0.113263f,0.146356f}, +{0.0211541f,-0.215517f,0.148776f},{0.0173396f,-0.167133f,0.148518f},{0.013533f,-0.118851f,0.148143f}, +{0.0132893f,-0.117569f,0.148115f},{0.0127783f,-0.116377f,0.148054f},{0.0120253f,-0.115321f,0.147961f}, +{0.0110634f,-0.114448f,0.147836f},{0.00994277f,-0.113799f,0.14768f},{0.00870927f,-0.113398f,0.147496f}, +{0.0123416f,-0.113525f,0.145204f},{0.0109102f,-0.112615f,0.145018f},{0.0135295f,-0.114734f,0.145346f}, +{0.0164058f,-0.15205f,0.14564f},{0.0192822f,-0.189366f,0.145867f},{0.0221586f,-0.226683f,0.146027f}, +{0.00932212f,-0.112054f,0.144792f},{0.00765064f,-0.111865f,0.144531f},{-0.00968775f,-0.119322f,0.140407f}, +{-0.00949318f,-0.117633f,0.140468f},{-0.00543154f,-0.112587f,0.141666f},{-0.00387196f,-0.112048f,0.142086f}, +{-0.00892517f,-0.116038f,0.140645f},{-0.0080214f,-0.114625f,0.14092f},{-0.00683431f,-0.113456f,0.141269f}, +{-0.00223012f,-0.111865f,0.142505f},{-0.00968775f,-0.119322f,0.141279f},{0.00268915f,-0.111865f,0.144987f}, +{-0.00223012f,-0.111865f,0.14386f},{0.00765064f,-0.111865f,0.145911f},{0.0143331f,-0.116009f,0.145639f}, +{0.0147899f,-0.117166f,0.146726f},{0.0148426f,-0.117347f,0.146158f},{0.0150857f,-0.118743f,0.146754f}, +{0.014171f,-0.115703f,0.146666f},{0.0132538f,-0.1144f,0.146574f},{0.0120868f,-0.113328f,0.14645f}, +{0.0107201f,-0.112525f,0.146296f},{0.00921907f,-0.112032f,0.146114f},{-0.00815064f,-0.114787f,0.142549f}, +{-0.00695586f,-0.113553f,0.14283f},{-0.00391721f,-0.112058f,0.143508f},{-0.00552233f,-0.112631f,0.143157f}, +{-0.0089918f,-0.116176f,0.141854f},{-0.00951028f,-0.117706f,0.141426f},{-0.00632699f,-0.113829f,0.144055f}, +{-0.0068323f,-0.113789f,0.143638f},{-0.00732043f,-0.114001f,0.143234f},{-0.00776225f,-0.114347f,0.14287f}, +{0.0235779f,-0.227685f,0.147426f},{0.0219204f,-0.216179f,0.148625f},{0.0224876f,-0.216137f,0.148085f}, +{0.0179164f,-0.155057f,0.147043f},{0.0149745f,-0.118746f,0.1473f},{0.0186837f,-0.167425f,0.147841f}, +{0.0140869f,-0.118809f,0.148094f},{0.0180963f,-0.167468f,0.148384f},{0.0146193f,-0.11877f,0.147797f}, +{0.0207472f,-0.191371f,0.147267f},{0.00748972f,-0.112274f,0.146886f},{0.00897658f,-0.112435f,0.147115f}, +{0.00911758f,-0.112116f,0.146645f},{0.0103998f,-0.112887f,0.147311f},{0.0119652f,-0.113376f,0.146998f}, +{0.0106014f,-0.112592f,0.146835f},{0.0128307f,-0.114648f,0.147613f},{0.0140507f,-0.11572f,0.147224f}, +{0.0131339f,-0.114435f,0.147128f},{0.0146743f,-0.117179f,0.147286f},{0.0124497f,-0.114951f,0.147903f}, +{0.0113986f,-0.114003f,0.14777f},{0.0138348f,-0.117405f,0.148064f},{0.0143101f,-0.117272f,0.147775f}, +{0.013274f,-0.116101f,0.148f},{0.00743905f,-0.112748f,0.147194f},{0.00883688f,-0.112873f,0.14741f}, +{0.00756687f,-0.111963f,0.146419f},{0.0101719f,-0.1133f,0.147604f},{0.0137111f,-0.115877f,0.147711f}, +{0.0117086f,-0.113636f,0.147479f},{0.00254212f,-0.112073f,0.145696f},{0.0024474f,-0.112539f,0.146152f}, +{-0.00239822f,-0.112048f,0.14453f},{-0.00252701f,-0.112586f,0.145044f},{-0.00405957f,-0.11229f,0.14418f}, +{-0.00550952f,-0.113281f,0.144258f},{-0.00559184f,-0.112863f,0.143809f},{-0.00407172f,-0.112743f,0.14463f}, +{0.022887f,-0.227099f,0.146255f},{0.0233314f,-0.227063f,0.14672f},{0.0174497f,-0.151481f,0.14634f}, +{0.0203893f,-0.189252f,0.146565f},{0.0199559f,-0.189288f,0.146102f},{0.0170273f,-0.151517f,0.145879f}, +{-0.0123416f,-0.489052f,0.145204f},{-0.0109102f,-0.489962f,0.145018f},{-0.0135295f,-0.487844f,0.145346f}, +{-0.0164058f,-0.450527f,0.14564f},{-0.0192822f,-0.413211f,0.145867f},{-0.0221586f,-0.375894f,0.146027f}, +{-0.00932212f,-0.490523f,0.144792f},{-0.00765064f,-0.490713f,0.144531f},{0.00968775f,-0.483255f,0.140407f}, +{0.00949318f,-0.484944f,0.140468f},{0.00543154f,-0.48999f,0.141666f},{0.00387196f,-0.49053f,0.142086f}, +{0.00892517f,-0.486539f,0.140645f},{0.0080214f,-0.487952f,0.14092f},{0.00683431f,-0.489121f,0.141269f}, +{0.00223012f,-0.490713f,0.142505f},{0.00379135f,-0.489193f,0.144903f},{0.00496458f,-0.488833f,0.14459f}, +{-0.00742307f,-0.489314f,0.147291f},{0.00257039f,-0.489314f,0.145216f},{0.00603944f,-0.48825f,0.144293f}, +{-0.00240499f,-0.489314f,0.146356f},{-0.0211541f,-0.387061f,0.148776f},{-0.0173396f,-0.435444f,0.148518f}, +{-0.013533f,-0.483726f,0.148143f},{-0.0132913f,-0.485001f,0.148115f},{-0.0127821f,-0.486194f,0.148055f}, +{-0.0120287f,-0.487252f,0.147962f},{-0.0110706f,-0.488124f,0.147837f},{-0.00994698f,-0.488776f,0.14768f}, +{-0.00871793f,-0.489178f,0.147497f},{0.00968775f,-0.483255f,0.141279f},{-0.00268915f,-0.490713f,0.144987f}, +{-0.00765064f,-0.490713f,0.145911f},{0.00223012f,-0.490713f,0.14386f},{-0.0143331f,-0.486568f,0.145639f}, +{-0.014793f,-0.4854f,0.146726f},{-0.0148426f,-0.48523f,0.146158f},{-0.0150857f,-0.483834f,0.146754f}, +{-0.014174f,-0.486869f,0.146667f},{-0.0132606f,-0.488168f,0.146575f},{-0.0120925f,-0.489246f,0.146451f}, +{-0.0107278f,-0.490048f,0.146297f},{-0.00922792f,-0.490544f,0.146115f},{0.00815064f,-0.48779f,0.142549f}, +{0.00695586f,-0.489024f,0.14283f},{0.00552233f,-0.489946f,0.143157f},{0.00391721f,-0.490519f,0.143508f}, +{0.0089918f,-0.486401f,0.141854f},{0.00951028f,-0.484871f,0.141426f},{0.0068323f,-0.488788f,0.143638f}, +{0.00632699f,-0.488748f,0.144055f},{0.00732043f,-0.488576f,0.143234f},{0.00776225f,-0.48823f,0.14287f}, +{-0.0235779f,-0.374892f,0.147426f},{-0.0219204f,-0.386398f,0.148625f},{-0.0224876f,-0.38644f,0.148085f}, +{-0.0179164f,-0.447521f,0.147043f},{-0.0149745f,-0.483831f,0.1473f},{-0.0186837f,-0.435152f,0.147841f}, +{-0.0140869f,-0.483769f,0.148094f},{-0.0180963f,-0.435109f,0.148384f},{-0.0146193f,-0.483807f,0.147797f}, +{-0.0207472f,-0.411206f,0.147267f},{-0.0137517f,-0.486695f,0.147682f},{-0.013838f,-0.485162f,0.148064f}, +{-0.0143462f,-0.485304f,0.147745f},{-0.0131473f,-0.488127f,0.147128f},{-0.0140617f,-0.486836f,0.147224f}, +{-0.0146779f,-0.485388f,0.147286f},{-0.0101903f,-0.48927f,0.147606f},{-0.0114133f,-0.488565f,0.147771f}, +{-0.00899738f,-0.490167f,0.147089f},{-0.00756687f,-0.490614f,0.146419f},{-0.00748972f,-0.490303f,0.146886f}, +{-0.0106218f,-0.489978f,0.146837f},{-0.0119815f,-0.489191f,0.146999f},{-0.00912889f,-0.490458f,0.146646f}, +{-0.0104352f,-0.489708f,0.147285f},{-0.00884706f,-0.489702f,0.147411f},{-0.0128697f,-0.487935f,0.147584f}, +{-0.0132839f,-0.486458f,0.148001f},{-0.00743905f,-0.489829f,0.147194f},{-0.0124617f,-0.487613f,0.147903f}, +{-0.0117456f,-0.488955f,0.147451f},{-0.00254212f,-0.490504f,0.145696f},{-0.0024474f,-0.490038f,0.146152f}, +{0.00239822f,-0.490529f,0.14453f},{0.00252701f,-0.489991f,0.145044f},{0.00405957f,-0.490287f,0.14418f}, +{0.00550952f,-0.489296f,0.144258f},{0.00559184f,-0.489714f,0.143809f},{0.00407172f,-0.489834f,0.14463f}, +{-0.0233314f,-0.375514f,0.14672f},{-0.022887f,-0.375478f,0.146255f},{-0.0170273f,-0.45106f,0.145879f}, +{-0.0174497f,-0.451096f,0.14634f},{-0.0203893f,-0.413325f,0.146565f},{-0.0199559f,-0.413289f,0.146102f}, +{0.0043568f,-0.299632f,0.127503f},{0.00383438f,-0.298639f,0.127503f},{0.00308638f,-0.297796f,0.127503f}, +{0.00216232f,-0.29716f,0.127503f},{0.00462734f,-0.301848f,0.127503f},{0.00462608f,-0.300722f,0.127503f}, +{0.00383806f,-0.303933f,0.127503f},{0.00435903f,-0.302939f,0.127503f},{0.00309213f,-0.304776f,0.127503f}, +{0.00216808f,-0.305415f,0.127503f},{0.00111857f,-0.305813f,0.127503f},{0.0011128f,-0.296762f,0.127503f}, +{-0.00150163f,-0.298964f,0.127503f},{-0.000787374f,-0.29861f,0.127503f},{-0.00211724f,-0.29946f,0.127503f}, +{-0.00254559f,-0.30013f,0.127503f},{-0.00276842f,-0.300894f,0.127503f},{-0.00276723f,-0.301689f,0.127503f}, +{-0.00254283f,-0.302452f,0.127503f},{-0.00210508f,-0.303112f,0.127503f},{-0.00150519f,-0.303628f,0.127503f}, +{-0.00078745f,-0.303974f,0.127503f},{-0.00254559f,-0.302447f,0.136825f},{-0.00276842f,-0.301683f,0.136825f}, +{-0.00150519f,-0.298949f,0.136825f},{-0.00276723f,-0.300888f,0.136825f},{-0.00210508f,-0.299465f,0.136825f}, +{-0.00078745f,-0.298603f,0.136825f},{-0.00254283f,-0.300125f,0.136825f},{-0.00211724f,-0.303117f,0.136825f}, +{-0.00150163f,-0.303613f,0.136825f},{-0.000787374f,-0.303967f,0.136825f},{0.00265777f,-0.322419f,0.127503f}, +{0.00225612f,-0.321638f,0.127503f},{0.00163414f,-0.321021f,0.127503f},{0.00266037f,-0.324145f,0.127503f}, +{0.00226719f,-0.324923f,0.127503f},{0.00279661f,-0.323289f,0.127503f},{0.00165072f,-0.325545f,0.127503f}, +{0.000869207f,-0.325946f,0.127503f},{0.000869207f,-0.320631f,0.127503f},{0.00265777f,-0.278419f,0.127503f}, +{0.00225612f,-0.277638f,0.127503f},{0.00163414f,-0.277021f,0.127503f},{0.00266037f,-0.280145f,0.127503f}, +{0.00279661f,-0.279289f,0.127503f},{0.00165072f,-0.281545f,0.127503f},{0.00226719f,-0.280923f,0.127503f}, +{0.000869207f,-0.281946f,0.127503f},{0.000869207f,-0.276631f,0.127503f},{0.14024f,0.0905829f,-0.141015f}, +{0.136285f,0.0947137f,-0.142188f},{0.141059f,0.0890842f,-0.140701f},{0.164944f,0.0609206f,-0.129448f}, +{0.166387f,0.0597515f,-0.12867f},{0.162134f,0.0647663f,-0.131224f},{0.121812f,0.11117f,-0.145366f}, +{0.121542f,0.1109f,-0.145713f},{0.12625f,0.10535f,-0.144944f},{0.13153f,0.100321f,-0.143429f}, +{0.135762f,0.095863f,-0.142366f},{0.130854f,0.0995405f,-0.144466f},{0.126104f,0.105142f,-0.145472f}, +{0.122103f,0.111436f,-0.145199f},{0.126512f,0.105627f,-0.144598f},{0.1268f,0.105898f,-0.144431f}, +{0.112085f,0.121672f,-0.147719f},{0.112073f,0.121686f,-0.147105f},{0.107472f,0.127074f,-0.147351f}, +{0.121386f,0.110705f,-0.146243f},{0.107827f,0.127376f,-0.148558f},{0.112579f,0.122056f,-0.148599f}, +{0.112283f,0.121818f,-0.148251f},{0.107534f,0.127127f,-0.148015f},{0.117758f,0.117092f,-0.148493f}, +{0.117549f,0.116806f,-0.148445f},{0.112883f,0.122308f,-0.148767f},{0.113146f,0.12253f,-0.14881f}, +{0.108275f,0.127755f,-0.148876f},{0.10853f,0.127972f,-0.148916f},{0.149108f,0.0801256f,-0.137702f}, +{0.145845f,0.0834412f,-0.138964f},{0.150634f,0.0777938f,-0.136973f},{0.14469f,0.0853356f,-0.13946f}, +{0.15542f,0.0721513f,-0.134725f},{0.153491f,0.0749577f,-0.135742f},{0.159928f,0.0662252f,-0.132375f}, +{0.160192f,0.0665236f,-0.132217f},{0.157834f,0.0698365f,-0.133582f},{0.169666f,0.0553525f,-0.126416f}, +{0.170589f,0.0547966f,-0.125923f},{0.178987f,0.0443625f,-0.119568f},{0.183567f,0.0389616f,-0.115753f}, +{0.182854f,0.040335f,-0.116543f},{0.17435f,0.0498296f,-0.123123f},{0.194531f,0.0265656f,-0.105516f}, +{0.19071f,0.0310716f,-0.109369f},{0.192523f,0.028401f,-0.107358f},{0.186816f,0.0356628f,-0.113046f}, +{0.201944f,0.0178247f,-0.0972923f},{0.201149f,0.0182303f,-0.0979722f},{0.205317f,0.0133161f,-0.0929223f}, +{0.196882f,0.0232619f,-0.102786f},{0.212441f,0.00544782f,-0.0837205f},{0.213321f,0.00387764f,-0.0821464f}, +{0.215761f,0.00153276f,-0.0788827f},{0.209376f,0.00852884f,-0.0876442f},{0.225146f,-0.009533f,-0.0634868f}, +{0.222116f,-0.00596092f,-0.0687614f},{0.224391f,-0.00917553f,-0.0644306f},{0.218987f,-0.00227125f,-0.0738949f}, +{0.220835f,-0.00498246f,-0.0705292f},{0.233609f,-0.0195123f,-0.0468636f},{0.231071f,-0.0170525f,-0.0517099f}, +{0.234185f,-0.0207242f,-0.0451124f},{0.227805f,-0.013201f,-0.0581535f},{0.239939f,-0.0275089f,-0.0315071f}, +{0.241084f,-0.0283265f,-0.0291439f},{0.238706f,-0.0255224f,-0.0351637f},{0.236213f,-0.0225835f,-0.041072f}, +{0.247512f,-0.0359059f,-0.010468f},{0.245489f,-0.0335205f,-0.0167907f},{0.247339f,-0.0362343f,-0.0102766f}, +{0.242572f,-0.0306138f,-0.0245261f},{0.249469f,-0.0387463f,-0.0030353f},{0.25119f,-0.0402428f,0.00244111f}, +{0.249413f,-0.0381473f,-0.00405553f},{0.254843f,-0.0450829f,0.0189909f},{0.254367f,-0.0439888f,0.0156645f}, +{0.253221f,-0.0431703f,0.0116119f},{0.252842f,-0.0421905f,0.00901635f},{0.25143f,-0.0410583f,0.00426541f}, +{0.257032f,-0.0471308f,0.0291557f},{0.257585f,-0.0483159f,0.0337941f},{0.258169f,-0.0484718f,0.0359868f}, +{0.256297f,-0.0467975f,0.0263892f},{0.255764f,-0.0456361f,0.0223796f},{0.259175f,-0.0496578f,0.0428671f}, +{0.259671f,-0.0507748f,0.0485748f},{0.260048f,-0.0506878f,0.0497904f},{0.258709f,-0.0496406f,0.0411933f}, +{0.262173f,-0.0537259f,0.0848371f},{0.262476f,-0.0535502f,0.0918925f},{0.262408f,-0.0534705f,0.0848393f}, +{0.260789f,-0.0515609f,0.0567509f},{0.260474f,-0.0517219f,0.0559272f},{0.261618f,-0.0530714f,0.0705019f}, +{0.261426f,-0.0534542f,0.0704868f},{0.261775f,-0.0538661f,0.077694f},{0.262205f,-0.0532315f,0.0777923f}, +{0.261395f,-0.0522762f,0.0637421f},{0.261868f,-0.0528332f,0.0707579f},{0.261967f,-0.053483f,0.0777041f}, +{0.261122f,-0.0524859f,0.0632397f},{0.26171f,-0.054377f,0.0776733f},{0.262073f,-0.0551849f,0.084806f}, +{0.261917f,-0.0546204f,0.0848218f},{0.259477f,-0.051156f,0.0485442f},{0.258514f,-0.050021f,0.0411575f}, +{0.26136f,-0.0539645f,0.0704555f},{0.260929f,-0.0528684f,0.0632194f},{0.260863f,-0.0533778f,0.0631775f}, +{0.259408f,-0.0516629f,0.0484808f},{0.261911f,-0.0549937f,0.0703525f},{0.261411f,-0.0544042f,0.0630396f}, +{0.262441f,-0.055239f,0.0703047f},{0.261017f,-0.0539394f,0.0631135f},{0.261516f,-0.0545274f,0.0704077f}, +{0.262955f,-0.0552578f,0.0702734f},{0.263308f,-0.0556738f,0.0775525f},{0.263265f,-0.0560102f,0.0918925f}, +{0.263001f,-0.0558996f,0.0847721f},{0.263516f,-0.0559194f,0.0847617f},{0.263926f,-0.0557923f,0.0847568f}, +{0.263974f,-0.0558822f,0.0918925f},{0.263625f,-0.0559923f,0.0918925f},{0.264284f,-0.055683f,0.0918925f}, +{0.256101f,-0.0471759f,0.026343f},{0.237143f,-0.0242111f,-0.0383737f},{0.243346f,-0.0309933f,-0.0230178f}, +{0.24504f,-0.033523f,-0.0174448f},{0.239731f,-0.0278737f,-0.0315942f},{0.230894f,-0.0163116f,-0.0525331f}, +{0.228073f,-0.0129842f,-0.0580758f},{0.217143f,-0.000628865f,-0.0764381f},{0.209029f,0.00947049f,-0.088404f}, +{0.220614f,-0.00533134f,-0.0706439f},{0.220489f,-0.00577124f,-0.0708815f},{0.224052f,-0.0099734f,-0.0647696f}, +{0.205529f,0.0135974f,-0.0929293f},{0.198277f,0.0221487f,-0.101489f},{0.178826f,0.0450842f,-0.119856f}, +{0.174737f,0.0499061f,-0.122984f},{0.188082f,0.0336377f,-0.111682f},{0.20076f,0.0174918f,-0.098384f}, +{0.196643f,0.0229329f,-0.102924f},{0.196483f,0.0225343f,-0.103209f},{0.13126f,0.101171f,-0.14351f}, +{0.126738f,0.106503f,-0.144448f},{0.1222f,0.111854f,-0.145179f},{0.11225f,0.121856f,-0.146574f}, +{0.107533f,0.127126f,-0.147023f},{0.117445f,0.116929f,-0.145739f},{0.11765f,0.117219f,-0.145701f}, +{0.112831f,0.122369f,-0.146057f},{0.113092f,0.122593f,-0.146014f},{0.107472f,0.127075f,-0.147687f}, +{0.108274f,0.127755f,-0.146158f},{0.10853f,0.127972f,-0.146119f},{0.108041f,0.127557f,-0.146297f}, +{0.107823f,0.127372f,-0.146474f},{0.112534f,0.12211f,-0.146225f},{0.107652f,0.127227f,-0.146724f}, +{0.11715f,0.116666f,-0.145907f},{0.131245f,0.100046f,-0.143596f},{0.136004f,0.0944352f,-0.142353f}, +{0.140782f,0.0888017f,-0.140865f},{0.145571f,0.0831547f,-0.139127f},{0.150363f,0.0775033f,-0.137134f}, +{0.155152f,0.0718569f,-0.134885f},{0.164476f,0.0602748f,-0.129928f},{0.169209f,0.0546946f,-0.12689f}, +{0.164683f,0.0606183f,-0.129604f},{0.169409f,0.0550462f,-0.126571f},{0.174096f,0.0495195f,-0.123274f}, +{0.178736f,0.0440485f,-0.119717f},{0.183319f,0.0386437f,-0.1159f},{0.187838f,0.0333161f,-0.111826f}, +{0.192282f,0.0280757f,-0.107499f},{0.200914f,0.0178978f,-0.0981062f},{0.205084f,0.0129801f,-0.0930527f}, +{0.209147f,0.00818951f,-0.087771f},{0.213094f,0.00353502f,-0.0822693f},{0.216919f,-0.000974661f,-0.0765569f}, +{0.224172f,-0.00952736f,-0.0645409f},{0.227589f,-0.0135557f,-0.0582594f},{0.230857f,-0.0174099f,-0.0518113f}, +{0.233973f,-0.0210842f,-0.0452091f},{0.236933f,-0.0245736f,-0.0384656f},{0.247174f,-0.0376161f,-0.0107265f}, +{0.244746f,-0.0343736f,-0.017682f},{0.244864f,-0.0348929f,-0.0179263f},{0.242366f,-0.0309808f,-0.0246083f}, +{0.244835f,-0.033892f,-0.017522f},{0.247136f,-0.0366052f,-0.0103487f},{0.249268f,-0.039119f,-0.0031023f}, +{0.25123f,-0.0414326f,0.00420356f},{0.253023f,-0.0435461f,0.0115553f},{0.254646f,-0.0454601f,0.0189394f}, +{0.25739f,-0.0486953f,0.0337531f},{0.258444f,-0.0505263f,0.0410833f},{0.26028f,-0.0521038f,0.0559018f}, +{0.261981f,-0.0541092f,0.0848321f},{0.262065f,-0.0541415f,0.0918925f},{0.262228f,-0.0538242f,0.0918925f}, +{0.107655f,0.12723f,-0.14831f},{0.116874f,0.116405f,-0.146254f},{0.130989f,0.0997606f,-0.14394f}, +{0.135755f,0.0941412f,-0.142695f},{0.14054f,0.0884994f,-0.141205f},{0.145336f,0.0828442f,-0.139464f}, +{0.150136f,0.0771845f,-0.137469f},{0.154931f,0.0715299f,-0.135216f},{0.159714f,0.0658899f,-0.132703f}, +{0.173903f,0.0491597f,-0.123589f},{0.173863f,0.0488268f,-0.12407f},{0.17852f,0.0433355f,-0.120499f}, +{0.17855f,0.0436807f,-0.120026f},{0.18314f,0.0382681f,-0.116203f},{0.187665f,0.0329327f,-0.112124f}, +{0.192115f,0.0276847f,-0.10779f},{0.209044f,0.00734409f,-0.0884349f},{0.209305f,0.00703665f,-0.0888979f}, +{0.213277f,0.00235295f,-0.0833616f},{0.204936f,0.012567f,-0.0933231f},{0.209005f,0.00776938f,-0.0880336f}, +{0.212958f,0.00310807f,-0.0825239f},{0.216788f,-0.00140821f,-0.0768032f},{0.230834f,-0.0183499f,-0.0523423f}, +{0.231151f,-0.0187233f,-0.0527127f},{0.234287f,-0.0224207f,-0.046069f},{0.227474f,-0.0140076f,-0.0584789f}, +{0.230747f,-0.0178675f,-0.0520214f},{0.233868f,-0.0215472f,-0.0454095f},{0.236831f,-0.0250416f,-0.0386562f}, +{0.239634f,-0.0283465f,-0.0317747f},{0.242273f,-0.0314582f,-0.0247786f},{0.24705f,-0.0370908f,-0.0104982f}, +{0.249185f,-0.0396083f,-0.00324118f},{0.25115f,-0.0419253f,0.00407537f},{0.252945f,-0.0440419f,0.0114378f}, +{0.254571f,-0.0459587f,0.0188328f},{0.256028f,-0.0476769f,0.0262471f},{0.257318f,-0.0491986f,0.0336681f}, +{0.260213f,-0.052612f,0.0558492f},{0.262263f,-0.0554082f,0.077605f},{0.261986f,-0.054502f,0.0918925f}, +{0.117242f,0.116558f,-0.148277f},{0.116707f,0.116222f,-0.146785f},{0.135631f,0.0939085f,-0.143218f}, +{0.135703f,0.0938233f,-0.143822f},{0.14051f,0.0881545f,-0.142325f},{0.140426f,0.0882542f,-0.141725f}, +{0.145233f,0.0825863f,-0.13998f},{0.150043f,0.076914f,-0.137981f},{0.154849f,0.0712468f,-0.135723f}, +{0.159643f,0.0655943f,-0.133204f},{0.164416f,0.0599666f,-0.130423f},{0.169159f,0.0543739f,-0.127378f}, +{0.183121f,0.0379109f,-0.116668f},{0.183315f,0.0376819f,-0.117203f},{0.187862f,0.0323208f,-0.113104f}, +{0.187656f,0.0325635f,-0.112579f},{0.192116f,0.0273038f,-0.108236f},{0.196494f,0.022142f,-0.103644f}, +{0.20078f,0.0170882f,-0.0988083f},{0.204966f,0.0121524f,-0.0937362f},{0.213006f,0.00267239f,-0.0829128f}, +{0.216844f,-0.00185395f,-0.0771794f},{0.220553f,-0.00622672f,-0.0712445f},{0.224125f,-0.0104382f,-0.065119f}, +{0.227554f,-0.0144815f,-0.0588143f},{0.233962f,-0.0220378f,-0.0457157f},{0.236932f,-0.0255401f,-0.0389474f}, +{0.239741f,-0.0288523f,-0.0320505f},{0.242386f,-0.0319709f,-0.0250388f},{0.249313f,-0.0401392f,-0.00345334f}, +{0.249678f,-0.0405686f,-0.00369814f},{0.251652f,-0.0428967f,0.00365355f},{0.251283f,-0.0424614f,0.00387953f}, +{0.253082f,-0.0445827f,0.0112584f},{0.254711f,-0.0465038f,0.0186698f},{0.256171f,-0.0482259f,0.0261007f}, +{0.257465f,-0.049751f,0.0335382f},{0.258593f,-0.0510816f,0.04097f},{0.259559f,-0.0522207f,0.048384f}, +{0.260366f,-0.053172f,0.0557688f},{0.261866f,-0.0549408f,0.0776416f},{0.262004f,-0.0548614f,0.0918925f}, +{0.121422f,0.110663f,-0.146855f},{0.126152f,0.105086f,-0.146081f},{0.116731f,0.116194f,-0.147398f}, +{0.130914f,0.0994698f,-0.145073f},{0.145329f,0.0824721f,-0.140576f},{0.150152f,0.0767852f,-0.138571f}, +{0.154971f,0.0711034f,-0.136307f},{0.155264f,0.071138f,-0.136814f},{0.16008f,0.0654584f,-0.134283f}, +{0.159777f,0.0654364f,-0.133782f},{0.164562f,0.0597942f,-0.130993f},{0.169317f,0.0541872f,-0.127941f}, +{0.174034f,0.0486258f,-0.124624f},{0.178703f,0.0431205f,-0.121044f},{0.192334f,0.0270476f,-0.10875f}, +{0.192709f,0.0269844f,-0.109195f},{0.197108f,0.0217978f,-0.104581f},{0.196723f,0.0218725f,-0.104146f}, +{0.20102f,0.0168058f,-0.0992979f},{0.205216f,0.0118573f,-0.0942128f},{0.217125f,-0.00218501f,-0.0776135f}, +{0.217556f,-0.0023131f,-0.0779897f},{0.221282f,-0.00670683f,-0.0720263f},{0.220843f,-0.00656901f,-0.0716633f}, +{0.224424f,-0.0107914f,-0.0655221f},{0.227862f,-0.0148449f,-0.0592012f},{0.237264f,-0.025932f,-0.0392833f}, +{0.23774f,-0.0261128f,-0.0395744f},{0.240562f,-0.0294409f,-0.0326445f},{0.240081f,-0.0292527f,-0.0323688f}, +{0.242732f,-0.0323793f,-0.025339f},{0.245217f,-0.0353088f,-0.0182083f},{0.247532f,-0.038039f,-0.01099f}, +{0.253456f,-0.0450235f,0.0110514f},{0.255089f,-0.0469495f,0.0184819f},{0.255604f,-0.0471769f,0.0183189f}, +{0.257071f,-0.0489073f,0.0257854f},{0.256553f,-0.048676f,0.0259318f},{0.25785f,-0.050205f,0.0333884f}, +{0.258981f,-0.051539f,0.0408392f},{0.25995f,-0.0526811f,0.0482723f},{0.260759f,-0.0536348f,0.0556761f}, +{0.26247f,-0.0556528f,0.0847878f},{0.262314f,-0.055521f,0.0918925f},{0.262114f,-0.0552103f,0.0918925f}, +{0.12164f,0.110785f,-0.147384f},{0.12638f,0.105196f,-0.14661f},{0.116939f,0.116328f,-0.147929f}, +{0.131153f,0.0995673f,-0.145599f},{0.135953f,0.0939083f,-0.144345f},{0.140771f,0.0882269f,-0.142845f}, +{0.145601f,0.0825319f,-0.141092f},{0.150434f,0.0768324f,-0.139082f},{0.164876f,0.0598037f,-0.131488f}, +{0.170021f,0.0543241f,-0.128748f},{0.169642f,0.0541843f,-0.128429f},{0.174369f,0.0486105f,-0.125105f}, +{0.179048f,0.043093f,-0.121517f},{0.183671f,0.0376423f,-0.117667f},{0.188227f,0.0322693f,-0.113559f}, +{0.20184f,0.0168054f,-0.1f},{0.201414f,0.0167199f,-0.0997223f},{0.20562f,0.0117604f,-0.0946258f}, +{0.209718f,0.00692902f,-0.0892991f},{0.213699f,0.00223494f,-0.0837506f},{0.225331f,-0.0108931f,-0.0661002f}, +{0.224871f,-0.0109385f,-0.0658715f},{0.228316f,-0.0150011f,-0.0595366f},{0.231613f,-0.0188881f,-0.0530336f}, +{0.234755f,-0.0225937f,-0.0463752f},{0.243706f,-0.0325604f,-0.0257695f},{0.24322f,-0.0325744f,-0.0255992f}, +{0.24571f,-0.0355104f,-0.0184526f},{0.24803f,-0.0382467f,-0.0112184f},{0.25018f,-0.0407819f,-0.00391029f}, +{0.252159f,-0.0431152f,0.00345771f},{0.253967f,-0.0452467f,0.0108719f},{0.258371f,-0.0504397f,0.0332586f}, +{0.260015f,-0.0517904f,0.0406518f},{0.259505f,-0.0517766f,0.0407259f},{0.260475f,-0.0529213f,0.0481755f}, +{0.261286f,-0.0538771f,0.0555957f},{0.26194f,-0.0546482f,0.0629755f},{0.262793f,-0.0556544f,0.0775733f}, +{0.262905f,-0.0559313f,0.0918925f},{0.26258f,-0.0557625f,0.0918925f},{0.108037f,0.127554f,-0.148751f}, +{0.12195f,0.111007f,-0.147731f},{0.126697f,0.105409f,-0.146955f},{0.131477f,0.0997729f,-0.145943f}, +{0.136283f,0.0941057f,-0.144688f},{0.141109f,0.0884161f,-0.143185f},{0.145945f,0.0827128f,-0.141429f}, +{0.150786f,0.077005f,-0.139417f},{0.155622f,0.0713023f,-0.137145f},{0.160446f,0.0656145f,-0.134611f}, +{0.165249f,0.0599517f,-0.131812f},{0.175103f,0.0489424f,-0.125571f},{0.179652f,0.0441098f,-0.122344f}, +{0.179792f,0.043413f,-0.121975f},{0.174755f,0.0487422f,-0.125419f},{0.179441f,0.0432167f,-0.121826f}, +{0.18407f,0.0377581f,-0.117971f},{0.188634f,0.0323774f,-0.113856f},{0.193122f,0.0270848f,-0.109486f}, +{0.197527f,0.0218907f,-0.104866f},{0.206052f,0.0118387f,-0.0948962f},{0.206422f,0.0120131f,-0.0950266f}, +{0.210155f,0.00700034f,-0.0895618f},{0.214142f,0.00229945f,-0.0840052f},{0.218005f,-0.00225518f,-0.0782359f}, +{0.221737f,-0.00665528f,-0.072264f},{0.229166f,-0.0148059f,-0.059862f},{0.232332f,-0.0180071f,-0.0542297f}, +{0.23247f,-0.0187013f,-0.053345f},{0.228781f,-0.0149616f,-0.059756f},{0.232082f,-0.0188542f,-0.0532437f}, +{0.235229f,-0.0225652f,-0.0465757f},{0.238218f,-0.0260893f,-0.039765f},{0.241045f,-0.0294223f,-0.0328251f}, +{0.2462f,-0.0355006f,-0.0186126f},{0.248923f,-0.0381014f,-0.0114399f},{0.248524f,-0.0382409f,-0.0113678f}, +{0.250677f,-0.0407797f,-0.00404916f},{0.252658f,-0.0431164f,0.00332952f},{0.254469f,-0.045251f,0.0107545f}, +{0.256108f,-0.047184f,0.0182123f},{0.257578f,-0.0489169f,0.0256896f},{0.258879f,-0.0504515f,0.0331736f}, +{0.260987f,-0.0529367f,0.0481121f},{0.261799f,-0.0538939f,0.0555431f},{0.262453f,-0.0546661f,0.0629336f}, +{0.12226f,0.111251f,-0.147899f},{0.127011f,0.105649f,-0.147122f},{0.131794f,0.100009f,-0.146109f}, +{0.136604f,0.0943376f,-0.144853f},{0.141433f,0.0886439f,-0.143349f},{0.146273f,0.0829367f,-0.141592f}, +{0.151117f,0.077225f,-0.139579f},{0.155957f,0.0715183f,-0.137305f},{0.160784f,0.0658265f,-0.134769f}, +{0.16559f,0.0601597f,-0.131968f},{0.170366f,0.0545282f,-0.128902f},{0.184425f,0.0379506f,-0.118117f}, +{0.188991f,0.0325661f,-0.114f},{0.193483f,0.0272698f,-0.109627f},{0.197891f,0.0220721f,-0.105003f}, +{0.202207f,0.0169833f,-0.100134f},{0.203042f,0.0165301f,-0.0995149f},{0.210528f,0.00717136f,-0.0896885f}, +{0.214517f,0.00246719f,-0.0841281f},{0.218383f,-0.00209063f,-0.0783547f},{0.222117f,-0.0064938f,-0.0723786f}, +{0.225713f,-0.0107346f,-0.0662105f},{0.235619f,-0.0224148f,-0.0466724f},{0.23861f,-0.0259414f,-0.039857f}, +{0.241439f,-0.0292767f,-0.0329122f},{0.244102f,-0.032417f,-0.0258517f},{0.246597f,-0.0353593f,-0.0186898f}, +{0.247098f,-0.035418f,-0.0180672f},{0.251077f,-0.0406421f,-0.00411618f},{0.25306f,-0.0429804f,0.00326766f}, +{0.254872f,-0.0451164f,0.0106978f},{0.256512f,-0.0470508f,0.0181608f},{0.257983f,-0.0487849f,0.0256434f}, +{0.259285f,-0.0503206f,0.0331326f},{0.260422f,-0.0516605f,0.040616f},{0.261395f,-0.0528075f,0.0480815f}, +{0.262207f,-0.0537654f,0.0555177f},{0.262862f,-0.0545382f,0.0629134f},{0.263364f,-0.0551303f,0.0702583f}, +{0.263717f,-0.0555466f,0.0775425f},{0.122361f,0.111664f,-0.147965f},{0.126952f,0.106251f,-0.147226f}, +{0.131527f,0.100856f,-0.146277f},{0.136082f,0.0954854f,-0.145118f},{0.140613f,0.0901431f,-0.143752f}, +{0.145115f,0.0848342f,-0.142179f},{0.149585f,0.0795631f,-0.1404f},{0.154019f,0.0743346f,-0.138417f}, +{0.158414f,0.069153f,-0.136232f},{0.162764f,0.0640231f,-0.133846f},{0.167067f,0.0589495f,-0.131262f}, +{0.171319f,0.0539366f,-0.128482f},{0.175515f,0.0489885f,-0.125509f},{0.183727f,0.0393048f,-0.118992f}, +{0.187736f,0.0345778f,-0.115454f},{0.191676f,0.0299328f,-0.111734f},{0.195542f,0.0253738f,-0.107835f}, +{0.199332f,0.0209049f,-0.103761f},{0.206669f,0.0122532f,-0.0951008f},{0.21021f,0.00807804f,-0.0905224f}, +{0.213662f,0.00400799f,-0.0857837f},{0.217021f,4.68757e-005f,-0.080889f},{0.220285f,-0.00380184f,-0.0758426f}, +{0.223451f,-0.00753479f,-0.0706488f},{0.226516f,-0.0111487f,-0.0653124f},{0.229477f,-0.0146406f,-0.0598376f}, +{0.235079f,-0.0212454f,-0.0484934f},{0.237714f,-0.0243525f,-0.042634f},{0.240235f,-0.027326f,-0.0366563f}, +{0.242642f,-0.030163f,-0.0305656f},{0.24493f,-0.0328612f,-0.0243674f},{0.249145f,-0.0378313f,-0.0116704f}, +{0.251068f,-0.0400991f,-0.00518257f},{0.252866f,-0.0422192f,0.00139061f},{0.254537f,-0.0441898f,0.00804317f}, +{0.25608f,-0.0460092f,0.0147693f},{0.257494f,-0.0476758f,0.0215631f},{0.258776f,-0.0491881f,0.0284189f}, +{0.259927f,-0.0505448f,0.0353305f},{0.260944f,-0.0517447f,0.0422916f},{0.261828f,-0.0527868f,0.0492962f}, +{0.262577f,-0.0536701f,0.0563382f},{0.263191f,-0.0543939f,0.0634117f},{0.263669f,-0.0549575f,0.0705101f}, +{0.264011f,-0.0553604f,0.0776272f},{0.264216f,-0.0556023f,0.0847567f},{-0.0421135f,0.305602f,0.0428677f}, +{-0.0431344f,0.306274f,0.0485758f},{-0.0421725f,0.30514f,0.0411945f},{-0.0348943f,0.296558f,0.00426646f}, +{-0.0341289f,0.296187f,0.00244165f},{-0.0357808f,0.298135f,0.00901696f},{-0.0445856f,0.307985f,0.0632405f}, +{-0.0450821f,0.30857f,0.0705025f},{-0.0449943f,0.307857f,0.0632202f},{-0.0437274f,0.307505f,0.0567511f}, +{-0.0443341f,0.308221f,0.0637424f},{-0.0465618f,0.309118f,0.084822f},{-0.0467942f,0.309247f,0.0918925f}, +{-0.047093f,0.309365f,0.0848062f},{-0.0460053f,0.308462f,0.0704561f},{-0.0455077f,0.307875f,0.0631783f}, +{-0.0454912f,0.308443f,0.0704874f},{-0.0474899f,0.309833f,0.084788f},{-0.0476948f,0.310316f,0.0918925f}, +{-0.0476466f,0.310397f,0.0847723f},{-0.0465353f,0.308707f,0.0704083f},{-0.0460366f,0.308119f,0.0631143f}, +{-0.0473898f,0.311292f,0.084757f},{-0.0471813f,0.311046f,0.0775429f},{-0.047582f,0.310908f,0.084762f}, +{-0.0477127f,0.310676f,0.0918925f},{-0.0472235f,0.311628f,0.0918925f},{-0.0474707f,0.311354f,0.0918925f}, +{-0.0469501f,0.311305f,0.0776267f},{-0.0439376f,0.307221f,0.0559281f},{-0.042987f,0.306632f,0.0497909f}, +{-0.0471552f,0.311547f,0.0847564f},{-0.0399705f,0.303075f,0.0291561f},{-0.0410491f,0.303815f,0.0337954f}, +{-0.0397614f,0.302297f,0.0263905f},{-0.0411077f,0.304416f,0.0359874f},{-0.0383074f,0.300582f,0.0189921f}, +{-0.0387028f,0.301581f,0.0223799f},{-0.0366854f,0.29867f,0.0116131f},{-0.0373058f,0.299933f,0.015665f}, +{-0.0329336f,0.294246f,-0.00303443f},{-0.0323518f,0.294092f,-0.0040552f},{-0.0285038f,0.289022f,-0.0174445f}, +{-0.0260366f,0.286113f,-0.0245261f},{-0.0262848f,0.286938f,-0.0230172f},{-0.0308032f,0.291734f,-0.010276f}, +{-0.0191526f,0.278528f,-0.0410717f},{-0.021645f,0.281467f,-0.0351634f},{-0.0206068f,0.279711f,-0.0383731f}, +{-0.0240231f,0.284271f,-0.0291434f},{-0.0138336f,0.272256f,-0.0525327f},{-0.0145359f,0.272552f,-0.051709f}, +{-0.0112697f,0.268701f,-0.0581524f},{-0.0176497f,0.276224f,-0.0451116f},{-0.00505546f,0.261906f,-0.0687612f}, +{-0.00429986f,0.260483f,-0.0705281f},{-0.0019264f,0.258216f,-0.0738946f},{-0.00785583f,0.264676f,-0.0644294f}, +{0.00803165f,0.246474f,-0.088404f},{0.00462002f,0.250497f,-0.0837203f},{0.00715869f,0.246971f,-0.0876434f}, +{0.0012997f,0.254412f,-0.0788824f},{0.0032141f,0.251623f,-0.0821454f},{0.0187835f,0.233796f,-0.101489f}, +{0.0153863f,0.23727f,-0.0979716f},{0.0196536f,0.232238f,-0.102786f},{0.0112187f,0.242184f,-0.0929216f}, +{0.0284535f,0.221862f,-0.111682f},{0.0302445f,0.220282f,-0.113046f},{0.0263509f,0.224873f,-0.109369f}, +{0.0225294f,0.229379f,-0.105516f},{0.042324f,0.206039f,-0.122984f},{0.0382345f,0.210861f,-0.119856f}, +{0.0421853f,0.20567f,-0.123123f},{0.0329688f,0.216538f,-0.115753f},{0.046869f,0.200148f,-0.126416f}, +{0.0506736f,0.196194f,-0.12867f},{0.0464716f,0.201148f,-0.125923f},{0.0611154f,0.183349f,-0.134725f}, +{0.0592264f,0.186109f,-0.133582f},{0.0563427f,0.188977f,-0.132217f},{0.0549264f,0.191179f,-0.131224f}, +{0.051591f,0.19458f,-0.129448f},{0.0679525f,0.175819f,-0.137702f},{0.0659006f,0.177707f,-0.136973f}, +{0.0706901f,0.172059f,-0.138964f},{0.0635697f,0.180987f,-0.135742f},{0.076821f,0.165362f,-0.141015f}, +{0.0754758f,0.166416f,-0.140701f},{0.0802502f,0.160787f,-0.142188f},{0.0723708f,0.170609f,-0.13946f}, +{0.085801f,0.154773f,-0.143511f},{0.081299f,0.160082f,-0.142366f},{0.0850057f,0.155179f,-0.14343f}, +{0.0935937f,0.143476f,-0.146244f},{0.0938119f,0.143598f,-0.145714f},{0.0891046f,0.149149f,-0.144944f}, +{0.103705f,0.133131f,-0.146058f},{0.0994105f,0.138726f,-0.145701f},{0.0990909f,0.138571f,-0.145739f}, +{0.103968f,0.133352f,-0.146015f},{0.0944326f,0.144064f,-0.145199f},{0.0897354f,0.149602f,-0.144432f}, +{0.0941219f,0.14382f,-0.145367f},{0.0948607f,0.144091f,-0.145179f},{0.0903229f,0.149442f,-0.144449f}, +{0.0751518f,0.166188f,-0.140865f},{0.0795988f,0.160357f,-0.142696f},{0.0799295f,0.160555f,-0.142353f}, +{0.0888759f,0.149039f,-0.145472f},{0.0894214f,0.149362f,-0.144599f},{0.093558f,0.143518f,-0.146855f}, +{0.0982489f,0.137987f,-0.147398f},{0.0982726f,0.137959f,-0.146786f},{0.0939839f,0.143983f,-0.147732f}, +{0.098692f,0.138431f,-0.148277f},{0.0937144f,0.143713f,-0.147385f},{0.103072f,0.132679f,-0.148251f}, +{0.103355f,0.132933f,-0.148599f},{0.103653f,0.133192f,-0.148767f},{0.103915f,0.133415f,-0.14881f}, +{0.0655698f,0.177487f,-0.137135f},{0.0240122f,0.227099f,-0.107358f},{0.0342068f,0.21561f,-0.116543f}, +{0.0375489f,0.211137f,-0.119568f},{0.0280962f,0.221673f,-0.111826f},{0.0151164f,0.23812f,-0.097292f}, +{0.0115314f,0.242348f,-0.0929291f},{-0.000607728f,0.256129f,-0.076437f},{-0.00808476f,0.265478f,-0.0634867f}, +{0.00283905f,0.251455f,-0.0822683f},{0.00239561f,0.25139f,-0.0825229f},{0.00634876f,0.246729f,-0.0880327f}, +{-0.0110117f,0.268929f,-0.0580755f},{-0.0165481f,0.275457f,-0.0468631f},{-0.028428f,0.289465f,-0.0167902f}, +{-0.0304509f,0.29185f,-0.0104677f},{-0.0234034f,0.283008f,-0.0315068f},{-0.0153929f,0.272365f,-0.0520204f}, +{-0.0180395f,0.276074f,-0.0452083f},{-0.0185135f,0.276045f,-0.0454087f},{-0.0370886f,0.298535f,0.0115564f}, +{-0.0448065f,0.308778f,0.0707584f},{-0.0473856f,0.309657f,0.0918925f},{-0.0451443f,0.309176f,0.0777929f}, +{-0.0454312f,0.308982f,0.0777045f},{-0.0460469f,0.309098f,0.0848323f},{-0.0464337f,0.309168f,0.0918925f}, +{-0.045347f,0.309415f,0.0848396f},{-0.0456374f,0.309225f,0.0848373f},{-0.0457254f,0.309296f,0.0918925f}, +{-0.0460743f,0.309186f,0.0918925f},{-0.0454147f,0.309495f,0.0918925f},{-0.0471187f,0.309415f,0.0918925f}, +{-0.0475847f,0.309968f,0.0918925f},{-0.0458406f,0.308855f,0.0776945f},{-0.0443459f,0.307092f,0.0559028f}, +{-0.0435421f,0.306145f,0.0485453f},{-0.0425796f,0.30501f,0.0411587f},{-0.0414554f,0.303684f,0.0337544f}, +{-0.0401668f,0.302165f,0.0263442f},{-0.0387117f,0.300449f,0.0189407f},{-0.0357954f,0.296423f,0.00407642f}, +{-0.0338304f,0.294106f,-0.00324031f},{-0.0352962f,0.296422f,0.00420461f},{-0.0333341f,0.294108f,-0.00310144f}, +{-0.0312023f,0.291594f,-0.0103481f},{-0.0289012f,0.288881f,-0.0175217f},{-0.0264323f,0.28597f,-0.0246083f}, +{-0.0237973f,0.282863f,-0.0315939f},{-0.0209987f,0.279563f,-0.038465f},{-0.0149235f,0.272399f,-0.0518103f}, +{-0.0116549f,0.268545f,-0.0582583f},{-0.00823869f,0.264517f,-0.0645398f},{-0.00468021f,0.260321f,-0.0706427f}, +{-0.00098547f,0.255965f,-0.0765558f},{0.00678642f,0.2468f,-0.0877701f},{0.0108493f,0.24201f,-0.093052f}, +{0.0150199f,0.237092f,-0.0981056f},{0.0192902f,0.232057f,-0.102923f},{0.0236518f,0.226914f,-0.107499f}, +{0.0411164f,0.205354f,-0.12407f},{0.0368049f,0.210817f,-0.120026f},{0.0364596f,0.210845f,-0.120499f}, +{0.0326147f,0.216345f,-0.1159f},{0.0371981f,0.210941f,-0.119717f},{0.0418378f,0.20547f,-0.123274f}, +{0.0465247f,0.199943f,-0.126571f},{0.0512501f,0.194372f,-0.129604f},{0.0560052f,0.188765f,-0.132375f}, +{0.0607812f,0.183133f,-0.134885f},{0.0703627f,0.171835f,-0.139127f},{0.0748141f,0.165999f,-0.141206f}, +{0.0846884f,0.154943f,-0.143596f},{0.0987835f,0.138323f,-0.145907f},{0.1034f,0.132879f,-0.146226f}, +{-0.0473737f,0.310663f,0.0775529f},{-0.0463552f,0.308874f,0.0776737f},{-0.0448583f,0.307109f,0.0558501f}, +{-0.0440534f,0.30616f,0.0484819f},{-0.0430895f,0.305024f,0.0410845f},{-0.0419636f,0.303696f,0.0336694f}, +{-0.0406731f,0.302174f,0.0262484f},{-0.0392159f,0.300456f,0.018834f},{-0.0375904f,0.298539f,0.011439f}, +{-0.0316955f,0.291588f,-0.0104976f},{-0.0321936f,0.291796f,-0.0107259f},{-0.029884f,0.289073f,-0.017926f}, +{-0.0293911f,0.288871f,-0.0176816f},{-0.0269185f,0.285956f,-0.0247786f},{-0.0242797f,0.282844f,-0.0317744f}, +{-0.0214769f,0.279539f,-0.0386556f},{-0.00914513f,0.264619f,-0.0651178f},{-0.00944459f,0.264972f,-0.065521f}, +{-0.00586379f,0.26075f,-0.0716622f},{-0.0121196f,0.268506f,-0.0584778f},{-0.00869832f,0.264472f,-0.0647685f}, +{-0.00513464f,0.26027f,-0.0708804f},{-0.0014345f,0.255907f,-0.0768021f},{0.0141994f,0.237092f,-0.0988077f}, +{0.0139599f,0.237375f,-0.0992973f},{0.018257f,0.232308f,-0.104145f},{0.0104176f,0.241931f,-0.0933224f}, +{0.0145943f,0.237006f,-0.0983834f},{0.0188708f,0.231964f,-0.103208f},{0.0232388f,0.226813f,-0.10779f}, +{0.0276897f,0.221565f,-0.112123f},{0.0322148f,0.216229f,-0.116203f},{0.0414513f,0.205338f,-0.123589f}, +{0.0461451f,0.199804f,-0.12689f},{0.0508775f,0.194224f,-0.129928f},{0.0556395f,0.188609f,-0.132703f}, +{0.0604225f,0.182969f,-0.135216f},{0.0652181f,0.177314f,-0.137469f},{0.0700179f,0.171654f,-0.139465f}, +{0.0843646f,0.154738f,-0.14394f},{0.102895f,0.132508f,-0.147719f},{0.0984804f,0.138093f,-0.146255f}, +{0.103104f,0.132641f,-0.146574f},{-0.0453858f,0.307352f,0.0557698f},{-0.046886f,0.309121f,0.077642f}, +{-0.044579f,0.3064f,0.0483851f},{-0.0449695f,0.306861f,0.0482734f},{-0.0440009f,0.305719f,0.0408405f}, +{-0.043613f,0.305261f,0.0409712f},{-0.0424846f,0.303931f,0.0335395f},{-0.0411912f,0.302406f,0.026102f}, +{-0.0397308f,0.300684f,0.0186711f},{-0.0381016f,0.298763f,0.0112596f},{-0.0363027f,0.296641f,0.00388058f}, +{-0.0343333f,0.294319f,-0.00345247f},{-0.0274059f,0.286151f,-0.0250388f},{-0.0277523f,0.286559f,-0.025339f}, +{-0.0251008f,0.283433f,-0.0323684f},{-0.0247612f,0.283032f,-0.0320502f},{-0.0219523f,0.27972f,-0.0389468f}, +{-0.0189822f,0.276218f,-0.0457149f},{-0.0158546f,0.27253f,-0.0523413f},{-0.012574f,0.268662f,-0.0588132f}, +{-0.0055735f,0.260407f,-0.0712434f},{-0.00186511f,0.256035f,-0.0771783f},{0.00197355f,0.251508f,-0.0829118f}, +{0.00593551f,0.246837f,-0.088434f},{0.0100134f,0.242028f,-0.0937354f},{0.0184855f,0.232039f,-0.103643f}, +{0.0228632f,0.226877f,-0.108235f},{0.0273241f,0.221617f,-0.112578f},{0.0318592f,0.216269f,-0.116668f}, +{0.0458206f,0.199807f,-0.127378f},{0.0456623f,0.199993f,-0.127941f},{0.0504174f,0.194386f,-0.130993f}, +{0.0505635f,0.194214f,-0.130423f},{0.0553362f,0.188587f,-0.133204f},{0.0601299f,0.182934f,-0.135723f}, +{0.0649361f,0.177267f,-0.137981f},{0.0697467f,0.171595f,-0.139981f},{0.0745535f,0.165927f,-0.141725f}, +{0.0793489f,0.160272f,-0.143219f},{0.0841253f,0.15464f,-0.144466f},{0.102907f,0.132495f,-0.147106f}, +{-0.0469308f,0.309173f,0.0703531f},{-0.0464308f,0.308584f,0.0630404f},{-0.0472824f,0.309588f,0.0776054f}, +{-0.0457783f,0.307814f,0.055677f},{-0.0428696f,0.304385f,0.0333897f},{-0.0415729f,0.302856f,0.0259331f}, +{-0.0401088f,0.301129f,0.0184831f},{-0.0402491f,0.301674f,0.0183202f},{-0.0386121f,0.299744f,0.0108731f}, +{-0.0384754f,0.299203f,0.0110526f},{-0.0366719f,0.297077f,0.00365461f},{-0.0346974f,0.294749f,-0.00369726f}, +{-0.0325522f,0.292219f,-0.0109894f},{-0.0302367f,0.289489f,-0.0182079f},{-0.0222846f,0.280112f,-0.0392827f}, +{-0.0223853f,0.280611f,-0.0395738f},{-0.019401f,0.277092f,-0.0463744f},{-0.0193069f,0.276601f,-0.0460682f}, +{-0.0161713f,0.272904f,-0.0527117f},{-0.0128823f,0.269025f,-0.0592001f},{-0.00214587f,0.256366f,-0.0776124f}, +{-0.00220193f,0.256811f,-0.0779886f},{0.00165512f,0.252264f,-0.0837496f},{0.00170264f,0.251828f,-0.0833607f}, +{0.00567477f,0.247144f,-0.088897f},{0.00976312f,0.242323f,-0.094212f},{0.022646f,0.227133f,-0.108749f}, +{0.0226449f,0.227514f,-0.109195f},{0.0271272f,0.222229f,-0.113558f},{0.0271182f,0.221859f,-0.113103f}, +{0.031665f,0.216498f,-0.117203f},{0.0362772f,0.21106f,-0.121044f},{0.0409459f,0.205555f,-0.124624f}, +{0.0552022f,0.188744f,-0.133782f},{0.0600083f,0.183077f,-0.136307f},{0.0600902f,0.183361f,-0.136814f}, +{0.0649195f,0.177666f,-0.139083f},{0.0648269f,0.177396f,-0.138571f},{0.0696498f,0.171709f,-0.140576f}, +{0.0744689f,0.166026f,-0.142325f},{0.0792766f,0.160357f,-0.143823f},{0.0840654f,0.154711f,-0.145073f}, +{0.0888281f,0.149095f,-0.146082f},{-0.0470862f,0.309736f,0.0703053f},{-0.0465851f,0.309145f,0.0629764f}, +{-0.0474386f,0.310152f,0.0775737f},{-0.0459312f,0.308374f,0.0555966f},{-0.0451206f,0.307418f,0.0481766f}, +{-0.0441499f,0.306274f,0.0407271f},{-0.043016f,0.304937f,0.0332599f},{-0.0417165f,0.303405f,0.0257867f}, +{-0.0368045f,0.297613f,0.00345877f},{-0.0347426f,0.295769f,-0.00404829f},{-0.0348257f,0.295279f,-0.00390942f}, +{-0.0326757f,0.292744f,-0.0112177f},{-0.0303551f,0.290008f,-0.0184523f},{-0.0278652f,0.287072f,-0.0255992f}, +{-0.0252078f,0.283939f,-0.0326442f},{-0.0161484f,0.273844f,-0.0532427f},{-0.0162585f,0.273386f,-0.0530326f}, +{-0.0129621f,0.269499f,-0.0595354f},{-0.00951684f,0.265437f,-0.0658703f},{-0.00592809f,0.261205f,-0.0720252f}, +{0.0057779f,0.24799f,-0.0895609f},{0.00563608f,0.247569f,-0.0892982f},{0.00973349f,0.242738f,-0.0946251f}, +{0.0139396f,0.237778f,-0.0997217f},{0.0182462f,0.2327f,-0.10458f},{0.0318636f,0.217231f,-0.117971f}, +{0.031684f,0.216855f,-0.117667f},{0.0363064f,0.211405f,-0.121517f},{0.0409855f,0.205888f,-0.125105f}, +{0.0457124f,0.200314f,-0.128429f},{0.050478f,0.194695f,-0.131488f},{0.0552735f,0.18904f,-0.134283f}, +{0.0697531f,0.171967f,-0.141092f},{0.0748247f,0.166574f,-0.143185f},{0.0745829f,0.166272f,-0.142845f}, +{0.0794013f,0.16059f,-0.144346f},{0.0842006f,0.154931f,-0.145599f},{0.0889739f,0.149303f,-0.14661f}, +{0.0984157f,0.13817f,-0.147929f},{-0.0476338f,0.311036f,0.0918925f},{-0.0470208f,0.310247f,0.070274f}, +{-0.046519f,0.309655f,0.0629344f},{-0.0458641f,0.308883f,0.055544f},{-0.0450523f,0.307925f,0.0481132f}, +{-0.0440802f,0.306779f,0.040653f},{-0.0429447f,0.30544f,0.0331749f},{-0.0416433f,0.303906f,0.0256909f}, +{-0.0401738f,0.302173f,0.0182135f},{-0.0385344f,0.30024f,0.0107557f},{-0.0367242f,0.298105f,0.00333058f}, +{-0.0323867f,0.293601f,-0.0114393f},{-0.0300372f,0.291363f,-0.0180677f},{-0.0300611f,0.290859f,-0.0186894f}, +{-0.0325894f,0.29323f,-0.0113672f},{-0.0302655f,0.29049f,-0.0186123f},{-0.0277719f,0.287549f,-0.0257695f}, +{-0.0251106f,0.284411f,-0.0328247f},{-0.0222841f,0.281079f,-0.0397644f},{-0.0192955f,0.277555f,-0.0465748f}, +{-0.0128473f,0.269951f,-0.0597549f},{-0.0126308f,0.270306f,-0.0598609f},{-0.00939697f,0.265883f,-0.066099f}, +{-0.00580302f,0.261645f,-0.0722628f},{-0.00207146f,0.257245f,-0.0782348f},{0.00179119f,0.25269f,-0.0840042f}, +{0.0101136f,0.243487f,-0.0950259f},{0.0140191f,0.239414f,-0.0995152f},{0.0143288f,0.238517f,-0.100133f}, +{0.00988127f,0.243151f,-0.0948954f},{0.0140934f,0.238184f,-0.0999994f},{0.0184063f,0.233099f,-0.104865f}, +{0.0228114f,0.227905f,-0.109486f},{0.0273001f,0.222612f,-0.113856f},{0.0364927f,0.211773f,-0.121826f}, +{0.0414329f,0.206557f,-0.125571f},{0.0411786f,0.206247f,-0.125419f},{0.0459123f,0.200666f,-0.128748f}, +{0.0506848f,0.195038f,-0.131812f},{0.0554873f,0.189375f,-0.134611f},{0.0603109f,0.183688f,-0.137145f}, +{0.0651472f,0.177985f,-0.139417f},{0.0699878f,0.172277f,-0.14143f},{0.07965f,0.160884f,-0.144688f}, +{0.0844564f,0.155217f,-0.145943f},{0.0892366f,0.14958f,-0.146956f},{-0.0468282f,0.310629f,0.0702589f}, +{-0.046326f,0.310037f,0.0629142f},{-0.0456706f,0.309264f,0.0555186f},{-0.0448583f,0.308307f,0.0480826f}, +{-0.0438855f,0.30716f,0.0406172f},{-0.0427492f,0.30582f,0.0331338f},{-0.0414469f,0.304284f,0.0256447f}, +{-0.0399763f,0.30255f,0.0181621f},{-0.0383359f,0.300616f,0.010699f},{-0.0365244f,0.29848f,0.00326873f}, +{-0.0345413f,0.296141f,-0.0041153f},{-0.0275658f,0.287916f,-0.0258517f},{-0.0249027f,0.284776f,-0.0329118f}, +{-0.0220742f,0.281441f,-0.0398563f},{-0.0190835f,0.277915f,-0.0466715f},{-0.0159342f,0.274201f,-0.0533441f}, +{-0.0152712f,0.273952f,-0.0542301f},{-0.00917805f,0.266235f,-0.0662094f},{-0.00558159f,0.261994f,-0.0723775f}, +{-0.00184742f,0.257591f,-0.0783537f},{0.00201793f,0.253033f,-0.0841271f},{0.00600743f,0.248329f,-0.0896876f}, +{0.0186446f,0.233428f,-0.105003f},{0.0230528f,0.22823f,-0.109627f},{0.0275447f,0.222934f,-0.114f}, +{0.0321114f,0.217549f,-0.118117f},{0.0367437f,0.212087f,-0.121975f},{0.0374089f,0.211834f,-0.122344f}, +{0.0461698f,0.200972f,-0.128902f},{0.0509457f,0.195341f,-0.131968f},{0.0557515f,0.189674f,-0.134769f}, +{0.0605785f,0.183982f,-0.137305f},{0.0654182f,0.178275f,-0.139579f},{0.0702622f,0.172564f,-0.141593f}, +{0.0751025f,0.166856f,-0.143349f},{0.0799311f,0.161163f,-0.144853f},{0.0847408f,0.155491f,-0.146109f}, +{0.0895244f,0.149851f,-0.147123f},{0.094275f,0.144249f,-0.147899f},{0.0989864f,0.138694f,-0.148445f}, +{-0.0466084f,0.310902f,0.0705096f},{-0.0461304f,0.310339f,0.0634113f},{-0.0455166f,0.309615f,0.056338f}, +{-0.0447675f,0.308732f,0.0492957f},{-0.0438837f,0.30769f,0.042291f},{-0.0428661f,0.30649f,0.0353299f}, +{-0.0417155f,0.305133f,0.0284186f},{-0.0404329f,0.303621f,0.0215629f},{-0.0390195f,0.301954f,0.0147688f}, +{-0.0374764f,0.300135f,0.00804257f},{-0.0358052f,0.298164f,0.00139006f},{-0.0340072f,0.296044f,-0.00518291f}, +{-0.032084f,0.293776f,-0.0116708f},{-0.0278688f,0.288806f,-0.024368f},{-0.0255805f,0.286108f,-0.0305661f}, +{-0.0231746f,0.283271f,-0.0366566f},{-0.0206528f,0.280297f,-0.0426344f},{-0.0180176f,0.27719f,-0.0484939f}, +{-0.0124162f,0.270585f,-0.0598379f},{-0.00945494f,0.267093f,-0.0653124f},{-0.00638994f,0.263479f,-0.0706491f}, +{-0.00322406f,0.259746f,-0.0758429f},{3.99566e-005f,0.255898f,-0.0808893f},{0.00339924f,0.251936f,-0.0857839f}, +{0.00685086f,0.247867f,-0.0905225f},{0.0103919f,0.243691f,-0.095101f},{0.0177293f,0.235039f,-0.103761f}, +{0.0215192f,0.230571f,-0.107835f},{0.0253855f,0.226012f,-0.111734f},{0.029325f,0.221366f,-0.115454f}, +{0.0333339f,0.216639f,-0.118992f},{0.0415463f,0.206956f,-0.125509f},{0.0457426f,0.202008f,-0.128482f}, +{0.0499941f,0.196995f,-0.131262f},{0.054297f,0.191921f,-0.133846f},{0.0586474f,0.186791f,-0.136231f}, +{0.0630417f,0.18161f,-0.138417f},{0.067476f,0.176381f,-0.1404f},{0.0719463f,0.17111f,-0.142179f}, +{0.0764488f,0.165801f,-0.143752f},{0.0809793f,0.160459f,-0.145118f},{0.0855341f,0.155088f,-0.146276f}, +{0.0901092f,0.149694f,-0.147225f},{0.0947004f,0.14428f,-0.147964f},{0.0993037f,0.138852f,-0.148493f}, +{-0.0215492f,0.281886f,-0.0398563f},{-0.0185585f,0.27836f,-0.0466715f},{-0.0108014f,0.27079f,-0.0592001f}, +{-0.00781054f,0.266884f,-0.0658703f},{-0.0112558f,0.270946f,-0.0595354f},{-0.0270408f,0.288362f,-0.0258517f}, +{-0.0243777f,0.285221f,-0.0329118f},{-0.0318617f,0.294046f,-0.0114393f},{-0.0295361f,0.291304f,-0.0186894f}, +{-0.0340163f,0.296587f,-0.0041153f},{-0.0359994f,0.298925f,0.00326873f},{-0.0378109f,0.301061f,0.010699f}, +{-0.0309694f,0.294191f,-0.0112177f},{-0.0314626f,0.294186f,-0.0113672f},{-0.0331194f,0.296727f,-0.00390942f}, +{-0.0394513f,0.302995f,0.0181621f},{-0.0409219f,0.304729f,0.0256447f},{-0.0422242f,0.306265f,0.0331338f}, +{-0.0433605f,0.307605f,0.0406172f},{-0.0443333f,0.308752f,0.0480826f},{-0.0451456f,0.30971f,0.0555186f}, +{-0.045801f,0.310482f,0.0629142f},{-0.0463032f,0.311075f,0.0702589f},{-0.045894f,0.311202f,0.070274f}, +{-0.0453922f,0.31061f,0.0629344f},{-0.0451123f,0.30967f,0.0848373f},{-0.0449201f,0.310054f,0.0848323f}, +{-0.0448555f,0.310565f,0.084822f},{-0.0449255f,0.310447f,0.0918925f},{-0.0451675f,0.309769f,0.0918925f}, +{-0.0449062f,0.309427f,0.0777045f},{-0.0445571f,0.309016f,0.0705025f},{-0.0443644f,0.309399f,0.0704874f}, +{-0.0453799f,0.311183f,0.0703053f},{-0.0448788f,0.310592f,0.0629764f},{-0.0443499f,0.310348f,0.0630404f}, +{-0.0442249f,0.309821f,0.0555966f},{-0.0448499f,0.310938f,0.0703531f},{-0.0466563f,0.311491f,0.0775429f}, +{-0.0462046f,0.311955f,0.0918925f},{-0.0459403f,0.311844f,0.0847723f},{-0.0464552f,0.311864f,0.084762f}, +{-0.045844f,0.311876f,0.0918925f},{-0.0454091f,0.311597f,0.084788f},{-0.0455195f,0.311707f,0.0918925f}, +{-0.046564f,0.311937f,0.0918925f},{-0.0468648f,0.311737f,0.084757f},{-0.0469128f,0.311827f,0.0918925f}, +{-0.0450122f,0.311129f,0.0848062f},{-0.0449434f,0.310806f,0.0918925f},{-0.0154092f,0.274646f,-0.0533441f}, +{-0.0121057f,0.270751f,-0.0598609f},{-0.00865303f,0.26668f,-0.0662094f},{-0.00505658f,0.262439f,-0.0723775f}, +{-0.00132241f,0.258036f,-0.0783537f},{0.00254294f,0.253478f,-0.0841271f},{0.0110081f,0.244107f,-0.0948954f}, +{0.00734237f,0.249017f,-0.0892982f},{0.0114398f,0.244185f,-0.0946251f},{0.00653244f,0.248774f,-0.0896876f}, +{0.0106387f,0.243932f,-0.0950259f},{0.0148538f,0.238962f,-0.100133f},{0.0191697f,0.233873f,-0.105003f}, +{0.0235778f,0.228675f,-0.109627f},{0.0280697f,0.223379f,-0.114f},{0.0326364f,0.217994f,-0.118117f}, +{0.0426918f,0.207335f,-0.125105f},{0.0430268f,0.207319f,-0.124624f},{0.0474187f,0.201761f,-0.128429f}, +{0.0372687f,0.212532f,-0.121975f},{0.0419579f,0.207003f,-0.125571f},{0.0466949f,0.201417f,-0.128902f}, +{0.0514707f,0.195786f,-0.131968f},{0.0562765f,0.190119f,-0.134769f},{0.0611035f,0.184427f,-0.137305f}, +{0.0659432f,0.178721f,-0.139579f},{0.0707872f,0.173009f,-0.141593f},{0.0759515f,0.16753f,-0.143185f}, +{0.0756275f,0.167302f,-0.143349f},{0.0711147f,0.173233f,-0.14143f},{0.0804562f,0.161608f,-0.144853f}, +{0.0900494f,0.150296f,-0.147123f},{0.0855832f,0.156172f,-0.145943f},{0.0903634f,0.150536f,-0.146956f}, +{0.0956389f,0.145282f,-0.146855f},{0.0956746f,0.14524f,-0.146244f},{0.10033f,0.139751f,-0.147398f}, +{0.0813575f,0.162122f,-0.143823f},{0.0861462f,0.156476f,-0.145073f},{0.0859069f,0.156378f,-0.145599f}, +{0.0952487f,0.144775f,-0.145367f},{0.0955182f,0.145045f,-0.145714f},{0.0905482f,0.150318f,-0.144599f}, +{0.104527f,0.133835f,-0.146226f},{0.109238f,0.128572f,-0.146474f},{0.10481f,0.134088f,-0.146574f}, +{0.100122f,0.139617f,-0.147929f},{0.0954207f,0.14516f,-0.147385f},{0.10902f,0.128388f,-0.146297f}, +{0.10423f,0.133576f,-0.146058f},{0.108787f,0.12819f,-0.146158f},{0.0906802f,0.15075f,-0.14661f}, +{0.0909089f,0.15086f,-0.146082f},{0.0998188f,0.139387f,-0.148277f},{0.0951107f,0.144938f,-0.147732f}, +{0.0852658f,0.155937f,-0.146109f},{0.0948f,0.144695f,-0.147899f},{0.0995114f,0.139139f,-0.148445f}, +{0.104178f,0.133637f,-0.148767f},{0.108786f,0.128189f,-0.148876f},{-0.0450535f,0.311155f,0.0918925f}, +{-0.0462469f,0.311618f,0.0775529f},{-0.0447373f,0.309838f,0.055544f},{-0.0439255f,0.308881f,0.0481132f}, +{-0.0429534f,0.307735f,0.040653f},{-0.0418179f,0.306396f,0.0331749f},{-0.0405165f,0.304861f,0.0256909f}, +{-0.039047f,0.303129f,0.0182135f},{-0.0374076f,0.301196f,0.0107557f},{-0.0355974f,0.299061f,0.00333058f}, +{-0.0336158f,0.296724f,-0.00404829f},{-0.0291387f,0.291445f,-0.0186123f},{-0.0266451f,0.288505f,-0.0257695f}, +{-0.0239838f,0.285367f,-0.0328247f},{-0.0211573f,0.282034f,-0.0397644f},{-0.0181687f,0.27851f,-0.0465748f}, +{-0.0150216f,0.274799f,-0.0532427f},{-0.0117205f,0.270907f,-0.0597549f},{-0.00827017f,0.266838f,-0.066099f}, +{-0.00467622f,0.262601f,-0.0722628f},{-0.000944657f,0.258201f,-0.0782348f},{0.00291799f,0.253646f,-0.0840042f}, +{0.0069047f,0.248945f,-0.0895609f},{0.0152202f,0.23914f,-0.0999994f},{0.0195331f,0.234055f,-0.104865f}, +{0.0239382f,0.22886f,-0.109486f},{0.0284269f,0.223568f,-0.113856f},{0.0329904f,0.218187f,-0.117971f}, +{0.0376195f,0.212728f,-0.121826f},{0.0423054f,0.207203f,-0.125419f},{0.0470391f,0.201621f,-0.128748f}, +{0.0518116f,0.195994f,-0.131812f},{0.0566141f,0.190331f,-0.134611f},{0.0614377f,0.184643f,-0.137145f}, +{0.066274f,0.178941f,-0.139417f},{0.0807768f,0.16184f,-0.144688f},{0.0811076f,0.162037f,-0.144346f}, +{0.104482f,0.133888f,-0.148599f},{0.109024f,0.128391f,-0.148751f},{-0.0457323f,0.311599f,0.0775737f}, +{-0.0434143f,0.308866f,0.0481766f},{-0.0424436f,0.307721f,0.0407271f},{-0.0413097f,0.306384f,0.0332599f}, +{-0.0400102f,0.304852f,0.0257867f},{-0.0385428f,0.303121f,0.0183202f},{-0.0369058f,0.301191f,0.0108731f}, +{-0.0350982f,0.29906f,0.00345877f},{-0.0261589f,0.288519f,-0.0255992f},{-0.0286488f,0.291455f,-0.0184523f}, +{-0.0281559f,0.291253f,-0.0182079f},{-0.0235015f,0.285386f,-0.0326442f},{-0.020679f,0.282058f,-0.0395738f}, +{-0.0176947f,0.278539f,-0.0463744f},{-0.0145522f,0.274833f,-0.0530326f},{-0.0042218f,0.262652f,-0.0720252f}, +{-0.000495634f,0.258259f,-0.0779886f},{0.00336142f,0.253711f,-0.0837496f},{0.0203378f,0.234073f,-0.104145f}, +{0.0205663f,0.233803f,-0.103643f},{0.0247268f,0.228898f,-0.108749f},{0.0156459f,0.239226f,-0.0997217f}, +{0.0199525f,0.234147f,-0.10458f},{0.0243512f,0.228961f,-0.109195f},{0.0288334f,0.223676f,-0.113558f}, +{0.0333903f,0.218302f,-0.117667f},{0.0380127f,0.212852f,-0.121517f},{0.0521843f,0.196142f,-0.131488f}, +{0.0569798f,0.190487f,-0.134283f},{0.0617965f,0.184808f,-0.136814f},{0.0666258f,0.179113f,-0.139083f}, +{0.0714594f,0.173414f,-0.141092f},{0.0762892f,0.167719f,-0.142845f},{0.109589f,0.12887f,-0.147687f}, +{0.104976f,0.134273f,-0.147719f},{0.104987f,0.134259f,-0.147106f},{0.104778f,0.134126f,-0.148251f}, +{0.109234f,0.128569f,-0.148558f},{-0.0452527f,0.311466f,0.0918925f},{-0.0452015f,0.311353f,0.0776054f}, +{-0.0436974f,0.309579f,0.055677f},{-0.0428886f,0.308625f,0.0482734f},{-0.0404037f,0.305695f,0.0335395f}, +{-0.0394921f,0.30462f,0.0259331f},{-0.0407888f,0.306149f,0.0333897f},{-0.0419201f,0.307483f,0.0408405f}, +{-0.0380279f,0.302894f,0.0184831f},{-0.0363946f,0.300968f,0.0110526f},{-0.034591f,0.298841f,0.00365461f}, +{-0.0326166f,0.296513f,-0.00369726f},{-0.0304713f,0.293984f,-0.0109894f},{-0.0226804f,0.284797f,-0.0320502f}, +{-0.0202037f,0.281877f,-0.0392827f},{-0.0230199f,0.285197f,-0.0323684f},{-0.0256714f,0.288324f,-0.025339f}, +{-0.017226f,0.278366f,-0.0460682f},{-0.0140905f,0.274668f,-0.0527117f},{-0.00349265f,0.262172f,-0.0712434f}, +{-6.50204e-005f,0.25813f,-0.0776124f},{-0.00378294f,0.262514f,-0.0716622f},{-0.00736374f,0.266737f,-0.065521f}, +{0.00378349f,0.253593f,-0.0833607f},{0.00775562f,0.248909f,-0.088897f},{0.011844f,0.244088f,-0.094212f}, +{0.0160407f,0.23914f,-0.0992973f},{0.0291991f,0.223624f,-0.113103f},{0.0337459f,0.218263f,-0.117203f}, +{0.0383581f,0.212824f,-0.121044f},{0.0526444f,0.195979f,-0.130423f},{0.0572831f,0.190509f,-0.133782f}, +{0.0524982f,0.196151f,-0.130993f},{0.0477432f,0.201758f,-0.127941f},{0.0620891f,0.184842f,-0.136307f}, +{0.0669077f,0.17916f,-0.138571f},{0.0717306f,0.173474f,-0.140576f},{0.0765498f,0.167791f,-0.142325f}, +{0.100187f,0.13954f,-0.146255f},{0.0909567f,0.150803f,-0.145472f},{0.109527f,0.128818f,-0.148015f}, +{0.109406f,0.128715f,-0.14831f},{-0.0444545f,0.310472f,0.0704083f},{-0.0448052f,0.310885f,0.077642f}, +{-0.0439558f,0.309884f,0.0631143f},{-0.0433049f,0.309116f,0.0557698f},{-0.0424982f,0.308165f,0.0483851f}, +{-0.0415321f,0.307026f,0.0409712f},{-0.0391104f,0.30417f,0.026102f},{-0.0342218f,0.298406f,0.00388058f}, +{-0.0360208f,0.300527f,0.0112596f},{-0.0358841f,0.299986f,0.011439f},{-0.0376499f,0.302448f,0.0186711f}, +{-0.0322525f,0.296084f,-0.00345247f},{-0.0301127f,0.293561f,-0.0107259f},{-0.0278032f,0.290838f,-0.017926f}, +{-0.0253251f,0.287916f,-0.0250388f},{-0.0137967f,0.273355f,-0.0518103f},{-0.0136866f,0.273813f,-0.0520204f}, +{-0.0169127f,0.277029f,-0.0452083f},{-0.0198714f,0.281485f,-0.0389468f},{-0.0169013f,0.277983f,-0.0457149f}, +{-0.0137738f,0.274295f,-0.0523413f},{-0.0104931f,0.270427f,-0.0588132f},{-0.00706428f,0.266384f,-0.0651178f}, +{0.00791323f,0.247756f,-0.0877701f},{0.00805506f,0.248176f,-0.0880327f},{0.00396585f,0.252411f,-0.0822683f}, +{0.000215743f,0.257799f,-0.0771783f},{0.0040544f,0.253273f,-0.0829118f},{0.00801636f,0.248601f,-0.088434f}, +{0.0120942f,0.243793f,-0.0937354f},{0.0162803f,0.238857f,-0.0988077f},{0.0339401f,0.218034f,-0.116668f}, +{0.0294049f,0.223381f,-0.112578f},{0.029396f,0.223012f,-0.112123f},{0.0249441f,0.228641f,-0.108235f}, +{0.0385404f,0.212609f,-0.120499f},{0.0431972f,0.207118f,-0.12407f},{0.0479015f,0.201571f,-0.127378f}, +{0.057417f,0.190351f,-0.133204f},{0.0718275f,0.173359f,-0.139981f},{0.067017f,0.179032f,-0.137981f}, +{0.0669244f,0.178761f,-0.137469f},{0.0622107f,0.184699f,-0.135723f},{0.0766344f,0.167691f,-0.141725f}, +{0.0814297f,0.162037f,-0.143219f},{0.0862062f,0.156405f,-0.144466f},{0.0908109f,0.150596f,-0.144944f}, +{0.100353f,0.139723f,-0.146786f},{-0.044299f,0.309909f,0.0704561f},{-0.0446489f,0.310321f,0.0776737f}, +{-0.0438014f,0.309322f,0.0631783f},{-0.043152f,0.308556f,0.0558501f},{-0.0423471f,0.307607f,0.0484819f}, +{-0.0413832f,0.306471f,0.0410845f},{-0.0402573f,0.305143f,0.0336694f},{-0.0389668f,0.303621f,0.0262484f}, +{-0.0375096f,0.301903f,0.018834f},{-0.0341694f,0.297377f,0.00420461f},{-0.0322073f,0.295064f,-0.00310144f}, +{-0.0321242f,0.295553f,-0.00324031f},{-0.0340891f,0.29787f,0.00407642f},{-0.0299892f,0.293036f,-0.0104976f}, +{-0.0276848f,0.290318f,-0.0176816f},{-0.0252122f,0.287403f,-0.0247786f},{-0.0225734f,0.284291f,-0.0317744f}, +{-0.0197706f,0.280986f,-0.0386556f},{-0.0168072f,0.277492f,-0.0454087f},{-0.0104133f,0.269953f,-0.0584778f}, +{-0.00699203f,0.265919f,-0.0647685f},{-0.00342834f,0.261717f,-0.0708804f},{0.000271795f,0.257354f,-0.0768021f}, +{0.00410191f,0.252837f,-0.0825229f},{0.0121239f,0.243378f,-0.0933224f},{0.0163006f,0.238454f,-0.0983834f}, +{0.0205771f,0.233411f,-0.103208f},{0.0249451f,0.22826f,-0.10779f},{0.0337415f,0.217301f,-0.1159f}, +{0.0383249f,0.211896f,-0.119717f},{0.0385112f,0.212264f,-0.120026f},{0.0339211f,0.217677f,-0.116203f}, +{0.0431576f,0.206785f,-0.123589f},{0.0478514f,0.201251f,-0.12689f},{0.0525838f,0.195671f,-0.129928f}, +{0.0573458f,0.190056f,-0.132703f},{0.0621288f,0.184416f,-0.135216f},{0.0717242f,0.173101f,-0.139465f}, +{0.0762786f,0.167144f,-0.140865f},{0.0810563f,0.16151f,-0.142353f},{0.0813051f,0.161804f,-0.142696f}, +{0.0765204f,0.167446f,-0.141206f},{0.0860709f,0.156185f,-0.14394f},{0.109528f,0.128818f,-0.147023f}, +{0.109589f,0.12887f,-0.147351f},{-0.0450044f,0.310086f,0.0918925f},{-0.0447138f,0.309811f,0.0776945f}, +{-0.0438675f,0.308813f,0.0632202f},{-0.0432191f,0.308048f,0.0559028f},{-0.0440605f,0.30843f,0.0632405f}, +{-0.0424153f,0.3071f,0.0485453f},{-0.0414528f,0.305965f,0.0411587f},{-0.0403286f,0.30464f,0.0337544f}, +{-0.03904f,0.30312f,0.0263442f},{-0.0375849f,0.301405f,0.0189407f},{-0.0359618f,0.299491f,0.0115564f}, +{-0.0279788f,0.289468f,-0.0174445f},{-0.0302782f,0.292179f,-0.010276f},{-0.0300755f,0.29255f,-0.0103481f}, +{-0.0277744f,0.289837f,-0.0175217f},{-0.0253055f,0.286925f,-0.0246083f},{-0.0226705f,0.283818f,-0.0315939f}, +{-0.0198719f,0.280518f,-0.038465f},{-0.0107446f,0.269146f,-0.0581524f},{-0.0105281f,0.269501f,-0.0582583f}, +{-0.0140109f,0.272998f,-0.051709f},{-0.00711189f,0.265473f,-0.0645398f},{-0.00355341f,0.261277f,-0.0706427f}, +{0.00014133f,0.25692f,-0.0765558f},{0.0117437f,0.242629f,-0.0929216f},{0.0159114f,0.237715f,-0.0979716f}, +{0.0119761f,0.242965f,-0.093052f},{0.0161467f,0.238048f,-0.0981056f},{0.020417f,0.233012f,-0.102923f}, +{0.0247786f,0.227869f,-0.107499f},{0.029223f,0.222629f,-0.111826f},{0.0427103f,0.206115f,-0.123123f}, +{0.0429646f,0.206426f,-0.123274f},{0.0380739f,0.211582f,-0.119568f},{0.0476515f,0.200899f,-0.126571f}, +{0.0523769f,0.195327f,-0.129604f},{0.057132f,0.18972f,-0.132375f},{0.061908f,0.184089f,-0.134885f}, +{0.0666966f,0.178442f,-0.137135f},{0.0714895f,0.172791f,-0.139127f},{0.0858152f,0.155899f,-0.143596f}, +{0.0996159f,0.139016f,-0.145739f},{0.0949576f,0.144509f,-0.145199f},{0.0999103f,0.139279f,-0.145907f}, +{0.109409f,0.128718f,-0.146724f},{-0.0434125f,0.307666f,0.0559281f},{-0.0426093f,0.306719f,0.0485758f}, +{-0.0416475f,0.305585f,0.0411945f},{-0.0405241f,0.30426f,0.0337954f},{-0.0392364f,0.302742f,0.0263905f}, +{-0.0377824f,0.301027f,0.0189921f},{-0.0361604f,0.299115f,0.0116131f},{-0.0343693f,0.297003f,0.00426646f}, +{-0.0324086f,0.294691f,-0.00303443f},{-0.0255116f,0.286558f,-0.0245261f},{-0.0228784f,0.283454f,-0.0315068f}, +{-0.0200818f,0.280156f,-0.0383731f},{-0.0171247f,0.276669f,-0.0451116f},{-0.00733081f,0.265121f,-0.0644294f}, +{-0.00377484f,0.260928f,-0.0705281f},{-8.27133e-005f,0.256574f,-0.076437f},{0.00373911f,0.252068f,-0.0821454f}, +{0.00768371f,0.247417f,-0.0876434f},{0.0201786f,0.232683f,-0.102786f},{0.0245372f,0.227544f,-0.107358f}, +{0.0289785f,0.222307f,-0.111682f},{0.0334938f,0.216983f,-0.115753f},{0.047394f,0.200593f,-0.126416f}, +{0.052116f,0.195025f,-0.129448f},{0.0568677f,0.189422f,-0.132217f},{0.0616404f,0.183794f,-0.134725f}, +{0.0664256f,0.178152f,-0.136973f},{0.0712151f,0.172504f,-0.138964f},{0.0760009f,0.166861f,-0.140701f}, +{0.0807752f,0.161232f,-0.142188f},{0.0855307f,0.155624f,-0.14343f},{0.0902604f,0.150047f,-0.144432f}, +{0.211424f,0.00837609f,-0.0892991f},{0.207327f,0.0132075f,-0.0946258f},{0.207297f,0.0136221f,-0.0942128f}, +{0.189516f,0.0330114f,-0.114f},{0.194008f,0.0277151f,-0.109627f},{0.18495f,0.0383959f,-0.118117f}, +{0.180317f,0.0438583f,-0.121975f},{0.175628f,0.0493877f,-0.125571f},{0.170891f,0.0549734f,-0.128902f}, +{0.166115f,0.0606049f,-0.131968f},{0.161309f,0.0662717f,-0.134769f},{0.175882f,0.0496979f,-0.125419f}, +{0.171348f,0.0556313f,-0.128429f},{0.176075f,0.0500576f,-0.125105f},{0.156482f,0.0719635f,-0.137305f}, +{0.151642f,0.0776702f,-0.139579f},{0.146798f,0.0833819f,-0.141592f},{0.137129f,0.0947828f,-0.144853f}, +{0.141958f,0.0890892f,-0.143349f},{0.132319f,0.100454f,-0.146109f},{0.127536f,0.106094f,-0.147122f}, +{0.122786f,0.111696f,-0.147899f},{0.113356f,0.122814f,-0.146057f},{0.123077f,0.111963f,-0.147731f}, +{0.127824f,0.106365f,-0.146955f},{0.122628f,0.111882f,-0.145199f},{0.122939f,0.112125f,-0.145366f}, +{0.11797f,0.117374f,-0.145739f},{0.128232f,0.10685f,-0.146081f},{0.13286f,0.101014f,-0.145599f}, +{0.128086f,0.106643f,-0.14661f},{0.113957f,0.123303f,-0.146574f},{0.114154f,0.12345f,-0.147105f}, +{0.11366f,0.123066f,-0.146225f},{0.123346f,0.112232f,-0.147384f},{0.114166f,0.123436f,-0.147719f}, +{0.113408f,0.122753f,-0.148767f},{0.113706f,0.123012f,-0.148599f},{0.118074f,0.117251f,-0.148445f}, +{0.113989f,0.123266f,-0.148251f},{0.123502f,0.112427f,-0.146855f},{0.198416f,0.0225174f,-0.105003f}, +{0.202732f,0.0174285f,-0.100134f},{0.206947f,0.0124584f,-0.0950266f},{0.211053f,0.00761661f,-0.0896885f}, +{0.215042f,0.00291244f,-0.0841281f},{0.218908f,-0.00164537f,-0.0783547f},{0.222642f,-0.00604854f,-0.0723786f}, +{0.229908f,-0.014006f,-0.059756f},{0.226577f,-0.00949148f,-0.0658715f},{0.230023f,-0.0135541f,-0.0595366f}, +{0.226238f,-0.0102893f,-0.0662105f},{0.229691f,-0.0143607f,-0.059862f},{0.232995f,-0.018256f,-0.053345f}, +{0.236144f,-0.0219695f,-0.0466724f},{0.239135f,-0.0254962f,-0.039857f},{0.241964f,-0.0288315f,-0.0329122f}, +{0.244627f,-0.0319717f,-0.0258517f},{0.249737f,-0.0367996f,-0.0112184f},{0.249613f,-0.0362743f,-0.01099f}, +{0.251887f,-0.0393348f,-0.00391029f},{0.247122f,-0.034914f,-0.0186898f},{0.249448f,-0.0376562f,-0.0114399f}, +{0.251602f,-0.0401968f,-0.00411618f},{0.253585f,-0.0425352f,0.00326766f},{0.255397f,-0.0446712f,0.0106978f}, +{0.257037f,-0.0466056f,0.0181608f},{0.258508f,-0.0483397f,0.0256434f},{0.25981f,-0.0498754f,0.0331326f}, +{0.261141f,-0.0508348f,0.0406518f},{0.260947f,-0.0512152f,0.040616f},{0.260006f,-0.0494959f,0.0331736f}, +{0.26192f,-0.0523623f,0.0480815f},{0.264708f,-0.0544525f,0.0847721f},{0.264344f,-0.0536435f,0.077605f}, +{0.264551f,-0.0538881f,0.0847878f},{0.263067f,-0.0525174f,0.0704555f},{0.263597f,-0.0527627f,0.0704077f}, +{0.262569f,-0.0519307f,0.0631775f},{0.262925f,-0.0529383f,0.0555431f},{0.26358f,-0.0537105f,0.0629336f}, +{0.263387f,-0.0540929f,0.0629134f},{0.262552f,-0.0524986f,0.0704868f},{0.262056f,-0.0519127f,0.0632194f}, +{0.263108f,-0.0531536f,0.0848321f},{0.263495f,-0.053223f,0.0918925f},{0.263623f,-0.0531734f,0.0848218f}, +{0.263492f,-0.0526395f,0.0630396f},{0.264147f,-0.0537919f,0.0703047f},{0.263646f,-0.0532011f,0.0629755f}, +{0.262698f,-0.0532807f,0.0848371f},{0.263135f,-0.0532409f,0.0918925f},{0.262839f,-0.0518701f,0.0556761f}, +{0.262992f,-0.05243f,0.0555957f},{0.262031f,-0.0509164f,0.0482723f},{0.262786f,-0.053351f,0.0918925f}, +{0.262732f,-0.0533202f,0.0555177f},{0.264242f,-0.0551013f,0.0775425f},{0.263889f,-0.054685f,0.0702583f}, +{0.264082f,-0.0543022f,0.0702734f},{0.264451f,-0.055347f,0.0847568f},{0.118369f,0.117514f,-0.148277f}, +{0.132604f,0.100729f,-0.145943f},{0.13741f,0.0950613f,-0.144688f},{0.142235f,0.0893717f,-0.143185f}, +{0.147072f,0.0836684f,-0.141429f},{0.151913f,0.0779607f,-0.139417f},{0.156749f,0.072258f,-0.137145f}, +{0.161573f,0.0665701f,-0.134611f},{0.166375f,0.0609073f,-0.131812f},{0.171148f,0.0552797f,-0.128748f}, +{0.180568f,0.0441723f,-0.121826f},{0.185197f,0.0387137f,-0.117971f},{0.189761f,0.033333f,-0.113856f}, +{0.194249f,0.0280404f,-0.109486f},{0.198654f,0.0228463f,-0.104866f},{0.202967f,0.017761f,-0.1f}, +{0.207179f,0.0127943f,-0.0948962f},{0.211282f,0.00795595f,-0.0895618f},{0.215269f,0.00325506f,-0.0840052f}, +{0.219132f,-0.00129956f,-0.0782359f},{0.222863f,-0.00569967f,-0.072264f},{0.226457f,-0.00993752f,-0.0661002f}, +{0.233209f,-0.0178986f,-0.0532437f},{0.236356f,-0.0216096f,-0.0465757f},{0.239345f,-0.0251337f,-0.039765f}, +{0.242172f,-0.0284667f,-0.0328251f},{0.244833f,-0.0316048f,-0.0257695f},{0.247326f,-0.034545f,-0.0186126f}, +{0.24965f,-0.0372852f,-0.0113678f},{0.251803f,-0.0398241f,-0.00404916f},{0.253785f,-0.0421608f,0.00332952f}, +{0.255595f,-0.0442954f,0.0107545f},{0.257235f,-0.0462284f,0.0182123f},{0.258704f,-0.0479613f,0.0256896f}, +{0.262114f,-0.0519811f,0.0481121f},{0.262182f,-0.0514742f,0.0481755f},{0.264643f,-0.0549637f,0.0847617f}, +{0.264435f,-0.0547182f,0.0775525f},{0.264695f,-0.0550917f,0.0918925f},{0.264532f,-0.055409f,0.0918925f}, +{0.118645f,0.117775f,-0.147929f},{0.137659f,0.0953554f,-0.144345f},{0.142477f,0.089674f,-0.142845f}, +{0.147307f,0.083979f,-0.141092f},{0.152141f,0.0782795f,-0.139082f},{0.15697f,0.072585f,-0.136814f}, +{0.161787f,0.0669054f,-0.134283f},{0.166582f,0.0612508f,-0.131488f},{0.185377f,0.0390894f,-0.117667f}, +{0.180754f,0.04454f,-0.121517f},{0.180784f,0.0448852f,-0.121044f},{0.189934f,0.0337164f,-0.113559f}, +{0.194416f,0.0284315f,-0.109195f},{0.198814f,0.0232449f,-0.104581f},{0.203121f,0.0181669f,-0.0997223f}, +{0.215405f,0.00368201f,-0.0837506f},{0.219262f,-0.000866029f,-0.0779897f},{0.222988f,-0.00525976f,-0.0720263f}, +{0.236368f,-0.020656f,-0.046069f},{0.236043f,-0.0202731f,-0.0457157f},{0.239345f,-0.0241672f,-0.0392833f}, +{0.233319f,-0.017441f,-0.0530336f},{0.236462f,-0.0211466f,-0.0463752f},{0.239446f,-0.0246657f,-0.0395744f}, +{0.242269f,-0.0279938f,-0.0326445f},{0.244926f,-0.0311274f,-0.0255992f},{0.247416f,-0.0340633f,-0.0184526f}, +{0.253865f,-0.0416681f,0.00345771f},{0.255673f,-0.0437996f,0.0108719f},{0.25731f,-0.0457298f,0.0183189f}, +{0.258778f,-0.0474602f,0.0257854f},{0.260077f,-0.0489926f,0.0332586f},{0.261211f,-0.0503296f,0.0407259f}, +{0.2645f,-0.0542073f,0.0775733f},{0.263992f,-0.053229f,0.0703525f},{0.264774f,-0.0547312f,0.0918925f}, +{0.118812f,0.117958f,-0.147398f},{0.132995f,0.101235f,-0.145073f},{0.137784f,0.095588f,-0.143822f}, +{0.147313f,0.0843511f,-0.13998f},{0.152233f,0.0785499f,-0.138571f},{0.14741f,0.0842368f,-0.140576f}, +{0.142591f,0.0899192f,-0.142325f},{0.157052f,0.0728681f,-0.136307f},{0.161858f,0.0672011f,-0.133782f}, +{0.166643f,0.061559f,-0.130993f},{0.171398f,0.055952f,-0.127941f},{0.176115f,0.0503905f,-0.124624f}, +{0.189737f,0.0343283f,-0.112579f},{0.194415f,0.0288123f,-0.10875f},{0.189942f,0.0340856f,-0.113104f}, +{0.185396f,0.0394466f,-0.117203f},{0.198803f,0.0236373f,-0.104146f},{0.2031f,0.0185705f,-0.0992979f}, +{0.215087f,0.00443712f,-0.0829128f},{0.219206f,-0.000420286f,-0.0776135f},{0.215358f,0.00411768f,-0.0833616f}, +{0.211385f,0.00880137f,-0.0888979f},{0.222924f,-0.00480429f,-0.0716633f},{0.226505f,-0.00902663f,-0.0655221f}, +{0.229943f,-0.0130802f,-0.0592012f},{0.233232f,-0.0169586f,-0.0527127f},{0.242162f,-0.027488f,-0.0323688f}, +{0.244813f,-0.0306146f,-0.025339f},{0.247298f,-0.0335441f,-0.0182083f},{0.253364f,-0.0406967f,0.00387953f}, +{0.255536f,-0.0432588f,0.0110514f},{0.253733f,-0.041132f,0.00365355f},{0.251758f,-0.0388039f,-0.00369814f}, +{0.25717f,-0.0451848f,0.0184819f},{0.258634f,-0.0469113f,0.0259318f},{0.259931f,-0.0484403f,0.0333884f}, +{0.261062f,-0.0497743f,0.0408392f},{0.263098f,-0.0521747f,0.0631135f},{0.264756f,-0.0543717f,0.0918925f}, +{0.123467f,0.112469f,-0.146243f},{0.118788f,0.117986f,-0.146785f},{0.128185f,0.106907f,-0.145472f}, +{0.132935f,0.101305f,-0.144466f},{0.137711f,0.0956732f,-0.143218f},{0.142507f,0.0900189f,-0.141725f}, +{0.152124f,0.0786788f,-0.137981f},{0.166497f,0.0617313f,-0.130423f},{0.161724f,0.067359f,-0.133204f}, +{0.161421f,0.067337f,-0.132703f},{0.15693f,0.0730115f,-0.135723f},{0.17124f,0.0561387f,-0.127378f}, +{0.175944f,0.0505915f,-0.12407f},{0.180601f,0.0451003f,-0.120499f},{0.185202f,0.0396756f,-0.116668f}, +{0.20204f,0.0188534f,-0.0981062f},{0.202466f,0.0189389f,-0.098384f},{0.19777f,0.0238885f,-0.102924f}, +{0.194197f,0.0290685f,-0.108236f},{0.198575f,0.0239067f,-0.103644f},{0.202861f,0.018853f,-0.0988083f}, +{0.207047f,0.0139172f,-0.0937362f},{0.211125f,0.00910882f,-0.0884349f},{0.225299f,-0.00857174f,-0.0645409f}, +{0.225759f,-0.00852633f,-0.0647696f},{0.22174f,-0.00437572f,-0.0706439f},{0.218925f,-8.92274e-005f,-0.0771794f}, +{0.222634f,-0.004462f,-0.0712445f},{0.226205f,-0.00867353f,-0.065119f},{0.229634f,-0.0127167f,-0.0588143f}, +{0.232915f,-0.0165852f,-0.0523423f},{0.244467f,-0.0302062f,-0.0250388f},{0.241822f,-0.0270876f,-0.0320505f}, +{0.241341f,-0.0268995f,-0.0317747f},{0.239013f,-0.0237754f,-0.0389474f},{0.246945f,-0.0331282f,-0.0179263f}, +{0.249254f,-0.0358514f,-0.0107265f},{0.251394f,-0.0383745f,-0.00345334f},{0.255163f,-0.042818f,0.0112584f}, +{0.259546f,-0.0479863f,0.0335382f},{0.258252f,-0.0464612f,0.0261007f},{0.257734f,-0.0462299f,0.0262471f}, +{0.256792f,-0.044739f,0.0186698f},{0.260674f,-0.0493168f,0.04097f},{0.26164f,-0.050456f,0.048384f}, +{0.262447f,-0.0514073f,0.0557688f},{0.263947f,-0.0531761f,0.0776416f},{0.264154f,-0.0534201f,0.084806f}, +{0.264446f,-0.0537122f,0.0918925f},{0.264646f,-0.0540229f,0.0918925f},{0.123249f,0.112347f,-0.145713f}, +{0.11858f,0.117852f,-0.146254f},{0.127956f,0.106797f,-0.144944f},{0.132696f,0.101208f,-0.14394f}, +{0.137461f,0.0955882f,-0.142695f},{0.142246f,0.0899465f,-0.141205f},{0.147042f,0.0842913f,-0.139464f}, +{0.151842f,0.0786316f,-0.137469f},{0.156638f,0.0729769f,-0.135216f},{0.16581f,0.0615739f,-0.129604f}, +{0.170536f,0.0560018f,-0.126571f},{0.170915f,0.0561416f,-0.12689f},{0.166183f,0.0617218f,-0.129928f}, +{0.175609f,0.0506068f,-0.123589f},{0.180256f,0.0451278f,-0.120026f},{0.184846f,0.0397152f,-0.116203f}, +{0.189371f,0.0343798f,-0.112124f},{0.193822f,0.0291317f,-0.10779f},{0.19819f,0.0239814f,-0.103209f}, +{0.206643f,0.0140141f,-0.0933231f},{0.210711f,0.00921645f,-0.0880336f},{0.214665f,0.00455514f,-0.0825239f}, +{0.218495f,3.88646e-005f,-0.0768032f},{0.222195f,-0.00432417f,-0.0708815f},{0.22918f,-0.0125605f,-0.0584789f}, +{0.232453f,-0.0164204f,-0.0520214f},{0.235574f,-0.0201001f,-0.0454095f},{0.238538f,-0.0235946f,-0.0386562f}, +{0.243493f,-0.0300252f,-0.0246083f},{0.245962f,-0.0329364f,-0.017522f},{0.246452f,-0.0329266f,-0.017682f}, +{0.243979f,-0.0300111f,-0.0247786f},{0.248756f,-0.0356438f,-0.0104982f},{0.250891f,-0.0381612f,-0.00324118f}, +{0.252856f,-0.0404783f,0.00407537f},{0.254651f,-0.0425948f,0.0114378f},{0.256277f,-0.0445116f,0.0188328f}, +{0.259025f,-0.0477516f,0.0336681f},{0.259641f,-0.0490654f,0.0411575f},{0.260603f,-0.0502004f,0.0485442f}, +{0.261115f,-0.0502158f,0.0484808f},{0.260151f,-0.0490792f,0.0410833f},{0.26192f,-0.051165f,0.0558492f}, +{0.263416f,-0.0529299f,0.0776733f},{0.263855f,-0.0533019f,0.0918925f},{0.26418f,-0.0534707f,0.0918925f}, +{0.118277f,0.117622f,-0.145907f},{0.127639f,0.106583f,-0.144598f},{0.132372f,0.101002f,-0.143596f}, +{0.127325f,0.106343f,-0.144431f},{0.137131f,0.0953908f,-0.142353f},{0.141908f,0.0897573f,-0.140865f}, +{0.146697f,0.0841104f,-0.139127f},{0.15149f,0.0784589f,-0.137134f},{0.156279f,0.0728125f,-0.134885f}, +{0.161055f,0.0671808f,-0.132375f},{0.179512f,0.0448077f,-0.119568f},{0.174875f,0.0502749f,-0.123123f}, +{0.175223f,0.0504751f,-0.123274f},{0.179863f,0.0450041f,-0.119717f},{0.184446f,0.0395993f,-0.1159f}, +{0.188964f,0.0342717f,-0.111826f},{0.193409f,0.0290313f,-0.107499f},{0.205842f,0.0137614f,-0.0929223f}, +{0.206211f,0.0139358f,-0.0930527f},{0.201674f,0.0186755f,-0.0979722f},{0.210274f,0.00914513f,-0.087771f}, +{0.214221f,0.00449063f,-0.0822693f},{0.218046f,-1.90473e-005f,-0.0765569f},{0.22833f,-0.0127558f,-0.0581535f}, +{0.231596f,-0.0166073f,-0.0517099f},{0.228715f,-0.0126001f,-0.0582594f},{0.231984f,-0.0164543f,-0.0518113f}, +{0.2351f,-0.0201286f,-0.0452091f},{0.238059f,-0.023618f,-0.0384656f},{0.240858f,-0.026918f,-0.0315942f}, +{0.247864f,-0.035789f,-0.0102766f},{0.248263f,-0.0356496f,-0.0103487f},{0.245565f,-0.0330777f,-0.0174448f}, +{0.250395f,-0.0381634f,-0.0031023f},{0.252357f,-0.040477f,0.00420356f},{0.25415f,-0.0425905f,0.0115553f}, +{0.255773f,-0.0445045f,0.0189394f},{0.257228f,-0.0462203f,0.026343f},{0.258517f,-0.0477397f,0.0337531f}, +{0.261407f,-0.0511481f,0.0559018f},{0.262492f,-0.0530377f,0.0777041f},{0.262143f,-0.0526261f,0.0705019f}, +{0.262902f,-0.0529105f,0.077694f},{0.132055f,0.100766f,-0.143429f},{0.13681f,0.095159f,-0.142188f}, +{0.141584f,0.0895295f,-0.140701f},{0.14637f,0.0838865f,-0.138964f},{0.151159f,0.078239f,-0.136973f}, +{0.155945f,0.0725966f,-0.134725f},{0.160717f,0.0669689f,-0.132217f},{0.165469f,0.0613659f,-0.129448f}, +{0.170191f,0.0557978f,-0.126416f},{0.184092f,0.0394068f,-0.115753f},{0.188607f,0.034083f,-0.111682f}, +{0.193048f,0.0288463f,-0.107358f},{0.197407f,0.0237071f,-0.102786f},{0.209901f,0.0089741f,-0.0876442f}, +{0.213846f,0.00432289f,-0.0821464f},{0.217668f,-0.000183612f,-0.0764381f},{0.22136f,-0.00453721f,-0.0705292f}, +{0.224916f,-0.00873028f,-0.0644306f},{0.23471f,-0.020279f,-0.0451124f},{0.237668f,-0.0237659f,-0.0383737f}, +{0.240464f,-0.0270636f,-0.0315071f},{0.243098f,-0.0301686f,-0.0245261f},{0.249994f,-0.038301f,-0.0030353f}, +{0.251955f,-0.0406131f,0.00426541f},{0.253746f,-0.042725f,0.0116119f},{0.255368f,-0.0446377f,0.0189909f}, +{0.256823f,-0.0463522f,0.0263892f},{0.25811f,-0.0478706f,0.0337941f},{0.259234f,-0.0491954f,0.0411933f}, +{0.260196f,-0.0503295f,0.0485748f},{0.260999f,-0.0512766f,0.0559272f},{0.261647f,-0.0520407f,0.0632397f}, +{-0.164482f,0.077386f,-0.141015f},{-0.160376f,0.0813663f,-0.142188f},{-0.165975f,0.076557f,-0.140701f}, +{-0.193989f,0.0524965f,-0.129448f},{-0.195149f,0.0510464f,-0.12867f},{-0.190161f,0.0553306f,-0.131224f}, +{-0.144011f,0.0959421f,-0.145366f},{-0.144282f,0.0962099f,-0.145713f},{-0.149803f,0.0914681f,-0.144944f}, +{-0.154798f,0.0861567f,-0.143429f},{-0.15923f,0.0818969f,-0.142366f},{-0.155583f,0.0868273f,-0.144466f}, +{-0.150012f,0.0916126f,-0.145472f},{-0.143742f,0.0956526f,-0.145199f},{-0.149524f,0.0912072f,-0.144598f}, +{-0.149251f,0.0909211f,-0.144431f},{-0.13357f,0.105734f,-0.147719f},{-0.133556f,0.105746f,-0.147105f}, +{-0.128196f,0.110381f,-0.147351f},{-0.144478f,0.096365f,-0.146243f},{-0.127892f,0.110028f,-0.148558f}, +{-0.133182f,0.105243f,-0.148599f},{-0.133422f,0.105538f,-0.148251f},{-0.128143f,0.11032f,-0.148015f}, +{-0.138114f,0.100033f,-0.148493f},{-0.138401f,0.10024f,-0.148445f},{-0.132929f,0.10494f,-0.148767f}, +{-0.132705f,0.104679f,-0.14881f},{-0.12751f,0.109583f,-0.148876f},{-0.127291f,0.109328f,-0.148916f}, +{-0.174884f,0.0684522f,-0.137702f},{-0.171588f,0.0717361f,-0.138964f},{-0.177206f,0.0669114f,-0.136973f}, +{-0.169701f,0.0729032f,-0.13946f},{-0.182818f,0.062091f,-0.134725f},{-0.180024f,0.0640372f,-0.135742f}, +{-0.188716f,0.0575456f,-0.132375f},{-0.188416f,0.0572832f,-0.132217f},{-0.185118f,0.0596621f,-0.133582f}, +{-0.199528f,0.0477396f,-0.126416f},{-0.200078f,0.0468134f,-0.125923f},{-0.210459f,0.0383507f,-0.119568f}, +{-0.215831f,0.0337366f,-0.115753f},{-0.214463f,0.0344587f,-0.116543f},{-0.205021f,0.0430213f,-0.123123f}, +{-0.228159f,0.0226953f,-0.105516f},{-0.223677f,0.0265448f,-0.109369f},{-0.226336f,0.0247146f,-0.107358f}, +{-0.21911f,0.0304671f,-0.113046f},{-0.236853f,0.0152278f,-0.0972923f},{-0.236452f,0.0160256f,-0.0979722f}, +{-0.24134f,0.0118274f,-0.0929223f},{-0.231448f,0.0203242f,-0.102786f},{-0.249164f,0.00465414f,-0.0837205f}, +{-0.250729f,0.00376401f,-0.0821464f},{-0.253058f,0.00130946f,-0.0788827f},{-0.246102f,0.00773759f,-0.0876442f}, +{-0.264065f,-0.00814415f,-0.0634868f},{-0.260512f,-0.00509248f,-0.0687614f},{-0.263712f,-0.00738746f,-0.0644306f}, +{-0.256842f,-0.00194036f,-0.0738949f},{-0.259542f,-0.00380527f,-0.0705292f},{-0.273991f,-0.0166696f,-0.0468636f}, +{-0.271547f,-0.0141168f,-0.0517099f},{-0.2752f,-0.0172537f,-0.0451124f},{-0.267717f,-0.0108265f,-0.0581535f}, +{-0.281948f,-0.0230499f,-0.0315071f},{-0.282759f,-0.0241996f,-0.0291439f},{-0.27997f,-0.0218041f,-0.0351637f}, +{-0.277046f,-0.0192933f,-0.041072f},{-0.290298f,-0.0306748f,-0.010468f},{-0.287925f,-0.0286369f,-0.0167907f}, +{-0.290627f,-0.030504f,-0.0102766f},{-0.285037f,-0.0257024f,-0.0245261f},{-0.293126f,-0.0326501f,-0.0030353f}, +{-0.294612f,-0.0343798f,0.00244111f},{-0.292527f,-0.0325897f,-0.00405553f},{-0.299429f,-0.0380636f,0.0189909f}, +{-0.298338f,-0.0375801f,0.0156645f},{-0.297526f,-0.0364296f,0.0116119f},{-0.296549f,-0.0360438f,0.00901635f}, +{-0.295426f,-0.0346253f,0.00426541f},{-0.301463f,-0.0402644f,0.0291557f},{-0.302645f,-0.0408255f,0.0337941f}, +{-0.302797f,-0.04141f,0.0359868f},{-0.301134f,-0.0395283f,0.0263892f},{-0.299976f,-0.0389874f,0.0223796f}, +{-0.303977f,-0.0424232f,0.0428671f},{-0.30509f,-0.0429262f,0.0485748f},{-0.305001f,-0.0433031f,0.0497904f}, +{-0.303962f,-0.0419573f,0.0411933f},{-0.308026f,-0.0454474f,0.0848371f},{-0.307848f,-0.0457485f,0.0918925f}, +{-0.307769f,-0.0456805f,0.0848393f},{-0.305869f,-0.044049f,0.0567509f},{-0.306032f,-0.0437353f,0.0559272f}, +{-0.307375f,-0.0448882f,0.0705019f},{-0.307759f,-0.0446979f,0.0704868f},{-0.308168f,-0.0450498f,0.077694f}, +{-0.307531f,-0.0454763f,0.0777923f},{-0.306581f,-0.0446602f,0.0637421f},{-0.307135f,-0.0451361f,0.0707579f}, +{-0.307784f,-0.0452398f,0.0777041f},{-0.306792f,-0.044388f,0.0632397f},{-0.30868f,-0.0449881f,0.0776733f}, +{-0.309485f,-0.0453564f,0.084806f},{-0.308922f,-0.0451961f,0.0848218f},{-0.305473f,-0.0427346f,0.0485442f}, +{-0.304344f,-0.041765f,0.0411575f},{-0.308269f,-0.0446357f,0.0704555f},{-0.307176f,-0.0441974f,0.0632194f}, +{-0.307686f,-0.0441345f,0.0631775f},{-0.30598f,-0.0426695f,0.0484808f},{-0.309295f,-0.0451931f,0.0703525f}, +{-0.308709f,-0.0446894f,0.0630396f},{-0.309537f,-0.0457246f,0.0703047f},{-0.308247f,-0.0442923f,0.0631135f}, +{-0.308831f,-0.0447947f,0.0704077f},{-0.309553f,-0.0462388f,0.0702734f},{-0.309967f,-0.0465942f,0.0775525f}, +{-0.310303f,-0.0465537f,0.0918925f},{-0.310194f,-0.0462889f,0.0847721f},{-0.310211f,-0.046804f,0.0847617f}, +{-0.310081f,-0.0472127f,0.0847568f},{-0.310171f,-0.0472612f,0.0918925f},{-0.310283f,-0.046913f,0.0918925f}, +{-0.30997f,-0.0475707f,0.0918925f},{-0.301514f,-0.0393343f,0.026343f},{-0.278668f,-0.0202326f,-0.0383737f}, +{-0.285411f,-0.0264779f,-0.0230178f},{-0.28793f,-0.0281877f,-0.0174448f},{-0.282314f,-0.0228442f,-0.0315942f}, +{-0.270808f,-0.0139352f,-0.0525331f},{-0.267498f,-0.0110925f,-0.0580758f},{-0.255211f,-8.59432e-005f,-0.0764381f}, +{-0.245163f,0.00809075f,-0.088404f},{-0.259892f,-0.00358602f,-0.0706439f},{-0.260333f,-0.0034637f,-0.0708815f}, +{-0.264512f,-0.00705366f,-0.0647696f},{-0.241058f,0.0116164f,-0.0929293f},{-0.232552f,0.0189219f,-0.101489f}, +{-0.209739f,0.0385159f,-0.119856f},{-0.204942f,0.0426353f,-0.122984f},{-0.221127f,0.0291884f,-0.111682f}, +{-0.237193f,0.0164102f,-0.098384f},{-0.231778f,0.0205605f,-0.102924f},{-0.232178f,0.0207181f,-0.103209f}, +{-0.15395f,0.0864318f,-0.14351f},{-0.148646f,0.090987f,-0.144448f},{-0.143324f,0.0955583f,-0.145179f}, +{-0.133384f,0.10557f,-0.146574f},{-0.128144f,0.110321f,-0.147023f},{-0.138279f,0.100345f,-0.145739f}, +{-0.137988f,0.100142f,-0.145701f},{-0.132868f,0.104993f,-0.146057f},{-0.132642f,0.104733f,-0.146014f}, +{-0.128196f,0.110381f,-0.147687f},{-0.12751f,0.109583f,-0.146158f},{-0.127291f,0.109328f,-0.146119f}, +{-0.12771f,0.109815f,-0.146297f},{-0.127896f,0.110032f,-0.146474f},{-0.133129f,0.105289f,-0.146225f}, +{-0.128042f,0.110202f,-0.146724f},{-0.138543f,0.100638f,-0.145907f},{-0.155075f,0.0864395f,-0.143596f}, +{-0.160656f,0.0816457f,-0.142353f},{-0.16626f,0.0768329f,-0.140865f},{-0.171877f,0.0720087f,-0.139127f}, +{-0.177498f,0.0671806f,-0.137134f},{-0.183114f,0.0623568f,-0.134885f},{-0.194638f,0.0529602f,-0.129928f}, +{-0.200189f,0.0481929f,-0.12689f},{-0.194293f,0.0527555f,-0.129604f},{-0.199836f,0.0479952f,-0.126571f}, +{-0.205333f,0.0432736f,-0.123274f},{-0.210775f,0.0385997f,-0.119717f},{-0.216151f,0.0339824f,-0.1159f}, +{-0.22145f,0.0294309f,-0.111826f},{-0.226663f,0.024954f,-0.107499f},{-0.236786f,0.0162589f,-0.0981062f}, +{-0.241678f,0.0120577f,-0.0930527f},{-0.246443f,0.00796499f,-0.087771f},{-0.251073f,0.00398861f,-0.0822693f}, +{-0.255558f,0.000135934f,-0.0765569f},{-0.264066f,-0.00717073f,-0.0645409f},{-0.268073f,-0.0106122f,-0.0582594f}, +{-0.271906f,-0.0139049f,-0.0518113f},{-0.275561f,-0.0170439f,-0.0452091f},{-0.279032f,-0.0200249f,-0.0384656f}, +{-0.29201f,-0.0303472f,-0.0107265f},{-0.288783f,-0.0278991f,-0.017682f},{-0.289301f,-0.0280207f,-0.0179263f}, +{-0.285405f,-0.0254986f,-0.0246083f},{-0.288301f,-0.0279857f,-0.017522f},{-0.290999f,-0.0303036f,-0.0103487f}, +{-0.2935f,-0.0324512f,-0.0031023f},{-0.295801f,-0.0344278f,0.00420356f},{-0.297903f,-0.0362334f,0.0115553f}, +{-0.299807f,-0.0378685f,0.0189394f},{-0.303025f,-0.0406324f,0.0337531f},{-0.30485f,-0.0416984f,0.0410833f}, +{-0.306415f,-0.0435442f,0.0559018f},{-0.30841f,-0.0452575f,0.0848321f},{-0.308442f,-0.0453419f,0.0918925f}, +{-0.308124f,-0.045503f,0.0918925f},{-0.128039f,0.110199f,-0.14831f},{-0.138807f,0.100913f,-0.146254f}, +{-0.155362f,0.0866934f,-0.14394f},{-0.160952f,0.0818926f,-0.142695f},{-0.166563f,0.0770728f,-0.141205f}, +{-0.172189f,0.0722415f,-0.139464f},{-0.177818f,0.0674064f,-0.137469f},{-0.183443f,0.0625755f,-0.135216f}, +{-0.189053f,0.0577573f,-0.132703f},{-0.205694f,0.0434645f,-0.123589f},{-0.206027f,0.043502f,-0.12407f}, +{-0.211489f,0.0388108f,-0.120499f},{-0.211144f,0.0387837f,-0.120026f},{-0.216528f,0.0341596f,-0.116203f}, +{-0.221835f,0.0296015f,-0.112124f},{-0.227055f,0.0251181f,-0.10779f},{-0.247289f,0.00806285f,-0.0884349f}, +{-0.247595f,0.00780019f,-0.0888979f},{-0.252254f,0.00379886f,-0.0833616f},{-0.242092f,0.0122029f,-0.0933231f}, +{-0.246864f,0.0081042f,-0.0880336f},{-0.251501f,0.00412199f,-0.0825239f},{-0.255993f,0.000263687f,-0.0768032f}, +{-0.272846f,-0.0138878f,-0.0523423f},{-0.273218f,-0.0142069f,-0.0527127f},{-0.276895f,-0.0173656f,-0.046069f}, +{-0.268525f,-0.0105001f,-0.0584789f},{-0.272364f,-0.0137976f,-0.0520214f},{-0.276025f,-0.0169413f,-0.0454095f}, +{-0.2795f,-0.0199266f,-0.0386562f},{-0.282788f,-0.02275f,-0.0317747f},{-0.285883f,-0.0254083f,-0.0247786f}, +{-0.291486f,-0.0302204f,-0.0104982f},{-0.29399f,-0.0323711f,-0.00324118f},{-0.296294f,-0.0343506f,0.00407537f}, +{-0.2984f,-0.0361588f,0.0114378f},{-0.300306f,-0.0377963f,0.0188328f},{-0.302015f,-0.0392642f,0.0262471f}, +{-0.303529f,-0.0405642f,0.0336681f},{-0.306924f,-0.0434803f,0.0558492f},{-0.309707f,-0.0455472f,0.077605f}, +{-0.308803f,-0.0452653f,0.0918925f},{-0.138651f,0.100546f,-0.148277f},{-0.138991f,0.101078f,-0.146785f}, +{-0.161185f,0.0820158f,-0.143218f},{-0.16127f,0.081943f,-0.143822f},{-0.166909f,0.0771001f,-0.142325f}, +{-0.166809f,0.0771853f,-0.141725f},{-0.172447f,0.0723432f,-0.13998f},{-0.178089f,0.0674973f,-0.137981f}, +{-0.183726f,0.0626556f,-0.135723f},{-0.189349f,0.0578266f,-0.133204f},{-0.194947f,0.0530188f,-0.130423f}, +{-0.200509f,0.048241f,-0.127378f},{-0.216885f,0.0341764f,-0.116668f},{-0.217113f,0.0339808f,-0.117203f}, +{-0.222445f,0.0294008f,-0.113104f},{-0.222204f,0.0296081f,-0.112579f},{-0.227436f,0.0251146f,-0.108236f}, +{-0.23257f,0.0207049f,-0.103644f},{-0.237597f,0.0163874f,-0.0988083f},{-0.242506f,0.0121707f,-0.0937362f}, +{-0.251936f,0.00407176f,-0.0829128f},{-0.256438f,0.00020485f,-0.0771794f},{-0.260788f,-0.00353086f,-0.0712445f}, +{-0.264977f,-0.00712881f,-0.065119f},{-0.268999f,-0.010583f,-0.0588143f},{-0.276515f,-0.0170385f,-0.0457157f}, +{-0.279998f,-0.0200305f,-0.0389474f},{-0.283293f,-0.0228602f,-0.0320505f},{-0.286395f,-0.0255244f,-0.0250388f}, +{-0.29452f,-0.0325027f,-0.00345334f},{-0.294947f,-0.0328695f,-0.00369814f},{-0.297263f,-0.0348585f,0.00365355f}, +{-0.29683f,-0.0344866f,0.00387953f},{-0.29894f,-0.0362988f,0.0112584f},{-0.30085f,-0.03794f,0.0186698f}, +{-0.302563f,-0.0394112f,0.0261007f},{-0.30408f,-0.0407141f,0.0335382f},{-0.305404f,-0.0418509f,0.04097f}, +{-0.306537f,-0.0428241f,0.048384f},{-0.307483f,-0.0436367f,0.0557688f},{-0.309243f,-0.0451479f,0.0776416f}, +{-0.309162f,-0.0452855f,0.0918925f},{-0.14452f,0.0963291f,-0.146855f},{-0.150068f,0.0915645f,-0.146081f}, +{-0.139019f,0.101054f,-0.147398f},{-0.155654f,0.0867669f,-0.145073f},{-0.172561f,0.0722455f,-0.140576f}, +{-0.178217f,0.0673872f,-0.138571f},{-0.183869f,0.0625331f,-0.136307f},{-0.183833f,0.0622407f,-0.136814f}, +{-0.189482f,0.0573886f,-0.134283f},{-0.189506f,0.0576918f,-0.133782f},{-0.195118f,0.0528716f,-0.130993f}, +{-0.200695f,0.0480815f,-0.127941f},{-0.206227f,0.0433303f,-0.124624f},{-0.211703f,0.0386271f,-0.121044f}, +{-0.22769f,0.0248958f,-0.10875f},{-0.227751f,0.0245198f,-0.109195f},{-0.23291f,0.0200889f,-0.104581f}, +{-0.232838f,0.0204747f,-0.104146f},{-0.237878f,0.0161461f,-0.0992979f},{-0.2428f,0.0119186f,-0.0942128f}, +{-0.256767f,-7.79773e-005f,-0.0776135f},{-0.256893f,-0.000509374f,-0.0779897f},{-0.261263f,-0.00426299f,-0.0720263f}, +{-0.261128f,-0.00382328f,-0.0716633f},{-0.265328f,-0.00743047f,-0.0655221f},{-0.26936f,-0.0108935f,-0.0592012f}, +{-0.280388f,-0.0203653f,-0.0392833f},{-0.280566f,-0.0208417f,-0.0395744f},{-0.283876f,-0.023685f,-0.0326445f}, +{-0.283691f,-0.0232022f,-0.0323688f},{-0.286801f,-0.0258733f,-0.025339f},{-0.289715f,-0.028376f,-0.0182083f}, +{-0.292431f,-0.0307085f,-0.01099f},{-0.299378f,-0.0366754f,0.0110514f},{-0.301294f,-0.0383208f,0.0184819f}, +{-0.301518f,-0.038837f,0.0183189f},{-0.303239f,-0.0403153f,0.0257854f},{-0.303011f,-0.0397958f,0.0259318f}, +{-0.304532f,-0.041102f,0.0333884f},{-0.305859f,-0.0422417f,0.0408392f},{-0.306995f,-0.0432174f,0.0482723f}, +{-0.307944f,-0.0440321f,0.0556761f},{-0.309951f,-0.0457562f,0.0847878f},{-0.30982f,-0.0455988f,0.0918925f}, +{-0.309511f,-0.0453977f,0.0918925f},{-0.144396f,0.0961117f,-0.147384f},{-0.149956f,0.0913365f,-0.14661f}, +{-0.138883f,0.100847f,-0.147929f},{-0.155555f,0.0865282f,-0.145599f},{-0.161183f,0.0816937f,-0.144345f}, +{-0.166835f,0.07684f,-0.142845f},{-0.172499f,0.0719747f,-0.141092f},{-0.178168f,0.0671055f,-0.139082f}, +{-0.195107f,0.0525577f,-0.131488f},{-0.200554f,0.0473783f,-0.128748f},{-0.200696f,0.047757f,-0.128429f}, +{-0.20624f,0.0429952f,-0.125105f},{-0.211728f,0.0382816f,-0.121517f},{-0.21715f,0.033625f,-0.117667f}, +{-0.222494f,0.0290348f,-0.113559f},{-0.237873f,0.0153256f,-0.1f},{-0.237961f,0.0157507f,-0.0997223f}, +{-0.242894f,0.0115138f,-0.0946258f},{-0.2477f,0.00738628f,-0.0892991f},{-0.252369f,0.00337607f,-0.0837506f}, +{-0.265424f,-0.00833753f,-0.0661002f},{-0.265472f,-0.00787819f,-0.0658715f},{-0.269513f,-0.0113489f,-0.0595366f}, +{-0.27338f,-0.0146696f,-0.0530336f},{-0.277066f,-0.0178353f,-0.0463752f},{-0.286976f,-0.0268481f,-0.0257695f}, +{-0.286993f,-0.026362f,-0.0255992f},{-0.289914f,-0.0288702f,-0.0184526f},{-0.292635f,-0.0312079f,-0.0112184f}, +{-0.295157f,-0.0333737f,-0.00391029f},{-0.297478f,-0.0353671f,0.00345771f},{-0.299598f,-0.037188f,0.0108719f}, +{-0.304763f,-0.0416245f,0.0332586f},{-0.306104f,-0.0432766f,0.0406518f},{-0.306093f,-0.0427667f,0.0407259f}, +{-0.307232f,-0.0437445f,0.0481755f},{-0.308183f,-0.0445611f,0.0555957f},{-0.30895f,-0.0452198f,0.0629755f}, +{-0.30995f,-0.0460795f,0.0775733f},{-0.310227f,-0.0461927f,0.0918925f},{-0.31006f,-0.0458671f,0.0918925f}, +{-0.127713f,0.109819f,-0.148751f},{-0.144173f,0.0958031f,-0.147731f},{-0.149741f,0.091021f,-0.146955f}, +{-0.155347f,0.0862057f,-0.145943f},{-0.160984f,0.0813642f,-0.144688f},{-0.166643f,0.0765035f,-0.143185f}, +{-0.172316f,0.0716311f,-0.141429f},{-0.177994f,0.0667549f,-0.139417f},{-0.183666f,0.061883f,-0.137145f}, +{-0.189324f,0.0570238f,-0.134611f},{-0.194956f,0.052186f,-0.131812f},{-0.205904f,0.0422634f,-0.125571f}, +{-0.210708f,0.0376835f,-0.122344f},{-0.211404f,0.0375395f,-0.121975f},{-0.206106f,0.0426097f,-0.125419f}, +{-0.211602f,0.0378891f,-0.121826f},{-0.217032f,0.0332258f,-0.117971f},{-0.222384f,0.028629f,-0.113856f}, +{-0.227648f,0.0241074f,-0.109486f},{-0.232815f,0.0196701f,-0.104866f},{-0.242813f,0.0110826f,-0.0948962f}, +{-0.242637f,0.0107143f,-0.0950266f},{-0.247626f,0.00694907f,-0.0895618f},{-0.252302f,0.00293304f,-0.0840052f}, +{-0.256832f,-0.000958027f,-0.0782359f},{-0.261209f,-0.00471708f,-0.072264f},{-0.269313f,-0.0121976f,-0.059862f}, +{-0.272494f,-0.0153837f,-0.0542297f},{-0.273188f,-0.0155254f,-0.053345f},{-0.269471f,-0.0118133f,-0.059756f}, +{-0.273343f,-0.0151388f,-0.0532437f},{-0.277034f,-0.0183091f,-0.0465757f},{-0.280539f,-0.0213198f,-0.039765f}, +{-0.283855f,-0.0241672f,-0.0328251f},{-0.289901f,-0.02936f,-0.0186126f},{-0.292484f,-0.0320992f,-0.0114399f}, +{-0.292626f,-0.031701f,-0.0113678f},{-0.295152f,-0.03387f,-0.00404916f},{-0.297476f,-0.0358663f,0.00332952f}, +{-0.299599f,-0.0376898f,0.0107545f},{-0.301522f,-0.0393413f,0.0182123f},{-0.303246f,-0.0408217f,0.0256896f}, +{-0.304772f,-0.0421327f,0.0331736f},{-0.307244f,-0.0442558f,0.0481121f},{-0.308196f,-0.0450736f,0.0555431f}, +{-0.308964f,-0.0457333f,0.0629336f},{-0.143927f,0.095494f,-0.147899f},{-0.149499f,0.0907085f,-0.147122f}, +{-0.155109f,0.0858899f,-0.146109f},{-0.16075f,0.081045f,-0.144853f},{-0.166413f,0.0761809f,-0.143349f}, +{-0.17209f,0.0713051f,-0.141592f},{-0.177772f,0.0664255f,-0.139579f},{-0.183448f,0.0615502f,-0.137305f}, +{-0.189109f,0.0566876f,-0.134769f},{-0.194746f,0.0518464f,-0.131968f},{-0.200348f,0.0470353f,-0.128902f}, +{-0.216837f,0.032873f,-0.118117f},{-0.222193f,0.0282729f,-0.114f},{-0.227461f,0.0237482f,-0.109627f}, +{-0.232631f,0.0193078f,-0.105003f},{-0.237693f,0.0149603f,-0.100134f},{-0.238141f,0.0141219f,-0.0995149f}, +{-0.247453f,0.00657788f,-0.0896885f},{-0.252132f,0.00255905f,-0.0841281f},{-0.256665f,-0.00133474f,-0.0783547f}, +{-0.261045f,-0.00509642f,-0.0723786f},{-0.265263f,-0.00871939f,-0.0662105f},{-0.276881f,-0.0186979f,-0.0466724f}, +{-0.280389f,-0.0217108f,-0.039857f},{-0.283707f,-0.0245601f,-0.0329122f},{-0.28683f,-0.0272429f,-0.0258517f}, +{-0.289757f,-0.0297565f,-0.0186898f},{-0.289812f,-0.030258f,-0.0180672f},{-0.295012f,-0.0342697f,-0.00411618f}, +{-0.297337f,-0.0362674f,0.00326766f},{-0.299462f,-0.0380922f,0.0106978f},{-0.301386f,-0.0397448f,0.0181608f}, +{-0.303111f,-0.0412262f,0.0256434f},{-0.304639f,-0.0425382f,0.0331326f},{-0.305971f,-0.0436828f,0.040616f}, +{-0.307112f,-0.0446628f,0.0480815f},{-0.308065f,-0.0454811f,0.0555177f},{-0.308834f,-0.0461413f,0.0629134f}, +{-0.309423f,-0.0466471f,0.0702583f},{-0.309837f,-0.0470028f,0.0775425f},{-0.143513f,0.0953962f,-0.147965f}, +{-0.148897f,0.0907713f,-0.147226f},{-0.154263f,0.0861627f,-0.146277f},{-0.159606f,0.0815743f,-0.145118f}, +{-0.164919f,0.0770103f,-0.143752f},{-0.1702f,0.0724748f,-0.142179f},{-0.175443f,0.0679717f,-0.1404f}, +{-0.180644f,0.0635049f,-0.138417f},{-0.185798f,0.0590782f,-0.136232f},{-0.1909f,0.0546957f,-0.133846f}, +{-0.195947f,0.0503613f,-0.131262f},{-0.200933f,0.0460786f,-0.128482f},{-0.205855f,0.0418515f,-0.125509f}, +{-0.215487f,0.0335786f,-0.118992f},{-0.220189f,0.0295402f,-0.115454f},{-0.224809f,0.0255719f,-0.111734f}, +{-0.229344f,0.0216771f,-0.107835f},{-0.233789f,0.0178593f,-0.103761f},{-0.242395f,0.0104681f,-0.0951008f}, +{-0.246548f,0.00690116f,-0.0905224f},{-0.250596f,0.00342407f,-0.0857837f},{-0.254536f,4.00465e-005f,-0.080889f}, +{-0.258365f,-0.00324795f,-0.0758426f},{-0.262078f,-0.00643705f,-0.0706488f},{-0.265672f,-0.00952448f,-0.0653124f}, +{-0.269146f,-0.0125076f,-0.0598376f},{-0.275715f,-0.0181502f,-0.0484934f},{-0.278806f,-0.0208047f,-0.042634f}, +{-0.281763f,-0.0233449f,-0.0366563f},{-0.284585f,-0.0257686f,-0.0305656f},{-0.287269f,-0.0280737f,-0.0243674f}, +{-0.292213f,-0.0323197f,-0.0116704f},{-0.294469f,-0.0342571f,-0.00518257f},{-0.296578f,-0.0360684f,0.00139061f}, +{-0.298538f,-0.0377519f,0.00804317f},{-0.300347f,-0.0393062f,0.0147693f},{-0.302005f,-0.04073f,0.0215631f}, +{-0.303509f,-0.042022f,0.0284189f},{-0.304859f,-0.043181f,0.0353305f},{-0.306052f,-0.0442061f,0.0422916f}, +{-0.307089f,-0.0450964f,0.0492962f},{-0.307967f,-0.045851f,0.0563382f},{-0.308687f,-0.0464693f,0.0634117f}, +{-0.309248f,-0.0469508f,0.0705101f},{-0.309649f,-0.047295f,0.0776272f},{-0.309889f,-0.0475017f,0.0847567f}, +{0.0493934f,0.26108f,0.0428677f},{0.0500586f,0.262105f,0.0485758f},{0.0489305f,0.261136f,0.0411945f}, +{0.0403941f,0.253804f,0.00426646f},{0.0400286f,0.253036f,0.00244165f},{0.041966f,0.2547f,0.00901696f}, +{0.0517606f,0.263566f,0.0632405f},{0.052343f,0.264067f,0.0705025f},{0.0516301f,0.263974f,0.0632202f}, +{0.0512863f,0.262705f,0.0567511f},{0.0519978f,0.263316f,0.0637424f},{0.0528812f,0.26555f,0.084822f}, +{0.0530084f,0.265783f,0.0918925f},{0.0531246f,0.266082f,0.0848062f},{0.0522285f,0.264989f,0.0704561f}, +{0.0516449f,0.264488f,0.0631783f},{0.0522129f,0.264475f,0.0704874f},{0.0535901f,0.266482f,0.084788f}, +{0.0540726f,0.26669f,0.0918925f},{0.0541535f,0.266643f,0.0847723f},{0.0524705f,0.265521f,0.0704083f}, +{0.0518855f,0.265018f,0.0631143f},{0.0550496f,0.266391f,0.084757f},{0.0548051f,0.266181f,0.0775429f}, +{0.0546651f,0.266581f,0.084762f},{0.0544319f,0.26671f,0.0918925f},{0.0553868f,0.266227f,0.0918925f}, +{0.0551112f,0.266473f,0.0918925f},{0.0550661f,0.265952f,0.0776267f},{0.0510006f,0.262914f,0.0559281f}, +{0.0504179f,0.261959f,0.0497909f},{0.0553066f,0.266158f,0.0847564f},{0.0468799f,0.258921f,0.0291561f}, +{0.0476128f,0.260004f,0.0337954f},{0.0461026f,0.258707f,0.0263905f},{0.0482137f,0.260066f,0.0359874f}, +{0.0443972f,0.257242f,0.0189921f},{0.0453931f,0.257644f,0.0223799f},{0.0424948f,0.255608f,0.0116131f}, +{0.0437546f,0.256236f,0.015665f},{0.0380944f,0.251829f,-0.00303443f},{0.0379442f,0.251246f,-0.0040552f}, +{0.0328989f,0.247366f,-0.0174445f},{0.0300052f,0.244881f,-0.0245261f},{0.0308284f,0.245134f,-0.0230172f}, +{0.0355958f,0.249683f,-0.010276f},{0.0224634f,0.23795f,-0.0410717f},{0.0253866f,0.240461f,-0.0351634f}, +{0.0236368f,0.239411f,-0.0383731f},{0.0281758f,0.242856f,-0.0291434f},{0.016225f,0.232592f,-0.0525327f}, +{0.0165165f,0.233296f,-0.051709f},{0.0126856f,0.230006f,-0.0581524f},{0.0201686f,0.236433f,-0.0451116f}, +{0.00592937f,0.223749f,-0.0687612f},{0.004511f,0.222985f,-0.0705281f},{0.00225941f,0.220597f,-0.0738946f}, +{0.00868167f,0.226567f,-0.0644294f},{-0.00942004f,0.210566f,-0.088404f},{-0.00541866f,0.214002f,-0.0837203f}, +{-0.00892832f,0.211442f,-0.0876434f},{-0.00152437f,0.217347f,-0.0788824f},{-0.00430185f,0.215415f,-0.0821454f}, +{-0.0220305f,0.199735f,-0.101489f},{-0.0185782f,0.203154f,-0.0979716f},{-0.0235832f,0.198855f,-0.102786f}, +{-0.0136901f,0.207352f,-0.0929216f},{-0.0339042f,0.189991f,-0.111682f},{-0.0354727f,0.18819f,-0.113046f}, +{-0.030906f,0.192112f,-0.109369f},{-0.026424f,0.195961f,-0.105516f},{-0.0496403f,0.176021f,-0.122984f}, +{-0.0448439f,0.180141f,-0.119856f},{-0.0500098f,0.176158f,-0.123123f},{-0.0392f,0.185442f,-0.115753f}, +{-0.055503f,0.17144f,-0.126416f},{-0.0594332f,0.16761f,-0.12867f},{-0.0545048f,0.171843f,-0.125923f}, +{-0.0722122f,0.157088f,-0.134725f},{-0.0694645f,0.158995f,-0.133582f},{-0.0666145f,0.161896f,-0.132217f}, +{-0.0644212f,0.163326f,-0.131224f},{-0.0610414f,0.166683f,-0.129448f},{-0.079699f,0.150204f,-0.137702f}, +{-0.0778246f,0.152268f,-0.136973f},{-0.083442f,0.147443f,-0.138964f},{-0.0745587f,0.154619f,-0.135742f}, +{-0.0901005f,0.141271f,-0.141015f},{-0.089055f,0.142623f,-0.140701f},{-0.0946547f,0.137813f,-0.142188f}, +{-0.0848811f,0.145754f,-0.13946f},{-0.100633f,0.132225f,-0.143511f},{-0.0953526f,0.13676f,-0.142366f}, +{-0.100232f,0.133023f,-0.14343f},{-0.111882f,0.124362f,-0.146244f},{-0.111758f,0.124144f,-0.145714f}, +{-0.106237f,0.128886f,-0.144944f},{-0.122163f,0.114186f,-0.146058f},{-0.116595f,0.118515f,-0.145701f}, +{-0.116752f,0.118834f,-0.145739f},{-0.121941f,0.113924f,-0.146015f},{-0.111289f,0.123526f,-0.145199f}, +{-0.10578f,0.128258f,-0.144432f},{-0.111534f,0.123836f,-0.145367f},{-0.111259f,0.123099f,-0.145179f}, +{-0.105936f,0.12767f,-0.144449f},{-0.0892849f,0.142945f,-0.140865f},{-0.095088f,0.138462f,-0.142696f}, +{-0.0948885f,0.138132f,-0.142353f},{-0.106348f,0.129114f,-0.145472f},{-0.106021f,0.128571f,-0.144599f}, +{-0.11184f,0.124398f,-0.146855f},{-0.117342f,0.119672f,-0.147398f},{-0.117369f,0.119648f,-0.146786f}, +{-0.111372f,0.123975f,-0.147732f},{-0.116894f,0.119232f,-0.148277f},{-0.111644f,0.124242f,-0.147385f}, +{-0.122619f,0.114816f,-0.148251f},{-0.122363f,0.114535f,-0.148599f},{-0.122103f,0.114239f,-0.148767f}, +{-0.121878f,0.113978f,-0.14881f},{-0.0780466f,0.152598f,-0.137135f},{-0.0286952f,0.194464f,-0.107358f}, +{-0.04012f,0.184198f,-0.116543f},{-0.0445719f,0.180828f,-0.119568f},{-0.0340952f,0.190347f,-0.111826f}, +{-0.0177295f,0.203429f,-0.097292f},{-0.0135248f,0.20704f,-0.0929291f},{0.000180634f,0.219265f,-0.076437f}, +{0.00948232f,0.226801f,-0.0634867f},{-0.00447193f,0.215789f,-0.0822683f},{-0.00453921f,0.216232f,-0.0825229f}, +{-0.00917572f,0.21225f,-0.0880327f},{0.0129153f,0.229749f,-0.0580755f},{0.0194086f,0.235326f,-0.0468631f}, +{0.0333422f,0.247293f,-0.0167902f},{0.0357148f,0.249331f,-0.0104677f},{0.0269169f,0.242229f,-0.0315068f}, +{0.0163243f,0.234152f,-0.0520204f},{0.0200158f,0.236821f,-0.0452083f},{0.0199843f,0.237295f,-0.0454087f}, +{0.0423578f,0.256011f,0.0115564f},{0.0525519f,0.263792f,0.0707584f},{0.0534149f,0.266377f,0.0918925f}, +{0.0529481f,0.264133f,0.0777929f},{0.0527525f,0.264418f,0.0777045f},{0.0528646f,0.265035f,0.0848323f}, +{0.0529317f,0.265422f,0.0918925f},{0.0531859f,0.264337f,0.0848396f},{0.0529943f,0.264626f,0.0848373f}, +{0.0530642f,0.264714f,0.0918925f},{0.0529519f,0.265063f,0.0918925f},{0.0532653f,0.264405f,0.0918925f}, +{0.0531751f,0.266108f,0.0918925f},{0.0537244f,0.266578f,0.0918925f},{0.0526227f,0.264827f,0.0776945f}, +{0.0508696f,0.263321f,0.0559028f},{0.0499269f,0.262512f,0.0485453f},{0.048798f,0.261542f,0.0411587f}, +{0.0474794f,0.260409f,0.0337544f},{0.0459681f,0.259111f,0.0263442f},{0.0442615f,0.257646f,0.0189407f}, +{0.0402537f,0.254704f,0.00407642f},{0.037949f,0.252725f,-0.00324031f},{0.0402556f,0.254205f,0.00420461f}, +{0.0379543f,0.252228f,-0.00310144f},{0.0354539f,0.250081f,-0.0103481f},{0.0327551f,0.247763f,-0.0175217f}, +{0.0298594f,0.245276f,-0.0246083f},{0.0267689f,0.242622f,-0.0315939f},{0.0234865f,0.239802f,-0.038465f}, +{0.0163611f,0.233683f,-0.0518103f},{0.0125275f,0.23039f,-0.0582583f},{0.00852075f,0.226949f,-0.0645398f}, +{0.00434714f,0.223364f,-0.0706427f},{1.37117e-005f,0.219642f,-0.0765558f},{-0.00910166f,0.211813f,-0.0877701f}, +{-0.0138668f,0.20772f,-0.093052f},{-0.0187584f,0.203519f,-0.0981056f},{-0.0237669f,0.199217f,-0.102923f}, +{-0.0288825f,0.194824f,-0.107499f},{-0.050333f,0.177225f,-0.12407f},{-0.0448966f,0.18157f,-0.120026f}, +{-0.0448712f,0.181916f,-0.120499f},{-0.0393947f,0.185795f,-0.1159f},{-0.0447704f,0.181178f,-0.119717f}, +{-0.0502121f,0.176504f,-0.123274f},{-0.0557093f,0.171783f,-0.126571f},{-0.0612515f,0.167022f,-0.129604f}, +{-0.0668286f,0.162232f,-0.132375f},{-0.0724302f,0.157421f,-0.134885f},{-0.0836679f,0.147769f,-0.139127f}, +{-0.0894762f,0.143282f,-0.141206f},{-0.10047f,0.133338f,-0.143596f},{-0.117002f,0.11914f,-0.145907f}, +{-0.122417f,0.114489f,-0.146226f},{0.0544208f,0.266371f,0.0775529f},{0.0526389f,0.265342f,0.0776737f}, +{0.0508832f,0.263834f,0.0558501f},{0.0499391f,0.263023f,0.0484819f},{0.0488086f,0.262052f,0.0410845f}, +{0.0474881f,0.260918f,0.0336694f},{0.0459745f,0.259618f,0.0262484f},{0.0442655f,0.25815f,0.018834f}, +{0.0423589f,0.256512f,0.011439f},{0.035445f,0.250574f,-0.0104976f},{0.0356495f,0.251073f,-0.0107259f}, +{0.0329408f,0.248747f,-0.017926f},{0.0327422f,0.248253f,-0.0176816f},{0.0298423f,0.245762f,-0.0247786f}, +{0.0267473f,0.243104f,-0.0317744f},{0.02346f,0.24028f,-0.0386556f},{0.00861687f,0.227856f,-0.0651178f}, +{0.00896809f,0.228157f,-0.065521f},{0.0047683f,0.22455f,-0.0716622f},{0.0124851f,0.230854f,-0.0584778f}, +{0.00847247f,0.227408f,-0.0647685f},{0.00429275f,0.223818f,-0.0708804f},{-4.70058e-005f,0.220091f,-0.0768021f}, +{-0.0187631f,0.20434f,-0.0988077f},{-0.0184822f,0.204581f,-0.0992973f},{-0.0235221f,0.200252f,-0.104145f}, +{-0.0139479f,0.208152f,-0.0933224f},{-0.0188466f,0.203944f,-0.0983834f},{-0.0238624f,0.199636f,-0.103208f}, +{-0.0289854f,0.195236f,-0.10779f},{-0.0342058f,0.190752f,-0.112123f},{-0.0395131f,0.186194f,-0.116203f}, +{-0.0503463f,0.17689f,-0.123589f},{-0.0558515f,0.172161f,-0.12689f},{-0.0614018f,0.167394f,-0.129928f}, +{-0.066987f,0.162597f,-0.132703f},{-0.0725969f,0.157779f,-0.135216f},{-0.0782214f,0.152948f,-0.137469f}, +{-0.083851f,0.148113f,-0.139465f},{-0.100678f,0.133661f,-0.14394f},{-0.122791f,0.114992f,-0.147719f}, +{-0.117234f,0.119441f,-0.146255f},{-0.122656f,0.114784f,-0.146574f},{0.0511222f,0.264363f,0.0557698f}, +{0.0528818f,0.265874f,0.077642f},{0.050176f,0.26355f,0.0483851f},{0.0506339f,0.263943f,0.0482734f}, +{0.049498f,0.262968f,0.0408405f},{0.0490429f,0.262577f,0.0409712f},{0.0477195f,0.26144f,0.0335395f}, +{0.0462026f,0.260137f,0.026102f},{0.0444897f,0.258666f,0.0186711f},{0.0425789f,0.257025f,0.0112596f}, +{0.040469f,0.255213f,0.00388058f},{0.0381592f,0.253229f,-0.00345247f},{0.0300343f,0.246251f,-0.0250388f}, +{0.0304405f,0.2466f,-0.025339f},{0.0273306f,0.243929f,-0.0323684f},{0.0269324f,0.243587f,-0.0320502f}, +{0.0236379f,0.240757f,-0.0389468f},{0.0201544f,0.237765f,-0.0457149f},{0.0164862f,0.234614f,-0.0523413f}, +{0.0126385f,0.23131f,-0.0588132f},{0.00442784f,0.224258f,-0.0712434f},{7.83923e-005f,0.220522f,-0.0771783f}, +{-0.00442383f,0.216655f,-0.0829118f},{-0.00907067f,0.212664f,-0.088434f},{-0.0138535f,0.208556f,-0.0937354f}, +{-0.0237901f,0.200022f,-0.103643f},{-0.0289246f,0.195612f,-0.108235f},{-0.0341565f,0.191118f,-0.112578f}, +{-0.0394757f,0.18655f,-0.116668f},{-0.0558505f,0.172486f,-0.127378f},{-0.0556648f,0.172645f,-0.127941f}, +{-0.0612418f,0.167855f,-0.130993f},{-0.0614133f,0.167708f,-0.130423f},{-0.0670109f,0.1629f,-0.133204f}, +{-0.0726333f,0.158071f,-0.135723f},{-0.0782704f,0.15323f,-0.137981f},{-0.0839125f,0.148384f,-0.139981f}, +{-0.0895502f,0.143542f,-0.141725f},{-0.0951746f,0.138711f,-0.143219f},{-0.100777f,0.1339f,-0.144466f}, +{-0.122804f,0.11498f,-0.147106f},{0.0529343f,0.265919f,0.0703531f},{0.0523479f,0.265415f,0.0630404f}, +{0.0533467f,0.266273f,0.0776054f},{0.0515825f,0.264758f,0.055677f},{0.0481711f,0.261828f,0.0333897f}, +{0.0466503f,0.260522f,0.0259331f},{0.044933f,0.259047f,0.0184831f},{0.0454772f,0.259191f,0.0183202f}, +{0.0435573f,0.257542f,0.0108731f},{0.0430173f,0.257402f,0.0110526f},{0.040902f,0.255585f,0.00365461f}, +{0.0385862f,0.253596f,-0.00369726f},{0.0360702f,0.251435f,-0.0109894f},{0.0333545f,0.249102f,-0.0182079f}, +{0.0240277f,0.241092f,-0.0392827f},{0.0245255f,0.241196f,-0.0395738f},{0.0210253f,0.238189f,-0.0463744f}, +{0.0205352f,0.238092f,-0.0460682f},{0.0168576f,0.234933f,-0.0527117f},{0.013f,0.23162f,-0.0592001f}, +{0.00040769f,0.220805f,-0.0776124f},{0.000853084f,0.220864f,-0.0779886f},{-0.00367072f,0.216978f,-0.0837496f}, +{-0.00410608f,0.216928f,-0.0833607f},{-0.00876485f,0.212927f,-0.088897f},{-0.0135599f,0.208808f,-0.094212f}, +{-0.0286697f,0.195831f,-0.108749f},{-0.0282889f,0.195834f,-0.109195f},{-0.0335459f,0.191319f,-0.113558f}, +{-0.0339151f,0.191326f,-0.113103f},{-0.0392479f,0.186745f,-0.117203f},{-0.0446573f,0.182099f,-0.121044f}, +{-0.0501331f,0.177396f,-0.124624f},{-0.0668538f,0.163035f,-0.133782f},{-0.0724906f,0.158194f,-0.136307f}, +{-0.072207f,0.158114f,-0.136814f},{-0.0778712f,0.153249f,-0.139083f},{-0.0781422f,0.15334f,-0.138571f}, +{-0.0837988f,0.148482f,-0.140576f},{-0.0894511f,0.143627f,-0.142325f},{-0.0950898f,0.138784f,-0.143823f}, +{-0.100706f,0.13396f,-0.145073f},{-0.106292f,0.129162f,-0.146082f},{0.0534963f,0.266078f,0.0703053f}, +{0.0529085f,0.265573f,0.0629764f},{0.0539095f,0.266433f,0.0775737f},{0.0521415f,0.264914f,0.0555966f}, +{0.0511908f,0.264098f,0.0481766f},{0.0500523f,0.26312f,0.0407271f},{0.0487225f,0.261978f,0.0332599f}, +{0.0471983f,0.260669f,0.0257867f},{0.0414372f,0.255721f,0.00345877f},{0.0396062f,0.253647f,-0.00404829f}, +{0.0391164f,0.253727f,-0.00390942f},{0.0365947f,0.251562f,-0.0112177f},{0.033873f,0.249224f,-0.0184523f}, +{0.0309526f,0.246716f,-0.0255992f},{0.0278358f,0.244039f,-0.0326442f},{0.0177978f,0.234916f,-0.0532427f}, +{0.0173395f,0.235024f,-0.0530326f},{0.0134733f,0.231703f,-0.0595354f},{0.00943248f,0.228232f,-0.0658703f}, +{0.00522337f,0.224617f,-0.0720252f},{-0.0079188f,0.212829f,-0.0895609f},{-0.00833983f,0.212968f,-0.0892982f}, +{-0.0131455f,0.208841f,-0.0946251f},{-0.0180787f,0.204604f,-0.0997217f},{-0.0231298f,0.200265f,-0.10458f}, +{-0.0385138f,0.186551f,-0.117971f},{-0.0388905f,0.186729f,-0.117667f},{-0.044312f,0.182072f,-0.121517f}, +{-0.0497999f,0.177359f,-0.125105f},{-0.0553439f,0.172597f,-0.128429f},{-0.0609333f,0.167797f,-0.131488f}, +{-0.0665577f,0.162966f,-0.134283f},{-0.0835403f,0.14838f,-0.141092f},{-0.0889013f,0.143275f,-0.143185f}, +{-0.0892051f,0.143514f,-0.142845f},{-0.0948564f,0.138661f,-0.144346f},{-0.100485f,0.133826f,-0.145599f}, +{-0.106084f,0.129018f,-0.14661f},{-0.117158f,0.119507f,-0.147929f},{0.0547929f,0.266634f,0.0918925f}, +{0.0540069f,0.266016f,0.070274f},{0.0534183f,0.26551f,0.0629344f},{0.0526502f,0.264851f,0.055544f}, +{0.0516981f,0.264033f,0.0481132f},{0.050558f,0.263054f,0.040653f},{0.0492262f,0.26191f,0.0331749f}, +{0.0476998f,0.260599f,0.0256909f},{0.0459762f,0.259118f,0.0182135f},{0.0440535f,0.257467f,0.0107557f}, +{0.0419304f,0.255643f,0.00333058f},{0.037453f,0.251278f,-0.0114393f},{0.0352296f,0.248914f,-0.0180677f}, +{0.0347255f,0.248935f,-0.0186894f},{0.0370809f,0.251478f,-0.0113672f},{0.0343552f,0.249137f,-0.0186123f}, +{0.0314306f,0.246625f,-0.0257695f},{0.0283092f,0.243945f,-0.0328247f},{0.0249941f,0.241097f,-0.0397644f}, +{0.0214889f,0.238087f,-0.0465748f},{0.013926f,0.231591f,-0.0597549f},{0.014282f,0.231377f,-0.0598609f}, +{0.00987926f,0.228115f,-0.066099f},{0.00566404f,0.224495f,-0.0722628f},{0.00128743f,0.220736f,-0.0782348f}, +{-0.00324293f,0.216845f,-0.0840042f},{-0.0123941f,0.208465f,-0.0950259f},{-0.0164425f,0.204534f,-0.0995152f}, +{-0.0173378f,0.204219f,-0.100133f},{-0.0127315f,0.208695f,-0.0948954f},{-0.0176718f,0.204452f,-0.0999994f}, +{-0.0227302f,0.200108f,-0.104865f},{-0.0278968f,0.19567f,-0.109486f},{-0.0331614f,0.191149f,-0.113856f}, +{-0.0439431f,0.181888f,-0.121826f},{-0.0491273f,0.176916f,-0.125571f},{-0.049439f,0.177168f,-0.125419f}, +{-0.054991f,0.1724f,-0.128748f},{-0.0605885f,0.167592f,-0.131812f},{-0.0662211f,0.162754f,-0.134611f}, +{-0.0718786f,0.157895f,-0.137145f},{-0.0775509f,0.153023f,-0.139417f},{-0.0832283f,0.148147f,-0.14143f}, +{-0.0945608f,0.138414f,-0.144688f},{-0.100198f,0.133572f,-0.145943f},{-0.105804f,0.128757f,-0.146956f}, +{0.0543909f,0.265826f,0.0702589f},{0.0538019f,0.26532f,0.0629142f},{0.0530333f,0.264659f,0.0555186f}, +{0.0520805f,0.263841f,0.0480826f},{0.0509396f,0.262861f,0.0406172f},{0.0496069f,0.261717f,0.0331338f}, +{0.0480794f,0.260405f,0.0256447f},{0.0463547f,0.258923f,0.0181621f},{0.0444306f,0.257271f,0.010699f}, +{0.042306f,0.255446f,0.00326873f},{0.0399801f,0.253448f,-0.0041153f},{0.0317988f,0.246422f,-0.0258517f}, +{0.0286753f,0.243739f,-0.0329118f},{0.0253579f,0.24089f,-0.0398563f},{0.0218502f,0.237877f,-0.0466715f}, +{0.0181565f,0.234704f,-0.0533441f},{0.0179111f,0.23404f,-0.0542301f},{0.0102325f,0.227899f,-0.0662094f}, +{0.0060143f,0.224276f,-0.0723775f},{0.00163463f,0.220514f,-0.0783537f},{-0.0028989f,0.21662f,-0.0841271f}, +{-0.00757805f,0.212602f,-0.0896876f},{-0.0223998f,0.199871f,-0.105003f},{-0.02757f,0.195431f,-0.109627f}, +{-0.0328383f,0.190906f,-0.114f},{-0.0381944f,0.186306f,-0.118117f},{-0.0436275f,0.181639f,-0.121975f}, +{-0.0438755f,0.180973f,-0.122344f},{-0.0546831f,0.172144f,-0.128902f},{-0.0602845f,0.167333f,-0.131968f}, +{-0.0659211f,0.162492f,-0.134769f},{-0.0715825f,0.157629f,-0.137305f},{-0.0772588f,0.152754f,-0.139579f}, +{-0.0829402f,0.147874f,-0.141593f},{-0.0886171f,0.142999f,-0.143349f},{-0.0942805f,0.138134f,-0.144853f}, +{-0.0999216f,0.133289f,-0.146109f},{-0.105532f,0.128471f,-0.147123f},{-0.111104f,0.123685f,-0.147899f}, +{-0.11663f,0.118939f,-0.148445f},{0.0546653f,0.265607f,0.0705096f},{0.0541047f,0.265126f,0.0634113f}, +{0.0533848f,0.264508f,0.056338f},{0.0525062f,0.263753f,0.0492957f},{0.0514696f,0.262863f,0.042291f}, +{0.0502761f,0.261838f,0.0353299f},{0.0489266f,0.260679f,0.0284186f},{0.0474223f,0.259387f,0.0215629f}, +{0.0457645f,0.257963f,0.0147688f},{0.0439548f,0.256408f,0.00804257f},{0.0419946f,0.254725f,0.00139006f}, +{0.0398858f,0.252914f,-0.00518291f},{0.0376301f,0.250976f,-0.0116708f},{0.0326863f,0.24673f,-0.024368f}, +{0.0300025f,0.244425f,-0.0305661f},{0.0271806f,0.242001f,-0.0366566f},{0.0242229f,0.239461f,-0.0426344f}, +{0.0211322f,0.236806f,-0.0484939f},{0.0145625f,0.231164f,-0.0598379f},{0.0110894f,0.228181f,-0.0653124f}, +{0.00749453f,0.225093f,-0.0706491f},{0.00378138f,0.221904f,-0.0758429f},{-4.68637e-005f,0.218616f,-0.0808893f}, +{-0.00398685f,0.215232f,-0.0857839f},{-0.00803512f,0.211755f,-0.0905225f},{-0.0121883f,0.208188f,-0.095101f}, +{-0.020794f,0.200797f,-0.103761f},{-0.025239f,0.196979f,-0.107835f},{-0.0297737f,0.193084f,-0.111734f}, +{-0.0343942f,0.189116f,-0.115454f},{-0.0390962f,0.185078f,-0.118992f},{-0.0487282f,0.176805f,-0.125509f}, +{-0.0536499f,0.172578f,-0.128482f},{-0.0586363f,0.168295f,-0.131262f},{-0.063683f,0.16396f,-0.133846f}, +{-0.0687854f,0.159578f,-0.136231f},{-0.0739393f,0.155151f,-0.138417f},{-0.0791401f,0.150685f,-0.1404f}, +{-0.0843832f,0.146181f,-0.142179f},{-0.089664f,0.141646f,-0.143752f},{-0.0949777f,0.137082f,-0.145118f}, +{-0.10032f,0.132494f,-0.146276f},{-0.105686f,0.127885f,-0.147225f},{-0.111071f,0.12326f,-0.147964f}, +{-0.11647f,0.118623f,-0.148493f},{0.0258064f,0.240367f,-0.0398563f},{0.0222987f,0.237355f,-0.0466715f}, +{0.0147777f,0.22955f,-0.0592001f},{0.0108902f,0.226535f,-0.0658703f},{0.0149311f,0.230006f,-0.0595354f}, +{0.0322473f,0.245899f,-0.0258517f},{0.0291238f,0.243217f,-0.0329118f},{0.0379016f,0.250756f,-0.0114393f}, +{0.035174f,0.248413f,-0.0186894f},{0.0404286f,0.252926f,-0.0041153f},{0.0427545f,0.254924f,0.00326873f}, +{0.0448791f,0.256749f,0.010699f},{0.0380524f,0.249864f,-0.0112177f},{0.0380435f,0.250358f,-0.0113672f}, +{0.0405741f,0.25203f,-0.00390942f},{0.0468032f,0.258401f,0.0181621f},{0.048528f,0.259882f,0.0256447f}, +{0.0500554f,0.261194f,0.0331338f},{0.0513881f,0.262339f,0.0406172f},{0.052529f,0.263319f,0.0480826f}, +{0.0534818f,0.264137f,0.0555186f},{0.0542505f,0.264797f,0.0629142f},{0.0548395f,0.265303f,0.0702589f}, +{0.0549696f,0.264895f,0.070274f},{0.054381f,0.264389f,0.0629344f},{0.0534428f,0.264104f,0.0848373f}, +{0.0538273f,0.263914f,0.0848323f},{0.0543389f,0.263852f,0.084822f},{0.0542202f,0.263922f,0.0918925f}, +{0.0535408f,0.26416f,0.0918925f},{0.053201f,0.263896f,0.0777045f},{0.0527915f,0.263544f,0.0705025f}, +{0.0531755f,0.263354f,0.0704874f},{0.054954f,0.264381f,0.0703053f},{0.0543662f,0.263876f,0.0629764f}, +{0.0541256f,0.263346f,0.0630404f},{0.0535992f,0.263217f,0.0555966f},{0.054712f,0.263849f,0.0703531f}, +{0.0552536f,0.265659f,0.0775429f},{0.0557203f,0.26521f,0.0918925f},{0.0556112f,0.264945f,0.0847723f}, +{0.0556278f,0.26546f,0.084762f},{0.0556436f,0.264849f,0.0918925f},{0.0553678f,0.264412f,0.084788f}, +{0.0554769f,0.264524f,0.0918925f},{0.0557001f,0.26557f,0.0918925f},{0.0554981f,0.265869f,0.084757f}, +{0.0555879f,0.265918f,0.0918925f},{0.0549023f,0.264013f,0.0848062f},{0.0545795f,0.263942f,0.0918925f}, +{0.018605f,0.234182f,-0.0533441f},{0.0147305f,0.230855f,-0.0598609f},{0.010681f,0.227376f,-0.0662094f}, +{0.00646282f,0.223754f,-0.0723775f},{0.00208315f,0.219992f,-0.0783537f},{-0.00245038f,0.216098f,-0.0841271f}, +{-0.0117689f,0.207575f,-0.0948954f},{-0.00688212f,0.211271f,-0.0892982f},{-0.0116878f,0.207143f,-0.0946251f}, +{-0.00712952f,0.212079f,-0.0896876f},{-0.0119456f,0.207943f,-0.0950259f},{-0.0168893f,0.203697f,-0.100133f}, +{-0.0219512f,0.199349f,-0.105003f},{-0.0271214f,0.194909f,-0.109627f},{-0.0323898f,0.190384f,-0.114f}, +{-0.0377459f,0.185784f,-0.118117f},{-0.0483422f,0.175662f,-0.125105f},{-0.0483555f,0.175327f,-0.124624f}, +{-0.0538862f,0.1709f,-0.128429f},{-0.043179f,0.181117f,-0.121975f},{-0.0486787f,0.176393f,-0.125571f}, +{-0.0542346f,0.171622f,-0.128902f},{-0.059836f,0.166811f,-0.131968f},{-0.0654725f,0.16197f,-0.134769f}, +{-0.071134f,0.157107f,-0.137305f},{-0.0768103f,0.152232f,-0.139579f},{-0.0824916f,0.147352f,-0.141593f}, +{-0.0879387f,0.142154f,-0.143185f},{-0.0881686f,0.142476f,-0.143349f},{-0.0822657f,0.147026f,-0.14143f}, +{-0.093832f,0.137612f,-0.144853f},{-0.105084f,0.127948f,-0.147123f},{-0.0992353f,0.132451f,-0.145943f}, +{-0.104842f,0.127636f,-0.146956f},{-0.110062f,0.122328f,-0.146855f},{-0.110104f,0.122292f,-0.146244f}, +{-0.115564f,0.117602f,-0.147398f},{-0.0933121f,0.136714f,-0.143823f},{-0.0989286f,0.13189f,-0.145073f}, +{-0.0990277f,0.132129f,-0.145599f},{-0.110572f,0.122715f,-0.145367f},{-0.1103f,0.122447f,-0.145714f}, +{-0.105059f,0.12745f,-0.144599f},{-0.121454f,0.113368f,-0.146226f},{-0.126687f,0.108624f,-0.146474f}, +{-0.121199f,0.113087f,-0.146574f},{-0.1157f,0.117809f,-0.147929f},{-0.110186f,0.122545f,-0.147385f}, +{-0.126873f,0.108841f,-0.146297f},{-0.121715f,0.113664f,-0.146058f},{-0.127073f,0.109073f,-0.146158f}, +{-0.104626f,0.12732f,-0.14661f},{-0.104515f,0.127092f,-0.146082f},{-0.115932f,0.118111f,-0.148277f}, +{-0.11041f,0.122854f,-0.147732f},{-0.0994731f,0.132767f,-0.146109f},{-0.110655f,0.123163f,-0.147899f}, +{-0.116181f,0.118417f,-0.148445f},{-0.121654f,0.113716f,-0.148767f},{-0.127073f,0.109074f,-0.148876f}, +{0.0549276f,0.264054f,0.0918925f},{0.0553834f,0.26525f,0.0775529f},{0.0536128f,0.26373f,0.055544f}, +{0.0526607f,0.262912f,0.0481132f},{0.0515206f,0.261933f,0.040653f},{0.0501889f,0.260789f,0.0331749f}, +{0.0486625f,0.259478f,0.0256909f},{0.0469389f,0.257998f,0.0182135f},{0.0450162f,0.256346f,0.0107557f}, +{0.042893f,0.254523f,0.00333058f},{0.0405688f,0.252526f,-0.00404829f},{0.0353178f,0.248016f,-0.0186123f}, +{0.0323932f,0.245505f,-0.0257695f},{0.0292719f,0.242824f,-0.0328247f},{0.0259568f,0.239976f,-0.0397644f}, +{0.0224515f,0.236966f,-0.0465748f},{0.0187604f,0.233796f,-0.0532427f},{0.0148886f,0.23047f,-0.0597549f}, +{0.0108419f,0.226995f,-0.066099f},{0.00662668f,0.223374f,-0.0722628f},{0.00225007f,0.219615f,-0.0782348f}, +{-0.00228029f,0.215724f,-0.0840042f},{-0.00695617f,0.211708f,-0.0895609f},{-0.0167092f,0.203331f,-0.0999994f}, +{-0.0217676f,0.198987f,-0.104865f},{-0.0269342f,0.194549f,-0.109486f},{-0.0321988f,0.190028f,-0.113856f}, +{-0.0375512f,0.185431f,-0.117971f},{-0.0429805f,0.180768f,-0.121826f},{-0.0484764f,0.176047f,-0.125419f}, +{-0.0540283f,0.171279f,-0.128748f},{-0.0596258f,0.166471f,-0.131812f},{-0.0652585f,0.161633f,-0.134611f}, +{-0.070916f,0.156774f,-0.137145f},{-0.0765883f,0.151902f,-0.139417f},{-0.0935981f,0.137293f,-0.144688f}, +{-0.0933987f,0.136964f,-0.144346f},{-0.121401f,0.113414f,-0.148599f},{-0.12687f,0.108837f,-0.148751f}, +{0.0553672f,0.264736f,0.0775737f},{0.0526485f,0.262401f,0.0481766f},{0.05151f,0.261423f,0.0407271f}, +{0.0501802f,0.260281f,0.0332599f},{0.048656f,0.258972f,0.0257867f},{0.0469349f,0.257493f,0.0183202f}, +{0.045015f,0.255844f,0.0108731f},{0.0428949f,0.254024f,0.00345877f},{0.0324103f,0.245018f,-0.0255992f}, +{0.0353307f,0.247527f,-0.0184523f},{0.0351321f,0.247032f,-0.0182079f},{0.0292935f,0.242341f,-0.0326442f}, +{0.0259832f,0.239498f,-0.0395738f},{0.022483f,0.236492f,-0.0463744f},{0.0187972f,0.233326f,-0.0530326f}, +{0.00668107f,0.22292f,-0.0720252f},{0.00231079f,0.219167f,-0.0779886f},{-0.00221301f,0.215281f,-0.0837496f}, +{-0.0217444f,0.198182f,-0.104145f},{-0.0220124f,0.197952f,-0.103643f},{-0.0268921f,0.193761f,-0.108749f}, +{-0.016621f,0.202906f,-0.0997217f},{-0.0216721f,0.198568f,-0.10458f},{-0.0268312f,0.194137f,-0.109195f}, +{-0.0320882f,0.189622f,-0.113558f},{-0.0374328f,0.185032f,-0.117667f},{-0.0428543f,0.180375f,-0.121517f}, +{-0.0594756f,0.166099f,-0.131488f},{-0.0651f,0.161269f,-0.134283f},{-0.0707493f,0.156417f,-0.136814f}, +{-0.0764135f,0.151552f,-0.139083f},{-0.0820826f,0.146683f,-0.141092f},{-0.0877474f,0.141817f,-0.142845f}, +{-0.126387f,0.108276f,-0.147687f},{-0.121013f,0.112922f,-0.147719f},{-0.121027f,0.112911f,-0.147106f}, +{-0.121161f,0.113119f,-0.148251f},{-0.12669f,0.108628f,-0.148558f},{0.0552371f,0.264255f,0.0918925f}, +{0.0551243f,0.264203f,0.0776054f},{0.0533602f,0.262688f,0.055677f},{0.0524116f,0.261874f,0.0482734f}, +{0.0494972f,0.25937f,0.0335395f},{0.048428f,0.258452f,0.0259331f},{0.0499488f,0.259758f,0.0333897f}, +{0.0512756f,0.260898f,0.0408405f},{0.0467107f,0.256977f,0.0184831f},{0.044795f,0.255332f,0.0110526f}, +{0.0426797f,0.253515f,0.00365461f},{0.0403639f,0.251526f,-0.00369726f},{0.0378479f,0.249365f,-0.0109894f}, +{0.0287101f,0.241517f,-0.0320502f},{0.0258054f,0.239022f,-0.0392827f},{0.0291083f,0.241859f,-0.0323684f}, +{0.0322182f,0.24453f,-0.025339f},{0.0223129f,0.236022f,-0.0460682f},{0.0186353f,0.232864f,-0.0527117f}, +{0.00620553f,0.222188f,-0.0712434f},{0.00218538f,0.218735f,-0.0776124f},{0.006546f,0.22248f,-0.0716622f}, +{0.0107458f,0.226088f,-0.065521f},{-0.00232839f,0.214858f,-0.0833607f},{-0.00698716f,0.210857f,-0.088897f}, +{-0.0117822f,0.206739f,-0.094212f},{-0.0167045f,0.202511f,-0.0992973f},{-0.0321374f,0.189256f,-0.113103f}, +{-0.0374702f,0.184676f,-0.117203f},{-0.0428796f,0.18003f,-0.121044f},{-0.0596356f,0.165638f,-0.130423f}, +{-0.0650762f,0.160965f,-0.133782f},{-0.0594641f,0.165786f,-0.130993f},{-0.0538871f,0.170576f,-0.127941f}, +{-0.0707129f,0.156124f,-0.136307f},{-0.0763645f,0.15127f,-0.138571f},{-0.0820211f,0.146412f,-0.140576f}, +{-0.0876734f,0.141557f,-0.142325f},{-0.115776f,0.117744f,-0.146255f},{-0.104571f,0.127044f,-0.145472f}, +{-0.12644f,0.108337f,-0.148015f},{-0.126544f,0.108458f,-0.14831f},{0.0542482f,0.263451f,0.0704083f}, +{0.0546595f,0.263804f,0.077642f},{0.0536632f,0.262949f,0.0631143f},{0.0528999f,0.262293f,0.0557698f}, +{0.0519537f,0.26148f,0.0483851f},{0.0508206f,0.260507f,0.0409712f},{0.0479802f,0.258067f,0.026102f}, +{0.0422467f,0.253143f,0.00388058f},{0.0443566f,0.254955f,0.0112596f},{0.0438167f,0.254815f,0.011439f}, +{0.0462674f,0.256596f,0.0186711f},{0.0399369f,0.251159f,-0.00345247f},{0.0374272f,0.249004f,-0.0107259f}, +{0.0347185f,0.246677f,-0.017926f},{0.031812f,0.244181f,-0.0250388f},{0.0173238f,0.232562f,-0.0518103f}, +{0.017782f,0.232454f,-0.0520204f},{0.0209784f,0.235701f,-0.0452083f},{0.0254156f,0.238687f,-0.0389468f}, +{0.0219321f,0.235695f,-0.0457149f},{0.0182639f,0.232545f,-0.0523413f},{0.0144162f,0.22924f,-0.0588132f}, +{0.0103946f,0.225786f,-0.0651178f},{-0.00813902f,0.210692f,-0.0877701f},{-0.00771801f,0.210553f,-0.0880327f}, +{-0.00350929f,0.214669f,-0.0822683f},{0.00185609f,0.218452f,-0.0771783f},{-0.00264613f,0.214585f,-0.0829118f}, +{-0.00729298f,0.210594f,-0.088434f},{-0.0120758f,0.206487f,-0.0937354f},{-0.0169854f,0.20227f,-0.0988077f}, +{-0.037698f,0.18448f,-0.116668f},{-0.0323788f,0.189049f,-0.112578f},{-0.0327481f,0.189055f,-0.112123f}, +{-0.0271469f,0.193542f,-0.108235f},{-0.0430935f,0.179846f,-0.120499f},{-0.0485553f,0.175155f,-0.12407f}, +{-0.0540728f,0.170416f,-0.127378f},{-0.0652332f,0.160831f,-0.133204f},{-0.0821348f,0.146314f,-0.139981f}, +{-0.0764927f,0.15116f,-0.137981f},{-0.0767637f,0.151251f,-0.137469f},{-0.0708556f,0.156002f,-0.135723f}, +{-0.0877726f,0.141472f,-0.141725f},{-0.0933968f,0.136641f,-0.143219f},{-0.098999f,0.13183f,-0.144466f}, +{-0.104779f,0.127189f,-0.144944f},{-0.115592f,0.117579f,-0.146786f},{0.0536862f,0.263292f,0.0704561f}, +{0.0540966f,0.263644f,0.0776737f},{0.0531026f,0.262791f,0.0631783f},{0.0523409f,0.262136f,0.0558501f}, +{0.0513968f,0.261326f,0.0484819f},{0.0502663f,0.260355f,0.0410845f},{0.0489458f,0.25922f,0.0336694f}, +{0.0474322f,0.257921f,0.0262484f},{0.0457232f,0.256453f,0.018834f},{0.0412182f,0.253084f,0.00420461f}, +{0.0389169f,0.251108f,-0.00310144f},{0.0394067f,0.251028f,-0.00324031f},{0.0417114f,0.253007f,0.00407642f}, +{0.0369027f,0.248877f,-0.0104976f},{0.0342f,0.246556f,-0.0176816f},{0.0313f,0.244065f,-0.0247786f}, +{0.028205f,0.241407f,-0.0317744f},{0.0249178f,0.238583f,-0.0386556f},{0.021442f,0.235598f,-0.0454087f}, +{0.0139428f,0.229157f,-0.0584778f},{0.00993018f,0.225711f,-0.0647685f},{0.00575046f,0.222121f,-0.0708804f}, +{0.0014107f,0.218393f,-0.0768021f},{-0.0030815f,0.214535f,-0.0825229f},{-0.0124902f,0.206454f,-0.0933224f}, +{-0.0173889f,0.202247f,-0.0983834f},{-0.0224047f,0.197939f,-0.103208f},{-0.0275277f,0.193539f,-0.10779f}, +{-0.0384321f,0.184674f,-0.1159f},{-0.0438078f,0.180057f,-0.119717f},{-0.0434389f,0.179873f,-0.120026f}, +{-0.0380553f,0.184497f,-0.116203f},{-0.0488885f,0.175192f,-0.123589f},{-0.0543937f,0.170464f,-0.12689f}, +{-0.0599441f,0.165697f,-0.129928f},{-0.0655293f,0.1609f,-0.132703f},{-0.0711392f,0.156082f,-0.135216f}, +{-0.0823933f,0.146416f,-0.139465f},{-0.0883223f,0.141824f,-0.140865f},{-0.0939259f,0.137011f,-0.142353f}, +{-0.0936303f,0.136765f,-0.142696f},{-0.0880185f,0.141584f,-0.141206f},{-0.09922f,0.131964f,-0.14394f}, +{-0.126439f,0.108336f,-0.147023f},{-0.126387f,0.108275f,-0.147351f},{0.0538591f,0.263998f,0.0918925f}, +{0.0535853f,0.263706f,0.0776945f},{0.0525928f,0.262854f,0.0632202f},{0.0518322f,0.2622f,0.0559028f}, +{0.0522092f,0.263044f,0.0632405f},{0.0508895f,0.261391f,0.0485453f},{0.0497606f,0.260421f,0.0411587f}, +{0.048442f,0.259289f,0.0337544f},{0.0469307f,0.257991f,0.0263442f},{0.0452241f,0.256525f,0.0189407f}, +{0.0433204f,0.25489f,0.0115564f},{0.0333475f,0.246844f,-0.0174445f},{0.0360443f,0.249161f,-0.010276f}, +{0.0364165f,0.24896f,-0.0103481f},{0.0337177f,0.246642f,-0.0175217f},{0.030822f,0.244155f,-0.0246083f}, +{0.0277315f,0.241501f,-0.0315939f},{0.0244491f,0.238682f,-0.038465f},{0.0131342f,0.229483f,-0.0581524f}, +{0.0134902f,0.229269f,-0.0582583f},{0.016965f,0.232774f,-0.051709f},{0.00948339f,0.225828f,-0.0645398f}, +{0.00530978f,0.222243f,-0.0706427f},{0.00097635f,0.218521f,-0.0765558f},{-0.0132416f,0.20683f,-0.0929216f}, +{-0.0181297f,0.202631f,-0.0979716f},{-0.0129042f,0.206599f,-0.093052f},{-0.0177958f,0.202398f,-0.0981056f}, +{-0.0228042f,0.198097f,-0.102923f},{-0.0279198f,0.193703f,-0.107499f},{-0.0331325f,0.189226f,-0.111826f}, +{-0.0495612f,0.175636f,-0.123123f},{-0.0492495f,0.175383f,-0.123274f},{-0.0441234f,0.180306f,-0.119568f}, +{-0.0547466f,0.170662f,-0.126571f},{-0.0602889f,0.165902f,-0.129604f},{-0.0658659f,0.161112f,-0.132375f}, +{-0.0714676f,0.156301f,-0.134885f},{-0.0770839f,0.151477f,-0.137135f},{-0.0827053f,0.146649f,-0.139127f}, +{-0.0995074f,0.132218f,-0.143596f},{-0.116304f,0.118312f,-0.145739f},{-0.11084f,0.123004f,-0.145199f}, +{-0.116039f,0.118019f,-0.145907f},{-0.126541f,0.108454f,-0.146724f},{0.0514492f,0.262391f,0.0559281f}, +{0.0505071f,0.261582f,0.0485758f},{0.049379f,0.260613f,0.0411945f},{0.0480614f,0.259482f,0.0337954f}, +{0.0465511f,0.258185f,0.0263905f},{0.0448457f,0.25672f,0.0189921f},{0.0429433f,0.255086f,0.0116131f}, +{0.0408426f,0.253282f,0.00426646f},{0.038543f,0.251307f,-0.00303443f},{0.0304538f,0.244359f,-0.0245261f}, +{0.0273654f,0.241706f,-0.0315068f},{0.0240853f,0.238889f,-0.0383731f},{0.0206171f,0.23591f,-0.0451116f}, +{0.00913019f,0.226044f,-0.0644294f},{0.00495953f,0.222462f,-0.0705281f},{0.00062916f,0.218743f,-0.076437f}, +{-0.00385332f,0.214893f,-0.0821454f},{-0.00847979f,0.21092f,-0.0876434f},{-0.0231347f,0.198333f,-0.102786f}, +{-0.0282467f,0.193942f,-0.107358f},{-0.0334557f,0.189468f,-0.111682f},{-0.0387515f,0.18492f,-0.115753f}, +{-0.0550545f,0.170917f,-0.126416f},{-0.0605929f,0.166161f,-0.129448f},{-0.066166f,0.161374f,-0.132217f}, +{-0.0717637f,0.156566f,-0.134725f},{-0.0773761f,0.151746f,-0.136973f},{-0.0829935f,0.146921f,-0.138964f}, +{-0.0886065f,0.1421f,-0.140701f},{-0.0942061f,0.137291f,-0.142188f},{-0.0997837f,0.1325f,-0.14343f}, +{-0.105331f,0.127736f,-0.144432f},{-0.246242f,0.00568906f,-0.0892991f},{-0.241437f,0.00981657f,-0.0946258f}, +{-0.241022f,0.00984878f,-0.0942128f},{-0.221744f,0.0277507f,-0.114f},{-0.227012f,0.023226f,-0.109627f}, +{-0.216388f,0.0323507f,-0.118117f},{-0.210955f,0.0370173f,-0.121975f},{-0.205455f,0.0417412f,-0.125571f}, +{-0.199899f,0.0465131f,-0.128902f},{-0.194298f,0.0513242f,-0.131968f},{-0.188661f,0.0561654f,-0.134769f}, +{-0.205143f,0.0414889f,-0.125419f},{-0.199238f,0.0460598f,-0.128429f},{-0.204783f,0.041298f,-0.125105f}, +{-0.182999f,0.061028f,-0.137305f},{-0.177323f,0.0659033f,-0.139579f},{-0.171642f,0.0707829f,-0.141592f}, +{-0.160302f,0.0805227f,-0.144853f},{-0.165965f,0.0756586f,-0.143349f},{-0.154661f,0.0853677f,-0.146109f}, +{-0.14905f,0.0901863f,-0.147122f},{-0.143479f,0.0949717f,-0.147899f},{-0.132419f,0.10447f,-0.146057f}, +{-0.14321f,0.0946823f,-0.147731f},{-0.148778f,0.0899002f,-0.146955f},{-0.143294f,0.0951304f,-0.145199f}, +{-0.143048f,0.0948213f,-0.145366f},{-0.13783f,0.0998229f,-0.145739f},{-0.14829f,0.0894947f,-0.146081f}, +{-0.154097f,0.084831f,-0.145599f},{-0.148499f,0.0896393f,-0.14661f},{-0.131926f,0.103873f,-0.146574f}, +{-0.131778f,0.103676f,-0.147105f},{-0.132166f,0.104168f,-0.146225f},{-0.142939f,0.0944145f,-0.147384f}, +{-0.131792f,0.103664f,-0.147719f},{-0.13248f,0.104418f,-0.148767f},{-0.132219f,0.104122f,-0.148599f}, +{-0.137953f,0.0997176f,-0.148445f},{-0.131964f,0.10384f,-0.148251f},{-0.142742f,0.0942593f,-0.146855f}, +{-0.232183f,0.0187856f,-0.105003f},{-0.237244f,0.0144381f,-0.100134f},{-0.242188f,0.010192f,-0.0950266f}, +{-0.247004f,0.00605566f,-0.0896885f},{-0.251683f,0.00203683f,-0.0841281f},{-0.256217f,-0.00185696f,-0.0783547f}, +{-0.260596f,-0.00561864f,-0.0723786f},{-0.268508f,-0.0129341f,-0.059756f},{-0.264015f,-0.00957541f,-0.0658715f}, +{-0.268056f,-0.0130461f,-0.0595366f},{-0.264815f,-0.00924161f,-0.0662105f},{-0.268864f,-0.0127198f,-0.059862f}, +{-0.272739f,-0.0160476f,-0.053345f},{-0.276433f,-0.0192201f,-0.0466724f},{-0.279941f,-0.022233f,-0.039857f}, +{-0.283258f,-0.0250823f,-0.0329122f},{-0.286382f,-0.0277651f,-0.0258517f},{-0.291178f,-0.0329051f,-0.0112184f}, +{-0.290653f,-0.0327782f,-0.01099f},{-0.293699f,-0.0350709f,-0.00391029f},{-0.289308f,-0.0302787f,-0.0186898f}, +{-0.292036f,-0.0326214f,-0.0114399f},{-0.294563f,-0.0347919f,-0.00411618f},{-0.296889f,-0.0367896f,0.00326766f}, +{-0.299014f,-0.0386144f,0.0106978f},{-0.300938f,-0.040267f,0.0181608f},{-0.302663f,-0.0417484f,0.0256434f}, +{-0.30419f,-0.0430604f,0.0331326f},{-0.305141f,-0.0443974f,0.0406518f},{-0.305523f,-0.044205f,0.040616f}, +{-0.303809f,-0.0432535f,0.0331736f},{-0.306664f,-0.045185f,0.0480815f},{-0.308737f,-0.0479862f,0.0847721f}, +{-0.30793f,-0.0476169f,0.077605f},{-0.308173f,-0.0478259f,0.0847878f},{-0.306812f,-0.0463329f,0.0704555f}, +{-0.307054f,-0.0468645f,0.0704077f},{-0.306228f,-0.0458317f,0.0631775f},{-0.307233f,-0.0461944f,0.0555431f}, +{-0.308002f,-0.0468541f,0.0629336f},{-0.308385f,-0.0466635f,0.0629134f},{-0.306796f,-0.0458187f,0.0704868f}, +{-0.306213f,-0.0453183f,0.0632194f},{-0.307448f,-0.0463783f,0.0848321f},{-0.307515f,-0.0467654f,0.0918925f}, +{-0.307464f,-0.0468934f,0.0848218f},{-0.306931f,-0.0467592f,0.0630396f},{-0.308079f,-0.0474218f,0.0703047f}, +{-0.307492f,-0.046917f,0.0629755f},{-0.307577f,-0.0459696f,0.0848371f},{-0.307535f,-0.0464061f,0.0918925f}, +{-0.306166f,-0.0461019f,0.0556761f},{-0.306725f,-0.0462583f,0.0555957f},{-0.305217f,-0.0452871f,0.0482723f}, +{-0.307647f,-0.046058f,0.0918925f},{-0.307617f,-0.0460033f,0.0555177f},{-0.309388f,-0.047525f,0.0775425f}, +{-0.308974f,-0.0471693f,0.0702583f},{-0.30859f,-0.0473596f,0.0702734f},{-0.309633f,-0.0477349f,0.0847568f}, +{-0.137688f,0.0994249f,-0.148277f},{-0.154384f,0.0850849f,-0.145943f},{-0.160021f,0.0802434f,-0.144688f}, +{-0.165681f,0.0753827f,-0.143185f},{-0.171354f,0.0705103f,-0.141429f},{-0.177031f,0.0656341f,-0.139417f}, +{-0.182703f,0.0607622f,-0.137145f},{-0.188361f,0.055903f,-0.134611f},{-0.193994f,0.0510652f,-0.131812f}, +{-0.199591f,0.0462575f,-0.128748f},{-0.21064f,0.0367683f,-0.121826f},{-0.216069f,0.032105f,-0.117971f}, +{-0.221421f,0.0275082f,-0.113856f},{-0.226686f,0.0229866f,-0.109486f},{-0.231852f,0.0185493f,-0.104866f}, +{-0.23691f,0.0142048f,-0.1f},{-0.241851f,0.00996175f,-0.0948962f},{-0.246663f,0.00582826f,-0.0895618f}, +{-0.251339f,0.00181224f,-0.0840052f},{-0.25587f,-0.00207883f,-0.0782359f},{-0.260246f,-0.00583789f,-0.072264f}, +{-0.264462f,-0.00945834f,-0.0661002f},{-0.27238f,-0.0162596f,-0.0532437f},{-0.276071f,-0.0194299f,-0.0465757f}, +{-0.279577f,-0.0224406f,-0.039765f},{-0.282892f,-0.025288f,-0.0328251f},{-0.286013f,-0.0279689f,-0.0257695f}, +{-0.288938f,-0.0304808f,-0.0186126f},{-0.291664f,-0.0328218f,-0.0113678f},{-0.294189f,-0.0349908f,-0.00404916f}, +{-0.296513f,-0.0369871f,0.00332952f},{-0.298637f,-0.0388106f,0.0107545f},{-0.300559f,-0.0404621f,0.0182123f}, +{-0.302283f,-0.0419425f,0.0256896f},{-0.306281f,-0.0453766f,0.0481121f},{-0.305774f,-0.0454417f,0.0481755f}, +{-0.309248f,-0.0479248f,0.0847617f},{-0.309004f,-0.047715f,0.0775525f},{-0.309376f,-0.0479772f,0.0918925f}, +{-0.309694f,-0.0478162f,0.0918925f},{-0.137425f,0.0991502f,-0.147929f},{-0.159726f,0.0799965f,-0.144345f}, +{-0.165377f,0.0751428f,-0.142845f},{-0.171042f,0.0702775f,-0.141092f},{-0.176711f,0.0654083f,-0.139082f}, +{-0.182375f,0.0605435f,-0.136814f},{-0.188024f,0.0556914f,-0.134283f},{-0.193649f,0.0508605f,-0.131488f}, +{-0.215692f,0.0319277f,-0.117667f},{-0.210271f,0.0365843f,-0.121517f},{-0.209925f,0.0365573f,-0.121044f}, +{-0.221037f,0.0273376f,-0.113559f},{-0.226294f,0.0228226f,-0.109195f},{-0.231453f,0.0183917f,-0.104581f}, +{-0.236503f,0.0140535f,-0.0997223f},{-0.250911f,0.00167885f,-0.0837506f},{-0.255435f,-0.00220659f,-0.0779897f}, +{-0.259806f,-0.00596021f,-0.0720263f},{-0.275118f,-0.0194353f,-0.046069f},{-0.274737f,-0.0191082f,-0.0457157f}, +{-0.27861f,-0.022435f,-0.0392833f},{-0.271922f,-0.0163668f,-0.0530336f},{-0.275608f,-0.0195325f,-0.0463752f}, +{-0.279108f,-0.0225389f,-0.0395744f},{-0.282419f,-0.0253822f,-0.0326445f},{-0.285535f,-0.0280592f,-0.0255992f}, +{-0.288456f,-0.0305674f,-0.0184526f},{-0.29602f,-0.0370643f,0.00345771f},{-0.29814f,-0.0388852f,0.0108719f}, +{-0.30006f,-0.0405343f,0.0183189f},{-0.301781f,-0.0420125f,0.0257854f},{-0.303306f,-0.0433217f,0.0332586f}, +{-0.304636f,-0.0444639f,0.0407259f},{-0.308493f,-0.0477767f,0.0775733f},{-0.307518f,-0.0472628f,0.0703525f}, +{-0.309015f,-0.0480539f,0.0918925f},{-0.137241f,0.0989846f,-0.147398f},{-0.153876f,0.0846971f,-0.145073f}, +{-0.159492f,0.0798733f,-0.143822f},{-0.170669f,0.0702734f,-0.13998f},{-0.17644f,0.0653174f,-0.138571f}, +{-0.170783f,0.0701758f,-0.140576f},{-0.165131f,0.0750303f,-0.142325f},{-0.182091f,0.0604634f,-0.136307f}, +{-0.187728f,0.055622f,-0.133782f},{-0.19334f,0.0508018f,-0.130993f},{-0.198917f,0.0460117f,-0.127941f}, +{-0.204449f,0.0412605f,-0.124624f},{-0.220426f,0.0275383f,-0.112579f},{-0.225913f,0.022826f,-0.10875f}, +{-0.220668f,0.027331f,-0.113104f},{-0.215335f,0.031911f,-0.117203f},{-0.23106f,0.0184049f,-0.104146f}, +{-0.2361f,0.0140763f,-0.0992979f},{-0.250158f,0.00200198f,-0.0829128f},{-0.25499f,-0.00214776f,-0.0776135f}, +{-0.250476f,0.00172908f,-0.0833616f},{-0.245817f,0.00573041f,-0.0888979f},{-0.25935f,-0.00589306f,-0.0716633f}, +{-0.26355f,-0.00950025f,-0.0655221f},{-0.267582f,-0.0129633f,-0.0592012f},{-0.27144f,-0.0162766f,-0.0527127f}, +{-0.281913f,-0.025272f,-0.0323688f},{-0.285023f,-0.0279431f,-0.025339f},{-0.287937f,-0.0304458f,-0.0182083f}, +{-0.295052f,-0.0365564f,0.00387953f},{-0.2976f,-0.0387452f,0.0110514f},{-0.295485f,-0.0369283f,0.00365355f}, +{-0.293169f,-0.0349393f,-0.00369814f},{-0.299516f,-0.0403906f,0.0184819f},{-0.301233f,-0.0418655f,0.0259318f}, +{-0.302754f,-0.0431718f,0.0333884f},{-0.304081f,-0.0443114f,0.0408392f},{-0.306469f,-0.0463621f,0.0631135f}, +{-0.308656f,-0.0480337f,0.0918925f},{-0.142701f,0.0942953f,-0.146243f},{-0.137213f,0.0990084f,-0.146785f}, +{-0.148234f,0.0895429f,-0.145472f},{-0.153805f,0.0847575f,-0.144466f},{-0.159408f,0.079946f,-0.143218f}, +{-0.165032f,0.0751155f,-0.141725f},{-0.176312f,0.0654275f,-0.137981f},{-0.193169f,0.0509491f,-0.130423f}, +{-0.187571f,0.0557569f,-0.133204f},{-0.187595f,0.05606f,-0.132703f},{-0.181949f,0.0605859f,-0.135723f}, +{-0.198732f,0.0461712f,-0.127378f},{-0.204249f,0.0414322f,-0.12407f},{-0.209711f,0.036741f,-0.120499f}, +{-0.215107f,0.0321066f,-0.116668f},{-0.235824f,0.0151381f,-0.0981062f},{-0.235736f,0.014713f,-0.098384f}, +{-0.230815f,0.0194397f,-0.102924f},{-0.225658f,0.0230449f,-0.108236f},{-0.230792f,0.0186351f,-0.103644f}, +{-0.235819f,0.0143176f,-0.0988083f},{-0.240729f,0.0101009f,-0.0937362f},{-0.245511f,0.00599306f,-0.0884349f}, +{-0.263103f,-0.00829154f,-0.0645409f},{-0.263055f,-0.00875088f,-0.0647696f},{-0.258929f,-0.00470683f,-0.0706439f}, +{-0.25466f,-0.00186493f,-0.0771794f},{-0.25901f,-0.00560064f,-0.0712445f},{-0.263199f,-0.00919859f,-0.065119f}, +{-0.267221f,-0.0126528f,-0.0588143f},{-0.271069f,-0.0159576f,-0.0523423f},{-0.284617f,-0.0275942f,-0.0250388f}, +{-0.281515f,-0.02493f,-0.0320505f},{-0.28133f,-0.0244472f,-0.0317747f},{-0.278221f,-0.0221003f,-0.0389474f}, +{-0.287524f,-0.0300905f,-0.0179263f},{-0.290232f,-0.032417f,-0.0107265f},{-0.292742f,-0.0345725f,-0.00345334f}, +{-0.297162f,-0.0383686f,0.0112584f},{-0.302303f,-0.0427839f,0.0335382f},{-0.300786f,-0.041481f,0.0261007f}, +{-0.300558f,-0.0409614f,0.0262471f},{-0.299073f,-0.0400098f,0.0186698f},{-0.303626f,-0.0439206f,0.04097f}, +{-0.304759f,-0.0448938f,0.048384f},{-0.305705f,-0.0457065f,0.0557688f},{-0.307465f,-0.0472177f,0.0776416f}, +{-0.307708f,-0.0474261f,0.084806f},{-0.307998f,-0.0477204f,0.0918925f},{-0.308307f,-0.0479214f,0.0918925f}, +{-0.142824f,0.0945127f,-0.145713f},{-0.137349f,0.0992153f,-0.146254f},{-0.148345f,0.0897709f,-0.144944f}, +{-0.153904f,0.0849962f,-0.14394f},{-0.159494f,0.0801954f,-0.142695f},{-0.165106f,0.0753756f,-0.141205f}, +{-0.170731f,0.0705443f,-0.139464f},{-0.176361f,0.0657091f,-0.137469f},{-0.181985f,0.0608783f,-0.135216f}, +{-0.193331f,0.0516347f,-0.129604f},{-0.198873f,0.0468744f,-0.126571f},{-0.198731f,0.0464957f,-0.12689f}, +{-0.19318f,0.0512629f,-0.129928f},{-0.204236f,0.0417672f,-0.123589f},{-0.209686f,0.0370865f,-0.120026f}, +{-0.21507f,0.0324624f,-0.116203f},{-0.220377f,0.0279043f,-0.112124f},{-0.225597f,0.0234208f,-0.10779f}, +{-0.23072f,0.0190209f,-0.103209f},{-0.240634f,0.0105057f,-0.0933231f},{-0.245406f,0.00640698f,-0.0880336f}, +{-0.250043f,0.00242477f,-0.0825239f},{-0.254535f,-0.00143353f,-0.0768032f},{-0.258875f,-0.00516092f,-0.0708815f}, +{-0.267067f,-0.0121974f,-0.0584789f},{-0.270907f,-0.0154949f,-0.0520214f},{-0.274567f,-0.0186385f,-0.0454095f}, +{-0.278043f,-0.0216238f,-0.0386562f},{-0.284442f,-0.0266194f,-0.0246083f},{-0.287338f,-0.0291065f,-0.017522f}, +{-0.287325f,-0.0295963f,-0.017682f},{-0.284425f,-0.0271056f,-0.0247786f},{-0.290028f,-0.0319176f,-0.0104982f}, +{-0.292532f,-0.0340683f,-0.00324118f},{-0.294837f,-0.0360478f,0.00407537f},{-0.296942f,-0.037856f,0.0114378f}, +{-0.298849f,-0.0394935f,0.0188328f},{-0.302071f,-0.0422615f,0.0336681f},{-0.303381f,-0.0428858f,0.0411575f}, +{-0.30451f,-0.0438554f,0.0485442f},{-0.304522f,-0.0443667f,0.0484808f},{-0.303392f,-0.0433957f,0.0410833f}, +{-0.305467f,-0.0451776f,0.0558492f},{-0.307222f,-0.0466854f,0.0776733f},{-0.307591f,-0.0471265f,0.0918925f}, +{-0.307758f,-0.047452f,0.0918925f},{-0.137581f,0.0995171f,-0.145907f},{-0.148561f,0.0900864f,-0.144598f}, +{-0.154112f,0.0853187f,-0.143596f},{-0.148803f,0.0903988f,-0.144431f},{-0.159694f,0.0805249f,-0.142353f}, +{-0.165297f,0.0757121f,-0.140865f},{-0.170914f,0.0708878f,-0.139127f},{-0.176535f,0.0660598f,-0.137134f}, +{-0.182152f,0.061236f,-0.134885f},{-0.187753f,0.0564248f,-0.132375f},{-0.210011f,0.0378285f,-0.119568f}, +{-0.204573f,0.0424991f,-0.123123f},{-0.20437f,0.0421528f,-0.123274f},{-0.209812f,0.0374789f,-0.119717f}, +{-0.215188f,0.0328616f,-0.1159f},{-0.220487f,0.0283101f,-0.111826f},{-0.2257f,0.0238332f,-0.107499f}, +{-0.240892f,0.0113052f,-0.0929223f},{-0.240715f,0.0109369f,-0.0930527f},{-0.236004f,0.0155034f,-0.0979722f}, +{-0.24548f,0.00684419f,-0.087771f},{-0.25011f,0.0028678f,-0.0822693f},{-0.254596f,-0.000984871f,-0.0765569f}, +{-0.267268f,-0.0113487f,-0.0581535f},{-0.271099f,-0.0146391f,-0.0517099f},{-0.26711f,-0.011733f,-0.0582594f}, +{-0.270944f,-0.0150257f,-0.0518113f},{-0.274598f,-0.0181647f,-0.0452091f},{-0.278069f,-0.0211457f,-0.0384656f}, +{-0.281352f,-0.023965f,-0.0315942f},{-0.290179f,-0.0310263f,-0.0102766f},{-0.290037f,-0.0314244f,-0.0103487f}, +{-0.287482f,-0.02871f,-0.0174448f},{-0.292537f,-0.033572f,-0.0031023f},{-0.294839f,-0.0355486f,0.00420356f}, +{-0.296941f,-0.0373542f,0.0115553f},{-0.298845f,-0.0389893f,0.0189394f},{-0.300551f,-0.0404551f,0.026343f}, +{-0.302063f,-0.0417532f,0.0337531f},{-0.305453f,-0.044665f,0.0559018f},{-0.307336f,-0.0457621f,0.0777041f}, +{-0.306926f,-0.0454104f,0.0705019f},{-0.307206f,-0.0461706f,0.077694f},{-0.15435f,0.0856345f,-0.143429f}, +{-0.159927f,0.0808441f,-0.142188f},{-0.165527f,0.0760347f,-0.140701f},{-0.17114f,0.0712139f,-0.138964f}, +{-0.176757f,0.0663892f,-0.136973f},{-0.18237f,0.0615688f,-0.134725f},{-0.187968f,0.056761f,-0.132217f}, +{-0.193541f,0.0519743f,-0.129448f},{-0.199079f,0.0472174f,-0.126416f},{-0.215383f,0.0332144f,-0.115753f}, +{-0.220678f,0.0286662f,-0.111682f},{-0.225887f,0.0241924f,-0.107358f},{-0.230999f,0.019802f,-0.102786f}, +{-0.245654f,0.00721537f,-0.0876442f},{-0.25028f,0.00324179f,-0.0821464f},{-0.254763f,-0.000608165f,-0.0764381f}, +{-0.259093f,-0.00432749f,-0.0705292f},{-0.263264f,-0.00790968f,-0.0644306f},{-0.274751f,-0.0177759f,-0.0451124f}, +{-0.27822f,-0.0207548f,-0.0383737f},{-0.2815f,-0.0235721f,-0.0315071f},{-0.284588f,-0.0262246f,-0.0245261f}, +{-0.292677f,-0.0331723f,-0.0030353f},{-0.294977f,-0.0351475f,0.00426541f},{-0.297078f,-0.0369518f,0.0116119f}, +{-0.29898f,-0.0385858f,0.0189909f},{-0.300686f,-0.0400505f,0.0263892f},{-0.302196f,-0.0413477f,0.0337941f}, +{-0.303514f,-0.0424795f,0.0411933f},{-0.304642f,-0.0434484f,0.0485748f},{-0.305584f,-0.0442575f,0.0559272f}, +{-0.306344f,-0.0449103f,0.0632397f},{0.164482f,-0.077386f,-0.141015f},{0.160376f,-0.0813663f,-0.142188f}, +{0.165975f,-0.076557f,-0.140701f},{0.193989f,-0.0524965f,-0.129448f},{0.195149f,-0.0510464f,-0.12867f}, +{0.190161f,-0.0553306f,-0.131224f},{0.144011f,-0.0959421f,-0.145366f},{0.144282f,-0.0962099f,-0.145713f}, +{0.149803f,-0.0914681f,-0.144944f},{0.154798f,-0.0861567f,-0.143429f},{0.15923f,-0.0818969f,-0.142366f}, +{0.155583f,-0.0868273f,-0.144466f},{0.150012f,-0.0916126f,-0.145472f},{0.143742f,-0.0956526f,-0.145199f}, +{0.149524f,-0.0912072f,-0.144598f},{0.149251f,-0.0909211f,-0.144431f},{0.13357f,-0.105734f,-0.147719f}, +{0.133556f,-0.105746f,-0.147105f},{0.128196f,-0.110381f,-0.147351f},{0.144478f,-0.096365f,-0.146243f}, +{0.127892f,-0.110028f,-0.148558f},{0.133182f,-0.105243f,-0.148599f},{0.133422f,-0.105538f,-0.148251f}, +{0.128143f,-0.11032f,-0.148015f},{0.138114f,-0.100033f,-0.148493f},{0.138401f,-0.10024f,-0.148445f}, +{0.132929f,-0.10494f,-0.148767f},{0.132705f,-0.104679f,-0.14881f},{0.12751f,-0.109583f,-0.148876f}, +{0.127291f,-0.109328f,-0.148916f},{0.174884f,-0.0684522f,-0.137702f},{0.171588f,-0.0717361f,-0.138964f}, +{0.177206f,-0.0669114f,-0.136973f},{0.169701f,-0.0729032f,-0.13946f},{0.182818f,-0.062091f,-0.134725f}, +{0.180024f,-0.0640372f,-0.135742f},{0.188716f,-0.0575456f,-0.132375f},{0.188416f,-0.0572832f,-0.132217f}, +{0.185118f,-0.0596621f,-0.133582f},{0.199528f,-0.0477396f,-0.126416f},{0.200078f,-0.0468134f,-0.125923f}, +{0.210459f,-0.0383507f,-0.119568f},{0.215831f,-0.0337366f,-0.115753f},{0.214463f,-0.0344587f,-0.116543f}, +{0.205021f,-0.0430213f,-0.123123f},{0.228159f,-0.0226953f,-0.105516f},{0.223677f,-0.0265448f,-0.109369f}, +{0.226336f,-0.0247146f,-0.107358f},{0.21911f,-0.0304671f,-0.113046f},{0.236853f,-0.0152278f,-0.0972923f}, +{0.236452f,-0.0160256f,-0.0979722f},{0.24134f,-0.0118274f,-0.0929223f},{0.231448f,-0.0203242f,-0.102786f}, +{0.249164f,-0.00465414f,-0.0837205f},{0.250729f,-0.00376401f,-0.0821464f},{0.253058f,-0.00130946f,-0.0788827f}, +{0.246102f,-0.00773759f,-0.0876442f},{0.264065f,0.00814415f,-0.0634868f},{0.260512f,0.00509248f,-0.0687614f}, +{0.263712f,0.00738746f,-0.0644306f},{0.256842f,0.00194036f,-0.0738949f},{0.259542f,0.00380527f,-0.0705292f}, +{0.273991f,0.0166696f,-0.0468636f},{0.271547f,0.0141168f,-0.0517099f},{0.2752f,0.0172537f,-0.0451124f}, +{0.267717f,0.0108265f,-0.0581535f},{0.281948f,0.0230499f,-0.0315071f},{0.282759f,0.0241996f,-0.0291439f}, +{0.27997f,0.0218041f,-0.0351637f},{0.277046f,0.0192933f,-0.041072f},{0.290298f,0.0306748f,-0.010468f}, +{0.287925f,0.0286369f,-0.0167907f},{0.290627f,0.030504f,-0.0102766f},{0.285037f,0.0257024f,-0.0245261f}, +{0.293126f,0.0326501f,-0.0030353f},{0.294612f,0.0343798f,0.00244111f},{0.292527f,0.0325897f,-0.00405553f}, +{0.299429f,0.0380636f,0.0189909f},{0.298338f,0.0375801f,0.0156645f},{0.297526f,0.0364296f,0.0116119f}, +{0.296549f,0.0360438f,0.00901635f},{0.295426f,0.0346253f,0.00426541f},{0.301463f,0.0402644f,0.0291557f}, +{0.302645f,0.0408255f,0.0337941f},{0.302797f,0.04141f,0.0359868f},{0.301134f,0.0395283f,0.0263892f}, +{0.299976f,0.0389874f,0.0223796f},{0.303977f,0.0424232f,0.0428671f},{0.30509f,0.0429262f,0.0485748f}, +{0.305001f,0.0433031f,0.0497904f},{0.303962f,0.0419573f,0.0411933f},{0.308026f,0.0454474f,0.0848371f}, +{0.307848f,0.0457485f,0.0918925f},{0.307769f,0.0456805f,0.0848393f},{0.305869f,0.044049f,0.0567509f}, +{0.306032f,0.0437353f,0.0559272f},{0.307375f,0.0448882f,0.0705019f},{0.307759f,0.0446979f,0.0704868f}, +{0.308168f,0.0450498f,0.077694f},{0.307531f,0.0454763f,0.0777923f},{0.306581f,0.0446602f,0.0637421f}, +{0.307135f,0.0451361f,0.0707579f},{0.307784f,0.0452398f,0.0777041f},{0.306792f,0.044388f,0.0632397f}, +{0.30868f,0.0449881f,0.0776733f},{0.309485f,0.0453564f,0.084806f},{0.308922f,0.0451961f,0.0848218f}, +{0.305473f,0.0427346f,0.0485442f},{0.304344f,0.041765f,0.0411575f},{0.308269f,0.0446357f,0.0704555f}, +{0.307176f,0.0441974f,0.0632194f},{0.307686f,0.0441345f,0.0631775f},{0.30598f,0.0426695f,0.0484808f}, +{0.309295f,0.0451931f,0.0703525f},{0.308709f,0.0446894f,0.0630396f},{0.309537f,0.0457246f,0.0703047f}, +{0.308247f,0.0442923f,0.0631135f},{0.308831f,0.0447947f,0.0704077f},{0.309553f,0.0462388f,0.0702734f}, +{0.309967f,0.0465942f,0.0775525f},{0.310303f,0.0465537f,0.0918925f},{0.310194f,0.0462889f,0.0847721f}, +{0.310211f,0.046804f,0.0847617f},{0.310081f,0.0472127f,0.0847568f},{0.310171f,0.0472612f,0.0918925f}, +{0.310283f,0.046913f,0.0918925f},{0.30997f,0.0475707f,0.0918925f},{0.301514f,0.0393343f,0.026343f}, +{0.278668f,0.0202326f,-0.0383737f},{0.285411f,0.0264779f,-0.0230178f},{0.28793f,0.0281877f,-0.0174448f}, +{0.282314f,0.0228442f,-0.0315942f},{0.270808f,0.0139352f,-0.0525331f},{0.267498f,0.0110925f,-0.0580758f}, +{0.255211f,8.59432e-005f,-0.0764381f},{0.245163f,-0.00809075f,-0.088404f},{0.259892f,0.00358602f,-0.0706439f}, +{0.260333f,0.0034637f,-0.0708815f},{0.264512f,0.00705366f,-0.0647696f},{0.241058f,-0.0116164f,-0.0929293f}, +{0.232552f,-0.0189219f,-0.101489f},{0.209739f,-0.0385159f,-0.119856f},{0.204942f,-0.0426353f,-0.122984f}, +{0.221127f,-0.0291884f,-0.111682f},{0.237193f,-0.0164102f,-0.098384f},{0.231778f,-0.0205605f,-0.102924f}, +{0.232178f,-0.0207181f,-0.103209f},{0.15395f,-0.0864318f,-0.14351f},{0.148646f,-0.090987f,-0.144448f}, +{0.143324f,-0.0955583f,-0.145179f},{0.133384f,-0.10557f,-0.146574f},{0.128144f,-0.110321f,-0.147023f}, +{0.138279f,-0.100345f,-0.145739f},{0.137988f,-0.100142f,-0.145701f},{0.132868f,-0.104993f,-0.146057f}, +{0.132642f,-0.104733f,-0.146014f},{0.128196f,-0.110381f,-0.147687f},{0.12751f,-0.109583f,-0.146158f}, +{0.127291f,-0.109328f,-0.146119f},{0.12771f,-0.109815f,-0.146297f},{0.127896f,-0.110032f,-0.146474f}, +{0.133129f,-0.105289f,-0.146225f},{0.128042f,-0.110202f,-0.146724f},{0.138543f,-0.100638f,-0.145907f}, +{0.155075f,-0.0864395f,-0.143596f},{0.160656f,-0.0816457f,-0.142353f},{0.16626f,-0.0768329f,-0.140865f}, +{0.171877f,-0.0720087f,-0.139127f},{0.177498f,-0.0671806f,-0.137134f},{0.183114f,-0.0623568f,-0.134885f}, +{0.194638f,-0.0529602f,-0.129928f},{0.200189f,-0.0481929f,-0.12689f},{0.194293f,-0.0527555f,-0.129604f}, +{0.199836f,-0.0479952f,-0.126571f},{0.205333f,-0.0432736f,-0.123274f},{0.210775f,-0.0385997f,-0.119717f}, +{0.216151f,-0.0339824f,-0.1159f},{0.22145f,-0.0294309f,-0.111826f},{0.226663f,-0.024954f,-0.107499f}, +{0.236786f,-0.0162589f,-0.0981062f},{0.241678f,-0.0120577f,-0.0930527f},{0.246443f,-0.00796499f,-0.087771f}, +{0.251073f,-0.00398861f,-0.0822693f},{0.255558f,-0.000135934f,-0.0765569f},{0.264066f,0.00717073f,-0.0645409f}, +{0.268073f,0.0106122f,-0.0582594f},{0.271906f,0.0139049f,-0.0518113f},{0.275561f,0.0170439f,-0.0452091f}, +{0.279032f,0.0200249f,-0.0384656f},{0.29201f,0.0303472f,-0.0107265f},{0.288783f,0.0278991f,-0.017682f}, +{0.289301f,0.0280207f,-0.0179263f},{0.285405f,0.0254986f,-0.0246083f},{0.288301f,0.0279857f,-0.017522f}, +{0.290999f,0.0303036f,-0.0103487f},{0.2935f,0.0324512f,-0.0031023f},{0.295801f,0.0344278f,0.00420356f}, +{0.297903f,0.0362334f,0.0115553f},{0.299807f,0.0378685f,0.0189394f},{0.303025f,0.0406324f,0.0337531f}, +{0.30485f,0.0416984f,0.0410833f},{0.306415f,0.0435442f,0.0559018f},{0.30841f,0.0452575f,0.0848321f}, +{0.308442f,0.0453419f,0.0918925f},{0.308124f,0.045503f,0.0918925f},{0.128039f,-0.110199f,-0.14831f}, +{0.138807f,-0.100913f,-0.146254f},{0.155362f,-0.0866934f,-0.14394f},{0.160952f,-0.0818926f,-0.142695f}, +{0.166563f,-0.0770728f,-0.141205f},{0.172189f,-0.0722415f,-0.139464f},{0.177818f,-0.0674064f,-0.137469f}, +{0.183443f,-0.0625755f,-0.135216f},{0.189053f,-0.0577573f,-0.132703f},{0.205694f,-0.0434645f,-0.123589f}, +{0.206027f,-0.043502f,-0.12407f},{0.211489f,-0.0388108f,-0.120499f},{0.211144f,-0.0387837f,-0.120026f}, +{0.216528f,-0.0341596f,-0.116203f},{0.221835f,-0.0296015f,-0.112124f},{0.227055f,-0.0251181f,-0.10779f}, +{0.247289f,-0.00806285f,-0.0884349f},{0.247595f,-0.00780019f,-0.0888979f},{0.252254f,-0.00379886f,-0.0833616f}, +{0.242092f,-0.0122029f,-0.0933231f},{0.246864f,-0.0081042f,-0.0880336f},{0.251501f,-0.00412199f,-0.0825239f}, +{0.255993f,-0.000263687f,-0.0768032f},{0.272846f,0.0138878f,-0.0523423f},{0.273218f,0.0142069f,-0.0527127f}, +{0.276895f,0.0173656f,-0.046069f},{0.268525f,0.0105001f,-0.0584789f},{0.272364f,0.0137976f,-0.0520214f}, +{0.276025f,0.0169413f,-0.0454095f},{0.2795f,0.0199266f,-0.0386562f},{0.282788f,0.02275f,-0.0317747f}, +{0.285883f,0.0254083f,-0.0247786f},{0.291486f,0.0302204f,-0.0104982f},{0.29399f,0.0323711f,-0.00324118f}, +{0.296294f,0.0343506f,0.00407537f},{0.2984f,0.0361588f,0.0114378f},{0.300306f,0.0377963f,0.0188328f}, +{0.302015f,0.0392642f,0.0262471f},{0.303529f,0.0405642f,0.0336681f},{0.306924f,0.0434803f,0.0558492f}, +{0.309707f,0.0455472f,0.077605f},{0.308803f,0.0452653f,0.0918925f},{0.138651f,-0.100546f,-0.148277f}, +{0.138991f,-0.101078f,-0.146785f},{0.161185f,-0.0820158f,-0.143218f},{0.16127f,-0.081943f,-0.143822f}, +{0.166909f,-0.0771001f,-0.142325f},{0.166809f,-0.0771853f,-0.141725f},{0.172447f,-0.0723432f,-0.13998f}, +{0.178089f,-0.0674973f,-0.137981f},{0.183726f,-0.0626556f,-0.135723f},{0.189349f,-0.0578266f,-0.133204f}, +{0.194947f,-0.0530188f,-0.130423f},{0.200509f,-0.048241f,-0.127378f},{0.216885f,-0.0341764f,-0.116668f}, +{0.217113f,-0.0339808f,-0.117203f},{0.222445f,-0.0294008f,-0.113104f},{0.222204f,-0.0296081f,-0.112579f}, +{0.227436f,-0.0251146f,-0.108236f},{0.23257f,-0.0207049f,-0.103644f},{0.237597f,-0.0163874f,-0.0988083f}, +{0.242506f,-0.0121707f,-0.0937362f},{0.251936f,-0.00407176f,-0.0829128f},{0.256438f,-0.00020485f,-0.0771794f}, +{0.260788f,0.00353086f,-0.0712445f},{0.264977f,0.00712881f,-0.065119f},{0.268999f,0.010583f,-0.0588143f}, +{0.276515f,0.0170385f,-0.0457157f},{0.279998f,0.0200305f,-0.0389474f},{0.283293f,0.0228602f,-0.0320505f}, +{0.286395f,0.0255244f,-0.0250388f},{0.29452f,0.0325027f,-0.00345334f},{0.294947f,0.0328695f,-0.00369814f}, +{0.297263f,0.0348585f,0.00365355f},{0.29683f,0.0344866f,0.00387953f},{0.29894f,0.0362988f,0.0112584f}, +{0.30085f,0.03794f,0.0186698f},{0.302563f,0.0394112f,0.0261007f},{0.30408f,0.0407141f,0.0335382f}, +{0.305404f,0.0418509f,0.04097f},{0.306537f,0.0428241f,0.048384f},{0.307483f,0.0436367f,0.0557688f}, +{0.309243f,0.0451479f,0.0776416f},{0.309162f,0.0452855f,0.0918925f},{0.14452f,-0.0963291f,-0.146855f}, +{0.150068f,-0.0915645f,-0.146081f},{0.139019f,-0.101054f,-0.147398f},{0.155654f,-0.0867669f,-0.145073f}, +{0.172561f,-0.0722455f,-0.140576f},{0.178217f,-0.0673872f,-0.138571f},{0.183869f,-0.0625331f,-0.136307f}, +{0.183833f,-0.0622407f,-0.136814f},{0.189482f,-0.0573886f,-0.134283f},{0.189506f,-0.0576918f,-0.133782f}, +{0.195118f,-0.0528716f,-0.130993f},{0.200695f,-0.0480815f,-0.127941f},{0.206227f,-0.0433303f,-0.124624f}, +{0.211703f,-0.0386271f,-0.121044f},{0.22769f,-0.0248958f,-0.10875f},{0.227751f,-0.0245198f,-0.109195f}, +{0.23291f,-0.0200889f,-0.104581f},{0.232838f,-0.0204747f,-0.104146f},{0.237878f,-0.0161461f,-0.0992979f}, +{0.2428f,-0.0119186f,-0.0942128f},{0.256767f,7.79773e-005f,-0.0776135f},{0.256893f,0.000509374f,-0.0779897f}, +{0.261263f,0.00426299f,-0.0720263f},{0.261128f,0.00382328f,-0.0716633f},{0.265328f,0.00743047f,-0.0655221f}, +{0.26936f,0.0108935f,-0.0592012f},{0.280388f,0.0203653f,-0.0392833f},{0.280566f,0.0208417f,-0.0395744f}, +{0.283876f,0.023685f,-0.0326445f},{0.283691f,0.0232022f,-0.0323688f},{0.286801f,0.0258733f,-0.025339f}, +{0.289715f,0.028376f,-0.0182083f},{0.292431f,0.0307085f,-0.01099f},{0.299378f,0.0366754f,0.0110514f}, +{0.301294f,0.0383208f,0.0184819f},{0.301518f,0.038837f,0.0183189f},{0.303239f,0.0403153f,0.0257854f}, +{0.303011f,0.0397958f,0.0259318f},{0.304532f,0.041102f,0.0333884f},{0.305859f,0.0422417f,0.0408392f}, +{0.306995f,0.0432174f,0.0482723f},{0.307944f,0.0440321f,0.0556761f},{0.309951f,0.0457562f,0.0847878f}, +{0.30982f,0.0455988f,0.0918925f},{0.309511f,0.0453977f,0.0918925f},{0.144396f,-0.0961117f,-0.147384f}, +{0.149956f,-0.0913365f,-0.14661f},{0.138883f,-0.100847f,-0.147929f},{0.155555f,-0.0865282f,-0.145599f}, +{0.161183f,-0.0816937f,-0.144345f},{0.166835f,-0.07684f,-0.142845f},{0.172499f,-0.0719747f,-0.141092f}, +{0.178168f,-0.0671055f,-0.139082f},{0.195107f,-0.0525577f,-0.131488f},{0.200554f,-0.0473783f,-0.128748f}, +{0.200696f,-0.047757f,-0.128429f},{0.20624f,-0.0429952f,-0.125105f},{0.211728f,-0.0382816f,-0.121517f}, +{0.21715f,-0.033625f,-0.117667f},{0.222494f,-0.0290348f,-0.113559f},{0.237873f,-0.0153256f,-0.1f}, +{0.237961f,-0.0157507f,-0.0997223f},{0.242894f,-0.0115138f,-0.0946258f},{0.2477f,-0.00738628f,-0.0892991f}, +{0.252369f,-0.00337607f,-0.0837506f},{0.265424f,0.00833753f,-0.0661002f},{0.265472f,0.00787819f,-0.0658715f}, +{0.269513f,0.0113489f,-0.0595366f},{0.27338f,0.0146696f,-0.0530336f},{0.277066f,0.0178353f,-0.0463752f}, +{0.286976f,0.0268481f,-0.0257695f},{0.286993f,0.026362f,-0.0255992f},{0.289914f,0.0288702f,-0.0184526f}, +{0.292635f,0.0312079f,-0.0112184f},{0.295157f,0.0333737f,-0.00391029f},{0.297478f,0.0353671f,0.00345771f}, +{0.299598f,0.037188f,0.0108719f},{0.304763f,0.0416245f,0.0332586f},{0.306104f,0.0432766f,0.0406518f}, +{0.306093f,0.0427667f,0.0407259f},{0.307232f,0.0437445f,0.0481755f},{0.308183f,0.0445611f,0.0555957f}, +{0.30895f,0.0452198f,0.0629755f},{0.30995f,0.0460795f,0.0775733f},{0.310227f,0.0461927f,0.0918925f}, +{0.31006f,0.0458671f,0.0918925f},{0.127713f,-0.109819f,-0.148751f},{0.144173f,-0.0958031f,-0.147731f}, +{0.149741f,-0.091021f,-0.146955f},{0.155347f,-0.0862057f,-0.145943f},{0.160984f,-0.0813642f,-0.144688f}, +{0.166643f,-0.0765035f,-0.143185f},{0.172316f,-0.0716311f,-0.141429f},{0.177994f,-0.0667549f,-0.139417f}, +{0.183666f,-0.061883f,-0.137145f},{0.189324f,-0.0570238f,-0.134611f},{0.194956f,-0.052186f,-0.131812f}, +{0.205904f,-0.0422634f,-0.125571f},{0.210708f,-0.0376835f,-0.122344f},{0.211404f,-0.0375395f,-0.121975f}, +{0.206106f,-0.0426097f,-0.125419f},{0.211602f,-0.0378891f,-0.121826f},{0.217032f,-0.0332258f,-0.117971f}, +{0.222384f,-0.028629f,-0.113856f},{0.227648f,-0.0241074f,-0.109486f},{0.232815f,-0.0196701f,-0.104866f}, +{0.242813f,-0.0110826f,-0.0948962f},{0.242637f,-0.0107143f,-0.0950266f},{0.247626f,-0.00694907f,-0.0895618f}, +{0.252302f,-0.00293304f,-0.0840052f},{0.256832f,0.000958027f,-0.0782359f},{0.261209f,0.00471708f,-0.072264f}, +{0.269313f,0.0121976f,-0.059862f},{0.272494f,0.0153837f,-0.0542297f},{0.273188f,0.0155254f,-0.053345f}, +{0.269471f,0.0118133f,-0.059756f},{0.273343f,0.0151388f,-0.0532437f},{0.277034f,0.0183091f,-0.0465757f}, +{0.280539f,0.0213198f,-0.039765f},{0.283855f,0.0241672f,-0.0328251f},{0.289901f,0.02936f,-0.0186126f}, +{0.292484f,0.0320992f,-0.0114399f},{0.292626f,0.031701f,-0.0113678f},{0.295152f,0.03387f,-0.00404916f}, +{0.297476f,0.0358663f,0.00332952f},{0.299599f,0.0376898f,0.0107545f},{0.301522f,0.0393413f,0.0182123f}, +{0.303246f,0.0408217f,0.0256896f},{0.304772f,0.0421327f,0.0331736f},{0.307244f,0.0442558f,0.0481121f}, +{0.308196f,0.0450736f,0.0555431f},{0.308964f,0.0457333f,0.0629336f},{0.143927f,-0.095494f,-0.147899f}, +{0.149499f,-0.0907085f,-0.147122f},{0.155109f,-0.0858899f,-0.146109f},{0.16075f,-0.081045f,-0.144853f}, +{0.166413f,-0.0761809f,-0.143349f},{0.17209f,-0.0713051f,-0.141592f},{0.177772f,-0.0664255f,-0.139579f}, +{0.183448f,-0.0615502f,-0.137305f},{0.189109f,-0.0566876f,-0.134769f},{0.194746f,-0.0518464f,-0.131968f}, +{0.200348f,-0.0470353f,-0.128902f},{0.216837f,-0.032873f,-0.118117f},{0.222193f,-0.0282729f,-0.114f}, +{0.227461f,-0.0237482f,-0.109627f},{0.232631f,-0.0193078f,-0.105003f},{0.237693f,-0.0149603f,-0.100134f}, +{0.238141f,-0.0141219f,-0.0995149f},{0.247453f,-0.00657788f,-0.0896885f},{0.252132f,-0.00255905f,-0.0841281f}, +{0.256665f,0.00133474f,-0.0783547f},{0.261045f,0.00509642f,-0.0723786f},{0.265263f,0.00871939f,-0.0662105f}, +{0.276881f,0.0186979f,-0.0466724f},{0.280389f,0.0217108f,-0.039857f},{0.283707f,0.0245601f,-0.0329122f}, +{0.28683f,0.0272429f,-0.0258517f},{0.289757f,0.0297565f,-0.0186898f},{0.289812f,0.030258f,-0.0180672f}, +{0.295012f,0.0342697f,-0.00411618f},{0.297337f,0.0362674f,0.00326766f},{0.299462f,0.0380922f,0.0106978f}, +{0.301386f,0.0397448f,0.0181608f},{0.303111f,0.0412262f,0.0256434f},{0.304639f,0.0425382f,0.0331326f}, +{0.305971f,0.0436828f,0.040616f},{0.307112f,0.0446628f,0.0480815f},{0.308065f,0.0454811f,0.0555177f}, +{0.308834f,0.0461413f,0.0629134f},{0.309423f,0.0466471f,0.0702583f},{0.309837f,0.0470028f,0.0775425f}, +{0.143513f,-0.0953962f,-0.147965f},{0.148897f,-0.0907713f,-0.147226f},{0.154263f,-0.0861627f,-0.146277f}, +{0.159606f,-0.0815743f,-0.145118f},{0.164919f,-0.0770103f,-0.143752f},{0.1702f,-0.0724748f,-0.142179f}, +{0.175443f,-0.0679717f,-0.1404f},{0.180644f,-0.0635049f,-0.138417f},{0.185798f,-0.0590782f,-0.136232f}, +{0.1909f,-0.0546957f,-0.133846f},{0.195947f,-0.0503613f,-0.131262f},{0.200933f,-0.0460786f,-0.128482f}, +{0.205855f,-0.0418515f,-0.125509f},{0.215487f,-0.0335786f,-0.118992f},{0.220189f,-0.0295402f,-0.115454f}, +{0.224809f,-0.0255719f,-0.111734f},{0.229344f,-0.0216771f,-0.107835f},{0.233789f,-0.0178593f,-0.103761f}, +{0.242395f,-0.0104681f,-0.0951008f},{0.246548f,-0.00690116f,-0.0905224f},{0.250596f,-0.00342407f,-0.0857837f}, +{0.254536f,-4.00465e-005f,-0.080889f},{0.258365f,0.00324795f,-0.0758426f},{0.262078f,0.00643705f,-0.0706488f}, +{0.265672f,0.00952448f,-0.0653124f},{0.269146f,0.0125076f,-0.0598376f},{0.275715f,0.0181502f,-0.0484934f}, +{0.278806f,0.0208047f,-0.042634f},{0.281763f,0.0233449f,-0.0366563f},{0.284585f,0.0257686f,-0.0305656f}, +{0.287269f,0.0280737f,-0.0243674f},{0.292213f,0.0323197f,-0.0116704f},{0.294469f,0.0342571f,-0.00518257f}, +{0.296578f,0.0360684f,0.00139061f},{0.298538f,0.0377519f,0.00804317f},{0.300347f,0.0393062f,0.0147693f}, +{0.302005f,0.04073f,0.0215631f},{0.303509f,0.042022f,0.0284189f},{0.304859f,0.043181f,0.0353305f}, +{0.306052f,0.0442061f,0.0422916f},{0.307089f,0.0450964f,0.0492962f},{0.307967f,0.045851f,0.0563382f}, +{0.308687f,0.0464693f,0.0634117f},{0.309248f,0.0469508f,0.0705101f},{0.309649f,0.047295f,0.0776272f}, +{0.309889f,0.0475017f,0.0847567f},{-0.0493934f,-0.26108f,0.0428677f},{-0.0500586f,-0.262105f,0.0485758f}, +{-0.0489305f,-0.261136f,0.0411945f},{-0.0403941f,-0.253804f,0.00426646f},{-0.0400286f,-0.253036f,0.00244165f}, +{-0.041966f,-0.2547f,0.00901696f},{-0.0517606f,-0.263566f,0.0632405f},{-0.052343f,-0.264067f,0.0705025f}, +{-0.0516301f,-0.263974f,0.0632202f},{-0.0512863f,-0.262705f,0.0567511f},{-0.0519978f,-0.263316f,0.0637424f}, +{-0.0528812f,-0.26555f,0.084822f},{-0.0530084f,-0.265783f,0.0918925f},{-0.0531246f,-0.266082f,0.0848062f}, +{-0.0522285f,-0.264989f,0.0704561f},{-0.0516449f,-0.264488f,0.0631783f},{-0.0522129f,-0.264475f,0.0704874f}, +{-0.0535901f,-0.266482f,0.084788f},{-0.0540726f,-0.26669f,0.0918925f},{-0.0541535f,-0.266643f,0.0847723f}, +{-0.0524705f,-0.265521f,0.0704083f},{-0.0518855f,-0.265018f,0.0631143f},{-0.0550496f,-0.266391f,0.084757f}, +{-0.0548051f,-0.266181f,0.0775429f},{-0.0546651f,-0.266581f,0.084762f},{-0.0544319f,-0.26671f,0.0918925f}, +{-0.0553868f,-0.266227f,0.0918925f},{-0.0551112f,-0.266473f,0.0918925f},{-0.0550661f,-0.265952f,0.0776267f}, +{-0.0510006f,-0.262914f,0.0559281f},{-0.0504179f,-0.261959f,0.0497909f},{-0.0553066f,-0.266158f,0.0847564f}, +{-0.0468799f,-0.258921f,0.0291561f},{-0.0476128f,-0.260004f,0.0337954f},{-0.0461026f,-0.258707f,0.0263905f}, +{-0.0482137f,-0.260066f,0.0359874f},{-0.0443972f,-0.257242f,0.0189921f},{-0.0453931f,-0.257644f,0.0223799f}, +{-0.0424948f,-0.255608f,0.0116131f},{-0.0437546f,-0.256236f,0.015665f},{-0.0380944f,-0.251829f,-0.00303443f}, +{-0.0379442f,-0.251246f,-0.0040552f},{-0.0328989f,-0.247366f,-0.0174445f},{-0.0300052f,-0.244881f,-0.0245261f}, +{-0.0308284f,-0.245134f,-0.0230172f},{-0.0355958f,-0.249683f,-0.010276f},{-0.0224634f,-0.23795f,-0.0410717f}, +{-0.0253866f,-0.240461f,-0.0351634f},{-0.0236368f,-0.239411f,-0.0383731f},{-0.0281758f,-0.242856f,-0.0291434f}, +{-0.016225f,-0.232592f,-0.0525327f},{-0.0165165f,-0.233296f,-0.051709f},{-0.0126856f,-0.230006f,-0.0581524f}, +{-0.0201686f,-0.236433f,-0.0451116f},{-0.00592937f,-0.223749f,-0.0687612f},{-0.004511f,-0.222985f,-0.0705281f}, +{-0.00225941f,-0.220597f,-0.0738946f},{-0.00868167f,-0.226567f,-0.0644294f},{0.00942004f,-0.210566f,-0.088404f}, +{0.00541866f,-0.214002f,-0.0837203f},{0.00892832f,-0.211442f,-0.0876434f},{0.00152437f,-0.217347f,-0.0788824f}, +{0.00430185f,-0.215415f,-0.0821454f},{0.0220305f,-0.199735f,-0.101489f},{0.0185782f,-0.203154f,-0.0979716f}, +{0.0235832f,-0.198855f,-0.102786f},{0.0136901f,-0.207352f,-0.0929216f},{0.0339042f,-0.189991f,-0.111682f}, +{0.0354727f,-0.18819f,-0.113046f},{0.030906f,-0.192112f,-0.109369f},{0.026424f,-0.195961f,-0.105516f}, +{0.0496403f,-0.176021f,-0.122984f},{0.0448439f,-0.180141f,-0.119856f},{0.0500098f,-0.176158f,-0.123123f}, +{0.0392f,-0.185442f,-0.115753f},{0.055503f,-0.17144f,-0.126416f},{0.0594332f,-0.16761f,-0.12867f}, +{0.0545048f,-0.171843f,-0.125923f},{0.0722122f,-0.157088f,-0.134725f},{0.0694645f,-0.158995f,-0.133582f}, +{0.0666145f,-0.161896f,-0.132217f},{0.0644212f,-0.163326f,-0.131224f},{0.0610414f,-0.166683f,-0.129448f}, +{0.079699f,-0.150204f,-0.137702f},{0.0778246f,-0.152268f,-0.136973f},{0.083442f,-0.147443f,-0.138964f}, +{0.0745587f,-0.154619f,-0.135742f},{0.0901005f,-0.141271f,-0.141015f},{0.089055f,-0.142623f,-0.140701f}, +{0.0946547f,-0.137813f,-0.142188f},{0.0848811f,-0.145754f,-0.13946f},{0.100633f,-0.132225f,-0.143511f}, +{0.0953526f,-0.13676f,-0.142366f},{0.100232f,-0.133023f,-0.14343f},{0.111882f,-0.124362f,-0.146244f}, +{0.111758f,-0.124144f,-0.145714f},{0.106237f,-0.128886f,-0.144944f},{0.122163f,-0.114186f,-0.146058f}, +{0.116595f,-0.118515f,-0.145701f},{0.116752f,-0.118834f,-0.145739f},{0.121941f,-0.113924f,-0.146015f}, +{0.111289f,-0.123526f,-0.145199f},{0.10578f,-0.128258f,-0.144432f},{0.111534f,-0.123836f,-0.145367f}, +{0.111259f,-0.123099f,-0.145179f},{0.105936f,-0.12767f,-0.144449f},{0.0892849f,-0.142945f,-0.140865f}, +{0.095088f,-0.138462f,-0.142696f},{0.0948885f,-0.138132f,-0.142353f},{0.106348f,-0.129114f,-0.145472f}, +{0.106021f,-0.128571f,-0.144599f},{0.11184f,-0.124398f,-0.146855f},{0.117342f,-0.119672f,-0.147398f}, +{0.117369f,-0.119648f,-0.146786f},{0.111372f,-0.123975f,-0.147732f},{0.116894f,-0.119232f,-0.148277f}, +{0.111644f,-0.124242f,-0.147385f},{0.122619f,-0.114816f,-0.148251f},{0.122363f,-0.114535f,-0.148599f}, +{0.122103f,-0.114239f,-0.148767f},{0.121878f,-0.113978f,-0.14881f},{0.0780466f,-0.152598f,-0.137135f}, +{0.0286952f,-0.194464f,-0.107358f},{0.04012f,-0.184198f,-0.116543f},{0.0445719f,-0.180828f,-0.119568f}, +{0.0340952f,-0.190347f,-0.111826f},{0.0177295f,-0.203429f,-0.097292f},{0.0135248f,-0.20704f,-0.0929291f}, +{-0.000180634f,-0.219265f,-0.076437f},{-0.00948232f,-0.226801f,-0.0634867f},{0.00447193f,-0.215789f,-0.0822683f}, +{0.00453921f,-0.216232f,-0.0825229f},{0.00917572f,-0.21225f,-0.0880327f},{-0.0129153f,-0.229749f,-0.0580755f}, +{-0.0194086f,-0.235326f,-0.0468631f},{-0.0333422f,-0.247293f,-0.0167902f},{-0.0357148f,-0.249331f,-0.0104677f}, +{-0.0269169f,-0.242229f,-0.0315068f},{-0.0163243f,-0.234152f,-0.0520204f},{-0.0200158f,-0.236821f,-0.0452083f}, +{-0.0199843f,-0.237295f,-0.0454087f},{-0.0423578f,-0.256011f,0.0115564f},{-0.0525519f,-0.263792f,0.0707584f}, +{-0.0534149f,-0.266377f,0.0918925f},{-0.0529481f,-0.264133f,0.0777929f},{-0.0527525f,-0.264418f,0.0777045f}, +{-0.0528646f,-0.265035f,0.0848323f},{-0.0529317f,-0.265422f,0.0918925f},{-0.0531859f,-0.264337f,0.0848396f}, +{-0.0529943f,-0.264626f,0.0848373f},{-0.0530642f,-0.264714f,0.0918925f},{-0.0529519f,-0.265063f,0.0918925f}, +{-0.0532653f,-0.264405f,0.0918925f},{-0.0531751f,-0.266108f,0.0918925f},{-0.0537244f,-0.266578f,0.0918925f}, +{-0.0526227f,-0.264827f,0.0776945f},{-0.0508696f,-0.263321f,0.0559028f},{-0.0499269f,-0.262512f,0.0485453f}, +{-0.048798f,-0.261542f,0.0411587f},{-0.0474794f,-0.260409f,0.0337544f},{-0.0459681f,-0.259111f,0.0263442f}, +{-0.0442615f,-0.257646f,0.0189407f},{-0.0402537f,-0.254704f,0.00407642f},{-0.037949f,-0.252725f,-0.00324031f}, +{-0.0402556f,-0.254205f,0.00420461f},{-0.0379543f,-0.252228f,-0.00310144f},{-0.0354539f,-0.250081f,-0.0103481f}, +{-0.0327551f,-0.247763f,-0.0175217f},{-0.0298594f,-0.245276f,-0.0246083f},{-0.0267689f,-0.242622f,-0.0315939f}, +{-0.0234865f,-0.239802f,-0.038465f},{-0.0163611f,-0.233683f,-0.0518103f},{-0.0125275f,-0.23039f,-0.0582583f}, +{-0.00852075f,-0.226949f,-0.0645398f},{-0.00434714f,-0.223364f,-0.0706427f},{-1.37117e-005f,-0.219642f,-0.0765558f}, +{0.00910166f,-0.211813f,-0.0877701f},{0.0138668f,-0.20772f,-0.093052f},{0.0187584f,-0.203519f,-0.0981056f}, +{0.0237669f,-0.199217f,-0.102923f},{0.0288825f,-0.194824f,-0.107499f},{0.050333f,-0.177225f,-0.12407f}, +{0.0448966f,-0.18157f,-0.120026f},{0.0448712f,-0.181916f,-0.120499f},{0.0393947f,-0.185795f,-0.1159f}, +{0.0447704f,-0.181178f,-0.119717f},{0.0502121f,-0.176504f,-0.123274f},{0.0557093f,-0.171783f,-0.126571f}, +{0.0612515f,-0.167022f,-0.129604f},{0.0668286f,-0.162232f,-0.132375f},{0.0724302f,-0.157421f,-0.134885f}, +{0.0836679f,-0.147769f,-0.139127f},{0.0894762f,-0.143282f,-0.141206f},{0.10047f,-0.133338f,-0.143596f}, +{0.117002f,-0.11914f,-0.145907f},{0.122417f,-0.114489f,-0.146226f},{-0.0544208f,-0.266371f,0.0775529f}, +{-0.0526389f,-0.265342f,0.0776737f},{-0.0508832f,-0.263834f,0.0558501f},{-0.0499391f,-0.263023f,0.0484819f}, +{-0.0488086f,-0.262052f,0.0410845f},{-0.0474881f,-0.260918f,0.0336694f},{-0.0459745f,-0.259618f,0.0262484f}, +{-0.0442655f,-0.25815f,0.018834f},{-0.0423589f,-0.256512f,0.011439f},{-0.035445f,-0.250574f,-0.0104976f}, +{-0.0356495f,-0.251073f,-0.0107259f},{-0.0329408f,-0.248747f,-0.017926f},{-0.0327422f,-0.248253f,-0.0176816f}, +{-0.0298423f,-0.245762f,-0.0247786f},{-0.0267473f,-0.243104f,-0.0317744f},{-0.02346f,-0.24028f,-0.0386556f}, +{-0.00861687f,-0.227856f,-0.0651178f},{-0.00896809f,-0.228157f,-0.065521f},{-0.0047683f,-0.22455f,-0.0716622f}, +{-0.0124851f,-0.230854f,-0.0584778f},{-0.00847247f,-0.227408f,-0.0647685f},{-0.00429275f,-0.223818f,-0.0708804f}, +{4.70058e-005f,-0.220091f,-0.0768021f},{0.0187631f,-0.20434f,-0.0988077f},{0.0184822f,-0.204581f,-0.0992973f}, +{0.0235221f,-0.200252f,-0.104145f},{0.0139479f,-0.208152f,-0.0933224f},{0.0188466f,-0.203944f,-0.0983834f}, +{0.0238624f,-0.199636f,-0.103208f},{0.0289854f,-0.195236f,-0.10779f},{0.0342058f,-0.190752f,-0.112123f}, +{0.0395131f,-0.186194f,-0.116203f},{0.0503463f,-0.17689f,-0.123589f},{0.0558515f,-0.172161f,-0.12689f}, +{0.0614018f,-0.167394f,-0.129928f},{0.066987f,-0.162597f,-0.132703f},{0.0725969f,-0.157779f,-0.135216f}, +{0.0782214f,-0.152948f,-0.137469f},{0.083851f,-0.148113f,-0.139465f},{0.100678f,-0.133661f,-0.14394f}, +{0.122791f,-0.114992f,-0.147719f},{0.117234f,-0.119441f,-0.146255f},{0.122656f,-0.114784f,-0.146574f}, +{-0.0511222f,-0.264363f,0.0557698f},{-0.0528818f,-0.265874f,0.077642f},{-0.050176f,-0.26355f,0.0483851f}, +{-0.0506339f,-0.263943f,0.0482734f},{-0.049498f,-0.262968f,0.0408405f},{-0.0490429f,-0.262577f,0.0409712f}, +{-0.0477195f,-0.26144f,0.0335395f},{-0.0462026f,-0.260137f,0.026102f},{-0.0444897f,-0.258666f,0.0186711f}, +{-0.0425789f,-0.257025f,0.0112596f},{-0.040469f,-0.255213f,0.00388058f},{-0.0381592f,-0.253229f,-0.00345247f}, +{-0.0300343f,-0.246251f,-0.0250388f},{-0.0304405f,-0.2466f,-0.025339f},{-0.0273306f,-0.243929f,-0.0323684f}, +{-0.0269324f,-0.243587f,-0.0320502f},{-0.0236379f,-0.240757f,-0.0389468f},{-0.0201544f,-0.237765f,-0.0457149f}, +{-0.0164862f,-0.234614f,-0.0523413f},{-0.0126385f,-0.23131f,-0.0588132f},{-0.00442784f,-0.224258f,-0.0712434f}, +{-7.83923e-005f,-0.220522f,-0.0771783f},{0.00442383f,-0.216655f,-0.0829118f},{0.00907067f,-0.212664f,-0.088434f}, +{0.0138535f,-0.208556f,-0.0937354f},{0.0237901f,-0.200022f,-0.103643f},{0.0289246f,-0.195612f,-0.108235f}, +{0.0341565f,-0.191118f,-0.112578f},{0.0394757f,-0.18655f,-0.116668f},{0.0558505f,-0.172486f,-0.127378f}, +{0.0556648f,-0.172645f,-0.127941f},{0.0612418f,-0.167855f,-0.130993f},{0.0614133f,-0.167708f,-0.130423f}, +{0.0670109f,-0.1629f,-0.133204f},{0.0726333f,-0.158071f,-0.135723f},{0.0782704f,-0.15323f,-0.137981f}, +{0.0839125f,-0.148384f,-0.139981f},{0.0895502f,-0.143542f,-0.141725f},{0.0951746f,-0.138711f,-0.143219f}, +{0.100777f,-0.1339f,-0.144466f},{0.122804f,-0.11498f,-0.147106f},{-0.0529343f,-0.265919f,0.0703531f}, +{-0.0523479f,-0.265415f,0.0630404f},{-0.0533467f,-0.266273f,0.0776054f},{-0.0515825f,-0.264758f,0.055677f}, +{-0.0481711f,-0.261828f,0.0333897f},{-0.0466503f,-0.260522f,0.0259331f},{-0.044933f,-0.259047f,0.0184831f}, +{-0.0454772f,-0.259191f,0.0183202f},{-0.0435573f,-0.257542f,0.0108731f},{-0.0430173f,-0.257402f,0.0110526f}, +{-0.040902f,-0.255585f,0.00365461f},{-0.0385862f,-0.253596f,-0.00369726f},{-0.0360702f,-0.251435f,-0.0109894f}, +{-0.0333545f,-0.249102f,-0.0182079f},{-0.0240277f,-0.241092f,-0.0392827f},{-0.0245255f,-0.241196f,-0.0395738f}, +{-0.0210253f,-0.238189f,-0.0463744f},{-0.0205352f,-0.238092f,-0.0460682f},{-0.0168576f,-0.234933f,-0.0527117f}, +{-0.013f,-0.23162f,-0.0592001f},{-0.00040769f,-0.220805f,-0.0776124f},{-0.000853084f,-0.220864f,-0.0779886f}, +{0.00367072f,-0.216978f,-0.0837496f},{0.00410608f,-0.216928f,-0.0833607f},{0.00876485f,-0.212927f,-0.088897f}, +{0.0135599f,-0.208808f,-0.094212f},{0.0286697f,-0.195831f,-0.108749f},{0.0282889f,-0.195834f,-0.109195f}, +{0.0335459f,-0.191319f,-0.113558f},{0.0339151f,-0.191326f,-0.113103f},{0.0392479f,-0.186745f,-0.117203f}, +{0.0446573f,-0.182099f,-0.121044f},{0.0501331f,-0.177396f,-0.124624f},{0.0668538f,-0.163035f,-0.133782f}, +{0.0724906f,-0.158194f,-0.136307f},{0.072207f,-0.158114f,-0.136814f},{0.0778712f,-0.153249f,-0.139083f}, +{0.0781422f,-0.15334f,-0.138571f},{0.0837988f,-0.148482f,-0.140576f},{0.0894511f,-0.143627f,-0.142325f}, +{0.0950898f,-0.138784f,-0.143823f},{0.100706f,-0.13396f,-0.145073f},{0.106292f,-0.129162f,-0.146082f}, +{-0.0534963f,-0.266078f,0.0703053f},{-0.0529085f,-0.265573f,0.0629764f},{-0.0539095f,-0.266433f,0.0775737f}, +{-0.0521415f,-0.264914f,0.0555966f},{-0.0511908f,-0.264098f,0.0481766f},{-0.0500523f,-0.26312f,0.0407271f}, +{-0.0487225f,-0.261978f,0.0332599f},{-0.0471983f,-0.260669f,0.0257867f},{-0.0414372f,-0.255721f,0.00345877f}, +{-0.0396062f,-0.253647f,-0.00404829f},{-0.0391164f,-0.253727f,-0.00390942f},{-0.0365947f,-0.251562f,-0.0112177f}, +{-0.033873f,-0.249224f,-0.0184523f},{-0.0309526f,-0.246716f,-0.0255992f},{-0.0278358f,-0.244039f,-0.0326442f}, +{-0.0177978f,-0.234916f,-0.0532427f},{-0.0173395f,-0.235024f,-0.0530326f},{-0.0134733f,-0.231703f,-0.0595354f}, +{-0.00943248f,-0.228232f,-0.0658703f},{-0.00522337f,-0.224617f,-0.0720252f},{0.0079188f,-0.212829f,-0.0895609f}, +{0.00833983f,-0.212968f,-0.0892982f},{0.0131455f,-0.208841f,-0.0946251f},{0.0180787f,-0.204604f,-0.0997217f}, +{0.0231298f,-0.200265f,-0.10458f},{0.0385138f,-0.186551f,-0.117971f},{0.0388905f,-0.186729f,-0.117667f}, +{0.044312f,-0.182072f,-0.121517f},{0.0497999f,-0.177359f,-0.125105f},{0.0553439f,-0.172597f,-0.128429f}, +{0.0609333f,-0.167797f,-0.131488f},{0.0665577f,-0.162966f,-0.134283f},{0.0835403f,-0.14838f,-0.141092f}, +{0.0889013f,-0.143275f,-0.143185f},{0.0892051f,-0.143514f,-0.142845f},{0.0948564f,-0.138661f,-0.144346f}, +{0.100485f,-0.133826f,-0.145599f},{0.106084f,-0.129018f,-0.14661f},{0.117158f,-0.119507f,-0.147929f}, +{-0.0547929f,-0.266634f,0.0918925f},{-0.0540069f,-0.266016f,0.070274f},{-0.0534183f,-0.26551f,0.0629344f}, +{-0.0526502f,-0.264851f,0.055544f},{-0.0516981f,-0.264033f,0.0481132f},{-0.050558f,-0.263054f,0.040653f}, +{-0.0492262f,-0.26191f,0.0331749f},{-0.0476998f,-0.260599f,0.0256909f},{-0.0459762f,-0.259118f,0.0182135f}, +{-0.0440535f,-0.257467f,0.0107557f},{-0.0419304f,-0.255643f,0.00333058f},{-0.037453f,-0.251278f,-0.0114393f}, +{-0.0352296f,-0.248914f,-0.0180677f},{-0.0347255f,-0.248935f,-0.0186894f},{-0.0370809f,-0.251478f,-0.0113672f}, +{-0.0343552f,-0.249137f,-0.0186123f},{-0.0314306f,-0.246625f,-0.0257695f},{-0.0283092f,-0.243945f,-0.0328247f}, +{-0.0249941f,-0.241097f,-0.0397644f},{-0.0214889f,-0.238087f,-0.0465748f},{-0.013926f,-0.231591f,-0.0597549f}, +{-0.014282f,-0.231377f,-0.0598609f},{-0.00987926f,-0.228115f,-0.066099f},{-0.00566404f,-0.224495f,-0.0722628f}, +{-0.00128743f,-0.220736f,-0.0782348f},{0.00324293f,-0.216845f,-0.0840042f},{0.0123941f,-0.208465f,-0.0950259f}, +{0.0164425f,-0.204534f,-0.0995152f},{0.0173378f,-0.204219f,-0.100133f},{0.0127315f,-0.208695f,-0.0948954f}, +{0.0176718f,-0.204452f,-0.0999994f},{0.0227302f,-0.200108f,-0.104865f},{0.0278968f,-0.19567f,-0.109486f}, +{0.0331614f,-0.191149f,-0.113856f},{0.0439431f,-0.181888f,-0.121826f},{0.0491273f,-0.176916f,-0.125571f}, +{0.049439f,-0.177168f,-0.125419f},{0.054991f,-0.1724f,-0.128748f},{0.0605885f,-0.167592f,-0.131812f}, +{0.0662211f,-0.162754f,-0.134611f},{0.0718786f,-0.157895f,-0.137145f},{0.0775509f,-0.153023f,-0.139417f}, +{0.0832283f,-0.148147f,-0.14143f},{0.0945608f,-0.138414f,-0.144688f},{0.100198f,-0.133572f,-0.145943f}, +{0.105804f,-0.128757f,-0.146956f},{-0.0543909f,-0.265826f,0.0702589f},{-0.0538019f,-0.26532f,0.0629142f}, +{-0.0530333f,-0.264659f,0.0555186f},{-0.0520805f,-0.263841f,0.0480826f},{-0.0509396f,-0.262861f,0.0406172f}, +{-0.0496069f,-0.261717f,0.0331338f},{-0.0480794f,-0.260405f,0.0256447f},{-0.0463547f,-0.258923f,0.0181621f}, +{-0.0444306f,-0.257271f,0.010699f},{-0.042306f,-0.255446f,0.00326873f},{-0.0399801f,-0.253448f,-0.0041153f}, +{-0.0317988f,-0.246422f,-0.0258517f},{-0.0286753f,-0.243739f,-0.0329118f},{-0.0253579f,-0.24089f,-0.0398563f}, +{-0.0218502f,-0.237877f,-0.0466715f},{-0.0181565f,-0.234704f,-0.0533441f},{-0.0179111f,-0.23404f,-0.0542301f}, +{-0.0102325f,-0.227899f,-0.0662094f},{-0.0060143f,-0.224276f,-0.0723775f},{-0.00163463f,-0.220514f,-0.0783537f}, +{0.0028989f,-0.21662f,-0.0841271f},{0.00757805f,-0.212602f,-0.0896876f},{0.0223998f,-0.199871f,-0.105003f}, +{0.02757f,-0.195431f,-0.109627f},{0.0328383f,-0.190906f,-0.114f},{0.0381944f,-0.186306f,-0.118117f}, +{0.0436275f,-0.181639f,-0.121975f},{0.0438755f,-0.180973f,-0.122344f},{0.0546831f,-0.172144f,-0.128902f}, +{0.0602845f,-0.167333f,-0.131968f},{0.0659211f,-0.162492f,-0.134769f},{0.0715825f,-0.157629f,-0.137305f}, +{0.0772588f,-0.152754f,-0.139579f},{0.0829402f,-0.147874f,-0.141593f},{0.0886171f,-0.142999f,-0.143349f}, +{0.0942805f,-0.138134f,-0.144853f},{0.0999216f,-0.133289f,-0.146109f},{0.105532f,-0.128471f,-0.147123f}, +{0.111104f,-0.123685f,-0.147899f},{0.11663f,-0.118939f,-0.148445f},{-0.0546653f,-0.265607f,0.0705096f}, +{-0.0541047f,-0.265126f,0.0634113f},{-0.0533848f,-0.264508f,0.056338f},{-0.0525062f,-0.263753f,0.0492957f}, +{-0.0514696f,-0.262863f,0.042291f},{-0.0502761f,-0.261838f,0.0353299f},{-0.0489266f,-0.260679f,0.0284186f}, +{-0.0474223f,-0.259387f,0.0215629f},{-0.0457645f,-0.257963f,0.0147688f},{-0.0439548f,-0.256408f,0.00804257f}, +{-0.0419946f,-0.254725f,0.00139006f},{-0.0398858f,-0.252914f,-0.00518291f},{-0.0376301f,-0.250976f,-0.0116708f}, +{-0.0326863f,-0.24673f,-0.024368f},{-0.0300025f,-0.244425f,-0.0305661f},{-0.0271806f,-0.242001f,-0.0366566f}, +{-0.0242229f,-0.239461f,-0.0426344f},{-0.0211322f,-0.236806f,-0.0484939f},{-0.0145625f,-0.231164f,-0.0598379f}, +{-0.0110894f,-0.228181f,-0.0653124f},{-0.00749453f,-0.225093f,-0.0706491f},{-0.00378138f,-0.221904f,-0.0758429f}, +{4.68637e-005f,-0.218616f,-0.0808893f},{0.00398685f,-0.215232f,-0.0857839f},{0.00803512f,-0.211755f,-0.0905225f}, +{0.0121883f,-0.208188f,-0.095101f},{0.020794f,-0.200797f,-0.103761f},{0.025239f,-0.196979f,-0.107835f}, +{0.0297737f,-0.193084f,-0.111734f},{0.0343942f,-0.189116f,-0.115454f},{0.0390962f,-0.185078f,-0.118992f}, +{0.0487282f,-0.176805f,-0.125509f},{0.0536499f,-0.172578f,-0.128482f},{0.0586363f,-0.168295f,-0.131262f}, +{0.063683f,-0.16396f,-0.133846f},{0.0687854f,-0.159578f,-0.136231f},{0.0739393f,-0.155151f,-0.138417f}, +{0.0791401f,-0.150685f,-0.1404f},{0.0843832f,-0.146181f,-0.142179f},{0.089664f,-0.141646f,-0.143752f}, +{0.0949777f,-0.137082f,-0.145118f},{0.10032f,-0.132494f,-0.146276f},{0.105686f,-0.127885f,-0.147225f}, +{0.111071f,-0.12326f,-0.147964f},{0.11647f,-0.118623f,-0.148493f},{-0.0258064f,-0.240367f,-0.0398563f}, +{-0.0222987f,-0.237355f,-0.0466715f},{-0.0147777f,-0.22955f,-0.0592001f},{-0.0108902f,-0.226535f,-0.0658703f}, +{-0.0149311f,-0.230006f,-0.0595354f},{-0.0322473f,-0.245899f,-0.0258517f},{-0.0291238f,-0.243217f,-0.0329118f}, +{-0.0379016f,-0.250756f,-0.0114393f},{-0.035174f,-0.248413f,-0.0186894f},{-0.0404286f,-0.252926f,-0.0041153f}, +{-0.0427545f,-0.254924f,0.00326873f},{-0.0448791f,-0.256749f,0.010699f},{-0.0380524f,-0.249864f,-0.0112177f}, +{-0.0380435f,-0.250358f,-0.0113672f},{-0.0405741f,-0.25203f,-0.00390942f},{-0.0468032f,-0.258401f,0.0181621f}, +{-0.048528f,-0.259882f,0.0256447f},{-0.0500554f,-0.261194f,0.0331338f},{-0.0513881f,-0.262339f,0.0406172f}, +{-0.052529f,-0.263319f,0.0480826f},{-0.0534818f,-0.264137f,0.0555186f},{-0.0542505f,-0.264797f,0.0629142f}, +{-0.0548395f,-0.265303f,0.0702589f},{-0.0549696f,-0.264895f,0.070274f},{-0.054381f,-0.264389f,0.0629344f}, +{-0.0534428f,-0.264104f,0.0848373f},{-0.0538273f,-0.263914f,0.0848323f},{-0.0543389f,-0.263852f,0.084822f}, +{-0.0542202f,-0.263922f,0.0918925f},{-0.0535408f,-0.26416f,0.0918925f},{-0.053201f,-0.263896f,0.0777045f}, +{-0.0527915f,-0.263544f,0.0705025f},{-0.0531755f,-0.263354f,0.0704874f},{-0.054954f,-0.264381f,0.0703053f}, +{-0.0543662f,-0.263876f,0.0629764f},{-0.0541256f,-0.263346f,0.0630404f},{-0.0535992f,-0.263217f,0.0555966f}, +{-0.054712f,-0.263849f,0.0703531f},{-0.0552536f,-0.265659f,0.0775429f},{-0.0557203f,-0.26521f,0.0918925f}, +{-0.0556112f,-0.264945f,0.0847723f},{-0.0556278f,-0.26546f,0.084762f},{-0.0556436f,-0.264849f,0.0918925f}, +{-0.0553678f,-0.264412f,0.084788f},{-0.0554769f,-0.264524f,0.0918925f},{-0.0557001f,-0.26557f,0.0918925f}, +{-0.0554981f,-0.265869f,0.084757f},{-0.0555879f,-0.265918f,0.0918925f},{-0.0549023f,-0.264013f,0.0848062f}, +{-0.0545795f,-0.263942f,0.0918925f},{-0.018605f,-0.234182f,-0.0533441f},{-0.0147305f,-0.230855f,-0.0598609f}, +{-0.010681f,-0.227376f,-0.0662094f},{-0.00646282f,-0.223754f,-0.0723775f},{-0.00208315f,-0.219992f,-0.0783537f}, +{0.00245038f,-0.216098f,-0.0841271f},{0.0117689f,-0.207575f,-0.0948954f},{0.00688212f,-0.211271f,-0.0892982f}, +{0.0116878f,-0.207143f,-0.0946251f},{0.00712952f,-0.212079f,-0.0896876f},{0.0119456f,-0.207943f,-0.0950259f}, +{0.0168893f,-0.203697f,-0.100133f},{0.0219512f,-0.199349f,-0.105003f},{0.0271214f,-0.194909f,-0.109627f}, +{0.0323898f,-0.190384f,-0.114f},{0.0377459f,-0.185784f,-0.118117f},{0.0483422f,-0.175662f,-0.125105f}, +{0.0483555f,-0.175327f,-0.124624f},{0.0538862f,-0.1709f,-0.128429f},{0.043179f,-0.181117f,-0.121975f}, +{0.0486787f,-0.176393f,-0.125571f},{0.0542346f,-0.171622f,-0.128902f},{0.059836f,-0.166811f,-0.131968f}, +{0.0654725f,-0.16197f,-0.134769f},{0.071134f,-0.157107f,-0.137305f},{0.0768103f,-0.152232f,-0.139579f}, +{0.0824916f,-0.147352f,-0.141593f},{0.0879387f,-0.142154f,-0.143185f},{0.0881686f,-0.142476f,-0.143349f}, +{0.0822657f,-0.147026f,-0.14143f},{0.093832f,-0.137612f,-0.144853f},{0.105084f,-0.127948f,-0.147123f}, +{0.0992353f,-0.132451f,-0.145943f},{0.104842f,-0.127636f,-0.146956f},{0.110062f,-0.122328f,-0.146855f}, +{0.110104f,-0.122292f,-0.146244f},{0.115564f,-0.117602f,-0.147398f},{0.0933121f,-0.136714f,-0.143823f}, +{0.0989286f,-0.13189f,-0.145073f},{0.0990277f,-0.132129f,-0.145599f},{0.110572f,-0.122715f,-0.145367f}, +{0.1103f,-0.122447f,-0.145714f},{0.105059f,-0.12745f,-0.144599f},{0.121454f,-0.113368f,-0.146226f}, +{0.126687f,-0.108624f,-0.146474f},{0.121199f,-0.113087f,-0.146574f},{0.1157f,-0.117809f,-0.147929f}, +{0.110186f,-0.122545f,-0.147385f},{0.126873f,-0.108841f,-0.146297f},{0.121715f,-0.113664f,-0.146058f}, +{0.127073f,-0.109073f,-0.146158f},{0.104626f,-0.12732f,-0.14661f},{0.104515f,-0.127092f,-0.146082f}, +{0.115932f,-0.118111f,-0.148277f},{0.11041f,-0.122854f,-0.147732f},{0.0994731f,-0.132767f,-0.146109f}, +{0.110655f,-0.123163f,-0.147899f},{0.116181f,-0.118417f,-0.148445f},{0.121654f,-0.113716f,-0.148767f}, +{0.127073f,-0.109074f,-0.148876f},{-0.0549276f,-0.264054f,0.0918925f},{-0.0553834f,-0.26525f,0.0775529f}, +{-0.0536128f,-0.26373f,0.055544f},{-0.0526607f,-0.262912f,0.0481132f},{-0.0515206f,-0.261933f,0.040653f}, +{-0.0501889f,-0.260789f,0.0331749f},{-0.0486625f,-0.259478f,0.0256909f},{-0.0469389f,-0.257998f,0.0182135f}, +{-0.0450162f,-0.256346f,0.0107557f},{-0.042893f,-0.254523f,0.00333058f},{-0.0405688f,-0.252526f,-0.00404829f}, +{-0.0353178f,-0.248016f,-0.0186123f},{-0.0323932f,-0.245505f,-0.0257695f},{-0.0292719f,-0.242824f,-0.0328247f}, +{-0.0259568f,-0.239976f,-0.0397644f},{-0.0224515f,-0.236966f,-0.0465748f},{-0.0187604f,-0.233796f,-0.0532427f}, +{-0.0148886f,-0.23047f,-0.0597549f},{-0.0108419f,-0.226995f,-0.066099f},{-0.00662668f,-0.223374f,-0.0722628f}, +{-0.00225007f,-0.219615f,-0.0782348f},{0.00228029f,-0.215724f,-0.0840042f},{0.00695617f,-0.211708f,-0.0895609f}, +{0.0167092f,-0.203331f,-0.0999994f},{0.0217676f,-0.198987f,-0.104865f},{0.0269342f,-0.194549f,-0.109486f}, +{0.0321988f,-0.190028f,-0.113856f},{0.0375512f,-0.185431f,-0.117971f},{0.0429805f,-0.180768f,-0.121826f}, +{0.0484764f,-0.176047f,-0.125419f},{0.0540283f,-0.171279f,-0.128748f},{0.0596258f,-0.166471f,-0.131812f}, +{0.0652585f,-0.161633f,-0.134611f},{0.070916f,-0.156774f,-0.137145f},{0.0765883f,-0.151902f,-0.139417f}, +{0.0935981f,-0.137293f,-0.144688f},{0.0933987f,-0.136964f,-0.144346f},{0.121401f,-0.113414f,-0.148599f}, +{0.12687f,-0.108837f,-0.148751f},{-0.0553672f,-0.264736f,0.0775737f},{-0.0526485f,-0.262401f,0.0481766f}, +{-0.05151f,-0.261423f,0.0407271f},{-0.0501802f,-0.260281f,0.0332599f},{-0.048656f,-0.258972f,0.0257867f}, +{-0.0469349f,-0.257493f,0.0183202f},{-0.045015f,-0.255844f,0.0108731f},{-0.0428949f,-0.254024f,0.00345877f}, +{-0.0324103f,-0.245018f,-0.0255992f},{-0.0353307f,-0.247527f,-0.0184523f},{-0.0351321f,-0.247032f,-0.0182079f}, +{-0.0292935f,-0.242341f,-0.0326442f},{-0.0259832f,-0.239498f,-0.0395738f},{-0.022483f,-0.236492f,-0.0463744f}, +{-0.0187972f,-0.233326f,-0.0530326f},{-0.00668107f,-0.22292f,-0.0720252f},{-0.00231079f,-0.219167f,-0.0779886f}, +{0.00221301f,-0.215281f,-0.0837496f},{0.0217444f,-0.198182f,-0.104145f},{0.0220124f,-0.197952f,-0.103643f}, +{0.0268921f,-0.193761f,-0.108749f},{0.016621f,-0.202906f,-0.0997217f},{0.0216721f,-0.198568f,-0.10458f}, +{0.0268312f,-0.194137f,-0.109195f},{0.0320882f,-0.189622f,-0.113558f},{0.0374328f,-0.185032f,-0.117667f}, +{0.0428543f,-0.180375f,-0.121517f},{0.0594756f,-0.166099f,-0.131488f},{0.0651f,-0.161269f,-0.134283f}, +{0.0707493f,-0.156417f,-0.136814f},{0.0764135f,-0.151552f,-0.139083f},{0.0820826f,-0.146683f,-0.141092f}, +{0.0877474f,-0.141817f,-0.142845f},{0.126387f,-0.108276f,-0.147687f},{0.121013f,-0.112922f,-0.147719f}, +{0.121027f,-0.112911f,-0.147106f},{0.121161f,-0.113119f,-0.148251f},{0.12669f,-0.108628f,-0.148558f}, +{-0.0552371f,-0.264255f,0.0918925f},{-0.0551243f,-0.264203f,0.0776054f},{-0.0533602f,-0.262688f,0.055677f}, +{-0.0524116f,-0.261874f,0.0482734f},{-0.0494972f,-0.25937f,0.0335395f},{-0.048428f,-0.258452f,0.0259331f}, +{-0.0499488f,-0.259758f,0.0333897f},{-0.0512756f,-0.260898f,0.0408405f},{-0.0467107f,-0.256977f,0.0184831f}, +{-0.044795f,-0.255332f,0.0110526f},{-0.0426797f,-0.253515f,0.00365461f},{-0.0403639f,-0.251526f,-0.00369726f}, +{-0.0378479f,-0.249365f,-0.0109894f},{-0.0287101f,-0.241517f,-0.0320502f},{-0.0258054f,-0.239022f,-0.0392827f}, +{-0.0291083f,-0.241859f,-0.0323684f},{-0.0322182f,-0.24453f,-0.025339f},{-0.0223129f,-0.236022f,-0.0460682f}, +{-0.0186353f,-0.232864f,-0.0527117f},{-0.00620553f,-0.222188f,-0.0712434f},{-0.00218538f,-0.218735f,-0.0776124f}, +{-0.006546f,-0.22248f,-0.0716622f},{-0.0107458f,-0.226088f,-0.065521f},{0.00232839f,-0.214858f,-0.0833607f}, +{0.00698716f,-0.210857f,-0.088897f},{0.0117822f,-0.206739f,-0.094212f},{0.0167045f,-0.202511f,-0.0992973f}, +{0.0321374f,-0.189256f,-0.113103f},{0.0374702f,-0.184676f,-0.117203f},{0.0428796f,-0.18003f,-0.121044f}, +{0.0596356f,-0.165638f,-0.130423f},{0.0650762f,-0.160965f,-0.133782f},{0.0594641f,-0.165786f,-0.130993f}, +{0.0538871f,-0.170576f,-0.127941f},{0.0707129f,-0.156124f,-0.136307f},{0.0763645f,-0.15127f,-0.138571f}, +{0.0820211f,-0.146412f,-0.140576f},{0.0876734f,-0.141557f,-0.142325f},{0.115776f,-0.117744f,-0.146255f}, +{0.104571f,-0.127044f,-0.145472f},{0.12644f,-0.108337f,-0.148015f},{0.126544f,-0.108458f,-0.14831f}, +{-0.0542482f,-0.263451f,0.0704083f},{-0.0546595f,-0.263804f,0.077642f},{-0.0536632f,-0.262949f,0.0631143f}, +{-0.0528999f,-0.262293f,0.0557698f},{-0.0519537f,-0.26148f,0.0483851f},{-0.0508206f,-0.260507f,0.0409712f}, +{-0.0479802f,-0.258067f,0.026102f},{-0.0422467f,-0.253143f,0.00388058f},{-0.0443566f,-0.254955f,0.0112596f}, +{-0.0438167f,-0.254815f,0.011439f},{-0.0462674f,-0.256596f,0.0186711f},{-0.0399369f,-0.251159f,-0.00345247f}, +{-0.0374272f,-0.249004f,-0.0107259f},{-0.0347185f,-0.246677f,-0.017926f},{-0.031812f,-0.244181f,-0.0250388f}, +{-0.0173238f,-0.232562f,-0.0518103f},{-0.017782f,-0.232454f,-0.0520204f},{-0.0209784f,-0.235701f,-0.0452083f}, +{-0.0254156f,-0.238687f,-0.0389468f},{-0.0219321f,-0.235695f,-0.0457149f},{-0.0182639f,-0.232545f,-0.0523413f}, +{-0.0144162f,-0.22924f,-0.0588132f},{-0.0103946f,-0.225786f,-0.0651178f},{0.00813902f,-0.210692f,-0.0877701f}, +{0.00771801f,-0.210553f,-0.0880327f},{0.00350929f,-0.214669f,-0.0822683f},{-0.00185609f,-0.218452f,-0.0771783f}, +{0.00264613f,-0.214585f,-0.0829118f},{0.00729298f,-0.210594f,-0.088434f},{0.0120758f,-0.206487f,-0.0937354f}, +{0.0169854f,-0.20227f,-0.0988077f},{0.037698f,-0.18448f,-0.116668f},{0.0323788f,-0.189049f,-0.112578f}, +{0.0327481f,-0.189055f,-0.112123f},{0.0271469f,-0.193542f,-0.108235f},{0.0430935f,-0.179846f,-0.120499f}, +{0.0485553f,-0.175155f,-0.12407f},{0.0540728f,-0.170416f,-0.127378f},{0.0652332f,-0.160831f,-0.133204f}, +{0.0821348f,-0.146314f,-0.139981f},{0.0764927f,-0.15116f,-0.137981f},{0.0767637f,-0.151251f,-0.137469f}, +{0.0708556f,-0.156002f,-0.135723f},{0.0877726f,-0.141472f,-0.141725f},{0.0933968f,-0.136641f,-0.143219f}, +{0.098999f,-0.13183f,-0.144466f},{0.104779f,-0.127189f,-0.144944f},{0.115592f,-0.117579f,-0.146786f}, +{-0.0536862f,-0.263292f,0.0704561f},{-0.0540966f,-0.263644f,0.0776737f},{-0.0531026f,-0.262791f,0.0631783f}, +{-0.0523409f,-0.262136f,0.0558501f},{-0.0513968f,-0.261326f,0.0484819f},{-0.0502663f,-0.260355f,0.0410845f}, +{-0.0489458f,-0.25922f,0.0336694f},{-0.0474322f,-0.257921f,0.0262484f},{-0.0457232f,-0.256453f,0.018834f}, +{-0.0412182f,-0.253084f,0.00420461f},{-0.0389169f,-0.251108f,-0.00310144f},{-0.0394067f,-0.251028f,-0.00324031f}, +{-0.0417114f,-0.253007f,0.00407642f},{-0.0369027f,-0.248877f,-0.0104976f},{-0.0342f,-0.246556f,-0.0176816f}, +{-0.0313f,-0.244065f,-0.0247786f},{-0.028205f,-0.241407f,-0.0317744f},{-0.0249178f,-0.238583f,-0.0386556f}, +{-0.021442f,-0.235598f,-0.0454087f},{-0.0139428f,-0.229157f,-0.0584778f},{-0.00993018f,-0.225711f,-0.0647685f}, +{-0.00575046f,-0.222121f,-0.0708804f},{-0.0014107f,-0.218393f,-0.0768021f},{0.0030815f,-0.214535f,-0.0825229f}, +{0.0124902f,-0.206454f,-0.0933224f},{0.0173889f,-0.202247f,-0.0983834f},{0.0224047f,-0.197939f,-0.103208f}, +{0.0275277f,-0.193539f,-0.10779f},{0.0384321f,-0.184674f,-0.1159f},{0.0438078f,-0.180057f,-0.119717f}, +{0.0434389f,-0.179873f,-0.120026f},{0.0380553f,-0.184497f,-0.116203f},{0.0488885f,-0.175192f,-0.123589f}, +{0.0543937f,-0.170464f,-0.12689f},{0.0599441f,-0.165697f,-0.129928f},{0.0655293f,-0.1609f,-0.132703f}, +{0.0711392f,-0.156082f,-0.135216f},{0.0823933f,-0.146416f,-0.139465f},{0.0883223f,-0.141824f,-0.140865f}, +{0.0939259f,-0.137011f,-0.142353f},{0.0936303f,-0.136765f,-0.142696f},{0.0880185f,-0.141584f,-0.141206f}, +{0.09922f,-0.131964f,-0.14394f},{0.126439f,-0.108336f,-0.147023f},{0.126387f,-0.108275f,-0.147351f}, +{-0.0538591f,-0.263998f,0.0918925f},{-0.0535853f,-0.263706f,0.0776945f},{-0.0525928f,-0.262854f,0.0632202f}, +{-0.0518322f,-0.2622f,0.0559028f},{-0.0522092f,-0.263044f,0.0632405f},{-0.0508895f,-0.261391f,0.0485453f}, +{-0.0497606f,-0.260421f,0.0411587f},{-0.048442f,-0.259289f,0.0337544f},{-0.0469307f,-0.257991f,0.0263442f}, +{-0.0452241f,-0.256525f,0.0189407f},{-0.0433204f,-0.25489f,0.0115564f},{-0.0333475f,-0.246844f,-0.0174445f}, +{-0.0360443f,-0.249161f,-0.010276f},{-0.0364165f,-0.24896f,-0.0103481f},{-0.0337177f,-0.246642f,-0.0175217f}, +{-0.030822f,-0.244155f,-0.0246083f},{-0.0277315f,-0.241501f,-0.0315939f},{-0.0244491f,-0.238682f,-0.038465f}, +{-0.0131342f,-0.229483f,-0.0581524f},{-0.0134902f,-0.229269f,-0.0582583f},{-0.016965f,-0.232774f,-0.051709f}, +{-0.00948339f,-0.225828f,-0.0645398f},{-0.00530978f,-0.222243f,-0.0706427f},{-0.00097635f,-0.218521f,-0.0765558f}, +{0.0132416f,-0.20683f,-0.0929216f},{0.0181297f,-0.202631f,-0.0979716f},{0.0129042f,-0.206599f,-0.093052f}, +{0.0177958f,-0.202398f,-0.0981056f},{0.0228042f,-0.198097f,-0.102923f},{0.0279198f,-0.193703f,-0.107499f}, +{0.0331325f,-0.189226f,-0.111826f},{0.0495612f,-0.175636f,-0.123123f},{0.0492495f,-0.175383f,-0.123274f}, +{0.0441234f,-0.180306f,-0.119568f},{0.0547466f,-0.170662f,-0.126571f},{0.0602889f,-0.165902f,-0.129604f}, +{0.0658659f,-0.161112f,-0.132375f},{0.0714676f,-0.156301f,-0.134885f},{0.0770839f,-0.151477f,-0.137135f}, +{0.0827053f,-0.146649f,-0.139127f},{0.0995074f,-0.132218f,-0.143596f},{0.116304f,-0.118312f,-0.145739f}, +{0.11084f,-0.123004f,-0.145199f},{0.116039f,-0.118019f,-0.145907f},{0.126541f,-0.108454f,-0.146724f}, +{-0.0514492f,-0.262391f,0.0559281f},{-0.0505071f,-0.261582f,0.0485758f},{-0.049379f,-0.260613f,0.0411945f}, +{-0.0480614f,-0.259482f,0.0337954f},{-0.0465511f,-0.258185f,0.0263905f},{-0.0448457f,-0.25672f,0.0189921f}, +{-0.0429433f,-0.255086f,0.0116131f},{-0.0408426f,-0.253282f,0.00426646f},{-0.038543f,-0.251307f,-0.00303443f}, +{-0.0304538f,-0.244359f,-0.0245261f},{-0.0273654f,-0.241706f,-0.0315068f},{-0.0240853f,-0.238889f,-0.0383731f}, +{-0.0206171f,-0.23591f,-0.0451116f},{-0.00913019f,-0.226044f,-0.0644294f},{-0.00495953f,-0.222462f,-0.0705281f}, +{-0.00062916f,-0.218743f,-0.076437f},{0.00385332f,-0.214893f,-0.0821454f},{0.00847979f,-0.21092f,-0.0876434f}, +{0.0231347f,-0.198333f,-0.102786f},{0.0282467f,-0.193942f,-0.107358f},{0.0334557f,-0.189468f,-0.111682f}, +{0.0387515f,-0.18492f,-0.115753f},{0.0550545f,-0.170917f,-0.126416f},{0.0605929f,-0.166161f,-0.129448f}, +{0.066166f,-0.161374f,-0.132217f},{0.0717637f,-0.156566f,-0.134725f},{0.0773761f,-0.151746f,-0.136973f}, +{0.0829935f,-0.146921f,-0.138964f},{0.0886065f,-0.1421f,-0.140701f},{0.0942061f,-0.137291f,-0.142188f}, +{0.0997837f,-0.1325f,-0.14343f},{0.105331f,-0.127736f,-0.144432f},{0.246242f,-0.00568906f,-0.0892991f}, +{0.241437f,-0.00981657f,-0.0946258f},{0.241022f,-0.00984878f,-0.0942128f},{0.221744f,-0.0277507f,-0.114f}, +{0.227012f,-0.023226f,-0.109627f},{0.216388f,-0.0323507f,-0.118117f},{0.210955f,-0.0370173f,-0.121975f}, +{0.205455f,-0.0417412f,-0.125571f},{0.199899f,-0.0465131f,-0.128902f},{0.194298f,-0.0513242f,-0.131968f}, +{0.188661f,-0.0561654f,-0.134769f},{0.205143f,-0.0414889f,-0.125419f},{0.199238f,-0.0460598f,-0.128429f}, +{0.204783f,-0.041298f,-0.125105f},{0.182999f,-0.061028f,-0.137305f},{0.177323f,-0.0659033f,-0.139579f}, +{0.171642f,-0.0707829f,-0.141592f},{0.160302f,-0.0805227f,-0.144853f},{0.165965f,-0.0756586f,-0.143349f}, +{0.154661f,-0.0853677f,-0.146109f},{0.14905f,-0.0901863f,-0.147122f},{0.143479f,-0.0949717f,-0.147899f}, +{0.132419f,-0.10447f,-0.146057f},{0.14321f,-0.0946823f,-0.147731f},{0.148778f,-0.0899002f,-0.146955f}, +{0.143294f,-0.0951304f,-0.145199f},{0.143048f,-0.0948213f,-0.145366f},{0.13783f,-0.0998229f,-0.145739f}, +{0.14829f,-0.0894947f,-0.146081f},{0.154097f,-0.084831f,-0.145599f},{0.148499f,-0.0896393f,-0.14661f}, +{0.131926f,-0.103873f,-0.146574f},{0.131778f,-0.103676f,-0.147105f},{0.132166f,-0.104168f,-0.146225f}, +{0.142939f,-0.0944145f,-0.147384f},{0.131792f,-0.103664f,-0.147719f},{0.13248f,-0.104418f,-0.148767f}, +{0.132219f,-0.104122f,-0.148599f},{0.137953f,-0.0997176f,-0.148445f},{0.131964f,-0.10384f,-0.148251f}, +{0.142742f,-0.0942593f,-0.146855f},{0.232183f,-0.0187856f,-0.105003f},{0.237244f,-0.0144381f,-0.100134f}, +{0.242188f,-0.010192f,-0.0950266f},{0.247004f,-0.00605566f,-0.0896885f},{0.251683f,-0.00203683f,-0.0841281f}, +{0.256217f,0.00185696f,-0.0783547f},{0.260596f,0.00561864f,-0.0723786f},{0.268508f,0.0129341f,-0.059756f}, +{0.264015f,0.00957541f,-0.0658715f},{0.268056f,0.0130461f,-0.0595366f},{0.264815f,0.00924161f,-0.0662105f}, +{0.268864f,0.0127198f,-0.059862f},{0.272739f,0.0160476f,-0.053345f},{0.276433f,0.0192201f,-0.0466724f}, +{0.279941f,0.022233f,-0.039857f},{0.283258f,0.0250823f,-0.0329122f},{0.286382f,0.0277651f,-0.0258517f}, +{0.291178f,0.0329051f,-0.0112184f},{0.290653f,0.0327782f,-0.01099f},{0.293699f,0.0350709f,-0.00391029f}, +{0.289308f,0.0302787f,-0.0186898f},{0.292036f,0.0326214f,-0.0114399f},{0.294563f,0.0347919f,-0.00411618f}, +{0.296889f,0.0367896f,0.00326766f},{0.299014f,0.0386144f,0.0106978f},{0.300938f,0.040267f,0.0181608f}, +{0.302663f,0.0417484f,0.0256434f},{0.30419f,0.0430604f,0.0331326f},{0.305141f,0.0443974f,0.0406518f}, +{0.305523f,0.044205f,0.040616f},{0.303809f,0.0432535f,0.0331736f},{0.306664f,0.045185f,0.0480815f}, +{0.308737f,0.0479862f,0.0847721f},{0.30793f,0.0476169f,0.077605f},{0.308173f,0.0478259f,0.0847878f}, +{0.306812f,0.0463329f,0.0704555f},{0.307054f,0.0468645f,0.0704077f},{0.306228f,0.0458317f,0.0631775f}, +{0.307233f,0.0461944f,0.0555431f},{0.308002f,0.0468541f,0.0629336f},{0.308385f,0.0466635f,0.0629134f}, +{0.306796f,0.0458187f,0.0704868f},{0.306213f,0.0453183f,0.0632194f},{0.307448f,0.0463783f,0.0848321f}, +{0.307515f,0.0467654f,0.0918925f},{0.307464f,0.0468934f,0.0848218f},{0.306931f,0.0467592f,0.0630396f}, +{0.308079f,0.0474218f,0.0703047f},{0.307492f,0.046917f,0.0629755f},{0.307577f,0.0459696f,0.0848371f}, +{0.307535f,0.0464061f,0.0918925f},{0.306166f,0.0461019f,0.0556761f},{0.306725f,0.0462583f,0.0555957f}, +{0.305217f,0.0452871f,0.0482723f},{0.307647f,0.046058f,0.0918925f},{0.307617f,0.0460033f,0.0555177f}, +{0.309388f,0.047525f,0.0775425f},{0.308974f,0.0471693f,0.0702583f},{0.30859f,0.0473596f,0.0702734f}, +{0.309633f,0.0477349f,0.0847568f},{0.137688f,-0.0994249f,-0.148277f},{0.154384f,-0.0850849f,-0.145943f}, +{0.160021f,-0.0802434f,-0.144688f},{0.165681f,-0.0753827f,-0.143185f},{0.171354f,-0.0705103f,-0.141429f}, +{0.177031f,-0.0656341f,-0.139417f},{0.182703f,-0.0607622f,-0.137145f},{0.188361f,-0.055903f,-0.134611f}, +{0.193994f,-0.0510652f,-0.131812f},{0.199591f,-0.0462575f,-0.128748f},{0.21064f,-0.0367683f,-0.121826f}, +{0.216069f,-0.032105f,-0.117971f},{0.221421f,-0.0275082f,-0.113856f},{0.226686f,-0.0229866f,-0.109486f}, +{0.231852f,-0.0185493f,-0.104866f},{0.23691f,-0.0142048f,-0.1f},{0.241851f,-0.00996175f,-0.0948962f}, +{0.246663f,-0.00582826f,-0.0895618f},{0.251339f,-0.00181224f,-0.0840052f},{0.25587f,0.00207883f,-0.0782359f}, +{0.260246f,0.00583789f,-0.072264f},{0.264462f,0.00945834f,-0.0661002f},{0.27238f,0.0162596f,-0.0532437f}, +{0.276071f,0.0194299f,-0.0465757f},{0.279577f,0.0224406f,-0.039765f},{0.282892f,0.025288f,-0.0328251f}, +{0.286013f,0.0279689f,-0.0257695f},{0.288938f,0.0304808f,-0.0186126f},{0.291664f,0.0328218f,-0.0113678f}, +{0.294189f,0.0349908f,-0.00404916f},{0.296513f,0.0369871f,0.00332952f},{0.298637f,0.0388106f,0.0107545f}, +{0.300559f,0.0404621f,0.0182123f},{0.302283f,0.0419425f,0.0256896f},{0.306281f,0.0453766f,0.0481121f}, +{0.305774f,0.0454417f,0.0481755f},{0.309248f,0.0479248f,0.0847617f},{0.309004f,0.047715f,0.0775525f}, +{0.309376f,0.0479772f,0.0918925f},{0.309694f,0.0478162f,0.0918925f},{0.137425f,-0.0991502f,-0.147929f}, +{0.159726f,-0.0799965f,-0.144345f},{0.165377f,-0.0751428f,-0.142845f},{0.171042f,-0.0702775f,-0.141092f}, +{0.176711f,-0.0654083f,-0.139082f},{0.182375f,-0.0605435f,-0.136814f},{0.188024f,-0.0556914f,-0.134283f}, +{0.193649f,-0.0508605f,-0.131488f},{0.215692f,-0.0319277f,-0.117667f},{0.210271f,-0.0365843f,-0.121517f}, +{0.209925f,-0.0365573f,-0.121044f},{0.221037f,-0.0273376f,-0.113559f},{0.226294f,-0.0228226f,-0.109195f}, +{0.231453f,-0.0183917f,-0.104581f},{0.236503f,-0.0140535f,-0.0997223f},{0.250911f,-0.00167885f,-0.0837506f}, +{0.255435f,0.00220659f,-0.0779897f},{0.259806f,0.00596021f,-0.0720263f},{0.275118f,0.0194353f,-0.046069f}, +{0.274737f,0.0191082f,-0.0457157f},{0.27861f,0.022435f,-0.0392833f},{0.271922f,0.0163668f,-0.0530336f}, +{0.275608f,0.0195325f,-0.0463752f},{0.279108f,0.0225389f,-0.0395744f},{0.282419f,0.0253822f,-0.0326445f}, +{0.285535f,0.0280592f,-0.0255992f},{0.288456f,0.0305674f,-0.0184526f},{0.29602f,0.0370643f,0.00345771f}, +{0.29814f,0.0388852f,0.0108719f},{0.30006f,0.0405343f,0.0183189f},{0.301781f,0.0420125f,0.0257854f}, +{0.303306f,0.0433217f,0.0332586f},{0.304636f,0.0444639f,0.0407259f},{0.308493f,0.0477767f,0.0775733f}, +{0.307518f,0.0472628f,0.0703525f},{0.309015f,0.0480539f,0.0918925f},{0.137241f,-0.0989846f,-0.147398f}, +{0.153876f,-0.0846971f,-0.145073f},{0.159492f,-0.0798733f,-0.143822f},{0.170669f,-0.0702734f,-0.13998f}, +{0.17644f,-0.0653174f,-0.138571f},{0.170783f,-0.0701758f,-0.140576f},{0.165131f,-0.0750303f,-0.142325f}, +{0.182091f,-0.0604634f,-0.136307f},{0.187728f,-0.055622f,-0.133782f},{0.19334f,-0.0508018f,-0.130993f}, +{0.198917f,-0.0460117f,-0.127941f},{0.204449f,-0.0412605f,-0.124624f},{0.220426f,-0.0275383f,-0.112579f}, +{0.225913f,-0.022826f,-0.10875f},{0.220668f,-0.027331f,-0.113104f},{0.215335f,-0.031911f,-0.117203f}, +{0.23106f,-0.0184049f,-0.104146f},{0.2361f,-0.0140763f,-0.0992979f},{0.250158f,-0.00200198f,-0.0829128f}, +{0.25499f,0.00214776f,-0.0776135f},{0.250476f,-0.00172908f,-0.0833616f},{0.245817f,-0.00573041f,-0.0888979f}, +{0.25935f,0.00589306f,-0.0716633f},{0.26355f,0.00950025f,-0.0655221f},{0.267582f,0.0129633f,-0.0592012f}, +{0.27144f,0.0162766f,-0.0527127f},{0.281913f,0.025272f,-0.0323688f},{0.285023f,0.0279431f,-0.025339f}, +{0.287937f,0.0304458f,-0.0182083f},{0.295052f,0.0365564f,0.00387953f},{0.2976f,0.0387452f,0.0110514f}, +{0.295485f,0.0369283f,0.00365355f},{0.293169f,0.0349393f,-0.00369814f},{0.299516f,0.0403906f,0.0184819f}, +{0.301233f,0.0418655f,0.0259318f},{0.302754f,0.0431718f,0.0333884f},{0.304081f,0.0443114f,0.0408392f}, +{0.306469f,0.0463621f,0.0631135f},{0.308656f,0.0480337f,0.0918925f},{0.142701f,-0.0942953f,-0.146243f}, +{0.137213f,-0.0990084f,-0.146785f},{0.148234f,-0.0895429f,-0.145472f},{0.153805f,-0.0847575f,-0.144466f}, +{0.159408f,-0.079946f,-0.143218f},{0.165032f,-0.0751155f,-0.141725f},{0.176312f,-0.0654275f,-0.137981f}, +{0.193169f,-0.0509491f,-0.130423f},{0.187571f,-0.0557569f,-0.133204f},{0.187595f,-0.05606f,-0.132703f}, +{0.181949f,-0.0605859f,-0.135723f},{0.198732f,-0.0461712f,-0.127378f},{0.204249f,-0.0414322f,-0.12407f}, +{0.209711f,-0.036741f,-0.120499f},{0.215107f,-0.0321066f,-0.116668f},{0.235824f,-0.0151381f,-0.0981062f}, +{0.235736f,-0.014713f,-0.098384f},{0.230815f,-0.0194397f,-0.102924f},{0.225658f,-0.0230449f,-0.108236f}, +{0.230792f,-0.0186351f,-0.103644f},{0.235819f,-0.0143176f,-0.0988083f},{0.240729f,-0.0101009f,-0.0937362f}, +{0.245511f,-0.00599306f,-0.0884349f},{0.263103f,0.00829154f,-0.0645409f},{0.263055f,0.00875088f,-0.0647696f}, +{0.258929f,0.00470683f,-0.0706439f},{0.25466f,0.00186493f,-0.0771794f},{0.25901f,0.00560064f,-0.0712445f}, +{0.263199f,0.00919859f,-0.065119f},{0.267221f,0.0126528f,-0.0588143f},{0.271069f,0.0159576f,-0.0523423f}, +{0.284617f,0.0275942f,-0.0250388f},{0.281515f,0.02493f,-0.0320505f},{0.28133f,0.0244472f,-0.0317747f}, +{0.278221f,0.0221003f,-0.0389474f},{0.287524f,0.0300905f,-0.0179263f},{0.290232f,0.032417f,-0.0107265f}, +{0.292742f,0.0345725f,-0.00345334f},{0.297162f,0.0383686f,0.0112584f},{0.302303f,0.0427839f,0.0335382f}, +{0.300786f,0.041481f,0.0261007f},{0.300558f,0.0409614f,0.0262471f},{0.299073f,0.0400098f,0.0186698f}, +{0.303626f,0.0439206f,0.04097f},{0.304759f,0.0448938f,0.048384f},{0.305705f,0.0457065f,0.0557688f}, +{0.307465f,0.0472177f,0.0776416f},{0.307708f,0.0474261f,0.084806f},{0.307998f,0.0477204f,0.0918925f}, +{0.308307f,0.0479214f,0.0918925f},{0.142824f,-0.0945127f,-0.145713f},{0.137349f,-0.0992153f,-0.146254f}, +{0.148345f,-0.0897709f,-0.144944f},{0.153904f,-0.0849962f,-0.14394f},{0.159494f,-0.0801954f,-0.142695f}, +{0.165106f,-0.0753756f,-0.141205f},{0.170731f,-0.0705443f,-0.139464f},{0.176361f,-0.0657091f,-0.137469f}, +{0.181985f,-0.0608783f,-0.135216f},{0.193331f,-0.0516347f,-0.129604f},{0.198873f,-0.0468744f,-0.126571f}, +{0.198731f,-0.0464957f,-0.12689f},{0.19318f,-0.0512629f,-0.129928f},{0.204236f,-0.0417672f,-0.123589f}, +{0.209686f,-0.0370865f,-0.120026f},{0.21507f,-0.0324624f,-0.116203f},{0.220377f,-0.0279043f,-0.112124f}, +{0.225597f,-0.0234208f,-0.10779f},{0.23072f,-0.0190209f,-0.103209f},{0.240634f,-0.0105057f,-0.0933231f}, +{0.245406f,-0.00640698f,-0.0880336f},{0.250043f,-0.00242477f,-0.0825239f},{0.254535f,0.00143353f,-0.0768032f}, +{0.258875f,0.00516092f,-0.0708815f},{0.267067f,0.0121974f,-0.0584789f},{0.270907f,0.0154949f,-0.0520214f}, +{0.274567f,0.0186385f,-0.0454095f},{0.278043f,0.0216238f,-0.0386562f},{0.284442f,0.0266194f,-0.0246083f}, +{0.287338f,0.0291065f,-0.017522f},{0.287325f,0.0295963f,-0.017682f},{0.284425f,0.0271056f,-0.0247786f}, +{0.290028f,0.0319176f,-0.0104982f},{0.292532f,0.0340683f,-0.00324118f},{0.294837f,0.0360478f,0.00407537f}, +{0.296942f,0.037856f,0.0114378f},{0.298849f,0.0394935f,0.0188328f},{0.302071f,0.0422615f,0.0336681f}, +{0.303381f,0.0428858f,0.0411575f},{0.30451f,0.0438554f,0.0485442f},{0.304522f,0.0443667f,0.0484808f}, +{0.303392f,0.0433957f,0.0410833f},{0.305467f,0.0451776f,0.0558492f},{0.307222f,0.0466854f,0.0776733f}, +{0.307591f,0.0471265f,0.0918925f},{0.307758f,0.047452f,0.0918925f},{0.137581f,-0.0995171f,-0.145907f}, +{0.148561f,-0.0900864f,-0.144598f},{0.154112f,-0.0853187f,-0.143596f},{0.148803f,-0.0903988f,-0.144431f}, +{0.159694f,-0.0805249f,-0.142353f},{0.165297f,-0.0757121f,-0.140865f},{0.170914f,-0.0708878f,-0.139127f}, +{0.176535f,-0.0660598f,-0.137134f},{0.182152f,-0.061236f,-0.134885f},{0.187753f,-0.0564248f,-0.132375f}, +{0.210011f,-0.0378285f,-0.119568f},{0.204573f,-0.0424991f,-0.123123f},{0.20437f,-0.0421528f,-0.123274f}, +{0.209812f,-0.0374789f,-0.119717f},{0.215188f,-0.0328616f,-0.1159f},{0.220487f,-0.0283101f,-0.111826f}, +{0.2257f,-0.0238332f,-0.107499f},{0.240892f,-0.0113052f,-0.0929223f},{0.240715f,-0.0109369f,-0.0930527f}, +{0.236004f,-0.0155034f,-0.0979722f},{0.24548f,-0.00684419f,-0.087771f},{0.25011f,-0.0028678f,-0.0822693f}, +{0.254596f,0.000984871f,-0.0765569f},{0.267268f,0.0113487f,-0.0581535f},{0.271099f,0.0146391f,-0.0517099f}, +{0.26711f,0.011733f,-0.0582594f},{0.270944f,0.0150257f,-0.0518113f},{0.274598f,0.0181647f,-0.0452091f}, +{0.278069f,0.0211457f,-0.0384656f},{0.281352f,0.023965f,-0.0315942f},{0.290179f,0.0310263f,-0.0102766f}, +{0.290037f,0.0314244f,-0.0103487f},{0.287482f,0.02871f,-0.0174448f},{0.292537f,0.033572f,-0.0031023f}, +{0.294839f,0.0355486f,0.00420356f},{0.296941f,0.0373542f,0.0115553f},{0.298845f,0.0389893f,0.0189394f}, +{0.300551f,0.0404551f,0.026343f},{0.302063f,0.0417532f,0.0337531f},{0.305453f,0.044665f,0.0559018f}, +{0.307336f,0.0457621f,0.0777041f},{0.306926f,0.0454104f,0.0705019f},{0.307206f,0.0461706f,0.077694f}, +{0.15435f,-0.0856345f,-0.143429f},{0.159927f,-0.0808441f,-0.142188f},{0.165527f,-0.0760347f,-0.140701f}, +{0.17114f,-0.0712139f,-0.138964f},{0.176757f,-0.0663892f,-0.136973f},{0.18237f,-0.0615688f,-0.134725f}, +{0.187968f,-0.056761f,-0.132217f},{0.193541f,-0.0519743f,-0.129448f},{0.199079f,-0.0472174f,-0.126416f}, +{0.215383f,-0.0332144f,-0.115753f},{0.220678f,-0.0286662f,-0.111682f},{0.225887f,-0.0241924f,-0.107358f}, +{0.230999f,-0.019802f,-0.102786f},{0.245654f,-0.00721537f,-0.0876442f},{0.25028f,-0.00324179f,-0.0821464f}, +{0.254763f,0.000608165f,-0.0764381f},{0.259093f,0.00432749f,-0.0705292f},{0.263264f,0.00790968f,-0.0644306f}, +{0.274751f,0.0177759f,-0.0451124f},{0.27822f,0.0207548f,-0.0383737f},{0.2815f,0.0235721f,-0.0315071f}, +{0.284588f,0.0262246f,-0.0245261f},{0.292677f,0.0331723f,-0.0030353f},{0.294977f,0.0351475f,0.00426541f}, +{0.297078f,0.0369518f,0.0116119f},{0.29898f,0.0385858f,0.0189909f},{0.300686f,0.0400505f,0.0263892f}, +{0.302196f,0.0413477f,0.0337941f},{0.303514f,0.0424795f,0.0411933f},{0.304642f,0.0434484f,0.0485748f}, +{0.305584f,0.0442575f,0.0559272f},{0.306344f,0.0449103f,0.0632397f},{-0.0768213f,-0.165362f,-0.141015f}, +{-0.0807759f,-0.161231f,-0.142188f},{-0.0760016f,-0.16686f,-0.140701f},{-0.0521167f,-0.195024f,-0.129448f}, +{-0.0506739f,-0.196193f,-0.12867f},{-0.0549268f,-0.191178f,-0.131224f},{-0.0952491f,-0.144775f,-0.145366f}, +{-0.0955186f,-0.145045f,-0.145713f},{-0.0908114f,-0.150595f,-0.144944f},{-0.0855313f,-0.155624f,-0.143429f}, +{-0.0812993f,-0.160082f,-0.142366f},{-0.0862068f,-0.156404f,-0.144466f},{-0.0909572f,-0.150803f,-0.145472f}, +{-0.094958f,-0.144508f,-0.145199f},{-0.0905487f,-0.150317f,-0.144598f},{-0.0902609f,-0.150047f,-0.144431f}, +{-0.104976f,-0.134273f,-0.147719f},{-0.104988f,-0.134259f,-0.147105f},{-0.109589f,-0.12887f,-0.147351f}, +{-0.095675f,-0.14524f,-0.146243f},{-0.109234f,-0.128569f,-0.148558f},{-0.104482f,-0.133888f,-0.148599f}, +{-0.104778f,-0.134126f,-0.148251f},{-0.109527f,-0.128818f,-0.148015f},{-0.0993034f,-0.138852f,-0.148493f}, +{-0.0995117f,-0.139139f,-0.148445f},{-0.104178f,-0.133637f,-0.148767f},{-0.103915f,-0.133415f,-0.14881f}, +{-0.108786f,-0.128189f,-0.148876f},{-0.10853f,-0.127972f,-0.148916f},{-0.0679527f,-0.175819f,-0.137702f}, +{-0.0712159f,-0.172503f,-0.138964f},{-0.0664265f,-0.178151f,-0.136973f},{-0.0723712f,-0.170609f,-0.13946f}, +{-0.0616412f,-0.183793f,-0.134725f},{-0.0635699f,-0.180987f,-0.135742f},{-0.0571328f,-0.189719f,-0.132375f}, +{-0.0568685f,-0.189421f,-0.132217f},{-0.0592267f,-0.186108f,-0.133582f},{-0.0473945f,-0.200592f,-0.126416f}, +{-0.0464718f,-0.201148f,-0.125923f},{-0.0380742f,-0.211582f,-0.119568f},{-0.0334938f,-0.216983f,-0.115753f}, +{-0.0342072f,-0.21561f,-0.116543f},{-0.0427107f,-0.206115f,-0.123123f},{-0.0225297f,-0.229379f,-0.105516f}, +{-0.0263511f,-0.224873f,-0.109369f},{-0.0245376f,-0.227544f,-0.107358f},{-0.0302448f,-0.220282f,-0.113046f}, +{-0.0151167f,-0.23812f,-0.0972923f},{-0.015912f,-0.237714f,-0.0979722f},{-0.0117444f,-0.242629f,-0.0929223f}, +{-0.0201792f,-0.232683f,-0.102786f},{-0.00462018f,-0.250497f,-0.0837205f},{-0.00373985f,-0.252067f,-0.0821464f}, +{-0.0012999f,-0.254412f,-0.0788827f},{-0.00768443f,-0.247416f,-0.0876442f},{0.00808472f,-0.265478f,-0.0634868f}, +{0.00505532f,-0.261906f,-0.0687614f},{0.00733025f,-0.26512f,-0.0644306f},{0.0019262f,-0.258216f,-0.0738949f}, +{0.0037742f,-0.260927f,-0.0705292f},{0.0165479f,-0.275457f,-0.0468636f},{0.0140105f,-0.272997f,-0.0517099f}, +{0.0171244f,-0.276669f,-0.0451124f},{0.0107442f,-0.269146f,-0.0581535f},{0.0228784f,-0.283454f,-0.0315071f}, +{0.0240231f,-0.284271f,-0.0291439f},{0.021645f,-0.281467f,-0.0351637f},{0.0191525f,-0.278528f,-0.041072f}, +{0.0304509f,-0.291851f,-0.010468f},{0.028428f,-0.289465f,-0.0167907f},{0.0302782f,-0.292179f,-0.0102766f}, +{0.0255116f,-0.286558f,-0.0245261f},{0.0324085f,-0.294691f,-0.0030353f},{0.034129f,-0.296187f,0.00244111f}, +{0.0323519f,-0.294092f,-0.00405553f},{0.0377825f,-0.301028f,0.0189909f},{0.0373059f,-0.299933f,0.0156645f}, +{0.0361604f,-0.299115f,0.0116119f},{0.0357808f,-0.298135f,0.00901635f},{0.0343693f,-0.297003f,0.00426541f}, +{0.0399706f,-0.303075f,0.0291557f},{0.0405243f,-0.304261f,0.0337941f},{0.0411078f,-0.304416f,0.0359868f}, +{0.0392366f,-0.302742f,0.0263892f},{0.0387029f,-0.301581f,0.0223796f},{0.0421137f,-0.305602f,0.0428671f}, +{0.0426097f,-0.306719f,0.0485748f},{0.0429872f,-0.306632f,0.0497904f},{0.0416478f,-0.305585f,0.0411933f}, +{0.0451124f,-0.309671f,0.0848371f},{0.0454147f,-0.309495f,0.0918925f},{0.0453472f,-0.309415f,0.0848393f}, +{0.0437276f,-0.307506f,0.0567509f},{0.0434129f,-0.307667f,0.0559272f},{0.0445573f,-0.309016f,0.0705019f}, +{0.0443647f,-0.309399f,0.0704868f},{0.044714f,-0.309811f,0.077694f},{0.0451444f,-0.309176f,0.0777923f}, +{0.0443343f,-0.308221f,0.0637421f},{0.0448067f,-0.308778f,0.0707579f},{0.0449064f,-0.309428f,0.0777041f}, +{0.0440608f,-0.308431f,0.0632397f},{0.0446491f,-0.310322f,0.0776733f},{0.0450123f,-0.31113f,0.084806f}, +{0.0448556f,-0.310565f,0.0848218f},{0.0424156f,-0.307101f,0.0485442f},{0.0414531f,-0.305966f,0.0411575f}, +{0.0442993f,-0.309909f,0.0704555f},{0.0438679f,-0.308813f,0.0632194f},{0.0438017f,-0.309322f,0.0631775f}, +{0.0423474f,-0.307608f,0.0484808f},{0.0448502f,-0.310938f,0.0703525f},{0.0443502f,-0.310349f,0.0630396f}, +{0.0453802f,-0.311184f,0.0703047f},{0.043956f,-0.309884f,0.0631135f},{0.0444547f,-0.310472f,0.0704077f}, +{0.0458943f,-0.311202f,0.0702734f},{0.0462471f,-0.311618f,0.0775525f},{0.0462046f,-0.311955f,0.0918925f}, +{0.0459404f,-0.311844f,0.0847721f},{0.0464553f,-0.311864f,0.0847617f},{0.0468649f,-0.311737f,0.0847568f}, +{0.0469128f,-0.311827f,0.0918925f},{0.046564f,-0.311937f,0.0918925f},{0.0472235f,-0.311628f,0.0918925f}, +{0.0390402f,-0.303121f,0.026343f},{0.0200816f,-0.280156f,-0.0383737f},{0.0262847f,-0.286938f,-0.0230178f}, +{0.0279788f,-0.289468f,-0.0174448f},{0.0226704f,-0.283818f,-0.0315942f},{0.0138335f,-0.272256f,-0.0525331f}, +{0.0110116f,-0.268929f,-0.0580758f},{8.20141e-005f,-0.256573f,-0.0764381f},{-0.00803171f,-0.246474f,-0.088404f}, +{0.00355277f,-0.261276f,-0.0706439f},{0.0034277f,-0.261716f,-0.0708815f},{0.00699146f,-0.265918f,-0.0647696f}, +{-0.0115316f,-0.242347f,-0.0929293f},{-0.0187838f,-0.233796f,-0.101489f},{-0.0382349f,-0.21086f,-0.119856f}, +{-0.0423242f,-0.206039f,-0.122984f},{-0.0289787f,-0.222307f,-0.111682f},{-0.0163012f,-0.238453f,-0.098384f}, +{-0.0204175f,-0.233012f,-0.102924f},{-0.0205776f,-0.23341f,-0.103209f},{-0.0858011f,-0.154773f,-0.14351f}, +{-0.0903231f,-0.149441f,-0.144448f},{-0.094861f,-0.14409f,-0.145179f},{-0.10481f,-0.134088f,-0.146574f}, +{-0.109528f,-0.128818f,-0.147023f},{-0.0996162f,-0.139016f,-0.145739f},{-0.0994109f,-0.138726f,-0.145701f}, +{-0.10423f,-0.133576f,-0.146057f},{-0.103969f,-0.133351f,-0.146014f},{-0.109589f,-0.12887f,-0.147687f}, +{-0.108787f,-0.12819f,-0.146158f},{-0.10853f,-0.127972f,-0.146119f},{-0.10902f,-0.128388f,-0.146297f}, +{-0.109238f,-0.128572f,-0.146474f},{-0.104527f,-0.133835f,-0.146225f},{-0.109409f,-0.128718f,-0.146724f}, +{-0.0999106f,-0.139278f,-0.145907f},{-0.0858158f,-0.155898f,-0.143596f},{-0.081057f,-0.161509f,-0.142353f}, +{-0.0762794f,-0.167143f,-0.140865f},{-0.0714903f,-0.17279f,-0.139127f},{-0.0666975f,-0.178441f,-0.137134f}, +{-0.0619089f,-0.184088f,-0.134885f},{-0.0525844f,-0.19567f,-0.129928f},{-0.047852f,-0.20125f,-0.12689f}, +{-0.0523776f,-0.195326f,-0.129604f},{-0.0476521f,-0.200898f,-0.126571f},{-0.042965f,-0.206425f,-0.123274f}, +{-0.0383251f,-0.211896f,-0.119717f},{-0.0337415f,-0.217301f,-0.1159f},{-0.0292233f,-0.222629f,-0.111826f}, +{-0.024779f,-0.227869f,-0.107499f},{-0.0161473f,-0.238047f,-0.0981062f},{-0.0119768f,-0.242965f,-0.0930527f}, +{-0.00791396f,-0.247755f,-0.087771f},{-0.00396659f,-0.25241f,-0.0822693f},{-0.000142029f,-0.256919f,-0.0765569f}, +{0.00711132f,-0.265472f,-0.0645409f},{0.0105277f,-0.2695f,-0.0582594f},{0.0137963f,-0.273355f,-0.0518113f}, +{0.0169124f,-0.277029f,-0.0452091f},{0.0198717f,-0.280518f,-0.0384656f},{0.0301127f,-0.293561f,-0.0107265f}, +{0.0276847f,-0.290318f,-0.017682f},{0.0278031f,-0.290838f,-0.0179263f},{0.0253055f,-0.286925f,-0.0246083f}, +{0.0277744f,-0.289837f,-0.017522f},{0.0300754f,-0.29255f,-0.0103487f},{0.0322073f,-0.295064f,-0.0031023f}, +{0.0341695f,-0.297377f,0.00420356f},{0.0359619f,-0.299491f,0.0115553f},{0.0375851f,-0.301405f,0.0189394f}, +{0.0403288f,-0.30464f,0.0337531f},{0.0413834f,-0.306471f,0.0410833f},{0.0432194f,-0.308048f,0.0559018f}, +{0.0449202f,-0.310054f,0.0848321f},{0.0450044f,-0.310086f,0.0918925f},{0.0451675f,-0.309769f,0.0918925f}, +{-0.109406f,-0.128715f,-0.14831f},{-0.100187f,-0.13954f,-0.146254f},{-0.0860715f,-0.156184f,-0.14394f}, +{-0.0813058f,-0.161803f,-0.142695f},{-0.0765212f,-0.167445f,-0.141205f},{-0.0717251f,-0.1731f,-0.139464f}, +{-0.0669252f,-0.17876f,-0.137469f},{-0.0621296f,-0.184415f,-0.135216f},{-0.0573465f,-0.190055f,-0.132703f}, +{-0.043158f,-0.206785f,-0.123589f},{-0.0431976f,-0.207118f,-0.12407f},{-0.0385406f,-0.212609f,-0.120499f}, +{-0.0385114f,-0.212264f,-0.120026f},{-0.0339211f,-0.217677f,-0.116203f},{-0.0293962f,-0.223012f,-0.112124f}, +{-0.0249455f,-0.22826f,-0.10779f},{-0.0080171f,-0.248601f,-0.0884349f},{-0.00775636f,-0.248908f,-0.0888979f}, +{-0.00378422f,-0.253592f,-0.0833616f},{-0.0121246f,-0.243378f,-0.0933231f},{-0.0080558f,-0.248175f,-0.0880336f}, +{-0.00410265f,-0.252837f,-0.0825239f},{-0.000272494f,-0.257353f,-0.0768032f},{0.0137734f,-0.274295f,-0.0523423f}, +{0.0140901f,-0.274668f,-0.0527127f},{0.0172258f,-0.278365f,-0.046069f},{0.0104128f,-0.269952f,-0.0584789f}, +{0.0136862f,-0.273812f,-0.0520214f},{0.0168069f,-0.277492f,-0.0454095f},{0.0197705f,-0.280986f,-0.0386562f}, +{0.0225733f,-0.284291f,-0.0317747f},{0.0252122f,-0.287403f,-0.0247786f},{0.0299891f,-0.293035f,-0.0104982f}, +{0.0321241f,-0.295553f,-0.00324118f},{0.0340892f,-0.29787f,0.00407537f},{0.0358842f,-0.299987f,0.0114378f}, +{0.0375098f,-0.301903f,0.0188328f},{0.038967f,-0.303622f,0.0262471f},{0.0402575f,-0.305143f,0.0336681f}, +{0.0431523f,-0.308557f,0.0558492f},{0.0452017f,-0.311353f,0.077605f},{0.0449255f,-0.310447f,0.0918925f}, +{-0.0998191f,-0.139386f,-0.148277f},{-0.100354f,-0.139723f,-0.146785f},{-0.0814304f,-0.162036f,-0.143218f}, +{-0.0813582f,-0.162121f,-0.143822f},{-0.0765506f,-0.16779f,-0.142325f},{-0.0766352f,-0.16769f,-0.141725f}, +{-0.0718284f,-0.173358f,-0.13998f},{-0.0670178f,-0.179031f,-0.137981f},{-0.0622115f,-0.184698f,-0.135723f}, +{-0.0574178f,-0.19035f,-0.133204f},{-0.0526451f,-0.195978f,-0.130423f},{-0.0479021f,-0.201571f,-0.127378f}, +{-0.0339401f,-0.218034f,-0.116668f},{-0.0337459f,-0.218263f,-0.117203f},{-0.0291993f,-0.223624f,-0.113104f}, +{-0.0294051f,-0.223381f,-0.112579f},{-0.0249445f,-0.228641f,-0.108236f},{-0.0205669f,-0.233803f,-0.103644f}, +{-0.0162809f,-0.238856f,-0.0988083f},{-0.0120949f,-0.243792f,-0.0937362f},{-0.00405513f,-0.253272f,-0.0829128f}, +{-0.000216443f,-0.257799f,-0.0771794f},{0.00349201f,-0.262171f,-0.0712445f},{0.00706371f,-0.266383f,-0.065119f}, +{0.0104927f,-0.270426f,-0.0588143f},{0.016901f,-0.277982f,-0.0457157f},{0.0198712f,-0.281485f,-0.0389474f}, +{0.0226803f,-0.284797f,-0.0320505f},{0.0253251f,-0.287916f,-0.0250388f},{0.0322524f,-0.296084f,-0.00345334f}, +{0.0326166f,-0.296513f,-0.00369814f},{0.034591f,-0.298841f,0.00365355f},{0.0342218f,-0.298406f,0.00387953f}, +{0.0360209f,-0.300527f,0.0112584f},{0.0376501f,-0.302448f,0.0186698f},{0.0391106f,-0.304171f,0.0261007f}, +{0.0404039f,-0.305696f,0.0335382f},{0.0415324f,-0.307026f,0.04097f},{0.0424985f,-0.308165f,0.048384f}, +{0.0433052f,-0.309117f,0.0557688f},{0.0448054f,-0.310885f,0.0776416f},{0.0449434f,-0.310806f,0.0918925f}, +{-0.0956393f,-0.145282f,-0.146855f},{-0.0909094f,-0.150859f,-0.146081f},{-0.10033f,-0.139751f,-0.147398f}, +{-0.0861468f,-0.156475f,-0.145073f},{-0.0717315f,-0.173473f,-0.140576f},{-0.0669086f,-0.179159f,-0.138571f}, +{-0.0620899f,-0.184841f,-0.136307f},{-0.0617973f,-0.184807f,-0.136814f},{-0.0569805f,-0.190486f,-0.134283f}, +{-0.0572839f,-0.190508f,-0.133782f},{-0.0524989f,-0.19615f,-0.130993f},{-0.0477437f,-0.201757f,-0.127941f}, +{-0.0430272f,-0.207319f,-0.124624f},{-0.0383583f,-0.212824f,-0.121044f},{-0.0247272f,-0.228897f,-0.10875f}, +{-0.0243516f,-0.22896f,-0.109195f},{-0.019953f,-0.234147f,-0.104581f},{-0.0203383f,-0.234072f,-0.104146f}, +{-0.0160414f,-0.239139f,-0.0992979f},{-0.0118447f,-0.244087f,-0.0942128f},{6.43211e-005f,-0.25813f,-0.0776135f}, +{0.000494926f,-0.258258f,-0.0779897f},{0.00422115f,-0.262651f,-0.0720263f},{0.0037823f,-0.262514f,-0.0716633f}, +{0.00736317f,-0.266736f,-0.0655221f},{0.0108009f,-0.27079f,-0.0592012f},{0.0202036f,-0.281877f,-0.0392833f}, +{0.0206789f,-0.282057f,-0.0395744f},{0.0235014f,-0.285386f,-0.0326445f},{0.0230198f,-0.285197f,-0.0323688f}, +{0.0256714f,-0.288324f,-0.025339f},{0.0281559f,-0.291253f,-0.0182083f},{0.0304713f,-0.293984f,-0.01099f}, +{0.0363947f,-0.300968f,0.0110514f},{0.0380281f,-0.302894f,0.0184819f},{0.0385429f,-0.303122f,0.0183189f}, +{0.0400104f,-0.304852f,0.0257854f},{0.0394923f,-0.304621f,0.0259318f},{0.040789f,-0.30615f,0.0333884f}, +{0.0419203f,-0.307484f,0.0408392f},{0.0428889f,-0.308626f,0.0482723f},{0.0436977f,-0.309579f,0.0556761f}, +{0.0454092f,-0.311597f,0.0847878f},{0.0452527f,-0.311466f,0.0918925f},{0.0450535f,-0.311155f,0.0918925f}, +{-0.0954211f,-0.14516f,-0.147384f},{-0.0906807f,-0.150749f,-0.14661f},{-0.100122f,-0.139616f,-0.147929f}, +{-0.0859076f,-0.156377f,-0.145599f},{-0.0811083f,-0.162036f,-0.144345f},{-0.07629f,-0.167718f,-0.142845f}, +{-0.0714602f,-0.173413f,-0.141092f},{-0.0666266f,-0.179112f,-0.139082f},{-0.052185f,-0.196141f,-0.131488f}, +{-0.0470397f,-0.201621f,-0.128748f},{-0.0474192f,-0.20176f,-0.128429f},{-0.0426922f,-0.207334f,-0.125105f}, +{-0.0380129f,-0.212852f,-0.121517f},{-0.0333903f,-0.218302f,-0.117667f},{-0.0288337f,-0.223675f,-0.113559f}, +{-0.0152209f,-0.239139f,-0.1f},{-0.0156465f,-0.239225f,-0.0997223f},{-0.0114405f,-0.244184f,-0.0946258f}, +{-0.00734311f,-0.249016f,-0.0892991f},{-0.00336217f,-0.25371f,-0.0837506f},{0.0082696f,-0.266838f,-0.0661002f}, +{0.00780997f,-0.266883f,-0.0658715f},{0.0112554f,-0.270946f,-0.0595366f},{0.0145518f,-0.274833f,-0.0530336f}, +{0.0176944f,-0.278538f,-0.0463752f},{0.0266451f,-0.288505f,-0.0257695f},{0.0261589f,-0.288519f,-0.0255992f}, +{0.0286488f,-0.291455f,-0.0184526f},{0.0309694f,-0.294191f,-0.0112184f},{0.0331194f,-0.296727f,-0.00391029f}, +{0.0350983f,-0.29906f,0.00345771f},{0.0369059f,-0.301191f,0.0108719f},{0.04131f,-0.306384f,0.0332586f}, +{0.0429537f,-0.307735f,0.0406518f},{0.0424438f,-0.307721f,0.0407259f},{0.0434146f,-0.308866f,0.0481755f}, +{0.0442252f,-0.309822f,0.0555957f},{0.0448791f,-0.310593f,0.0629755f},{0.0457325f,-0.311599f,0.0775733f}, +{0.045844f,-0.311876f,0.0918925f},{0.0455195f,-0.311707f,0.0918925f},{-0.109024f,-0.128391f,-0.148751f}, +{-0.0951111f,-0.144938f,-0.147731f},{-0.0903639f,-0.150535f,-0.146955f},{-0.0855838f,-0.156172f,-0.145943f}, +{-0.0807776f,-0.161839f,-0.144688f},{-0.0759523f,-0.167529f,-0.143185f},{-0.0711155f,-0.173232f,-0.141429f}, +{-0.0662749f,-0.17894f,-0.139417f},{-0.0614385f,-0.184642f,-0.137145f},{-0.0566148f,-0.19033f,-0.134611f}, +{-0.0518123f,-0.195993f,-0.131812f},{-0.0419583f,-0.207002f,-0.125571f},{-0.0374085f,-0.211835f,-0.122344f}, +{-0.0372689f,-0.212532f,-0.121975f},{-0.0423058f,-0.207202f,-0.125419f},{-0.0376197f,-0.212728f,-0.121826f}, +{-0.0329904f,-0.218187f,-0.117971f},{-0.0284272f,-0.223567f,-0.113856f},{-0.0239386f,-0.22886f,-0.109486f}, +{-0.0195336f,-0.234054f,-0.104866f},{-0.0110088f,-0.244106f,-0.0948962f},{-0.0106394f,-0.243932f,-0.0950266f}, +{-0.00690545f,-0.248944f,-0.0895618f},{-0.00291873f,-0.253645f,-0.0840052f},{0.000943949f,-0.2582f,-0.0782359f}, +{0.00467558f,-0.2626f,-0.072264f},{0.0121053f,-0.270751f,-0.059862f},{0.0152714f,-0.273952f,-0.0542297f}, +{0.0154088f,-0.274646f,-0.053345f},{0.01172f,-0.270906f,-0.059756f},{0.0150212f,-0.274799f,-0.0532437f}, +{0.0181684f,-0.27851f,-0.0465757f},{0.0211572f,-0.282034f,-0.039765f},{0.0239838f,-0.285367f,-0.0328251f}, +{0.0291386f,-0.291445f,-0.0186126f},{0.0318617f,-0.294046f,-0.0114399f},{0.0314626f,-0.294185f,-0.0113678f}, +{0.0336157f,-0.296724f,-0.00404916f},{0.0355975f,-0.299061f,0.00332952f},{0.0374077f,-0.301196f,0.0107545f}, +{0.0390471f,-0.303129f,0.0182123f},{0.0405167f,-0.304862f,0.0256896f},{0.0418182f,-0.306396f,0.0331736f}, +{0.0439258f,-0.308881f,0.0481121f},{0.0447376f,-0.309839f,0.0555431f},{0.0453925f,-0.310611f,0.0629336f}, +{-0.0948004f,-0.144694f,-0.147899f},{-0.0900499f,-0.150296f,-0.147122f},{-0.0852665f,-0.155936f,-0.146109f}, +{-0.0804569f,-0.161607f,-0.144853f},{-0.0756283f,-0.167301f,-0.143349f},{-0.0707881f,-0.173008f,-0.141592f}, +{-0.0659441f,-0.17872f,-0.139579f},{-0.0611044f,-0.184426f,-0.137305f},{-0.0562773f,-0.190118f,-0.134769f}, +{-0.0514714f,-0.195785f,-0.131968f},{-0.0466954f,-0.201416f,-0.128902f},{-0.0326364f,-0.217994f,-0.118117f}, +{-0.0280699f,-0.223379f,-0.114f},{-0.0235782f,-0.228675f,-0.109627f},{-0.0191702f,-0.233873f,-0.105003f}, +{-0.0148544f,-0.238961f,-0.100134f},{-0.0140188f,-0.239415f,-0.0995149f},{-0.00653318f,-0.248773f,-0.0896885f}, +{-0.00254368f,-0.253477f,-0.0841281f},{0.0013217f,-0.258035f,-0.0783547f},{0.00505593f,-0.262438f,-0.0723786f}, +{0.00865246f,-0.266679f,-0.0662105f},{0.0185582f,-0.278359f,-0.0466724f},{0.021549f,-0.281886f,-0.039857f}, +{0.0243776f,-0.285221f,-0.0329122f},{0.0270408f,-0.288362f,-0.0258517f},{0.0295361f,-0.291304f,-0.0186898f}, +{0.0300372f,-0.291363f,-0.0180672f},{0.0340163f,-0.296587f,-0.00411618f},{0.0359994f,-0.298925f,0.00326766f}, +{0.0378109f,-0.301061f,0.0106978f},{0.0394515f,-0.302996f,0.0181608f},{0.0409221f,-0.30473f,0.0256434f}, +{0.0422245f,-0.306265f,0.0331326f},{0.0433608f,-0.307605f,0.040616f},{0.0443336f,-0.308752f,0.0480815f}, +{0.0451459f,-0.30971f,0.0555177f},{0.0458013f,-0.310483f,0.0629134f},{0.0463034f,-0.311075f,0.0702583f}, +{0.0466565f,-0.311491f,0.0775425f},{-0.0947f,-0.14428f,-0.147965f},{-0.0901089f,-0.149694f,-0.147226f}, +{-0.0855339f,-0.155088f,-0.146277f},{-0.080979f,-0.160459f,-0.145118f},{-0.0764484f,-0.165802f,-0.143752f}, +{-0.071946f,-0.17111f,-0.142179f},{-0.0674757f,-0.176382f,-0.1404f},{-0.0630415f,-0.18161f,-0.138417f}, +{-0.0586471f,-0.186792f,-0.136232f},{-0.0542966f,-0.191922f,-0.133846f},{-0.0499938f,-0.196995f,-0.131262f}, +{-0.0457424f,-0.202008f,-0.128482f},{-0.0415461f,-0.206956f,-0.125509f},{-0.0333335f,-0.21664f,-0.118992f}, +{-0.0293246f,-0.221367f,-0.115454f},{-0.0253853f,-0.226012f,-0.111734f},{-0.0215189f,-0.230571f,-0.107835f}, +{-0.017729f,-0.23504f,-0.103761f},{-0.0103917f,-0.243691f,-0.0951008f},{-0.0068508f,-0.247867f,-0.0905224f}, +{-0.00339908f,-0.251937f,-0.0857837f},{-3.97542e-005f,-0.255898f,-0.080889f},{0.00322425f,-0.259746f,-0.0758426f}, +{0.00639008f,-0.263479f,-0.0706488f},{0.00945498f,-0.267093f,-0.0653124f},{0.0124163f,-0.270585f,-0.0598376f}, +{0.0180177f,-0.27719f,-0.0484934f},{0.0206528f,-0.280297f,-0.042634f},{0.0231745f,-0.283271f,-0.0366563f}, +{0.0255806f,-0.286108f,-0.0305656f},{0.0278688f,-0.288806f,-0.0243674f},{0.0320839f,-0.293776f,-0.0116704f}, +{0.0340071f,-0.296044f,-0.00518257f},{0.0358052f,-0.298164f,0.00139061f},{0.0374764f,-0.300134f,0.00804317f}, +{0.0390194f,-0.301954f,0.0147693f},{0.0404328f,-0.30362f,0.0215631f},{0.0417153f,-0.305133f,0.0284189f}, +{0.0428659f,-0.306489f,0.0353305f},{0.0438836f,-0.307689f,0.0422916f},{0.0447673f,-0.308731f,0.0492962f}, +{0.0455164f,-0.309615f,0.0563382f},{0.0461302f,-0.310339f,0.0634117f},{0.0466082f,-0.310902f,0.0705101f}, +{0.0469499f,-0.311305f,0.0776272f},{0.0471551f,-0.311547f,0.0847567f},{-0.259174f,0.0496576f,0.0428677f}, +{-0.260195f,0.0503292f,0.0485758f},{-0.259233f,0.0491951f,0.0411945f},{-0.251955f,0.040613f,0.00426646f}, +{-0.25119f,0.0402427f,0.00244165f},{-0.252842f,0.0421904f,0.00901696f},{-0.261646f,0.0520403f,0.0632405f}, +{-0.262143f,0.0526258f,0.0705025f},{-0.262055f,0.0519124f,0.0632202f},{-0.260788f,0.0515606f,0.0567511f}, +{-0.261395f,0.052276f,0.0637424f},{-0.263623f,0.0531732f,0.084822f},{-0.263855f,0.0533019f,0.0918925f}, +{-0.264154f,0.05342f,0.0848062f},{-0.263066f,0.0525171f,0.0704561f},{-0.262569f,0.0519303f,0.0631783f}, +{-0.262552f,0.0524983f,0.0704874f},{-0.264551f,0.053888f,0.084788f},{-0.264756f,0.0543717f,0.0918925f}, +{-0.264708f,0.0544524f,0.0847723f},{-0.263596f,0.0527624f,0.0704083f},{-0.263098f,0.0521743f,0.0631143f}, +{-0.264451f,0.0553469f,0.084757f},{-0.264242f,0.0551011f,0.0775429f},{-0.264643f,0.0549636f,0.084762f}, +{-0.264774f,0.0547312f,0.0918925f},{-0.264284f,0.055683f,0.0918925f},{-0.264532f,0.055409f,0.0918925f}, +{-0.264011f,0.0553606f,0.0776267f},{-0.260998f,0.0512763f,0.0559281f},{-0.260048f,0.0506876f,0.0497909f}, +{-0.264216f,0.0556025f,0.0847564f},{-0.257031f,0.0471307f,0.0291561f},{-0.25811f,0.0478703f,0.0337954f}, +{-0.256822f,0.046352f,0.0263905f},{-0.258169f,0.0484716f,0.0359874f},{-0.255368f,0.0446375f,0.0189921f}, +{-0.255764f,0.0456359f,0.0223799f},{-0.253746f,0.0427249f,0.0116131f},{-0.254367f,0.0439887f,0.015665f}, +{-0.249995f,0.038301f,-0.00303443f},{-0.249413f,0.0381472f,-0.0040552f},{-0.245565f,0.0330777f,-0.0174445f}, +{-0.243098f,0.0301686f,-0.0245261f},{-0.243346f,0.0309933f,-0.0230172f},{-0.247864f,0.035789f,-0.010276f}, +{-0.236214f,0.0225835f,-0.0410717f},{-0.238706f,0.0255224f,-0.0351634f},{-0.237668f,0.0237661f,-0.0383731f}, +{-0.241084f,0.0283265f,-0.0291434f},{-0.230895f,0.0163118f,-0.0525327f},{-0.231597f,0.0166077f,-0.051709f}, +{-0.228331f,0.0127563f,-0.0581524f},{-0.234711f,0.0202793f,-0.0451116f},{-0.222116f,0.00596108f,-0.0687612f}, +{-0.221361f,0.00453797f,-0.0705281f},{-0.218987f,0.00227149f,-0.0738946f},{-0.224917f,0.00873094f,-0.0644294f}, +{-0.209029f,-0.00947042f,-0.088404f},{-0.212441f,-0.00544764f,-0.0837203f},{-0.209902f,-0.00897324f,-0.0876434f}, +{-0.215761f,-0.00153252f,-0.0788824f},{-0.213847f,-0.00432202f,-0.0821454f},{-0.198277f,-0.0221483f,-0.101489f}, +{-0.201675f,-0.0186748f,-0.0979716f},{-0.197407f,-0.0237065f,-0.102786f},{-0.205842f,-0.0137605f,-0.0929216f}, +{-0.188607f,-0.0340827f,-0.111682f},{-0.186816f,-0.0356624f,-0.113046f},{-0.19071f,-0.0310714f,-0.109369f}, +{-0.194531f,-0.0265653f,-0.105516f},{-0.174737f,-0.0499058f,-0.122984f},{-0.178826f,-0.0450837f,-0.119856f}, +{-0.174876f,-0.0502744f,-0.123123f},{-0.184092f,-0.0394068f,-0.115753f},{-0.170192f,-0.0557971f,-0.126416f}, +{-0.166387f,-0.0597511f,-0.12867f},{-0.170589f,-0.0547964f,-0.125923f},{-0.155946f,-0.0725956f,-0.134725f}, +{-0.157835f,-0.0698361f,-0.133582f},{-0.160718f,-0.066968f,-0.132217f},{-0.162134f,-0.0647658f,-0.131224f}, +{-0.16547f,-0.0613651f,-0.129448f},{-0.149108f,-0.0801253f,-0.137702f},{-0.15116f,-0.078238f,-0.136973f}, +{-0.146371f,-0.0838855f,-0.138964f},{-0.153491f,-0.0749575f,-0.135742f},{-0.14024f,-0.0905825f,-0.141015f}, +{-0.141585f,-0.0895285f,-0.140701f},{-0.136811f,-0.0951581f,-0.142188f},{-0.14469f,-0.0853352f,-0.13946f}, +{-0.13126f,-0.101171f,-0.143511f},{-0.135762f,-0.0958627f,-0.142366f},{-0.132055f,-0.100766f,-0.14343f}, +{-0.123467f,-0.112469f,-0.146244f},{-0.123249f,-0.112347f,-0.145714f},{-0.127956f,-0.106796f,-0.144944f}, +{-0.113356f,-0.122814f,-0.146058f},{-0.11765f,-0.117219f,-0.145701f},{-0.11797f,-0.117374f,-0.145739f}, +{-0.113092f,-0.122593f,-0.146015f},{-0.122628f,-0.111881f,-0.145199f},{-0.127326f,-0.106343f,-0.144432f}, +{-0.122939f,-0.112125f,-0.145367f},{-0.1222f,-0.111854f,-0.145179f},{-0.126738f,-0.106503f,-0.144449f}, +{-0.141909f,-0.0897564f,-0.140865f},{-0.137462f,-0.0955874f,-0.142696f},{-0.137131f,-0.09539f,-0.142353f}, +{-0.128185f,-0.106906f,-0.145472f},{-0.12764f,-0.106582f,-0.144599f},{-0.123503f,-0.112427f,-0.146855f}, +{-0.118812f,-0.117958f,-0.147398f},{-0.118788f,-0.117986f,-0.146786f},{-0.123077f,-0.111962f,-0.147732f}, +{-0.118369f,-0.117514f,-0.148277f},{-0.123347f,-0.112232f,-0.147385f},{-0.113989f,-0.123265f,-0.148251f}, +{-0.113706f,-0.123012f,-0.148599f},{-0.113408f,-0.122753f,-0.148767f},{-0.113146f,-0.12253f,-0.14881f}, +{-0.151491f,-0.078458f,-0.137135f},{-0.193049f,-0.0288458f,-0.107358f},{-0.182854f,-0.0403346f,-0.116543f}, +{-0.179512f,-0.0448075f,-0.119568f},{-0.188965f,-0.0342715f,-0.111826f},{-0.201945f,-0.0178243f,-0.097292f}, +{-0.205529f,-0.0135971f,-0.0929291f},{-0.217669f,0.000184436f,-0.076437f},{-0.225146f,0.00953304f,-0.0634867f}, +{-0.214222f,-0.00448977f,-0.0822683f},{-0.214665f,-0.00455427f,-0.0825229f},{-0.210712f,-0.00921558f,-0.0880327f}, +{-0.228073f,0.0129843f,-0.0580755f},{-0.233609f,0.0195124f,-0.0468631f},{-0.245489f,0.0335205f,-0.0167902f}, +{-0.247512f,0.0359058f,-0.0104677f},{-0.240464f,0.0270637f,-0.0315068f},{-0.232454f,0.0164208f,-0.0520204f}, +{-0.2351f,0.0201289f,-0.0452083f},{-0.235574f,0.0201004f,-0.0454087f},{-0.25415f,0.0425904f,0.0115564f}, +{-0.261867f,0.052833f,0.0707584f},{-0.264446f,0.0537122f,0.0918925f},{-0.262205f,0.0532313f,0.0777929f}, +{-0.262492f,0.0530375f,0.0777045f},{-0.263108f,0.0531535f,0.0848323f},{-0.263495f,0.053223f,0.0918925f}, +{-0.262408f,0.0534704f,0.0848396f},{-0.262698f,0.0532806f,0.0848373f},{-0.262786f,0.053351f,0.0918925f}, +{-0.263135f,0.0532409f,0.0918925f},{-0.262476f,0.0535502f,0.0918925f},{-0.26418f,0.0534707f,0.0918925f}, +{-0.264646f,0.0540229f,0.0918925f},{-0.262902f,0.0529103f,0.0776945f},{-0.261407f,0.0511478f,0.0559028f}, +{-0.260603f,0.0502f,0.0485453f},{-0.259641f,0.0490651f,0.0411587f},{-0.258516f,0.0477394f,0.0337544f}, +{-0.257228f,0.04622f,0.0263442f},{-0.255773f,0.0445043f,0.0189407f},{-0.252856f,0.0404782f,0.00407642f}, +{-0.250891f,0.0381612f,-0.00324031f},{-0.252357f,0.040477f,0.00420461f},{-0.250395f,0.0381634f,-0.00310144f}, +{-0.248263f,0.0356496f,-0.0103481f},{-0.245962f,0.0329364f,-0.0175217f},{-0.243493f,0.0300252f,-0.0246083f}, +{-0.240858f,0.0269181f,-0.0315939f},{-0.23806f,0.0236182f,-0.038465f},{-0.231984f,0.0164547f,-0.0518103f}, +{-0.228716f,0.0126006f,-0.0582583f},{-0.2253f,0.00857242f,-0.0645398f},{-0.221741f,0.00437648f,-0.0706427f}, +{-0.218046f,1.98718e-005f,-0.0765558f},{-0.210275f,-0.00914426f,-0.0877701f},{-0.206212f,-0.0139349f,-0.093052f}, +{-0.202041f,-0.0188527f,-0.0981056f},{-0.197771f,-0.0238879f,-0.102923f},{-0.193409f,-0.0290309f,-0.107499f}, +{-0.175945f,-0.050591f,-0.12407f},{-0.180256f,-0.0451276f,-0.120026f},{-0.180601f,-0.0451f,-0.120499f}, +{-0.184446f,-0.0395993f,-0.1159f},{-0.179863f,-0.0450038f,-0.119717f},{-0.175223f,-0.0504746f,-0.123274f}, +{-0.170536f,-0.0560012f,-0.126571f},{-0.165811f,-0.0615731f,-0.129604f},{-0.161056f,-0.0671799f,-0.132375f}, +{-0.15628f,-0.0728116f,-0.134885f},{-0.146698f,-0.0841094f,-0.139127f},{-0.142247f,-0.0899456f,-0.141206f}, +{-0.132373f,-0.101001f,-0.143596f},{-0.118277f,-0.117621f,-0.145907f},{-0.11366f,-0.123065f,-0.146226f}, +{-0.264435f,0.054718f,0.0775529f},{-0.263416f,0.0529297f,0.0776737f},{-0.261919f,0.0511646f,0.0558501f}, +{-0.261114f,0.0502154f,0.0484819f},{-0.26015f,0.0490789f,0.0410845f},{-0.259025f,0.0477513f,0.0336694f}, +{-0.257734f,0.0462296f,0.0262484f},{-0.256277f,0.0445114f,0.018834f},{-0.254651f,0.0425947f,0.011439f}, +{-0.248756f,0.0356438f,-0.0104976f},{-0.249254f,0.0358515f,-0.0107259f},{-0.246945f,0.0331282f,-0.017926f}, +{-0.246452f,0.0329266f,-0.0176816f},{-0.243979f,0.0300111f,-0.0247786f},{-0.241341f,0.0268995f,-0.0317744f}, +{-0.238538f,0.0235948f,-0.0386556f},{-0.226206f,0.0086742f,-0.0651178f},{-0.226506f,0.0090273f,-0.065521f}, +{-0.222925f,0.00480505f,-0.0716622f},{-0.22918f,0.0125611f,-0.0584778f},{-0.225759f,0.008527f,-0.0647685f}, +{-0.222196f,0.00432493f,-0.0708804f},{-0.218495f,-3.80402e-005f,-0.0768021f},{-0.202862f,-0.0188522f,-0.0988077f}, +{-0.203101f,-0.0185698f,-0.0992973f},{-0.198804f,-0.0236366f,-0.104145f},{-0.206643f,-0.0140133f,-0.0933224f}, +{-0.202467f,-0.0189382f,-0.0983834f},{-0.19819f,-0.0239808f,-0.103208f},{-0.193822f,-0.0291313f,-0.10779f}, +{-0.189371f,-0.0343795f,-0.112123f},{-0.184846f,-0.0397152f,-0.116203f},{-0.17561f,-0.0506063f,-0.123589f}, +{-0.170916f,-0.056141f,-0.12689f},{-0.166183f,-0.061721f,-0.129928f},{-0.161421f,-0.0673361f,-0.132703f}, +{-0.156638f,-0.072976f,-0.135216f},{-0.151843f,-0.0786306f,-0.137469f},{-0.147043f,-0.0842903f,-0.139465f}, +{-0.132696f,-0.101207f,-0.14394f},{-0.114166f,-0.123436f,-0.147719f},{-0.118581f,-0.117851f,-0.146255f}, +{-0.113957f,-0.123303f,-0.146574f},{-0.262447f,0.0514069f,0.0557698f},{-0.263947f,0.0531759f,0.077642f}, +{-0.26164f,0.0504556f,0.0483851f},{-0.26203f,0.050916f,0.0482734f},{-0.261062f,0.0497739f,0.0408405f}, +{-0.260674f,0.0493165f,0.0409712f},{-0.259545f,0.047986f,0.0335395f},{-0.258252f,0.0464609f,0.026102f}, +{-0.256792f,0.0447389f,0.0186711f},{-0.255163f,0.0428179f,0.0112596f},{-0.253364f,0.0406967f,0.00388058f}, +{-0.251394f,0.0383745f,-0.00345247f},{-0.244467f,0.0302062f,-0.0250388f},{-0.244813f,0.0306146f,-0.025339f}, +{-0.242162f,0.0274881f,-0.0323684f},{-0.241822f,0.0270877f,-0.0320502f},{-0.239013f,0.0237756f,-0.0389468f}, +{-0.236043f,0.0202734f,-0.0457149f},{-0.232916f,0.0165856f,-0.0523413f},{-0.229635f,0.0127173f,-0.0588132f}, +{-0.222634f,0.00446276f,-0.0712434f},{-0.218926f,9.00519e-005f,-0.0771783f},{-0.215087f,-0.00443625f,-0.0829118f}, +{-0.211125f,-0.00910795f,-0.088434f},{-0.207048f,-0.0139163f,-0.0937354f},{-0.198575f,-0.0239061f,-0.103643f}, +{-0.194198f,-0.0290681f,-0.108235f},{-0.189737f,-0.034328f,-0.112578f},{-0.185202f,-0.0396756f,-0.116668f}, +{-0.17124f,-0.056138f,-0.127378f},{-0.171399f,-0.0559513f,-0.127941f},{-0.166644f,-0.0615582f,-0.130993f}, +{-0.166497f,-0.0617305f,-0.130423f},{-0.161725f,-0.0673581f,-0.133204f},{-0.156931f,-0.0730105f,-0.135723f}, +{-0.152125f,-0.0786778f,-0.137981f},{-0.147314f,-0.0843501f,-0.139981f},{-0.142507f,-0.090018f,-0.141725f}, +{-0.137712f,-0.0956724f,-0.143219f},{-0.132936f,-0.101305f,-0.144466f},{-0.114154f,-0.12345f,-0.147106f}, +{-0.263992f,0.0532287f,0.0703531f},{-0.263492f,0.0526391f,0.0630404f},{-0.264343f,0.0536432f,0.0776054f}, +{-0.262839f,0.0518697f,0.055677f},{-0.259931f,0.04844f,0.0333897f},{-0.258634f,0.046911f,0.0259331f}, +{-0.25717f,0.0451846f,0.0184831f},{-0.25731f,0.0457297f,0.0183202f},{-0.255673f,0.0437995f,0.0108731f}, +{-0.255536f,0.0432587f,0.0110526f},{-0.253733f,0.041132f,0.00365461f},{-0.251758f,0.0388039f,-0.00369726f}, +{-0.249613f,0.0362743f,-0.0109894f},{-0.247298f,0.0335441f,-0.0182079f},{-0.239346f,0.0241674f,-0.0392827f}, +{-0.239446f,0.0246659f,-0.0395738f},{-0.236462f,0.0211469f,-0.0463744f},{-0.236368f,0.0206563f,-0.0460682f}, +{-0.233232f,0.016959f,-0.0527117f},{-0.229943f,0.0130808f,-0.0592001f},{-0.219207f,0.000421111f,-0.0776124f}, +{-0.219263f,0.000866864f,-0.0779886f},{-0.215406f,-0.00368113f,-0.0837496f},{-0.215358f,-0.00411681f,-0.0833607f}, +{-0.211386f,-0.0088005f,-0.088897f},{-0.207298f,-0.0136212f,-0.094212f},{-0.194415f,-0.0288119f,-0.108749f}, +{-0.194416f,-0.028431f,-0.109195f},{-0.189934f,-0.0337161f,-0.113558f},{-0.189943f,-0.0340853f,-0.113103f}, +{-0.185396f,-0.0394466f,-0.117203f},{-0.180784f,-0.044885f,-0.121044f},{-0.176115f,-0.0503901f,-0.124624f}, +{-0.161859f,-0.0672002f,-0.133782f},{-0.157053f,-0.0728671f,-0.136307f},{-0.156971f,-0.0725841f,-0.136814f}, +{-0.152141f,-0.0782785f,-0.139083f},{-0.152234f,-0.078549f,-0.138571f},{-0.147411f,-0.0842358f,-0.140576f}, +{-0.142592f,-0.0899183f,-0.142325f},{-0.137784f,-0.0955872f,-0.143823f},{-0.132996f,-0.101234f,-0.145073f}, +{-0.128233f,-0.10685f,-0.146082f},{-0.264147f,0.0537916f,0.0703053f},{-0.263646f,0.0532007f,0.0629764f}, +{-0.2645f,0.0542071f,0.0775737f},{-0.262992f,0.0524296f,0.0555966f},{-0.262181f,0.0514738f,0.0481766f}, +{-0.261211f,0.0503292f,0.0407271f},{-0.260077f,0.0489923f,0.0332599f},{-0.258777f,0.04746f,0.0257867f}, +{-0.253865f,0.0416681f,0.00345877f},{-0.251803f,0.0398241f,-0.00404829f},{-0.251887f,0.0393348f,-0.00390942f}, +{-0.249737f,0.0367997f,-0.0112177f},{-0.247416f,0.0340634f,-0.0184523f},{-0.244926f,0.0311274f,-0.0255992f}, +{-0.242269f,0.0279939f,-0.0326442f},{-0.233209f,0.0178991f,-0.0532427f},{-0.233319f,0.0174415f,-0.0530326f}, +{-0.230023f,0.0135546f,-0.0595354f},{-0.226578f,0.00949215f,-0.0658703f},{-0.222989f,0.00526052f,-0.0720252f}, +{-0.211283f,-0.00795507f,-0.0895609f},{-0.211425f,-0.00837522f,-0.0892982f},{-0.207327f,-0.0132066f,-0.0946251f}, +{-0.203121f,-0.0181662f,-0.0997217f},{-0.198815f,-0.0232443f,-0.10458f},{-0.185197f,-0.0387137f,-0.117971f}, +{-0.185377f,-0.0390894f,-0.117667f},{-0.180754f,-0.0445398f,-0.121517f},{-0.176075f,-0.0500571f,-0.125105f}, +{-0.171349f,-0.0556307f,-0.128429f},{-0.166583f,-0.06125f,-0.131488f},{-0.161787f,-0.0669045f,-0.134283f}, +{-0.147308f,-0.083978f,-0.141092f},{-0.142236f,-0.0893707f,-0.143185f},{-0.142478f,-0.089673f,-0.142845f}, +{-0.13766f,-0.0953545f,-0.144346f},{-0.13286f,-0.101014f,-0.145599f},{-0.128087f,-0.106642f,-0.14661f}, +{-0.118645f,-0.117775f,-0.147929f},{-0.264695f,0.0550917f,0.0918925f},{-0.264082f,0.0543019f,0.070274f}, +{-0.26358f,0.0537101f,0.0629344f},{-0.262925f,0.0529379f,0.055544f},{-0.262113f,0.0519807f,0.0481132f}, +{-0.261141f,0.0508345f,0.040653f},{-0.260006f,0.0494956f,0.0331749f},{-0.258704f,0.047961f,0.0256909f}, +{-0.257235f,0.0462282f,0.0182135f},{-0.255595f,0.0442953f,0.0107557f},{-0.253785f,0.0421608f,0.00333058f}, +{-0.249448f,0.0376562f,-0.0114393f},{-0.247098f,0.035418f,-0.0180677f},{-0.247122f,0.034914f,-0.0186894f}, +{-0.24965f,0.0372853f,-0.0113672f},{-0.247326f,0.034545f,-0.0186123f},{-0.244833f,0.0316048f,-0.0257695f}, +{-0.242172f,0.0284668f,-0.0328247f},{-0.239345f,0.0251339f,-0.0397644f},{-0.236356f,0.0216099f,-0.0465748f}, +{-0.229908f,0.0140066f,-0.0597549f},{-0.229692f,0.0143612f,-0.0598609f},{-0.226458f,0.00993819f,-0.066099f}, +{-0.222864f,0.00570042f,-0.0722628f},{-0.219132f,0.0013004f,-0.0782348f},{-0.21527f,-0.00325419f,-0.0840042f}, +{-0.206947f,-0.0124575f,-0.0950259f},{-0.203042f,-0.0165305f,-0.0995152f},{-0.202732f,-0.0174277f,-0.100133f}, +{-0.20718f,-0.0127935f,-0.0948954f},{-0.202967f,-0.0177602f,-0.0999994f},{-0.198655f,-0.0228457f,-0.104865f}, +{-0.19425f,-0.0280399f,-0.109486f},{-0.189761f,-0.0333327f,-0.113856f},{-0.180568f,-0.0441721f,-0.121826f}, +{-0.175628f,-0.0493872f,-0.125571f},{-0.175882f,-0.0496974f,-0.125419f},{-0.171149f,-0.055279f,-0.128748f}, +{-0.166376f,-0.0609065f,-0.131812f},{-0.161574f,-0.0665692f,-0.134611f},{-0.15675f,-0.072257f,-0.137145f}, +{-0.151914f,-0.0779597f,-0.139417f},{-0.147073f,-0.0836674f,-0.14143f},{-0.137411f,-0.0950605f,-0.144688f}, +{-0.132605f,-0.100728f,-0.145943f},{-0.127824f,-0.106364f,-0.146956f},{-0.263889f,0.0546847f,0.0702589f}, +{-0.263387f,0.0540926f,0.0629142f},{-0.262732f,0.0533198f,0.0555186f},{-0.261919f,0.0523619f,0.0480826f}, +{-0.260946f,0.0512149f,0.0406172f},{-0.25981f,0.0498751f,0.0331338f},{-0.258508f,0.0483394f,0.0256447f}, +{-0.257037f,0.0466054f,0.0181621f},{-0.255397f,0.0446711f,0.010699f},{-0.253585f,0.0425351f,0.00326873f}, +{-0.251602f,0.0401968f,-0.0041153f},{-0.244627f,0.0319717f,-0.0258517f},{-0.241964f,0.0288315f,-0.0329118f}, +{-0.239135f,0.0254964f,-0.0398563f},{-0.236144f,0.0219699f,-0.0466715f},{-0.232995f,0.0182565f,-0.0533441f}, +{-0.232332f,0.0180069f,-0.0542301f},{-0.226239f,0.01029f,-0.0662094f},{-0.222643f,0.0060493f,-0.0723775f}, +{-0.218908f,0.00164621f,-0.0783537f},{-0.215043f,-0.00291157f,-0.0841271f},{-0.211054f,-0.00761574f,-0.0896876f}, +{-0.198416f,-0.0225168f,-0.105003f},{-0.194008f,-0.0277146f,-0.109627f},{-0.189516f,-0.0330111f,-0.114f}, +{-0.18495f,-0.0383959f,-0.118117f},{-0.180317f,-0.043858f,-0.121975f},{-0.179652f,-0.0441102f,-0.122344f}, +{-0.170891f,-0.0549727f,-0.128902f},{-0.166115f,-0.0606041f,-0.131968f},{-0.161309f,-0.0662708f,-0.134769f}, +{-0.156482f,-0.0719626f,-0.137305f},{-0.151643f,-0.0776692f,-0.139579f},{-0.146799f,-0.083381f,-0.141593f}, +{-0.141958f,-0.0890883f,-0.143349f},{-0.13713f,-0.094782f,-0.144853f},{-0.13232f,-0.100453f,-0.146109f}, +{-0.127537f,-0.106094f,-0.147123f},{-0.122786f,-0.111695f,-0.147899f},{-0.118075f,-0.117251f,-0.148445f}, +{-0.263669f,0.0549577f,0.0705096f},{-0.263191f,0.0543941f,0.0634113f},{-0.262578f,0.0536704f,0.056338f}, +{-0.261828f,0.052787f,0.0492957f},{-0.260945f,0.0517449f,0.042291f},{-0.259927f,0.050545f,0.0353299f}, +{-0.258776f,0.0491883f,0.0284186f},{-0.257494f,0.047676f,0.0215629f},{-0.25608f,0.0460093f,0.0147688f}, +{-0.254537f,0.0441899f,0.00804257f},{-0.252866f,0.0422193f,0.00139006f},{-0.251068f,0.0400992f,-0.00518291f}, +{-0.249145f,0.0378314f,-0.0116708f},{-0.24493f,0.0328611f,-0.024368f},{-0.242641f,0.030163f,-0.0305661f}, +{-0.240235f,0.027326f,-0.0366566f},{-0.237714f,0.0243525f,-0.0426344f},{-0.235078f,0.0212452f,-0.0484939f}, +{-0.229477f,0.0146404f,-0.0598379f},{-0.226516f,0.0111487f,-0.0653124f},{-0.223451f,0.00753462f,-0.0706491f}, +{-0.220285f,0.00380161f,-0.0758429f},{-0.217021f,-4.71144e-005f,-0.0808893f},{-0.213662f,-0.00400817f,-0.0857839f}, +{-0.21021f,-0.0080781f,-0.0905225f},{-0.206669f,-0.0122535f,-0.095101f},{-0.199332f,-0.0209053f,-0.103761f}, +{-0.195542f,-0.025374f,-0.107835f},{-0.191675f,-0.029933f,-0.111734f},{-0.187736f,-0.0345782f,-0.115454f}, +{-0.183727f,-0.0393053f,-0.118992f},{-0.175515f,-0.0489888f,-0.125509f},{-0.171318f,-0.0539368f,-0.128482f}, +{-0.167067f,-0.0589499f,-0.131262f},{-0.162764f,-0.0640236f,-0.133846f},{-0.158413f,-0.0691534f,-0.136231f}, +{-0.154019f,-0.0743348f,-0.138417f},{-0.149585f,-0.0795634f,-0.1404f},{-0.145115f,-0.0848346f,-0.142179f}, +{-0.140612f,-0.0901436f,-0.143752f},{-0.136082f,-0.0954858f,-0.145118f},{-0.131527f,-0.100856f,-0.146276f}, +{-0.126952f,-0.106251f,-0.147225f},{-0.122361f,-0.111665f,-0.147964f},{-0.117757f,-0.117093f,-0.148493f}, +{-0.23861f,0.0259416f,-0.0398563f},{-0.235619f,0.0224151f,-0.0466715f},{-0.227862f,0.0148455f,-0.0592001f}, +{-0.224871f,0.0109392f,-0.0658703f},{-0.228317f,0.0150017f,-0.0595354f},{-0.244102f,0.032417f,-0.0258517f}, +{-0.241439f,0.0292768f,-0.0329118f},{-0.248923f,0.0381015f,-0.0114393f},{-0.246597f,0.0353593f,-0.0186894f}, +{-0.251077f,0.0406421f,-0.0041153f},{-0.25306f,0.0429804f,0.00326873f},{-0.254872f,0.0451164f,0.010699f}, +{-0.24803f,0.0382467f,-0.0112177f},{-0.248524f,0.0382409f,-0.0113672f},{-0.25018f,0.0407819f,-0.00390942f}, +{-0.256512f,0.0470507f,0.0181621f},{-0.257983f,0.0487847f,0.0256447f},{-0.259285f,0.0503203f,0.0331338f}, +{-0.260421f,0.0516601f,0.0406172f},{-0.261394f,0.0528072f,0.0480826f},{-0.262207f,0.053765f,0.0555186f}, +{-0.262862f,0.0545378f,0.0629142f},{-0.263364f,0.05513f,0.0702589f},{-0.262955f,0.0552575f,0.070274f}, +{-0.262453f,0.0546658f,0.0629344f},{-0.262173f,0.0537258f,0.0848373f},{-0.261981f,0.0541091f,0.0848323f}, +{-0.261916f,0.0546203f,0.084822f},{-0.261986f,0.054502f,0.0918925f},{-0.262228f,0.0538242f,0.0918925f}, +{-0.261967f,0.0534828f,0.0777045f},{-0.261618f,0.0530711f,0.0705025f},{-0.261425f,0.0534539f,0.0704874f}, +{-0.262441f,0.0552387f,0.0703053f},{-0.26194f,0.0546478f,0.0629764f},{-0.261411f,0.0544038f,0.0630404f}, +{-0.261286f,0.0538767f,0.0555966f},{-0.261911f,0.0549934f,0.0703531f},{-0.263717f,0.0555463f,0.0775429f}, +{-0.263265f,0.0560102f,0.0918925f},{-0.263001f,0.0558995f,0.0847723f},{-0.263516f,0.0559192f,0.084762f}, +{-0.262905f,0.0559313f,0.0918925f},{-0.26247f,0.0556527f,0.084788f},{-0.26258f,0.0557625f,0.0918925f}, +{-0.263625f,0.0559923f,0.0918925f},{-0.263926f,0.0557921f,0.084757f},{-0.263974f,0.0558822f,0.0918925f}, +{-0.262073f,0.0551847f,0.0848062f},{-0.262004f,0.0548614f,0.0918925f},{-0.23247f,0.0187017f,-0.0533441f}, +{-0.229167f,0.0148065f,-0.0598609f},{-0.225714f,0.0107353f,-0.0662094f},{-0.222117f,0.00649456f,-0.0723775f}, +{-0.218383f,0.00209146f,-0.0783537f},{-0.214518f,-0.00246632f,-0.0841271f},{-0.206053f,-0.0118379f,-0.0948954f}, +{-0.209719f,-0.00692815f,-0.0892982f},{-0.205621f,-0.0117596f,-0.0946251f},{-0.210528f,-0.00717049f,-0.0896876f}, +{-0.206422f,-0.0120123f,-0.0950259f},{-0.202207f,-0.0169825f,-0.100133f},{-0.197891f,-0.0220715f,-0.105003f}, +{-0.193483f,-0.0272694f,-0.109627f},{-0.188991f,-0.0325659f,-0.114f},{-0.184425f,-0.0379506f,-0.118117f}, +{-0.174369f,-0.04861f,-0.125105f},{-0.174034f,-0.0486253f,-0.124624f},{-0.169642f,-0.0541836f,-0.128429f}, +{-0.179792f,-0.0434128f,-0.121975f},{-0.175103f,-0.0489419f,-0.125571f},{-0.170366f,-0.0545275f,-0.128902f}, +{-0.16559f,-0.0601589f,-0.131968f},{-0.160784f,-0.0658256f,-0.134769f},{-0.155957f,-0.0715173f,-0.137305f}, +{-0.151118f,-0.077224f,-0.139579f},{-0.146274f,-0.0829357f,-0.141593f},{-0.141109f,-0.0884151f,-0.143185f}, +{-0.141433f,-0.088643f,-0.143349f},{-0.145946f,-0.0827118f,-0.14143f},{-0.136605f,-0.0943367f,-0.144853f}, +{-0.127012f,-0.105648f,-0.147123f},{-0.131478f,-0.0997722f,-0.145943f},{-0.126698f,-0.105409f,-0.146956f}, +{-0.121422f,-0.110662f,-0.146855f},{-0.121386f,-0.110704f,-0.146244f},{-0.116731f,-0.116193f,-0.147398f}, +{-0.135703f,-0.0938225f,-0.143823f},{-0.130915f,-0.099469f,-0.145073f},{-0.131154f,-0.0995666f,-0.145599f}, +{-0.121812f,-0.111169f,-0.145367f},{-0.121543f,-0.1109f,-0.145714f},{-0.126513f,-0.105627f,-0.144599f}, +{-0.112534f,-0.12211f,-0.146226f},{-0.107823f,-0.127372f,-0.146474f},{-0.112251f,-0.121856f,-0.146574f}, +{-0.116939f,-0.116328f,-0.147929f},{-0.12164f,-0.110785f,-0.147385f},{-0.108041f,-0.127557f,-0.146297f}, +{-0.112831f,-0.122369f,-0.146058f},{-0.108274f,-0.127755f,-0.146158f},{-0.126381f,-0.105195f,-0.14661f}, +{-0.126152f,-0.105085f,-0.146082f},{-0.117242f,-0.116558f,-0.148277f},{-0.12195f,-0.111006f,-0.147732f}, +{-0.131795f,-0.100008f,-0.146109f},{-0.122261f,-0.11125f,-0.147899f},{-0.117549f,-0.116805f,-0.148445f}, +{-0.112883f,-0.122308f,-0.148767f},{-0.108275f,-0.127755f,-0.148876f},{-0.262114f,0.0552103f,0.0918925f}, +{-0.263308f,0.0556736f,0.0775529f},{-0.261798f,0.0538935f,0.055544f},{-0.260986f,0.0529363f,0.0481132f}, +{-0.260014f,0.0517901f,0.040653f},{-0.258879f,0.0504512f,0.0331749f},{-0.257577f,0.0489167f,0.0256909f}, +{-0.256108f,0.0471839f,0.0182135f},{-0.254469f,0.0452509f,0.0107557f},{-0.252658f,0.0431164f,0.00333058f}, +{-0.250677f,0.0407797f,-0.00404829f},{-0.2462f,0.0355006f,-0.0186123f},{-0.243706f,0.0325604f,-0.0257695f}, +{-0.241045f,0.0294224f,-0.0328247f},{-0.238218f,0.0260895f,-0.0397644f},{-0.23523f,0.0225655f,-0.0465748f}, +{-0.232083f,0.0188547f,-0.0532427f},{-0.228781f,0.0149622f,-0.0597549f},{-0.225331f,0.0108938f,-0.066099f}, +{-0.221737f,0.00665604f,-0.0722628f},{-0.218006f,0.00225601f,-0.0782348f},{-0.214143f,-0.00229858f,-0.0840042f}, +{-0.210156f,-0.00699946f,-0.0895609f},{-0.201841f,-0.0168046f,-0.0999994f},{-0.197528f,-0.0218901f,-0.104865f}, +{-0.193123f,-0.0270843f,-0.109486f},{-0.188634f,-0.0323771f,-0.113856f},{-0.18407f,-0.0377581f,-0.117971f}, +{-0.179441f,-0.0432164f,-0.121826f},{-0.174756f,-0.0487418f,-0.125419f},{-0.170022f,-0.0543234f,-0.128748f}, +{-0.165249f,-0.0599509f,-0.131812f},{-0.160447f,-0.0656136f,-0.134611f},{-0.155623f,-0.0713014f,-0.137145f}, +{-0.150787f,-0.0770041f,-0.139417f},{-0.136284f,-0.0941049f,-0.144688f},{-0.135953f,-0.0939075f,-0.144346f}, +{-0.112579f,-0.122056f,-0.148599f},{-0.108037f,-0.127554f,-0.148751f},{-0.262793f,0.0556542f,0.0775737f}, +{-0.260475f,0.0529209f,0.0481766f},{-0.259504f,0.0517763f,0.0407271f},{-0.258371f,0.0504394f,0.0332599f}, +{-0.257071f,0.048907f,0.0257867f},{-0.255604f,0.0471768f,0.0183202f},{-0.253967f,0.0452466f,0.0108731f}, +{-0.252159f,0.0431152f,0.00345877f},{-0.24322f,0.0325744f,-0.0255992f},{-0.24571f,0.0355104f,-0.0184523f}, +{-0.245217f,0.0353088f,-0.0182079f},{-0.240562f,0.029441f,-0.0326442f},{-0.23774f,0.0261129f,-0.0395738f}, +{-0.234756f,0.022594f,-0.0463744f},{-0.231613f,0.0188886f,-0.0530326f},{-0.221283f,0.00670759f,-0.0720252f}, +{-0.217557f,0.00231394f,-0.0779886f},{-0.2137f,-0.00223406f,-0.0837496f},{-0.196723f,-0.0218719f,-0.104145f}, +{-0.196495f,-0.0221414f,-0.103643f},{-0.192334f,-0.0270471f,-0.108749f},{-0.201415f,-0.0167191f,-0.0997217f}, +{-0.197108f,-0.0217972f,-0.10458f},{-0.19271f,-0.0269839f,-0.109195f},{-0.188227f,-0.0322691f,-0.113558f}, +{-0.183671f,-0.0376423f,-0.117667f},{-0.179048f,-0.0430927f,-0.121517f},{-0.164877f,-0.0598029f,-0.131488f}, +{-0.160081f,-0.0654575f,-0.134283f},{-0.155264f,-0.071137f,-0.136814f},{-0.150435f,-0.0768314f,-0.139083f}, +{-0.145602f,-0.0825309f,-0.141092f},{-0.140772f,-0.088226f,-0.142845f},{-0.107472f,-0.127075f,-0.147687f}, +{-0.112085f,-0.121672f,-0.147719f},{-0.112074f,-0.121685f,-0.147106f},{-0.112283f,-0.121818f,-0.148251f}, +{-0.107827f,-0.127376f,-0.148558f},{-0.262314f,0.055521f,0.0918925f},{-0.262262f,0.055408f,0.0776054f}, +{-0.260758f,0.0536344f,0.055677f},{-0.25995f,0.0526807f,0.0482734f},{-0.257465f,0.0497507f,0.0335395f}, +{-0.256553f,0.0486758f,0.0259331f},{-0.25785f,0.0502047f,0.0333897f},{-0.258981f,0.0515387f,0.0408405f}, +{-0.255089f,0.0469493f,0.0184831f},{-0.253456f,0.0450234f,0.0110526f},{-0.251652f,0.0428967f,0.00365461f}, +{-0.249678f,0.0405686f,-0.00369726f},{-0.247532f,0.0380391f,-0.0109894f},{-0.239741f,0.0288524f,-0.0320502f}, +{-0.237265f,0.0259322f,-0.0392827f},{-0.240081f,0.0292528f,-0.0323684f},{-0.242732f,0.0323793f,-0.025339f}, +{-0.234287f,0.022421f,-0.0460682f},{-0.231151f,0.0187238f,-0.0527117f},{-0.220554f,0.00622748f,-0.0712434f}, +{-0.217126f,0.00218583f,-0.0776124f},{-0.220844f,0.00656977f,-0.0716622f},{-0.224425f,0.010792f,-0.065521f}, +{-0.213277f,-0.00235208f,-0.0833607f},{-0.209305f,-0.00703577f,-0.088897f},{-0.205217f,-0.0118565f,-0.094212f}, +{-0.20102f,-0.0168051f,-0.0992973f},{-0.187862f,-0.0323206f,-0.113103f},{-0.183315f,-0.0376819f,-0.117203f}, +{-0.178703f,-0.0431203f,-0.121044f},{-0.164417f,-0.0599658f,-0.130423f},{-0.159778f,-0.0654355f,-0.133782f}, +{-0.164563f,-0.0597934f,-0.130993f},{-0.169318f,-0.0541866f,-0.127941f},{-0.154972f,-0.0711024f,-0.136307f}, +{-0.150153f,-0.0767842f,-0.138571f},{-0.14533f,-0.0824711f,-0.140576f},{-0.140511f,-0.0881536f,-0.142325f}, +{-0.116874f,-0.116404f,-0.146255f},{-0.126104f,-0.105141f,-0.145472f},{-0.107534f,-0.127127f,-0.148015f}, +{-0.107655f,-0.12723f,-0.14831f},{-0.261515f,0.0545271f,0.0704083f},{-0.261866f,0.0549406f,0.077642f}, +{-0.261017f,0.053939f,0.0631143f},{-0.260366f,0.0531716f,0.0557698f},{-0.259559f,0.0522203f,0.0483851f}, +{-0.258593f,0.0510812f,0.0409712f},{-0.256171f,0.0482257f,0.026102f},{-0.251283f,0.0424614f,0.00388058f}, +{-0.253082f,0.0445826f,0.0112596f},{-0.252945f,0.0440418f,0.011439f},{-0.254711f,0.0465036f,0.0186711f}, +{-0.249313f,0.0401392f,-0.00345247f},{-0.247174f,0.0376162f,-0.0107259f},{-0.244864f,0.0348929f,-0.017926f}, +{-0.242386f,0.0319709f,-0.0250388f},{-0.230858f,0.0174103f,-0.0518103f},{-0.230748f,0.0178679f,-0.0520204f}, +{-0.233974f,0.0210845f,-0.0452083f},{-0.236932f,0.0255403f,-0.0389468f},{-0.233962f,0.0220381f,-0.0457149f}, +{-0.230835f,0.0183503f,-0.0523413f},{-0.227554f,0.014482f,-0.0588132f},{-0.224125f,0.0104389f,-0.0651178f}, +{-0.209148f,-0.00818865f,-0.0877701f},{-0.209006f,-0.00776851f,-0.0880327f},{-0.213095f,-0.00353415f,-0.0822683f}, +{-0.216845f,0.00185478f,-0.0771783f},{-0.213007f,-0.00267152f,-0.0829118f},{-0.209045f,-0.00734323f,-0.088434f}, +{-0.204967f,-0.0121516f,-0.0937354f},{-0.200781f,-0.0170875f,-0.0988077f},{-0.183121f,-0.0379109f,-0.116668f}, +{-0.187656f,-0.0325633f,-0.112578f},{-0.187665f,-0.0329324f,-0.112123f},{-0.192117f,-0.0273033f,-0.108235f}, +{-0.178521f,-0.0433353f,-0.120499f},{-0.173864f,-0.0488263f,-0.12407f},{-0.169159f,-0.0543733f,-0.127378f}, +{-0.159644f,-0.0655934f,-0.133204f},{-0.145233f,-0.0825854f,-0.139981f},{-0.150044f,-0.0769131f,-0.137981f}, +{-0.150137f,-0.0771835f,-0.137469f},{-0.15485f,-0.0712458f,-0.135723f},{-0.140427f,-0.0882533f,-0.141725f}, +{-0.135631f,-0.0939077f,-0.143219f},{-0.130855f,-0.0995398f,-0.144466f},{-0.12625f,-0.105349f,-0.144944f}, +{-0.116707f,-0.116221f,-0.146786f},{-0.26136f,0.0539641f,0.0704561f},{-0.26171f,0.0543767f,0.0776737f}, +{-0.260862f,0.0533774f,0.0631783f},{-0.260213f,0.0526117f,0.0558501f},{-0.259408f,0.0516625f,0.0484819f}, +{-0.258444f,0.0505259f,0.0410845f},{-0.257318f,0.0491984f,0.0336694f},{-0.256028f,0.0476767f,0.0262484f}, +{-0.254571f,0.0459585f,0.018834f},{-0.25123f,0.0414326f,0.00420461f},{-0.249268f,0.039119f,-0.00310144f}, +{-0.249185f,0.0396083f,-0.00324031f},{-0.25115f,0.0419253f,0.00407642f},{-0.24705f,0.0370909f,-0.0104976f}, +{-0.244746f,0.0343737f,-0.0176816f},{-0.242273f,0.0314582f,-0.0247786f},{-0.239634f,0.0283466f,-0.0317744f}, +{-0.236832f,0.0250418f,-0.0386556f},{-0.233868f,0.0215475f,-0.0454087f},{-0.227474f,0.0140082f,-0.0584778f}, +{-0.224053f,0.00997407f,-0.0647685f},{-0.220489f,0.005772f,-0.0708804f},{-0.216789f,0.00140903f,-0.0768021f}, +{-0.212959f,-0.0031072f,-0.0825229f},{-0.204937f,-0.0125662f,-0.0933224f},{-0.20076f,-0.0174911f,-0.0983834f}, +{-0.196484f,-0.0225337f,-0.103208f},{-0.192116f,-0.0276842f,-0.10779f},{-0.183319f,-0.0386437f,-0.1159f}, +{-0.178736f,-0.0440482f,-0.119717f},{-0.17855f,-0.0436805f,-0.120026f},{-0.18314f,-0.0382681f,-0.116203f}, +{-0.173903f,-0.0491593f,-0.123589f},{-0.169209f,-0.0546939f,-0.12689f},{-0.164477f,-0.060274f,-0.129928f}, +{-0.159715f,-0.065889f,-0.132703f},{-0.154932f,-0.0715289f,-0.135216f},{-0.145337f,-0.0828432f,-0.139465f}, +{-0.140782f,-0.0888008f,-0.140865f},{-0.136005f,-0.0944344f,-0.142353f},{-0.135756f,-0.0941403f,-0.142696f}, +{-0.140541f,-0.0884985f,-0.141206f},{-0.13099f,-0.0997599f,-0.14394f},{-0.107533f,-0.127126f,-0.147023f}, +{-0.107472f,-0.127074f,-0.147351f},{-0.262065f,0.0541415f,0.0918925f},{-0.261775f,0.0538659f,0.0776945f}, +{-0.260928f,0.052868f,0.0632202f},{-0.26028f,0.0521034f,0.0559028f},{-0.261121f,0.0524856f,0.0632405f}, +{-0.259476f,0.0511556f,0.0485453f},{-0.258514f,0.0500207f,0.0411587f},{-0.25739f,0.0486951f,0.0337544f}, +{-0.256101f,0.0471756f,0.0263442f},{-0.254646f,0.0454599f,0.0189407f},{-0.253023f,0.043546f,0.0115564f}, +{-0.24504f,0.033523f,-0.0174445f},{-0.247339f,0.0362343f,-0.010276f},{-0.247136f,0.0366052f,-0.0103481f}, +{-0.244835f,0.033892f,-0.0175217f},{-0.242366f,0.0309808f,-0.0246083f},{-0.239731f,0.0278737f,-0.0315939f}, +{-0.236933f,0.0245738f,-0.038465f},{-0.227806f,0.0132016f,-0.0581524f},{-0.227589f,0.0135563f,-0.0582583f}, +{-0.231072f,0.0170529f,-0.051709f},{-0.224173f,0.00952803f,-0.0645398f},{-0.220614f,0.0053321f,-0.0706427f}, +{-0.21692f,0.000975486f,-0.0765558f},{-0.205317f,-0.0133153f,-0.0929216f},{-0.20115f,-0.0182295f,-0.0979716f}, +{-0.205085f,-0.0129793f,-0.093052f},{-0.200914f,-0.017897f,-0.0981056f},{-0.196644f,-0.0229323f,-0.102923f}, +{-0.192282f,-0.0280753f,-0.107499f},{-0.187838f,-0.0333159f,-0.111826f},{-0.174351f,-0.0498292f,-0.123123f}, +{-0.174096f,-0.049519f,-0.123274f},{-0.178987f,-0.0443622f,-0.119568f},{-0.169409f,-0.0550456f,-0.126571f}, +{-0.164684f,-0.0606175f,-0.129604f},{-0.159929f,-0.0662243f,-0.132375f},{-0.155153f,-0.071856f,-0.134885f}, +{-0.150364f,-0.0775023f,-0.137135f},{-0.145571f,-0.0831538f,-0.139127f},{-0.131246f,-0.100046f,-0.143596f}, +{-0.117445f,-0.116929f,-0.145739f},{-0.122103f,-0.111436f,-0.145199f},{-0.117151f,-0.116666f,-0.145907f}, +{-0.107652f,-0.127227f,-0.146724f},{-0.260473f,0.0517215f,0.0559281f},{-0.25967f,0.0507744f,0.0485758f}, +{-0.258708f,0.0496403f,0.0411945f},{-0.257585f,0.0483156f,0.0337954f},{-0.256297f,0.0467972f,0.0263905f}, +{-0.254843f,0.0450828f,0.0189921f},{-0.253221f,0.0431702f,0.0116131f},{-0.25143f,0.0410583f,0.00426646f}, +{-0.249469f,0.0387463f,-0.00303443f},{-0.242572f,0.0306138f,-0.0245261f},{-0.239939f,0.027509f,-0.0315068f}, +{-0.237143f,0.0242113f,-0.0383731f},{-0.234186f,0.0207246f,-0.0451116f},{-0.224392f,0.00917619f,-0.0644294f}, +{-0.220836f,0.00498322f,-0.0705281f},{-0.217144f,0.000629689f,-0.076437f},{-0.213322f,-0.00387677f,-0.0821454f}, +{-0.209377f,-0.00852799f,-0.0876434f},{-0.196882f,-0.0232612f,-0.102786f},{-0.192524f,-0.0284006f,-0.107358f}, +{-0.188082f,-0.0336375f,-0.111682f},{-0.183567f,-0.0389616f,-0.115753f},{-0.169667f,-0.0553518f,-0.126416f}, +{-0.164945f,-0.0609198f,-0.129448f},{-0.160193f,-0.0665227f,-0.132217f},{-0.15542f,-0.0721504f,-0.134725f}, +{-0.150635f,-0.0777928f,-0.136973f},{-0.145846f,-0.0834402f,-0.138964f},{-0.14106f,-0.0890833f,-0.140701f}, +{-0.136286f,-0.0947129f,-0.142188f},{-0.13153f,-0.10032f,-0.14343f},{-0.126801f,-0.105897f,-0.144432f}, +{-0.00563681f,-0.247569f,-0.0892991f},{-0.0097342f,-0.242737f,-0.0946258f},{-0.00976382f,-0.242323f,-0.0942128f}, +{-0.0275449f,-0.222933f,-0.114f},{-0.0230532f,-0.22823f,-0.109627f},{-0.0321114f,-0.217549f,-0.118117f}, +{-0.0367439f,-0.212086f,-0.121975f},{-0.0414333f,-0.206557f,-0.125571f},{-0.0461704f,-0.200971f,-0.128902f}, +{-0.0509464f,-0.19534f,-0.131968f},{-0.0557523f,-0.189673f,-0.134769f},{-0.041179f,-0.206247f,-0.125419f}, +{-0.0457129f,-0.200313f,-0.128429f},{-0.0409859f,-0.205887f,-0.125105f},{-0.0605794f,-0.183981f,-0.137305f}, +{-0.0654191f,-0.178274f,-0.139579f},{-0.0702631f,-0.172563f,-0.141592f},{-0.0799319f,-0.161162f,-0.144853f}, +{-0.0751032f,-0.166855f,-0.143349f},{-0.0847415f,-0.155491f,-0.146109f},{-0.0895249f,-0.14985f,-0.147122f}, +{-0.0942754f,-0.144249f,-0.147899f},{-0.103705f,-0.13313f,-0.146057f},{-0.0939843f,-0.143982f,-0.147731f}, +{-0.0892371f,-0.14958f,-0.146955f},{-0.094433f,-0.144063f,-0.145199f},{-0.0941223f,-0.143819f,-0.145366f}, +{-0.0990912f,-0.13857f,-0.145739f},{-0.0888286f,-0.149094f,-0.146081f},{-0.0842013f,-0.15493f,-0.145599f}, +{-0.0889744f,-0.149302f,-0.14661f},{-0.103104f,-0.132641f,-0.146574f},{-0.102907f,-0.132494f,-0.147105f}, +{-0.103401f,-0.132879f,-0.146225f},{-0.0937148f,-0.143713f,-0.147384f},{-0.102895f,-0.132508f,-0.147719f}, +{-0.103653f,-0.133192f,-0.148767f},{-0.103355f,-0.132933f,-0.148599f},{-0.0989867f,-0.138694f,-0.148445f}, +{-0.103072f,-0.132679f,-0.148251f},{-0.0935584f,-0.143517f,-0.146855f},{-0.0186452f,-0.233427f,-0.105003f}, +{-0.0143294f,-0.238516f,-0.100134f},{-0.0101144f,-0.243486f,-0.0950266f},{-0.00600817f,-0.248328f,-0.0896885f}, +{-0.00201866f,-0.253032f,-0.0841281f},{0.00184672f,-0.25759f,-0.0783547f},{0.00558095f,-0.261993f,-0.0723786f}, +{0.0128468f,-0.269951f,-0.059756f},{0.00951627f,-0.265436f,-0.0658715f},{0.0129617f,-0.269499f,-0.0595366f}, +{0.00917748f,-0.266234f,-0.0662105f},{0.0126303f,-0.270305f,-0.059862f},{0.0159338f,-0.274201f,-0.053345f}, +{0.0190832f,-0.277914f,-0.0466724f},{0.022074f,-0.281441f,-0.039857f},{0.0249026f,-0.284776f,-0.0329122f}, +{0.0275658f,-0.287916f,-0.0258517f},{0.0326757f,-0.292744f,-0.0112184f},{0.0325522f,-0.292219f,-0.01099f}, +{0.0348257f,-0.295279f,-0.00391029f},{0.0300611f,-0.290859f,-0.0186898f},{0.0323867f,-0.293601f,-0.0114399f}, +{0.0345413f,-0.296141f,-0.00411618f},{0.0365244f,-0.29848f,0.00326766f},{0.0383359f,-0.300616f,0.0106978f}, +{0.0399765f,-0.30255f,0.0181608f},{0.0414471f,-0.304284f,0.0256434f},{0.0427495f,-0.30582f,0.0331326f}, +{0.0440805f,-0.306779f,0.0406518f},{0.0438858f,-0.30716f,0.040616f},{0.042945f,-0.305441f,0.0331736f}, +{0.0448586f,-0.308307f,0.0480815f},{0.0476467f,-0.310397f,0.0847721f},{0.0472826f,-0.309588f,0.077605f}, +{0.04749f,-0.309833f,0.0847878f},{0.0460056f,-0.308462f,0.0704555f},{0.0465356f,-0.308707f,0.0704077f}, +{0.045508f,-0.307875f,0.0631775f},{0.0458644f,-0.308883f,0.0555431f},{0.0465193f,-0.309655f,0.0629336f}, +{0.0463263f,-0.310038f,0.0629134f},{0.0454915f,-0.308443f,0.0704868f},{0.0449947f,-0.307857f,0.0632194f}, +{0.046047f,-0.309098f,0.0848321f},{0.0464337f,-0.309168f,0.0918925f},{0.0465619f,-0.309118f,0.0848218f}, +{0.0464311f,-0.308584f,0.0630396f},{0.0470865f,-0.309737f,0.0703047f},{0.0465854f,-0.309146f,0.0629755f}, +{0.0456375f,-0.309225f,0.0848371f},{0.0460743f,-0.309186f,0.0918925f},{0.0457786f,-0.307815f,0.0556761f}, +{0.0459315f,-0.308375f,0.0555957f},{0.0449698f,-0.306861f,0.0482723f},{0.0457254f,-0.309296f,0.0918925f}, +{0.0456709f,-0.309265f,0.0555177f},{0.0471815f,-0.311046f,0.0775425f},{0.0468284f,-0.31063f,0.0702583f}, +{0.0470211f,-0.310247f,0.0702734f},{0.0473899f,-0.311292f,0.0847568f},{-0.0986923f,-0.138431f,-0.148277f}, +{-0.084457f,-0.155216f,-0.145943f},{-0.0796508f,-0.160883f,-0.144688f},{-0.0748255f,-0.166573f,-0.143185f}, +{-0.0699887f,-0.172276f,-0.141429f},{-0.0651481f,-0.177984f,-0.139417f},{-0.0603117f,-0.183687f,-0.137145f}, +{-0.055488f,-0.189375f,-0.134611f},{-0.0506855f,-0.195037f,-0.131812f},{-0.0459129f,-0.200665f,-0.128748f}, +{-0.0364929f,-0.211772f,-0.121826f},{-0.0318636f,-0.217231f,-0.117971f},{-0.0273004f,-0.222612f,-0.113856f}, +{-0.0228118f,-0.227904f,-0.109486f},{-0.0184068f,-0.233098f,-0.104866f},{-0.0140941f,-0.238184f,-0.1f}, +{-0.00988197f,-0.24315f,-0.0948962f},{-0.00577865f,-0.247989f,-0.0895618f},{-0.00179193f,-0.25269f,-0.0840052f}, +{0.00207075f,-0.257244f,-0.0782359f},{0.00580238f,-0.261644f,-0.072264f},{0.0093964f,-0.265882f,-0.0661002f}, +{0.016148f,-0.273843f,-0.0532437f},{0.0192952f,-0.277554f,-0.0465757f},{0.022284f,-0.281078f,-0.039765f}, +{0.0251106f,-0.284411f,-0.0328251f},{0.0277719f,-0.287549f,-0.0257695f},{0.0302654f,-0.29049f,-0.0186126f}, +{0.0325894f,-0.29323f,-0.0113678f},{0.0347425f,-0.295769f,-0.00404916f},{0.0367243f,-0.298105f,0.00332952f}, +{0.0385345f,-0.30024f,0.0107545f},{0.0401739f,-0.302173f,0.0182123f},{0.0416435f,-0.303906f,0.0256896f}, +{0.0450526f,-0.307926f,0.0481121f},{0.0451209f,-0.307419f,0.0481755f},{0.0475821f,-0.310908f,0.0847617f}, +{0.0473739f,-0.310663f,0.0775525f},{0.0476338f,-0.311036f,0.0918925f},{0.0474707f,-0.311354f,0.0918925f}, +{-0.0984159f,-0.138169f,-0.147929f},{-0.079402f,-0.160589f,-0.144345f},{-0.0745837f,-0.166271f,-0.142845f}, +{-0.0697539f,-0.171966f,-0.141092f},{-0.0649203f,-0.177665f,-0.139082f},{-0.060091f,-0.18336f,-0.136814f}, +{-0.0552742f,-0.189039f,-0.134283f},{-0.0504787f,-0.194694f,-0.131488f},{-0.031684f,-0.216855f,-0.117667f}, +{-0.0363066f,-0.211405f,-0.121517f},{-0.0362774f,-0.211059f,-0.121044f},{-0.0271274f,-0.222228f,-0.113559f}, +{-0.0226453f,-0.227513f,-0.109195f},{-0.0182467f,-0.2327f,-0.104581f},{-0.0139402f,-0.237778f,-0.0997223f}, +{-0.00165587f,-0.252263f,-0.0837506f},{0.00220122f,-0.256811f,-0.0779897f},{0.00592745f,-0.261204f,-0.0720263f}, +{0.0193066f,-0.276601f,-0.046069f},{0.0189819f,-0.276218f,-0.0457157f},{0.0222844f,-0.280112f,-0.0392833f}, +{0.0162581f,-0.273386f,-0.0530336f},{0.0194007f,-0.277091f,-0.0463752f},{0.0223852f,-0.28061f,-0.0395744f}, +{0.0252077f,-0.283938f,-0.0326445f},{0.0278652f,-0.287072f,-0.0255992f},{0.0303551f,-0.290008f,-0.0184526f}, +{0.0368046f,-0.297613f,0.00345771f},{0.0386122f,-0.299744f,0.0108719f},{0.0402492f,-0.301674f,0.0183189f}, +{0.0417167f,-0.303405f,0.0257854f},{0.0430163f,-0.304937f,0.0332586f},{0.0441501f,-0.306274f,0.0407259f}, +{0.0474388f,-0.310152f,0.0775733f},{0.046931f,-0.309174f,0.0703525f},{0.0477127f,-0.310676f,0.0918925f}, +{-0.0982492f,-0.137986f,-0.147398f},{-0.084066f,-0.15471f,-0.145073f},{-0.0792773f,-0.160357f,-0.143822f}, +{-0.0697475f,-0.171594f,-0.13998f},{-0.0648277f,-0.177395f,-0.138571f},{-0.0696506f,-0.171708f,-0.140576f}, +{-0.0744697f,-0.166025f,-0.142325f},{-0.0600091f,-0.183077f,-0.136307f},{-0.055203f,-0.188744f,-0.133782f}, +{-0.050418f,-0.194386f,-0.130993f},{-0.0456629f,-0.199993f,-0.127941f},{-0.0409464f,-0.205554f,-0.124624f}, +{-0.0273243f,-0.221616f,-0.112579f},{-0.0226464f,-0.227132f,-0.10875f},{-0.0271185f,-0.221859f,-0.113104f}, +{-0.031665f,-0.216498f,-0.117203f},{-0.0182575f,-0.232307f,-0.104146f},{-0.0139605f,-0.237374f,-0.0992979f}, +{-0.00197428f,-0.251508f,-0.0829128f},{0.00214517f,-0.256365f,-0.0776135f},{-0.00170337f,-0.251827f,-0.0833616f}, +{-0.00567551f,-0.247143f,-0.0888979f},{0.00586315f,-0.260749f,-0.0716633f},{0.00944402f,-0.264971f,-0.0655221f}, +{0.0128818f,-0.269025f,-0.0592012f},{0.0161709f,-0.272903f,-0.0527127f},{0.0251007f,-0.283433f,-0.0323688f}, +{0.0277523f,-0.286559f,-0.025339f},{0.0302367f,-0.289489f,-0.0182083f},{0.0363027f,-0.296641f,0.00387953f}, +{0.0384755f,-0.299203f,0.0110514f},{0.0366719f,-0.297077f,0.00365355f},{0.0346974f,-0.294749f,-0.00369814f}, +{0.0401089f,-0.301129f,0.0184819f},{0.0415731f,-0.302856f,0.0259318f},{0.0428699f,-0.304385f,0.0333884f}, +{0.0440012f,-0.305719f,0.0408392f},{0.0460369f,-0.308119f,0.0631135f},{0.0476948f,-0.310316f,0.0918925f}, +{-0.0935941f,-0.143475f,-0.146243f},{-0.0982728f,-0.137958f,-0.146785f},{-0.0888764f,-0.149038f,-0.145472f}, +{-0.084126f,-0.154639f,-0.144466f},{-0.0793496f,-0.160271f,-0.143218f},{-0.0745543f,-0.165926f,-0.141725f}, +{-0.064937f,-0.177266f,-0.137981f},{-0.0505642f,-0.194213f,-0.130423f},{-0.0553369f,-0.188586f,-0.133204f}, +{-0.0556402f,-0.188608f,-0.132703f},{-0.0601307f,-0.182933f,-0.135723f},{-0.0458212f,-0.199806f,-0.127378f}, +{-0.0411168f,-0.205353f,-0.12407f},{-0.0364598f,-0.210844f,-0.120499f},{-0.0318592f,-0.216269f,-0.116668f}, +{-0.0150205f,-0.237091f,-0.0981062f},{-0.0145949f,-0.237006f,-0.098384f},{-0.0192907f,-0.232056f,-0.102924f}, +{-0.0228636f,-0.226876f,-0.108236f},{-0.018486f,-0.232038f,-0.103644f},{-0.0142f,-0.237092f,-0.0988083f}, +{-0.0100141f,-0.242028f,-0.0937362f},{-0.00593625f,-0.246836f,-0.0884349f},{0.00823812f,-0.264516f,-0.0645409f}, +{0.00869775f,-0.264471f,-0.0647696f},{0.00467957f,-0.26032f,-0.0706439f},{0.00186441f,-0.256034f,-0.0771794f}, +{0.00557286f,-0.260407f,-0.0712445f},{0.00914456f,-0.264618f,-0.065119f},{0.0125735f,-0.268661f,-0.0588143f}, +{0.0158543f,-0.27253f,-0.0523423f},{0.0274059f,-0.286151f,-0.0250388f},{0.0247611f,-0.283032f,-0.0320505f}, +{0.0242796f,-0.282844f,-0.0317747f},{0.0219521f,-0.27972f,-0.0389474f},{0.029884f,-0.289073f,-0.0179263f}, +{0.0321935f,-0.291796f,-0.0107265f},{0.0343333f,-0.294319f,-0.00345334f},{0.0381017f,-0.298763f,0.0112584f}, +{0.0424848f,-0.303931f,0.0335382f},{0.0411914f,-0.302406f,0.0261007f},{0.0406733f,-0.302175f,0.0262471f}, +{0.0397309f,-0.300684f,0.0186698f},{0.0436132f,-0.305261f,0.04097f},{0.0445793f,-0.306401f,0.048384f}, +{0.0453861f,-0.307352f,0.0557688f},{0.0468862f,-0.309121f,0.0776416f},{0.0470932f,-0.309365f,0.084806f}, +{0.0473856f,-0.309657f,0.0918925f},{0.0475847f,-0.309968f,0.0918925f},{-0.0938123f,-0.143598f,-0.145713f}, +{-0.0984806f,-0.138093f,-0.146254f},{-0.0891051f,-0.149148f,-0.144944f},{-0.0843652f,-0.154737f,-0.14394f}, +{-0.0795995f,-0.160356f,-0.142695f},{-0.0748149f,-0.165998f,-0.141205f},{-0.0700188f,-0.171653f,-0.139464f}, +{-0.0652189f,-0.177313f,-0.137469f},{-0.0604233f,-0.182968f,-0.135216f},{-0.0512508f,-0.194371f,-0.129604f}, +{-0.0465253f,-0.199943f,-0.126571f},{-0.0461457f,-0.199803f,-0.12689f},{-0.0508781f,-0.194223f,-0.129928f}, +{-0.0414517f,-0.205338f,-0.123589f},{-0.0368051f,-0.210817f,-0.120026f},{-0.0322148f,-0.216229f,-0.116203f}, +{-0.0276899f,-0.221565f,-0.112124f},{-0.0232392f,-0.226813f,-0.10779f},{-0.0188713f,-0.231963f,-0.103209f}, +{-0.0104183f,-0.241931f,-0.0933231f},{-0.0063495f,-0.246728f,-0.0880336f},{-0.00239635f,-0.25139f,-0.0825239f}, +{0.0014338f,-0.255906f,-0.0768032f},{0.00513399f,-0.260269f,-0.0708815f},{0.0121191f,-0.268505f,-0.0584789f}, +{0.0153925f,-0.272365f,-0.0520214f},{0.0185132f,-0.276045f,-0.0454095f},{0.0214768f,-0.279539f,-0.0386562f}, +{0.0264323f,-0.28597f,-0.0246083f},{0.0289012f,-0.288881f,-0.017522f},{0.029391f,-0.288871f,-0.017682f}, +{0.0269185f,-0.285956f,-0.0247786f},{0.0316954f,-0.291588f,-0.0104982f},{0.0338304f,-0.294106f,-0.00324118f}, +{0.0357955f,-0.296423f,0.00407537f},{0.0375905f,-0.298539f,0.0114378f},{0.0392161f,-0.300456f,0.0188328f}, +{0.0419638f,-0.303696f,0.0336681f},{0.0425799f,-0.30501f,0.0411575f},{0.0435424f,-0.306145f,0.0485442f}, +{0.0440537f,-0.30616f,0.0484808f},{0.0430897f,-0.305024f,0.0410833f},{0.0448586f,-0.30711f,0.0558492f}, +{0.0463554f,-0.308875f,0.0776733f},{0.0467942f,-0.309247f,0.0918925f},{0.0471187f,-0.309415f,0.0918925f}, +{-0.0987838f,-0.138323f,-0.145907f},{-0.0894219f,-0.149362f,-0.144598f},{-0.084689f,-0.154943f,-0.143596f}, +{-0.0897359f,-0.149602f,-0.144431f},{-0.0799302f,-0.160554f,-0.142353f},{-0.0751526f,-0.166187f,-0.140865f}, +{-0.0703635f,-0.171834f,-0.139127f},{-0.0655707f,-0.177486f,-0.137134f},{-0.0607821f,-0.183132f,-0.134885f}, +{-0.056006f,-0.188764f,-0.132375f},{-0.0375491f,-0.211137f,-0.119568f},{-0.0421857f,-0.20567f,-0.123123f}, +{-0.0418382f,-0.20547f,-0.123274f},{-0.0371983f,-0.210941f,-0.119717f},{-0.0326147f,-0.216345f,-0.1159f}, +{-0.0280965f,-0.221673f,-0.111826f},{-0.0236522f,-0.226913f,-0.107499f},{-0.0112194f,-0.242183f,-0.0929223f}, +{-0.01085f,-0.242009f,-0.0930527f},{-0.015387f,-0.237269f,-0.0979722f},{-0.00678716f,-0.2468f,-0.087771f}, +{-0.00283979f,-0.251454f,-0.0822693f},{0.000984771f,-0.255964f,-0.0765569f},{0.0112692f,-0.2687f,-0.0581535f}, +{0.0145356f,-0.272552f,-0.0517099f},{0.0116545f,-0.268545f,-0.0582594f},{0.0149231f,-0.272399f,-0.0518113f}, +{0.0180392f,-0.276073f,-0.0452091f},{0.0209985f,-0.279563f,-0.0384656f},{0.0237972f,-0.282863f,-0.0315942f}, +{0.0308032f,-0.291734f,-0.0102766f},{0.0312022f,-0.291594f,-0.0103487f},{0.0285038f,-0.289022f,-0.0174448f}, +{0.0333341f,-0.294108f,-0.0031023f},{0.0352963f,-0.296422f,0.00420356f},{0.0370887f,-0.298535f,0.0115553f}, +{0.0387119f,-0.300449f,0.0189394f},{0.040167f,-0.302165f,0.026343f},{0.0414556f,-0.303684f,0.0337531f}, +{0.0443462f,-0.307093f,0.0559018f},{0.0454314f,-0.308982f,0.0777041f},{0.0450823f,-0.308571f,0.0705019f}, +{0.0458408f,-0.308855f,0.077694f},{-0.0850063f,-0.155178f,-0.143429f},{-0.0802509f,-0.160786f,-0.142188f}, +{-0.0754766f,-0.166415f,-0.140701f},{-0.0706909f,-0.172058f,-0.138964f},{-0.0659015f,-0.177706f,-0.136973f}, +{-0.0611162f,-0.183348f,-0.134725f},{-0.0563435f,-0.188976f,-0.132217f},{-0.0515917f,-0.194579f,-0.129448f}, +{-0.0468695f,-0.200147f,-0.126416f},{-0.0329688f,-0.216538f,-0.115753f},{-0.0284537f,-0.221862f,-0.111682f}, +{-0.0240126f,-0.227098f,-0.107358f},{-0.0196542f,-0.232238f,-0.102786f},{-0.00715942f,-0.246971f,-0.0876442f}, +{-0.00321483f,-0.251622f,-0.0821464f},{0.000607029f,-0.256128f,-0.0764381f},{0.00429921f,-0.260482f,-0.0705292f}, +{0.00785526f,-0.264675f,-0.0644306f},{0.0176495f,-0.276224f,-0.0451124f},{0.0206066f,-0.279711f,-0.0383737f}, +{0.0234034f,-0.283008f,-0.0315071f},{0.0260366f,-0.286113f,-0.0245261f},{0.0329336f,-0.294246f,-0.0030353f}, +{0.0348943f,-0.296558f,0.00426541f},{0.0366855f,-0.29867f,0.0116119f},{0.0383075f,-0.300582f,0.0189909f}, +{0.0397616f,-0.302297f,0.0263892f},{0.0410493f,-0.303815f,0.0337941f},{0.0421728f,-0.30514f,0.0411933f}, +{0.0431347f,-0.306274f,0.0485748f},{0.0439379f,-0.307221f,0.0559272f},{0.0445859f,-0.307985f,0.0632397f}, +{-0.0391526f,0.0783052f,0.0434179f},{-0.0388614f,0.0783204f,0.0340958f},{-0.0394464f,0.0783208f,0.0340958f}, +{-0.0400182f,0.0784426f,0.0340958f},{-0.0396981f,0.0783592f,0.0434179f},{-0.0402232f,0.0785175f,0.0434179f}, +{-0.041025f,0.0790247f,0.0340958f},{-0.0407075f,0.0787756f,0.0434179f},{-0.0405514f,0.0786801f,0.0340958f}, +{-0.0414158f,0.0794592f,0.0340958f},{-0.0411317f,0.0791238f,0.0434179f},{-0.0414795f,0.079548f,0.0434179f}, +{-0.0417077f,0.0799651f,0.0340958f},{-0.041888f,0.08052f,0.0340958f},{-0.0417379f,0.0800316f,0.0434179f}, +{-0.0419492f,0.0811018f,0.0434179f},{-0.0418971f,0.0805563f,0.0434179f},{-0.0386063f,0.0783596f,0.0434179f}, +{-0.0382892f,0.0784417f,0.0340958f},{-0.0380818f,0.0785201f,0.0434179f},{-0.037599f,0.0787792f,0.0434179f}, +{-0.0377553f,0.0786794f,0.0340958f},{-0.0371757f,0.0791268f,0.0434179f},{-0.0372831f,0.0790223f,0.0340958f}, +{-0.0368907f,0.0794572f,0.0340958f},{-0.0368282f,0.0795501f,0.0434179f},{-0.0365701f,0.0800331f,0.0434179f}, +{-0.036598f,0.0799637f,0.0340958f},{-0.0364108f,0.0805572f,0.0434179f},{-0.0364177f,0.0805185f,0.0340958f}, +{-0.036356f,0.0811018f,0.0434179f},{-0.0391526f,0.0811018f,0.0450982f},{-0.035689f,0.0842218f,0.0359602f}, +{-0.035116f,0.0834323f,0.0359602f},{-0.0353809f,0.08384f,0.0340958f},{-0.0391526f,0.0857628f,0.0359602f}, +{-0.0391526f,0.0857628f,0.0340958f},{-0.0398869f,0.0857044f,0.0340958f},{-0.0349993f,0.0832175f,0.0340958f}, +{-0.0347708f,0.0826925f,0.0359602f},{-0.0347209f,0.0825456f,0.0340958f},{-0.0345623f,0.0819115f,0.0359602f}, +{-0.03455f,0.0818361f,0.0340958f},{-0.0344918f,0.0811018f,0.0359602f},{-0.0344916f,0.0811018f,0.0340958f}, +{-0.0358568f,0.0843977f,0.0340958f},{-0.0364173f,0.0848756f,0.0340958f},{-0.0364146f,0.084874f,0.0359602f}, +{-0.0370399f,0.0852564f,0.0340958f},{-0.0372574f,0.0853604f,0.0359602f},{-0.0377117f,0.0855347f,0.0340958f}, +{-0.0381842f,0.0856612f,0.0359602f},{-0.0384218f,0.085705f,0.0340958f},{-0.0410494f,0.0853588f,0.0359602f}, +{-0.0401233f,0.0856603f,0.0359602f},{-0.0405964f,0.0855335f,0.0340958f},{-0.0424484f,0.0843977f,0.0340958f}, +{-0.0418918f,0.0848727f,0.0359602f},{-0.0418907f,0.0848735f,0.0340958f},{-0.0412683f,0.0852551f,0.0340958f}, +{-0.0435327f,0.0826912f,0.0359602f},{-0.0431892f,0.0834324f,0.0359602f},{-0.0433072f,0.0832145f,0.0340958f}, +{-0.0426166f,0.0842194f,0.0359602f},{-0.0429264f,0.0838371f,0.0340958f},{-0.0437552f,0.0818361f,0.0340958f}, +{-0.0437427f,0.0819107f,0.0359602f},{-0.0435855f,0.0825427f,0.0340958f},{-0.0438136f,0.0811018f,0.0340958f}, +{-0.0438134f,0.0811018f,0.0359602f},{-0.0391526f,0.0838984f,0.062062f},{-0.0388614f,0.0838832f,0.071384f}, +{-0.0394464f,0.0838828f,0.071384f},{-0.0400182f,0.083761f,0.071384f},{-0.0396981f,0.0838444f,0.062062f}, +{-0.0402232f,0.0836861f,0.062062f},{-0.041025f,0.0831789f,0.071384f},{-0.0407075f,0.083428f,0.062062f}, +{-0.0405514f,0.0835236f,0.071384f},{-0.0414158f,0.0827444f,0.071384f},{-0.0411317f,0.0830798f,0.062062f}, +{-0.0414795f,0.0826556f,0.062062f},{-0.0417077f,0.0822385f,0.071384f},{-0.041888f,0.0816837f,0.071384f}, +{-0.0417379f,0.082172f,0.062062f},{-0.0419492f,0.0811018f,0.071384f},{-0.0419492f,0.0811018f,0.062062f}, +{-0.0418971f,0.0816473f,0.062062f},{-0.0386063f,0.083844f,0.062062f},{-0.0382892f,0.0837619f,0.071384f}, +{-0.0380818f,0.0836835f,0.062062f},{-0.037599f,0.0834244f,0.062062f},{-0.0377553f,0.0835242f,0.071384f}, +{-0.0371757f,0.0830768f,0.062062f},{-0.0372831f,0.0831813f,0.071384f},{-0.0368907f,0.0827465f,0.071384f}, +{-0.0368282f,0.0826535f,0.062062f},{-0.0365701f,0.0821705f,0.062062f},{-0.036598f,0.0822399f,0.071384f}, +{-0.0364108f,0.0816464f,0.062062f},{-0.0364177f,0.0816851f,0.071384f},{-0.036356f,0.0811018f,0.071384f}, +{-0.036356f,0.0811018f,0.062062f},{-0.0391526f,0.0811018f,0.0603816f},{-0.035689f,0.0779818f,0.0695196f}, +{-0.035116f,0.0787713f,0.0695196f},{-0.0353809f,0.0783636f,0.071384f},{-0.0391526f,0.0764408f,0.0695196f}, +{-0.0391526f,0.0764408f,0.071384f},{-0.0398869f,0.0764992f,0.071384f},{-0.0349993f,0.0789861f,0.071384f}, +{-0.0347708f,0.0795111f,0.0695196f},{-0.0347209f,0.079658f,0.071384f},{-0.0345623f,0.0802921f,0.0695196f}, +{-0.03455f,0.0803675f,0.071384f},{-0.0344918f,0.0811018f,0.0695196f},{-0.0344916f,0.0811018f,0.071384f}, +{-0.0358568f,0.077806f,0.071384f},{-0.0364173f,0.077328f,0.071384f},{-0.0364146f,0.0773296f,0.0695196f}, +{-0.0370399f,0.0769472f,0.071384f},{-0.0372574f,0.0768432f,0.0695196f},{-0.0377117f,0.0766689f,0.071384f}, +{-0.0381842f,0.0765424f,0.0695196f},{-0.0384218f,0.0764986f,0.071384f},{-0.0410494f,0.0768448f,0.0695196f}, +{-0.0401233f,0.0765433f,0.0695196f},{-0.0405964f,0.0766702f,0.071384f},{-0.0424484f,0.077806f,0.071384f}, +{-0.0418918f,0.0773309f,0.0695196f},{-0.0418907f,0.0773301f,0.071384f},{-0.0412683f,0.0769485f,0.071384f}, +{-0.0435327f,0.0795124f,0.0695196f},{-0.0431892f,0.0787712f,0.0695196f},{-0.0433072f,0.0789891f,0.071384f}, +{-0.0426166f,0.0779842f,0.0695196f},{-0.0429264f,0.0783665f,0.071384f},{-0.0437552f,0.0803675f,0.071384f}, +{-0.0437427f,0.0802929f,0.0695196f},{-0.0435855f,0.079661f,0.071384f},{-0.0438136f,0.0811018f,0.071384f}, +{-0.0438134f,0.0811018f,0.0695196f},{-0.0337705f,0.0811018f,0.0359602f},{-0.0351159f,0.0834324f,0.0695196f}, +{-0.0364616f,0.0857628f,0.0359602f},{-0.0364616f,0.0857628f,0.0695196f},{-0.0337705f,0.0811018f,0.0695196f}, +{-0.0388588f,0.0838828f,0.0340958f},{-0.0394438f,0.0838832f,0.0340958f},{-0.0405499f,0.0835242f,0.0340958f}, +{-0.040016f,0.0837619f,0.0340958f},{-0.0345484f,0.0803724f,0.0340958f},{-0.0347196f,0.0796609f,0.0340958f}, +{-0.0365975f,0.0822385f,0.0340958f},{-0.0364172f,0.0816837f,0.0340958f},{-0.0368894f,0.0827444f,0.0340958f}, +{-0.0372802f,0.0831789f,0.0340958f},{-0.0377538f,0.0835236f,0.0340958f},{-0.038287f,0.083761f,0.0340958f}, +{-0.0358645f,0.0778104f,0.0340958f},{-0.0364144f,0.0773296f,0.0340958f},{-0.0377132f,0.0766684f,0.0340958f}, +{-0.0370378f,0.0769479f,0.0340958f},{-0.038424f,0.076498f,0.0340958f},{-0.0410221f,0.0831813f,0.0340958f}, +{-0.0414831f,0.0834323f,0.0340958f},{-0.0398819f,0.0764984f,0.0340958f},{-0.0391526f,0.0764408f,0.0340958f}, +{-0.0412686f,0.0769492f,0.0340958f},{-0.0418918f,0.0773311f,0.0340958f},{-0.0405931f,0.0766694f,0.0340958f}, +{-0.0417072f,0.0822399f,0.0340958f},{-0.0414145f,0.0827465f,0.0340958f},{-0.0424471f,0.0778077f,0.0340958f}, +{-0.0433038f,0.0789871f,0.0340958f},{-0.0435854f,0.0796621f,0.0340958f},{-0.0437559f,0.0803733f,0.0340958f}, +{-0.0418875f,0.0816851f,0.0340958f},{-0.042921f,0.0783646f,0.0340958f},{-0.0349967f,0.0789819f,0.0340958f}, +{-0.0353925f,0.07837f,0.0340958f},{-0.0445347f,0.0811018f,0.0359602f},{-0.0431893f,0.0787712f,0.0359602f}, +{-0.0418436f,0.0764408f,0.0359602f},{-0.0418436f,0.0764408f,0.0695196f},{-0.0445347f,0.0811018f,0.0695196f}, +{-0.0364616f,0.0764408f,0.0359602f},{-0.0351159f,0.0787712f,0.0359602f},{-0.0364616f,0.0764408f,0.0695196f}, +{-0.0391526f,0.0764412f,0.0359602f},{-0.0391526f,0.0857625f,0.0695196f},{-0.0418436f,0.0857628f,0.0359602f}, +{-0.0418436f,0.0857628f,0.0695196f},{-0.0364144f,0.084874f,0.071384f},{-0.0358645f,0.0843932f,0.071384f}, +{-0.0437559f,0.0818303f,0.071384f},{-0.0435854f,0.0825415f,0.071384f},{-0.0370378f,0.0852557f,0.071384f}, +{-0.0377132f,0.0855352f,0.071384f},{-0.038424f,0.0857056f,0.071384f},{-0.0391526f,0.0857628f,0.071384f}, +{-0.0405931f,0.0855343f,0.071384f},{-0.0412686f,0.0852544f,0.071384f},{-0.0398819f,0.0857052f,0.071384f}, +{-0.0418918f,0.0848725f,0.071384f},{-0.0353925f,0.0838337f,0.071384f},{-0.0345484f,0.0818312f,0.071384f}, +{-0.0424471f,0.0843959f,0.071384f},{-0.0364172f,0.08052f,0.071384f},{-0.0368221f,0.0787713f,0.071384f}, +{-0.0368894f,0.0794592f,0.071384f},{-0.040016f,0.0784417f,0.071384f},{-0.0394438f,0.0783204f,0.071384f}, +{-0.038287f,0.0784426f,0.071384f},{-0.0410221f,0.0790223f,0.071384f},{-0.0405499f,0.0786794f,0.071384f}, +{-0.0417072f,0.0799637f,0.071384f},{-0.0414145f,0.0794572f,0.071384f},{-0.0388588f,0.0783208f,0.071384f}, +{-0.0418875f,0.0805185f,0.071384f},{-0.0365975f,0.0799651f,0.071384f},{-0.0377538f,0.0786801f,0.071384f}, +{-0.0433038f,0.0832165f,0.071384f},{-0.0347196f,0.0825428f,0.071384f},{-0.0349967f,0.0832217f,0.071384f}, +{-0.042921f,0.083839f,0.071384f},{-0.0372802f,0.0790247f,0.071384f},{-0.0431893f,0.0834324f,0.0695196f}, +{-0.0345623f,0.081909f,0.0695196f},{-0.0356893f,0.0842209f,0.0695196f},{-0.0347719f,0.0826889f,0.0695196f}, +{-0.0381833f,0.0856608f,0.0695196f},{-0.0364121f,0.0848714f,0.0695196f},{-0.0372548f,0.0853584f,0.0695196f}, +{-0.041893f,0.0848726f,0.0695196f},{-0.041049f,0.08536f,0.0695196f},{-0.0401215f,0.0856611f,0.0695196f}, +{-0.0426157f,0.0842217f,0.0695196f},{-0.0435351f,0.0826902f,0.0695196f},{-0.0437434f,0.0819096f,0.0695196f}, +{-0.0417086f,0.0799637f,0.062062f},{-0.041416f,0.0794571f,0.062062f},{-0.0418896f,0.08052f,0.062062f}, +{-0.0410244f,0.0790222f,0.062062f},{-0.0405506f,0.0786785f,0.062062f},{-0.0400156f,0.0784417f,0.062062f}, +{-0.0394436f,0.0783205f,0.062062f},{-0.0388585f,0.078321f,0.062062f},{-0.0377533f,0.078683f,0.062062f}, +{-0.0382866f,0.0784441f,0.062062f},{-0.0368906f,0.0794606f,0.062062f},{-0.0372812f,0.0790267f,0.062062f}, +{-0.0364182f,0.0805216f,0.062062f},{-0.0365988f,0.0799663f,0.062062f},{-0.0345623f,0.0802946f,0.0359602f}, +{-0.035689f,0.077983f,0.0359602f},{-0.0347719f,0.0795147f,0.0359602f},{-0.0381819f,0.0765431f,0.0359602f}, +{-0.0364115f,0.0773327f,0.0359602f},{-0.0372538f,0.0768457f,0.0359602f},{-0.0418924f,0.0773306f,0.0359602f}, +{-0.041048f,0.0768432f,0.0359602f},{-0.0401201f,0.0765423f,0.0359602f},{-0.0426154f,0.0779817f,0.0359602f}, +{-0.0435351f,0.0795134f,0.0359602f},{-0.0437434f,0.080294f,0.0359602f},{-0.0417086f,0.0822399f,0.0434179f}, +{-0.041416f,0.0827465f,0.0434179f},{-0.0418896f,0.0816836f,0.0434179f},{-0.0410244f,0.0831814f,0.0434179f}, +{-0.0405506f,0.0835251f,0.0434179f},{-0.0400156f,0.0837619f,0.0434179f},{-0.0394436f,0.0838831f,0.0434179f}, +{-0.0388585f,0.0838826f,0.0434179f},{-0.0377533f,0.0835206f,0.0434179f},{-0.0382866f,0.0837595f,0.0434179f}, +{-0.0368906f,0.082743f,0.0434179f},{-0.0372812f,0.0831769f,0.0434179f},{-0.0364182f,0.081682f,0.0434179f}, +{-0.0365988f,0.0822373f,0.0434179f},{0.0389901f,-0.0783099f,0.0434179f},{0.0387003f,-0.0783421f,0.0340958f}, +{0.0392843f,-0.0783085f,0.0340958f},{0.0398623f,-0.0783968f,0.0340958f},{0.0395378f,-0.0783322f,0.0434179f}, +{0.0400712f,-0.0784597f,0.0434179f},{0.0409011f,-0.0789195f,0.0340958f},{0.0405697f,-0.0786892f,0.0434179f}, +{0.0404083f,-0.0786029f,0.0340958f},{0.0413165f,-0.0793305f,0.0340958f},{0.0410134f,-0.0790122f,0.0434179f}, +{0.0413853f,-0.0794154f,0.0434179f},{0.0416374f,-0.0798186f,0.0340958f},{0.0418496f,-0.080362f,0.0340958f}, +{0.0416714f,-0.0798832f,0.0434179f},{0.0419445f,-0.0809393f,0.0340958f},{0.0419445f,-0.0809393f,0.0434179f}, +{0.0418608f,-0.0803977f,0.0434179f},{0.0384479f,-0.078396f,0.0434179f},{0.0381361f,-0.0784964f,0.0340958f}, +{0.0379336f,-0.0785867f,0.0434179f},{0.0374667f,-0.0788734f,0.0434179f},{0.0376169f,-0.0787647f,0.0340958f}, +{0.0370643f,-0.0792449f,0.0434179f},{0.0371654f,-0.0791345f,0.0340958f},{0.036799f,-0.0795913f,0.0340958f}, +{0.036742f,-0.0796878f,0.0434179f},{0.0365123f,-0.080185f,0.0434179f},{0.0365362f,-0.080114f,0.0340958f}, +{0.0363838f,-0.0807174f,0.0434179f},{0.0363884f,-0.0806783f,0.0340958f},{0.0363607f,-0.0812643f,0.0340958f}, +{0.0363607f,-0.0812643f,0.0434179f},{0.0391526f,-0.0811018f,0.0450982f},{0.0358762f,-0.0844178f,0.0359602f}, +{0.0352583f,-0.0836629f,0.0359602f},{0.0355463f,-0.0840545f,0.0340958f},{0.0394234f,-0.085755f,0.0359602f}, +{0.0394234f,-0.085755f,0.0340958f},{0.0401531f,-0.085654f,0.0340958f},{0.0351292f,-0.0834552f,0.0340958f}, +{0.0348706f,-0.0829444f,0.0359602f},{0.0348123f,-0.0828006f,0.0340958f},{0.0346171f,-0.0821768f,0.0359602f}, +{0.0346004f,-0.0821023f,0.0340958f},{0.0344997f,-0.0813726f,0.0359602f},{0.0344994f,-0.0813726f,0.0340958f}, +{0.0360538f,-0.0845836f,0.0340958f},{0.0366412f,-0.0850281f,0.0340958f},{0.0366384f,-0.0850267f,0.0359602f}, +{0.0372848f,-0.0853721f,0.0340958f},{0.037508f,-0.0854633f,0.0359602f},{0.0379717f,-0.0856109f,0.0340958f}, +{0.0384507f,-0.0857098f,0.0359602f},{0.0386904f,-0.0857397f,0.0340958f},{0.0412936f,-0.0852414f,0.0359602f}, +{0.0403865f,-0.0855962f,0.0359602f},{0.0408514f,-0.0854421f,0.0340958f},{0.0426344f,-0.0842006f,0.0340958f}, +{0.0421063f,-0.0847072f,0.0359602f},{0.0421053f,-0.0847081f,0.0340958f},{0.041506f,-0.0851252f,0.0340958f}, +{0.0436176f,-0.082434f,0.0359602f},{0.0433178f,-0.0831939f,0.0359602f},{0.0434229f,-0.0829696f,0.0340958f}, +{0.0427919f,-0.0840129f,0.0359602f},{0.0430789f,-0.0836132f,0.0340958f},{0.0437901f,-0.0815675f,0.0340958f}, +{0.0437819f,-0.0816426f,0.0359602f},{0.0436617f,-0.0822827f,0.0340958f},{0.0438057f,-0.080831f,0.0340958f}, +{0.0438055f,-0.080831f,0.0359602f},{0.0393151f,-0.0838937f,0.062062f},{0.0390235f,-0.0838954f,0.071384f}, +{0.0396075f,-0.083861f,0.071384f},{0.0401713f,-0.0837062f,0.071384f},{0.0398565f,-0.0838081f,0.062062f}, +{0.0403715f,-0.0836196f,0.062062f},{0.0411425f,-0.0830666f,0.071384f},{0.04084f,-0.0833337f,0.062062f}, +{0.0406897f,-0.0834382f,0.071384f},{0.0415074f,-0.0826102f,0.071384f},{0.0412433f,-0.0829615f,0.062062f}, +{0.0415658f,-0.0825178f,0.062062f},{0.0417695f,-0.0820881f,0.071384f},{0.0419172f,-0.0815237f,0.071384f}, +{0.0417958f,-0.08202f,0.062062f},{0.0419445f,-0.0809393f,0.071384f},{0.0419445f,-0.0809393f,0.062062f}, +{0.0419241f,-0.081487f,0.062062f},{0.0387666f,-0.0838711f,0.062062f},{0.0384452f,-0.0838076f,0.071384f}, +{0.0382336f,-0.0837413f,0.062062f},{0.0377365f,-0.0835108f,0.062062f},{0.0378984f,-0.0836013f,0.071384f}, +{0.0372938f,-0.0831884f,0.062062f},{0.0374071f,-0.0832864f,0.071384f},{0.0369901f,-0.0828751f,0.071384f}, +{0.0369223f,-0.0827859f,0.062062f},{0.0366365f,-0.0823187f,0.062062f},{0.0366685f,-0.0823864f,0.071384f}, +{0.0364471f,-0.0818048f,0.062062f},{0.0364562f,-0.0818431f,0.071384f},{0.0363607f,-0.0812643f,0.071384f}, +{0.0363607f,-0.0812643f,0.062062f},{0.0391526f,-0.0811018f,0.0603816f},{0.0355136f,-0.0781883f,0.0695196f}, +{0.0349875f,-0.0790097f,0.0695196f},{0.0352282f,-0.0785874f,0.071384f},{0.0388818f,-0.0764487f,0.0695196f}, +{0.0388818f,-0.0764487f,0.071384f},{0.0396183f,-0.0764643f,0.071384f},{0.0348834f,-0.079231f,0.071384f}, +{0.0346858f,-0.0797684f,0.0695196f},{0.0346446f,-0.0799179f,0.071384f},{0.034523f,-0.0805601f,0.0695196f}, +{0.0345151f,-0.0806361f,0.071384f},{0.0344996f,-0.0813726f,0.0695196f},{0.0344994f,-0.0813726f,0.071384f}, +{0.0356708f,-0.078003f,0.071384f},{0.0362027f,-0.0774933f,0.071384f},{0.0362001f,-0.0774951f,0.0695196f}, +{0.0368021f,-0.077077f,0.071384f},{0.0370131f,-0.0769605f,0.0695196f},{0.0374566f,-0.0767601f,0.071384f}, +{0.0379209f,-0.0766064f,0.0695196f},{0.0381555f,-0.0765489f,0.071384f},{0.0407989f,-0.0767418f,0.0695196f}, +{0.0398569f,-0.0764946f,0.0695196f},{0.0403365f,-0.0765938f,0.071384f},{0.0422514f,-0.07762f,0.071384f}, +{0.0416681f,-0.0771781f,0.0695196f},{0.041667f,-0.0771774f,0.071384f},{0.0410234f,-0.0768326f,0.071384f}, +{0.0434329f,-0.0792607f,0.0695196f},{0.043047f,-0.0785407f,0.0695196f},{0.0431774f,-0.0787513f,0.071384f}, +{0.0424296f,-0.0777882f,0.0695196f},{0.0427611f,-0.0781519f,0.071384f},{0.0437048f,-0.0801013f,0.071384f}, +{0.0436879f,-0.0800276f,0.0695196f},{0.0434943f,-0.0794058f,0.071384f},{0.0438057f,-0.080831f,0.071384f}, +{0.0438056f,-0.080831f,0.0695196f},{0.0337796f,-0.0814145f,0.0359602f},{0.0352581f,-0.083663f,0.0695196f}, +{0.0367369f,-0.0859113f,0.0359602f},{0.0367369f,-0.0859113f,0.0695196f},{0.0337796f,-0.0814145f,0.0695196f}, +{0.0390208f,-0.0838951f,0.0340958f},{0.0396049f,-0.0838616f,0.0340958f},{0.0406883f,-0.0834389f,0.0340958f}, +{0.0401691f,-0.0837073f,0.0340958f},{0.0345138f,-0.0806411f,0.0340958f},{0.0346434f,-0.0799208f,0.0340958f}, +{0.0366678f,-0.082385f,0.0340958f},{0.0364556f,-0.0818416f,0.0340958f},{0.0369886f,-0.0828732f,0.0340958f}, +{0.037404f,-0.0832841f,0.0340958f},{0.0378969f,-0.0836007f,0.0340958f},{0.0384429f,-0.0838068f,0.0340958f}, +{0.0356789f,-0.078007f,0.0340958f},{0.0361998f,-0.0774951f,0.0340958f},{0.0374581f,-0.0767596f,0.0340958f}, +{0.0368f,-0.0770778f,0.0340958f},{0.0381577f,-0.0765482f,0.0340958f},{0.0411398f,-0.0830691f,0.0340958f}, +{0.0416146f,-0.083293f,0.0340958f},{0.0396132f,-0.0764638f,0.0340958f},{0.0388818f,-0.0764487f,0.0340958f}, +{0.0410238f,-0.0768332f,0.0340958f},{0.0416681f,-0.0771784f,0.0340958f},{0.0403331f,-0.0765932f,0.0340958f}, +{0.041769f,-0.0820896f,0.0340958f},{0.0415062f,-0.0826123f,0.0340958f},{0.0422501f,-0.0776219f,0.0340958f}, +{0.043174f,-0.0787495f,0.0340958f},{0.0434943f,-0.079407f,0.0340958f},{0.0437058f,-0.0801071f,0.0340958f}, +{0.0419168f,-0.0815253f,0.0340958f},{0.0427556f,-0.0781503f,0.0340958f},{0.0348806f,-0.0792269f,0.0340958f}, +{0.0352401f,-0.078593f,0.0340958f},{0.0445256f,-0.0807891f,0.0359602f},{0.0430471f,-0.0785406f,0.0359602f}, +{0.0415683f,-0.0762923f,0.0359602f},{0.0415683f,-0.0762923f,0.0695196f},{0.0445256f,-0.0807891f,0.0695196f}, +{0.0361953f,-0.076605f,0.0359602f},{0.0349873f,-0.0790097f,0.0359602f},{0.0361953f,-0.076605f,0.0695196f}, +{0.0388818f,-0.0764491f,0.0359602f},{0.0394234f,-0.0857546f,0.0695196f},{0.0421099f,-0.0855986f,0.0359602f}, +{0.0421099f,-0.0855986f,0.0695196f},{0.0366381f,-0.0850267f,0.071384f},{0.0360613f,-0.0845787f,0.071384f}, +{0.0437905f,-0.0815617f,0.071384f},{0.0436616f,-0.0822815f,0.071384f},{0.0372827f,-0.0853716f,0.071384f}, +{0.0379732f,-0.0856113f,0.071384f},{0.0386927f,-0.0857401f,0.071384f},{0.0394234f,-0.085755f,0.071384f}, +{0.0408481f,-0.0854431f,0.071384f},{0.0415063f,-0.0851245f,0.071384f},{0.0401481f,-0.0856551f,0.071384f}, +{0.0421062f,-0.084707f,0.071384f},{0.0355575f,-0.0840475f,0.071384f},{0.0345985f,-0.0820975f,0.071384f}, +{0.0426329f,-0.0841989f,0.071384f},{0.036388f,-0.0806799f,0.071384f},{0.0366906f,-0.0789106f,0.071384f}, +{0.0367978f,-0.0795934f,0.071384f},{0.03986f,-0.078396f,0.071384f},{0.0392817f,-0.0783082f,0.071384f}, +{0.0381339f,-0.0784974f,0.071384f},{0.0408981f,-0.0789173f,0.071384f},{0.0404068f,-0.0786023f,0.071384f}, +{0.0416367f,-0.0798172f,0.071384f},{0.0413151f,-0.0793285f,0.071384f},{0.0386977f,-0.0783426f,0.071384f}, +{0.041849f,-0.0803606f,0.071384f},{0.0365357f,-0.0801155f,0.071384f},{0.0376155f,-0.0787654f,0.071384f}, +{0.0434197f,-0.0829717f,0.071384f},{0.0348108f,-0.0827979f,0.071384f},{0.0351269f,-0.0834596f,0.071384f}, +{0.0430736f,-0.0836154f,0.071384f},{0.0371627f,-0.079137f,0.071384f},{0.0433179f,-0.0831939f,0.0695196f}, +{0.034617f,-0.0821743f,0.0695196f},{0.0358763f,-0.0844168f,0.0695196f},{0.0348715f,-0.0829407f,0.0695196f}, +{0.0384498f,-0.0857094f,0.0695196f},{0.0366357f,-0.0850242f,0.0695196f},{0.0375053f,-0.0854614f,0.0695196f}, +{0.0421074f,-0.084707f,0.0695196f},{0.0412932f,-0.0852426f,0.0695196f},{0.0403848f,-0.0855971f,0.0695196f}, +{0.0427911f,-0.0840152f,0.0695196f},{0.0436199f,-0.0824329f,0.0695196f},{0.0437826f,-0.0816416f,0.0695196f}, +{0.0416382f,-0.0798171f,0.062062f},{0.0413167f,-0.0793284f,0.062062f},{0.0418511f,-0.080362f,0.062062f}, +{0.0409005f,-0.0789169f,0.062062f},{0.0404074f,-0.0786014f,0.062062f},{0.0398596f,-0.078396f,0.062062f}, +{0.0392815f,-0.0783083f,0.062062f},{0.0386975f,-0.0783428f,0.062062f},{0.0376151f,-0.0787684f,0.062062f}, +{0.0381337f,-0.0784989f,0.062062f},{0.036799f,-0.0795948f,0.062062f},{0.0371638f,-0.0791389f,0.062062f}, +{0.0363891f,-0.0806814f,0.062062f},{0.0365371f,-0.0801166f,0.062062f},{0.0345232f,-0.0805627f,0.0359602f}, +{0.0355137f,-0.0781895f,0.0359602f},{0.0346871f,-0.0797719f,0.0359602f},{0.0379187f,-0.0766072f,0.0359602f}, +{0.0361971f,-0.0774983f,0.0359602f},{0.0370098f,-0.0769632f,0.0359602f},{0.0416687f,-0.0771778f,0.0359602f}, +{0.0407974f,-0.0767403f,0.0359602f},{0.0398536f,-0.0764937f,0.0359602f},{0.0424283f,-0.0777858f,0.0359602f}, +{0.0434354f,-0.0792615f,0.0359602f},{0.0436887f,-0.0800286f,0.0359602f},{0.0417704f,-0.0820895f,0.0434179f}, +{0.0415078f,-0.0826122f,0.0434179f},{0.0419187f,-0.0815236f,0.0434179f},{0.0411421f,-0.0830692f,0.0434179f}, +{0.040689f,-0.0834398f,0.0434179f},{0.0401687f,-0.0837073f,0.0434179f},{0.0396047f,-0.0838615f,0.0434179f}, +{0.0390206f,-0.083895f,0.0434179f},{0.0378962f,-0.0835978f,0.0434179f},{0.0384425f,-0.0838053f,0.0434179f}, +{0.0369897f,-0.0828716f,0.0434179f},{0.0374049f,-0.0832822f,0.0434179f},{0.0364565f,-0.0818399f,0.0434179f}, +{0.036669f,-0.0823837f,0.0434179f},{-0.0391526f,-0.0783052f,0.0434179f},{-0.0394438f,-0.0783204f,0.0340958f}, +{-0.0388588f,-0.0783208f,0.0340958f},{-0.038287f,-0.0784426f,0.0340958f},{-0.0386071f,-0.0783592f,0.0434179f}, +{-0.038082f,-0.0785175f,0.0434179f},{-0.0372802f,-0.0790247f,0.0340958f},{-0.0375977f,-0.0787756f,0.0434179f}, +{-0.0377538f,-0.0786801f,0.0340958f},{-0.0368894f,-0.0794592f,0.0340958f},{-0.0371735f,-0.0791238f,0.0434179f}, +{-0.0368257f,-0.079548f,0.0434179f},{-0.0365975f,-0.0799651f,0.0340958f},{-0.0364172f,-0.08052f,0.0340958f}, +{-0.0365672f,-0.0800316f,0.0434179f},{-0.036356f,-0.0811018f,0.0434179f},{-0.0364081f,-0.0805563f,0.0434179f}, +{-0.0396989f,-0.0783596f,0.0434179f},{-0.040016f,-0.0784417f,0.0340958f},{-0.0402234f,-0.0785201f,0.0434179f}, +{-0.0407062f,-0.0787792f,0.0434179f},{-0.0405499f,-0.0786794f,0.0340958f},{-0.0411295f,-0.0791268f,0.0434179f}, +{-0.0410221f,-0.0790223f,0.0340958f},{-0.0414145f,-0.0794572f,0.0340958f},{-0.041477f,-0.0795501f,0.0434179f}, +{-0.0417351f,-0.0800331f,0.0434179f},{-0.0417072f,-0.0799637f,0.0340958f},{-0.0418944f,-0.0805572f,0.0434179f}, +{-0.0418875f,-0.0805185f,0.0340958f},{-0.0419492f,-0.0811018f,0.0434179f},{-0.0391526f,-0.0811018f,0.0450982f}, +{-0.0426161f,-0.0842218f,0.0359602f},{-0.0431891f,-0.0834323f,0.0359602f},{-0.0429243f,-0.08384f,0.0340958f}, +{-0.0391526f,-0.0857628f,0.0359602f},{-0.0391526f,-0.0857628f,0.0340958f},{-0.0384183f,-0.0857044f,0.0340958f}, +{-0.0433059f,-0.0832175f,0.0340958f},{-0.0435344f,-0.0826925f,0.0359602f},{-0.0435842f,-0.0825456f,0.0340958f}, +{-0.0437429f,-0.0819115f,0.0359602f},{-0.0437552f,-0.0818361f,0.0340958f},{-0.0438134f,-0.0811018f,0.0359602f}, +{-0.0438136f,-0.0811018f,0.0340958f},{-0.0424484f,-0.0843976f,0.0340958f},{-0.0418879f,-0.0848756f,0.0340958f}, +{-0.0418906f,-0.084874f,0.0359602f},{-0.0412653f,-0.0852564f,0.0340958f},{-0.0410478f,-0.0853604f,0.0359602f}, +{-0.0405934f,-0.0855347f,0.0340958f},{-0.040121f,-0.0856612f,0.0359602f},{-0.0398834f,-0.085705f,0.0340958f}, +{-0.0372558f,-0.0853588f,0.0359602f},{-0.0381819f,-0.0856603f,0.0359602f},{-0.0377088f,-0.0855335f,0.0340958f}, +{-0.0358568f,-0.0843976f,0.0340958f},{-0.0364134f,-0.0848727f,0.0359602f},{-0.0364144f,-0.0848735f,0.0340958f}, +{-0.0370369f,-0.0852551f,0.0340958f},{-0.0347725f,-0.0826912f,0.0359602f},{-0.0351159f,-0.0834324f,0.0359602f}, +{-0.034998f,-0.0832145f,0.0340958f},{-0.0356886f,-0.0842194f,0.0359602f},{-0.0353788f,-0.0838371f,0.0340958f}, +{-0.03455f,-0.0818361f,0.0340958f},{-0.0345625f,-0.0819107f,0.0359602f},{-0.0347197f,-0.0825427f,0.0340958f}, +{-0.0344916f,-0.0811018f,0.0340958f},{-0.0344918f,-0.0811018f,0.0359602f},{-0.0391526f,-0.0838984f,0.062062f}, +{-0.0394438f,-0.0838832f,0.071384f},{-0.0388588f,-0.0838828f,0.071384f},{-0.038287f,-0.083761f,0.071384f}, +{-0.0386071f,-0.0838444f,0.062062f},{-0.038082f,-0.0836861f,0.062062f},{-0.0372802f,-0.0831789f,0.071384f}, +{-0.0375977f,-0.083428f,0.062062f},{-0.0377538f,-0.0835236f,0.071384f},{-0.0368894f,-0.0827444f,0.071384f}, +{-0.0371735f,-0.0830798f,0.062062f},{-0.0368257f,-0.0826556f,0.062062f},{-0.0365975f,-0.0822385f,0.071384f}, +{-0.0364172f,-0.0816837f,0.071384f},{-0.0365672f,-0.082172f,0.062062f},{-0.036356f,-0.0811018f,0.071384f}, +{-0.036356f,-0.0811018f,0.062062f},{-0.0364081f,-0.0816473f,0.062062f},{-0.0396989f,-0.083844f,0.062062f}, +{-0.040016f,-0.0837619f,0.071384f},{-0.0402234f,-0.0836835f,0.062062f},{-0.0407062f,-0.0834244f,0.062062f}, +{-0.0405499f,-0.0835242f,0.071384f},{-0.0411295f,-0.0830768f,0.062062f},{-0.0410221f,-0.0831813f,0.071384f}, +{-0.0414145f,-0.0827465f,0.071384f},{-0.041477f,-0.0826535f,0.062062f},{-0.0417351f,-0.0821705f,0.062062f}, +{-0.0417072f,-0.0822399f,0.071384f},{-0.0418944f,-0.0816464f,0.062062f},{-0.0418875f,-0.0816851f,0.071384f}, +{-0.0419492f,-0.0811018f,0.071384f},{-0.0419492f,-0.0811018f,0.062062f},{-0.0391526f,-0.0811018f,0.0603816f}, +{-0.0426161f,-0.0779818f,0.0695196f},{-0.0431891f,-0.0787713f,0.0695196f},{-0.0429243f,-0.0783636f,0.071384f}, +{-0.0391526f,-0.0764408f,0.0695196f},{-0.0391526f,-0.0764408f,0.071384f},{-0.0384183f,-0.0764992f,0.071384f}, +{-0.0433059f,-0.0789861f,0.071384f},{-0.0435344f,-0.0795111f,0.0695196f},{-0.0435842f,-0.079658f,0.071384f}, +{-0.0437429f,-0.0802921f,0.0695196f},{-0.0437552f,-0.0803675f,0.071384f},{-0.0438134f,-0.0811018f,0.0695196f}, +{-0.0438136f,-0.0811018f,0.071384f},{-0.0424484f,-0.077806f,0.071384f},{-0.0418879f,-0.077328f,0.071384f}, +{-0.0418906f,-0.0773296f,0.0695196f},{-0.0412653f,-0.0769472f,0.071384f},{-0.0410478f,-0.0768432f,0.0695196f}, +{-0.0405934f,-0.0766689f,0.071384f},{-0.040121f,-0.0765424f,0.0695196f},{-0.0398834f,-0.0764986f,0.071384f}, +{-0.0372558f,-0.0768448f,0.0695196f},{-0.0381819f,-0.0765433f,0.0695196f},{-0.0377088f,-0.0766702f,0.071384f}, +{-0.0358568f,-0.077806f,0.071384f},{-0.0364134f,-0.0773309f,0.0695196f},{-0.0364144f,-0.0773301f,0.071384f}, +{-0.0370369f,-0.0769485f,0.071384f},{-0.0347725f,-0.0795124f,0.0695196f},{-0.0351159f,-0.0787712f,0.0695196f}, +{-0.034998f,-0.0789891f,0.071384f},{-0.0356886f,-0.0779842f,0.0695196f},{-0.0353788f,-0.0783665f,0.071384f}, +{-0.03455f,-0.0803675f,0.071384f},{-0.0345625f,-0.0802929f,0.0695196f},{-0.0347197f,-0.079661f,0.071384f}, +{-0.0344916f,-0.0811018f,0.071384f},{-0.0344918f,-0.0811018f,0.0695196f},{-0.0445347f,-0.0811018f,0.0359602f}, +{-0.0431893f,-0.0834324f,0.0695196f},{-0.0418436f,-0.0857628f,0.0359602f},{-0.0418436f,-0.0857628f,0.0695196f}, +{-0.0445347f,-0.0811018f,0.0695196f},{-0.0394464f,-0.0838828f,0.0340958f},{-0.0388614f,-0.0838832f,0.0340958f}, +{-0.0377553f,-0.0835242f,0.0340958f},{-0.0382892f,-0.0837619f,0.0340958f},{-0.0437568f,-0.0803724f,0.0340958f}, +{-0.0435856f,-0.0796609f,0.0340958f},{-0.0417077f,-0.0822385f,0.0340958f},{-0.041888f,-0.0816837f,0.0340958f}, +{-0.0414158f,-0.0827444f,0.0340958f},{-0.041025f,-0.0831789f,0.0340958f},{-0.0405514f,-0.0835236f,0.0340958f}, +{-0.0400182f,-0.083761f,0.0340958f},{-0.0424407f,-0.0778104f,0.0340958f},{-0.0418908f,-0.0773296f,0.0340958f}, +{-0.040592f,-0.0766684f,0.0340958f},{-0.0412674f,-0.0769479f,0.0340958f},{-0.0398812f,-0.076498f,0.0340958f}, +{-0.0372831f,-0.0831813f,0.0340958f},{-0.0368221f,-0.0834323f,0.0340958f},{-0.0384233f,-0.0764984f,0.0340958f}, +{-0.0391526f,-0.0764408f,0.0340958f},{-0.0370366f,-0.0769492f,0.0340958f},{-0.0364134f,-0.0773311f,0.0340958f}, +{-0.0377121f,-0.0766694f,0.0340958f},{-0.036598f,-0.0822399f,0.0340958f},{-0.0368907f,-0.0827465f,0.0340958f}, +{-0.0358581f,-0.0778077f,0.0340958f},{-0.0350014f,-0.0789871f,0.0340958f},{-0.0347198f,-0.0796621f,0.0340958f}, +{-0.0345493f,-0.0803733f,0.0340958f},{-0.0364177f,-0.0816851f,0.0340958f},{-0.0353842f,-0.0783646f,0.0340958f}, +{-0.0433085f,-0.0789819f,0.0340958f},{-0.0429127f,-0.07837f,0.0340958f},{-0.0337705f,-0.0811018f,0.0359602f}, +{-0.0351159f,-0.0787712f,0.0359602f},{-0.0364616f,-0.0764408f,0.0359602f},{-0.0364616f,-0.0764408f,0.0695196f}, +{-0.0337705f,-0.0811018f,0.0695196f},{-0.0418436f,-0.0764408f,0.0359602f},{-0.0431893f,-0.0787712f,0.0359602f}, +{-0.0418436f,-0.0764408f,0.0695196f},{-0.0391526f,-0.0764412f,0.0359602f},{-0.0391526f,-0.0857625f,0.0695196f}, +{-0.0364616f,-0.0857628f,0.0359602f},{-0.0364616f,-0.0857628f,0.0695196f},{-0.0418908f,-0.084874f,0.071384f}, +{-0.0424407f,-0.0843932f,0.071384f},{-0.0345493f,-0.0818303f,0.071384f},{-0.0347198f,-0.0825415f,0.071384f}, +{-0.0412674f,-0.0852557f,0.071384f},{-0.040592f,-0.0855352f,0.071384f},{-0.0398812f,-0.0857056f,0.071384f}, +{-0.0391526f,-0.0857628f,0.071384f},{-0.0377121f,-0.0855343f,0.071384f},{-0.0370366f,-0.0852544f,0.071384f}, +{-0.0384233f,-0.0857052f,0.071384f},{-0.0364134f,-0.0848725f,0.071384f},{-0.0429127f,-0.0838337f,0.071384f}, +{-0.0437568f,-0.0818312f,0.071384f},{-0.0358581f,-0.0843959f,0.071384f},{-0.041888f,-0.08052f,0.071384f}, +{-0.0414831f,-0.0787713f,0.071384f},{-0.0414158f,-0.0794592f,0.071384f},{-0.0382892f,-0.0784417f,0.071384f}, +{-0.0388614f,-0.0783204f,0.071384f},{-0.0400182f,-0.0784426f,0.071384f},{-0.0372831f,-0.0790223f,0.071384f}, +{-0.0377553f,-0.0786794f,0.071384f},{-0.036598f,-0.0799637f,0.071384f},{-0.0368907f,-0.0794572f,0.071384f}, +{-0.0394464f,-0.0783208f,0.071384f},{-0.0364177f,-0.0805185f,0.071384f},{-0.0417077f,-0.0799651f,0.071384f}, +{-0.0405514f,-0.0786801f,0.071384f},{-0.0350014f,-0.0832165f,0.071384f},{-0.0435856f,-0.0825428f,0.071384f}, +{-0.0433085f,-0.0832217f,0.071384f},{-0.0353842f,-0.083839f,0.071384f},{-0.041025f,-0.0790247f,0.071384f}, +{-0.0351159f,-0.0834324f,0.0695196f},{-0.0437429f,-0.081909f,0.0695196f},{-0.0426159f,-0.0842209f,0.0695196f}, +{-0.0435333f,-0.0826889f,0.0695196f},{-0.0401218f,-0.0856608f,0.0695196f},{-0.0418931f,-0.0848714f,0.0695196f}, +{-0.0410504f,-0.0853584f,0.0695196f},{-0.0364122f,-0.0848726f,0.0695196f},{-0.0372562f,-0.08536f,0.0695196f}, +{-0.0381837f,-0.0856611f,0.0695196f},{-0.0356895f,-0.0842217f,0.0695196f},{-0.0347701f,-0.0826902f,0.0695196f}, +{-0.0345618f,-0.0819096f,0.0695196f},{-0.0365965f,-0.0799637f,0.062062f},{-0.0368892f,-0.0794571f,0.062062f}, +{-0.0364156f,-0.08052f,0.062062f},{-0.0372807f,-0.0790222f,0.062062f},{-0.0377546f,-0.0786785f,0.062062f}, +{-0.0382896f,-0.0784417f,0.062062f},{-0.0388616f,-0.0783205f,0.062062f},{-0.0394467f,-0.078321f,0.062062f}, +{-0.0405519f,-0.078683f,0.062062f},{-0.0400186f,-0.0784441f,0.062062f},{-0.0414146f,-0.0794606f,0.062062f}, +{-0.041024f,-0.0790267f,0.062062f},{-0.041887f,-0.0805216f,0.062062f},{-0.0417064f,-0.0799663f,0.062062f}, +{-0.0437429f,-0.0802946f,0.0359602f},{-0.0426161f,-0.077983f,0.0359602f},{-0.0435333f,-0.0795147f,0.0359602f}, +{-0.0401233f,-0.0765431f,0.0359602f},{-0.0418937f,-0.0773327f,0.0359602f},{-0.0410514f,-0.0768457f,0.0359602f}, +{-0.0364128f,-0.0773306f,0.0359602f},{-0.0372572f,-0.0768432f,0.0359602f},{-0.0381851f,-0.0765422f,0.0359602f}, +{-0.0356898f,-0.0779817f,0.0359602f},{-0.0347701f,-0.0795134f,0.0359602f},{-0.0345618f,-0.080294f,0.0359602f}, +{-0.0365965f,-0.0822399f,0.0434179f},{-0.0368892f,-0.0827465f,0.0434179f},{-0.0364156f,-0.0816836f,0.0434179f}, +{-0.0372807f,-0.0831814f,0.0434179f},{-0.0377546f,-0.0835251f,0.0434179f},{-0.0382896f,-0.0837619f,0.0434179f}, +{-0.0388616f,-0.0838831f,0.0434179f},{-0.0394467f,-0.0838826f,0.0434179f},{-0.0405519f,-0.0835206f,0.0434179f}, +{-0.0400186f,-0.0837595f,0.0434179f},{-0.0414146f,-0.082743f,0.0434179f},{-0.041024f,-0.0831769f,0.0434179f}, +{-0.041887f,-0.081682f,0.0434179f},{-0.0417064f,-0.0822373f,0.0434179f},{0.0391526f,0.0838984f,0.0434179f}, +{0.0388614f,0.0838832f,0.0340958f},{0.0394464f,0.0838828f,0.0340958f},{0.0400182f,0.083761f,0.0340958f}, +{0.0396981f,0.0838444f,0.0434179f},{0.0402232f,0.0836861f,0.0434179f},{0.041025f,0.0831789f,0.0340958f}, +{0.0407075f,0.083428f,0.0434179f},{0.0405514f,0.0835236f,0.0340958f},{0.0414158f,0.0827444f,0.0340958f}, +{0.0411317f,0.0830798f,0.0434179f},{0.0414795f,0.0826556f,0.0434179f},{0.0417077f,0.0822385f,0.0340958f}, +{0.041888f,0.0816837f,0.0340958f},{0.0417379f,0.082172f,0.0434179f},{0.0419492f,0.0811018f,0.0434179f}, +{0.0418971f,0.0816473f,0.0434179f},{0.0386063f,0.083844f,0.0434179f},{0.0382892f,0.0837619f,0.0340958f}, +{0.0380818f,0.0836835f,0.0434179f},{0.037599f,0.0834244f,0.0434179f},{0.0377553f,0.0835242f,0.0340958f}, +{0.0371757f,0.0830768f,0.0434179f},{0.0372831f,0.0831813f,0.0340958f},{0.0368907f,0.0827465f,0.0340958f}, +{0.0368282f,0.0826535f,0.0434179f},{0.0365701f,0.0821705f,0.0434179f},{0.036598f,0.0822399f,0.0340958f}, +{0.0364108f,0.0816464f,0.0434179f},{0.0364177f,0.0816851f,0.0340958f},{0.036356f,0.0811018f,0.0434179f}, +{0.0391526f,0.0811018f,0.0450982f},{0.035689f,0.0779818f,0.0359602f},{0.035116f,0.0787713f,0.0359602f}, +{0.0353809f,0.0783636f,0.0340958f},{0.0391526f,0.0764408f,0.0359602f},{0.0391526f,0.0764408f,0.0340958f}, +{0.0398869f,0.0764992f,0.0340958f},{0.0349993f,0.0789861f,0.0340958f},{0.0347708f,0.0795111f,0.0359602f}, +{0.0347209f,0.079658f,0.0340958f},{0.0345623f,0.0802921f,0.0359602f},{0.03455f,0.0803675f,0.0340958f}, +{0.0344918f,0.0811018f,0.0359602f},{0.0344916f,0.0811018f,0.0340958f},{0.0358568f,0.077806f,0.0340958f}, +{0.0364173f,0.077328f,0.0340958f},{0.0364146f,0.0773296f,0.0359602f},{0.0370399f,0.0769472f,0.0340958f}, +{0.0372574f,0.0768432f,0.0359602f},{0.0377117f,0.0766689f,0.0340958f},{0.0381842f,0.0765424f,0.0359602f}, +{0.0384218f,0.0764986f,0.0340958f},{0.0410494f,0.0768448f,0.0359602f},{0.0401233f,0.0765433f,0.0359602f}, +{0.0405964f,0.0766702f,0.0340958f},{0.0424484f,0.077806f,0.0340958f},{0.0418918f,0.0773309f,0.0359602f}, +{0.0418907f,0.0773301f,0.0340958f},{0.0412683f,0.0769485f,0.0340958f},{0.0435327f,0.0795124f,0.0359602f}, +{0.0431892f,0.0787712f,0.0359602f},{0.0433072f,0.0789891f,0.0340958f},{0.0426166f,0.0779842f,0.0359602f}, +{0.0429264f,0.0783665f,0.0340958f},{0.0437552f,0.0803675f,0.0340958f},{0.0437427f,0.0802929f,0.0359602f}, +{0.0435855f,0.079661f,0.0340958f},{0.0438136f,0.0811018f,0.0340958f},{0.0438134f,0.0811018f,0.0359602f}, +{0.0391526f,0.0783052f,0.062062f},{0.0388614f,0.0783204f,0.071384f},{0.0394464f,0.0783208f,0.071384f}, +{0.0400182f,0.0784426f,0.071384f},{0.0396981f,0.0783592f,0.062062f},{0.0402232f,0.0785175f,0.062062f}, +{0.041025f,0.0790247f,0.071384f},{0.0407075f,0.0787756f,0.062062f},{0.0405514f,0.0786801f,0.071384f}, +{0.0414158f,0.0794592f,0.071384f},{0.0411317f,0.0791238f,0.062062f},{0.0414795f,0.079548f,0.062062f}, +{0.0417077f,0.0799651f,0.071384f},{0.041888f,0.08052f,0.071384f},{0.0417379f,0.0800316f,0.062062f}, +{0.0419492f,0.0811018f,0.071384f},{0.0419492f,0.0811018f,0.062062f},{0.0418971f,0.0805563f,0.062062f}, +{0.0386063f,0.0783596f,0.062062f},{0.0382892f,0.0784417f,0.071384f},{0.0380818f,0.0785201f,0.062062f}, +{0.037599f,0.0787792f,0.062062f},{0.0377553f,0.0786794f,0.071384f},{0.0371757f,0.0791268f,0.062062f}, +{0.0372831f,0.0790223f,0.071384f},{0.0368907f,0.0794572f,0.071384f},{0.0368282f,0.0795501f,0.062062f}, +{0.0365701f,0.0800331f,0.062062f},{0.036598f,0.0799637f,0.071384f},{0.0364108f,0.0805572f,0.062062f}, +{0.0364177f,0.0805185f,0.071384f},{0.036356f,0.0811018f,0.071384f},{0.036356f,0.0811018f,0.062062f}, +{0.0391526f,0.0811018f,0.0603816f},{0.035689f,0.0842218f,0.0695196f},{0.035116f,0.0834323f,0.0695196f}, +{0.0353809f,0.08384f,0.071384f},{0.0391526f,0.0857628f,0.0695196f},{0.0391526f,0.0857628f,0.071384f}, +{0.0398869f,0.0857044f,0.071384f},{0.0349993f,0.0832175f,0.071384f},{0.0347708f,0.0826925f,0.0695196f}, +{0.0347209f,0.0825456f,0.071384f},{0.0345623f,0.0819115f,0.0695196f},{0.03455f,0.0818361f,0.071384f}, +{0.0344918f,0.0811018f,0.0695196f},{0.0344916f,0.0811018f,0.071384f},{0.0358568f,0.0843977f,0.071384f}, +{0.0364173f,0.0848756f,0.071384f},{0.0364146f,0.084874f,0.0695196f},{0.0370399f,0.0852564f,0.071384f}, +{0.0372574f,0.0853604f,0.0695196f},{0.0377117f,0.0855347f,0.071384f},{0.0381842f,0.0856612f,0.0695196f}, +{0.0384218f,0.085705f,0.071384f},{0.0410494f,0.0853588f,0.0695196f},{0.0401233f,0.0856603f,0.0695196f}, +{0.0405964f,0.0855335f,0.071384f},{0.0424484f,0.0843977f,0.071384f},{0.0418918f,0.0848727f,0.0695196f}, +{0.0418907f,0.0848735f,0.071384f},{0.0412683f,0.0852551f,0.071384f},{0.0435327f,0.0826912f,0.0695196f}, +{0.0431892f,0.0834324f,0.0695196f},{0.0433072f,0.0832145f,0.071384f},{0.0426166f,0.0842194f,0.0695196f}, +{0.0429264f,0.0838371f,0.071384f},{0.0437552f,0.0818361f,0.071384f},{0.0437427f,0.0819107f,0.0695196f}, +{0.0435855f,0.0825427f,0.071384f},{0.0438136f,0.0811018f,0.071384f},{0.0438134f,0.0811018f,0.0695196f}, +{0.0337705f,0.0811018f,0.0359602f},{0.0351159f,0.0787712f,0.0695196f},{0.0364616f,0.0764408f,0.0359602f}, +{0.0364616f,0.0764408f,0.0695196f},{0.0337705f,0.0811018f,0.0695196f},{0.0388588f,0.0783208f,0.0340958f}, +{0.0394438f,0.0783204f,0.0340958f},{0.0405499f,0.0786794f,0.0340958f},{0.040016f,0.0784417f,0.0340958f}, +{0.0345484f,0.0818312f,0.0340958f},{0.0347196f,0.0825428f,0.0340958f},{0.0365975f,0.0799651f,0.0340958f}, +{0.0364172f,0.08052f,0.0340958f},{0.0368894f,0.0794592f,0.0340958f},{0.0372802f,0.0790247f,0.0340958f}, +{0.0377538f,0.0786801f,0.0340958f},{0.038287f,0.0784426f,0.0340958f},{0.0358645f,0.0843932f,0.0340958f}, +{0.0364144f,0.084874f,0.0340958f},{0.0377132f,0.0855352f,0.0340958f},{0.0370378f,0.0852557f,0.0340958f}, +{0.038424f,0.0857056f,0.0340958f},{0.0410221f,0.0790223f,0.0340958f},{0.0414831f,0.0787713f,0.0340958f}, +{0.0398819f,0.0857052f,0.0340958f},{0.0391526f,0.0857628f,0.0340958f},{0.0412686f,0.0852544f,0.0340958f}, +{0.0418918f,0.0848725f,0.0340958f},{0.0405931f,0.0855343f,0.0340958f},{0.0417072f,0.0799637f,0.0340958f}, +{0.0414145f,0.0794572f,0.0340958f},{0.0424471f,0.0843959f,0.0340958f},{0.0433038f,0.0832165f,0.0340958f}, +{0.0435854f,0.0825415f,0.0340958f},{0.0437559f,0.0818303f,0.0340958f},{0.0418875f,0.0805185f,0.0340958f}, +{0.042921f,0.083839f,0.0340958f},{0.0349967f,0.0832217f,0.0340958f},{0.0353925f,0.0838337f,0.0340958f}, +{0.0445347f,0.0811018f,0.0359602f},{0.0431893f,0.0834324f,0.0359602f},{0.0418436f,0.0857628f,0.0359602f}, +{0.0418436f,0.0857628f,0.0695196f},{0.0445347f,0.0811018f,0.0695196f},{0.0364616f,0.0857628f,0.0359602f}, +{0.0351159f,0.0834324f,0.0359602f},{0.0364616f,0.0857628f,0.0695196f},{0.0391526f,0.0857624f,0.0359602f}, +{0.0391526f,0.0764411f,0.0695196f},{0.0418436f,0.0764408f,0.0359602f},{0.0418436f,0.0764408f,0.0695196f}, +{0.0364144f,0.0773296f,0.071384f},{0.0358645f,0.0778104f,0.071384f},{0.0437559f,0.0803733f,0.071384f}, +{0.0435854f,0.0796621f,0.071384f},{0.0370378f,0.0769479f,0.071384f},{0.0377132f,0.0766684f,0.071384f}, +{0.038424f,0.076498f,0.071384f},{0.0391526f,0.0764408f,0.071384f},{0.0405931f,0.0766694f,0.071384f}, +{0.0412686f,0.0769492f,0.071384f},{0.0398819f,0.0764984f,0.071384f},{0.0418918f,0.0773311f,0.071384f}, +{0.0353925f,0.07837f,0.071384f},{0.0345484f,0.0803724f,0.071384f},{0.0424471f,0.0778077f,0.071384f}, +{0.0364172f,0.0816837f,0.071384f},{0.0368221f,0.0834323f,0.071384f},{0.0368894f,0.0827444f,0.071384f}, +{0.040016f,0.0837619f,0.071384f},{0.0394438f,0.0838832f,0.071384f},{0.038287f,0.083761f,0.071384f}, +{0.0410221f,0.0831813f,0.071384f},{0.0405499f,0.0835242f,0.071384f},{0.0417072f,0.0822399f,0.071384f}, +{0.0414145f,0.0827465f,0.071384f},{0.0388588f,0.0838828f,0.071384f},{0.0418875f,0.0816851f,0.071384f}, +{0.0365975f,0.0822385f,0.071384f},{0.0377538f,0.0835236f,0.071384f},{0.0433038f,0.0789871f,0.071384f}, +{0.0347196f,0.0796609f,0.071384f},{0.0349967f,0.0789819f,0.071384f},{0.042921f,0.0783646f,0.071384f}, +{0.0372802f,0.0831789f,0.071384f},{0.0431893f,0.0787712f,0.0695196f},{0.0345623f,0.0802946f,0.0695196f}, +{0.0356893f,0.0779827f,0.0695196f},{0.0347719f,0.0795147f,0.0695196f},{0.0381833f,0.0765428f,0.0695196f}, +{0.0364121f,0.0773322f,0.0695196f},{0.0372548f,0.0768453f,0.0695196f},{0.041893f,0.0773311f,0.0695196f}, +{0.041049f,0.0768436f,0.0695196f},{0.0401215f,0.0765425f,0.0695196f},{0.0426157f,0.077982f,0.0695196f}, +{0.0435351f,0.0795134f,0.0695196f},{0.0437434f,0.080294f,0.0695196f},{0.0417086f,0.0822399f,0.062062f}, +{0.041416f,0.0827465f,0.062062f},{0.0418896f,0.0816836f,0.062062f},{0.0410244f,0.0831814f,0.062062f}, +{0.0405506f,0.0835251f,0.062062f},{0.0400156f,0.0837619f,0.062062f},{0.0394436f,0.0838831f,0.062062f}, +{0.0388585f,0.0838826f,0.062062f},{0.0377533f,0.0835206f,0.062062f},{0.0382866f,0.0837595f,0.062062f}, +{0.0368906f,0.082743f,0.062062f},{0.0372812f,0.0831769f,0.062062f},{0.0364182f,0.081682f,0.062062f}, +{0.0365988f,0.0822373f,0.062062f},{0.0345623f,0.081909f,0.0359602f},{0.035689f,0.0842206f,0.0359602f}, +{0.0347719f,0.0826889f,0.0359602f},{0.0381819f,0.0856605f,0.0359602f},{0.0364115f,0.0848709f,0.0359602f}, +{0.0372538f,0.0853579f,0.0359602f},{0.0418924f,0.084873f,0.0359602f},{0.041048f,0.0853604f,0.0359602f}, +{0.0401201f,0.0856614f,0.0359602f},{0.0426154f,0.0842219f,0.0359602f},{0.0435351f,0.0826902f,0.0359602f}, +{0.0437434f,0.0819096f,0.0359602f},{0.0417086f,0.0799637f,0.0434179f},{0.041416f,0.0794571f,0.0434179f}, +{0.0418896f,0.08052f,0.0434179f},{0.0410244f,0.0790222f,0.0434179f},{0.0405506f,0.0786785f,0.0434179f}, +{0.0400156f,0.0784417f,0.0434179f},{0.0394436f,0.0783205f,0.0434179f},{0.0388585f,0.078321f,0.0434179f}, +{0.0377533f,0.078683f,0.0434179f},{0.0382866f,0.0784441f,0.0434179f},{0.0368906f,0.0794606f,0.0434179f}, +{0.0372812f,0.0790267f,0.0434179f},{0.0364182f,0.0805216f,0.0434179f},{0.0365988f,0.0799663f,0.0434179f}, +{-0.023239f,-0.071786f,0.071384f},{-0.0231144f,-0.0708235f,0.0732484f},{-0.023239f,-0.0717882f,0.0732484f}, +{-0.0231106f,-0.0727502f,0.071384f},{-0.0231103f,-0.0727513f,0.0732484f},{-0.0227371f,-0.0736484f,0.071384f}, +{-0.0227371f,-0.0736484f,0.0732484f},{-0.0231141f,-0.0708224f,0.071384f},{-0.0227444f,-0.0699238f,0.0732484f}, +{-0.0227444f,-0.0699238f,0.071384f},{-0.0225127f,-0.00424291f,0.071384f},{-0.0216035f,-0.00385992f,0.0732484f}, +{-0.0225146f,-0.00424405f,0.0732484f},{-0.0232912f,-0.00485238f,0.071384f},{-0.023292f,-0.00485321f,0.0732484f}, +{-0.0238822f,-0.00564511f,0.071384f},{-0.0238822f,-0.00564511f,0.0732484f},{-0.0216024f,-0.00385961f,0.071384f}, +{-0.0206235f,-0.00372882f,0.0732484f},{-0.0206235f,-0.00372882f,0.071384f},{-0.0243511f,0.0075482f,0.071384f}, +{-0.024197f,0.00852259f,0.0732484f},{-0.0243512f,0.00754595f,0.0732484f},{-0.024244f,0.0065653f,0.071384f}, +{-0.0242437f,0.00656417f,0.0732484f},{-0.0238822f,0.00564511f,0.071384f},{-0.0238822f,0.00564511f,0.0732484f}, +{-0.0241967f,0.00852371f,0.071384f},{-0.0237915f,0.00942436f,0.0732484f},{-0.0237915f,0.00942436f,0.071384f}, +{-0.0213716f,0.0750107f,0.071384f},{-0.0204747f,0.0753817f,0.0732484f},{-0.0213735f,0.0750096f,0.0732484f}, +{-0.022144f,0.0744194f,0.071384f},{-0.0221448f,0.0744186f,0.0732484f},{-0.0227371f,0.0736484f,0.071384f}, +{-0.0227371f,0.0736484f,0.0732484f},{-0.0204736f,0.075382f,0.071384f},{-0.0195103f,0.0755086f,0.0732484f}, +{-0.0195103f,0.0755086f,0.071384f},{-0.0391526f,-0.00279661f,0.071384f},{-0.0397007f,-0.00274238f,0.0732484f}, +{-0.0391526f,-0.00279661f,0.0732484f},{-0.0380824f,-0.00258373f,0.0732484f},{-0.0380824f,-0.00258373f,0.071384f}, +{-0.0386045f,-0.00274238f,0.0732484f},{-0.0386045f,-0.00274238f,0.071384f},{-0.037601f,-0.00232674f,0.071384f}, +{-0.0371751f,-0.00197751f,0.071384f},{-0.0371751f,-0.00197751f,0.0732484f},{-0.0368259f,-0.00155157f,0.071384f}, +{-0.0368259f,-0.00155157f,0.0732484f},{-0.037601f,-0.00232674f,0.0732484f},{-0.036356f,3.97423e-017f,0.071384f}, +{-0.0364102f,-0.000548134f,0.071384f},{-0.0364102f,-0.000548134f,0.0732484f},{-0.0365689f,-0.00107022f,0.0732484f}, +{-0.0365689f,-0.00107022f,0.071384f},{-0.036356f,3.97423e-017f,0.0732484f},{-0.0397007f,-0.00274238f,0.071384f}, +{-0.0402228f,-0.00258373f,0.0732484f},{-0.0402228f,-0.00258373f,0.071384f},{-0.0407042f,-0.00232674f,0.071384f}, +{-0.0407042f,-0.00232674f,0.0732484f},{-0.0411301f,-0.00197751f,0.071384f},{-0.0411301f,-0.00197751f,0.0732484f}, +{-0.0414793f,-0.00155157f,0.0732484f},{-0.0414793f,-0.00155157f,0.071384f},{-0.0417363f,-0.00107022f,0.071384f}, +{-0.0417363f,-0.00107022f,0.0732484f},{-0.041895f,-0.000548134f,0.071384f},{-0.041895f,-0.000548134f,0.0732484f}, +{-0.0419492f,3.97423e-017f,0.0732484f},{-0.0419492f,3.97423e-017f,0.071384f},{0.0391526f,-0.00279661f,0.071384f}, +{0.0386045f,-0.00274238f,0.0732484f},{0.0391526f,-0.00279661f,0.0732484f},{0.0402228f,-0.00258373f,0.0732484f}, +{0.0402228f,-0.00258373f,0.071384f},{0.0397007f,-0.00274238f,0.0732484f},{0.0397007f,-0.00274238f,0.071384f}, +{0.0407042f,-0.00232674f,0.071384f},{0.0411301f,-0.00197751f,0.071384f},{0.0411301f,-0.00197751f,0.0732484f}, +{0.0414793f,-0.00155157f,0.071384f},{0.0414793f,-0.00155157f,0.0732484f},{0.0407042f,-0.00232674f,0.0732484f}, +{0.0419492f,3.97423e-017f,0.071384f},{0.041895f,-0.000548134f,0.071384f},{0.041895f,-0.000548134f,0.0732484f}, +{0.0417363f,-0.00107022f,0.0732484f},{0.0417363f,-0.00107022f,0.071384f},{0.0419492f,3.97423e-017f,0.0732484f}, +{0.0386045f,-0.00274238f,0.071384f},{0.0380824f,-0.00258373f,0.0732484f},{0.0380824f,-0.00258373f,0.071384f}, +{0.037601f,-0.00232674f,0.071384f},{0.037601f,-0.00232674f,0.0732484f},{0.0371751f,-0.00197751f,0.071384f}, +{0.0371751f,-0.00197751f,0.0732484f},{0.0368259f,-0.00155157f,0.0732484f},{0.0368259f,-0.00155157f,0.071384f}, +{0.0365689f,-0.00107022f,0.071384f},{0.0365689f,-0.00107022f,0.0732484f},{0.0364102f,-0.000548134f,0.071384f}, +{0.0364102f,-0.000548134f,0.0732484f},{0.036356f,3.97423e-017f,0.0732484f},{0.036356f,3.97423e-017f,0.071384f}, +{-0.0391526f,0.0783052f,0.071384f},{-0.0397007f,0.0783594f,0.0732484f},{-0.0391526f,0.0783052f,0.0732484f}, +{-0.0380824f,0.0785181f,0.0732484f},{-0.0380824f,0.0785181f,0.071384f},{-0.0386045f,0.0783594f,0.0732484f}, +{-0.0386045f,0.0783594f,0.071384f},{-0.037601f,0.0787751f,0.071384f},{-0.0371751f,0.0791243f,0.071384f}, +{-0.0371751f,0.0791243f,0.0732484f},{-0.0368259f,0.0795502f,0.071384f},{-0.0368259f,0.0795502f,0.0732484f}, +{-0.037601f,0.0787751f,0.0732484f},{-0.0364102f,0.0805537f,0.071384f},{-0.0364102f,0.0805537f,0.0732484f}, +{-0.0365689f,0.0800316f,0.0732484f},{-0.0365689f,0.0800316f,0.071384f},{-0.036356f,0.0811018f,0.0732484f}, +{-0.0397007f,0.0783594f,0.071384f},{-0.0402228f,0.0785181f,0.0732484f},{-0.0402228f,0.0785181f,0.071384f}, +{-0.0407042f,0.0787751f,0.071384f},{-0.0407042f,0.0787751f,0.0732484f},{-0.0411301f,0.0791243f,0.071384f}, +{-0.0411301f,0.0791243f,0.0732484f},{-0.0414793f,0.0795502f,0.0732484f},{-0.0414793f,0.0795502f,0.071384f}, +{-0.0417363f,0.0800316f,0.071384f},{-0.0417363f,0.0800316f,0.0732484f},{-0.041895f,0.0805537f,0.071384f}, +{-0.041895f,0.0805537f,0.0732484f},{-0.0419492f,0.0811018f,0.0732484f},{0.0391526f,0.0783052f,0.071384f}, +{0.0386045f,0.0783594f,0.0732484f},{0.0391526f,0.0783052f,0.0732484f},{0.0402228f,0.0785181f,0.0732484f}, +{0.0402228f,0.0785181f,0.071384f},{0.0397007f,0.0783594f,0.0732484f},{0.0397007f,0.0783594f,0.071384f}, +{0.0407042f,0.0787751f,0.071384f},{0.0411301f,0.0791243f,0.071384f},{0.0411301f,0.0791243f,0.0732484f}, +{0.0414793f,0.0795502f,0.071384f},{0.0414793f,0.0795502f,0.0732484f},{0.0407042f,0.0787751f,0.0732484f}, +{0.041895f,0.0805537f,0.071384f},{0.041895f,0.0805537f,0.0732484f},{0.0417363f,0.0800316f,0.0732484f}, +{0.0417363f,0.0800316f,0.071384f},{0.0419492f,0.0811018f,0.0732484f},{0.0386045f,0.0783594f,0.071384f}, +{0.0380824f,0.0785181f,0.0732484f},{0.0380824f,0.0785181f,0.071384f},{0.037601f,0.0787751f,0.071384f}, +{0.037601f,0.0787751f,0.0732484f},{0.0371751f,0.0791243f,0.071384f},{0.0371751f,0.0791243f,0.0732484f}, +{0.0368259f,0.0795502f,0.0732484f},{0.0368259f,0.0795502f,0.071384f},{0.0365689f,0.0800316f,0.071384f}, +{0.0365689f,0.0800316f,0.0732484f},{0.0364102f,0.0805537f,0.071384f},{0.0364102f,0.0805537f,0.0732484f}, +{0.036356f,0.0811018f,0.0732484f},{0.0391526f,-0.0838984f,0.071384f},{0.0386045f,-0.0838442f,0.0732484f}, +{0.0391526f,-0.0838984f,0.0732484f},{0.0402228f,-0.0836855f,0.0732484f},{0.0402228f,-0.0836855f,0.071384f}, +{0.0397007f,-0.0838442f,0.0732484f},{0.0397007f,-0.0838442f,0.071384f},{0.0407042f,-0.0834285f,0.071384f}, +{0.0411301f,-0.0830793f,0.071384f},{0.0411301f,-0.0830793f,0.0732484f},{0.0414793f,-0.0826534f,0.071384f}, +{0.0414793f,-0.0826534f,0.0732484f},{0.0407042f,-0.0834285f,0.0732484f},{0.0419492f,-0.0811018f,0.071384f}, +{0.041895f,-0.0816499f,0.071384f},{0.041895f,-0.0816499f,0.0732484f},{0.0417363f,-0.082172f,0.0732484f}, +{0.0417363f,-0.082172f,0.071384f},{0.0419492f,-0.0811018f,0.0732484f},{0.0386045f,-0.0838442f,0.071384f}, +{0.0380824f,-0.0836855f,0.0732484f},{0.0380824f,-0.0836855f,0.071384f},{0.037601f,-0.0834285f,0.071384f}, +{0.037601f,-0.0834285f,0.0732484f},{0.0371751f,-0.0830793f,0.071384f},{0.0371751f,-0.0830793f,0.0732484f}, +{0.0368259f,-0.0826534f,0.0732484f},{0.0368259f,-0.0826534f,0.071384f},{0.0365689f,-0.082172f,0.071384f}, +{0.0365689f,-0.082172f,0.0732484f},{0.0364102f,-0.0816499f,0.071384f},{0.0364102f,-0.0816499f,0.0732484f}, +{0.036356f,-0.0811018f,0.0732484f},{0.036356f,-0.0811018f,0.071384f},{-0.0391526f,-0.0838984f,0.071384f}, +{-0.0397007f,-0.0838442f,0.0732484f},{-0.0391526f,-0.0838984f,0.0732484f},{-0.0380824f,-0.0836855f,0.0732484f}, +{-0.0380824f,-0.0836855f,0.071384f},{-0.0386045f,-0.0838442f,0.0732484f},{-0.0386045f,-0.0838442f,0.071384f}, +{-0.037601f,-0.0834285f,0.071384f},{-0.0371751f,-0.0830793f,0.071384f},{-0.0371751f,-0.0830793f,0.0732484f}, +{-0.0368259f,-0.0826534f,0.071384f},{-0.0368259f,-0.0826534f,0.0732484f},{-0.037601f,-0.0834285f,0.0732484f}, +{-0.0364102f,-0.0816499f,0.071384f},{-0.0364102f,-0.0816499f,0.0732484f},{-0.0365689f,-0.082172f,0.0732484f}, +{-0.0365689f,-0.082172f,0.071384f},{-0.036356f,-0.0811018f,0.0732484f},{-0.0397007f,-0.0838442f,0.071384f}, +{-0.0402228f,-0.0836855f,0.0732484f},{-0.0402228f,-0.0836855f,0.071384f},{-0.0407042f,-0.0834285f,0.071384f}, +{-0.0407042f,-0.0834285f,0.0732484f},{-0.0411301f,-0.0830793f,0.071384f},{-0.0411301f,-0.0830793f,0.0732484f}, +{-0.0414793f,-0.0826534f,0.0732484f},{-0.0414793f,-0.0826534f,0.071384f},{-0.0417363f,-0.082172f,0.071384f}, +{-0.0417363f,-0.082172f,0.0732484f},{-0.041895f,-0.0816499f,0.071384f},{-0.041895f,-0.0816499f,0.0732484f}, +{-0.0419492f,-0.0811018f,0.0732484f},{0.0225785f,-0.0258241f,0.071384f},{0.0237254f,-0.0222932f,0.071384f}, +{0.0237253f,-0.0222933f,0.0732484f},{0.0216792f,-0.0294283f,0.071384f},{0.0225785f,-0.0258242f,0.0732484f}, +{0.0216792f,-0.0294286f,0.0732484f},{0.0210317f,-0.0330928f,0.071384f},{0.0206399f,-0.0368049f,0.0732484f}, +{0.0205085f,-0.0405509f,0.071384f},{0.02064f,-0.0368047f,0.071384f},{0.0210316f,-0.0330931f,0.0732484f}, +{0.0205085f,-0.0405509f,0.0732484f},{0.0251155f,-0.0188485f,0.0732484f},{0.0267447f,-0.0155029f,0.0732484f}, +{0.0251156f,-0.0188483f,0.071384f},{0.0267448f,-0.0155026f,0.071384f},{0.0286089f,-0.0122693f,0.0732484f}, +{0.028609f,-0.0122691f,0.071384f},{0.0307038f,-0.00916071f,0.0732484f},{0.0307038f,-0.00916071f,0.071384f}, +{-0.03984f,-0.0885276f,0.0732484f},{-0.0398371f,-0.0885279f,0.071384f},{-0.0387004f,-0.0885456f,0.071384f}, +{-0.0409568f,-0.0883379f,0.071384f},{-0.0409588f,-0.0883374f,0.0732484f},{-0.0420378f,-0.0879786f,0.0732484f}, +{-0.042035f,-0.0879797f,0.071384f},{-0.0430486f,-0.0874608f,0.0732484f},{-0.043047f,-0.0874618f,0.071384f}, +{-0.0439672f,-0.0867969f,0.071384f},{-0.0439685f,-0.086796f,0.0732484f},{-0.0447784f,-0.0859974f,0.0732484f}, +{-0.0447773f,-0.0859985f,0.071384f},{-0.045456f,-0.0850872f,0.0732484f},{-0.0454557f,-0.0850877f,0.071384f}, +{-0.0459883f,-0.0840833f,0.0732484f},{-0.0459883f,-0.0840833f,0.071384f},{-0.0387033f,-0.0885458f,0.0732484f}, +{-0.037576f,-0.0883909f,0.071384f},{-0.0375781f,-0.0883913f,0.0732484f},{-0.0364863f,-0.0880664f,0.071384f}, +{-0.0364891f,-0.0880674f,0.0732484f},{-0.0354613f,-0.0875818f,0.0732484f},{-0.0354596f,-0.0875808f,0.071384f}, +{-0.0345192f,-0.0869454f,0.071384f},{-0.0345204f,-0.0869463f,0.0732484f},{-0.0336844f,-0.0861728f,0.071384f}, +{-0.0336855f,-0.0861739f,0.0732484f},{-0.0329787f,-0.085285f,0.0732484f},{-0.0329784f,-0.0852846f,0.071384f}, +{-0.0324146f,-0.0842979f,0.071384f},{-0.0324146f,-0.0842979f,0.0732484f},{-0.0440592f,-0.00561614f,0.071384f}, +{-0.0430328f,-0.00636862f,0.071384f},{-0.0440603f,-0.00561515f,0.0732484f},{-0.044941f,-0.00470215f,0.0732484f}, +{-0.0449406f,-0.00470266f,0.071384f},{-0.0456552f,-0.0036514f,0.0732484f},{-0.0456542f,-0.00365287f,0.071384f}, +{-0.046181f,-0.00249363f,0.071384f},{-0.0461811f,-0.00249326f,0.0732484f},{-0.046502f,-0.00126624f,0.0732484f}, +{-0.0465017f,-0.00126733f,0.071384f},{-0.0466102f,3.97423e-017f,0.0732484f},{-0.0466102f,3.97423e-017f,0.071384f}, +{-0.0430341f,-0.00636786f,0.0732484f},{-0.0418973f,-0.00693419f,0.071384f},{-0.0418979f,-0.00693393f,0.0732484f}, +{-0.0406822f,-0.00729899f,0.0732484f},{-0.0406805f,-0.00729943f,0.071384f},{-0.0394178f,-0.00745289f,0.071384f}, +{-0.0394182f,-0.00745292f,0.0732484f},{-0.0381511f,-0.00739011f,0.071384f},{-0.0381522f,-0.00739019f,0.0732484f}, +{-0.0369109f,-0.00711273f,0.071384f},{-0.0369109f,-0.00711273f,0.0732484f},{-0.0450626f,0.0765535f,0.0732484f}, +{-0.0450608f,0.0765512f,0.071384f},{-0.0443005f,0.075706f,0.071384f},{-0.0456834f,0.0775011f,0.071384f}, +{-0.0456844f,0.0775029f,0.0732484f},{-0.0461555f,0.0785378f,0.0732484f},{-0.0461544f,0.078535f,0.071384f}, +{-0.0464637f,0.0796309f,0.0732484f},{-0.0464633f,0.079629f,0.071384f},{-0.0466021f,0.0807558f,0.071384f}, +{-0.0466023f,0.0807574f,0.0732484f},{-0.046568f,0.0818943f,0.0732484f},{-0.0465681f,0.0818927f,0.071384f}, +{-0.046362f,0.0830101f,0.0732484f},{-0.0463621f,0.0830096f,0.071384f},{-0.0459883f,0.0840833f,0.0732484f}, +{-0.0459883f,0.0840833f,0.071384f},{-0.0443026f,0.0757081f,0.0732484f},{-0.0434222f,0.0749873f,0.071384f}, +{-0.0434238f,0.0749885f,0.0732484f},{-0.0424429f,0.0744094f,0.071384f},{-0.0424456f,0.0744107f,0.0732484f}, +{-0.0413904f,0.0739879f,0.0732484f},{-0.0413886f,0.0739873f,0.071384f},{-0.040283f,0.0737303f,0.071384f}, +{-0.0402846f,0.0737307f,0.0732484f},{-0.0391489f,0.0736442f,0.071384f},{-0.0391504f,0.0736443f,0.0732484f}, +{-0.0380181f,0.073731f,0.0732484f},{-0.0380175f,0.073731f,0.071384f},{-0.0369109f,0.0739891f,0.071384f}, +{-0.0369109f,0.0739891f,0.0732484f},{0.0225785f,0.0552777f,0.071384f},{0.0237254f,0.0588086f,0.071384f}, +{0.0237253f,0.0588085f,0.0732484f},{0.0216792f,0.0516735f,0.071384f},{0.0225785f,0.0552776f,0.0732484f}, +{0.0216792f,0.0516732f,0.0732484f},{0.0210317f,0.048009f,0.071384f},{0.0206399f,0.0442969f,0.0732484f}, +{0.0205085f,0.0405509f,0.071384f},{0.02064f,0.0442971f,0.071384f},{0.0210316f,0.0480087f,0.0732484f}, +{0.0205085f,0.0405509f,0.0732484f},{0.0251155f,0.0622533f,0.0732484f},{0.0267447f,0.0655989f,0.0732484f}, +{0.0251156f,0.0622535f,0.071384f},{0.0267448f,0.0655992f,0.071384f},{0.0286089f,0.0688326f,0.0732484f}, +{0.028609f,0.0688327f,0.071384f},{0.0307038f,0.0719411f,0.0732484f},{0.0307038f,0.0719411f,0.071384f}, +{0.0167768f,-0.0552561f,0.0732484f},{0.0159195f,-0.0513911f,0.0732484f},{0.0167768f,-0.0552561f,0.071384f}, +{0.0159195f,-0.0513911f,0.071384f},{0.0153227f,-0.0474729f,0.0732484f},{0.0149897f,-0.0435148f,0.0732484f}, +{0.0153227f,-0.0474729f,0.071384f},{0.0149241f,-0.0395297f,0.0732484f},{0.0149897f,-0.0435148f,0.071384f}, +{0.0149241f,-0.0395297f,0.071384f},{0.0178914f,-0.059055f,0.071384f},{0.0192597f,-0.0627747f,0.071384f}, +{0.0178914f,-0.059055f,0.0732484f},{0.0208785f,-0.066402f,0.071384f},{0.0192597f,-0.0627747f,0.0732484f}, +{0.0208785f,-0.066402f,0.0732484f},{0.0227444f,-0.0699238f,0.071384f},{0.0227444f,-0.0699238f,0.0732484f}, +{0.0173199f,0.0238768f,0.0732484f},{0.0163293f,0.0277099f,0.0732484f},{0.0173199f,0.0238768f,0.071384f}, +{0.0163293f,0.0277099f,0.071384f},{0.0155973f,0.031605f,0.0732484f},{0.0151276f,0.0355493f,0.0732484f}, +{0.0155973f,0.031605f,0.071384f},{0.0149241f,0.0395297f,0.0732484f},{0.0151276f,0.0355493f,0.071384f}, +{0.0149241f,0.0395297f,0.071384f},{0.0185653f,0.0201187f,0.071384f},{0.0200615f,0.0164487f,0.071384f}, +{0.0185653f,0.0201187f,0.0732484f},{0.0218049f,0.0128796f,0.071384f},{0.0200615f,0.0164487f,0.0732484f}, +{0.0218049f,0.0128796f,0.0732484f},{0.0237915f,0.00942436f,0.071384f},{0.0237915f,0.00942436f,0.0732484f}, +{0.0149897f,0.0435148f,0.0732484f},{0.0167768f,0.0552561f,0.0732484f},{0.0159195f,0.0513911f,0.071384f}, +{0.0159195f,0.0513911f,0.0732484f},{0.0153227f,0.0474729f,0.0732484f},{0.0153227f,0.0474729f,0.071384f}, +{0.0149897f,0.0435148f,0.071384f},{0.0192597f,0.0627747f,0.071384f},{0.0192597f,0.0627747f,0.0732484f}, +{0.0208785f,0.066402f,0.0732484f},{0.0167768f,0.0552561f,0.071384f},{0.0178914f,0.059055f,0.0732484f}, +{0.0178914f,0.059055f,0.071384f},{0.0227444f,0.0699238f,0.0732484f},{0.0208785f,0.066402f,0.071384f}, +{0.0227444f,0.0699238f,0.071384f},{-0.0206235f,0.00372882f,0.071384f},{-0.0206235f,0.00372882f,0.0732484f}, +{0.0206235f,0.00372882f,0.0732484f},{0.0206235f,0.00372882f,0.071384f},{-0.0149256f,0.0416576f,0.0732484f}, +{-0.0149993f,0.0374031f,0.0732484f},{-0.0149257f,0.0416577f,0.071384f},{-0.0151577f,0.0458938f,0.071384f}, +{-0.0151576f,0.0458937f,0.0732484f},{-0.0156914f,0.0500904f,0.071384f},{-0.0156914f,0.0500902f,0.0732484f}, +{-0.0165229f,0.0542313f,0.0732484f},{-0.016523f,0.0542315f,0.071384f},{-0.0176481f,0.0583013f,0.071384f}, +{-0.017648f,0.0583011f,0.0732484f},{-0.0190628f,0.0622838f,0.071384f},{-0.0190627f,0.0622837f,0.0732484f}, +{-0.0207629f,0.0661632f,0.0732484f},{-0.0207629f,0.0661633f,0.071384f},{-0.0227444f,0.0699238f,0.071384f}, +{-0.0227444f,0.0699238f,0.0732484f},{-0.0149993f,0.0374031f,0.071384f},{-0.0153777f,0.0331776f,0.071384f}, +{-0.0153777f,0.0331775f,0.0732484f},{-0.0160564f,0.0290019f,0.0732484f},{-0.0160564f,0.0290021f,0.071384f}, +{-0.0170307f,0.024892f,0.0732484f},{-0.0170307f,0.0248922f,0.071384f},{-0.018296f,0.0208638f,0.071384f}, +{-0.018296f,0.0208636f,0.0732484f},{-0.0198477f,0.0169324f,0.0732484f},{-0.0198476f,0.0169326f,0.071384f}, +{-0.021681f,0.0131141f,0.0732484f},{-0.021681f,0.0131142f,0.071384f},{0.0151276f,-0.0355493f,0.0732484f}, +{0.0173199f,-0.0238768f,0.0732484f},{0.0163293f,-0.0277099f,0.071384f},{0.0163293f,-0.0277099f,0.0732484f}, +{0.0155973f,-0.031605f,0.0732484f},{0.0155973f,-0.031605f,0.071384f},{0.0151276f,-0.0355493f,0.071384f}, +{0.0200615f,-0.0164487f,0.071384f},{0.0200615f,-0.0164487f,0.0732484f},{0.0218049f,-0.0128796f,0.0732484f}, +{0.0173199f,-0.0238768f,0.071384f},{0.0185653f,-0.0201187f,0.0732484f},{0.0185653f,-0.0201187f,0.071384f}, +{0.0237915f,-0.00942436f,0.0732484f},{0.0218049f,-0.0128796f,0.071384f},{0.0237915f,-0.00942436f,0.071384f}, +{-0.0195103f,-0.0755086f,0.071384f},{0.0195103f,-0.0755086f,0.0732484f},{0.0195103f,-0.0755086f,0.071384f}, +{-0.0195103f,-0.0755086f,0.0732484f},{-0.0149993f,-0.0374031f,0.0732484f},{-0.0149257f,-0.0416576f,0.0732484f}, +{-0.0149993f,-0.0374031f,0.071384f},{-0.0153777f,-0.0331775f,0.071384f},{-0.0153777f,-0.0331776f,0.0732484f}, +{-0.0160564f,-0.0290019f,0.071384f},{-0.0160564f,-0.0290021f,0.0732484f},{-0.0170307f,-0.0248922f,0.0732484f}, +{-0.0170307f,-0.024892f,0.071384f},{-0.018296f,-0.0208636f,0.071384f},{-0.018296f,-0.0208638f,0.0732484f}, +{-0.0198477f,-0.0169324f,0.071384f},{-0.0198476f,-0.0169326f,0.0732484f},{-0.021681f,-0.0131142f,0.0732484f}, +{-0.021681f,-0.0131141f,0.071384f},{-0.0237915f,-0.00942436f,0.071384f},{-0.0237915f,-0.00942436f,0.0732484f}, +{-0.0149256f,-0.0416576f,0.071384f},{-0.0151576f,-0.0458937f,0.071384f},{-0.0151577f,-0.0458938f,0.0732484f}, +{-0.0156914f,-0.0500904f,0.0732484f},{-0.0156914f,-0.0500902f,0.071384f},{-0.016523f,-0.0542315f,0.0732484f}, +{-0.0165229f,-0.0542313f,0.071384f},{-0.017648f,-0.0583011f,0.071384f},{-0.0176481f,-0.0583013f,0.0732484f}, +{-0.0190628f,-0.0622838f,0.0732484f},{-0.0190627f,-0.0622837f,0.071384f},{-0.0207629f,-0.0661633f,0.0732484f}, +{-0.0207629f,-0.0661632f,0.071384f},{0.02064f,0.0368047f,0.0732484f},{0.0206399f,0.0368049f,0.071384f}, +{0.0225785f,0.0258241f,0.0732484f},{0.0225785f,0.0258242f,0.071384f},{0.0216792f,0.0294283f,0.0732484f}, +{0.0216792f,0.0294286f,0.071384f},{0.0210316f,0.0330931f,0.071384f},{0.0210317f,0.0330928f,0.0732484f}, +{0.0267447f,0.0155029f,0.071384f},{0.0251156f,0.0188483f,0.0732484f},{0.0267448f,0.0155026f,0.0732484f}, +{0.0237253f,0.0222933f,0.071384f},{0.0237254f,0.0222932f,0.0732484f},{0.0251155f,0.0188485f,0.071384f}, +{0.028609f,0.0122691f,0.0732484f},{0.0286089f,0.0122693f,0.071384f},{0.0307038f,0.00916071f,0.0732484f}, +{0.0307038f,0.00916071f,0.071384f},{0.0462025f,0.0835337f,0.0732484f},{0.0457312f,0.0846141f,0.071384f}, +{0.0457326f,0.0846116f,0.0732484f},{0.0450998f,0.0856014f,0.0732484f},{0.0450987f,0.085603f,0.071384f}, +{0.044317f,0.0864818f,0.071384f},{0.0443187f,0.0864801f,0.0732484f},{0.0434093f,0.0872252f,0.0732484f}, +{0.0434083f,0.0872259f,0.071384f},{0.0423945f,0.087818f,0.071384f},{0.0423947f,0.0878178f,0.0732484f}, +{0.0412975f,0.0882443f,0.071384f},{0.041298f,0.0882442f,0.0732484f},{0.040151f,0.0884923f,0.0732484f}, +{0.0401493f,0.0884924f,0.071384f},{0.0389772f,0.0885573f,0.0732484f},{0.0389749f,0.0885572f,0.071384f}, +{0.0378063f,0.0884369f,0.071384f},{0.0378083f,0.0884373f,0.0732484f},{0.0366734f,0.0881351f,0.0732484f}, +{0.0366703f,0.0881341f,0.071384f},{0.0355963f,0.0876568f,0.071384f},{0.0355984f,0.087658f,0.0732484f}, +{0.0346116f,0.0870176f,0.071384f},{0.0346134f,0.0870188f,0.0732484f},{0.0337395f,0.0862314f,0.0732484f}, +{0.0337379f,0.0862299f,0.071384f},{0.0330004f,0.0853169f,0.071384f},{0.0330008f,0.0853175f,0.0732484f}, +{0.0324146f,0.0842979f,0.071384f},{0.0324146f,0.0842979f,0.0732484f},{0.0462016f,0.0835364f,0.071384f}, +{0.0464969f,0.0823973f,0.0732484f},{0.0464965f,0.0823992f,0.071384f},{0.0466091f,0.0812265f,0.0732484f}, +{0.046609f,0.0812289f,0.071384f},{0.0465363f,0.0800543f,0.0732484f},{0.0465364f,0.0800555f,0.071384f}, +{0.0462805f,0.0789088f,0.071384f},{0.0462804f,0.0789085f,0.0732484f},{0.0458466f,0.0778144f,0.0732484f}, +{0.0458468f,0.0778149f,0.071384f},{0.0452473f,0.0768042f,0.0732484f},{0.0452483f,0.0768055f,0.071384f}, +{0.0444957f,0.0758993f,0.0732484f},{0.0444974f,0.075901f,0.071384f},{0.0436142f,0.075126f,0.071384f}, +{0.0436125f,0.0751248f,0.0732484f},{0.0426177f,0.0744982f,0.0732484f},{0.0426206f,0.0744998f,0.071384f}, +{0.0415395f,0.0740365f,0.071384f},{0.0415373f,0.0740358f,0.0732484f},{0.0403988f,0.073749f,0.0732484f}, +{0.0404009f,0.0737495f,0.071384f},{0.0392271f,0.0736446f,0.0732484f},{0.0392293f,0.0736447f,0.071384f}, +{0.038057f,0.0737251f,0.071384f},{0.0380562f,0.0737252f,0.0732484f},{0.0369109f,0.0739891f,0.0732484f}, +{0.0369109f,0.0739891f,0.071384f},{0.027361f,0.0811018f,0.071384f},{-0.027361f,0.0811018f,0.071384f}, +{-0.027361f,0.0811018f,0.0732484f},{0.027361f,0.0811018f,0.0732484f},{-0.0454557f,0.0850877f,0.0732484f}, +{-0.043047f,0.0874618f,0.0732484f},{-0.0430486f,0.0874608f,0.071384f},{-0.0439672f,0.0867969f,0.0732484f}, +{-0.0447773f,0.0859985f,0.0732484f},{-0.0439685f,0.086796f,0.071384f},{-0.0447784f,0.0859974f,0.071384f}, +{-0.03984f,0.0885276f,0.071384f},{-0.0409568f,0.0883379f,0.0732484f},{-0.0398371f,0.0885279f,0.0732484f}, +{-0.0420378f,0.0879786f,0.071384f},{-0.042035f,0.0879797f,0.0732484f},{-0.0409588f,0.0883374f,0.071384f}, +{-0.037576f,0.0883909f,0.0732484f},{-0.0364863f,0.0880664f,0.0732484f},{-0.0364891f,0.0880674f,0.071384f}, +{-0.0387004f,0.0885456f,0.0732484f},{-0.0375781f,0.0883913f,0.071384f},{-0.0387033f,0.0885458f,0.071384f}, +{-0.0354596f,0.0875809f,0.0732484f},{-0.0345192f,0.0869454f,0.0732484f},{-0.0345204f,0.0869463f,0.071384f}, +{-0.0354613f,0.0875818f,0.071384f},{-0.0336855f,0.0861739f,0.071384f},{-0.0336844f,0.0861728f,0.0732484f}, +{-0.0329784f,0.0852846f,0.0732484f},{-0.0329787f,0.085285f,0.071384f},{-0.0324146f,0.0842979f,0.0732484f}, +{-0.0324146f,0.0842979f,0.071384f},{-0.045456f,0.0850872f,0.071384f},{-0.021027f,0.0331264f,0.0732484f}, +{-0.0206381f,0.0368319f,0.0732484f},{-0.0206381f,0.0368317f,0.071384f},{-0.0205085f,0.0405509f,0.0732484f}, +{-0.0205085f,0.0405509f,0.071384f},{-0.021027f,0.0331261f,0.071384f},{-0.0216751f,0.0294476f,0.071384f}, +{-0.0216749f,0.0294486f,0.0732484f},{-0.0237299f,0.0222807f,0.0732484f},{-0.0225785f,0.0258242f,0.0732484f}, +{-0.0225785f,0.025824f,0.071384f},{-0.0237299f,0.0222806f,0.071384f},{-0.0267542f,0.0154851f,0.0732484f}, +{-0.0251237f,0.01883f,0.071384f},{-0.0267544f,0.0154848f,0.071384f},{-0.0286161f,0.0122577f,0.0732484f}, +{-0.0251236f,0.0188302f,0.0732484f},{-0.0286162f,0.0122575f,0.071384f},{-0.0307038f,0.00916071f,0.0732484f}, +{-0.0307038f,0.00916071f,0.071384f},{-0.0206381f,0.0442701f,0.0732484f},{-0.0206381f,0.0442699f,0.071384f}, +{-0.021027f,0.0479754f,0.071384f},{-0.021027f,0.0479757f,0.0732484f},{-0.0216751f,0.0516542f,0.0732484f}, +{-0.0216749f,0.0516532f,0.071384f},{-0.0225785f,0.0552778f,0.0732484f},{-0.0225785f,0.0552777f,0.071384f}, +{-0.0237299f,0.0588211f,0.071384f},{-0.0237299f,0.0588212f,0.0732484f},{-0.0251237f,0.0622718f,0.0732484f}, +{-0.0251236f,0.0622716f,0.071384f},{-0.0267544f,0.065617f,0.0732484f},{-0.0267542f,0.0656167f,0.071384f}, +{-0.0286161f,0.0688441f,0.071384f},{-0.0286162f,0.0688443f,0.0732484f},{-0.0307038f,0.0719411f,0.071384f}, +{-0.0307038f,0.0719411f,0.0732484f},{-0.0465017f,0.00126733f,0.0732484f},{-0.044941f,0.00470215f,0.071384f}, +{-0.0456552f,0.0036514f,0.071384f},{-0.0449406f,0.00470266f,0.0732484f},{-0.0456542f,0.00365287f,0.0732484f}, +{-0.0461811f,0.00249326f,0.071384f},{-0.046181f,0.00249363f,0.0732484f},{-0.0430341f,0.00636786f,0.071384f}, +{-0.0418973f,0.00693419f,0.0732484f},{-0.0418979f,0.00693393f,0.071384f},{-0.0440592f,0.00561614f,0.0732484f}, +{-0.0430328f,0.00636862f,0.0732484f},{-0.0440603f,0.00561515f,0.071384f},{-0.0406822f,0.00729899f,0.071384f}, +{-0.0394178f,0.00745289f,0.0732484f},{-0.0394182f,0.00745292f,0.071384f},{-0.0406805f,0.00729943f,0.0732484f}, +{-0.0381522f,0.00739019f,0.071384f},{-0.0381511f,0.00739011f,0.0732484f},{-0.0369109f,0.00711273f,0.0732484f}, +{-0.0369109f,0.00711273f,0.071384f},{-0.046502f,0.00126624f,0.071384f},{-0.021027f,-0.0479754f,0.0732484f}, +{-0.0206381f,-0.0442699f,0.0732484f},{-0.0206381f,-0.0442701f,0.071384f},{-0.0205085f,-0.0405509f,0.0732484f}, +{-0.0205085f,-0.0405509f,0.071384f},{-0.021027f,-0.0479757f,0.071384f},{-0.0216751f,-0.0516542f,0.071384f}, +{-0.0216749f,-0.0516532f,0.0732484f},{-0.0237299f,-0.0588211f,0.0732484f},{-0.0225785f,-0.0552777f,0.0732484f}, +{-0.0225785f,-0.0552778f,0.071384f},{-0.0237299f,-0.0588212f,0.071384f},{-0.0267542f,-0.0656167f,0.0732484f}, +{-0.0251237f,-0.0622718f,0.071384f},{-0.0267544f,-0.065617f,0.071384f},{-0.0286161f,-0.0688441f,0.0732484f}, +{-0.0251236f,-0.0622716f,0.0732484f},{-0.0286162f,-0.0688443f,0.071384f},{-0.0307038f,-0.0719411f,0.0732484f}, +{-0.0307038f,-0.0719411f,0.071384f},{-0.0206381f,-0.0368317f,0.0732484f},{-0.0206381f,-0.0368319f,0.071384f}, +{-0.021027f,-0.0331264f,0.071384f},{-0.021027f,-0.0331261f,0.0732484f},{-0.0216751f,-0.0294476f,0.0732484f}, +{-0.0216749f,-0.0294486f,0.071384f},{-0.0225785f,-0.025824f,0.0732484f},{-0.0225785f,-0.0258241f,0.071384f}, +{-0.0237299f,-0.0222807f,0.071384f},{-0.0237299f,-0.0222806f,0.0732484f},{-0.0251237f,-0.01883f,0.0732484f}, +{-0.0251236f,-0.0188302f,0.071384f},{-0.0267544f,-0.0154848f,0.0732484f},{-0.0267542f,-0.0154851f,0.071384f}, +{-0.0286161f,-0.0122577f,0.071384f},{-0.0286162f,-0.0122575f,0.0732484f},{-0.0307038f,-0.00916071f,0.071384f}, +{-0.0307038f,-0.00916071f,0.0732484f},{-0.0463621f,-0.0830096f,0.0732484f},{-0.0464633f,-0.079629f,0.0732484f}, +{-0.0464637f,-0.0796309f,0.071384f},{-0.0466021f,-0.0807558f,0.0732484f},{-0.0465681f,-0.0818927f,0.0732484f}, +{-0.0466023f,-0.0807574f,0.071384f},{-0.046568f,-0.0818943f,0.071384f},{-0.0450626f,-0.0765535f,0.071384f}, +{-0.0456834f,-0.0775011f,0.0732484f},{-0.0450608f,-0.0765512f,0.0732484f},{-0.0461555f,-0.0785378f,0.071384f}, +{-0.0461544f,-0.078535f,0.0732484f},{-0.0456844f,-0.0775029f,0.071384f},{-0.0434222f,-0.0749873f,0.0732484f}, +{-0.0424429f,-0.0744094f,0.0732484f},{-0.0424456f,-0.0744108f,0.071384f},{-0.0443005f,-0.075706f,0.0732484f}, +{-0.0434238f,-0.0749885f,0.071384f},{-0.0443026f,-0.0757081f,0.071384f},{-0.0413886f,-0.0739873f,0.0732484f}, +{-0.040283f,-0.0737303f,0.0732484f},{-0.0402846f,-0.0737307f,0.071384f},{-0.0413904f,-0.0739879f,0.071384f}, +{-0.0391504f,-0.0736443f,0.071384f},{-0.0391489f,-0.0736442f,0.0732484f},{-0.0380175f,-0.073731f,0.0732484f}, +{-0.0380181f,-0.073731f,0.071384f},{-0.0369109f,-0.0739891f,0.0732484f},{-0.0369109f,-0.0739891f,0.071384f}, +{-0.046362f,-0.0830101f,0.071384f},{0.027361f,-0.0811018f,0.0732484f},{-0.027361f,-0.0811018f,0.071384f}, +{0.027361f,-0.0811018f,0.071384f},{-0.027361f,-0.0811018f,0.0732484f},{0.0457312f,-0.0846141f,0.0732484f}, +{0.0462025f,-0.0835337f,0.071384f},{0.0462016f,-0.0835364f,0.0732484f},{0.0464965f,-0.0823992f,0.0732484f}, +{0.0464969f,-0.0823973f,0.071384f},{0.0466091f,-0.0812265f,0.071384f},{0.046609f,-0.0812289f,0.0732484f}, +{0.0465364f,-0.0800555f,0.0732484f},{0.0465363f,-0.0800543f,0.071384f},{0.0462804f,-0.0789085f,0.071384f}, +{0.0462805f,-0.0789088f,0.0732484f},{0.0458466f,-0.0778144f,0.071384f},{0.0458468f,-0.0778149f,0.0732484f}, +{0.0452483f,-0.0768055f,0.0732484f},{0.0452473f,-0.0768041f,0.071384f},{0.0444974f,-0.075901f,0.0732484f}, +{0.0444957f,-0.0758994f,0.071384f},{0.0436125f,-0.0751248f,0.071384f},{0.0436142f,-0.075126f,0.0732484f}, +{0.0426206f,-0.0744997f,0.0732484f},{0.0426177f,-0.0744982f,0.071384f},{0.0415373f,-0.0740358f,0.071384f}, +{0.0415395f,-0.0740365f,0.0732484f},{0.0403988f,-0.073749f,0.071384f},{0.0404009f,-0.0737495f,0.0732484f}, +{0.0392293f,-0.0736447f,0.0732484f},{0.0392271f,-0.0736446f,0.071384f},{0.0380562f,-0.0737252f,0.071384f}, +{0.038057f,-0.0737251f,0.0732484f},{0.0369109f,-0.0739891f,0.071384f},{0.0369109f,-0.0739891f,0.0732484f}, +{0.0457326f,-0.0846116f,0.071384f},{0.0450987f,-0.085603f,0.0732484f},{0.0450998f,-0.0856014f,0.071384f}, +{0.044317f,-0.0864818f,0.0732484f},{0.0443187f,-0.0864801f,0.071384f},{0.0434083f,-0.0872259f,0.0732484f}, +{0.0434093f,-0.0872252f,0.071384f},{0.0423947f,-0.0878178f,0.071384f},{0.0423945f,-0.087818f,0.0732484f}, +{0.0412975f,-0.0882443f,0.0732484f},{0.041298f,-0.0882442f,0.071384f},{0.0401493f,-0.0884924f,0.0732484f}, +{0.040151f,-0.0884923f,0.071384f},{0.0389749f,-0.0885572f,0.0732484f},{0.0389772f,-0.0885573f,0.071384f}, +{0.0378083f,-0.0884373f,0.071384f},{0.0378063f,-0.0884369f,0.0732484f},{0.0366703f,-0.088134f,0.0732484f}, +{0.0366734f,-0.0881351f,0.071384f},{0.0355984f,-0.087658f,0.071384f},{0.0355963f,-0.0876568f,0.0732484f}, +{0.0346116f,-0.0870176f,0.0732484f},{0.0346134f,-0.0870188f,0.071384f},{0.0337379f,-0.0862299f,0.0732484f}, +{0.0337395f,-0.0862314f,0.071384f},{0.0330008f,-0.0853175f,0.071384f},{0.0330004f,-0.0853169f,0.0732484f}, +{0.0324146f,-0.0842979f,0.0732484f},{0.0324146f,-0.0842979f,0.071384f},{0.02064f,-0.0442971f,0.0732484f}, +{0.0206399f,-0.0442969f,0.071384f},{0.0225785f,-0.0552777f,0.0732484f},{0.0225785f,-0.0552776f,0.071384f}, +{0.0216792f,-0.0516735f,0.0732484f},{0.0216792f,-0.0516732f,0.071384f},{0.0210316f,-0.0480087f,0.071384f}, +{0.0210317f,-0.048009f,0.0732484f},{0.0267447f,-0.0655989f,0.071384f},{0.0251156f,-0.0622535f,0.0732484f}, +{0.0267448f,-0.0655992f,0.0732484f},{0.0237253f,-0.0588085f,0.071384f},{0.0237254f,-0.0588086f,0.0732484f}, +{0.0251155f,-0.0622533f,0.071384f},{0.028609f,-0.0688327f,0.0732484f},{0.0286089f,-0.0688325f,0.071384f}, +{0.0307038f,-0.0719411f,0.0732484f},{0.0307038f,-0.0719411f,0.071384f},{0.0206235f,-0.00372882f,0.071384f}, +{0.0206235f,-0.00372882f,0.0732484f},{0.0466102f,3.97423e-017f,0.0732484f},{0.0466102f,3.97423e-017f,0.071384f}, +{0.0465018f,0.00126639f,0.071384f},{0.0461802f,0.00249579f,0.071384f},{0.0465022f,0.00126441f,0.0732484f}, +{0.0456552f,0.00365135f,0.071384f},{0.0461804f,0.00249531f,0.0732484f},{0.0456558f,0.00365019f,0.0732484f}, +{0.0449402f,0.00470316f,0.071384f},{0.0440587f,0.00561661f,0.071384f},{0.0449409f,0.00470218f,0.0732484f}, +{0.043034f,0.00636795f,0.071384f},{0.0440594f,0.00561601f,0.0732484f},{0.0430353f,0.00636709f,0.0732484f}, +{0.0418963f,0.00693455f,0.071384f},{0.040681f,0.00729936f,0.071384f},{0.0418969f,0.00693434f,0.0732484f}, +{0.0394182f,0.00745287f,0.071384f},{0.0406822f,0.00729903f,0.0732484f},{0.0394186f,0.0074529f,0.0732484f}, +{0.0381506f,0.00739003f,0.071384f},{0.0369109f,0.00711273f,0.071384f},{0.0381517f,0.00739014f,0.0732484f}, +{0.0369109f,0.00711273f,0.0732484f},{0.0465018f,-0.00126639f,0.0732484f},{0.0465022f,-0.00126441f,0.071384f}, +{0.0461802f,-0.00249579f,0.0732484f},{0.0456552f,-0.00365135f,0.0732484f},{0.0461804f,-0.00249531f,0.071384f}, +{0.0449402f,-0.00470316f,0.0732484f},{0.0456558f,-0.00365019f,0.071384f},{0.0449409f,-0.00470218f,0.071384f}, +{0.0440587f,-0.00561661f,0.0732484f},{0.043034f,-0.00636795f,0.0732484f},{0.0440594f,-0.00561601f,0.071384f}, +{0.0418963f,-0.00693455f,0.0732484f},{0.0430353f,-0.00636709f,0.071384f},{0.0418969f,-0.00693434f,0.071384f}, +{0.040681f,-0.00729936f,0.0732484f},{0.0394182f,-0.00745287f,0.0732484f},{0.0406822f,-0.00729903f,0.071384f}, +{0.0381506f,-0.00739003f,0.0732484f},{0.0394186f,-0.0074529f,0.071384f},{0.0381517f,-0.00739014f,0.071384f}, +{0.0369109f,-0.00711273f,0.0732484f},{0.0369109f,-0.00711273f,0.071384f},{0.0195103f,0.0755086f,0.071384f}, +{0.0195103f,0.0755086f,0.0732484f},{0.0418944f,0.000544649f,0.0732484f},{-0.0396981f,0.00274259f,0.0732484f}, +{-0.0346445f,-0.00688452f,0.0732484f},{-0.033477f,-0.00713571f,0.0732484f},{0.0417351f,0.00106869f,0.0732484f}, +{-0.0323894f,-0.0734732f,0.0732484f},{-0.033477f,-0.0739661f,0.0732484f},{-0.029784f,-0.081654f,0.0732484f}, +{0.0396989f,-0.0783596f,0.0732484f},{0.0402234f,-0.0785201f,0.0732484f},{0.038082f,0.0836861f,0.0732484f}, +{0.0386071f,0.0838444f,0.0732484f},{0.041477f,0.00155172f,0.0732484f},{0.041477f,-0.0795501f,0.0732484f}, +{0.0411295f,-0.0791268f,0.0732484f},{0.0417351f,-0.0800331f,0.0732484f},{0.0411295f,0.00197505f,0.0732484f}, +{0.0418944f,-0.0805572f,0.0732484f},{0.0407062f,0.00232262f,0.0732484f},{0.0402234f,0.00258168f,0.0732484f}, +{0.0396989f,0.00274216f,0.0732484f},{0.0391526f,0.00279661f,0.0732484f},{0.0386071f,0.00274259f,0.0732484f}, +{0.038082f,0.00258432f,0.0732484f},{0.0358134f,0.00688407f,0.0732484f},{0.0375977f,0.00232618f,0.0732484f}, +{0.0364081f,0.000545524f,0.0732484f},{0.0236456f,0.00527349f,0.0732484f},{0.0365672f,0.00107021f,0.0732484f}, +{0.033477f,0.00713571f,0.0732484f},{0.0371735f,0.00197799f,0.0732484f},{0.0346445f,0.00688452f,0.0732484f}, +{0.0346482f,-0.00688511f,0.0732484f},{0.0241643f,0.0086281f,0.0732484f},{0.0243399f,0.00776655f,0.0732484f}, +{0.0230511f,-0.00462716f,0.0732484f},{0.023646f,-0.00527393f,0.0732484f},{-0.0396981f,0.0838444f,0.0732484f}, +{-0.0402232f,0.0836861f,0.0732484f},{-0.0386063f,0.083844f,0.0732484f},{-0.0380818f,0.0836835f,0.0732484f}, +{-0.0346445f,0.0742173f,0.0732484f},{-0.0308772f,0.0823454f,0.0732484f},{0.0211824f,0.075113f,0.0732484f}, +{0.0219051f,0.0746381f,0.0732484f},{0.0358165f,0.0742161f,0.0732484f},{0.0323894f,0.0734732f,0.0732484f}, +{0.033477f,0.0739661f,0.0732484f},{0.029784f,0.081654f,0.0732484f},{0.03177f,0.0832527f,0.0732484f}, +{0.0364081f,0.0816473f,0.0732484f},{0.0375977f,0.083428f,0.0732484f},{0.0371735f,0.0830798f,0.0732484f}, +{0.0407062f,0.0834244f,0.0732484f},{0.0417351f,0.0821705f,0.0732484f},{0.0418944f,0.0816464f,0.0732484f}, +{0.041477f,0.0826535f,0.0732484f},{0.0411295f,0.0830768f,0.0732484f},{0.0396989f,0.083844f,0.0732484f}, +{0.0402234f,0.0836835f,0.0732484f},{0.0391526f,0.0838984f,0.0732484f},{0.0365672f,0.082172f,0.0732484f}, +{0.0368257f,0.0826556f,0.0732484f},{0.0346482f,0.0742167f,0.0732484f},{0.0308757f,0.0823441f,0.0732484f}, +{0.0285789f,0.0812367f,0.0732484f},{0.0314497f,0.072778f,0.0732484f},{0.0224988f,0.0740097f,0.0732484f}, +{0.0229321f,0.0732614f,0.0732484f},{0.0203695f,0.0754087f,0.0732484f},{-0.0314481f,0.0727748f,0.0732484f}, +{-0.0285817f,0.0812363f,0.0732484f},{-0.0231141f,0.0708224f,0.0732484f},{-0.0407075f,0.083428f,0.0732484f}, +{-0.0411317f,0.0830798f,0.0732484f},{-0.0417379f,0.082172f,0.0732484f},{-0.0418971f,0.0816473f,0.0732484f}, +{-0.0414795f,0.0826556f,0.0732484f},{-0.0391526f,0.0838984f,0.0732484f},{-0.0358134f,0.0742177f,0.0732484f}, +{-0.037599f,0.0834244f,0.0732484f},{-0.033477f,0.0739661f,0.0732484f},{-0.0418971f,0.000545524f,0.0732484f}, +{-0.0371757f,0.0830768f,0.0732484f},{-0.0368282f,0.0826535f,0.0732484f},{-0.0365701f,0.0821705f,0.0732484f}, +{-0.0323867f,0.0734705f,0.0732484f},{-0.0297859f,0.0816548f,0.0732484f},{-0.0231106f,0.0727502f,0.0732484f}, +{-0.0241967f,-0.00852371f,0.0732484f},{-0.0323867f,-0.00763125f,0.0732484f},{-0.0314481f,-0.00832702f,0.0732484f}, +{-0.033477f,0.00713571f,0.0732484f},{-0.0365701f,0.00106869f,0.0732484f},{-0.0364108f,0.000544649f,0.0732484f}, +{-0.0323894f,0.00762858f,0.0732484f},{-0.0386063f,0.00274216f,0.0732484f},{-0.0391526f,0.00279661f,0.0732484f}, +{-0.0368282f,0.00155172f,0.0732484f},{-0.0417379f,0.00107021f,0.0732484f},{-0.0414795f,0.0015538f,0.0732484f}, +{-0.0411317f,0.00197799f,0.0732484f},{-0.0407075f,0.00232618f,0.0732484f},{-0.0402232f,0.00258432f,0.0732484f}, +{-0.0418971f,-0.0805563f,0.0732484f},{-0.0417379f,-0.0800316f,0.0732484f},{-0.0358134f,-0.00688407f,0.0732484f}, +{-0.0225127f,0.00424291f,0.0732484f},{-0.0380818f,0.00258168f,0.0732484f},{-0.0358165f,0.00688568f,0.0732484f}, +{0.0214967f,-0.00383203f,0.0732484f},{0.0223196f,0.0041374f,0.0732484f},{0.0214955f,0.00383263f,0.0732484f}, +{-0.0216024f,0.00385961f,0.0732484f},{-0.024244f,-0.0065653f,0.0732484f},{0.0314497f,-0.00832383f,0.0732484f}, +{0.0243085f,-0.00688932f,0.0732484f},{0.0364081f,-0.0805563f,0.0732484f},{0.0308772f,-0.0823454f,0.0732484f}, +{0.0314481f,-0.0727748f,0.0732484f},{0.0285817f,-0.0812363f,0.0732484f},{0.0230854f,-0.0707188f,0.0732484f}, +{-0.0285788f,-0.0812367f,0.0732484f},{-0.0213716f,-0.0750107f,0.0732484f},{-0.022144f,-0.0744194f,0.0732484f}, +{-0.0365701f,-0.0800331f,0.0732484f},{-0.0391526f,-0.0783052f,0.0732484f},{-0.03177f,-0.0832527f,0.0732484f}, +{-0.0308757f,-0.0823441f,0.0732484f},{-0.0364108f,-0.0805572f,0.0732484f},{-0.0414795f,-0.079548f,0.0732484f}, +{-0.0411317f,-0.0791238f,0.0732484f},{-0.0407075f,-0.0787756f,0.0732484f},{-0.0402232f,-0.0785175f,0.0732484f}, +{-0.0396981f,-0.0783592f,0.0732484f},{-0.0386063f,-0.0783596f,0.0732484f},{-0.0368282f,-0.0795501f,0.0732484f}, +{-0.0371757f,-0.0791268f,0.0732484f},{-0.0346482f,-0.0742167f,0.0732484f},{-0.0358165f,-0.0742161f,0.0732484f}, +{0.0386071f,-0.0783592f,0.0732484f},{0.038082f,-0.0785175f,0.0732484f},{-0.0314497f,-0.072778f,0.0732484f}, +{0.0391526f,-0.0783052f,0.0732484f},{0.0407062f,-0.0787792f,0.0732484f},{0.0358134f,-0.0742177f,0.0732484f}, +{0.0375977f,-0.0787756f,0.0732484f},{0.0368257f,-0.079548f,0.0732484f},{0.0346445f,-0.0742173f,0.0732484f}, +{0.0365672f,-0.0800316f,0.0732484f},{0.0371735f,-0.0791238f,0.0732484f},{0.0297859f,-0.0816548f,0.0732484f}, +{0.033477f,-0.0739661f,0.0732484f},{0.0317708f,-0.0832554f,0.0732484f},{0.0323867f,-0.0734706f,0.0732484f}, +{0.0229318f,-0.0732619f,0.0732484f},{0.0223212f,-0.0041373f,0.0732484f},{0.0240731f,-0.00604206f,0.0732484f}, +{0.0323894f,-0.00762858f,0.0732484f},{0.0243087f,0.00688805f,0.0732484f},{0.0314481f,0.00832702f,0.0732484f}, +{0.0323867f,0.00763125f,0.0732484f},{0.0358165f,-0.00688568f,0.0732484f},{-0.023239f,0.071786f,0.0732484f}, +{0.0232328f,0.0715697f,0.0732484f},{0.0230844f,0.0707181f,0.0732484f},{0.0231812f,0.072433f,0.0732484f}, +{0.0240729f,0.00604156f,0.0732484f},{0.02305f,0.00462664f,0.0732484f},{0.033477f,-0.00713571f,0.0732484f}, +{0.024339f,-0.00776783f,0.0732484f},{0.0241632f,-0.00862874f,0.0732484f},{-0.0314497f,0.00832383f,0.0732484f}, +{-0.0346482f,0.00688511f,0.0732484f},{0.0231813f,-0.0724342f,0.0732484f},{0.0232336f,-0.071571f,0.0732484f}, +{0.021904f,-0.0746385f,0.0732484f},{0.0224985f,-0.0740101f,0.0732484f},{0.0203684f,-0.0754081f,0.0732484f}, +{0.0211809f,-0.0751129f,0.0732484f},{-0.0204736f,-0.075382f,0.0732484f},{-0.0243511f,-0.0075482f,0.0732484f}, +{-0.0232912f,0.00485238f,0.0732484f},{-0.0380818f,-0.0785201f,0.0732484f},{-0.037599f,-0.0787792f,0.0732484f}, +{-0.0364108f,0.0816464f,0.0732484f},{-0.0317708f,0.0832554f,0.0732484f},{0.0368257f,0.0015538f,0.0732484f}, +{-0.037599f,0.00232262f,0.0732484f},{-0.0371757f,0.00197505f,0.0732484f},{0.0314481f,0.0727748f,0.071384f}, +{0.0229318f,0.0732619f,0.071384f},{-0.0358134f,-0.0742177f,0.071384f},{-0.0375977f,-0.0787756f,0.071384f}, +{-0.038082f,-0.0785175f,0.071384f},{-0.0391526f,-0.0783052f,0.071384f},{0.0243399f,-0.00776655f,0.071384f}, +{0.0243087f,-0.00688805f,0.071384f},{0.0358165f,0.00688568f,0.071384f},{0.0380818f,0.00258168f,0.071384f}, +{0.037599f,0.00232262f,0.071384f},{0.0241643f,-0.0086281f,0.071384f},{0.033477f,-0.00713571f,0.071384f}, +{0.0323867f,-0.00763125f,0.071384f},{0.0396981f,0.00274259f,0.071384f},{0.0391526f,0.00279661f,0.071384f}, +{0.0407075f,0.00232618f,0.071384f},{0.0402232f,0.00258432f,0.071384f},{0.0417379f,0.00107021f,0.071384f}, +{0.0358134f,-0.00688407f,0.071384f},{0.0346445f,-0.00688452f,0.071384f},{0.0417379f,0.082172f,0.071384f}, +{0.0407075f,0.083428f,0.071384f},{0.0402232f,0.0836861f,0.071384f},{0.0396981f,0.0838444f,0.071384f}, +{0.0418971f,0.000545524f,0.071384f},{0.0414795f,0.0015538f,0.071384f},{0.0411317f,0.00197799f,0.071384f}, +{0.0386063f,0.00274216f,0.071384f},{0.033477f,0.00713571f,0.071384f},{0.0364108f,0.000544649f,0.071384f}, +{0.0323894f,0.00762858f,0.071384f},{0.0240729f,-0.00604156f,0.071384f},{0.0236456f,-0.00527349f,0.071384f}, +{0.0223212f,0.0041373f,0.071384f},{0.0230511f,0.00462716f,0.071384f},{0.0223196f,-0.0041374f,0.071384f}, +{0.0346482f,0.00688511f,0.071384f},{0.0368282f,0.00155172f,0.071384f},{0.0365701f,0.00106869f,0.071384f}, +{-0.0346445f,-0.0742173f,0.071384f},{-0.0371735f,-0.0791238f,0.071384f},{-0.0386071f,-0.0783592f,0.071384f}, +{-0.0396989f,-0.0783596f,0.071384f},{-0.0402234f,-0.0785201f,0.071384f},{-0.0417351f,-0.0800331f,0.071384f}, +{-0.0407062f,-0.0787792f,0.071384f},{-0.0411295f,-0.0791268f,0.071384f},{-0.041477f,-0.0795501f,0.071384f}, +{-0.0285817f,-0.0812363f,0.071384f},{-0.0323867f,-0.0734706f,0.071384f},{-0.0314481f,-0.0727748f,0.071384f}, +{-0.0365672f,-0.0800316f,0.071384f},{-0.0308772f,-0.0823454f,0.071384f},{-0.0364081f,-0.0805563f,0.071384f}, +{0.029784f,-0.081654f,0.071384f},{0.0323894f,-0.0734732f,0.071384f},{0.033477f,-0.0739661f,0.071384f}, +{0.0219051f,-0.0746381f,0.071384f},{0.0211824f,-0.075113f,0.071384f},{0.0391526f,-0.0783052f,0.071384f}, +{0.0396981f,-0.0783592f,0.071384f},{0.0386063f,-0.0783596f,0.071384f},{0.0411317f,-0.0791238f,0.071384f}, +{0.0407075f,-0.0787756f,0.071384f},{0.0414795f,-0.079548f,0.071384f},{0.0365701f,-0.0800331f,0.071384f}, +{0.0417379f,-0.0800316f,0.071384f},{0.0418971f,-0.0805563f,0.071384f},{0.03177f,-0.0832527f,0.071384f}, +{0.0308757f,-0.0823441f,0.071384f},{0.0364108f,-0.0805572f,0.071384f},{0.0402232f,-0.0785175f,0.071384f}, +{0.0380818f,-0.0785201f,0.071384f},{0.0346482f,-0.0742167f,0.071384f},{0.0368282f,-0.0795501f,0.071384f}, +{0.0371757f,-0.0791268f,0.071384f},{0.0285789f,-0.0812367f,0.071384f},{0.0314497f,-0.072778f,0.071384f}, +{0.0224988f,-0.0740097f,0.071384f},{0.0229321f,-0.0732614f,0.071384f},{0.0230844f,-0.0707181f,0.071384f}, +{-0.0418944f,-0.0805572f,0.071384f},{-0.033477f,-0.0739661f,0.071384f},{-0.0297859f,-0.0816548f,0.071384f}, +{-0.0317708f,-0.0832554f,0.071384f},{-0.0243512f,-0.00754595f,0.071384f},{-0.0242437f,-0.00656417f,0.071384f}, +{-0.0216035f,0.00385992f,0.071384f},{-0.024197f,-0.00852259f,0.071384f},{-0.0323867f,0.00763125f,0.071384f}, +{-0.0364081f,0.000545524f,0.071384f},{-0.0418944f,0.000544649f,0.071384f},{-0.0411295f,0.00197505f,0.071384f}, +{-0.0407062f,0.00232262f,0.071384f},{-0.0386071f,0.00274259f,0.071384f},{-0.0391526f,0.00279661f,0.071384f}, +{-0.0358134f,0.00688407f,0.071384f},{-0.0375977f,0.00232618f,0.071384f},{-0.038082f,0.00258432f,0.071384f}, +{-0.041477f,0.00155172f,0.071384f},{-0.0417351f,0.00106869f,0.071384f},{-0.0402234f,0.00258168f,0.071384f}, +{-0.0371735f,0.00197799f,0.071384f},{-0.0346445f,0.00688452f,0.071384f},{-0.0396989f,0.00274216f,0.071384f}, +{-0.0358165f,-0.00688568f,0.071384f},{-0.033477f,0.00713571f,0.071384f},{-0.023292f,0.00485321f,0.071384f}, +{-0.0346482f,-0.00688511f,0.071384f},{0.0314497f,0.00832383f,0.071384f},{0.0243085f,0.00688932f,0.071384f}, +{0.0230854f,0.0707188f,0.071384f},{-0.0346482f,0.0742167f,0.071384f},{-0.033477f,0.0739661f,0.071384f}, +{-0.0231144f,0.0708235f,0.071384f},{-0.0368257f,0.0826556f,0.071384f},{-0.0396989f,0.083844f,0.071384f}, +{-0.0391526f,0.0838984f,0.071384f},{-0.0375977f,0.083428f,0.071384f},{-0.038082f,0.0836861f,0.071384f}, +{-0.0411295f,0.0830768f,0.071384f},{-0.041477f,0.0826535f,0.071384f},{-0.0371735f,0.0830798f,0.071384f}, +{-0.0418944f,0.0816464f,0.071384f},{-0.0417351f,0.0821705f,0.071384f},{-0.0402234f,0.0836835f,0.071384f}, +{-0.0386071f,0.0838444f,0.071384f},{-0.0407062f,0.0834244f,0.071384f},{-0.0364081f,0.0816473f,0.071384f}, +{-0.0365672f,0.082172f,0.071384f},{-0.03177f,0.0832527f,0.071384f},{-0.0308757f,0.0823441f,0.071384f}, +{-0.0358165f,0.0742161f,0.071384f},{-0.029784f,0.081654f,0.071384f},{-0.0323894f,0.0734732f,0.071384f}, +{-0.0285788f,0.0812367f,0.071384f},{-0.0314497f,0.072778f,0.071384f},{-0.0231103f,0.0727513f,0.071384f}, +{0.0391526f,0.0838984f,0.071384f},{0.0380818f,0.0836835f,0.071384f},{0.0386063f,0.083844f,0.071384f}, +{0.0414795f,0.0826556f,0.071384f},{0.0411317f,0.0830798f,0.071384f},{0.0418971f,0.0816473f,0.071384f}, +{0.0358134f,0.0742177f,0.071384f},{0.0346445f,0.0742173f,0.071384f},{0.033477f,0.0739661f,0.071384f}, +{0.0371757f,0.0830768f,0.071384f},{0.037599f,0.0834244f,0.071384f},{0.0368282f,0.0826535f,0.071384f}, +{0.0308772f,0.0823454f,0.071384f},{0.0323867f,0.0734705f,0.071384f},{0.0297859f,0.0816548f,0.071384f}, +{0.0285817f,0.0812363f,0.071384f},{0.0187991f,0.0422603f,0.071384f},{0.0232336f,0.071571f,0.071384f}, +{0.0231813f,0.0724342f,0.071384f},{0.021904f,0.0746385f,0.071384f},{0.0224985f,0.0740101f,0.071384f}, +{0.0203684f,0.0754081f,0.071384f},{0.0211809f,0.0751129f,0.071384f},{-0.023239f,0.0717882f,0.071384f}, +{0.024339f,0.00776783f,0.071384f},{0.0241632f,0.00862874f,0.071384f},{-0.0314481f,0.00832702f,0.071384f}, +{-0.0225146f,0.00424405f,0.071384f},{-0.0323894f,-0.00762858f,0.071384f},{-0.0314497f,-0.00832383f,0.071384f}, +{0.023646f,0.00527393f,0.071384f},{0.0240731f,0.00604206f,0.071384f},{0.0314481f,-0.00832702f,0.071384f}, +{0.02305f,-0.00462664f,0.071384f},{0.0214955f,-0.00383263f,0.071384f},{0.0214967f,0.00383203f,0.071384f}, +{-0.033477f,-0.00713571f,0.071384f},{-0.0213735f,-0.0750096f,0.071384f},{-0.0221448f,-0.0744186f,0.071384f}, +{-0.0204747f,-0.0753817f,0.071384f},{0.0232328f,-0.0715697f,0.071384f},{0.0231812f,-0.072433f,0.071384f}, +{0.0203695f,-0.0754087f,0.071384f},{-0.0368257f,-0.079548f,0.071384f},{0.0358165f,-0.0742161f,0.071384f}, +{0.037599f,-0.0787792f,0.071384f},{0.0365701f,0.0821705f,0.071384f},{0.0364108f,0.0816464f,0.071384f}, +{0.0317708f,0.0832554f,0.071384f},{0.0371757f,0.00197505f,0.071384f},{-0.0368257f,0.0015538f,0.071384f}, +{-0.0365672f,0.00107021f,0.071384f},{0.0386654f,0.0838556f,0.0732484f},{0.0391526f,0.0838984f,0.080706f}, +{0.0396411f,0.0838554f,0.0732484f},{0.040109f,0.0837298f,0.080706f},{0.0396398f,0.0838556f,0.080706f}, +{0.0401103f,0.0837293f,0.0732484f},{0.0405482f,0.0835251f,0.080706f},{0.0405499f,0.0835245f,0.0732484f}, +{0.0409476f,0.0832459f,0.080706f},{0.0412967f,0.0828968f,0.0732484f},{0.0412948f,0.0828995f,0.080706f}, +{0.0409503f,0.083244f,0.0732484f},{0.0415759f,0.0824974f,0.0732484f},{0.0415753f,0.0824991f,0.080706f}, +{0.0417806f,0.0820583f,0.0732484f},{0.0417801f,0.0820595f,0.080706f},{0.0419062f,0.0815903f,0.080706f}, +{0.0419062f,0.0815903f,0.0732484f},{0.0419492f,0.0811018f,0.080706f},{0.0386641f,0.0838554f,0.080706f}, +{0.0381949f,0.0837293f,0.080706f},{0.0381961f,0.0837298f,0.0732484f},{0.037757f,0.0835251f,0.0732484f}, +{0.0377553f,0.0835245f,0.080706f},{0.0373549f,0.083244f,0.080706f},{0.0373576f,0.0832459f,0.0732484f}, +{0.0370085f,0.0828968f,0.080706f},{0.0370104f,0.0828995f,0.0732484f},{0.0367299f,0.0824991f,0.0732484f}, +{0.0367293f,0.0824974f,0.080706f},{0.0365246f,0.0820583f,0.080706f},{0.0365251f,0.0820595f,0.0732484f}, +{0.036399f,0.0815903f,0.080706f},{0.036399f,0.0815903f,0.0732484f},{0.036356f,0.0811018f,0.080706f}, +{0.0351171f,0.0787719f,0.0751128f},{0.0351836f,0.0786864f,0.0732484f},{0.0355373f,0.0781593f,0.0732484f}, +{0.0394705f,0.0764554f,0.0732484f},{0.0391526f,0.0764408f,0.0751128f},{0.0388355f,0.076451f,0.0732484f}, +{0.0348819f,0.0792468f,0.0732484f},{0.034847f,0.0793182f,0.0751128f},{0.034664f,0.0798436f,0.0732484f}, +{0.0346475f,0.079899f,0.0751128f},{0.0345395f,0.080468f,0.0732484f},{0.0345304f,0.0804959f,0.0751128f}, +{0.0344916f,0.0811018f,0.0732484f},{0.0344918f,0.0811018f,0.0751128f},{0.0356898f,0.0779809f,0.0751128f}, +{0.0364147f,0.0773294f,0.0751128f},{0.0359728f,0.0776969f,0.0732484f},{0.0370083f,0.076961f,0.0732484f}, +{0.0364669f,0.0772961f,0.0732484f},{0.037596f,0.0767216f,0.0732484f},{0.0372582f,0.0768428f,0.0751128f}, +{0.0381846f,0.0765423f,0.0751128f},{0.0382078f,0.0765464f,0.0732484f},{0.0407151f,0.0767081f,0.0732484f}, +{0.041049f,0.0768446f,0.0751128f},{0.0401226f,0.0765432f,0.0751128f},{0.0401013f,0.0765401f,0.0732484f}, +{0.0423348f,0.0776954f,0.0732484f},{0.0418908f,0.0773301f,0.0751128f},{0.0418394f,0.0772978f,0.0732484f}, +{0.0412894f,0.0769789f,0.0732484f},{0.0431881f,0.0787719f,0.0751128f},{0.0431347f,0.0786808f,0.0732484f}, +{0.0434289f,0.0792447f,0.0732484f},{0.0426156f,0.0779832f,0.0751128f},{0.0427645f,0.0781631f,0.0732484f}, +{0.0436546f,0.079901f,0.0751128f},{0.0436222f,0.0798502f,0.0732484f},{0.0437699f,0.0804677f,0.0732484f}, +{0.0434582f,0.0793181f,0.0751128f},{0.0438136f,0.0811018f,0.0732484f},{0.0437742f,0.0804963f,0.0751128f}, +{0.0438134f,0.0811018f,0.0751128f},{0.0391526f,0.0857628f,0.0900281f},{0.0418436f,0.0857628f,0.0751128f}, +{0.0391526f,0.0857628f,0.0751128f},{0.0364616f,0.0857628f,0.0751128f},{0.0364616f,0.0857628f,0.0900281f}, +{0.0418436f,0.0857628f,0.0900281f},{0.0386654f,0.078348f,0.0918925f},{0.0391526f,0.0783052f,0.0918925f}, +{0.0391526f,0.0783052f,0.0844349f},{0.0396411f,0.0783482f,0.0918925f},{0.040109f,0.0784738f,0.0844349f}, +{0.0396398f,0.078348f,0.0844349f},{0.0401103f,0.0784743f,0.0918925f},{0.0405482f,0.0786785f,0.0844349f}, +{0.0405499f,0.0786791f,0.0918925f},{0.0409476f,0.0789577f,0.0844349f},{0.0412967f,0.0793068f,0.0918925f}, +{0.0412948f,0.0793041f,0.0844349f},{0.0409503f,0.0789596f,0.0918925f},{0.0415759f,0.0797062f,0.0918925f}, +{0.0415753f,0.0797045f,0.0844349f},{0.0417806f,0.0801454f,0.0918925f},{0.0417801f,0.0801441f,0.0844349f}, +{0.0419062f,0.0806133f,0.0844349f},{0.0419062f,0.0806133f,0.0918925f},{0.0419492f,0.0811018f,0.0918925f}, +{0.0419492f,0.0811018f,0.0844349f},{0.0386641f,0.0783482f,0.0844349f},{0.0381949f,0.0784743f,0.0844349f}, +{0.0381961f,0.0784738f,0.0918925f},{0.037757f,0.0786785f,0.0918925f},{0.0377553f,0.0786791f,0.0844349f}, +{0.0373549f,0.0789596f,0.0844349f},{0.0373576f,0.0789577f,0.0918925f},{0.0370085f,0.0793068f,0.0844349f}, +{0.0370104f,0.0793041f,0.0918925f},{0.0367299f,0.0797045f,0.0918925f},{0.0367293f,0.0797062f,0.0844349f}, +{0.0365246f,0.0801454f,0.0844349f},{0.0365251f,0.0801441f,0.0918925f},{0.036399f,0.0806133f,0.0844349f}, +{0.036399f,0.0806133f,0.0918925f},{0.036356f,0.0811018f,0.0918925f},{0.036356f,0.0811018f,0.0844349f}, +{0.0351171f,0.0834317f,0.0900281f},{0.0351836f,0.0835172f,0.0918925f},{0.0355373f,0.0840443f,0.0918925f}, +{0.0394705f,0.0857482f,0.0918925f},{0.0388355f,0.0857526f,0.0918925f},{0.0348819f,0.0829568f,0.0918925f}, +{0.034847f,0.0828854f,0.0900281f},{0.034664f,0.08236f,0.0918925f},{0.0346475f,0.0823046f,0.0900281f}, +{0.0345395f,0.0817356f,0.0918925f},{0.0345304f,0.0817077f,0.0900281f},{0.0344916f,0.0811018f,0.0918925f}, +{0.0344917f,0.0811018f,0.0900281f},{0.0356898f,0.0842227f,0.0900281f},{0.0364147f,0.0848742f,0.0900281f}, +{0.0359728f,0.0845067f,0.0918925f},{0.0370083f,0.0852426f,0.0918925f},{0.0364669f,0.0849075f,0.0918925f}, +{0.037596f,0.0854821f,0.0918925f},{0.0372582f,0.0853608f,0.0900281f},{0.0381846f,0.0856613f,0.0900281f}, +{0.0382078f,0.0856572f,0.0918925f},{0.0407151f,0.0854955f,0.0918925f},{0.041049f,0.0853591f,0.0900281f}, +{0.0401226f,0.0856604f,0.0900281f},{0.0401013f,0.0856635f,0.0918925f},{0.0423348f,0.0845082f,0.0918925f}, +{0.0418908f,0.0848735f,0.0900281f},{0.0418394f,0.0849058f,0.0918925f},{0.0412894f,0.0852247f,0.0918925f}, +{0.0431881f,0.0834317f,0.0900281f},{0.0431347f,0.0835228f,0.0918925f},{0.0434289f,0.0829589f,0.0918925f}, +{0.0426156f,0.0842204f,0.0900281f},{0.0427645f,0.0840405f,0.0918925f},{0.0436546f,0.0823026f,0.0900281f}, +{0.0436222f,0.0823534f,0.0918925f},{0.0437699f,0.0817359f,0.0918925f},{0.0434582f,0.0828855f,0.0900281f}, +{0.0438136f,0.0811018f,0.0918925f},{0.0437742f,0.0817073f,0.0900281f},{0.0438134f,0.0811018f,0.0900281f}, +{0.0337705f,0.0811018f,0.0751128f},{0.0351171f,0.0787719f,0.0900281f},{0.0364616f,0.0764408f,0.0751128f}, +{0.0364616f,0.0764408f,0.0900281f},{0.0337705f,0.0811018f,0.0900281f},{0.0417795f,0.0801478f,0.0732484f}, +{0.0419056f,0.0806167f,0.0732484f},{0.0359715f,0.0845087f,0.0732484f},{0.0364649f,0.0849099f,0.0732484f}, +{0.0409507f,0.0789629f,0.0732484f},{0.041295f,0.0793075f,0.0732484f},{0.0396393f,0.0783484f,0.0732484f}, +{0.0401104f,0.0784759f,0.0732484f},{0.0405519f,0.078683f,0.0732484f},{0.0386677f,0.0783479f,0.0732484f}, +{0.0381969f,0.0784733f,0.0732484f},{0.0377546f,0.0786785f,0.0732484f},{0.0365233f,0.0801446f,0.0732484f}, +{0.0373546f,0.0789579f,0.0732484f},{0.0367296f,0.0797026f,0.0732484f},{0.0370095f,0.079303f,0.0732484f}, +{0.036397f,0.0806159f,0.0732484f},{0.0345334f,0.0817376f,0.0732484f},{0.0351704f,0.0835247f,0.0732484f}, +{0.0348854f,0.0829569f,0.0732484f},{0.0346707f,0.0823578f,0.0732484f},{0.0355373f,0.0840442f,0.0732484f}, +{0.0370084f,0.0852404f,0.0732484f},{0.0382048f,0.0856654f,0.0732484f},{0.0388351f,0.085752f,0.0732484f}, +{0.0394712f,0.0857519f,0.0732484f},{0.0375921f,0.0854939f,0.0732484f},{0.0401013f,0.0856652f,0.0732484f}, +{0.0407137f,0.0854936f,0.0732484f},{0.0418405f,0.0849096f,0.0732484f},{0.0412969f,0.0852402f,0.0732484f}, +{0.042334f,0.084508f,0.0732484f},{0.0434248f,0.0829572f,0.0732484f},{0.0427684f,0.0840431f,0.0732484f}, +{0.0431324f,0.0835222f,0.0732484f},{0.0436384f,0.0823587f,0.0732484f},{0.0437705f,0.0817364f,0.0732484f}, +{0.041574f,0.0797065f,0.0732484f},{0.0445347f,0.0811018f,0.0751128f},{0.0431881f,0.0834317f,0.0751128f}, +{0.0445347f,0.0811018f,0.0900281f},{0.0351171f,0.0834317f,0.0751128f},{0.0419082f,0.0806159f,0.080706f}, +{0.0412957f,0.079303f,0.080706f},{0.0415756f,0.0797026f,0.080706f},{0.0417819f,0.0801446f,0.080706f}, +{0.0401082f,0.0784733f,0.080706f},{0.0396375f,0.0783479f,0.080706f},{0.0405506f,0.0786785f,0.080706f}, +{0.0381948f,0.0784759f,0.080706f},{0.0386659f,0.0783484f,0.080706f},{0.0391526f,0.0783052f,0.080706f}, +{0.0373545f,0.0789629f,0.080706f},{0.0377533f,0.078683f,0.080706f},{0.0367312f,0.0797065f,0.080706f}, +{0.0370102f,0.0793075f,0.080706f},{0.0365256f,0.0801478f,0.080706f},{0.0363996f,0.0806167f,0.080706f}, +{0.0409506f,0.0789579f,0.080706f},{0.0391526f,0.0764408f,0.0900281f},{0.0418436f,0.0764408f,0.0751128f}, +{0.0418436f,0.0764408f,0.0900281f},{0.0346707f,0.0798458f,0.0918925f},{0.0391526f,0.0838984f,0.0918925f}, +{0.0359715f,0.0776949f,0.0918925f},{0.0364649f,0.0772937f,0.0918925f},{0.0355373f,0.0781595f,0.0918925f}, +{0.0351704f,0.0786789f,0.0918925f},{0.0388351f,0.0764516f,0.0918925f},{0.0382048f,0.0765382f,0.0918925f}, +{0.0375921f,0.0767097f,0.0918925f},{0.0407137f,0.07671f,0.0918925f},{0.0401013f,0.0765384f,0.0918925f}, +{0.0370084f,0.0769632f,0.0918925f},{0.0394712f,0.0764517f,0.0918925f},{0.0412969f,0.0769634f,0.0918925f}, +{0.0418405f,0.077294f,0.0918925f},{0.042334f,0.0776957f,0.0918925f},{0.0431324f,0.0786814f,0.0918925f}, +{0.0434248f,0.0792464f,0.0918925f},{0.0436384f,0.0798449f,0.0918925f},{0.0367296f,0.082501f,0.0918925f}, +{0.0365233f,0.082059f,0.0918925f},{0.0377546f,0.0835251f,0.0918925f},{0.0437705f,0.0804672f,0.0918925f}, +{0.0419056f,0.0815869f,0.0918925f},{0.0417795f,0.0820558f,0.0918925f},{0.041295f,0.0828961f,0.0918925f}, +{0.041574f,0.0824971f,0.0918925f},{0.0373546f,0.0832457f,0.0918925f},{0.0405519f,0.0835206f,0.0918925f}, +{0.0409507f,0.0832407f,0.0918925f},{0.0396393f,0.0838552f,0.0918925f},{0.0401104f,0.0837277f,0.0918925f}, +{0.0381969f,0.0837303f,0.0918925f},{0.0386677f,0.0838558f,0.0918925f},{0.0370095f,0.0829006f,0.0918925f}, +{0.036397f,0.0815877f,0.0918925f},{0.0345334f,0.080466f,0.0918925f},{0.0348854f,0.0792467f,0.0918925f}, +{0.0427684f,0.0781605f,0.0918925f},{0.0431881f,0.0787719f,0.0900281f},{0.034531f,0.0804963f,0.0900281f}, +{0.034847f,0.0793181f,0.0900281f},{0.0346506f,0.079901f,0.0900281f},{0.0356896f,0.0779832f,0.0900281f}, +{0.0381825f,0.0765432f,0.0900281f},{0.0372562f,0.0768446f,0.0900281f},{0.0418905f,0.0773294f,0.0900281f}, +{0.0401206f,0.0765423f,0.0900281f},{0.0426154f,0.0779809f,0.0900281f},{0.0434581f,0.0793182f,0.0900281f}, +{0.0436577f,0.079899f,0.0900281f},{0.0437748f,0.0804959f,0.0900281f},{0.041047f,0.0768428f,0.0900281f}, +{0.0364144f,0.0773301f,0.0900281f},{0.0401082f,0.0837303f,0.0844349f},{0.0386659f,0.0838552f,0.0844349f}, +{0.0381948f,0.0837277f,0.0844349f},{0.0365256f,0.0820558f,0.0844349f},{0.0391526f,0.0838984f,0.0844349f}, +{0.0396375f,0.0838558f,0.0844349f},{0.0370102f,0.0828961f,0.0844349f},{0.0367312f,0.0824971f,0.0844349f}, +{0.0377533f,0.0835206f,0.0844349f},{0.0373545f,0.0832407f,0.0844349f},{0.0363996f,0.0815869f,0.0844349f}, +{0.0405506f,0.0835251f,0.0844349f},{0.0412957f,0.0829006f,0.0844349f},{0.0409506f,0.0832457f,0.0844349f}, +{0.0415756f,0.082501f,0.0844349f},{0.0417819f,0.082059f,0.0844349f},{0.0419082f,0.0815877f,0.0844349f}, +{0.034531f,0.0817073f,0.0751128f},{0.034847f,0.0828855f,0.0751128f},{0.0346506f,0.0823026f,0.0751128f}, +{0.0356896f,0.0842204f,0.0751128f},{0.0381825f,0.0856604f,0.0751128f},{0.0372562f,0.0853591f,0.0751128f}, +{0.0418905f,0.0848742f,0.0751128f},{0.0401206f,0.0856613f,0.0751128f},{0.0426154f,0.0842227f,0.0751128f}, +{0.0434581f,0.0828854f,0.0751128f},{0.0436577f,0.0823046f,0.0751128f},{0.0437748f,0.0817077f,0.0751128f}, +{0.041047f,0.0853608f,0.0751128f},{0.0364144f,0.0848735f,0.0751128f},{-0.0396398f,-0.078348f,0.0732484f}, +{-0.0391526f,-0.0783052f,0.080706f},{-0.0386641f,-0.0783482f,0.0732484f},{-0.0381961f,-0.0784738f,0.080706f}, +{-0.0386654f,-0.078348f,0.080706f},{-0.0381949f,-0.0784743f,0.0732484f},{-0.037757f,-0.0786785f,0.080706f}, +{-0.0377553f,-0.0786791f,0.0732484f},{-0.0373576f,-0.0789577f,0.080706f},{-0.0370085f,-0.0793068f,0.0732484f}, +{-0.0370104f,-0.0793041f,0.080706f},{-0.0373549f,-0.0789596f,0.0732484f},{-0.0367293f,-0.0797062f,0.0732484f}, +{-0.0367299f,-0.0797045f,0.080706f},{-0.0365246f,-0.0801454f,0.0732484f},{-0.0365251f,-0.0801441f,0.080706f}, +{-0.036399f,-0.0806133f,0.080706f},{-0.036399f,-0.0806133f,0.0732484f},{-0.036356f,-0.0811018f,0.080706f}, +{-0.0396411f,-0.0783482f,0.080706f},{-0.0401103f,-0.0784743f,0.080706f},{-0.040109f,-0.0784738f,0.0732484f}, +{-0.0405482f,-0.0786785f,0.0732484f},{-0.0405499f,-0.0786791f,0.080706f},{-0.0409503f,-0.0789596f,0.080706f}, +{-0.0409476f,-0.0789577f,0.0732484f},{-0.0412967f,-0.0793068f,0.080706f},{-0.0412948f,-0.0793041f,0.0732484f}, +{-0.0415753f,-0.0797045f,0.0732484f},{-0.0415759f,-0.0797062f,0.080706f},{-0.0417806f,-0.0801454f,0.080706f}, +{-0.0417801f,-0.0801441f,0.0732484f},{-0.0419062f,-0.0806133f,0.080706f},{-0.0419062f,-0.0806133f,0.0732484f}, +{-0.0419492f,-0.0811018f,0.080706f},{-0.0431881f,-0.0834317f,0.0751128f},{-0.0431216f,-0.0835172f,0.0732484f}, +{-0.0427679f,-0.0840443f,0.0732484f},{-0.0388347f,-0.0857482f,0.0732484f},{-0.0391526f,-0.0857628f,0.0751128f}, +{-0.0394697f,-0.0857526f,0.0732484f},{-0.0434233f,-0.0829568f,0.0732484f},{-0.0434581f,-0.0828854f,0.0751128f}, +{-0.0436412f,-0.08236f,0.0732484f},{-0.0436577f,-0.0823046f,0.0751128f},{-0.0437656f,-0.0817356f,0.0732484f}, +{-0.0437748f,-0.0817077f,0.0751128f},{-0.0438136f,-0.0811018f,0.0732484f},{-0.0438134f,-0.0811018f,0.0751128f}, +{-0.0426154f,-0.0842227f,0.0751128f},{-0.0418905f,-0.0848742f,0.0751128f},{-0.0423324f,-0.0845067f,0.0732484f}, +{-0.0412969f,-0.0852426f,0.0732484f},{-0.0418383f,-0.0849075f,0.0732484f},{-0.0407092f,-0.0854821f,0.0732484f}, +{-0.041047f,-0.0853608f,0.0751128f},{-0.0401206f,-0.0856613f,0.0751128f},{-0.0400974f,-0.0856572f,0.0732484f}, +{-0.0375901f,-0.0854955f,0.0732484f},{-0.0372562f,-0.0853591f,0.0751128f},{-0.0381825f,-0.0856604f,0.0751128f}, +{-0.0382039f,-0.0856635f,0.0732484f},{-0.0359704f,-0.0845082f,0.0732484f},{-0.0364144f,-0.0848735f,0.0751128f}, +{-0.0364658f,-0.0849058f,0.0732484f},{-0.0370158f,-0.0852247f,0.0732484f},{-0.0351171f,-0.0834317f,0.0751128f}, +{-0.0351705f,-0.0835228f,0.0732484f},{-0.0348763f,-0.0829589f,0.0732484f},{-0.0356896f,-0.0842204f,0.0751128f}, +{-0.0355407f,-0.0840405f,0.0732484f},{-0.0346506f,-0.0823026f,0.0751128f},{-0.034683f,-0.0823534f,0.0732484f}, +{-0.0345353f,-0.0817359f,0.0732484f},{-0.034847f,-0.0828855f,0.0751128f},{-0.0344916f,-0.0811018f,0.0732484f}, +{-0.034531f,-0.0817073f,0.0751128f},{-0.0344918f,-0.0811018f,0.0751128f},{-0.0391526f,-0.0764408f,0.0900281f}, +{-0.0364616f,-0.0764408f,0.0751128f},{-0.0391526f,-0.0764408f,0.0751128f},{-0.0418436f,-0.0764408f,0.0751128f}, +{-0.0418436f,-0.0764408f,0.0900281f},{-0.0364616f,-0.0764408f,0.0900281f},{-0.0396398f,-0.0838556f,0.0918925f}, +{-0.0391526f,-0.0838984f,0.0918925f},{-0.0391526f,-0.0838984f,0.0844349f},{-0.0386641f,-0.0838554f,0.0918925f}, +{-0.0381961f,-0.0837298f,0.0844349f},{-0.0386654f,-0.0838556f,0.0844349f},{-0.0381949f,-0.0837293f,0.0918925f}, +{-0.037757f,-0.0835251f,0.0844349f},{-0.0377553f,-0.0835245f,0.0918925f},{-0.0373576f,-0.0832459f,0.0844349f}, +{-0.0370085f,-0.0828968f,0.0918925f},{-0.0370104f,-0.0828995f,0.0844349f},{-0.0373549f,-0.083244f,0.0918925f}, +{-0.0367293f,-0.0824974f,0.0918925f},{-0.0367299f,-0.0824991f,0.0844349f},{-0.0365246f,-0.0820583f,0.0918925f}, +{-0.0365251f,-0.0820595f,0.0844349f},{-0.036399f,-0.0815903f,0.0844349f},{-0.036399f,-0.0815903f,0.0918925f}, +{-0.036356f,-0.0811018f,0.0918925f},{-0.036356f,-0.0811018f,0.0844349f},{-0.0396411f,-0.0838554f,0.0844349f}, +{-0.0401103f,-0.0837293f,0.0844349f},{-0.040109f,-0.0837298f,0.0918925f},{-0.0405482f,-0.0835251f,0.0918925f}, +{-0.0405499f,-0.0835245f,0.0844349f},{-0.0409503f,-0.083244f,0.0844349f},{-0.0409476f,-0.0832459f,0.0918925f}, +{-0.0412967f,-0.0828968f,0.0844349f},{-0.0412948f,-0.0828995f,0.0918925f},{-0.0415753f,-0.0824991f,0.0918925f}, +{-0.0415759f,-0.0824974f,0.0844349f},{-0.0417806f,-0.0820583f,0.0844349f},{-0.0417801f,-0.0820595f,0.0918925f}, +{-0.0419062f,-0.0815903f,0.0844349f},{-0.0419062f,-0.0815903f,0.0918925f},{-0.0419492f,-0.0811018f,0.0918925f}, +{-0.0419492f,-0.0811018f,0.0844349f},{-0.0431881f,-0.0787719f,0.0900281f},{-0.0431216f,-0.0786864f,0.0918925f}, +{-0.0427679f,-0.0781593f,0.0918925f},{-0.0388347f,-0.0764554f,0.0918925f},{-0.0394697f,-0.076451f,0.0918925f}, +{-0.0434233f,-0.0792468f,0.0918925f},{-0.0434581f,-0.0793182f,0.0900281f},{-0.0436412f,-0.0798436f,0.0918925f}, +{-0.0436577f,-0.079899f,0.0900281f},{-0.0437656f,-0.080468f,0.0918925f},{-0.0437748f,-0.0804959f,0.0900281f}, +{-0.0438136f,-0.0811018f,0.0918925f},{-0.0438134f,-0.0811018f,0.0900281f},{-0.0426154f,-0.0779809f,0.0900281f}, +{-0.0418905f,-0.0773294f,0.0900281f},{-0.0423324f,-0.0776969f,0.0918925f},{-0.0412969f,-0.076961f,0.0918925f}, +{-0.0418383f,-0.0772961f,0.0918925f},{-0.0407092f,-0.0767215f,0.0918925f},{-0.041047f,-0.0768428f,0.0900281f}, +{-0.0401206f,-0.0765423f,0.0900281f},{-0.0400974f,-0.0765464f,0.0918925f},{-0.0375901f,-0.0767081f,0.0918925f}, +{-0.0372562f,-0.0768445f,0.0900281f},{-0.0381825f,-0.0765432f,0.0900281f},{-0.0382039f,-0.0765401f,0.0918925f}, +{-0.0359704f,-0.0776954f,0.0918925f},{-0.0364144f,-0.0773301f,0.0900281f},{-0.0364658f,-0.0772978f,0.0918925f}, +{-0.0370158f,-0.0769789f,0.0918925f},{-0.0351171f,-0.0787719f,0.0900281f},{-0.0351705f,-0.0786808f,0.0918925f}, +{-0.0348763f,-0.0792447f,0.0918925f},{-0.0356896f,-0.0779832f,0.0900281f},{-0.0355407f,-0.0781631f,0.0918925f}, +{-0.0346506f,-0.079901f,0.0900281f},{-0.034683f,-0.0798502f,0.0918925f},{-0.0345353f,-0.0804677f,0.0918925f}, +{-0.034847f,-0.0793181f,0.0900281f},{-0.0344916f,-0.0811018f,0.0918925f},{-0.034531f,-0.0804963f,0.0900281f}, +{-0.0344917f,-0.0811018f,0.0900281f},{-0.0445347f,-0.0811018f,0.0751128f},{-0.0431881f,-0.0834317f,0.0900281f}, +{-0.0418436f,-0.0857628f,0.0751128f},{-0.0418436f,-0.0857628f,0.0900281f},{-0.0445347f,-0.0811018f,0.0900281f}, +{-0.0365256f,-0.0820558f,0.0732484f},{-0.0363996f,-0.0815869f,0.0732484f},{-0.0423336f,-0.0776949f,0.0732484f}, +{-0.0418403f,-0.0772937f,0.0732484f},{-0.0373545f,-0.0832407f,0.0732484f},{-0.0370102f,-0.0828961f,0.0732484f}, +{-0.0386659f,-0.0838552f,0.0732484f},{-0.0381948f,-0.0837277f,0.0732484f},{-0.0377533f,-0.0835206f,0.0732484f}, +{-0.0396375f,-0.0838558f,0.0732484f},{-0.0401082f,-0.0837303f,0.0732484f},{-0.0405506f,-0.0835251f,0.0732484f}, +{-0.0417819f,-0.082059f,0.0732484f},{-0.0409506f,-0.0832457f,0.0732484f},{-0.0415756f,-0.082501f,0.0732484f}, +{-0.0412957f,-0.0829006f,0.0732484f},{-0.0419082f,-0.0815877f,0.0732484f},{-0.0437718f,-0.080466f,0.0732484f}, +{-0.0431348f,-0.0786789f,0.0732484f},{-0.0434198f,-0.0792467f,0.0732484f},{-0.0436345f,-0.0798458f,0.0732484f}, +{-0.0427679f,-0.0781594f,0.0732484f},{-0.0412968f,-0.0769632f,0.0732484f},{-0.0401004f,-0.0765382f,0.0732484f}, +{-0.0394701f,-0.0764516f,0.0732484f},{-0.038834f,-0.0764517f,0.0732484f},{-0.0407131f,-0.0767097f,0.0732484f}, +{-0.0382039f,-0.0765384f,0.0732484f},{-0.0375915f,-0.07671f,0.0732484f},{-0.0364646f,-0.077294f,0.0732484f}, +{-0.0370082f,-0.0769634f,0.0732484f},{-0.0359712f,-0.0776957f,0.0732484f},{-0.0348804f,-0.0792464f,0.0732484f}, +{-0.0355368f,-0.0781605f,0.0732484f},{-0.0351728f,-0.0786814f,0.0732484f},{-0.0346667f,-0.0798449f,0.0732484f}, +{-0.0345346f,-0.0804672f,0.0732484f},{-0.0367312f,-0.0824971f,0.0732484f},{-0.0337705f,-0.0811018f,0.0751128f}, +{-0.0351171f,-0.0787719f,0.0751128f},{-0.0337705f,-0.0811018f,0.0900281f},{-0.0431881f,-0.0787719f,0.0751128f}, +{-0.036397f,-0.0815877f,0.080706f},{-0.0370095f,-0.0829006f,0.080706f},{-0.0367296f,-0.082501f,0.080706f}, +{-0.0365233f,-0.082059f,0.080706f},{-0.0381969f,-0.0837303f,0.080706f},{-0.0386677f,-0.0838558f,0.080706f}, +{-0.0377546f,-0.0835251f,0.080706f},{-0.0401104f,-0.0837277f,0.080706f},{-0.0396392f,-0.0838552f,0.080706f}, +{-0.0391526f,-0.0838984f,0.080706f},{-0.0409507f,-0.0832407f,0.080706f},{-0.0405519f,-0.0835206f,0.080706f}, +{-0.041574f,-0.0824971f,0.080706f},{-0.041295f,-0.0828961f,0.080706f},{-0.0417795f,-0.0820558f,0.080706f}, +{-0.0419056f,-0.0815869f,0.080706f},{-0.0373546f,-0.0832457f,0.080706f},{-0.0391526f,-0.0857628f,0.0900281f}, +{-0.0364616f,-0.0857628f,0.0751128f},{-0.0364616f,-0.0857628f,0.0900281f},{-0.0436345f,-0.0823578f,0.0918925f}, +{-0.0391526f,-0.0783052f,0.0918925f},{-0.0423336f,-0.0845087f,0.0918925f},{-0.0418403f,-0.0849099f,0.0918925f}, +{-0.0427679f,-0.0840442f,0.0918925f},{-0.0431348f,-0.0835247f,0.0918925f},{-0.0394701f,-0.085752f,0.0918925f}, +{-0.0401004f,-0.0856654f,0.0918925f},{-0.0407131f,-0.0854939f,0.0918925f},{-0.0375915f,-0.0854936f,0.0918925f}, +{-0.0382039f,-0.0856652f,0.0918925f},{-0.0412968f,-0.0852404f,0.0918925f},{-0.038834f,-0.0857519f,0.0918925f}, +{-0.0370082f,-0.0852402f,0.0918925f},{-0.0364646f,-0.0849096f,0.0918925f},{-0.0359712f,-0.084508f,0.0918925f}, +{-0.0351728f,-0.0835222f,0.0918925f},{-0.0348804f,-0.0829572f,0.0918925f},{-0.0346667f,-0.0823587f,0.0918925f}, +{-0.0415756f,-0.0797026f,0.0918925f},{-0.0417819f,-0.0801446f,0.0918925f},{-0.0405506f,-0.0786785f,0.0918925f}, +{-0.0345346f,-0.0817364f,0.0918925f},{-0.0363996f,-0.0806167f,0.0918925f},{-0.0365256f,-0.0801478f,0.0918925f}, +{-0.0370102f,-0.0793075f,0.0918925f},{-0.0367312f,-0.0797065f,0.0918925f},{-0.0409506f,-0.0789579f,0.0918925f}, +{-0.0377533f,-0.078683f,0.0918925f},{-0.0373545f,-0.0789629f,0.0918925f},{-0.0386659f,-0.0783484f,0.0918925f}, +{-0.0381948f,-0.0784759f,0.0918925f},{-0.0401082f,-0.0784733f,0.0918925f},{-0.0396375f,-0.0783479f,0.0918925f}, +{-0.0412957f,-0.079303f,0.0918925f},{-0.0419082f,-0.0806159f,0.0918925f},{-0.0437718f,-0.0817376f,0.0918925f}, +{-0.0434198f,-0.0829569f,0.0918925f},{-0.0355368f,-0.0840431f,0.0918925f},{-0.0351171f,-0.0834317f,0.0900281f}, +{-0.0437742f,-0.0817073f,0.0900281f},{-0.0434582f,-0.0828855f,0.0900281f},{-0.0436546f,-0.0823026f,0.0900281f}, +{-0.0426156f,-0.0842204f,0.0900281f},{-0.0401226f,-0.0856604f,0.0900281f},{-0.041049f,-0.0853591f,0.0900281f}, +{-0.0364147f,-0.0848742f,0.0900281f},{-0.0381846f,-0.0856613f,0.0900281f},{-0.0356898f,-0.0842227f,0.0900281f}, +{-0.034847f,-0.0828854f,0.0900281f},{-0.0346475f,-0.0823046f,0.0900281f},{-0.0345304f,-0.0817077f,0.0900281f}, +{-0.0372582f,-0.0853608f,0.0900281f},{-0.0418908f,-0.0848735f,0.0900281f},{-0.0381969f,-0.0784733f,0.0844349f}, +{-0.0396392f,-0.0783484f,0.0844349f},{-0.0401104f,-0.0784759f,0.0844349f},{-0.0417795f,-0.0801478f,0.0844349f}, +{-0.0391526f,-0.0783052f,0.0844349f},{-0.0386677f,-0.0783479f,0.0844349f},{-0.041295f,-0.0793075f,0.0844349f}, +{-0.041574f,-0.0797065f,0.0844349f},{-0.0405519f,-0.078683f,0.0844349f},{-0.0409507f,-0.0789629f,0.0844349f}, +{-0.0419056f,-0.0806167f,0.0844349f},{-0.0377546f,-0.0786785f,0.0844349f},{-0.0370095f,-0.079303f,0.0844349f}, +{-0.0373546f,-0.0789579f,0.0844349f},{-0.0367296f,-0.0797026f,0.0844349f},{-0.0365233f,-0.0801446f,0.0844349f}, +{-0.036397f,-0.0806159f,0.0844349f},{-0.0437742f,-0.0804963f,0.0751128f},{-0.0434582f,-0.0793181f,0.0751128f}, +{-0.0436546f,-0.079901f,0.0751128f},{-0.0426156f,-0.0779832f,0.0751128f},{-0.0401226f,-0.0765432f,0.0751128f}, +{-0.041049f,-0.0768445f,0.0751128f},{-0.0364147f,-0.0773294f,0.0751128f},{-0.0381846f,-0.0765423f,0.0751128f}, +{-0.0356898f,-0.0779809f,0.0751128f},{-0.034847f,-0.0793182f,0.0751128f},{-0.0346475f,-0.079899f,0.0751128f}, +{-0.0345304f,-0.0804959f,0.0751128f},{-0.0372582f,-0.0768428f,0.0751128f},{-0.0418908f,-0.0773301f,0.0751128f}, +{-0.0396398f,0.0838556f,0.0732484f},{-0.0391526f,0.0838984f,0.080706f},{-0.0386641f,0.0838554f,0.0732484f}, +{-0.0381961f,0.0837298f,0.080706f},{-0.0386654f,0.0838556f,0.080706f},{-0.0381949f,0.0837293f,0.0732484f}, +{-0.037757f,0.0835251f,0.080706f},{-0.0377553f,0.0835245f,0.0732484f},{-0.0373576f,0.0832459f,0.080706f}, +{-0.0370085f,0.0828968f,0.0732484f},{-0.0370104f,0.0828995f,0.080706f},{-0.0373549f,0.083244f,0.0732484f}, +{-0.0367293f,0.0824974f,0.0732484f},{-0.0367299f,0.0824991f,0.080706f},{-0.0365246f,0.0820583f,0.0732484f}, +{-0.0365251f,0.0820595f,0.080706f},{-0.036399f,0.0815903f,0.080706f},{-0.036399f,0.0815903f,0.0732484f}, +{-0.036356f,0.0811018f,0.080706f},{-0.0396411f,0.0838554f,0.080706f},{-0.0401103f,0.0837293f,0.080706f}, +{-0.040109f,0.0837298f,0.0732484f},{-0.0405482f,0.0835251f,0.0732484f},{-0.0405499f,0.0835245f,0.080706f}, +{-0.0409503f,0.083244f,0.080706f},{-0.0409476f,0.0832459f,0.0732484f},{-0.0412967f,0.0828968f,0.080706f}, +{-0.0412948f,0.0828995f,0.0732484f},{-0.0415753f,0.0824991f,0.0732484f},{-0.0415759f,0.0824974f,0.080706f}, +{-0.0417806f,0.0820583f,0.080706f},{-0.0417801f,0.0820595f,0.0732484f},{-0.0419062f,0.0815903f,0.080706f}, +{-0.0419062f,0.0815903f,0.0732484f},{-0.0419492f,0.0811018f,0.080706f},{-0.0431881f,0.0787719f,0.0751128f}, +{-0.0431216f,0.0786864f,0.0732484f},{-0.0427679f,0.0781593f,0.0732484f},{-0.0388347f,0.0764554f,0.0732484f}, +{-0.0391526f,0.0764408f,0.0751128f},{-0.0394697f,0.076451f,0.0732484f},{-0.0434233f,0.0792468f,0.0732484f}, +{-0.0434581f,0.0793182f,0.0751128f},{-0.0436412f,0.0798436f,0.0732484f},{-0.0436577f,0.079899f,0.0751128f}, +{-0.0437656f,0.080468f,0.0732484f},{-0.0437748f,0.0804959f,0.0751128f},{-0.0438136f,0.0811018f,0.0732484f}, +{-0.0438134f,0.0811018f,0.0751128f},{-0.0426154f,0.0779809f,0.0751128f},{-0.0418905f,0.0773294f,0.0751128f}, +{-0.0423324f,0.0776969f,0.0732484f},{-0.0412969f,0.076961f,0.0732484f},{-0.0418383f,0.0772961f,0.0732484f}, +{-0.0407092f,0.0767216f,0.0732484f},{-0.041047f,0.0768428f,0.0751128f},{-0.0401206f,0.0765423f,0.0751128f}, +{-0.0400974f,0.0765464f,0.0732484f},{-0.0375901f,0.0767081f,0.0732484f},{-0.0372562f,0.0768446f,0.0751128f}, +{-0.0381825f,0.0765432f,0.0751128f},{-0.0382039f,0.0765401f,0.0732484f},{-0.0359704f,0.0776954f,0.0732484f}, +{-0.0364144f,0.0773301f,0.0751128f},{-0.0364658f,0.0772978f,0.0732484f},{-0.0370158f,0.0769789f,0.0732484f}, +{-0.0351171f,0.0787719f,0.0751128f},{-0.0351705f,0.0786808f,0.0732484f},{-0.0348763f,0.0792447f,0.0732484f}, +{-0.0356896f,0.0779832f,0.0751128f},{-0.0355407f,0.0781631f,0.0732484f},{-0.0346506f,0.079901f,0.0751128f}, +{-0.034683f,0.0798502f,0.0732484f},{-0.0345353f,0.0804677f,0.0732484f},{-0.034847f,0.0793181f,0.0751128f}, +{-0.0344916f,0.0811018f,0.0732484f},{-0.034531f,0.0804963f,0.0751128f},{-0.0344918f,0.0811018f,0.0751128f}, +{-0.0391526f,0.0857628f,0.0900281f},{-0.0364616f,0.0857628f,0.0751128f},{-0.0391526f,0.0857628f,0.0751128f}, +{-0.0418436f,0.0857628f,0.0751128f},{-0.0418436f,0.0857628f,0.0900281f},{-0.0364616f,0.0857628f,0.0900281f}, +{-0.0396398f,0.078348f,0.0918925f},{-0.0391526f,0.0783052f,0.0918925f},{-0.0391526f,0.0783052f,0.0844349f}, +{-0.0386641f,0.0783482f,0.0918925f},{-0.0381961f,0.0784738f,0.0844349f},{-0.0386654f,0.078348f,0.0844349f}, +{-0.0381949f,0.0784743f,0.0918925f},{-0.037757f,0.0786785f,0.0844349f},{-0.0377553f,0.0786791f,0.0918925f}, +{-0.0373576f,0.0789577f,0.0844349f},{-0.0370085f,0.0793068f,0.0918925f},{-0.0370104f,0.0793041f,0.0844349f}, +{-0.0373549f,0.0789596f,0.0918925f},{-0.0367293f,0.0797062f,0.0918925f},{-0.0367299f,0.0797045f,0.0844349f}, +{-0.0365246f,0.0801454f,0.0918925f},{-0.0365251f,0.0801441f,0.0844349f},{-0.036399f,0.0806133f,0.0844349f}, +{-0.036399f,0.0806133f,0.0918925f},{-0.036356f,0.0811018f,0.0918925f},{-0.036356f,0.0811018f,0.0844349f}, +{-0.0396411f,0.0783482f,0.0844349f},{-0.0401103f,0.0784743f,0.0844349f},{-0.040109f,0.0784738f,0.0918925f}, +{-0.0405482f,0.0786785f,0.0918925f},{-0.0405499f,0.0786791f,0.0844349f},{-0.0409503f,0.0789596f,0.0844349f}, +{-0.0409476f,0.0789577f,0.0918925f},{-0.0412967f,0.0793068f,0.0844349f},{-0.0412948f,0.0793041f,0.0918925f}, +{-0.0415753f,0.0797045f,0.0918925f},{-0.0415759f,0.0797062f,0.0844349f},{-0.0417806f,0.0801454f,0.0844349f}, +{-0.0417801f,0.0801441f,0.0918925f},{-0.0419062f,0.0806133f,0.0844349f},{-0.0419062f,0.0806133f,0.0918925f}, +{-0.0419492f,0.0811018f,0.0918925f},{-0.0419492f,0.0811018f,0.0844349f},{-0.0431881f,0.0834317f,0.0900281f}, +{-0.0431216f,0.0835172f,0.0918925f},{-0.0427679f,0.0840443f,0.0918925f},{-0.0388347f,0.0857482f,0.0918925f}, +{-0.0394697f,0.0857526f,0.0918925f},{-0.0434233f,0.0829568f,0.0918925f},{-0.0434581f,0.0828854f,0.0900281f}, +{-0.0436412f,0.08236f,0.0918925f},{-0.0436577f,0.0823046f,0.0900281f},{-0.0437656f,0.0817356f,0.0918925f}, +{-0.0437748f,0.0817077f,0.0900281f},{-0.0438136f,0.0811018f,0.0918925f},{-0.0438134f,0.0811018f,0.0900281f}, +{-0.0426154f,0.0842227f,0.0900281f},{-0.0418905f,0.0848742f,0.0900281f},{-0.0423324f,0.0845067f,0.0918925f}, +{-0.0412969f,0.0852426f,0.0918925f},{-0.0418383f,0.0849075f,0.0918925f},{-0.0407092f,0.0854821f,0.0918925f}, +{-0.041047f,0.0853608f,0.0900281f},{-0.0401206f,0.0856613f,0.0900281f},{-0.0400974f,0.0856572f,0.0918925f}, +{-0.0375901f,0.0854955f,0.0918925f},{-0.0372562f,0.0853591f,0.0900281f},{-0.0381825f,0.0856604f,0.0900281f}, +{-0.0382039f,0.0856635f,0.0918925f},{-0.0359704f,0.0845082f,0.0918925f},{-0.0364144f,0.0848735f,0.0900281f}, +{-0.0364658f,0.0849058f,0.0918925f},{-0.0370158f,0.0852247f,0.0918925f},{-0.0351171f,0.0834317f,0.0900281f}, +{-0.0351705f,0.0835228f,0.0918925f},{-0.0348763f,0.0829589f,0.0918925f},{-0.0356896f,0.0842204f,0.0900281f}, +{-0.0355407f,0.0840405f,0.0918925f},{-0.0346506f,0.0823026f,0.0900281f},{-0.034683f,0.0823534f,0.0918925f}, +{-0.0345353f,0.0817359f,0.0918925f},{-0.034847f,0.0828855f,0.0900281f},{-0.0344916f,0.0811018f,0.0918925f}, +{-0.034531f,0.0817073f,0.0900281f},{-0.0344917f,0.0811018f,0.0900281f},{-0.0445347f,0.0811018f,0.0751128f}, +{-0.0431881f,0.0787719f,0.0900281f},{-0.0418436f,0.0764408f,0.0751128f},{-0.0418436f,0.0764408f,0.0900281f}, +{-0.0445347f,0.0811018f,0.0900281f},{-0.0365256f,0.0801478f,0.0732484f},{-0.0363996f,0.0806167f,0.0732484f}, +{-0.0423336f,0.0845087f,0.0732484f},{-0.0418403f,0.0849099f,0.0732484f},{-0.0373545f,0.0789629f,0.0732484f}, +{-0.0370102f,0.0793075f,0.0732484f},{-0.0386659f,0.0783484f,0.0732484f},{-0.0381948f,0.0784759f,0.0732484f}, +{-0.0377533f,0.078683f,0.0732484f},{-0.0396375f,0.0783479f,0.0732484f},{-0.0401082f,0.0784733f,0.0732484f}, +{-0.0405506f,0.0786785f,0.0732484f},{-0.0417819f,0.0801446f,0.0732484f},{-0.0409506f,0.0789579f,0.0732484f}, +{-0.0415756f,0.0797026f,0.0732484f},{-0.0412957f,0.079303f,0.0732484f},{-0.0419082f,0.0806159f,0.0732484f}, +{-0.0437718f,0.0817376f,0.0732484f},{-0.0431348f,0.0835247f,0.0732484f},{-0.0434198f,0.0829569f,0.0732484f}, +{-0.0436345f,0.0823578f,0.0732484f},{-0.0427679f,0.0840442f,0.0732484f},{-0.0412968f,0.0852404f,0.0732484f}, +{-0.0401004f,0.0856654f,0.0732484f},{-0.0394701f,0.085752f,0.0732484f},{-0.038834f,0.0857519f,0.0732484f}, +{-0.0407131f,0.0854939f,0.0732484f},{-0.0382039f,0.0856652f,0.0732484f},{-0.0375915f,0.0854936f,0.0732484f}, +{-0.0364646f,0.0849096f,0.0732484f},{-0.0370082f,0.0852402f,0.0732484f},{-0.0359712f,0.084508f,0.0732484f}, +{-0.0348804f,0.0829572f,0.0732484f},{-0.0355368f,0.0840431f,0.0732484f},{-0.0351728f,0.0835222f,0.0732484f}, +{-0.0346667f,0.0823587f,0.0732484f},{-0.0345346f,0.0817364f,0.0732484f},{-0.0367312f,0.0797065f,0.0732484f}, +{-0.0337705f,0.0811018f,0.0751128f},{-0.0351171f,0.0834317f,0.0751128f},{-0.0337705f,0.0811018f,0.0900281f}, +{-0.0431881f,0.0834317f,0.0751128f},{-0.036397f,0.0806159f,0.080706f},{-0.0370095f,0.079303f,0.080706f}, +{-0.0367296f,0.0797026f,0.080706f},{-0.0365233f,0.0801446f,0.080706f},{-0.0381969f,0.0784733f,0.080706f}, +{-0.0386677f,0.0783479f,0.080706f},{-0.0377546f,0.0786785f,0.080706f},{-0.0401104f,0.0784759f,0.080706f}, +{-0.0396392f,0.0783484f,0.080706f},{-0.0391526f,0.0783052f,0.080706f},{-0.0409507f,0.0789629f,0.080706f}, +{-0.0405519f,0.078683f,0.080706f},{-0.041574f,0.0797065f,0.080706f},{-0.041295f,0.0793075f,0.080706f}, +{-0.0417795f,0.0801478f,0.080706f},{-0.0419056f,0.0806167f,0.080706f},{-0.0373546f,0.0789579f,0.080706f}, +{-0.0391526f,0.0764408f,0.0900281f},{-0.0364616f,0.0764408f,0.0751128f},{-0.0364616f,0.0764408f,0.0900281f}, +{-0.0436345f,0.0798458f,0.0918925f},{-0.0391526f,0.0838984f,0.0918925f},{-0.0423336f,0.0776949f,0.0918925f}, +{-0.0418403f,0.0772937f,0.0918925f},{-0.0427679f,0.0781595f,0.0918925f},{-0.0431348f,0.0786789f,0.0918925f}, +{-0.0394701f,0.0764516f,0.0918925f},{-0.0401004f,0.0765382f,0.0918925f},{-0.0407131f,0.0767097f,0.0918925f}, +{-0.0375915f,0.07671f,0.0918925f},{-0.0382039f,0.0765384f,0.0918925f},{-0.0412968f,0.0769632f,0.0918925f}, +{-0.038834f,0.0764517f,0.0918925f},{-0.0370082f,0.0769634f,0.0918925f},{-0.0364646f,0.077294f,0.0918925f}, +{-0.0359712f,0.0776957f,0.0918925f},{-0.0351728f,0.0786814f,0.0918925f},{-0.0348804f,0.0792464f,0.0918925f}, +{-0.0346667f,0.0798449f,0.0918925f},{-0.0415756f,0.082501f,0.0918925f},{-0.0417819f,0.082059f,0.0918925f}, +{-0.0405506f,0.0835251f,0.0918925f},{-0.0345346f,0.0804672f,0.0918925f},{-0.0363996f,0.0815869f,0.0918925f}, +{-0.0365256f,0.0820558f,0.0918925f},{-0.0370102f,0.0828961f,0.0918925f},{-0.0367312f,0.0824971f,0.0918925f}, +{-0.0409506f,0.0832457f,0.0918925f},{-0.0377533f,0.0835206f,0.0918925f},{-0.0373545f,0.0832407f,0.0918925f}, +{-0.0386659f,0.0838552f,0.0918925f},{-0.0381948f,0.0837277f,0.0918925f},{-0.0401082f,0.0837303f,0.0918925f}, +{-0.0396375f,0.0838558f,0.0918925f},{-0.0412957f,0.0829006f,0.0918925f},{-0.0419082f,0.0815877f,0.0918925f}, +{-0.0437718f,0.080466f,0.0918925f},{-0.0434198f,0.0792467f,0.0918925f},{-0.0355368f,0.0781605f,0.0918925f}, +{-0.0351171f,0.0787719f,0.0900281f},{-0.0437742f,0.0804963f,0.0900281f},{-0.0434582f,0.0793181f,0.0900281f}, +{-0.0436546f,0.079901f,0.0900281f},{-0.0426156f,0.0779832f,0.0900281f},{-0.0401226f,0.0765432f,0.0900281f}, +{-0.041049f,0.0768446f,0.0900281f},{-0.0364147f,0.0773294f,0.0900281f},{-0.0381846f,0.0765423f,0.0900281f}, +{-0.0356898f,0.0779809f,0.0900281f},{-0.034847f,0.0793182f,0.0900281f},{-0.0346475f,0.079899f,0.0900281f}, +{-0.0345304f,0.0804959f,0.0900281f},{-0.0372582f,0.0768428f,0.0900281f},{-0.0418908f,0.0773301f,0.0900281f}, +{-0.0381969f,0.0837303f,0.0844349f},{-0.0396392f,0.0838552f,0.0844349f},{-0.0401104f,0.0837277f,0.0844349f}, +{-0.0417795f,0.0820558f,0.0844349f},{-0.0391526f,0.0838984f,0.0844349f},{-0.0386677f,0.0838558f,0.0844349f}, +{-0.041295f,0.0828961f,0.0844349f},{-0.041574f,0.0824971f,0.0844349f},{-0.0405519f,0.0835206f,0.0844349f}, +{-0.0409507f,0.0832407f,0.0844349f},{-0.0419056f,0.0815869f,0.0844349f},{-0.0377546f,0.0835251f,0.0844349f}, +{-0.0370095f,0.0829006f,0.0844349f},{-0.0373546f,0.0832457f,0.0844349f},{-0.0367296f,0.082501f,0.0844349f}, +{-0.0365233f,0.082059f,0.0844349f},{-0.036397f,0.0815877f,0.0844349f},{-0.0437742f,0.0817073f,0.0751128f}, +{-0.0434582f,0.0828855f,0.0751128f},{-0.0436546f,0.0823026f,0.0751128f},{-0.0426156f,0.0842204f,0.0751128f}, +{-0.0401226f,0.0856604f,0.0751128f},{-0.041049f,0.0853591f,0.0751128f},{-0.0364147f,0.0848742f,0.0751128f}, +{-0.0381846f,0.0856613f,0.0751128f},{-0.0356898f,0.0842227f,0.0751128f},{-0.034847f,0.0828854f,0.0751128f}, +{-0.0346475f,0.0823046f,0.0751128f},{-0.0345304f,0.0817077f,0.0751128f},{-0.0372582f,0.0853608f,0.0751128f}, +{-0.0418908f,0.0848735f,0.0751128f},{0.0386654f,-0.078348f,0.0732484f},{0.0391526f,-0.0783052f,0.080706f}, +{0.0396411f,-0.0783482f,0.0732484f},{0.040109f,-0.0784738f,0.080706f},{0.0396398f,-0.078348f,0.080706f}, +{0.0401103f,-0.0784743f,0.0732484f},{0.0405482f,-0.0786785f,0.080706f},{0.0405499f,-0.0786791f,0.0732484f}, +{0.0409476f,-0.0789577f,0.080706f},{0.0412967f,-0.0793068f,0.0732484f},{0.0412948f,-0.0793041f,0.080706f}, +{0.0409503f,-0.0789596f,0.0732484f},{0.0415759f,-0.0797062f,0.0732484f},{0.0415753f,-0.0797045f,0.080706f}, +{0.0417806f,-0.0801454f,0.0732484f},{0.0417801f,-0.0801441f,0.080706f},{0.0419062f,-0.0806133f,0.080706f}, +{0.0419062f,-0.0806133f,0.0732484f},{0.0419492f,-0.0811018f,0.080706f},{0.0386641f,-0.0783482f,0.080706f}, +{0.0381949f,-0.0784743f,0.080706f},{0.0381961f,-0.0784738f,0.0732484f},{0.037757f,-0.0786785f,0.0732484f}, +{0.0377553f,-0.0786791f,0.080706f},{0.0373549f,-0.0789596f,0.080706f},{0.0373576f,-0.0789577f,0.0732484f}, +{0.0370085f,-0.0793068f,0.080706f},{0.0370104f,-0.0793041f,0.0732484f},{0.0367299f,-0.0797045f,0.0732484f}, +{0.0367293f,-0.0797062f,0.080706f},{0.0365246f,-0.0801454f,0.080706f},{0.0365251f,-0.0801441f,0.0732484f}, +{0.036399f,-0.0806133f,0.080706f},{0.036399f,-0.0806133f,0.0732484f},{0.036356f,-0.0811018f,0.080706f}, +{0.0351171f,-0.0834317f,0.0751128f},{0.0351836f,-0.0835172f,0.0732484f},{0.0355373f,-0.0840443f,0.0732484f}, +{0.0394705f,-0.0857482f,0.0732484f},{0.0391526f,-0.0857628f,0.0751128f},{0.0388355f,-0.0857526f,0.0732484f}, +{0.0348819f,-0.0829568f,0.0732484f},{0.034847f,-0.0828854f,0.0751128f},{0.034664f,-0.08236f,0.0732484f}, +{0.0346475f,-0.0823046f,0.0751128f},{0.0345395f,-0.0817356f,0.0732484f},{0.0345304f,-0.0817077f,0.0751128f}, +{0.0344916f,-0.0811018f,0.0732484f},{0.0344918f,-0.0811018f,0.0751128f},{0.0356898f,-0.0842227f,0.0751128f}, +{0.0364147f,-0.0848742f,0.0751128f},{0.0359728f,-0.0845067f,0.0732484f},{0.0370083f,-0.0852426f,0.0732484f}, +{0.0364669f,-0.0849075f,0.0732484f},{0.037596f,-0.0854821f,0.0732484f},{0.0372582f,-0.0853608f,0.0751128f}, +{0.0381846f,-0.0856613f,0.0751128f},{0.0382078f,-0.0856572f,0.0732484f},{0.0407151f,-0.0854955f,0.0732484f}, +{0.041049f,-0.0853591f,0.0751128f},{0.0401226f,-0.0856604f,0.0751128f},{0.0401013f,-0.0856635f,0.0732484f}, +{0.0423348f,-0.0845082f,0.0732484f},{0.0418908f,-0.0848735f,0.0751128f},{0.0418394f,-0.0849058f,0.0732484f}, +{0.0412894f,-0.0852247f,0.0732484f},{0.0431881f,-0.0834317f,0.0751128f},{0.0431347f,-0.0835228f,0.0732484f}, +{0.0434289f,-0.0829589f,0.0732484f},{0.0426156f,-0.0842204f,0.0751128f},{0.0427645f,-0.0840405f,0.0732484f}, +{0.0436546f,-0.0823026f,0.0751128f},{0.0436222f,-0.0823534f,0.0732484f},{0.0437699f,-0.0817359f,0.0732484f}, +{0.0434582f,-0.0828855f,0.0751128f},{0.0438136f,-0.0811018f,0.0732484f},{0.0437742f,-0.0817073f,0.0751128f}, +{0.0438134f,-0.0811018f,0.0751128f},{0.0391526f,-0.0764408f,0.0900281f},{0.0418436f,-0.0764408f,0.0751128f}, +{0.0391526f,-0.0764408f,0.0751128f},{0.0364616f,-0.0764408f,0.0751128f},{0.0364616f,-0.0764408f,0.0900281f}, +{0.0418436f,-0.0764408f,0.0900281f},{0.0386654f,-0.0838556f,0.0918925f},{0.0391526f,-0.0838984f,0.0918925f}, +{0.0391526f,-0.0838984f,0.0844349f},{0.0396411f,-0.0838554f,0.0918925f},{0.040109f,-0.0837298f,0.0844349f}, +{0.0396398f,-0.0838556f,0.0844349f},{0.0401103f,-0.0837293f,0.0918925f},{0.0405482f,-0.0835251f,0.0844349f}, +{0.0405499f,-0.0835245f,0.0918925f},{0.0409476f,-0.0832459f,0.0844349f},{0.0412967f,-0.0828968f,0.0918925f}, +{0.0412948f,-0.0828995f,0.0844349f},{0.0409503f,-0.083244f,0.0918925f},{0.0415759f,-0.0824974f,0.0918925f}, +{0.0415753f,-0.0824991f,0.0844349f},{0.0417806f,-0.0820583f,0.0918925f},{0.0417801f,-0.0820595f,0.0844349f}, +{0.0419062f,-0.0815903f,0.0844349f},{0.0419062f,-0.0815903f,0.0918925f},{0.0419492f,-0.0811018f,0.0918925f}, +{0.0419492f,-0.0811018f,0.0844349f},{0.0386641f,-0.0838554f,0.0844349f},{0.0381949f,-0.0837293f,0.0844349f}, +{0.0381961f,-0.0837298f,0.0918925f},{0.037757f,-0.0835251f,0.0918925f},{0.0377553f,-0.0835245f,0.0844349f}, +{0.0373549f,-0.083244f,0.0844349f},{0.0373576f,-0.0832459f,0.0918925f},{0.0370085f,-0.0828968f,0.0844349f}, +{0.0370104f,-0.0828995f,0.0918925f},{0.0367299f,-0.0824991f,0.0918925f},{0.0367293f,-0.0824974f,0.0844349f}, +{0.0365246f,-0.0820583f,0.0844349f},{0.0365251f,-0.0820595f,0.0918925f},{0.036399f,-0.0815903f,0.0844349f}, +{0.036399f,-0.0815903f,0.0918925f},{0.036356f,-0.0811018f,0.0918925f},{0.036356f,-0.0811018f,0.0844349f}, +{0.0351171f,-0.0787719f,0.0900281f},{0.0351836f,-0.0786864f,0.0918925f},{0.0355373f,-0.0781593f,0.0918925f}, +{0.0394705f,-0.0764554f,0.0918925f},{0.0388355f,-0.076451f,0.0918925f},{0.0348819f,-0.0792468f,0.0918925f}, +{0.034847f,-0.0793182f,0.0900281f},{0.034664f,-0.0798436f,0.0918925f},{0.0346475f,-0.079899f,0.0900281f}, +{0.0345395f,-0.080468f,0.0918925f},{0.0345304f,-0.0804959f,0.0900281f},{0.0344916f,-0.0811018f,0.0918925f}, +{0.0344917f,-0.0811018f,0.0900281f},{0.0356898f,-0.0779809f,0.0900281f},{0.0364147f,-0.0773294f,0.0900281f}, +{0.0359728f,-0.0776969f,0.0918925f},{0.0370083f,-0.076961f,0.0918925f},{0.0364669f,-0.0772961f,0.0918925f}, +{0.037596f,-0.0767215f,0.0918925f},{0.0372582f,-0.0768428f,0.0900281f},{0.0381846f,-0.0765423f,0.0900281f}, +{0.0382078f,-0.0765464f,0.0918925f},{0.0407151f,-0.0767081f,0.0918925f},{0.041049f,-0.0768445f,0.0900281f}, +{0.0401226f,-0.0765432f,0.0900281f},{0.0401013f,-0.0765401f,0.0918925f},{0.0423348f,-0.0776954f,0.0918925f}, +{0.0418908f,-0.0773301f,0.0900281f},{0.0418394f,-0.0772978f,0.0918925f},{0.0412894f,-0.0769789f,0.0918925f}, +{0.0431881f,-0.0787719f,0.0900281f},{0.0431347f,-0.0786808f,0.0918925f},{0.0434289f,-0.0792447f,0.0918925f}, +{0.0426156f,-0.0779832f,0.0900281f},{0.0427645f,-0.0781631f,0.0918925f},{0.0436546f,-0.079901f,0.0900281f}, +{0.0436222f,-0.0798502f,0.0918925f},{0.0437699f,-0.0804677f,0.0918925f},{0.0434582f,-0.0793181f,0.0900281f}, +{0.0438136f,-0.0811018f,0.0918925f},{0.0437742f,-0.0804963f,0.0900281f},{0.0438134f,-0.0811018f,0.0900281f}, +{0.0337705f,-0.0811018f,0.0751128f},{0.0351171f,-0.0834317f,0.0900281f},{0.0364616f,-0.0857628f,0.0751128f}, +{0.0364616f,-0.0857628f,0.0900281f},{0.0337705f,-0.0811018f,0.0900281f},{0.0417795f,-0.0820558f,0.0732484f}, +{0.0419056f,-0.0815869f,0.0732484f},{0.0359715f,-0.0776949f,0.0732484f},{0.0364649f,-0.0772937f,0.0732484f}, +{0.0409507f,-0.0832407f,0.0732484f},{0.041295f,-0.0828961f,0.0732484f},{0.0396393f,-0.0838552f,0.0732484f}, +{0.0401104f,-0.0837277f,0.0732484f},{0.0405519f,-0.0835206f,0.0732484f},{0.0386677f,-0.0838558f,0.0732484f}, +{0.0381969f,-0.0837303f,0.0732484f},{0.0377546f,-0.0835251f,0.0732484f},{0.0365233f,-0.082059f,0.0732484f}, +{0.0373546f,-0.0832457f,0.0732484f},{0.0367296f,-0.082501f,0.0732484f},{0.0370095f,-0.0829006f,0.0732484f}, +{0.036397f,-0.0815877f,0.0732484f},{0.0345334f,-0.080466f,0.0732484f},{0.0351704f,-0.0786789f,0.0732484f}, +{0.0348854f,-0.0792467f,0.0732484f},{0.0346707f,-0.0798458f,0.0732484f},{0.0355373f,-0.0781594f,0.0732484f}, +{0.0370084f,-0.0769632f,0.0732484f},{0.0382048f,-0.0765382f,0.0732484f},{0.0388351f,-0.0764516f,0.0732484f}, +{0.0394712f,-0.0764517f,0.0732484f},{0.0375921f,-0.0767097f,0.0732484f},{0.0401013f,-0.0765384f,0.0732484f}, +{0.0407137f,-0.07671f,0.0732484f},{0.0418405f,-0.077294f,0.0732484f},{0.0412969f,-0.0769634f,0.0732484f}, +{0.042334f,-0.0776957f,0.0732484f},{0.0434248f,-0.0792464f,0.0732484f},{0.0427684f,-0.0781605f,0.0732484f}, +{0.0431324f,-0.0786814f,0.0732484f},{0.0436384f,-0.0798449f,0.0732484f},{0.0437705f,-0.0804672f,0.0732484f}, +{0.041574f,-0.0824971f,0.0732484f},{0.0445347f,-0.0811018f,0.0751128f},{0.0431881f,-0.0787719f,0.0751128f}, +{0.0445347f,-0.0811018f,0.0900281f},{0.0351171f,-0.0787719f,0.0751128f},{0.0419082f,-0.0815877f,0.080706f}, +{0.0412957f,-0.0829006f,0.080706f},{0.0415756f,-0.082501f,0.080706f},{0.0417819f,-0.082059f,0.080706f}, +{0.0401082f,-0.0837303f,0.080706f},{0.0396375f,-0.0838558f,0.080706f},{0.0405506f,-0.0835251f,0.080706f}, +{0.0381948f,-0.0837277f,0.080706f},{0.0386659f,-0.0838552f,0.080706f},{0.0391526f,-0.0838984f,0.080706f}, +{0.0373545f,-0.0832407f,0.080706f},{0.0377533f,-0.0835206f,0.080706f},{0.0367312f,-0.0824971f,0.080706f}, +{0.0370102f,-0.0828961f,0.080706f},{0.0365256f,-0.0820558f,0.080706f},{0.0363996f,-0.0815869f,0.080706f}, +{0.0409506f,-0.0832457f,0.080706f},{0.0391526f,-0.0857628f,0.0900281f},{0.0418436f,-0.0857628f,0.0751128f}, +{0.0418436f,-0.0857628f,0.0900281f},{0.0346707f,-0.0823578f,0.0918925f},{0.0391526f,-0.0783052f,0.0918925f}, +{0.0359715f,-0.0845087f,0.0918925f},{0.0364649f,-0.0849099f,0.0918925f},{0.0355373f,-0.0840442f,0.0918925f}, +{0.0351704f,-0.0835247f,0.0918925f},{0.0388351f,-0.085752f,0.0918925f},{0.0382048f,-0.0856654f,0.0918925f}, +{0.0375921f,-0.0854939f,0.0918925f},{0.0407137f,-0.0854936f,0.0918925f},{0.0401013f,-0.0856652f,0.0918925f}, +{0.0370084f,-0.0852404f,0.0918925f},{0.0394712f,-0.0857519f,0.0918925f},{0.0412969f,-0.0852402f,0.0918925f}, +{0.0418405f,-0.0849096f,0.0918925f},{0.042334f,-0.084508f,0.0918925f},{0.0431324f,-0.0835222f,0.0918925f}, +{0.0434248f,-0.0829572f,0.0918925f},{0.0436384f,-0.0823587f,0.0918925f},{0.0367296f,-0.0797026f,0.0918925f}, +{0.0365233f,-0.0801446f,0.0918925f},{0.0377546f,-0.0786785f,0.0918925f},{0.0437705f,-0.0817364f,0.0918925f}, +{0.0419056f,-0.0806167f,0.0918925f},{0.0417795f,-0.0801478f,0.0918925f},{0.041295f,-0.0793075f,0.0918925f}, +{0.041574f,-0.0797065f,0.0918925f},{0.0373546f,-0.0789579f,0.0918925f},{0.0405519f,-0.078683f,0.0918925f}, +{0.0409507f,-0.0789629f,0.0918925f},{0.0396393f,-0.0783484f,0.0918925f},{0.0401104f,-0.0784759f,0.0918925f}, +{0.0381969f,-0.0784733f,0.0918925f},{0.0386677f,-0.0783479f,0.0918925f},{0.0370095f,-0.079303f,0.0918925f}, +{0.036397f,-0.0806159f,0.0918925f},{0.0345334f,-0.0817376f,0.0918925f},{0.0348854f,-0.0829569f,0.0918925f}, +{0.0427684f,-0.0840431f,0.0918925f},{0.0431881f,-0.0834317f,0.0900281f},{0.034531f,-0.0817073f,0.0900281f}, +{0.034847f,-0.0828855f,0.0900281f},{0.0346506f,-0.0823026f,0.0900281f},{0.0356896f,-0.0842204f,0.0900281f}, +{0.0381825f,-0.0856604f,0.0900281f},{0.0372562f,-0.0853591f,0.0900281f},{0.0418905f,-0.0848742f,0.0900281f}, +{0.0401206f,-0.0856613f,0.0900281f},{0.0426154f,-0.0842227f,0.0900281f},{0.0434581f,-0.0828854f,0.0900281f}, +{0.0436577f,-0.0823046f,0.0900281f},{0.0437748f,-0.0817077f,0.0900281f},{0.041047f,-0.0853608f,0.0900281f}, +{0.0364144f,-0.0848735f,0.0900281f},{0.0401082f,-0.0784733f,0.0844349f},{0.0386659f,-0.0783484f,0.0844349f}, +{0.0381948f,-0.0784759f,0.0844349f},{0.0365256f,-0.0801478f,0.0844349f},{0.0391526f,-0.0783052f,0.0844349f}, +{0.0396375f,-0.0783479f,0.0844349f},{0.0370102f,-0.0793075f,0.0844349f},{0.0367312f,-0.0797065f,0.0844349f}, +{0.0377533f,-0.078683f,0.0844349f},{0.0373545f,-0.0789629f,0.0844349f},{0.0363996f,-0.0806167f,0.0844349f}, +{0.0405506f,-0.0786785f,0.0844349f},{0.0412957f,-0.079303f,0.0844349f},{0.0409506f,-0.0789579f,0.0844349f}, +{0.0415756f,-0.0797026f,0.0844349f},{0.0417819f,-0.0801446f,0.0844349f},{0.0419082f,-0.0806159f,0.0844349f}, +{0.034531f,-0.0804963f,0.0751128f},{0.034847f,-0.0793181f,0.0751128f},{0.0346506f,-0.079901f,0.0751128f}, +{0.0356896f,-0.0779832f,0.0751128f},{0.0381825f,-0.0765432f,0.0751128f},{0.0372562f,-0.0768445f,0.0751128f}, +{0.0418905f,-0.0773294f,0.0751128f},{0.0401206f,-0.0765423f,0.0751128f},{0.0426154f,-0.0779809f,0.0751128f}, +{0.0434581f,-0.0793182f,0.0751128f},{0.0436577f,-0.079899f,0.0751128f},{0.0437748f,-0.0804959f,0.0751128f}, +{0.041047f,-0.0768428f,0.0751128f},{0.0364144f,-0.0773301f,0.0751128f},{0.0205353f,-0.305423f,0.0918925f}, +{0.0197119f,-0.306322f,0.0918925f},{0.0197119f,-0.306322f,0.100469f},{0.018681f,-0.306977f,0.0918925f}, +{0.0175301f,-0.30734f,0.100469f},{0.0186838f,-0.306976f,0.100469f},{0.0163096f,-0.307394f,0.0918925f}, +{0.0163096f,-0.307394f,0.100469f},{0.0175273f,-0.307341f,0.0918925f},{0.0205366f,-0.30542f,0.100469f}, +{0.0210952f,-0.304347f,0.100469f},{0.0210939f,-0.30435f,0.0918925f},{0.0213591f,-0.303157f,0.0918925f}, +{0.0213591f,-0.303157f,0.100469f},{0.0124916f,-0.297856f,0.0918925f},{0.0131454f,-0.29683f,0.0918925f}, +{0.0131452f,-0.29683f,0.100469f},{0.014044f,-0.296007f,0.0918925f},{0.01512f,-0.295447f,0.100469f}, +{0.0140418f,-0.296008f,0.100469f},{0.0163096f,-0.295183f,0.0918925f},{0.0163096f,-0.295183f,0.100469f}, +{0.0151227f,-0.295446f,0.0918925f},{0.0124909f,-0.297858f,0.100469f},{0.0121253f,-0.299018f,0.100469f}, +{0.0121261f,-0.299015f,0.0918925f},{0.012073f,-0.300232f,0.0918925f},{0.012073f,-0.300232f,0.100469f}, +{-0.305423f,-0.0205353f,0.0918925f},{-0.306322f,-0.0197119f,0.0918925f},{-0.306322f,-0.0197119f,0.100469f}, +{-0.306977f,-0.018681f,0.0918925f},{-0.30734f,-0.0175301f,0.100469f},{-0.306976f,-0.0186838f,0.100469f}, +{-0.307394f,-0.0163096f,0.0918925f},{-0.307394f,-0.0163096f,0.100469f},{-0.307341f,-0.0175273f,0.0918925f}, +{-0.30542f,-0.0205366f,0.100469f},{-0.304347f,-0.0210952f,0.100469f},{-0.30435f,-0.0210939f,0.0918925f}, +{-0.303157f,-0.0213591f,0.0918925f},{-0.303157f,-0.0213591f,0.100469f},{-0.297855f,-0.0124921f,0.0918925f}, +{-0.29683f,-0.0131453f,0.0918925f},{-0.29683f,-0.0131452f,0.100469f},{-0.296007f,-0.0140439f,0.0918925f}, +{-0.295447f,-0.01512f,0.100469f},{-0.296009f,-0.0140413f,0.100469f},{-0.295183f,-0.0163096f,0.0918925f}, +{-0.295183f,-0.0163096f,0.100469f},{-0.295446f,-0.0151233f,0.0918925f},{-0.297858f,-0.0124909f,0.100469f}, +{-0.299018f,-0.0121254f,0.100469f},{-0.299015f,-0.012126f,0.0918925f},{-0.300232f,-0.012073f,0.0918925f}, +{-0.300232f,-0.012073f,0.100469f},{-0.0205353f,0.305423f,0.0918925f},{-0.0197119f,0.306322f,0.0918925f}, +{-0.0197119f,0.306322f,0.100469f},{-0.018681f,0.306977f,0.0918925f},{-0.0175301f,0.30734f,0.100469f}, +{-0.0186838f,0.306976f,0.100469f},{-0.0163096f,0.307394f,0.0918925f},{-0.0163096f,0.307394f,0.100469f}, +{-0.0175273f,0.307341f,0.0918925f},{-0.0205366f,0.30542f,0.100469f},{-0.0210952f,0.304347f,0.100469f}, +{-0.0210939f,0.30435f,0.0918925f},{-0.0213591f,0.303157f,0.0918925f},{-0.0213591f,0.303157f,0.100469f}, +{-0.0124916f,0.297856f,0.0918925f},{-0.0131454f,0.29683f,0.0918925f},{-0.0131452f,0.29683f,0.100469f}, +{-0.014044f,0.296007f,0.0918925f},{-0.01512f,0.295447f,0.100469f},{-0.0140418f,0.296008f,0.100469f}, +{-0.0163096f,0.295183f,0.0918925f},{-0.0163096f,0.295183f,0.100469f},{-0.0151227f,0.295446f,0.0918925f}, +{-0.0124909f,0.297858f,0.100469f},{-0.0121253f,0.299018f,0.100469f},{-0.0121261f,0.299015f,0.0918925f}, +{-0.012073f,0.300232f,0.0918925f},{-0.012073f,0.300232f,0.100469f},{-0.00413429f,-0.321824f,0.0918925f}, +{-0.005033f,-0.321f,0.0918925f},{-0.005033f,-0.321f,0.100469f},{-0.00568869f,-0.31997f,0.0918925f}, +{-0.00605158f,-0.318819f,0.100469f},{-0.00568781f,-0.319972f,0.100469f},{-0.00610573f,-0.317598f,0.0918925f}, +{-0.00610573f,-0.317598f,0.100469f},{-0.00605247f,-0.318816f,0.0918925f},{-0.00413168f,-0.321825f,0.100469f}, +{-0.00305863f,-0.322384f,0.100469f},{-0.00306124f,-0.322382f,0.0918925f},{-0.00186868f,-0.322648f,0.0918925f}, +{-0.00186868f,-0.322648f,0.100469f},{0.00343343f,-0.313781f,0.0918925f},{0.00445856f,-0.314434f,0.0918925f}, +{0.00445842f,-0.314434f,0.100469f},{0.00528145f,-0.315332f,0.0918925f},{0.00584165f,-0.316409f,0.100469f}, +{0.0052798f,-0.31533f,0.100469f},{0.00610573f,-0.317598f,0.0918925f},{0.00610573f,-0.317598f,0.100469f}, +{0.00584289f,-0.316412f,0.0918925f},{0.00343061f,-0.313779f,0.100469f},{0.00227009f,-0.313414f,0.100469f}, +{0.00227354f,-0.313415f,0.0918925f},{0.00105623f,-0.313362f,0.0918925f},{0.00105623f,-0.313362f,0.100469f}, +{-0.321824f,0.00413429f,0.0918925f},{-0.321f,0.005033f,0.0918925f},{-0.321f,0.005033f,0.100469f}, +{-0.31997f,0.00568869f,0.0918925f},{-0.318819f,0.00605158f,0.100469f},{-0.319972f,0.00568781f,0.100469f}, +{-0.317598f,0.00610573f,0.0918925f},{-0.317598f,0.00610573f,0.100469f},{-0.318816f,0.00605247f,0.0918925f}, +{-0.321825f,0.00413168f,0.100469f},{-0.322384f,0.00305863f,0.100469f},{-0.322382f,0.00306124f,0.0918925f}, +{-0.322648f,0.00186868f,0.0918925f},{-0.322648f,0.00186868f,0.100469f},{-0.313781f,-0.00343343f,0.0918925f}, +{-0.314434f,-0.00445856f,0.0918925f},{-0.314434f,-0.00445842f,0.100469f},{-0.315332f,-0.00528145f,0.0918925f}, +{-0.316409f,-0.00584165f,0.100469f},{-0.31533f,-0.0052798f,0.100469f},{-0.317598f,-0.00610573f,0.0918925f}, +{-0.317598f,-0.00610573f,0.100469f},{-0.316412f,-0.00584289f,0.0918925f},{-0.313779f,-0.00343061f,0.100469f}, +{-0.313414f,-0.00227009f,0.100469f},{-0.313415f,-0.00227354f,0.0918925f},{-0.313362f,-0.00105623f,0.0918925f}, +{-0.313362f,-0.00105623f,0.100469f},{0.00413429f,0.321824f,0.0918925f},{0.005033f,0.321f,0.0918925f}, +{0.005033f,0.321f,0.100469f},{0.00568869f,0.31997f,0.0918925f},{0.00605158f,0.318819f,0.100469f}, +{0.00568781f,0.319972f,0.100469f},{0.00610573f,0.317598f,0.0918925f},{0.00610573f,0.317598f,0.100469f}, +{0.00605247f,0.318816f,0.0918925f},{0.00413168f,0.321825f,0.100469f},{0.00305863f,0.322384f,0.100469f}, +{0.00306124f,0.322382f,0.0918925f},{0.00186868f,0.322648f,0.0918925f},{0.00186868f,0.322648f,0.100469f}, +{-0.00343343f,0.313781f,0.0918925f},{-0.00445856f,0.314434f,0.0918925f},{-0.00445842f,0.314434f,0.100469f}, +{-0.00528145f,0.315332f,0.0918925f},{-0.00584165f,0.316409f,0.100469f},{-0.0052798f,0.31533f,0.100469f}, +{-0.00610573f,0.317598f,0.0918925f},{-0.00610573f,0.317598f,0.100469f},{-0.00584289f,0.316412f,0.0918925f}, +{-0.00343061f,0.313779f,0.100469f},{-0.00227009f,0.313414f,0.100469f},{-0.00227354f,0.313415f,0.0918925f}, +{-0.00105623f,0.313362f,0.0918925f},{-0.00105623f,0.313362f,0.100469f},{-0.0205353f,-0.297154f,0.0918925f}, +{-0.0197119f,-0.296256f,0.0918925f},{-0.0197119f,-0.296256f,0.100469f},{-0.018681f,-0.2956f,0.0918925f}, +{-0.0175301f,-0.295237f,0.100469f},{-0.0186838f,-0.295601f,0.100469f},{-0.0163096f,-0.295183f,0.0918925f}, +{-0.0163096f,-0.295183f,0.100469f},{-0.0175273f,-0.295236f,0.0918925f},{-0.0205366f,-0.297157f,0.100469f}, +{-0.0210952f,-0.29823f,0.100469f},{-0.0210939f,-0.298227f,0.0918925f},{-0.0213591f,-0.29942f,0.0918925f}, +{-0.0213591f,-0.29942f,0.100469f},{-0.0124916f,-0.304721f,0.0918925f},{-0.0131454f,-0.305747f,0.0918925f}, +{-0.0131452f,-0.305747f,0.100469f},{-0.014044f,-0.30657f,0.0918925f},{-0.01512f,-0.30713f,0.100469f}, +{-0.0140418f,-0.306569f,0.100469f},{-0.0163096f,-0.307394f,0.0918925f},{-0.0163096f,-0.307394f,0.100469f}, +{-0.0151227f,-0.307131f,0.0918925f},{-0.0124909f,-0.304719f,0.100469f},{-0.0121253f,-0.303559f,0.100469f}, +{-0.0121261f,-0.303562f,0.0918925f},{-0.012073f,-0.302345f,0.0918925f},{-0.012073f,-0.302345f,0.100469f}, +{-0.297154f,0.0205353f,0.0918925f},{-0.296256f,0.0197119f,0.0918925f},{-0.296256f,0.0197119f,0.100469f}, +{-0.2956f,0.018681f,0.0918925f},{-0.295237f,0.0175301f,0.100469f},{-0.295601f,0.0186838f,0.100469f}, +{-0.295183f,0.0163096f,0.0918925f},{-0.295183f,0.0163096f,0.100469f},{-0.295236f,0.0175273f,0.0918925f}, +{-0.297157f,0.0205366f,0.100469f},{-0.29823f,0.0210952f,0.100469f},{-0.298227f,0.0210939f,0.0918925f}, +{-0.29942f,0.0213591f,0.0918925f},{-0.29942f,0.0213591f,0.100469f},{-0.304721f,0.0124916f,0.0918925f}, +{-0.305747f,0.0131454f,0.0918925f},{-0.305747f,0.0131452f,0.100469f},{-0.30657f,0.014044f,0.0918925f}, +{-0.30713f,0.01512f,0.100469f},{-0.306569f,0.0140418f,0.100469f},{-0.307394f,0.0163096f,0.0918925f}, +{-0.307394f,0.0163096f,0.100469f},{-0.307131f,0.0151227f,0.0918925f},{-0.304719f,0.0124909f,0.100469f}, +{-0.303559f,0.0121253f,0.100469f},{-0.303562f,0.0121261f,0.0918925f},{-0.302345f,0.012073f,0.0918925f}, +{-0.302345f,0.012073f,0.100469f},{0.0205329f,0.297151f,0.0918925f},{0.0197119f,0.296256f,0.0918925f}, +{0.0197119f,0.296256f,0.100469f},{0.0186836f,0.295601f,0.0918925f},{0.0175301f,0.295237f,0.100469f}, +{0.0186838f,0.295601f,0.100469f},{0.0163096f,0.295183f,0.0918925f},{0.0163096f,0.295183f,0.100469f}, +{0.0175235f,0.295236f,0.0918925f},{0.0205366f,0.297157f,0.100469f},{0.0210952f,0.29823f,0.100469f}, +{0.0210948f,0.29823f,0.0918925f},{0.0213591f,0.29942f,0.0918925f},{0.0213591f,0.29942f,0.100469f}, +{0.0124921f,0.304722f,0.0918925f},{0.0131453f,0.305747f,0.0918925f},{0.0131452f,0.305747f,0.100469f}, +{0.0140439f,0.30657f,0.0918925f},{0.01512f,0.30713f,0.100469f},{0.0140413f,0.306568f,0.100469f}, +{0.0163096f,0.307394f,0.0918925f},{0.0163096f,0.307394f,0.100469f},{0.0151233f,0.307131f,0.0918925f}, +{0.0124909f,0.304719f,0.100469f},{0.0121254f,0.303559f,0.100469f},{0.012126f,0.303562f,0.0918925f}, +{0.012073f,0.302345f,0.0918925f},{0.012073f,0.302345f,0.100469f},{0.00413429f,-0.280753f,0.0918925f}, +{0.005033f,-0.281577f,0.0918925f},{0.005033f,-0.281577f,0.100469f},{0.00568869f,-0.282607f,0.0918925f}, +{0.00605158f,-0.283758f,0.100469f},{0.00568781f,-0.282605f,0.100469f},{0.00610573f,-0.284979f,0.0918925f}, +{0.00610573f,-0.284979f,0.100469f},{0.00605247f,-0.283761f,0.0918925f},{0.00413168f,-0.280752f,0.100469f}, +{0.00305863f,-0.280193f,0.100469f},{0.00306124f,-0.280195f,0.0918925f},{0.00186868f,-0.279929f,0.0918925f}, +{0.00186868f,-0.279929f,0.100469f},{-0.00343343f,-0.288796f,0.0918925f},{-0.00445856f,-0.288143f,0.0918925f}, +{-0.00445842f,-0.288143f,0.100469f},{-0.00528145f,-0.287245f,0.0918925f},{-0.00584165f,-0.286169f,0.100469f}, +{-0.0052798f,-0.287247f,0.100469f},{-0.00610573f,-0.284979f,0.0918925f},{-0.00610573f,-0.284979f,0.100469f}, +{-0.00584289f,-0.286165f,0.0918925f},{-0.00343061f,-0.288798f,0.100469f},{-0.00227009f,-0.289163f,0.100469f}, +{-0.00227354f,-0.289162f,0.0918925f},{-0.00105623f,-0.289216f,0.0918925f},{-0.00105623f,-0.289216f,0.100469f}, +{-0.280753f,-0.00413429f,0.0918925f},{-0.281577f,-0.005033f,0.0918925f},{-0.281577f,-0.005033f,0.100469f}, +{-0.282607f,-0.00568869f,0.0918925f},{-0.283758f,-0.00605158f,0.100469f},{-0.282605f,-0.00568781f,0.100469f}, +{-0.284979f,-0.00610573f,0.0918925f},{-0.284979f,-0.00610573f,0.100469f},{-0.283761f,-0.00605247f,0.0918925f}, +{-0.280752f,-0.00413168f,0.100469f},{-0.280193f,-0.00305863f,0.100469f},{-0.280195f,-0.00306124f,0.0918925f}, +{-0.279929f,-0.00186868f,0.0918925f},{-0.279929f,-0.00186868f,0.100469f},{-0.288796f,0.00343343f,0.0918925f}, +{-0.288143f,0.00445856f,0.0918925f},{-0.288143f,0.00445842f,0.100469f},{-0.287245f,0.00528145f,0.0918925f}, +{-0.286169f,0.00584165f,0.100469f},{-0.287247f,0.0052798f,0.100469f},{-0.284979f,0.00610573f,0.0918925f}, +{-0.284979f,0.00610573f,0.100469f},{-0.286165f,0.00584289f,0.0918925f},{-0.288798f,0.00343061f,0.100469f}, +{-0.289163f,0.00227009f,0.100469f},{-0.289162f,0.00227354f,0.0918925f},{-0.289216f,0.00105623f,0.0918925f}, +{-0.289216f,0.00105623f,0.100469f},{-0.00413429f,0.280753f,0.0918925f},{-0.005033f,0.281577f,0.0918925f}, +{-0.005033f,0.281577f,0.100469f},{-0.00568869f,0.282607f,0.0918925f},{-0.00605158f,0.283758f,0.100469f}, +{-0.00568781f,0.282605f,0.100469f},{-0.00610573f,0.284979f,0.0918925f},{-0.00610573f,0.284979f,0.100469f}, +{-0.00605247f,0.283761f,0.0918925f},{-0.00413168f,0.280752f,0.100469f},{-0.00305863f,0.280193f,0.100469f}, +{-0.00306124f,0.280195f,0.0918925f},{-0.00186868f,0.279929f,0.0918925f},{-0.00186868f,0.279929f,0.100469f}, +{0.00343343f,0.288796f,0.0918925f},{0.00445856f,0.288143f,0.0918925f},{0.00445842f,0.288143f,0.100469f}, +{0.00528145f,0.287245f,0.0918925f},{0.00584165f,0.286169f,0.100469f},{0.0052798f,0.287247f,0.100469f}, +{0.00610573f,0.284979f,0.0918925f},{0.00610573f,0.284979f,0.100469f},{0.00584289f,0.286165f,0.0918925f}, +{0.00343061f,0.288798f,0.100469f},{0.00227009f,0.289163f,0.100469f},{0.00227354f,0.289162f,0.0918925f}, +{0.00105623f,0.289216f,0.0918925f},{0.00105623f,0.289216f,0.100469f},{0.305423f,0.0205353f,0.0918925f}, +{0.306322f,0.0197119f,0.0918925f},{0.306322f,0.0197119f,0.100469f},{0.306977f,0.018681f,0.0918925f}, +{0.30734f,0.0175301f,0.100469f},{0.306976f,0.0186838f,0.100469f},{0.307394f,0.0163096f,0.0918925f}, +{0.307394f,0.0163096f,0.100469f},{0.307341f,0.0175273f,0.0918925f},{0.30542f,0.0205366f,0.100469f}, +{0.304347f,0.0210952f,0.100469f},{0.30435f,0.0210939f,0.0918925f},{0.303157f,0.0213591f,0.0918925f}, +{0.303157f,0.0213591f,0.100469f},{0.297856f,0.0124916f,0.0918925f},{0.29683f,0.0131454f,0.0918925f}, +{0.29683f,0.0131452f,0.100469f},{0.296007f,0.014044f,0.0918925f},{0.295447f,0.01512f,0.100469f}, +{0.296008f,0.0140418f,0.100469f},{0.295183f,0.0163096f,0.0918925f},{0.295183f,0.0163096f,0.100469f}, +{0.295446f,0.0151227f,0.0918925f},{0.297858f,0.0124909f,0.100469f},{0.299018f,0.0121253f,0.100469f}, +{0.299015f,0.0121261f,0.0918925f},{0.300232f,0.012073f,0.0918925f},{0.300232f,0.012073f,0.100469f}, +{0.321824f,-0.00413429f,0.0918925f},{0.321f,-0.005033f,0.0918925f},{0.321f,-0.005033f,0.100469f}, +{0.31997f,-0.00568869f,0.0918925f},{0.318819f,-0.00605158f,0.100469f},{0.319972f,-0.00568781f,0.100469f}, +{0.317598f,-0.00610573f,0.0918925f},{0.317598f,-0.00610573f,0.100469f},{0.318816f,-0.00605247f,0.0918925f}, +{0.321825f,-0.00413168f,0.100469f},{0.322384f,-0.00305863f,0.100469f},{0.322382f,-0.00306124f,0.0918925f}, +{0.322648f,-0.00186868f,0.0918925f},{0.322648f,-0.00186868f,0.100469f},{0.313781f,0.00343343f,0.0918925f}, +{0.314434f,0.00445856f,0.0918925f},{0.314434f,0.00445842f,0.100469f},{0.315332f,0.00528145f,0.0918925f}, +{0.316409f,0.00584165f,0.100469f},{0.31533f,0.0052798f,0.100469f},{0.317598f,0.00610573f,0.0918925f}, +{0.317598f,0.00610573f,0.100469f},{0.316412f,0.00584289f,0.0918925f},{0.313779f,0.00343061f,0.100469f}, +{0.313414f,0.00227009f,0.100469f},{0.313415f,0.00227354f,0.0918925f},{0.313362f,0.00105623f,0.0918925f}, +{0.313362f,0.00105623f,0.100469f},{0.297151f,-0.0205329f,0.0918925f},{0.296256f,-0.0197119f,0.0918925f}, +{0.296256f,-0.0197119f,0.100469f},{0.295601f,-0.0186836f,0.0918925f},{0.295237f,-0.0175301f,0.100469f}, +{0.295601f,-0.0186838f,0.100469f},{0.295183f,-0.0163096f,0.0918925f},{0.295183f,-0.0163096f,0.100469f}, +{0.295236f,-0.0175235f,0.0918925f},{0.297157f,-0.0205366f,0.100469f},{0.29823f,-0.0210952f,0.100469f}, +{0.29823f,-0.0210948f,0.0918925f},{0.29942f,-0.0213591f,0.0918925f},{0.29942f,-0.0213591f,0.100469f}, +{0.304721f,-0.0124916f,0.0918925f},{0.305747f,-0.0131454f,0.0918925f},{0.305747f,-0.0131452f,0.100469f}, +{0.30657f,-0.014044f,0.0918925f},{0.30713f,-0.01512f,0.100469f},{0.306569f,-0.0140418f,0.100469f}, +{0.307394f,-0.0163096f,0.0918925f},{0.307394f,-0.0163096f,0.100469f},{0.307131f,-0.0151227f,0.0918925f}, +{0.304719f,-0.0124909f,0.100469f},{0.303559f,-0.0121253f,0.100469f},{0.303562f,-0.0121261f,0.0918925f}, +{0.302345f,-0.012073f,0.0918925f},{0.302345f,-0.012073f,0.100469f},{-0.313522f,-0.0153056f,0.0918925f}, +{-0.314107f,-0.015305f,0.0918925f},{-0.314104f,-0.0153056f,0.100469f},{-0.313518f,-0.015305f,0.100469f}, +{-0.312949f,-0.0151842f,0.0918925f},{-0.312948f,-0.0151836f,0.100469f},{-0.312414f,-0.014946f,0.100469f}, +{-0.311943f,-0.0146037f,0.0918925f},{-0.312416f,-0.0149467f,0.0918925f},{-0.31194f,-0.0146009f,0.100469f}, +{-0.311551f,-0.0141686f,0.0918925f},{-0.31155f,-0.0141674f,0.100469f},{-0.311258f,-0.0136627f,0.0918925f}, +{-0.311257f,-0.0136603f,0.100469f},{-0.311078f,-0.0131075f,0.0918925f},{-0.311077f,-0.013106f,0.100469f}, +{-0.311016f,-0.0125242f,0.100469f},{-0.311016f,-0.0125242f,0.0918925f},{-0.314676f,-0.0151842f,0.100469f}, +{-0.31521f,-0.0149467f,0.100469f},{-0.314678f,-0.0151836f,0.0918925f},{-0.315212f,-0.014946f,0.0918925f}, +{-0.315682f,-0.0146037f,0.100469f},{-0.315685f,-0.0146009f,0.0918925f},{-0.316075f,-0.0141686f,0.100469f}, +{-0.316367f,-0.0136627f,0.100469f},{-0.316076f,-0.0141674f,0.0918925f},{-0.316368f,-0.0136603f,0.0918925f}, +{-0.316548f,-0.0131075f,0.100469f},{-0.316548f,-0.013106f,0.0918925f},{-0.316609f,-0.0125242f,0.100469f}, +{-0.316609f,-0.0125242f,0.0918925f},{-0.313522f,0.00974281f,0.0918925f},{-0.314107f,0.0097434f,0.0918925f}, +{-0.314104f,0.00974281f,0.100469f},{-0.313518f,0.0097434f,0.100469f},{-0.312949f,0.00986419f,0.0918925f}, +{-0.312948f,0.00986481f,0.100469f},{-0.312414f,0.0101024f,0.100469f},{-0.311943f,0.0104447f,0.0918925f}, +{-0.312416f,0.0101017f,0.0918925f},{-0.31194f,0.0104475f,0.100469f},{-0.311551f,0.0108798f,0.0918925f}, +{-0.31155f,0.010881f,0.100469f},{-0.311258f,0.0113857f,0.0918925f},{-0.311257f,0.0113881f,0.100469f}, +{-0.311078f,0.0119409f,0.0918925f},{-0.311077f,0.0119424f,0.100469f},{-0.311016f,0.0125242f,0.100469f}, +{-0.314676f,0.00986419f,0.100469f},{-0.31521f,0.0101017f,0.100469f},{-0.314678f,0.00986481f,0.0918925f}, +{-0.315212f,0.0101024f,0.0918925f},{-0.315682f,0.0104447f,0.100469f},{-0.315685f,0.0104475f,0.0918925f}, +{-0.316075f,0.0108798f,0.100469f},{-0.316367f,0.0113857f,0.100469f},{-0.316076f,0.010881f,0.0918925f}, +{-0.316368f,0.0113881f,0.0918925f},{-0.316548f,0.0119409f,0.100469f},{-0.316548f,0.0119424f,0.0918925f}, +{-0.316609f,0.0125242f,0.100469f},{-0.288473f,0.00974281f,0.0918925f},{-0.289059f,0.0097434f,0.0918925f}, +{-0.289055f,0.00974281f,0.100469f},{-0.28847f,0.0097434f,0.100469f},{-0.287901f,0.00986419f,0.0918925f}, +{-0.287899f,0.00986481f,0.100469f},{-0.287366f,0.0101024f,0.100469f},{-0.286895f,0.0104447f,0.0918925f}, +{-0.287367f,0.0101017f,0.0918925f},{-0.286892f,0.0104475f,0.100469f},{-0.286502f,0.0108798f,0.0918925f}, +{-0.286501f,0.010881f,0.100469f},{-0.28621f,0.0113857f,0.0918925f},{-0.286209f,0.0113881f,0.100469f}, +{-0.286029f,0.0119409f,0.0918925f},{-0.286029f,0.0119424f,0.100469f},{-0.285968f,0.0125242f,0.100469f}, +{-0.285968f,0.0125242f,0.0918925f},{-0.289628f,0.00986419f,0.100469f},{-0.290161f,0.0101017f,0.100469f}, +{-0.289629f,0.00986481f,0.0918925f},{-0.290163f,0.0101024f,0.0918925f},{-0.290634f,0.0104447f,0.100469f}, +{-0.290637f,0.0104475f,0.0918925f},{-0.291026f,0.0108798f,0.100469f},{-0.291319f,0.0113857f,0.100469f}, +{-0.291027f,0.010881f,0.0918925f},{-0.29132f,0.0113881f,0.0918925f},{-0.291499f,0.0119409f,0.100469f}, +{-0.2915f,0.0119424f,0.0918925f},{-0.291561f,0.0125242f,0.100469f},{-0.291561f,0.0125242f,0.0918925f}, +{-0.288473f,-0.0153056f,0.0918925f},{-0.289059f,-0.015305f,0.0918925f},{-0.289055f,-0.0153056f,0.100469f}, +{-0.28847f,-0.015305f,0.100469f},{-0.287901f,-0.0151842f,0.0918925f},{-0.287899f,-0.0151836f,0.100469f}, +{-0.287366f,-0.014946f,0.100469f},{-0.286895f,-0.0146037f,0.0918925f},{-0.287367f,-0.0149467f,0.0918925f}, +{-0.286892f,-0.0146009f,0.100469f},{-0.286502f,-0.0141686f,0.0918925f},{-0.286501f,-0.0141674f,0.100469f}, +{-0.28621f,-0.0136627f,0.0918925f},{-0.286209f,-0.0136603f,0.100469f},{-0.286029f,-0.0131075f,0.0918925f}, +{-0.286029f,-0.013106f,0.100469f},{-0.285968f,-0.0125242f,0.100469f},{-0.289628f,-0.0151842f,0.100469f}, +{-0.290161f,-0.0149467f,0.100469f},{-0.289629f,-0.0151836f,0.0918925f},{-0.290163f,-0.014946f,0.0918925f}, +{-0.290634f,-0.0146037f,0.100469f},{-0.290637f,-0.0146009f,0.0918925f},{-0.291026f,-0.0141686f,0.100469f}, +{-0.291319f,-0.0136627f,0.100469f},{-0.291027f,-0.0141674f,0.0918925f},{-0.29132f,-0.0136603f,0.0918925f}, +{-0.291499f,-0.0131075f,0.100469f},{-0.2915f,-0.013106f,0.0918925f},{-0.291561f,-0.0125242f,0.100469f}, +{0.0128153f,0.311031f,0.0918925f},{0.0122298f,0.311032f,0.0918925f},{0.0122331f,0.311031f,0.100469f}, +{0.0128186f,0.311032f,0.100469f},{0.0133877f,0.311153f,0.0918925f},{0.0133893f,0.311153f,0.100469f}, +{0.013923f,0.311391f,0.100469f},{0.0143937f,0.311733f,0.0918925f},{0.0139213f,0.31139f,0.0918925f}, +{0.0143968f,0.311736f,0.100469f},{0.0147862f,0.312168f,0.0918925f},{0.0147871f,0.312169f,0.100469f}, +{0.0150786f,0.312674f,0.0918925f},{0.0150796f,0.312677f,0.100469f},{0.0152591f,0.313229f,0.0918925f}, +{0.0152596f,0.313231f,0.100469f},{0.0153208f,0.313813f,0.100469f},{0.0116607f,0.311153f,0.100469f}, +{0.0111271f,0.31139f,0.100469f},{0.0116591f,0.311153f,0.0918925f},{0.0111254f,0.311391f,0.0918925f}, +{0.0106546f,0.311733f,0.100469f},{0.0106515f,0.311736f,0.0918925f},{0.0102622f,0.312168f,0.100469f}, +{0.00996978f,0.312674f,0.100469f},{0.0102613f,0.312169f,0.0918925f},{0.00996883f,0.312677f,0.0918925f}, +{0.00978928f,0.313229f,0.100469f},{0.0097888f,0.313231f,0.0918925f},{0.00972758f,0.313813f,0.100469f}, +{0.0128153f,0.285983f,0.0918925f},{0.0122298f,0.285984f,0.0918925f},{0.0122331f,0.285983f,0.100469f}, +{0.0128186f,0.285984f,0.100469f},{0.0133877f,0.286104f,0.0918925f},{0.0133893f,0.286105f,0.100469f}, +{0.013923f,0.286343f,0.100469f},{0.0143937f,0.286685f,0.0918925f},{0.0139213f,0.286342f,0.0918925f}, +{0.0143968f,0.286688f,0.100469f},{0.0147862f,0.28712f,0.0918925f},{0.0147871f,0.287121f,0.100469f}, +{0.0150786f,0.287626f,0.0918925f},{0.0150796f,0.287628f,0.100469f},{0.0152591f,0.288181f,0.0918925f}, +{0.0152596f,0.288183f,0.100469f},{0.0153208f,0.288764f,0.100469f},{0.0153208f,0.288764f,0.0918925f}, +{0.0116607f,0.286104f,0.100469f},{0.0111271f,0.286342f,0.100469f},{0.0116591f,0.286105f,0.0918925f}, +{0.0111254f,0.286343f,0.0918925f},{0.0106546f,0.286685f,0.100469f},{0.0106515f,0.286688f,0.0918925f}, +{0.0102622f,0.28712f,0.100469f},{0.00996978f,0.287626f,0.100469f},{0.0102613f,0.287121f,0.0918925f}, +{0.00996883f,0.287628f,0.0918925f},{0.00978928f,0.288181f,0.100469f},{0.0097888f,0.288183f,0.0918925f}, +{0.00972758f,0.288764f,0.100469f},{0.00972758f,0.288764f,0.0918925f},{-0.0122331f,0.311031f,0.0918925f}, +{-0.0128186f,0.311032f,0.0918925f},{-0.0128153f,0.311031f,0.100469f},{-0.0122298f,0.311032f,0.100469f}, +{-0.0116607f,0.311153f,0.0918925f},{-0.0116591f,0.311153f,0.100469f},{-0.0111254f,0.311391f,0.100469f}, +{-0.0106546f,0.311733f,0.0918925f},{-0.0111271f,0.31139f,0.0918925f},{-0.0106515f,0.311736f,0.100469f}, +{-0.0102622f,0.312168f,0.0918925f},{-0.0102613f,0.312169f,0.100469f},{-0.00996978f,0.312674f,0.0918925f}, +{-0.00996883f,0.312677f,0.100469f},{-0.00978928f,0.313229f,0.0918925f},{-0.0097888f,0.313231f,0.100469f}, +{-0.00972758f,0.313813f,0.100469f},{-0.00972758f,0.313813f,0.0918925f},{-0.0133877f,0.311153f,0.100469f}, +{-0.0139213f,0.31139f,0.100469f},{-0.0133893f,0.311153f,0.0918925f},{-0.013923f,0.311391f,0.0918925f}, +{-0.0143937f,0.311733f,0.100469f},{-0.0143968f,0.311736f,0.0918925f},{-0.0147862f,0.312168f,0.100469f}, +{-0.0150786f,0.312674f,0.100469f},{-0.0147871f,0.312169f,0.0918925f},{-0.0150796f,0.312677f,0.0918925f}, +{-0.0152591f,0.313229f,0.100469f},{-0.0152596f,0.313231f,0.0918925f},{-0.0153208f,0.313813f,0.100469f}, +{-0.0153208f,0.313813f,0.0918925f},{-0.0122331f,0.285983f,0.0918925f},{-0.0128186f,0.285984f,0.0918925f}, +{-0.0128153f,0.285983f,0.100469f},{-0.0122298f,0.285984f,0.100469f},{-0.0116607f,0.286104f,0.0918925f}, +{-0.0116591f,0.286105f,0.100469f},{-0.0111254f,0.286343f,0.100469f},{-0.0106546f,0.286685f,0.0918925f}, +{-0.0111271f,0.286342f,0.0918925f},{-0.0106515f,0.286688f,0.100469f},{-0.0102622f,0.28712f,0.0918925f}, +{-0.0102613f,0.287121f,0.100469f},{-0.00996978f,0.287626f,0.0918925f},{-0.00996883f,0.287628f,0.100469f}, +{-0.00978928f,0.288181f,0.0918925f},{-0.0097888f,0.288183f,0.100469f},{-0.00972758f,0.288764f,0.100469f}, +{-0.0133877f,0.286104f,0.100469f},{-0.0139213f,0.286342f,0.100469f},{-0.0133893f,0.286105f,0.0918925f}, +{-0.013923f,0.286343f,0.0918925f},{-0.0143937f,0.286685f,0.100469f},{-0.0143968f,0.286688f,0.0918925f}, +{-0.0147862f,0.28712f,0.100469f},{-0.0150786f,0.287626f,0.100469f},{-0.0147871f,0.287121f,0.0918925f}, +{-0.0150796f,0.287628f,0.0918925f},{-0.0152591f,0.288181f,0.100469f},{-0.0152596f,0.288183f,0.0918925f}, +{-0.0153208f,0.288764f,0.100469f},{0.314104f,0.00974281f,0.0918925f},{0.313518f,0.0097434f,0.0918925f}, +{0.313522f,0.00974281f,0.100469f},{0.314107f,0.0097434f,0.100469f},{0.314676f,0.00986419f,0.0918925f}, +{0.314678f,0.00986481f,0.100469f},{0.315212f,0.0101024f,0.100469f},{0.315682f,0.0104447f,0.0918925f}, +{0.31521f,0.0101017f,0.0918925f},{0.315685f,0.0104475f,0.100469f},{0.316075f,0.0108798f,0.0918925f}, +{0.316076f,0.010881f,0.100469f},{0.316367f,0.0113857f,0.0918925f},{0.316368f,0.0113881f,0.100469f}, +{0.316548f,0.0119409f,0.0918925f},{0.316548f,0.0119424f,0.100469f},{0.316609f,0.0125242f,0.100469f}, +{0.316609f,0.0125242f,0.0918925f},{0.312949f,0.00986419f,0.100469f},{0.312416f,0.0101017f,0.100469f}, +{0.312948f,0.00986481f,0.0918925f},{0.312414f,0.0101024f,0.0918925f},{0.311943f,0.0104447f,0.100469f}, +{0.31194f,0.0104475f,0.0918925f},{0.311551f,0.0108798f,0.100469f},{0.311258f,0.0113857f,0.100469f}, +{0.31155f,0.010881f,0.0918925f},{0.311257f,0.0113881f,0.0918925f},{0.311078f,0.0119409f,0.100469f}, +{0.311077f,0.0119424f,0.0918925f},{0.311016f,0.0125242f,0.100469f},{0.311016f,0.0125242f,0.0918925f}, +{0.289055f,0.00974281f,0.0918925f},{0.28847f,0.0097434f,0.0918925f},{0.288473f,0.00974281f,0.100469f}, +{0.289059f,0.0097434f,0.100469f},{0.289628f,0.00986419f,0.0918925f},{0.289629f,0.00986481f,0.100469f}, +{0.290163f,0.0101024f,0.100469f},{0.290634f,0.0104447f,0.0918925f},{0.290161f,0.0101017f,0.0918925f}, +{0.290637f,0.0104475f,0.100469f},{0.291026f,0.0108798f,0.0918925f},{0.291027f,0.010881f,0.100469f}, +{0.291319f,0.0113857f,0.0918925f},{0.29132f,0.0113881f,0.100469f},{0.291499f,0.0119409f,0.0918925f}, +{0.2915f,0.0119424f,0.100469f},{0.291561f,0.0125242f,0.100469f},{0.287901f,0.00986419f,0.100469f}, +{0.287367f,0.0101017f,0.100469f},{0.287899f,0.00986481f,0.0918925f},{0.287366f,0.0101024f,0.0918925f}, +{0.286895f,0.0104447f,0.100469f},{0.286892f,0.0104475f,0.0918925f},{0.286502f,0.0108798f,0.100469f}, +{0.28621f,0.0113857f,0.100469f},{0.286501f,0.010881f,0.0918925f},{0.286209f,0.0113881f,0.0918925f}, +{0.286029f,0.0119409f,0.100469f},{0.286029f,0.0119424f,0.0918925f},{0.285968f,0.0125242f,0.100469f}, +{0.289055f,-0.0153056f,0.0918925f},{0.28847f,-0.015305f,0.0918925f},{0.288473f,-0.0153056f,0.100469f}, +{0.289059f,-0.015305f,0.100469f},{0.289628f,-0.0151842f,0.0918925f},{0.289629f,-0.0151836f,0.100469f}, +{0.290163f,-0.014946f,0.100469f},{0.290634f,-0.0146037f,0.0918925f},{0.290161f,-0.0149467f,0.0918925f}, +{0.290637f,-0.0146009f,0.100469f},{0.291026f,-0.0141686f,0.0918925f},{0.291027f,-0.0141674f,0.100469f}, +{0.291319f,-0.0136627f,0.0918925f},{0.29132f,-0.0136603f,0.100469f},{0.291499f,-0.0131075f,0.0918925f}, +{0.2915f,-0.013106f,0.100469f},{0.291561f,-0.0125242f,0.100469f},{0.291561f,-0.0125242f,0.0918925f}, +{0.287901f,-0.0151842f,0.100469f},{0.287367f,-0.0149467f,0.100469f},{0.287899f,-0.0151836f,0.0918925f}, +{0.287366f,-0.014946f,0.0918925f},{0.286895f,-0.0146037f,0.100469f},{0.286892f,-0.0146009f,0.0918925f}, +{0.286502f,-0.0141686f,0.100469f},{0.28621f,-0.0136627f,0.100469f},{0.286501f,-0.0141674f,0.0918925f}, +{0.286209f,-0.0136603f,0.0918925f},{0.286029f,-0.0131075f,0.100469f},{0.286029f,-0.013106f,0.0918925f}, +{0.285968f,-0.0125242f,0.100469f},{0.285968f,-0.0125242f,0.0918925f},{0.314104f,-0.0153056f,0.0918925f}, +{0.313518f,-0.015305f,0.0918925f},{0.313522f,-0.0153056f,0.100469f},{0.314107f,-0.015305f,0.100469f}, +{0.314676f,-0.0151842f,0.0918925f},{0.314678f,-0.0151836f,0.100469f},{0.315212f,-0.014946f,0.100469f}, +{0.315682f,-0.0146037f,0.0918925f},{0.31521f,-0.0149467f,0.0918925f},{0.315685f,-0.0146009f,0.100469f}, +{0.316075f,-0.0141686f,0.0918925f},{0.316076f,-0.0141674f,0.100469f},{0.316367f,-0.0136627f,0.0918925f}, +{0.316368f,-0.0136603f,0.100469f},{0.316548f,-0.0131075f,0.0918925f},{0.316548f,-0.013106f,0.100469f}, +{0.316609f,-0.0125242f,0.100469f},{0.312949f,-0.0151842f,0.100469f},{0.312416f,-0.0149467f,0.100469f}, +{0.312948f,-0.0151836f,0.0918925f},{0.312414f,-0.014946f,0.0918925f},{0.311943f,-0.0146037f,0.100469f}, +{0.31194f,-0.0146009f,0.0918925f},{0.311551f,-0.0141686f,0.100469f},{0.311258f,-0.0136627f,0.100469f}, +{0.31155f,-0.0141674f,0.0918925f},{0.311257f,-0.0136603f,0.0918925f},{0.311078f,-0.0131075f,0.100469f}, +{0.311077f,-0.013106f,0.0918925f},{0.311016f,-0.0125242f,0.100469f},{-0.0122331f,-0.316594f,0.0918925f}, +{-0.0128186f,-0.316594f,0.0918925f},{-0.0128153f,-0.316594f,0.100469f},{-0.0122298f,-0.316594f,0.100469f}, +{-0.0116607f,-0.316473f,0.0918925f},{-0.0116591f,-0.316472f,0.100469f},{-0.0111254f,-0.316235f,0.100469f}, +{-0.0106546f,-0.315892f,0.0918925f},{-0.0111271f,-0.316235f,0.0918925f},{-0.0106515f,-0.315889f,0.100469f}, +{-0.0102622f,-0.315457f,0.0918925f},{-0.0102613f,-0.315456f,0.100469f},{-0.00996978f,-0.314951f,0.0918925f}, +{-0.00996883f,-0.314949f,0.100469f},{-0.00978928f,-0.314396f,0.0918925f},{-0.0097888f,-0.314395f,0.100469f}, +{-0.00972758f,-0.313813f,0.100469f},{-0.0133877f,-0.316473f,0.100469f},{-0.0139213f,-0.316235f,0.100469f}, +{-0.0133893f,-0.316472f,0.0918925f},{-0.013923f,-0.316235f,0.0918925f},{-0.0143937f,-0.315892f,0.100469f}, +{-0.0143968f,-0.315889f,0.0918925f},{-0.0147862f,-0.315457f,0.100469f},{-0.0150786f,-0.314951f,0.100469f}, +{-0.0147871f,-0.315456f,0.0918925f},{-0.0150796f,-0.314949f,0.0918925f},{-0.0152591f,-0.314396f,0.100469f}, +{-0.0152596f,-0.314395f,0.0918925f},{-0.0153208f,-0.313813f,0.100469f},{-0.0122331f,-0.291546f,0.0918925f}, +{-0.0128186f,-0.291545f,0.0918925f},{-0.0128153f,-0.291546f,0.100469f},{-0.0122298f,-0.291545f,0.100469f}, +{-0.0116607f,-0.291424f,0.0918925f},{-0.0116591f,-0.291424f,0.100469f},{-0.0111254f,-0.291186f,0.100469f}, +{-0.0106546f,-0.290844f,0.0918925f},{-0.0111271f,-0.291187f,0.0918925f},{-0.0106515f,-0.290841f,0.100469f}, +{-0.0102622f,-0.290409f,0.0918925f},{-0.0102613f,-0.290408f,0.100469f},{-0.00996978f,-0.289903f,0.0918925f}, +{-0.00996883f,-0.2899f,0.100469f},{-0.00978928f,-0.289348f,0.0918925f},{-0.0097888f,-0.289346f,0.100469f}, +{-0.00972758f,-0.288764f,0.100469f},{-0.00972758f,-0.288764f,0.0918925f},{-0.0133877f,-0.291424f,0.100469f}, +{-0.0139213f,-0.291187f,0.100469f},{-0.0133893f,-0.291424f,0.0918925f},{-0.013923f,-0.291186f,0.0918925f}, +{-0.0143937f,-0.290844f,0.100469f},{-0.0143968f,-0.290841f,0.0918925f},{-0.0147862f,-0.290409f,0.100469f}, +{-0.0150786f,-0.289903f,0.100469f},{-0.0147871f,-0.290408f,0.0918925f},{-0.0150796f,-0.2899f,0.0918925f}, +{-0.0152591f,-0.289348f,0.100469f},{-0.0152596f,-0.289346f,0.0918925f},{-0.0153208f,-0.288764f,0.100469f}, +{-0.0153208f,-0.288764f,0.0918925f},{0.0128153f,-0.291546f,0.0918925f},{0.0122298f,-0.291545f,0.0918925f}, +{0.0122331f,-0.291546f,0.100469f},{0.0128186f,-0.291545f,0.100469f},{0.0133877f,-0.291424f,0.0918925f}, +{0.0133893f,-0.291424f,0.100469f},{0.013923f,-0.291186f,0.100469f},{0.0143937f,-0.290844f,0.0918925f}, +{0.0139213f,-0.291187f,0.0918925f},{0.0143968f,-0.290841f,0.100469f},{0.0147862f,-0.290409f,0.0918925f}, +{0.0147871f,-0.290408f,0.100469f},{0.0150786f,-0.289903f,0.0918925f},{0.0150796f,-0.2899f,0.100469f}, +{0.0152591f,-0.289348f,0.0918925f},{0.0152596f,-0.289346f,0.100469f},{0.0153208f,-0.288764f,0.100469f}, +{0.0116607f,-0.291424f,0.100469f},{0.0111271f,-0.291187f,0.100469f},{0.0116591f,-0.291424f,0.0918925f}, +{0.0111254f,-0.291186f,0.0918925f},{0.0106546f,-0.290844f,0.100469f},{0.0106515f,-0.290841f,0.0918925f}, +{0.0102622f,-0.290409f,0.100469f},{0.00996978f,-0.289903f,0.100469f},{0.0102613f,-0.290408f,0.0918925f}, +{0.00996883f,-0.2899f,0.0918925f},{0.00978928f,-0.289348f,0.100469f},{0.0097888f,-0.289346f,0.0918925f}, +{0.00972758f,-0.288764f,0.100469f},{0.0128153f,-0.316594f,0.0918925f},{0.0122298f,-0.316594f,0.0918925f}, +{0.0122331f,-0.316594f,0.100469f},{0.0128186f,-0.316594f,0.100469f},{0.0133877f,-0.316473f,0.0918925f}, +{0.0133893f,-0.316472f,0.100469f},{0.013923f,-0.316235f,0.100469f},{0.0143937f,-0.315892f,0.0918925f}, +{0.0139213f,-0.316235f,0.0918925f},{0.0143968f,-0.315889f,0.100469f},{0.0147862f,-0.315457f,0.0918925f}, +{0.0147871f,-0.315456f,0.100469f},{0.0150786f,-0.314951f,0.0918925f},{0.0150796f,-0.314949f,0.100469f}, +{0.0152591f,-0.314396f,0.0918925f},{0.0152596f,-0.314395f,0.100469f},{0.0153208f,-0.313813f,0.100469f}, +{0.0153208f,-0.313813f,0.0918925f},{0.0116607f,-0.316473f,0.100469f},{0.0111271f,-0.316235f,0.100469f}, +{0.0116591f,-0.316472f,0.0918925f},{0.0111254f,-0.316235f,0.0918925f},{0.0106546f,-0.315892f,0.100469f}, +{0.0106515f,-0.315889f,0.0918925f},{0.0102622f,-0.315457f,0.100469f},{0.00996978f,-0.314951f,0.100469f}, +{0.0102613f,-0.315456f,0.0918925f},{0.00996883f,-0.314949f,0.0918925f},{0.00978928f,-0.314396f,0.100469f}, +{0.0097888f,-0.314395f,0.0918925f},{0.00972758f,-0.313813f,0.100469f},{0.00972758f,-0.313813f,0.0918925f}, +{-0.254583f,-0.00139831f,0.0918925f},{-0.255011f,-0.00133018f,0.100469f},{-0.254583f,-0.00139831f,0.100469f}, +{-0.253766f,-0.0011336f,0.0918925f},{-0.254148f,-0.00132889f,0.100469f},{-0.253758f,-0.00112806f,0.100469f}, +{-0.254155f,-0.00133018f,0.0918925f},{-0.253455f,-0.000825358f,0.0918925f},{-0.253254f,-0.000434603f,0.100469f}, +{-0.253185f,2.35333e-017f,0.0918925f},{-0.253254f,-0.000434603f,0.0918925f},{-0.253449f,-0.00081707f,0.100469f}, +{-0.253185f,2.35333e-017f,0.100469f},{-0.255018f,-0.00132889f,0.0918925f},{-0.2554f,-0.0011336f,0.100469f}, +{-0.255408f,-0.00112806f,0.0918925f},{-0.255717f,-0.00081707f,0.0918925f},{-0.255711f,-0.000825358f,0.100469f}, +{-0.255912f,-0.000434603f,0.0918925f},{-0.255912f,-0.000434603f,0.100469f},{-0.255981f,2.33621e-017f,0.100469f}, +{-0.255981f,2.33621e-017f,0.0918925f},{0.217061f,-0.00139831f,0.0918925f},{0.216633f,-0.00133018f,0.100469f}, +{0.217061f,-0.00139831f,0.100469f},{0.217878f,-0.0011336f,0.0918925f},{0.217496f,-0.00132889f,0.100469f}, +{0.217886f,-0.00112806f,0.100469f},{0.217489f,-0.00133018f,0.0918925f},{0.218189f,-0.000825358f,0.0918925f}, +{0.21839f,-0.000434603f,0.100469f},{0.218459f,1.5386e-017f,0.0918925f},{0.21839f,-0.000434603f,0.0918925f}, +{0.218195f,-0.00081707f,0.100469f},{0.218459f,1.5386e-017f,0.100469f},{0.216626f,-0.00132889f,0.0918925f}, +{0.216244f,-0.0011336f,0.100469f},{0.216236f,-0.00112806f,0.0918925f},{0.215927f,-0.00081707f,0.0918925f}, +{0.215933f,-0.000825358f,0.100469f},{0.215732f,-0.000434603f,0.0918925f},{0.215732f,-0.000434603f,0.100469f}, +{0.215663f,1.52148e-017f,0.100469f},{0.215663f,1.52148e-017f,0.0918925f},{2.89787e-017f,0.254546f,0.0918925f}, +{-0.000428086f,0.254614f,0.100469f},{2.89787e-017f,0.254546f,0.100469f},{0.00081707f,0.254811f,0.0918925f}, +{0.000434603f,0.254616f,0.100469f},{0.000825358f,0.254817f,0.100469f},{0.000428086f,0.254614f,0.0918925f}, +{0.00112806f,0.255119f,0.0918925f},{0.00132889f,0.25551f,0.100469f},{0.00139831f,0.255945f,0.0918925f}, +{0.00132889f,0.25551f,0.0918925f},{0.0011336f,0.255128f,0.100469f},{0.00139831f,0.255945f,0.100469f}, +{-0.000434603f,0.254616f,0.0918925f},{-0.00081707f,0.254811f,0.100469f},{-0.000825358f,0.254817f,0.0918925f}, +{-0.0011336f,0.255128f,0.0918925f},{-0.00112806f,0.255119f,0.100469f},{-0.00132889f,0.25551f,0.0918925f}, +{-0.00132889f,0.25551f,0.100469f},{-0.00139831f,0.255945f,0.100469f},{-0.00139831f,0.255945f,0.0918925f}, +{2.89787e-017f,0.217258f,0.0918925f},{-0.000428086f,0.217326f,0.100469f},{2.89787e-017f,0.217258f,0.100469f}, +{0.00081707f,0.217523f,0.0918925f},{0.000434603f,0.217328f,0.100469f},{0.000825358f,0.217528f,0.100469f}, +{0.000428086f,0.217326f,0.0918925f},{0.00112806f,0.217831f,0.0918925f},{0.00132889f,0.218222f,0.100469f}, +{0.00139831f,0.218656f,0.0918925f},{0.00132889f,0.218222f,0.0918925f},{0.0011336f,0.217839f,0.100469f}, +{0.00139831f,0.218656f,0.100469f},{-0.000434603f,0.217328f,0.0918925f},{-0.00081707f,0.217523f,0.100469f}, +{-0.000825358f,0.217528f,0.0918925f},{-0.0011336f,0.217839f,0.0918925f},{-0.00112806f,0.217831f,0.100469f}, +{-0.00132889f,0.218222f,0.0918925f},{-0.00132889f,0.218222f,0.100469f},{-0.00139831f,0.218656f,0.100469f}, +{-0.00139831f,0.218656f,0.0918925f},{0.254583f,-0.00139831f,0.0918925f},{0.254155f,-0.00133018f,0.100469f}, +{0.254583f,-0.00139831f,0.100469f},{0.2554f,-0.0011336f,0.0918925f},{0.255018f,-0.00132889f,0.100469f}, +{0.255408f,-0.00112806f,0.100469f},{0.255011f,-0.00133018f,0.0918925f},{0.255711f,-0.000825358f,0.0918925f}, +{0.255912f,-0.000434603f,0.100469f},{0.255981f,2.35333e-017f,0.0918925f},{0.255912f,-0.000434603f,0.0918925f}, +{0.255717f,-0.00081707f,0.100469f},{0.255981f,2.35333e-017f,0.100469f},{0.254148f,-0.00132889f,0.0918925f}, +{0.253766f,-0.0011336f,0.100469f},{0.253758f,-0.00112806f,0.0918925f},{0.253449f,-0.00081707f,0.0918925f}, +{0.253455f,-0.000825358f,0.100469f},{0.253254f,-0.000434603f,0.0918925f},{0.253254f,-0.000434603f,0.100469f}, +{0.253185f,2.33621e-017f,0.100469f},{0.253185f,2.33621e-017f,0.0918925f},{5.54736e-017f,-0.257343f,0.0918925f}, +{-0.000428086f,-0.257275f,0.100469f},{2.89787e-017f,-0.257343f,0.100469f},{0.00081707f,-0.257078f,0.0918925f}, +{0.000434603f,-0.257274f,0.100469f},{0.000825358f,-0.257073f,0.100469f},{0.000428086f,-0.257275f,0.0918925f}, +{0.00112806f,-0.25677f,0.0918925f},{0.00132889f,-0.256379f,0.100469f},{0.00139831f,-0.255945f,0.0918925f}, +{0.00132889f,-0.256379f,0.0918925f},{0.0011336f,-0.256762f,0.100469f},{0.00139831f,-0.255945f,0.100469f}, +{-0.000434603f,-0.257274f,0.0918925f},{-0.00081707f,-0.257078f,0.100469f},{-0.000825358f,-0.257073f,0.0918925f}, +{-0.0011336f,-0.256762f,0.0918925f},{-0.00112806f,-0.25677f,0.100469f},{-0.00132889f,-0.256379f,0.0918925f}, +{-0.00132889f,-0.256379f,0.100469f},{-0.00139831f,-0.255945f,0.100469f},{-0.00139831f,-0.255945f,0.0918925f}, +{5.54736e-017f,-0.220055f,0.0918925f},{-0.000428086f,-0.219987f,0.100469f},{2.89787e-017f,-0.220055f,0.100469f}, +{0.00081707f,-0.21979f,0.0918925f},{0.000434603f,-0.219985f,0.100469f},{0.000825358f,-0.219785f,0.100469f}, +{0.000428086f,-0.219987f,0.0918925f},{0.00112806f,-0.219482f,0.0918925f},{0.00132889f,-0.219091f,0.100469f}, +{0.00139831f,-0.218656f,0.0918925f},{0.00132889f,-0.219091f,0.0918925f},{0.0011336f,-0.219474f,0.100469f}, +{0.00139831f,-0.218656f,0.100469f},{-0.000434603f,-0.219985f,0.0918925f},{-0.00081707f,-0.21979f,0.100469f}, +{-0.000825358f,-0.219785f,0.0918925f},{-0.0011336f,-0.219474f,0.0918925f},{-0.00112806f,-0.219482f,0.100469f}, +{-0.00132889f,-0.219091f,0.0918925f},{-0.00132889f,-0.219091f,0.100469f},{-0.00139831f,-0.218656f,0.100469f}, +{-0.00139831f,-0.218656f,0.0918925f},{-0.217061f,-0.00139831f,0.0918925f},{-0.217489f,-0.00133018f,0.100469f}, +{-0.217061f,-0.00139831f,0.100469f},{-0.216244f,-0.0011336f,0.0918925f},{-0.216626f,-0.00132889f,0.100469f}, +{-0.216236f,-0.00112806f,0.100469f},{-0.216633f,-0.00133018f,0.0918925f},{-0.215933f,-0.000825358f,0.0918925f}, +{-0.215732f,-0.000434603f,0.100469f},{-0.215663f,1.5386e-017f,0.0918925f},{-0.215732f,-0.000434603f,0.0918925f}, +{-0.215927f,-0.00081707f,0.100469f},{-0.215663f,1.5386e-017f,0.100469f},{-0.217496f,-0.00132889f,0.0918925f}, +{-0.217878f,-0.0011336f,0.100469f},{-0.217886f,-0.00112806f,0.0918925f},{-0.218195f,-0.00081707f,0.0918925f}, +{-0.218189f,-0.000825358f,0.100469f},{-0.21839f,-0.000434603f,0.0918925f},{-0.21839f,-0.000434603f,0.100469f}, +{-0.218459f,1.52148e-017f,0.100469f},{-0.218459f,1.52148e-017f,0.0918925f},{-0.0206412f,-0.0600622f,0.0918925f}, +{-0.0218566f,-0.0614015f,0.0918925f},{-0.0218559f,-0.0614007f,0.100469f},{-0.0446572f,-0.069784f,0.100469f}, +{-0.0428559f,-0.0699006f,0.0918925f},{-0.0446573f,-0.069784f,0.0918925f},{-0.0410436f,-0.0699007f,0.0918925f}, +{-0.0428548f,-0.0699007f,0.100469f},{-0.0464389f,-0.0695527f,0.100469f},{-0.0464391f,-0.0695526f,0.0918925f}, +{-0.0481956f,-0.0692089f,0.100469f},{-0.0481959f,-0.0692088f,0.0918925f},{-0.0499225f,-0.0687547f,0.100469f}, +{-0.0499226f,-0.0687546f,0.0918925f},{-0.0516141f,-0.0681921f,0.100469f},{-0.0564273f,-0.065876f,0.100469f}, +{-0.0548716f,-0.0667507f,0.100469f},{-0.0548718f,-0.0667507f,0.0918925f},{-0.0516143f,-0.0681921f,0.0918925f}, +{-0.0532658f,-0.0675234f,0.0918925f},{-0.0532655f,-0.0675235f,0.100469f},{-0.0579272f,-0.0649016f,0.100469f}, +{-0.0564274f,-0.065876f,0.0918925f},{-0.0579275f,-0.0649015f,0.0918925f},{-0.0593666f,-0.0638294f,0.100469f}, +{-0.0607404f,-0.0626615f,0.0918925f},{-0.0607403f,-0.0626615f,0.100469f},{-0.0593668f,-0.0638293f,0.0918925f}, +{-0.0620418f,-0.0614015f,0.100469f},{-0.0620425f,-0.0614007f,0.0918925f},{-0.0632572f,-0.0600622f,0.100469f}, +{-0.0632573f,-0.0600619f,0.0918925f},{-0.0643775f,-0.0586549f,0.0918925f},{-0.0643775f,-0.058655f,0.100469f}, +{-0.0693947f,-0.0473208f,0.100469f},{-0.0689955f,-0.0490631f,0.0918925f},{-0.0693947f,-0.0473207f,0.0918925f}, +{-0.066326f,-0.055656f,0.0918925f},{-0.0671499f,-0.0540747f,0.100469f},{-0.0663259f,-0.0556563f,0.100469f}, +{-0.0654011f,-0.0571847f,0.100469f},{-0.0654012f,-0.0571845f,0.0918925f},{-0.06715f,-0.0540746f,0.0918925f}, +{-0.0678709f,-0.0524453f,0.100469f},{-0.067871f,-0.0524451f,0.0918925f},{-0.0684867f,-0.0507732f,0.100469f}, +{-0.0684868f,-0.0507729f,0.0918925f},{-0.0689954f,-0.0490633f,0.100469f},{-0.0696826f,-0.0455508f,0.0918925f}, +{-0.0698568f,-0.0437586f,0.0918925f},{-0.0698567f,-0.0437588f,0.100469f},{-0.0696825f,-0.045551f,0.100469f}, +{-0.0699153f,-0.0419492f,0.100469f},{-0.0699153f,-0.0419492f,0.0918925f},{-0.0410425f,-0.0699006f,0.100469f}, +{-0.0392411f,-0.069784f,0.100469f},{-0.0392412f,-0.069784f,0.0918925f},{-0.0374596f,-0.0695527f,0.0918925f}, +{-0.0374593f,-0.0695526f,0.100469f},{-0.0357025f,-0.0692088f,0.100469f},{-0.0357028f,-0.0692089f,0.0918925f}, +{-0.0339758f,-0.0687546f,0.100469f},{-0.033976f,-0.0687547f,0.0918925f},{-0.0322843f,-0.0681921f,0.0918925f}, +{-0.0322841f,-0.0681921f,0.100469f},{-0.0306327f,-0.0675234f,0.100469f},{-0.030633f,-0.0675235f,0.0918925f}, +{-0.0290267f,-0.0667507f,0.100469f},{-0.0290268f,-0.0667507f,0.0918925f},{-0.0274712f,-0.065876f,0.0918925f}, +{-0.027471f,-0.065876f,0.100469f},{-0.0259709f,-0.0649015f,0.100469f},{-0.0259712f,-0.0649016f,0.0918925f}, +{-0.0245316f,-0.0638293f,0.100469f},{-0.0245318f,-0.0638294f,0.0918925f},{-0.0231581f,-0.0626615f,0.0918925f}, +{-0.023158f,-0.0626615f,0.100469f},{-0.0206411f,-0.0600619f,0.100469f},{-0.0195209f,-0.0586549f,0.100469f}, +{-0.0195209f,-0.058655f,0.0918925f},{-0.0184973f,-0.0571847f,0.0918925f},{-0.0184973f,-0.0571845f,0.100469f}, +{-0.0175724f,-0.055656f,0.100469f},{-0.0175725f,-0.0556563f,0.0918925f},{-0.0167485f,-0.0540746f,0.100469f}, +{-0.0167485f,-0.0540747f,0.0918925f},{-0.0160275f,-0.0524453f,0.0918925f},{-0.0160275f,-0.0524451f,0.100469f}, +{-0.0154116f,-0.0507729f,0.100469f},{-0.0154117f,-0.0507732f,0.0918925f},{-0.014903f,-0.0490631f,0.100469f}, +{-0.014903f,-0.0490633f,0.0918925f},{-0.0145037f,-0.0473208f,0.0918925f},{-0.0145037f,-0.0473207f,0.100469f}, +{-0.0142158f,-0.0455508f,0.100469f},{-0.0142159f,-0.045551f,0.0918925f},{-0.0140416f,-0.0437586f,0.100469f}, +{-0.0140417f,-0.0437588f,0.0918925f},{-0.0139831f,-0.0419492f,0.0918925f},{-0.0139831f,-0.0419492f,0.100469f}, +{-0.0206412f,0.0238362f,0.0918925f},{-0.0218566f,0.0224969f,0.0918925f},{-0.0218559f,0.0224977f,0.100469f}, +{-0.0446572f,0.0141144f,0.100469f},{-0.0428559f,0.0139978f,0.0918925f},{-0.0446573f,0.0141144f,0.0918925f}, +{-0.0410436f,0.0139977f,0.0918925f},{-0.0428548f,0.0139977f,0.100469f},{-0.0464389f,0.0143457f,0.100469f}, +{-0.0464391f,0.0143458f,0.0918925f},{-0.0481956f,0.0146895f,0.100469f},{-0.0481959f,0.0146896f,0.0918925f}, +{-0.0499225f,0.0151437f,0.100469f},{-0.0499226f,0.0151438f,0.0918925f},{-0.0516141f,0.0157063f,0.100469f}, +{-0.0564273f,0.0180224f,0.100469f},{-0.0548716f,0.0171477f,0.100469f},{-0.0548718f,0.0171478f,0.0918925f}, +{-0.0516143f,0.0157063f,0.0918925f},{-0.0532658f,0.016375f,0.0918925f},{-0.0532655f,0.0163749f,0.100469f}, +{-0.0579272f,0.0189968f,0.100469f},{-0.0564274f,0.0180224f,0.0918925f},{-0.0579275f,0.018997f,0.0918925f}, +{-0.0593666f,0.020069f,0.100469f},{-0.0607404f,0.0212369f,0.0918925f},{-0.0607403f,0.0212369f,0.100469f}, +{-0.0593668f,0.0200691f,0.0918925f},{-0.0620418f,0.0224969f,0.100469f},{-0.0620425f,0.0224977f,0.0918925f}, +{-0.0632572f,0.0238362f,0.100469f},{-0.0632573f,0.0238365f,0.0918925f},{-0.0643775f,0.0252435f,0.0918925f}, +{-0.0643775f,0.0252434f,0.100469f},{-0.0693947f,0.0365776f,0.100469f},{-0.0689955f,0.0348353f,0.0918925f}, +{-0.0693947f,0.0365777f,0.0918925f},{-0.066326f,0.0282424f,0.0918925f},{-0.0671499f,0.0298237f,0.100469f}, +{-0.0663259f,0.0282422f,0.100469f},{-0.0654011f,0.0267137f,0.100469f},{-0.0654012f,0.0267139f,0.0918925f}, +{-0.06715f,0.0298238f,0.0918925f},{-0.0678709f,0.0314531f,0.100469f},{-0.067871f,0.0314533f,0.0918925f}, +{-0.0684867f,0.0331252f,0.100469f},{-0.0684868f,0.0331255f,0.0918925f},{-0.0689954f,0.0348351f,0.100469f}, +{-0.0696826f,0.0383477f,0.0918925f},{-0.0698568f,0.0401399f,0.0918925f},{-0.0698567f,0.0401396f,0.100469f}, +{-0.0696825f,0.0383474f,0.100469f},{-0.0699153f,0.0419492f,0.100469f},{-0.0699153f,0.0419492f,0.0918925f}, +{-0.0410425f,0.0139978f,0.100469f},{-0.0392411f,0.0141144f,0.100469f},{-0.0392412f,0.0141144f,0.0918925f}, +{-0.0374596f,0.0143457f,0.0918925f},{-0.0374593f,0.0143458f,0.100469f},{-0.0357025f,0.0146896f,0.100469f}, +{-0.0357028f,0.0146895f,0.0918925f},{-0.0339758f,0.0151438f,0.100469f},{-0.033976f,0.0151437f,0.0918925f}, +{-0.0322843f,0.0157063f,0.0918925f},{-0.0322841f,0.0157063f,0.100469f},{-0.0306327f,0.016375f,0.100469f}, +{-0.030633f,0.0163749f,0.0918925f},{-0.0290267f,0.0171478f,0.100469f},{-0.0290268f,0.0171477f,0.0918925f}, +{-0.0274712f,0.0180224f,0.0918925f},{-0.027471f,0.0180224f,0.100469f},{-0.0259709f,0.018997f,0.100469f}, +{-0.0259712f,0.0189968f,0.0918925f},{-0.0245316f,0.0200691f,0.100469f},{-0.0245318f,0.020069f,0.0918925f}, +{-0.0231581f,0.0212369f,0.0918925f},{-0.023158f,0.0212369f,0.100469f},{-0.0206411f,0.0238365f,0.100469f}, +{-0.0195209f,0.0252435f,0.100469f},{-0.0195209f,0.0252434f,0.0918925f},{-0.0184973f,0.0267137f,0.0918925f}, +{-0.0184973f,0.0267139f,0.100469f},{-0.0175724f,0.0282424f,0.100469f},{-0.0175725f,0.0282422f,0.0918925f}, +{-0.0167485f,0.0298238f,0.100469f},{-0.0167485f,0.0298237f,0.0918925f},{-0.0160275f,0.0314531f,0.0918925f}, +{-0.0160275f,0.0314533f,0.100469f},{-0.0154116f,0.0331255f,0.100469f},{-0.0154117f,0.0331252f,0.0918925f}, +{-0.014903f,0.0348353f,0.100469f},{-0.014903f,0.0348351f,0.0918925f},{-0.0145037f,0.0365776f,0.0918925f}, +{-0.0145037f,0.0365777f,0.100469f},{-0.0142158f,0.0383477f,0.100469f},{-0.0142159f,0.0383474f,0.0918925f}, +{-0.0140416f,0.0401399f,0.100469f},{-0.0140417f,0.0401396f,0.0918925f},{-0.0139831f,0.0419492f,0.0918925f}, +{-0.0139831f,0.0419492f,0.100469f},{0.0632572f,-0.0600622f,0.0918925f},{0.0620418f,-0.0614015f,0.0918925f}, +{0.0620425f,-0.0614007f,0.100469f},{0.0392412f,-0.069784f,0.100469f},{0.0410425f,-0.0699006f,0.0918925f}, +{0.0392411f,-0.069784f,0.0918925f},{0.0428548f,-0.0699007f,0.0918925f},{0.0410436f,-0.0699007f,0.100469f}, +{0.0374596f,-0.0695527f,0.100469f},{0.0374593f,-0.0695526f,0.0918925f},{0.0357028f,-0.0692089f,0.100469f}, +{0.0357025f,-0.0692088f,0.0918925f},{0.033976f,-0.0687547f,0.100469f},{0.0339758f,-0.0687546f,0.0918925f}, +{0.0322843f,-0.0681921f,0.100469f},{0.0274712f,-0.065876f,0.100469f},{0.0290268f,-0.0667507f,0.100469f}, +{0.0290267f,-0.0667507f,0.0918925f},{0.0322841f,-0.0681921f,0.0918925f},{0.0306327f,-0.0675234f,0.0918925f}, +{0.030633f,-0.0675235f,0.100469f},{0.0259712f,-0.0649016f,0.100469f},{0.027471f,-0.065876f,0.0918925f}, +{0.0259709f,-0.0649015f,0.0918925f},{0.0245318f,-0.0638294f,0.100469f},{0.023158f,-0.0626615f,0.0918925f}, +{0.0231581f,-0.0626615f,0.100469f},{0.0245316f,-0.0638293f,0.0918925f},{0.0218566f,-0.0614015f,0.100469f}, +{0.0218559f,-0.0614007f,0.0918925f},{0.0206412f,-0.0600622f,0.100469f},{0.0206411f,-0.0600619f,0.0918925f}, +{0.0195209f,-0.0586549f,0.0918925f},{0.0195209f,-0.058655f,0.100469f},{0.0145037f,-0.0473208f,0.100469f}, +{0.014903f,-0.0490631f,0.0918925f},{0.0145037f,-0.0473207f,0.0918925f},{0.0175724f,-0.055656f,0.0918925f}, +{0.0167485f,-0.0540747f,0.100469f},{0.0175725f,-0.0556563f,0.100469f},{0.0184973f,-0.0571847f,0.100469f}, +{0.0184973f,-0.0571845f,0.0918925f},{0.0167485f,-0.0540746f,0.0918925f},{0.0160275f,-0.0524453f,0.100469f}, +{0.0160275f,-0.0524451f,0.0918925f},{0.0154117f,-0.0507732f,0.100469f},{0.0154116f,-0.0507729f,0.0918925f}, +{0.014903f,-0.0490633f,0.100469f},{0.0142158f,-0.0455508f,0.0918925f},{0.0140416f,-0.0437586f,0.0918925f}, +{0.0140417f,-0.0437588f,0.100469f},{0.0142159f,-0.045551f,0.100469f},{0.0139831f,-0.0419492f,0.100469f}, +{0.0139831f,-0.0419492f,0.0918925f},{0.0428559f,-0.0699006f,0.100469f},{0.0446573f,-0.069784f,0.100469f}, +{0.0446572f,-0.069784f,0.0918925f},{0.0464389f,-0.0695527f,0.0918925f},{0.0464391f,-0.0695526f,0.100469f}, +{0.0481959f,-0.0692088f,0.100469f},{0.0481956f,-0.0692089f,0.0918925f},{0.0499226f,-0.0687546f,0.100469f}, +{0.0499225f,-0.0687547f,0.0918925f},{0.0516141f,-0.0681921f,0.0918925f},{0.0516143f,-0.0681921f,0.100469f}, +{0.0532658f,-0.0675234f,0.100469f},{0.0532655f,-0.0675235f,0.0918925f},{0.0548718f,-0.0667507f,0.100469f}, +{0.0548716f,-0.0667507f,0.0918925f},{0.0564273f,-0.065876f,0.0918925f},{0.0564274f,-0.065876f,0.100469f}, +{0.0579275f,-0.0649015f,0.100469f},{0.0579272f,-0.0649016f,0.0918925f},{0.0593668f,-0.0638293f,0.100469f}, +{0.0593666f,-0.0638294f,0.0918925f},{0.0607403f,-0.0626615f,0.0918925f},{0.0607404f,-0.0626615f,0.100469f}, +{0.0632573f,-0.0600619f,0.100469f},{0.0643775f,-0.0586549f,0.100469f},{0.0643775f,-0.058655f,0.0918925f}, +{0.0654011f,-0.0571847f,0.0918925f},{0.0654012f,-0.0571845f,0.100469f},{0.066326f,-0.055656f,0.100469f}, +{0.0663259f,-0.0556563f,0.0918925f},{0.06715f,-0.0540746f,0.100469f},{0.0671499f,-0.0540747f,0.0918925f}, +{0.0678709f,-0.0524453f,0.0918925f},{0.067871f,-0.0524451f,0.100469f},{0.0684868f,-0.0507729f,0.100469f}, +{0.0684867f,-0.0507732f,0.0918925f},{0.0689955f,-0.0490631f,0.100469f},{0.0689954f,-0.0490633f,0.0918925f}, +{0.0693947f,-0.0473208f,0.0918925f},{0.0693947f,-0.0473207f,0.100469f},{0.0696826f,-0.0455508f,0.100469f}, +{0.0696825f,-0.045551f,0.0918925f},{0.0698568f,-0.0437586f,0.100469f},{0.0698567f,-0.0437588f,0.0918925f}, +{0.0699153f,-0.0419492f,0.0918925f},{0.0699153f,-0.0419492f,0.100469f},{0.0632572f,0.0238362f,0.0918925f}, +{0.0620418f,0.0224969f,0.0918925f},{0.0620425f,0.0224977f,0.100469f},{0.0392412f,0.0141144f,0.100469f}, +{0.0410425f,0.0139978f,0.0918925f},{0.0392411f,0.0141144f,0.0918925f},{0.0428548f,0.0139977f,0.0918925f}, +{0.0410436f,0.0139977f,0.100469f},{0.0374596f,0.0143457f,0.100469f},{0.0374593f,0.0143458f,0.0918925f}, +{0.0357028f,0.0146895f,0.100469f},{0.0357025f,0.0146896f,0.0918925f},{0.033976f,0.0151437f,0.100469f}, +{0.0339758f,0.0151438f,0.0918925f},{0.0322843f,0.0157063f,0.100469f},{0.0274712f,0.0180224f,0.100469f}, +{0.0290268f,0.0171477f,0.100469f},{0.0290267f,0.0171478f,0.0918925f},{0.0322841f,0.0157063f,0.0918925f}, +{0.0306327f,0.016375f,0.0918925f},{0.030633f,0.0163749f,0.100469f},{0.0259712f,0.0189968f,0.100469f}, +{0.027471f,0.0180224f,0.0918925f},{0.0259709f,0.018997f,0.0918925f},{0.0245318f,0.020069f,0.100469f}, +{0.023158f,0.0212369f,0.0918925f},{0.0231581f,0.0212369f,0.100469f},{0.0245316f,0.0200691f,0.0918925f}, +{0.0218566f,0.0224969f,0.100469f},{0.0218559f,0.0224977f,0.0918925f},{0.0206412f,0.0238362f,0.100469f}, +{0.0206411f,0.0238365f,0.0918925f},{0.0195209f,0.0252435f,0.0918925f},{0.0195209f,0.0252434f,0.100469f}, +{0.0145037f,0.0365776f,0.100469f},{0.014903f,0.0348353f,0.0918925f},{0.0145037f,0.0365777f,0.0918925f}, +{0.0175724f,0.0282424f,0.0918925f},{0.0167485f,0.0298237f,0.100469f},{0.0175725f,0.0282422f,0.100469f}, +{0.0184973f,0.0267137f,0.100469f},{0.0184973f,0.0267139f,0.0918925f},{0.0167485f,0.0298238f,0.0918925f}, +{0.0160275f,0.0314531f,0.100469f},{0.0160275f,0.0314533f,0.0918925f},{0.0154117f,0.0331252f,0.100469f}, +{0.0154116f,0.0331255f,0.0918925f},{0.014903f,0.0348351f,0.100469f},{0.0142158f,0.0383477f,0.0918925f}, +{0.0140416f,0.0401399f,0.0918925f},{0.0140417f,0.0401396f,0.100469f},{0.0142159f,0.0383474f,0.100469f}, +{0.0139831f,0.0419492f,0.100469f},{0.0139831f,0.0419492f,0.0918925f},{0.0428559f,0.0139978f,0.100469f}, +{0.0446573f,0.0141144f,0.100469f},{0.0446572f,0.0141144f,0.0918925f},{0.0464389f,0.0143457f,0.0918925f}, +{0.0464391f,0.0143458f,0.100469f},{0.0481959f,0.0146896f,0.100469f},{0.0481956f,0.0146895f,0.0918925f}, +{0.0499226f,0.0151438f,0.100469f},{0.0499225f,0.0151437f,0.0918925f},{0.0516141f,0.0157063f,0.0918925f}, +{0.0516143f,0.0157063f,0.100469f},{0.0532658f,0.016375f,0.100469f},{0.0532655f,0.0163749f,0.0918925f}, +{0.0548718f,0.0171478f,0.100469f},{0.0548716f,0.0171477f,0.0918925f},{0.0564273f,0.0180224f,0.0918925f}, +{0.0564274f,0.0180224f,0.100469f},{0.0579275f,0.018997f,0.100469f},{0.0579272f,0.0189968f,0.0918925f}, +{0.0593668f,0.0200691f,0.100469f},{0.0593666f,0.020069f,0.0918925f},{0.0607403f,0.0212369f,0.0918925f}, +{0.0607404f,0.0212369f,0.100469f},{0.0632573f,0.0238365f,0.100469f},{0.0643775f,0.0252435f,0.100469f}, +{0.0643775f,0.0252434f,0.0918925f},{0.0654011f,0.0267137f,0.0918925f},{0.0654012f,0.0267139f,0.100469f}, +{0.066326f,0.0282424f,0.100469f},{0.0663259f,0.0282422f,0.0918925f},{0.06715f,0.0298238f,0.100469f}, +{0.0671499f,0.0298237f,0.0918925f},{0.0678709f,0.0314531f,0.0918925f},{0.067871f,0.0314533f,0.100469f}, +{0.0684868f,0.0331255f,0.100469f},{0.0684867f,0.0331252f,0.0918925f},{0.0689955f,0.0348353f,0.100469f}, +{0.0689954f,0.0348351f,0.0918925f},{0.0693947f,0.0365776f,0.0918925f},{0.0693947f,0.0365777f,0.100469f}, +{0.0696826f,0.0383477f,0.100469f},{0.0696825f,0.0383474f,0.0918925f},{0.0698568f,0.0401399f,0.100469f}, +{0.0698567f,0.0401396f,0.0918925f},{0.0699153f,0.0419492f,0.0918925f},{0.0699153f,0.0419492f,0.100469f}, +{0.0394436f,-0.0838832f,0.0918925f},{0.0388582f,-0.0838826f,0.0918925f},{0.0388615f,-0.0838832f,0.100469f}, +{0.039447f,-0.0838826f,0.100469f},{0.0400161f,-0.0837618f,0.0918925f},{0.0400177f,-0.0837612f,0.100469f}, +{0.0405514f,-0.0835236f,0.100469f},{0.0410221f,-0.0831813f,0.0918925f},{0.0405497f,-0.0835243f,0.0918925f}, +{0.0410252f,-0.0831785f,0.100469f},{0.0414146f,-0.0827462f,0.0918925f},{0.0414155f,-0.082745f,0.100469f}, +{0.041707f,-0.0822403f,0.0918925f},{0.041708f,-0.0822379f,0.100469f},{0.0418875f,-0.0816851f,0.0918925f}, +{0.041888f,-0.0816836f,0.100469f},{0.0419492f,-0.0811018f,0.100469f},{0.0382891f,-0.0837618f,0.100469f}, +{0.0377555f,-0.0835243f,0.100469f},{0.0382875f,-0.0837612f,0.0918925f},{0.0377538f,-0.0835236f,0.0918925f}, +{0.037283f,-0.0831813f,0.100469f},{0.0372799f,-0.0831785f,0.0918925f},{0.0368906f,-0.0827462f,0.100469f}, +{0.0365982f,-0.0822403f,0.100469f},{0.0368897f,-0.082745f,0.0918925f},{0.0365972f,-0.0822379f,0.0918925f}, +{0.0364177f,-0.0816851f,0.100469f},{0.0364172f,-0.0816836f,0.0918925f},{0.036356f,-0.0811018f,0.100469f}, +{-0.0388615f,-0.0838832f,0.0918925f},{-0.039447f,-0.0838826f,0.0918925f},{-0.0394436f,-0.0838832f,0.100469f}, +{-0.0388582f,-0.0838826f,0.100469f},{-0.0382891f,-0.0837618f,0.0918925f},{-0.0382875f,-0.0837612f,0.100469f}, +{-0.0377538f,-0.0835236f,0.100469f},{-0.037283f,-0.0831813f,0.0918925f},{-0.0377555f,-0.0835243f,0.0918925f}, +{-0.0372799f,-0.0831785f,0.100469f},{-0.0368906f,-0.0827462f,0.0918925f},{-0.0368897f,-0.082745f,0.100469f}, +{-0.0365982f,-0.0822403f,0.0918925f},{-0.0365972f,-0.0822379f,0.100469f},{-0.0364177f,-0.0816851f,0.0918925f}, +{-0.0364172f,-0.0816836f,0.100469f},{-0.036356f,-0.0811018f,0.100469f},{-0.0400161f,-0.0837618f,0.100469f}, +{-0.0405497f,-0.0835243f,0.100469f},{-0.0400177f,-0.0837612f,0.0918925f},{-0.0405514f,-0.0835236f,0.0918925f}, +{-0.0410221f,-0.0831813f,0.100469f},{-0.0410252f,-0.0831785f,0.0918925f},{-0.0414146f,-0.0827462f,0.100469f}, +{-0.041707f,-0.0822403f,0.100469f},{-0.0414155f,-0.082745f,0.0918925f},{-0.041708f,-0.0822379f,0.0918925f}, +{-0.0418875f,-0.0816851f,0.100469f},{-0.041888f,-0.0816836f,0.0918925f},{-0.0419492f,-0.0811018f,0.100469f}, +{0.0394436f,0.0783204f,0.0918925f},{0.0388582f,0.078321f,0.0918925f},{0.0388615f,0.0783204f,0.100469f}, +{0.039447f,0.078321f,0.100469f},{0.0400161f,0.0784418f,0.0918925f},{0.0400177f,0.0784424f,0.100469f}, +{0.0405514f,0.07868f,0.100469f},{0.0410221f,0.0790223f,0.0918925f},{0.0405497f,0.0786793f,0.0918925f}, +{0.0410252f,0.0790251f,0.100469f},{0.0414146f,0.0794574f,0.0918925f},{0.0414155f,0.0794586f,0.100469f}, +{0.041707f,0.0799633f,0.0918925f},{0.041708f,0.0799657f,0.100469f},{0.0418875f,0.0805185f,0.0918925f}, +{0.041888f,0.08052f,0.100469f},{0.0419492f,0.0811018f,0.100469f},{0.0382891f,0.0784418f,0.100469f}, +{0.0377555f,0.0786793f,0.100469f},{0.0382875f,0.0784424f,0.0918925f},{0.0377538f,0.07868f,0.0918925f}, +{0.037283f,0.0790223f,0.100469f},{0.0372799f,0.0790251f,0.0918925f},{0.0368906f,0.0794574f,0.100469f}, +{0.0365982f,0.0799633f,0.100469f},{0.0368897f,0.0794586f,0.0918925f},{0.0365972f,0.0799657f,0.0918925f}, +{0.0364177f,0.0805185f,0.100469f},{0.0364172f,0.08052f,0.0918925f},{0.036356f,0.0811018f,0.100469f}, +{-0.0388615f,0.0783204f,0.0918925f},{-0.039447f,0.078321f,0.0918925f},{-0.0394436f,0.0783204f,0.100469f}, +{-0.0388582f,0.078321f,0.100469f},{-0.0382891f,0.0784418f,0.0918925f},{-0.0382875f,0.0784424f,0.100469f}, +{-0.0377538f,0.07868f,0.100469f},{-0.037283f,0.0790223f,0.0918925f},{-0.0377555f,0.0786793f,0.0918925f}, +{-0.0372799f,0.0790251f,0.100469f},{-0.0368906f,0.0794574f,0.0918925f},{-0.0368897f,0.0794586f,0.100469f}, +{-0.0365982f,0.0799633f,0.0918925f},{-0.0365972f,0.0799657f,0.100469f},{-0.0364177f,0.0805185f,0.0918925f}, +{-0.0364172f,0.08052f,0.100469f},{-0.036356f,0.0811018f,0.100469f},{-0.0400161f,0.0784418f,0.100469f}, +{-0.0405497f,0.0786793f,0.100469f},{-0.0400177f,0.0784424f,0.0918925f},{-0.0405514f,0.07868f,0.0918925f}, +{-0.0410221f,0.0790223f,0.100469f},{-0.0410252f,0.0790251f,0.0918925f},{-0.0414146f,0.0794574f,0.100469f}, +{-0.041707f,0.0799633f,0.100469f},{-0.0414155f,0.0794586f,0.0918925f},{-0.041708f,0.0799657f,0.0918925f}, +{-0.0418875f,0.0805185f,0.100469f},{-0.041888f,0.08052f,0.0918925f},{-0.0419492f,0.0811018f,0.100469f}, +{-0.0808108f,0.0783204f,0.0918925f},{-0.0813962f,0.078321f,0.0918925f},{-0.0813929f,0.0783204f,0.100469f}, +{-0.0808074f,0.078321f,0.100469f},{-0.0802383f,0.0784418f,0.0918925f},{-0.0802367f,0.0784424f,0.100469f}, +{-0.079703f,0.07868f,0.100469f},{-0.0792323f,0.0790223f,0.0918925f},{-0.0797047f,0.0786793f,0.0918925f}, +{-0.0792292f,0.0790251f,0.100469f},{-0.0788398f,0.0794574f,0.0918925f},{-0.0788389f,0.0794586f,0.100469f}, +{-0.0785474f,0.0799633f,0.0918925f},{-0.0785464f,0.0799657f,0.100469f},{-0.0783669f,0.0805185f,0.0918925f}, +{-0.0783664f,0.08052f,0.100469f},{-0.0783052f,0.0811018f,0.100469f},{-0.0783052f,0.0811018f,0.0918925f}, +{-0.0819653f,0.0784418f,0.100469f},{-0.0824989f,0.0786793f,0.100469f},{-0.0819669f,0.0784424f,0.0918925f}, +{-0.0825006f,0.07868f,0.0918925f},{-0.0829714f,0.0790223f,0.100469f},{-0.0829744f,0.0790251f,0.0918925f}, +{-0.0833638f,0.0794574f,0.100469f},{-0.0836562f,0.0799633f,0.100469f},{-0.0833647f,0.0794586f,0.0918925f}, +{-0.0836572f,0.0799657f,0.0918925f},{-0.0838367f,0.0805185f,0.100469f},{-0.0838372f,0.08052f,0.0918925f}, +{-0.0838984f,0.0811018f,0.100469f},{-0.0838984f,0.0811018f,0.0918925f},{0.0813929f,0.0783204f,0.0918925f}, +{0.0808074f,0.078321f,0.0918925f},{0.0808108f,0.0783204f,0.100469f},{0.0813962f,0.078321f,0.100469f}, +{0.0819653f,0.0784418f,0.0918925f},{0.0819669f,0.0784424f,0.100469f},{0.0825006f,0.07868f,0.100469f}, +{0.0829714f,0.0790223f,0.0918925f},{0.0824989f,0.0786793f,0.0918925f},{0.0829744f,0.0790251f,0.100469f}, +{0.0833638f,0.0794574f,0.0918925f},{0.0833647f,0.0794586f,0.100469f},{0.0836562f,0.0799633f,0.0918925f}, +{0.0836572f,0.0799657f,0.100469f},{0.0838367f,0.0805185f,0.0918925f},{0.0838372f,0.08052f,0.100469f}, +{0.0838984f,0.0811018f,0.100469f},{0.0838984f,0.0811018f,0.0918925f},{0.0802383f,0.0784418f,0.100469f}, +{0.0797047f,0.0786793f,0.100469f},{0.0802367f,0.0784424f,0.0918925f},{0.079703f,0.07868f,0.0918925f}, +{0.0792323f,0.0790223f,0.100469f},{0.0792292f,0.0790251f,0.0918925f},{0.0788398f,0.0794574f,0.100469f}, +{0.0785474f,0.0799633f,0.100469f},{0.0788389f,0.0794586f,0.0918925f},{0.0785464f,0.0799657f,0.0918925f}, +{0.0783669f,0.0805185f,0.100469f},{0.0783664f,0.08052f,0.0918925f},{0.0783052f,0.0811018f,0.100469f}, +{0.0783052f,0.0811018f,0.0918925f},{0.0813929f,-0.0838832f,0.0918925f},{0.0808074f,-0.0838826f,0.0918925f}, +{0.0808108f,-0.0838832f,0.100469f},{0.0813962f,-0.0838826f,0.100469f},{0.0819653f,-0.0837618f,0.0918925f}, +{0.0819669f,-0.0837612f,0.100469f},{0.0825006f,-0.0835236f,0.100469f},{0.0829714f,-0.0831813f,0.0918925f}, +{0.0824989f,-0.0835243f,0.0918925f},{0.0829744f,-0.0831785f,0.100469f},{0.0833638f,-0.0827462f,0.0918925f}, +{0.0833647f,-0.082745f,0.100469f},{0.0836562f,-0.0822403f,0.0918925f},{0.0836572f,-0.0822379f,0.100469f}, +{0.0838367f,-0.0816851f,0.0918925f},{0.0838372f,-0.0816836f,0.100469f},{0.0838984f,-0.0811018f,0.100469f}, +{0.0838984f,-0.0811018f,0.0918925f},{0.0802383f,-0.0837618f,0.100469f},{0.0797047f,-0.0835243f,0.100469f}, +{0.0802367f,-0.0837612f,0.0918925f},{0.079703f,-0.0835236f,0.0918925f},{0.0792323f,-0.0831813f,0.100469f}, +{0.0792292f,-0.0831785f,0.0918925f},{0.0788398f,-0.0827462f,0.100469f},{0.0785474f,-0.0822403f,0.100469f}, +{0.0788389f,-0.082745f,0.0918925f},{0.0785464f,-0.0822379f,0.0918925f},{0.0783669f,-0.0816851f,0.100469f}, +{0.0783664f,-0.0816836f,0.0918925f},{0.0783052f,-0.0811018f,0.100469f},{0.0783052f,-0.0811018f,0.0918925f}, +{-0.0603023f,-0.0838832f,0.0918925f},{-0.0608877f,-0.0838826f,0.0918925f},{-0.0608844f,-0.0838832f,0.100469f}, +{-0.0602989f,-0.0838826f,0.100469f},{-0.0597298f,-0.0837618f,0.0918925f},{-0.0597282f,-0.0837612f,0.100469f}, +{-0.0591945f,-0.0835236f,0.100469f},{-0.0587238f,-0.0831813f,0.0918925f},{-0.0591962f,-0.0835243f,0.0918925f}, +{-0.0587207f,-0.0831785f,0.100469f},{-0.0583313f,-0.0827462f,0.0918925f},{-0.0583304f,-0.082745f,0.100469f}, +{-0.0580389f,-0.0822403f,0.0918925f},{-0.0580379f,-0.0822379f,0.100469f},{-0.0578584f,-0.0816851f,0.0918925f}, +{-0.0578579f,-0.0816836f,0.100469f},{-0.0577967f,-0.0811018f,0.100469f},{-0.0577967f,-0.0811018f,0.0918925f}, +{-0.0614568f,-0.0837618f,0.100469f},{-0.0619904f,-0.0835243f,0.100469f},{-0.0614584f,-0.0837612f,0.0918925f}, +{-0.0619921f,-0.0835236f,0.0918925f},{-0.0624629f,-0.0831813f,0.100469f},{-0.0624659f,-0.0831785f,0.0918925f}, +{-0.0628553f,-0.0827462f,0.100469f},{-0.0631477f,-0.0822403f,0.100469f},{-0.0628562f,-0.082745f,0.0918925f}, +{-0.0631487f,-0.0822379f,0.0918925f},{-0.0633282f,-0.0816851f,0.100469f},{-0.0633287f,-0.0816836f,0.0918925f}, +{-0.0633899f,-0.0811018f,0.100469f},{-0.0633899f,-0.0811018f,0.0918925f},{0.280753f,0.00413429f,0.0918925f}, +{0.281577f,0.005033f,0.0918925f},{0.281577f,0.005033f,0.100469f},{0.282607f,0.00568869f,0.0918925f}, +{0.283758f,0.00605158f,0.100469f},{0.282605f,0.00568781f,0.100469f},{0.284979f,0.00610573f,0.0918925f}, +{0.284979f,0.00610573f,0.100469f},{0.283761f,0.00605247f,0.0918925f},{0.280752f,0.00413168f,0.100469f}, +{0.280193f,0.00305863f,0.100469f},{0.280195f,0.00306124f,0.0918925f},{0.279929f,0.00186868f,0.0918925f}, +{0.279929f,0.00186868f,0.100469f},{0.288796f,-0.00343343f,0.0918925f},{0.288143f,-0.00445856f,0.0918925f}, +{0.288143f,-0.00445842f,0.100469f},{0.287245f,-0.00528145f,0.0918925f},{0.286169f,-0.00584165f,0.100469f}, +{0.287247f,-0.0052798f,0.100469f},{0.284979f,-0.00610573f,0.0918925f},{0.284979f,-0.00610573f,0.100469f}, +{0.286165f,-0.00584289f,0.0918925f},{0.288798f,-0.00343061f,0.100469f},{0.289163f,-0.00227009f,0.100469f}, +{0.289162f,-0.00227354f,0.0918925f},{0.289216f,-0.00105623f,0.0918925f},{0.289216f,-0.00105623f,0.100469f}, +{-0.301706f,-0.00557749f,0.100469f},{-0.300865f,-0.00557653f,0.100469f},{-0.300871f,-0.00557749f,0.0918925f}, +{-0.302537f,-0.00545222f,0.100469f},{-0.301712f,-0.00557653f,0.0918925f},{-0.302539f,-0.00545147f,0.0918925f}, +{-0.303332f,-0.00520667f,0.100469f},{-0.303333f,-0.00520615f,0.0918925f},{-0.304083f,-0.00484531f,0.0918925f}, +{-0.30408f,-0.00484666f,0.100469f},{-0.30477f,-0.00437673f,0.100469f},{-0.305913f,-0.00314621f,0.0918925f}, +{-0.306328f,-0.0024268f,0.100469f},{-0.305912f,-0.00314718f,0.100469f},{-0.304776f,-0.00437292f,0.0918925f}, +{-0.305388f,-0.00380457f,0.100469f},{-0.305391f,-0.00380129f,0.0918925f},{-0.306329f,-0.0024238f,0.0918925f}, +{-0.306632f,-0.00165337f,0.100469f},{-0.306633f,-0.00164971f,0.0918925f},{-0.306818f,-0.000839977f,0.0918925f}, +{-0.306882f,1.19421e-018f,0.100469f},{-0.306818f,-0.000839977f,0.100469f},{-0.306882f,1.19421e-018f,0.0918925f}, +{-0.30004f,-0.00545222f,0.0918925f},{-0.299245f,-0.00520667f,0.0918925f},{-0.300038f,-0.00545147f,0.100469f}, +{-0.299244f,-0.00520615f,0.100469f},{-0.298497f,-0.00484666f,0.0918925f},{-0.298494f,-0.00484531f,0.100469f}, +{-0.297807f,-0.00437673f,0.0918925f},{-0.297189f,-0.00380457f,0.0918925f},{-0.297802f,-0.00437292f,0.100469f}, +{-0.297186f,-0.00380129f,0.100469f},{-0.296665f,-0.00314718f,0.0918925f},{-0.296664f,-0.00314621f,0.100469f}, +{-0.296249f,-0.0024268f,0.0918925f},{-0.295945f,-0.00165337f,0.0918925f},{-0.296248f,-0.0024238f,0.100469f}, +{-0.295944f,-0.00164971f,0.100469f},{-0.295759f,-0.000839977f,0.0918925f},{-0.295759f,-0.000839977f,0.100469f}, +{-0.295695f,5.09237e-019f,0.0918925f},{-0.295695f,5.09237e-019f,0.100469f},{-0.000417625f,0.295711f,0.100469f}, +{0.000423769f,0.295712f,0.100469f},{0.000417625f,0.295711f,0.0918925f},{-0.00124862f,0.295836f,0.100469f}, +{-0.000423769f,0.295712f,0.0918925f},{-0.00125042f,0.295837f,0.0918925f},{-0.00204323f,0.296082f,0.100469f}, +{-0.0020445f,0.296082f,0.0918925f},{-0.00279455f,0.296443f,0.0918925f},{-0.00279128f,0.296442f,0.100469f}, +{-0.00348179f,0.296912f,0.100469f},{-0.00462441f,0.298142f,0.0918925f},{-0.00503944f,0.298862f,0.100469f}, +{-0.00462371f,0.298141f,0.100469f},{-0.00348701f,0.296916f,0.0918925f},{-0.00409988f,0.297484f,0.100469f}, +{-0.00410228f,0.297487f,0.0918925f},{-0.00504068f,0.298865f,0.0918925f},{-0.00534308f,0.299635f,0.100469f}, +{-0.0053446f,0.299639f,0.0918925f},{-0.00552953f,0.300449f,0.0918925f},{-0.00559323f,0.301289f,0.100469f}, +{-0.00552953f,0.300449f,0.100469f},{-0.00559323f,0.301289f,0.0918925f},{0.00124862f,0.295836f,0.0918925f}, +{0.00204323f,0.296082f,0.0918925f},{0.00125042f,0.295837f,0.100469f},{0.0020445f,0.296082f,0.100469f}, +{0.00279128f,0.296442f,0.0918925f},{0.00279455f,0.296443f,0.100469f},{0.00348179f,0.296912f,0.0918925f}, +{0.00409988f,0.297484f,0.0918925f},{0.00348701f,0.296916f,0.100469f},{0.00410228f,0.297487f,0.100469f}, +{0.00462371f,0.298141f,0.0918925f},{0.00462441f,0.298142f,0.100469f},{0.00503944f,0.298862f,0.0918925f}, +{0.00534308f,0.299635f,0.0918925f},{0.00504068f,0.298865f,0.100469f},{0.0053446f,0.299639f,0.100469f}, +{0.00552953f,0.300449f,0.0918925f},{0.00552953f,0.300449f,0.100469f},{0.00559323f,0.301289f,0.0918925f}, +{0.00559323f,0.301289f,0.100469f},{0.300871f,-0.00557749f,0.100469f},{0.301712f,-0.00557653f,0.100469f}, +{0.301706f,-0.00557749f,0.0918925f},{0.30004f,-0.00545222f,0.100469f},{0.300865f,-0.00557653f,0.0918925f}, +{0.300038f,-0.00545147f,0.0918925f},{0.299245f,-0.00520667f,0.100469f},{0.299244f,-0.00520615f,0.0918925f}, +{0.298494f,-0.00484531f,0.0918925f},{0.298497f,-0.00484666f,0.100469f},{0.297807f,-0.00437673f,0.100469f}, +{0.296664f,-0.00314621f,0.0918925f},{0.296249f,-0.0024268f,0.100469f},{0.296665f,-0.00314718f,0.100469f}, +{0.297802f,-0.00437292f,0.0918925f},{0.297189f,-0.00380457f,0.100469f},{0.297186f,-0.00380129f,0.0918925f}, +{0.296248f,-0.0024238f,0.0918925f},{0.295945f,-0.00165337f,0.100469f},{0.295944f,-0.00164971f,0.0918925f}, +{0.295759f,-0.000839977f,0.0918925f},{0.295695f,1.19421e-018f,0.100469f},{0.295759f,-0.000839977f,0.100469f}, +{0.295695f,1.19421e-018f,0.0918925f},{0.302537f,-0.00545222f,0.0918925f},{0.303332f,-0.00520667f,0.0918925f}, +{0.302539f,-0.00545147f,0.100469f},{0.303333f,-0.00520615f,0.100469f},{0.30408f,-0.00484666f,0.0918925f}, +{0.304083f,-0.00484531f,0.100469f},{0.30477f,-0.00437673f,0.0918925f},{0.305388f,-0.00380457f,0.0918925f}, +{0.304776f,-0.00437292f,0.100469f},{0.305391f,-0.00380129f,0.100469f},{0.305912f,-0.00314718f,0.0918925f}, +{0.305913f,-0.00314621f,0.100469f},{0.306328f,-0.0024268f,0.0918925f},{0.306632f,-0.00165337f,0.0918925f}, +{0.306329f,-0.0024238f,0.100469f},{0.306633f,-0.00164971f,0.100469f},{0.306818f,-0.000839977f,0.0918925f}, +{0.306818f,-0.000839977f,0.100469f},{0.306882f,5.09237e-019f,0.0918925f},{0.306882f,5.09237e-019f,0.100469f}, +{-0.000417625f,-0.306866f,0.100469f},{0.000423769f,-0.306865f,0.100469f},{0.000417625f,-0.306866f,0.0918925f}, +{-0.00124862f,-0.306741f,0.100469f},{-0.000423769f,-0.306865f,0.0918925f},{-0.00125042f,-0.30674f,0.0918925f}, +{-0.00204323f,-0.306495f,0.100469f},{-0.0020445f,-0.306495f,0.0918925f},{-0.00279455f,-0.306134f,0.0918925f}, +{-0.00279128f,-0.306135f,0.100469f},{-0.00348179f,-0.305665f,0.100469f},{-0.00462441f,-0.304435f,0.0918925f}, +{-0.00503944f,-0.303715f,0.100469f},{-0.00462371f,-0.304436f,0.100469f},{-0.00348701f,-0.305661f,0.0918925f}, +{-0.00409988f,-0.305093f,0.100469f},{-0.00410228f,-0.30509f,0.0918925f},{-0.00504068f,-0.303712f,0.0918925f}, +{-0.00534308f,-0.302942f,0.100469f},{-0.0053446f,-0.302938f,0.0918925f},{-0.00552953f,-0.302129f,0.0918925f}, +{-0.00559323f,-0.301289f,0.100469f},{-0.00552953f,-0.302129f,0.100469f},{-0.00559323f,-0.301289f,0.0918925f}, +{0.00124862f,-0.306741f,0.0918925f},{0.00204323f,-0.306495f,0.0918925f},{0.00125042f,-0.30674f,0.100469f}, +{0.0020445f,-0.306495f,0.100469f},{0.00279128f,-0.306135f,0.0918925f},{0.00279455f,-0.306134f,0.100469f}, +{0.00348179f,-0.305665f,0.0918925f},{0.00409988f,-0.305093f,0.0918925f},{0.00348701f,-0.305661f,0.100469f}, +{0.00410228f,-0.30509f,0.100469f},{0.00462371f,-0.304436f,0.0918925f},{0.00462441f,-0.304435f,0.100469f}, +{0.00503944f,-0.303715f,0.0918925f},{0.00534308f,-0.302942f,0.0918925f},{0.00504068f,-0.303712f,0.100469f}, +{0.0053446f,-0.302938f,0.100469f},{0.00552953f,-0.302129f,0.0918925f},{0.00552953f,-0.302129f,0.100469f}, +{0.00559323f,-0.301289f,0.0918925f},{0.00559323f,-0.301289f,0.100469f},{-0.0348217f,0.314624f,0.0918925f}, +{-0.0337164f,0.317214f,0.100469f},{-0.0337175f,0.317211f,0.0918925f},{-0.0324231f,0.319705f,0.0918925f}, +{-0.0324223f,0.319706f,0.100469f},{-0.0309468f,0.32209f,0.100469f},{-0.0309475f,0.322089f,0.0918925f}, +{-0.0292965f,0.324356f,0.100469f},{-0.0292972f,0.324355f,0.0918925f},{-0.0274788f,0.326494f,0.0918925f}, +{-0.0274777f,0.326495f,0.100469f},{-0.0254989f,0.328495f,0.100469f},{-0.0255009f,0.328493f,0.0918925f}, +{-0.0233785f,0.330338f,0.100469f},{-0.0233795f,0.330337f,0.0918925f},{-0.0211301f,0.332012f,0.0918925f}, +{-0.0211293f,0.332013f,0.100469f},{-0.0187614f,0.333513f,0.100469f},{-0.0187622f,0.333513f,0.0918925f}, +{-0.0162847f,0.334833f,0.100469f},{-0.0162855f,0.334832f,0.0918925f},{-0.0137109f,0.335964f,0.0918925f}, +{-0.0137094f,0.335965f,0.100469f},{-0.0110591f,0.336899f,0.100469f},{-0.0110599f,0.336899f,0.0918925f}, +{-0.00835103f,0.33763f,0.100469f},{-0.00835149f,0.337629f,0.0918925f},{-0.00559768f,0.338154f,0.0918925f}, +{-0.00559736f,0.338154f,0.100469f},{-0.00280978f,0.338471f,0.100469f},{-0.00280994f,0.338471f,0.0918925f}, +{-6.08556e-017f,0.338577f,0.100469f},{-6.08556e-017f,0.338577f,0.0918925f},{-0.0348209f,0.314627f,0.100469f}, +{-0.0357267f,0.311966f,0.0918925f},{-0.0357264f,0.311967f,0.100469f},{-0.036428f,0.309251f,0.0918925f}, +{-0.0364278f,0.309253f,0.100469f},{-0.0369231f,0.306493f,0.100469f},{-0.0369234f,0.306492f,0.0918925f}, +{-0.0372102f,0.303699f,0.0918925f},{-0.03721f,0.303701f,0.100469f},{-0.0372859f,0.300887f,0.0918925f}, +{-0.037286f,0.300889f,0.100469f},{-0.0371501f,0.298082f,0.100469f},{-0.0371499f,0.298081f,0.0918925f}, +{-0.0368038f,0.295298f,0.0918925f},{-0.036804f,0.295299f,0.100469f},{-0.0362498f,0.29255f,0.0918925f}, +{-0.03625f,0.292551f,0.100469f},{-0.0354901f,0.289849f,0.100469f},{-0.0354899f,0.289848f,0.0918925f}, +{-0.0345264f,0.287205f,0.0918925f},{-0.034527f,0.287207f,0.100469f},{-0.0333678f,0.284645f,0.0918925f}, +{-0.0333682f,0.284646f,0.100469f},{-0.0320226f,0.282185f,0.100469f},{-0.0320224f,0.282184f,0.0918925f}, +{-0.0304967f,0.279833f,0.0918925f},{-0.0304969f,0.279833f,0.100469f},{-0.0287972f,0.2776f,0.0918925f}, +{-0.0287973f,0.2776f,0.100469f},{-0.0269304f,0.275498f,0.0918925f},{-0.0269304f,0.275498f,0.100469f}, +{-0.314624f,-0.0348217f,0.0918925f},{-0.317214f,-0.0337164f,0.100469f},{-0.317211f,-0.0337175f,0.0918925f}, +{-0.319705f,-0.0324231f,0.0918925f},{-0.319706f,-0.0324223f,0.100469f},{-0.32209f,-0.0309468f,0.100469f}, +{-0.322089f,-0.0309475f,0.0918925f},{-0.324356f,-0.0292965f,0.100469f},{-0.324355f,-0.0292972f,0.0918925f}, +{-0.326494f,-0.0274788f,0.0918925f},{-0.326495f,-0.0274777f,0.100469f},{-0.328495f,-0.0254989f,0.100469f}, +{-0.328493f,-0.0255009f,0.0918925f},{-0.330338f,-0.0233785f,0.100469f},{-0.330337f,-0.0233795f,0.0918925f}, +{-0.332012f,-0.0211301f,0.0918925f},{-0.332013f,-0.0211293f,0.100469f},{-0.333513f,-0.0187614f,0.100469f}, +{-0.333513f,-0.0187622f,0.0918925f},{-0.334833f,-0.0162847f,0.100469f},{-0.334832f,-0.0162855f,0.0918925f}, +{-0.335964f,-0.0137109f,0.0918925f},{-0.335965f,-0.0137094f,0.100469f},{-0.336899f,-0.0110591f,0.100469f}, +{-0.336899f,-0.0110599f,0.0918925f},{-0.33763f,-0.00835103f,0.100469f},{-0.337629f,-0.00835149f,0.0918925f}, +{-0.338154f,-0.00559768f,0.0918925f},{-0.338154f,-0.00559736f,0.100469f},{-0.338471f,-0.00280978f,0.100469f}, +{-0.338471f,-0.00280994f,0.0918925f},{-0.338577f,5.09237e-019f,0.100469f},{-0.338577f,5.09237e-019f,0.0918925f}, +{-0.314627f,-0.0348209f,0.100469f},{-0.311966f,-0.0357267f,0.0918925f},{-0.311967f,-0.0357264f,0.100469f}, +{-0.309251f,-0.036428f,0.0918925f},{-0.309253f,-0.0364278f,0.100469f},{-0.306493f,-0.0369231f,0.100469f}, +{-0.306492f,-0.0369234f,0.0918925f},{-0.303699f,-0.0372102f,0.0918925f},{-0.303701f,-0.03721f,0.100469f}, +{-0.300887f,-0.0372859f,0.0918925f},{-0.300889f,-0.037286f,0.100469f},{-0.298082f,-0.0371501f,0.100469f}, +{-0.298081f,-0.0371499f,0.0918925f},{-0.295298f,-0.0368038f,0.0918925f},{-0.295299f,-0.036804f,0.100469f}, +{-0.29255f,-0.0362498f,0.0918925f},{-0.292551f,-0.03625f,0.100469f},{-0.289849f,-0.0354901f,0.100469f}, +{-0.289848f,-0.0354899f,0.0918925f},{-0.287205f,-0.0345264f,0.0918925f},{-0.287207f,-0.034527f,0.100469f}, +{-0.284645f,-0.0333678f,0.0918925f},{-0.284646f,-0.0333682f,0.100469f},{-0.282185f,-0.0320226f,0.100469f}, +{-0.282184f,-0.0320224f,0.0918925f},{-0.279833f,-0.0304967f,0.0918925f},{-0.279833f,-0.0304969f,0.100469f}, +{-0.2776f,-0.0287972f,0.0918925f},{-0.2776f,-0.0287973f,0.100469f},{-0.275498f,-0.0269304f,0.0918925f}, +{-0.275498f,-0.0269304f,0.100469f},{0.0348217f,-0.314624f,0.0918925f},{0.0337164f,-0.317214f,0.100469f}, +{0.0337175f,-0.317211f,0.0918925f},{0.0324231f,-0.319705f,0.0918925f},{0.0324223f,-0.319706f,0.100469f}, +{0.0309468f,-0.32209f,0.100469f},{0.0309475f,-0.322089f,0.0918925f},{0.0292965f,-0.324356f,0.100469f}, +{0.0292972f,-0.324355f,0.0918925f},{0.0274788f,-0.326494f,0.0918925f},{0.0274777f,-0.326495f,0.100469f}, +{0.0254989f,-0.328495f,0.100469f},{0.0255009f,-0.328493f,0.0918925f},{0.0233785f,-0.330338f,0.100469f}, +{0.0233795f,-0.330337f,0.0918925f},{0.0211301f,-0.332012f,0.0918925f},{0.0211293f,-0.332013f,0.100469f}, +{0.0187614f,-0.333513f,0.100469f},{0.0187622f,-0.333513f,0.0918925f},{0.0162847f,-0.334833f,0.100469f}, +{0.0162855f,-0.334832f,0.0918925f},{0.0137109f,-0.335964f,0.0918925f},{0.0137094f,-0.335965f,0.100469f}, +{0.0110591f,-0.336899f,0.100469f},{0.0110599f,-0.336899f,0.0918925f},{0.00835103f,-0.33763f,0.100469f}, +{0.00835149f,-0.337629f,0.0918925f},{0.00559768f,-0.338154f,0.0918925f},{0.00559736f,-0.338154f,0.100469f}, +{0.00280978f,-0.338471f,0.100469f},{0.00280994f,-0.338471f,0.0918925f},{5.51904e-017f,-0.338577f,0.100469f}, +{5.51904e-017f,-0.338577f,0.0918925f},{0.0348209f,-0.314627f,0.100469f},{0.0357267f,-0.311966f,0.0918925f}, +{0.0357264f,-0.311967f,0.100469f},{0.036428f,-0.309251f,0.0918925f},{0.0364278f,-0.309253f,0.100469f}, +{0.0369231f,-0.306493f,0.100469f},{0.0369234f,-0.306492f,0.0918925f},{0.0372102f,-0.303699f,0.0918925f}, +{0.03721f,-0.303701f,0.100469f},{0.0372859f,-0.300887f,0.0918925f},{0.037286f,-0.300889f,0.100469f}, +{0.0371501f,-0.298082f,0.100469f},{0.0371499f,-0.298081f,0.0918925f},{0.0368038f,-0.295298f,0.0918925f}, +{0.036804f,-0.295299f,0.100469f},{0.0362498f,-0.29255f,0.0918925f},{0.03625f,-0.292551f,0.100469f}, +{0.0354901f,-0.289849f,0.100469f},{0.0354899f,-0.289848f,0.0918925f},{0.0345264f,-0.287205f,0.0918925f}, +{0.034527f,-0.287207f,0.100469f},{0.0333678f,-0.284645f,0.0918925f},{0.0333682f,-0.284646f,0.100469f}, +{0.0320226f,-0.282185f,0.100469f},{0.0320224f,-0.282184f,0.0918925f},{0.0304967f,-0.279833f,0.0918925f}, +{0.0304969f,-0.279833f,0.100469f},{0.0287972f,-0.2776f,0.0918925f},{0.0287973f,-0.2776f,0.100469f}, +{0.0269304f,-0.275498f,0.0918925f},{0.0269304f,-0.275498f,0.100469f},{-0.0768194f,-0.0930843f,0.100469f}, +{-0.079125f,-0.0926561f,0.100469f},{0.0167528f,-0.0298143f,0.100469f},{-0.0167532f,-0.0298151f,0.100469f}, +{-0.0160285f,-0.0314546f,0.100469f},{-0.107313f,-0.0145465f,0.100469f},{-0.107316f,0.0145474f,0.100469f}, +{-0.109619f,-0.0141179f,0.100469f},{-0.0745764f,-0.0932205f,0.100469f},{-0.0932205f,-0.0326272f,0.100469f}, +{-0.0696868f,-0.0383722f,0.100469f},{-0.0694022f,-0.0366018f,0.100469f},{-0.306315f,0.00242058f,0.100469f}, +{-0.313415f,0.00227358f,0.100469f},{-0.306637f,0.00165192f,0.100469f},{-0.27258f,-0.0243605f,0.100469f}, +{-0.29667f,0.00314874f,0.100469f},{-0.296252f,0.00242484f,0.100469f},{0.0145465f,-0.107313f,0.100469f}, +{-0.0145474f,-0.107316f,0.100469f},{-0.0141193f,-0.109622f,0.100469f},{-0.0628562f,-0.0794586f,0.100469f}, +{-0.0932205f,-0.0745764f,0.100469f},{-0.0631487f,-0.0799657f,0.100469f},{-0.2915f,-0.0119424f,0.100469f}, +{-0.304721f,-0.0124916f,0.100469f},{-0.0326272f,-0.0932205f,0.100469f},{-0.0877597f,-0.0877597f,0.100469f}, +{-0.0858213f,-0.089447f,0.100469f},{-0.0633287f,-0.08052f,0.100469f},{-0.0365982f,-0.0799633f,0.100469f}, +{-0.0368906f,-0.0794574f,0.100469f},{-0.0213792f,-0.0969955f,0.100469f},{-0.0194438f,-0.0986812f,0.100469f}, +{-0.0259491f,-0.0190126f,0.100469f},{-0.0274515f,-0.0180347f,0.100469f},{0.0213822f,-0.0969939f,0.100469f}, +{0.0194438f,-0.0986812f,0.100469f},{-0.0177565f,-0.10062f,0.100469f},{0.0177581f,-0.100617f,0.100469f}, +{0.0745764f,-0.0932205f,0.100469f},{-0.0152921f,-0.105002f,0.100469f},{0.0152921f,-0.105002f,0.100469f}, +{0.0163653f,-0.102745f,0.100469f},{-0.0163644f,-0.102748f,0.100469f},{0.0141179f,-0.109619f,0.100469f}, +{-0.00227358f,-0.313415f,0.100469f},{-0.00105623f,-0.313362f,0.100469f},{-0.00343287f,-0.31378f,0.100469f}, +{0.0213591f,-0.29942f,0.100469f},{0.0186351f,-0.295578f,0.100469f},{0.0131454f,-0.305747f,0.100469f}, +{0.0122298f,-0.311032f,0.100469f},{0.014044f,-0.30657f,0.100469f},{-0.0116607f,-0.311153f,0.100469f}, +{-0.0111271f,-0.31139f,0.100469f},{0.00298716f,-0.322407f,0.100469f},{0.00408405f,-0.321856f,0.100469f}, +{-0.0151227f,-0.295446f,0.100469f},{-0.00461423f,-0.29814f,0.100469f},{-0.0131454f,-0.29683f,0.100469f}, +{-0.0324248f,-0.319702f,0.100469f},{-0.0309477f,-0.322089f,0.100469f},{-0.0292931f,-0.324357f,0.100469f}, +{-0.0274755f,-0.326496f,0.100469f},{-0.0121261f,-0.299015f,0.100469f},{-0.00502626f,-0.298868f,0.100469f}, +{-0.0124916f,-0.297856f,0.100469f},{-0.0102622f,-0.312168f,0.100469f},{-0.0211299f,-0.332011f,0.100469f}, +{-0.0187591f,-0.333514f,0.100469f},{-0.295223f,-0.0174585f,0.100469f},{-0.29719f,0.00380369f,0.100469f}, +{-0.301289f,-0.0214407f,0.100469f},{-0.29942f,-0.0213591f,0.100469f},{-0.00584288f,-0.316411f,0.100469f}, +{0.00571052f,-0.319924f,0.100469f},{-0.297802f,0.0043727f,0.100469f},{-0.297856f,0.0124916f,0.100469f}, +{-0.298493f,0.00484368f,0.100469f},{0.0139213f,-0.31139f,0.100469f},{0.0143937f,-0.311733f,0.100469f}, +{-0.302532f,0.00545321f,0.100469f},{-0.301706f,0.00557763f,0.100469f},{-0.312949f,-0.00986419f,0.100469f}, +{-0.312416f,-0.0101017f,0.100469f},{0.0106515f,-0.311736f,0.100469f},{0.0111254f,-0.311391f,0.100469f}, +{-0.30087f,0.00557747f,0.100469f},{-0.301289f,0.0121187f,0.100469f},{-0.31378f,0.00343287f,0.100469f}, +{5.8201e-009f,-0.313407f,0.100469f},{0.0214407f,-0.301289f,0.100469f},{0.0174585f,-0.295223f,0.100469f}, +{0.0197119f,-0.296256f,0.100469f},{0.0121261f,-0.303562f,0.100469f},{0.0147862f,-0.312168f,0.100469f}, +{0.005033f,-0.321f,0.100469f},{0.0147862f,-0.28712f,0.100469f},{0.00409889f,-0.297485f,0.100469f}, +{0.0046188f,-0.29814f,0.100469f},{0.00503626f,-0.298864f,0.100469f},{0.0364172f,-0.08052f,0.100469f}, +{-0.00996978f,-0.312674f,0.100469f},{-0.00445857f,-0.314434f,0.100469f},{-0.00835238f,-0.337628f,0.100469f}, +{-0.0110628f,-0.336897f,0.100469f},{0.00186868f,-0.322648f,0.100469f},{-6.42929e-017f,-0.322729f,0.100469f}, +{-0.00534833f,-0.299637f,0.100469f},{-0.00409933f,-0.297483f,0.100469f},{-0.00348669f,-0.296915f,0.100469f}, +{-0.0255017f,-0.328493f,0.100469f},{-0.0233817f,-0.330334f,0.100469f},{-0.00553085f,-0.300454f,0.100469f}, +{-0.00132352f,-0.218226f,0.100469f},{-0.0139831f,-0.243259f,0.100469f},{-0.00124367f,-0.295835f,0.100469f}, +{-0.00041711f,-0.295711f,0.100469f},{-0.0139831f,-0.111865f,0.100469f},{0.0139831f,-0.111865f,0.100469f}, +{0.0166349f,-0.258757f,0.100469f},{0.0154692f,-0.254935f,0.100469f},{-0.0214407f,-0.301289f,0.100469f}, +{-0.0372872f,-0.300891f,0.100469f},{-0.0371926f,-0.303697f,0.100469f},{-0.00132352f,-0.255514f,0.100469f}, +{-0.00112134f,-0.255125f,0.100469f},{-0.0146388f,-0.25105f,0.100469f},{0.00584288f,-0.286166f,0.100469f}, +{0.0102613f,-0.287121f,0.100469f},{0.0146388f,-0.251049f,0.100469f},{0.0013304f,-0.255513f,0.100469f}, +{0.0139831f,-0.243259f,0.100469f},{0.000433147f,-0.254615f,0.100469f},{0.0141453f,-0.247143f,0.100469f}, +{0.000819963f,-0.254817f,0.100469f},{0.00112493f,-0.255127f,0.100469f},{-0.0154693f,-0.254936f,0.100469f}, +{3.01689e-017f,-0.254546f,0.100469f},{-0.000431051f,-0.254614f,0.100469f},{0.0372799f,-0.0790251f,0.100469f}, +{0.0836959f,-0.0908383f,0.100469f},{0.0814392f,-0.0919114f,0.100469f},{0.0768218f,-0.0930856f,0.100469f}, +{0.0937839f,-0.0280757f,0.100469f},{0.0663164f,-0.0282257f,0.100469f},{0.0671452f,-0.0298151f,0.100469f}, +{0.089447f,-0.0858213f,0.100469f},{0.0908391f,-0.0836927f,0.100469f},{0.0919114f,-0.0814392f,0.100469f}, +{0.0926561f,-0.079125f,0.100469f},{0.0836562f,-0.0799633f,0.100469f},{0.0838367f,-0.0805185f,0.100469f}, +{0.0932205f,-0.0745764f,0.100469f},{0.0829714f,-0.0790223f,0.100469f},{0.0833638f,-0.0794574f,0.100469f}, +{0.0877597f,-0.0877597f,0.100469f},{0.107313f,0.0145465f,0.100469f},{0.105002f,-0.0152921f,0.100469f}, +{0.107316f,-0.0145474f,0.100469f},{0.0819653f,-0.0784418f,0.100469f},{0.0813929f,-0.0783204f,0.100469f}, +{0.0858243f,-0.0894455f,0.100469f},{0.0932205f,-0.0326272f,0.100469f},{-0.0142141f,-0.0383731f,0.100469f}, +{0.0144962f,-0.0366018f,0.100469f},{-0.0145004f,-0.0366037f,0.100469f},{0.0932205f,0.0326272f,0.100469f}, +{0.102748f,-0.0163644f,0.100469f},{0.105002f,0.0152921f,0.100469f},{0.102745f,0.0163653f,0.100469f}, +{0.0986812f,-0.0194438f,0.100469f},{0.100617f,0.0177581f,0.100469f},{0.0986812f,0.0194438f,0.100469f}, +{0.109619f,0.0141179f,0.100469f},{0.109622f,-0.0141193f,0.100469f},{0.290634f,0.0146037f,0.100469f}, +{0.291026f,0.0141686f,0.100469f},{0.111865f,0.0139831f,0.100469f},{0.311372f,-0.035899f,0.100469f}, +{0.314002f,-0.0350539f,0.100469f},{0.305373f,-0.0205678f,0.100469f},{0.305907f,0.00314874f,0.100469f}, +{0.306325f,0.00242484f,0.100469f},{0.319924f,0.00571052f,0.100469f},{0.313415f,-0.00227358f,0.100469f}, +{0.315682f,-0.0104447f,0.100469f},{0.316075f,-0.0108798f,0.100469f},{0.299015f,-0.0121261f,0.100469f}, +{0.300232f,-0.012073f,0.100469f},{0.335522f,0.0147828f,0.100469f},{0.334333f,0.0172772f,0.100469f}, +{0.321f,0.005033f,0.100469f},{0.31194f,-0.0104475f,0.100469f},{0.331418f,-0.0219665f,0.100469f}, +{0.337328f,-0.00956357f,0.100469f},{0.335521f,-0.0147817f,0.100469f},{0.334333f,-0.0172761f,0.100469f}, +{0.322729f,-7.81484e-018f,0.100469f},{0.338551f,-0.00138096f,0.100469f},{0.338551f,0.00138181f,0.100469f}, +{0.332963f,-0.0196753f,0.100469f},{0.33733f,0.00956509f,0.100469f},{0.321856f,0.00408405f,0.100469f}, +{0.322407f,0.00298716f,0.100469f},{0.337939f,0.00686983f,0.100469f},{0.322648f,0.00186868f,0.100469f}, +{0.338347f,0.00413689f,0.100469f},{0.312414f,-0.0101024f,0.100469f},{0.329709f,-0.024138f,0.100469f}, +{0.314434f,-0.00445857f,0.100469f},{0.313518f,-0.0097434f,0.100469f},{0.315333f,-0.00528144f,0.100469f}, +{0.327844f,-0.0261764f,0.100469f},{0.325832f,-0.0280694f,0.100469f},{0.297856f,-0.0124916f,0.100469f}, +{0.31521f,-0.0101017f,0.100469f},{0.323687f,-0.0298108f,0.100469f},{0.295446f,-0.0151227f,0.100469f}, +{0.319039f,-0.032792f,0.100469f},{0.321418f,-0.0313879f,0.100469f},{0.307354f,-0.0174585f,0.100469f}, +{0.306322f,-0.0197119f,0.100469f},{0.321418f,0.0313882f,0.100469f},{0.314676f,0.0151842f,0.100469f}, +{0.323687f,0.0298117f,0.100469f},{0.325828f,0.0280668f,0.100469f},{0.31521f,0.0149467f,0.100469f}, +{0.315682f,0.0146037f,0.100469f},{0.305959f,0.0369915f,0.100469f},{0.303208f,0.0372381f,0.100469f}, +{0.294948f,0.0367442f,0.100469f},{0.29942f,0.0213591f,0.100469f},{0.297686f,0.037113f,0.100469f}, +{0.312414f,0.014946f,0.100469f},{0.31194f,0.0146009f,0.100469f},{0.296256f,0.0197119f,0.100469f}, +{0.28847f,0.015305f,0.100469f},{0.289055f,0.0153056f,0.100469f},{0.30657f,0.014044f,0.100469f}, +{0.305747f,0.0131454f,0.100469f},{0.303562f,0.0121261f,0.100469f},{0.302345f,0.012073f,0.100469f}, +{0.302534f,0.00545274f,0.100469f},{0.290161f,0.0149467f,0.100469f},{0.295223f,0.0174585f,0.100469f}, +{0.289628f,0.0151842f,0.100469f},{0.286209f,0.0136603f,0.100469f},{0.27258f,0.0243605f,0.100469f}, +{0.286029f,0.013106f,0.100469f},{0.288143f,0.00445857f,0.100469f},{0.269417f,0.0220151f,0.100469f}, +{0.287245f,0.00528144f,0.100469f},{0.297802f,0.00437403f,0.100469f},{0.255403f,0.00112774f,0.100469f}, +{0.254935f,0.0154692f,0.100469f},{0.255016f,0.00132937f,0.100469f},{0.297189f,0.00380587f,0.100469f}, +{0.289162f,0.00227358f,0.100469f},{0.296262f,0.00242058f,0.100469f},{0.288797f,0.00343287f,0.100469f}, +{0.300045f,0.00545321f,0.100469f},{0.282071f,-0.0319552f,0.100469f},{0.28449f,-0.0332908f,0.100469f}, +{0.289216f,0.00105623f,0.100469f},{0.28917f,-5.8201e-009f,0.100469f},{0.28383f,-0.00606509f,0.100469f}, +{0.286209f,-0.0113881f,0.100469f},{0.286501f,-0.010881f,0.100469f},{0.111865f,-0.0139831f,0.100469f}, +{0.291026f,-0.0108798f,0.100469f},{0.269418f,-0.0220158f,0.100469f},{0.281577f,-0.005033f,0.100469f}, +{0.275498f,-0.0269304f,0.100469f},{0.243259f,0.0139831f,0.100469f},{0.243259f,-0.0139831f,0.100469f}, +{0.279848f,1.74344e-017f,0.100469f},{0.295758f,0.000834183f,0.100469f},{0.29594f,0.00165192f,0.100469f}, +{0.27258f,-0.024361f,0.100469f},{0.258757f,-0.016635f,0.100469f},{0.254936f,-0.0154693f,0.100469f}, +{0.279929f,-0.00186868f,0.100469f},{0.28017f,-0.00298716f,0.100469f},{0.253259f,0.000430548f,0.100469f}, +{0.253462f,0.000819718f,0.100469f},{0.247143f,0.0141453f,0.100469f},{0.25105f,-0.0146388f,0.100469f}, +{0.247144f,-0.0141452f,0.100469f},{0.218391f,0.000431293f,0.100469f},{0.218186f,0.000817561f,0.100469f}, +{0.10062f,-0.0177565f,0.100469f},{0.0933567f,0.0303842f,0.100469f},{0.0418875f,0.0816851f,0.100469f}, +{0.0516079f,0.0681943f,0.100469f},{0.0709097f,0.0709097f,0.100469f},{0.0548849f,0.0667435f,0.100469f}, +{0.0564469f,0.0658638f,0.100469f},{-0.0245125f,0.0638136f,0.100469f},{-0.0235109f,0.0956018f,0.100469f}, +{-0.0259491f,0.0648858f,0.100469f},{-0.0185115f,-0.0266927f,0.100469f},{0.0195369f,-0.0252221f,0.100469f}, +{-0.019537f,-0.0252222f,0.100469f},{0.0185112f,-0.0266922f,0.100469f},{0.0548849f,-0.0171549f,0.100469f}, +{0.0175819f,-0.028225f,0.100469f},{-0.0175821f,-0.0282257f,0.100469f},{0.0838367f,0.0816851f,0.100469f}, +{0.0894455f,0.0858243f,0.100469f},{0.0836562f,0.0822403f,0.100469f},{0.092657f,0.0791278f,0.100469f}, +{0.0919114f,0.0814392f,0.100469f},{0.0908383f,0.0836959f,0.100469f},{0.0792292f,0.0831785f,0.100469f}, +{0.079703f,0.0835236f,0.100469f},{0.0768194f,0.0930843f,0.100469f},{0.0829714f,0.0831813f,0.100469f}, +{0.0877597f,0.0877597f,0.100469f},{0.0824989f,0.0835243f,0.100469f},{0.0326272f,0.0932205f,0.100469f}, +{0.0388582f,0.0838826f,0.100469f},{0.0394436f,0.0838832f,0.100469f},{0.0745764f,0.0932205f,0.100469f}, +{0.0783664f,0.0816836f,0.100469f},{0.079125f,0.0926561f,0.100469f},{0.0802367f,0.0837612f,0.100469f}, +{0.0785464f,0.0822379f,0.100469f},{0.0788389f,0.082745f,0.100469f},{0.0808074f,0.0838826f,0.100469f}, +{0.0813929f,0.0838832f,0.100469f},{0.0836927f,0.0908391f,0.100469f},{0.0930856f,0.0768218f,0.100469f}, +{0.0481725f,-0.0146844f,0.100469f},{0.0499065f,-0.0151392f,0.100469f},{-0.0339919f,0.0687593f,0.100469f}, +{-0.0306287f,0.0675214f,0.100469f},{-0.0290135f,0.0667435f,0.100469f},{-0.0969939f,-0.0213822f,0.100469f}, +{-0.0632437f,-0.0238204f,0.100469f},{-0.0620385f,-0.0224931f,0.100469f},{0.0163644f,0.102748f,0.100469f}, +{-0.0163653f,0.102745f,0.100469f},{-0.0177581f,0.100617f,0.100469f},{-0.0218598f,0.0614045f,0.100469f}, +{-0.0213822f,0.0969939f,0.100469f},{-0.0231475f,0.0626516f,0.100469f},{0.0152921f,0.105002f,0.100469f}, +{0.0145474f,0.107316f,0.100469f},{-0.0152921f,0.105002f,0.100469f},{-0.0145465f,0.107313f,0.100469f}, +{0.0141193f,0.109622f,0.100469f},{0.0139831f,0.111865f,0.100469f},{-0.0141179f,0.109619f,0.100469f}, +{-0.0139831f,0.111865f,0.100469f},{-0.00584288f,0.286166f,0.100469f},{-0.0131454f,0.305747f,0.100469f}, +{-0.0147871f,0.290408f,0.100469f},{-0.0143968f,0.290841f,0.100469f},{-0.00348669f,0.305663f,0.100469f}, +{-0.00279621f,0.306133f,0.100469f},{-0.0220151f,0.269417f,0.100469f},{-0.00124367f,0.306742f,0.100469f}, +{7.81291e-017f,0.322729f,0.100469f},{-0.00186868f,0.322648f,0.100469f},{0.0121261f,0.299015f,0.100469f}, +{0.0143937f,0.290844f,0.100469f},{0.0147862f,0.290409f,0.100469f},{0.0106515f,0.290841f,0.100469f}, +{0.0372872f,0.300891f,0.100469f},{0.0371926f,0.303697f,0.100469f},{0.0214407f,0.301289f,0.100469f}, +{0.0111254f,0.291186f,0.100469f},{0.0152591f,0.289348f,0.100469f},{0.0122298f,0.291545f,0.100469f}, +{0.014044f,0.296007f,0.100469f},{0.0131454f,0.29683f,0.100469f},{0.0197119f,0.306322f,0.100469f}, +{0.0324248f,0.319702f,0.100469f},{0.0174585f,0.307354f,0.100469f},{0.0186351f,0.306999f,0.100469f}, +{0.033718f,0.31721f,0.100469f},{0.0116591f,0.316472f,0.100469f},{0.0122298f,0.316594f,0.100469f}, +{0.0150786f,0.314951f,0.100469f},{0.0292931f,0.324357f,0.100469f},{0.0147862f,0.315457f,0.100469f}, +{-0.005033f,0.321f,0.100469f},{0.0269304f,0.275498f,0.100469f},{-0.0147871f,0.315456f,0.100469f}, +{-0.0122331f,0.316594f,0.100469f},{-0.00571052f,0.319924f,0.100469f},{-0.014044f,0.30657f,0.100469f}, +{-0.0213591f,0.29942f,0.100469f},{-0.0214407f,0.301289f,0.100469f},{-0.00409933f,0.305094f,0.100469f}, +{-0.0150796f,0.2899f,0.100469f},{-0.0186351f,0.295578f,0.100469f},{-0.0152596f,0.289346f,0.100469f}, +{-0.00204265f,0.306496f,0.100469f},{-0.0152596f,0.314395f,0.100469f},{-0.0243605f,0.27258f,0.100469f}, +{-5.8201e-009f,0.313407f,0.100469f},{-0.00041711f,0.306866f,0.100469f},{0.000418664f,0.306866f,0.100469f}, +{-0.0111271f,0.291187f,0.100469f},{-0.0116607f,0.291424f,0.100469f},{-0.0121261f,0.303562f,0.100469f}, +{-0.00534833f,0.30294f,0.100469f},{-0.00502626f,0.303709f,0.100469f},{-0.0128186f,0.316594f,0.100469f}, +{-0.0133893f,0.316472f,0.100469f},{0.00528144f,0.315333f,0.100469f},{0.0097888f,0.314395f,0.100469f}, +{-0.00445857f,0.288143f,0.100469f},{-0.00343287f,0.288797f,0.100469f},{-0.00996978f,0.289903f,0.100469f}, +{0.000819963f,0.257072f,0.100469f},{0.0181266f,0.262471f,0.100469f},{0.00298716f,0.28017f,0.100469f}, +{-0.00082033f,0.257077f,0.100469f},{-0.0181265f,0.262471f,0.100469f},{-0.0166349f,0.258757f,0.100469f}, +{-0.00978928f,0.314396f,0.100469f},{-0.305903f,0.00314864f,0.100469f},{0.00559444f,0.338154f,0.100469f}, +{0.00280508f,0.338471f,0.100469f},{0.0046188f,0.304437f,0.100469f},{0.00503626f,0.303713f,0.100469f}, +{0.00553077f,0.302122f,0.100469f},{0.0139213f,0.291187f,0.100469f},{0.0097888f,0.289346f,0.100469f}, +{0.0354896f,0.289845f,0.100469f},{0.0345284f,0.287208f,0.100469f},{0.0154693f,0.254936f,0.100469f}, +{0.0146388f,0.25105f,0.100469f},{0.0320239f,0.282186f,0.100469f},{0.0333708f,0.284649f,0.100469f}, +{-0.0548845f,-0.0171541f,0.100469f},{0.0304957f,0.279831f,0.100469f},{0.0013304f,0.256376f,0.100469f}, +{-0.00132352f,0.256375f,0.100469f},{-0.00112134f,0.256764f,0.100469f},{-0.0154692f,0.254935f,0.100469f}, +{-0.0141453f,0.247143f,0.100469f},{0.0139831f,0.243259f,0.100469f},{0.016635f,0.258757f,0.100469f}, +{0.0141452f,0.247144f,0.100469f},{0.00112493f,0.256762f,0.100469f},{-0.0139831f,0.243259f,0.100469f}, +{-0.00082033f,0.219789f,0.100469f},{-0.000431051f,0.219987f,0.100469f},{0.0177565f,0.10062f,0.100469f}, +{-0.0194438f,0.0986812f,0.100469f},{0.0194438f,0.0986812f,0.100469f},{-0.0357259f,0.069214f,0.100469f}, +{-0.0322905f,0.0681943f,0.100469f},{-0.0306287f,-0.016377f,0.100469f},{-0.0322905f,-0.0157041f,0.100469f}, +{-0.0339919f,-0.0151392f,0.100469f},{-0.0671457f,-0.0298143f,0.100469f},{-0.0663166f,-0.028225f,0.100469f}, +{-0.0937848f,-0.0280785f,0.100469f},{-0.0532694f,-0.0163764f,0.100469f},{-0.0516077f,-0.0157037f,0.100469f}, +{-0.0877597f,0.0877597f,0.100469f},{-0.0829744f,0.0831785f,0.100469f},{-0.0825006f,0.0835236f,0.100469f}, +{-0.0919114f,0.0814392f,0.100469f},{-0.0926561f,0.079125f,0.100469f},{-0.0930843f,0.0768194f,0.100469f}, +{-0.0932205f,0.0745764f,0.100469f},{-0.0908391f,0.0836927f,0.100469f},{-0.0838372f,0.0816836f,0.100469f}, +{-0.089447f,0.0858213f,0.100469f},{-0.0836572f,0.0822379f,0.100469f},{-0.0819669f,0.0837612f,0.100469f}, +{-0.0836959f,0.0908383f,0.100469f},{-0.0858243f,0.0894455f,0.100469f},{-0.0932205f,0.0326272f,0.100469f}, +{-0.0933553f,0.0303817f,0.100469f},{-0.0814392f,0.0919114f,0.100469f},{-0.0813962f,0.0838826f,0.100469f}, +{-0.0808108f,0.0838832f,0.100469f},{-0.0696868f,0.0455262f,0.100469f},{-0.0694022f,0.0472966f,0.100469f}, +{-0.0797047f,0.0835243f,0.100469f},{-0.0791278f,0.092657f,0.100469f},{-0.0802383f,0.0837618f,0.100469f}, +{-0.0579489f,-0.0190117f,0.100469f},{-0.0593856f,-0.0200839f,0.100469f},{-0.0956018f,-0.0235109f,0.100469f}, +{-0.0643615f,-0.0252221f,0.100469f},{-0.0933567f,-0.0303842f,0.100469f},{-0.0678671f,-0.0314549f,0.100469f}, +{-0.105002f,-0.0152921f,0.100469f},{-0.102745f,-0.0163653f,0.100469f},{-0.102748f,0.0163644f,0.100469f}, +{-0.100617f,-0.0177581f,0.100469f},{-0.10062f,0.0177565f,0.100469f},{-0.109622f,0.0141193f,0.100469f}, +{-0.105002f,0.0152921f,0.100469f},{-0.111865f,0.0139831f,0.100469f},{-0.111865f,-0.0139831f,0.100469f}, +{-0.254936f,0.0154693f,0.100469f},{-0.258757f,0.016635f,0.100469f},{-0.255403f,0.00113282f,0.100469f}, +{-0.247143f,-0.0141453f,0.100469f},{-0.316411f,0.00584288f,0.100469f},{-0.322648f,-0.00186868f,0.100469f}, +{-0.322407f,-0.00298716f,0.100469f},{-0.321f,-0.005033f,0.100469f},{-0.304775f,0.00437403f,0.100469f}, +{-0.305388f,0.00380587f,0.100469f},{-0.304085f,0.00484444f,0.100469f},{-0.336897f,0.0110628f,0.100469f}, +{-0.335964f,0.0137103f,0.100469f},{-0.303331f,0.00520701f,0.100469f},{-0.315212f,0.014946f,0.100469f}, +{-0.326496f,0.0274755f,0.100469f},{-0.315685f,0.0146009f,0.100469f},{-0.314107f,0.015305f,0.100469f}, +{-0.319702f,0.0324248f,0.100469f},{-0.314678f,0.0151836f,0.100469f},{-0.313522f,0.0153056f,0.100469f}, +{-0.306999f,0.0186351f,0.100469f},{-0.306322f,0.0197119f,0.100469f},{-0.311551f,-0.0108798f,0.100469f}, +{-0.311943f,-0.0104447f,0.100469f},{-0.311258f,-0.0113857f,0.100469f},{-0.305747f,-0.0131454f,0.100469f}, +{-0.311943f,0.0146037f,0.100469f},{-0.307354f,0.0174585f,0.100469f},{-0.312416f,0.0149467f,0.100469f}, +{-0.289059f,0.015305f,0.100469f},{-0.289629f,0.0151836f,0.100469f},{-0.307131f,-0.0151227f,0.100469f}, +{-0.269417f,-0.0220151f,0.100469f},{-0.290637f,-0.0104475f,0.100469f},{-0.262471f,-0.0181265f,0.100469f}, +{-0.266037f,-0.0199275f,0.100469f},{-0.302345f,-0.012073f,0.100469f},{-0.303562f,-0.0121261f,0.100469f}, +{-0.295758f,0.000833312f,0.100469f},{-0.290163f,-0.0101024f,0.100469f},{-0.295946f,0.00164777f,0.100469f}, +{-0.262471f,0.0181266f,0.100469f},{-0.266037f,0.019928f,0.100469f},{-0.28017f,0.00298716f,0.100469f}, +{-0.28383f,0.00606509f,0.100469f},{-0.282653f,0.00571052f,0.100469f},{-0.287367f,-0.0101017f,0.100469f}, +{-0.286895f,-0.0104447f,0.100469f},{-0.287245f,-0.00528144f,0.100469f},{-0.288143f,-0.00445857f,0.100469f}, +{-0.289059f,-0.0097434f,0.100469f},{-0.269418f,0.0220158f,0.100469f},{-0.281577f,0.005033f,0.100469f}, +{-0.258757f,-0.0166349f,0.100469f},{-0.255704f,0.000819718f,0.100469f},{-0.255906f,0.000430548f,0.100469f}, +{-0.25105f,0.0146388f,0.100469f},{-0.254583f,0.00139831f,0.100469f},{-0.255014f,0.00133028f,0.100469f}, +{-0.243259f,0.0139831f,0.100469f},{-0.253253f,0.000431293f,0.100469f},{-0.216628f,0.00132937f,0.100469f}, +{-0.216241f,0.00112774f,0.100469f},{-0.0986812f,0.0194438f,0.100469f},{-0.0945295f,-0.0257644f,0.100469f}, +{-0.0653872f,-0.0266922f,0.100469f},{-0.0986812f,-0.0194438f,0.100469f},{-0.0684765f,-0.0331407f,0.100469f}, +{-0.0464123f,-0.0143415f,0.100469f},{-0.048172f,-0.0146841f,0.100469f},{-0.0698583f,-0.040157f,0.100469f}, +{0.0235109f,-0.0956018f,0.100469f},{-0.0908383f,-0.0836959f,0.100469f},{-0.0894455f,-0.0858243f,0.100469f}, +{0.0257644f,-0.0945295f,0.100469f},{0.0388582f,-0.078321f,0.100469f},{0.0410221f,-0.0790223f,0.100469f}, +{0.0303842f,-0.0933567f,0.100469f},{-0.0235077f,-0.0956027f,0.100469f},{-0.0257644f,-0.0945295f,0.100469f}, +{-0.0280757f,-0.0937839f,0.100469f},{-0.0364177f,-0.0805185f,0.100469f},{-0.037283f,-0.0790223f,0.100469f}, +{-0.0388615f,-0.0783204f,0.100469f},{-0.039447f,-0.078321f,0.100469f},{-0.0382891f,-0.0784418f,0.100469f}, +{-0.0377555f,-0.0786793f,0.100469f},{-0.0414155f,-0.0794586f,0.100469f},{-0.0405514f,-0.07868f,0.100469f}, +{-0.0400177f,-0.0784424f,0.100469f},{-0.041708f,-0.0799657f,0.100469f},{-0.0578584f,-0.0805185f,0.100469f}, +{-0.0580389f,-0.0799633f,0.100469f},{-0.0587238f,-0.0790223f,0.100469f},{-0.0591962f,-0.0786793f,0.100469f}, +{-0.0583313f,-0.0794574f,0.100469f},{-0.0614584f,-0.0784424f,0.100469f},{-0.0608877f,-0.078321f,0.100469f}, +{-0.0603023f,-0.0783204f,0.100469f},{-0.0597298f,-0.0784418f,0.100469f},{-0.0624659f,-0.0790251f,0.100469f}, +{-0.0619921f,-0.07868f,0.100469f},{-0.0814392f,-0.0919114f,0.100469f},{-0.0836927f,-0.0908391f,0.100469f}, +{-0.0689986f,-0.0348554f,0.100469f},{-0.0607507f,-0.021246f,0.100469f},{-0.0564465f,-0.0180338f,0.100469f}, +{-0.0499063f,-0.0151388f,0.100469f},{-0.0428452f,-0.0139974f,0.100469f},{-0.0357259f,-0.0146844f,0.100469f}, +{-0.0392635f,-0.0141124f,0.100469f},{0.0306291f,-0.0163764f,0.100469f},{-0.0653872f,0.0572063f,0.100469f}, +{-0.0326272f,0.0932205f,0.100469f},{-0.0377555f,0.0835243f,0.100469f},{-0.037283f,0.0831813f,0.100469f}, +{0.0290139f,-0.0171541f,0.100469f},{0.0306291f,0.0675221f,0.100469f},{0.0290139f,0.0667443f,0.100469f}, +{-0.0365982f,0.0822403f,0.100469f},{-0.0364177f,0.0816851f,0.100469f},{-0.0303842f,0.0933567f,0.100469f}, +{0.0374861f,-0.0143415f,0.100469f},{-0.0257644f,0.0945295f,0.100469f},{-0.0280785f,0.0937848f,0.100469f}, +{0.0322907f,-0.0157037f,0.100469f},{0.0245128f,-0.0200839f,0.100469f},{0.0206547f,-0.0238204f,0.100469f}, +{-0.0154086f,-0.033137f,0.100469f},{0.0160313f,-0.0314549f,0.100469f},{-0.0148988f,-0.034856f,0.100469f}, +{0.0154219f,-0.0331407f,0.100469f},{0.0148999f,-0.0348554f,0.100469f},{0.0140401f,-0.040157f,0.100469f}, +{0.0142116f,-0.0383722f,0.100469f},{-0.0140402f,-0.0401574f,0.100469f},{0.0937848f,0.0280785f,0.100469f}, +{0.0956018f,0.0235109f,0.100469f},{0.0632438f,-0.0238208f,0.100469f},{0.0643614f,-0.0252222f,0.100469f}, +{0.0956027f,-0.0235077f,0.100469f},{0.0802367f,-0.0784424f,0.100469f},{0.0788389f,-0.0794586f,0.100469f}, +{0.0785464f,-0.0799657f,0.100469f},{0.0792292f,-0.0790251f,0.100469f},{0.0783664f,-0.08052f,0.100469f}, +{0.0791278f,-0.092657f,0.100469f},{0.0418875f,-0.0805185f,0.100469f},{0.0414146f,-0.0794574f,0.100469f}, +{0.041707f,-0.0799633f,0.100469f},{0.0394436f,-0.0783204f,0.100469f},{0.0400161f,-0.0784418f,0.100469f}, +{0.0365972f,-0.0799657f,0.100469f},{0.0368897f,-0.0794586f,0.100469f},{0.0326272f,-0.0932205f,0.100469f}, +{0.0280785f,-0.0937848f,0.100469f},{0.0945295f,0.0257644f,0.100469f},{0.0322907f,0.0681947f,0.100469f}, +{-0.0245125f,-0.0200848f,0.100469f},{-0.0206546f,-0.0238208f,0.100469f},{0.0218599f,-0.0224931f,0.100469f}, +{0.0231477f,-0.021246f,0.100469f},{-0.0218598f,-0.0224939f,0.100469f},{0.0274519f,-0.0180338f,0.100469f}, +{0.0357264f,-0.0146841f,0.100469f},{0.0392642f,-0.0141123f,0.100469f},{0.0410532f,-0.0139974f,0.100469f}, +{-0.0446342f,0.0697861f,0.100469f},{0.0428459f,-0.0139975f,0.100469f},{0.0678699f,0.0524438f,0.100469f}, +{0.0932205f,0.0745764f,0.100469f},{0.0374861f,0.069557f,0.100469f},{0.0357264f,0.0692143f,0.100469f}, +{0.0428459f,0.069901f,0.100469f},{0.0446349f,0.0697861f,0.100469f},{0.0392642f,0.0697861f,0.100469f}, +{0.0579493f,-0.0190126f,0.100469f},{0.0410532f,0.069901f,0.100469f},{0.0593859f,-0.0200848f,0.100469f}, +{0.0607509f,-0.0212468f,0.100469f},{0.0969939f,0.0213822f,0.100469f},{0.0620386f,-0.0224939f,0.100469f}, +{0.0969955f,-0.0213792f,0.100469f},{0.0653869f,-0.0266927f,0.100469f},{0.0945295f,-0.0257644f,0.100469f}, +{0.0678699f,-0.0314546f,0.100469f},{0.0933553f,-0.0303817f,0.100469f},{0.0684898f,-0.033137f,0.100469f}, +{0.0689996f,-0.034856f,0.100469f},{0.0696843f,-0.0383731f,0.100469f},{0.069398f,-0.0366037f,0.100469f}, +{0.0698582f,-0.0401574f,0.100469f},{0.0097888f,-0.313231f,0.100469f},{-3.0178e-017f,-0.279848f,0.100469f}, +{-0.0213591f,-0.303157f,0.100469f},{-0.0369236f,-0.30649f,0.100469f},{-0.0211188f,-0.304276f,0.100469f}, +{0.00606509f,-0.318747f,0.100469f},{-0.0106546f,-0.311733f,0.100469f},{-0.0162807f,-0.334834f,0.100469f}, +{-0.0205678f,-0.305373f,0.100469f},{-0.0357252f,-0.311971f,0.100469f},{-0.0348202f,-0.314629f,0.100469f}, +{-0.014044f,-0.296007f,0.100469f},{0.00227358f,-0.289162f,0.100469f},{0.00105623f,-0.289216f,0.100469f}, +{0.00124497f,-0.295836f,0.100469f},{-0.00279621f,-0.296444f,0.100469f},{-0.0362494f,-0.292548f,0.100469f}, +{-0.0368049f,-0.295301f,0.100469f},{-0.00204265f,-0.296082f,0.100469f},{-0.0345284f,-0.287208f,0.100469f}, +{-0.0354896f,-0.289845f,0.100469f},{0.000418664f,-0.295711f,0.100469f},{-5.8201e-009f,-0.28917f,0.100469f}, +{-0.0150796f,-0.287628f,0.100469f},{-0.0287947f,-0.277597f,0.100469f},{-0.0304957f,-0.279831f,0.100469f}, +{0.00348695f,-0.296916f,0.100469f},{0.00343287f,-0.288797f,0.100469f},{0.002796f,-0.296445f,0.100469f}, +{0.0181265f,-0.262471f,0.100469f},{-0.0143968f,-0.286688f,0.100469f},{-0.013923f,-0.286343f,0.100469f}, +{-0.024361f,-0.27258f,0.100469f},{-0.00298716f,-0.28017f,0.100469f},{-0.0181266f,-0.262471f,0.100469f}, +{0.00553077f,-0.300455f,0.100469f},{0.0143937f,-0.286685f,0.100469f},{0.0243605f,-0.27258f,0.100469f}, +{0.0150786f,-0.287626f,0.100469f},{0.0152591f,-0.288181f,0.100469f},{0.0124916f,-0.304721f,0.100469f}, +{0.306819f,0.000833312f,0.100469f},{0.295578f,0.0186351f,0.100469f},{0.306999f,-0.0186351f,0.100469f}, +{0.291319f,-0.0113857f,0.100469f},{0.29683f,-0.0131454f,0.100469f},{0.297687f,-0.0371146f,0.100469f}, +{0.294949f,-0.0367459f,0.100469f},{0.287899f,-0.00986481f,0.100469f},{0.287366f,-0.0101024f,0.100469f}, +{0.289628f,-0.00986419f,0.100469f},{0.290161f,-0.0101017f,0.100469f},{0.289591f,-0.0354067f,0.100469f}, +{0.292245f,-0.036175f,0.100469f},{0.287001f,-0.0344436f,0.100469f},{0.258757f,0.0166349f,0.100469f}, +{0.255708f,0.000817561f,0.100469f},{0.262471f,0.0181265f,0.100469f},{0.254152f,0.00133028f,0.100469f}, +{0.251049f,0.0146388f,0.100469f},{0.253763f,0.00113282f,0.100469f},{0.266037f,0.0199275f,0.100469f}, +{0.286166f,0.00584288f,0.100469f},{0.287899f,0.0151836f,0.100469f},{0.282071f,0.0319538f,0.100469f}, +{0.279758f,0.0304433f,0.100469f},{0.311077f,0.013106f,0.100469f},{0.28449f,0.0332889f,0.100469f}, +{0.287001f,0.0344412f,0.100469f},{0.304776f,0.0043727f,0.100469f},{0.304721f,0.0124916f,0.100469f}, +{0.304085f,0.00484368f,0.100469f},{0.297204f,0.0205678f,0.100469f},{0.298301f,0.0211188f,0.100469f}, +{0.292244f,0.0361745f,0.100469f},{0.312948f,0.0151836f,0.100469f},{0.313518f,0.015305f,0.100469f}, +{0.300444f,0.0372784f,0.100469f},{0.314002f,0.035054f,0.100469f},{0.311371f,0.0358991f,0.100469f}, +{0.319038f,0.0327925f,0.100469f},{0.316562f,0.0340166f,0.100469f},{0.306631f,0.00164777f,0.100469f}, +{0.316367f,0.0136627f,0.100469f},{0.316548f,0.0131075f,0.100469f},{0.331419f,0.0219685f,0.100469f}, +{0.332963f,0.0196768f,0.100469f},{0.31378f,-0.00343287f,0.100469f},{0.318747f,0.00606509f,0.100469f}, +{0.00606509f,0.28383f,0.100469f},{0.0139213f,0.316235f,0.100469f},{0.0233817f,0.330334f,0.100469f}, +{0.0133877f,0.316473f,0.100469f},{0.00124497f,0.306741f,0.100469f},{0.00227358f,0.313415f,0.100469f}, +{0.00105623f,0.313362f,0.100469f},{-0.00105623f,0.289216f,0.100469f},{-0.00227358f,0.289162f,0.100469f}, +{0.0287947f,0.277597f,0.100469f},{-0.0106546f,0.290844f,0.100469f},{-0.0197119f,0.296256f,0.100469f}, +{-0.0211188f,0.298301f,0.100469f},{-0.0143968f,0.315889f,0.100469f},{-0.013923f,0.316235f,0.100469f}, +{-0.00606509f,0.318747f,0.100469f},{-0.0116607f,0.316473f,0.100469f},{-0.0111271f,0.316235f,0.100469f}, +{0.00445857f,0.314434f,0.100469f},{-0.0106546f,0.315892f,0.100469f},{-0.0102622f,0.315457f,0.100469f}, +{0.00343287f,0.31378f,0.100469f},{-0.00408405f,0.321856f,0.100469f},{-0.00298716f,0.322407f,0.100469f}, +{0.0110628f,0.336897f,0.100469f},{0.00835238f,0.337628f,0.100469f},{0.0187591f,0.333514f,0.100469f}, +{0.0128153f,0.316594f,0.100469f},{0.0309477f,0.322089f,0.100469f},{0.0152591f,0.314396f,0.100469f}, +{0.0124916f,0.297856f,0.100469f},{0.0205678f,0.305373f,0.100469f},{0.0357252f,0.311971f,0.100469f}, +{0.0348202f,0.314629f,0.100469f},{-0.296256f,-0.0197119f,0.100469f},{-0.300232f,0.012073f,0.100469f}, +{-0.300044f,0.00545274f,0.100469f},{-0.299015f,0.0121261f,0.100469f},{-0.295578f,-0.0186351f,0.100469f}, +{-0.298301f,-0.0211188f,0.100469f},{-0.297204f,-0.0205678f,0.100469f},{-0.316076f,-0.010881f,0.100469f}, +{-0.315685f,-0.0104475f,0.100469f},{-0.318747f,-0.00606509f,0.100469f},{-0.316368f,-0.0113881f,0.100469f}, +{-0.322729f,1.62449e-016f,0.100469f},{-0.337628f,0.00835238f,0.100469f},{-0.338154f,0.00559444f,0.100469f}, +{-0.316548f,0.013106f,0.100469f},{-0.333514f,0.0187591f,0.100469f},{-0.328493f,0.0255017f,0.100469f}, +{-0.330334f,0.0233817f,0.100469f},{-0.316076f,0.0141674f,0.100469f},{-0.324357f,0.0292931f,0.100469f}, +{-0.311551f,0.0141686f,0.100469f},{-0.291027f,0.0141674f,0.100469f},{-0.290637f,0.0146009f,0.100469f}, +{-0.296007f,0.014044f,0.100469f},{-0.299245f,0.00520628f,0.100469f},{-0.30649f,0.0369236f,0.100469f}, +{-0.309253f,0.0364276f,0.100469f},{-0.304276f,0.0211188f,0.100469f},{-0.303697f,0.0371926f,0.100469f}, +{-0.301289f,0.0214407f,0.100469f},{-0.300891f,0.0372872f,0.100469f},{-0.298087f,0.0371512f,0.100469f}, +{-0.295301f,0.0368049f,0.100469f},{-0.287208f,0.0345284f,0.100469f},{-0.289845f,0.0354896f,0.100469f}, +{-0.286895f,0.0146037f,0.100469f},{-0.275498f,0.0269304f,0.100469f},{-0.277597f,0.0287947f,0.100469f}, +{-0.282186f,0.0320239f,0.100469f},{-0.288473f,0.0153056f,0.100469f},{-0.287901f,0.0151842f,0.100469f}, +{-0.288797f,-0.00343287f,0.100469f},{-0.289162f,-0.00227358f,0.100469f},{-0.27258f,0.024361f,0.100469f}, +{-0.28621f,0.0136627f,0.100469f},{-0.286029f,0.0131075f,0.100469f},{-0.286029f,-0.0119409f,0.100469f}, +{-0.28621f,-0.0113857f,0.100469f},{0.255913f,0.000431293f,0.100469f},{0.279758f,-0.0304444f,0.100469f}, +{0.280721f,-0.00408405f,0.100469f},{0.266037f,-0.019928f,0.100469f},{0.262471f,-0.0181266f,0.100469f}, +{0.254583f,0.00139831f,0.100469f},{0.299246f,0.00520701f,0.100469f},{0.300871f,0.00557763f,0.100469f}, +{0.301707f,0.00557747f,0.100469f},{0.301289f,0.0121187f,0.100469f},{0.296674f,0.00314864f,0.100469f}, +{0.277562f,0.0287659f,0.100469f},{0.287366f,0.014946f,0.100469f},{0.275498f,0.0269304f,0.100469f}, +{0.286501f,0.0141674f,0.100469f},{0.286892f,0.0146009f,0.100469f},{0.289055f,-0.00974281f,0.100469f}, +{0.290634f,-0.0104447f,0.100469f},{0.300445f,-0.0372813f,0.100469f},{0.303207f,-0.0372145f,0.100469f}, +{0.282653f,-0.00571052f,0.100469f},{0.286029f,-0.0119424f,0.100469f},{-0.041888f,-0.08052f,0.100469f}, +{-0.0410252f,-0.0790251f,0.100469f},{-0.0930856f,-0.0768218f,0.100469f},{-0.0919114f,-0.0814392f,0.100469f}, +{-0.092657f,-0.0791278f,0.100469f},{0.0808074f,-0.078321f,0.100469f},{0.079703f,-0.07868f,0.100469f}, +{0.0824989f,-0.0786793f,0.100469f},{0.0930843f,-0.0768194f,0.100469f},{0.0814392f,0.0919114f,0.100469f}, +{0.0632438f,0.0600777f,0.100469f},{0.0643614f,0.0586762f,0.100469f},{0.0653869f,0.0572057f,0.100469f}, +{0.0663164f,0.0556727f,0.100469f},{0.0464129f,0.0695568f,0.100469f},{0.0481725f,0.069214f,0.100469f}, +{0.0499065f,0.0687593f,0.100469f},{0.0819653f,0.0837618f,0.100469f},{0.0858213f,0.089447f,0.100469f}, +{0.0833638f,0.0827462f,0.100469f},{-0.0689986f,0.0490431f,0.100469f},{-0.0684765f,0.0507578f,0.100469f}, +{-0.0833647f,0.082745f,0.100469f},{-0.0698583f,0.0437414f,0.100469f},{-0.041888f,0.0816836f,0.100469f}, +{-0.0516077f,0.0681947f,0.100469f},{-0.0969955f,0.0213792f,0.100469f},{-0.0499063f,0.0687596f,0.100469f}, +{-0.0937839f,0.0280757f,0.100469f},{-0.0768218f,0.0930856f,0.100469f},{-0.0745764f,0.0932205f,0.100469f}, +{-0.0792323f,0.0831813f,0.100469f},{-0.0785474f,0.0822403f,0.100469f},{-0.0788398f,0.0827462f,0.100469f}, +{-0.0783669f,0.0816851f,0.100469f},{-0.0410252f,0.0831785f,0.100469f},{-0.0405514f,0.0835236f,0.100469f}, +{-0.0290135f,-0.0171549f,0.100469f},{-0.0620385f,0.0614053f,0.100469f},{-0.0632437f,0.0600781f,0.100469f}, +{-0.0607507f,0.0626525f,0.100469f},{-0.0593856f,0.0638145f,0.100469f},{-0.0579489f,0.0648867f,0.100469f}, +{-0.0564465f,0.0658647f,0.100469f},{-0.041708f,0.0822379f,0.100469f},{-0.0548845f,0.0667443f,0.100469f}, +{-0.0532694f,0.0675221f,0.100469f},{-0.0414155f,0.082745f,0.100469f},{-0.0400177f,0.0837612f,0.100469f}, +{-0.0388615f,0.0838832f,0.100469f},{-0.039447f,0.0838826f,0.100469f},{-0.0382891f,0.0837618f,0.100469f}, +{-0.0368906f,0.0827462f,0.100469f},{0.0257644f,0.0945295f,0.100469f},{0.0280757f,0.0937839f,0.100469f}, +{0.0303817f,0.0933553f,0.100469f},{0.0364172f,0.0816836f,0.100469f},{0.0564469f,-0.0180347f,0.100469f}, +{0.0532697f,-0.016377f,0.100469f},{0.0516079f,-0.0157041f,0.100469f},{0.0446349f,-0.0141124f,0.100469f}, +{0.0259495f,0.0648867f,0.100469f},{0.0235077f,0.0956027f,0.100469f},{-0.0231475f,-0.0212468f,0.100469f}, +{0.0245128f,0.0638145f,0.100469f},{0.0365972f,0.0822379f,0.100469f},{0.0368897f,0.082745f,0.100469f}, +{0.0372799f,0.0831785f,0.100469f},{0.0382875f,0.0837612f,0.100469f},{0.0377538f,0.0835236f,0.100469f}, +{0.0400161f,0.0837618f,0.100469f},{0.0405497f,0.0835243f,0.100469f},{0.0414146f,0.0827462f,0.100469f}, +{0.0410221f,0.0831813f,0.100469f},{0.041707f,0.0822403f,0.100469f},{-0.0303817f,-0.0933553f,0.100469f}, +{0.0377538f,-0.07868f,0.100469f},{0.0382875f,-0.0784424f,0.100469f},{0.0405497f,-0.0786793f,0.100469f}, +{0.0339921f,0.0687596f,0.100469f},{0.0464129f,-0.0143416f,0.100469f},{0.0274519f,0.0658647f,0.100469f}, +{0.0339921f,-0.0151388f,0.100469f},{0.0259495f,-0.0190117f,0.100469f},{0.0213792f,0.0969955f,0.100469f}, +{0.0231477f,0.0626525f,0.100469f},{-0.0142141f,0.0455253f,0.100469f},{-0.0140402f,0.043741f,0.100469f}, +{0.0142116f,0.0455262f,0.100469f},{0.0140401f,0.0437414f,0.100469f},{0.0144962f,0.0472966f,0.100469f}, +{0.0148999f,0.0490431f,0.100469f},{-0.0145004f,0.0472947f,0.100469f},{-0.0410525f,0.069901f,0.100469f}, +{-0.0428452f,0.069901f,0.100469f},{-0.0392635f,0.0697861f,0.100469f},{0.0154219f,0.0507578f,0.100469f}, +{0.0160313f,0.0524435f,0.100469f},{-0.0154086f,0.0507615f,0.100469f},{-0.0167532f,0.0540833f,0.100469f}, +{-0.0160285f,0.0524438f,0.100469f},{0.0167528f,0.0540841f,0.100469f},{-0.0374855f,0.0695568f,0.100469f}, +{0.0185112f,0.0572063f,0.100469f},{-0.0185115f,0.0572057f,0.100469f},{-0.0175821f,0.0556727f,0.100469f}, +{0.0206547f,0.0600781f,0.100469f},{-0.0206546f,0.0600777f,0.100469f},{-0.019537f,0.0586762f,0.100469f}, +{-0.0274515f,0.0658638f,0.100469f},{0.0218599f,0.0614053f,0.100469f},{0.0532697f,0.0675214f,0.100469f}, +{0.0579493f,0.0648858f,0.100469f},{0.0593859f,0.0638136f,0.100469f},{0.0607509f,0.0626516f,0.100469f}, +{0.0620386f,0.0614045f,0.100469f},{0.0671452f,0.0540833f,0.100469f},{0.0684898f,0.0507615f,0.100469f}, +{0.0689996f,0.0490425f,0.100469f},{0.0696843f,0.0455253f,0.100469f},{0.069398f,0.0472947f,0.100469f}, +{0.0698582f,0.043741f,0.100469f},{-0.048172f,0.0692143f,0.100469f},{-0.0464123f,0.069557f,0.100469f}, +{-0.0374855f,-0.0143416f,0.100469f},{-0.0410525f,-0.0139975f,0.100469f},{-0.0446342f,-0.0141123f,0.100469f}, +{-0.0956027f,0.0235077f,0.100469f},{-0.0945295f,0.0257644f,0.100469f},{-0.0678671f,0.0524435f,0.100469f}, +{-0.0671457f,0.0540841f,0.100469f},{-0.0663166f,0.0556734f,0.100469f},{-0.0643615f,0.0586764f,0.100469f}, +{0.0195369f,0.0586764f,0.100469f},{0.0175819f,0.0556734f,0.100469f},{-0.0148988f,0.0490425f,0.100469f}, +{-0.243259f,-0.0139831f,0.100469f},{-0.218182f,0.000819718f,0.100469f},{-0.218384f,0.000430548f,0.100469f}, +{-0.217492f,0.00133028f,0.100469f},{-0.217881f,0.00113282f,0.100469f},{-0.217061f,0.00139831f,0.100469f}, +{-0.215936f,0.000817561f,0.100469f},{-0.215731f,0.000431293f,0.100469f},{-0.00112134f,-0.217837f,0.100469f}, +{-0.00082033f,-0.217524f,0.100469f},{-0.000431051f,-0.217326f,0.100469f},{3.14109e-017f,-0.217258f,0.100469f}, +{0.000819963f,-0.217529f,0.100469f},{0.000433147f,-0.217327f,0.100469f},{0.0013304f,-0.218225f,0.100469f}, +{0.00112493f,-0.217839f,0.100469f},{-0.016635f,-0.258757f,0.100469f},{-0.005033f,-0.281577f,0.100469f}, +{-0.0128186f,-0.285984f,0.100469f},{-0.0122331f,-0.285983f,0.100469f},{-0.0141452f,-0.247144f,0.100469f}, +{-0.00082033f,-0.254812f,0.100469f},{0.0106515f,-0.286688f,0.100469f},{0.00204334f,-0.296082f,0.100469f}, +{-0.00186868f,-0.279929f,0.100469f},{0.00445857f,-0.288143f,0.100469f},{-0.00408405f,-0.280721f,0.100469f}, +{-0.019928f,-0.266037f,0.100469f},{-0.00112134f,0.219476f,0.100469f},{-0.00132352f,0.219087f,0.100469f}, +{2.64296e-017f,0.220055f,0.100469f},{0.000819963f,0.219784f,0.100469f},{0.000433147f,0.219986f,0.100469f}, +{0.0013304f,0.219088f,0.100469f},{0.00112493f,0.219474f,0.100469f},{-0.0146388f,0.251049f,0.100469f}, +{0.019928f,0.266037f,0.100469f},{0.00408405f,0.280721f,0.100469f},{0.000433147f,0.257274f,0.100469f}, +{0.00186868f,0.279929f,0.100469f},{2.76524e-017f,0.257343f,0.100469f},{-0.000431051f,0.257275f,0.100469f}, +{0.005033f,0.281577f,0.100469f},{0.0220158f,0.269418f,0.100469f},{0.21663f,0.00133028f,0.100469f}, +{0.217061f,0.00139831f,0.100469f},{0.21594f,0.000819718f,0.100469f},{0.215737f,0.000430548f,0.100469f}, +{0.216241f,0.00113282f,0.100469f},{0.217881f,0.00112774f,0.100469f},{0.217494f,0.00132937f,0.100469f}, +{-0.254935f,-0.0154692f,0.100469f},{-0.251049f,-0.0146388f,0.100469f},{-0.25415f,0.00132937f,0.100469f}, +{-0.253763f,0.00112774f,0.100469f},{-0.247144f,0.0141452f,0.100469f},{-0.253458f,0.000817561f,0.100469f}, +{0.00996883f,-0.312677f,0.100469f},{0.0102613f,-0.312169f,0.100469f},{0.0116591f,-0.311153f,0.100469f}, +{0.0128153f,-0.311031f,0.100469f},{0.0151227f,-0.307131f,0.100469f},{0.0205678f,-0.297204f,0.100469f}, +{0.0211188f,-0.298301f,0.100469f},{0.00534277f,-0.299641f,0.100469f},{0.0150786f,-0.312674f,0.100469f}, +{0.012073f,-0.302345f,0.100469f},{0.0121187f,-0.301289f,0.100469f},{0.00528144f,-0.287245f,0.100469f}, +{0.0097888f,-0.288183f,0.100469f},{-0.0102622f,-0.28712f,0.100469f},{-0.00996978f,-0.287626f,0.100469f}, +{-0.0116607f,-0.286104f,0.100469f},{-0.00606509f,-0.28383f,0.100469f},{-0.00571052f,-0.282653f,0.100469f}, +{-0.0220158f,-0.269418f,0.100469f},{-0.0133893f,-0.286105f,0.100469f},{0.0133877f,-0.286104f,0.100469f}, +{0.0220151f,-0.269417f,0.100469f},{0.0128153f,-0.285983f,0.100469f},{0.0199275f,-0.266037f,0.100469f}, +{0.0139213f,-0.286342f,0.100469f},{-0.0320239f,-0.282186f,0.100469f},{-0.0152596f,-0.288183f,0.100469f}, +{-0.0147871f,-0.312169f,0.100469f},{-0.0143968f,-0.311736f,0.100469f},{-0.0150796f,-0.312677f,0.100469f}, +{-0.0174585f,-0.307354f,0.100469f},{-0.0186351f,-0.306999f,0.100469f},{-0.0364276f,-0.309253f,0.100469f}, +{-0.0371512f,-0.298087f,0.100469f},{-0.0333708f,-0.284649f,0.100469f},{-0.0147871f,-0.287121f,0.100469f}, +{-0.0269304f,-0.275498f,0.100469f},{-0.0111271f,-0.286342f,0.100469f},{-0.0106546f,-0.286685f,0.100469f}, +{0.0116591f,-0.286105f,0.100469f},{0.0111254f,-0.286343f,0.100469f},{-0.00978928f,-0.288181f,0.100469f}, +{-0.0137103f,-0.335964f,0.100469f},{-0.00280508f,-0.338471f,0.100469f},{-0.00559444f,-0.338154f,0.100469f}, +{-0.0152596f,-0.313231f,0.100469f},{-0.0197119f,-0.306322f,0.100469f},{-0.033718f,-0.31721f,0.100469f}, +{-0.013923f,-0.311391f,0.100469f},{-0.0133893f,-0.311153f,0.100469f},{-0.0122331f,-0.311031f,0.100469f}, +{-0.0128186f,-0.311032f,0.100469f},{-0.012073f,-0.300232f,0.100469f},{-0.0121187f,-0.301289f,0.100469f}, +{-0.00978928f,-0.313229f,0.100469f},{-0.00528144f,-0.315333f,0.100469f},{0.301289f,-0.0121187f,0.100469f}, +{0.316563f,-0.0340163f,0.100469f},{0.311077f,-0.0119424f,0.100469f},{0.311257f,-0.0113881f,0.100469f}, +{0.31155f,-0.010881f,0.100469f},{0.312948f,-0.00986481f,0.100469f},{0.314104f,-0.00974281f,0.100469f}, +{0.316411f,-0.00584288f,0.100469f},{0.316548f,-0.0119409f,0.100469f},{0.338346f,-0.00413651f,0.100469f}, +{0.308687f,-0.036547f,0.100469f},{0.304276f,-0.0211188f,0.100469f},{0.30596f,-0.0369944f,0.100469f}, +{0.286892f,-0.0104475f,0.100469f},{0.303157f,-0.0213591f,0.100469f},{0.277563f,-0.0287664f,0.100469f}, +{0.28847f,-0.0097434f,0.100469f},{0.291499f,-0.0119409f,0.100469f},{0.296007f,-0.014044f,0.100469f}, +{0.298492f,0.00484444f,0.100469f},{0.303332f,0.00520628f,0.100469f},{0.291499f,0.0131075f,0.100469f}, +{0.305387f,0.00380369f,0.100469f},{0.31155f,0.0141674f,0.100469f},{0.316075f,0.0141686f,0.100469f}, +{0.32971f,0.0241396f,0.100469f},{0.327834f,0.0261674f,0.100469f},{0.316367f,-0.0113857f,0.100469f}, +{0.336523f,0.0122076f,0.100469f},{0.313362f,-0.00105623f,0.100469f},{0.313407f,5.8201e-009f,0.100469f}, +{0.307131f,0.0151227f,0.100469f},{0.28959f,0.035405f,0.100469f},{0.314104f,0.0153056f,0.100469f}, +{5.35539e-017f,0.279848f,0.100469f},{-0.0102622f,0.290409f,0.100469f},{0.024361f,0.27258f,0.100469f}, +{-0.0199275f,0.266037f,0.100469f},{-0.0174585f,0.295223f,0.100469f},{-0.00553085f,0.302123f,0.100469f}, +{-0.0128186f,0.291545f,0.100469f},{-0.0122331f,0.291546f,0.100469f},{-0.00461423f,0.304437f,0.100469f}, +{-0.012073f,0.302345f,0.100469f},{-0.0121187f,0.301289f,0.100469f},{-0.00978928f,0.289348f,0.100469f}, +{-0.00528144f,0.287245f,0.100469f},{-0.0150796f,0.314949f,0.100469f},{-0.0151227f,0.307131f,0.100469f}, +{-0.0124916f,0.304721f,0.100469f},{-0.013923f,0.291186f,0.100469f},{-0.0133893f,0.291424f,0.100469f}, +{-0.0205678f,0.297204f,0.100469f},{0.00204334f,0.306495f,0.100469f},{0.00348695f,0.305661f,0.100469f}, +{0.00409889f,0.305092f,0.100469f},{0.002796f,0.306132f,0.100469f},{5.8201e-009f,0.28917f,0.100469f}, +{0.00571052f,0.282653f,0.100469f},{0.00996883f,0.2899f,0.100469f},{0.0102613f,0.290408f,0.100469f}, +{0.0116591f,0.291424f,0.100469f},{0.0128153f,0.291546f,0.100469f},{0.0151227f,0.295446f,0.100469f}, +{0.0211188f,0.304276f,0.100469f},{0.0369236f,0.30649f,0.100469f},{0.0364276f,0.309253f,0.100469f}, +{0.0213591f,0.303157f,0.100469f},{0.0371512f,0.298087f,0.100469f},{0.0368049f,0.295301f,0.100469f}, +{0.0362494f,0.292548f,0.100469f},{0.00534277f,0.302936f,0.100469f},{0.0143937f,0.315892f,0.100469f}, +{0.0274755f,0.326496f,0.100469f},{0.0255017f,0.328493f,0.100469f},{0.0150786f,0.289903f,0.100469f}, +{0.012073f,0.300232f,0.100469f},{0.0121187f,0.301289f,0.100469f},{0.0137103f,0.335964f,0.100469f}, +{0.00584288f,0.316411f,0.100469f},{0.0106515f,0.315889f,0.100469f},{0.0111254f,0.316235f,0.100469f}, +{0.0102613f,0.315456f,0.100469f},{0.0162807f,0.334834f,0.100469f},{0.0211299f,0.332011f,0.100469f}, +{-0.301289f,-0.0121187f,0.100469f},{-0.29132f,-0.0113881f,0.100469f},{-0.291027f,-0.010881f,0.100469f}, +{-0.289629f,-0.00986481f,0.100469f},{-0.288473f,-0.00974281f,0.100469f},{-0.286166f,-0.00584288f,0.100469f}, +{-0.286502f,-0.0108798f,0.100469f},{-0.280721f,0.00408405f,0.100469f},{-0.279848f,6.36295e-017f,0.100469f}, +{-0.279929f,0.00186868f,0.100469f},{-0.289216f,-0.00105623f,0.100469f},{-0.28917f,5.8201e-009f,0.100469f}, +{-0.29683f,0.0131454f,0.100469f},{-0.2915f,0.013106f,0.100469f},{-0.295446f,0.0151227f,0.100469f}, +{-0.312949f,0.0151842f,0.100469f},{-0.31721f,0.033718f,0.100469f},{-0.303157f,0.0213591f,0.100469f}, +{-0.292548f,0.0362494f,0.100469f},{-0.284649f,0.0333708f,0.100469f},{-0.279831f,0.0304957f,0.100469f}, +{-0.287367f,0.0149467f,0.100469f},{-0.286502f,0.0141686f,0.100469f},{-0.316368f,0.0136603f,0.100469f}, +{-0.332011f,0.0211299f,0.100469f},{-0.314434f,0.00445857f,0.100469f},{-0.315333f,0.00528144f,0.100469f}, +{-0.306819f,0.000834183f,0.100469f},{-0.316548f,-0.0119424f,0.100469f},{-0.319924f,-0.00571052f,0.100469f}, +{-0.321856f,-0.00408405f,0.100469f},{-0.338471f,0.00280508f,0.100469f},{-0.334834f,0.0162807f,0.100469f}, +{-0.322089f,0.0309477f,0.100469f},{-0.314629f,0.0348202f,0.100469f},{-0.305373f,0.0205678f,0.100469f}, +{-0.311971f,0.0357252f,0.100469f},{-0.290163f,0.014946f,0.100469f},{-0.311078f,0.0131075f,0.100469f}, +{-0.315212f,-0.0101024f,0.100469f},{-0.314678f,-0.00986481f,0.100469f},{-0.313522f,-0.00974281f,0.100469f}, +{-0.314107f,-0.0097434f,0.100469f},{-0.313362f,0.00105623f,0.100469f},{-0.313407f,-5.8201e-009f,0.100469f}, +{-0.311078f,-0.0119409f,0.100469f},{-0.30657f,-0.014044f,0.100469f},{0.337938f,-0.00686904f,0.100469f}, +{0.336521f,-0.0122059f,0.100469f},{0.314676f,-0.00986419f,0.100469f},{0.291319f,0.0136627f,0.100469f}, +{0.308686f,0.0365475f,0.100469f},{0.311257f,0.0136603f,0.100469f},{-0.287901f,-0.00986419f,0.100469f}, +{0.0122298f,-0.285984f,0.100469f},{0.00996883f,-0.287628f,0.100469f},{0.0133877f,0.291424f,0.100469f}, +{-0.311258f,0.0136627f,0.100469f},{-0.29132f,0.0136603f,0.100469f},{-0.00996978f,0.314951f,0.100469f}, +{0.00996883f,0.314949f,0.100469f},{0.0152591f,-0.313229f,0.100469f},{0.0133877f,-0.311153f,0.100469f}, +{-0.0836959f,-0.0908383f,0.0918925f},{-0.0858243f,-0.0894455f,0.0918925f},{-0.0633282f,-0.0805185f,0.0918925f}, +{-0.0671452f,-0.0298151f,0.0918925f},{-0.0937839f,-0.0280757f,0.0918925f},{-0.0663164f,-0.0282257f,0.0918925f}, +{-0.0580379f,-0.0799657f,0.0918925f},{0.0145474f,-0.107316f,0.0918925f},{-0.0141179f,-0.109619f,0.0918925f}, +{-0.0145465f,-0.107313f,0.0918925f},{-0.089447f,-0.0858213f,0.0918925f},{-0.0908391f,-0.0836927f,0.0918925f}, +{-0.0877597f,-0.0877597f,0.0918925f},{-0.005033f,-0.281577f,0.0918925f},{-0.0057111f,-0.28266f,0.0918925f}, +{-0.0122298f,-0.285984f,0.0918925f},{-0.0919114f,-0.0814392f,0.0918925f},{-0.0631477f,-0.0799633f,0.0918925f}, +{-0.0619904f,-0.0786793f,0.0918925f},{-0.0624629f,-0.0790223f,0.0918925f},{-0.0932205f,-0.0745764f,0.0918925f}, +{-0.0628553f,-0.0794574f,0.0918925f},{-0.0362489f,-0.292548f,0.0918925f},{-0.0333688f,-0.28465f,0.0918925f}, +{-0.0320225f,-0.282186f,0.0918925f},{-0.0926561f,-0.079125f,0.0918925f},{-0.0930843f,-0.0768194f,0.0918925f}, +{-0.0932205f,-0.0326272f,0.0918925f},{-0.0602989f,-0.078321f,0.0918925f},{-0.0597282f,-0.0784424f,0.0918925f}, +{-0.100617f,0.0177581f,0.0918925f},{-0.0986812f,0.0194438f,0.0918925f},{-0.10062f,-0.0177565f,0.0918925f}, +{0.0194438f,0.0986812f,0.0918925f},{0.0206546f,0.0600777f,0.0918925f},{-0.0206547f,0.0600781f,0.0918925f}, +{-0.105002f,0.0152921f,0.0918925f},{-0.102745f,0.0163653f,0.0918925f},{-0.105002f,-0.0152921f,0.0918925f}, +{-0.102748f,-0.0163644f,0.0918925f},{-0.107316f,-0.0145474f,0.0918925f},{-0.109622f,-0.0141193f,0.0918925f}, +{-0.107313f,0.0145465f,0.0918925f},{-0.312414f,-0.0101024f,0.0918925f},{-0.312948f,-0.00986481f,0.0918925f}, +{-0.109619f,0.0141179f,0.0918925f},{-0.313414f,0.00227064f,0.0918925f},{-0.306819f,0.000833312f,0.0918925f}, +{-0.313362f,0.00105623f,0.0918925f},{-0.313518f,0.015305f,0.0918925f},{-0.307f,0.0186287f,0.0918925f}, +{-0.312948f,0.0151836f,0.0918925f},{-0.287207f,0.034526f,0.0918925f},{-0.28465f,0.0333688f,0.0918925f}, +{-0.287366f,0.014946f,0.0918925f},{-0.27983f,0.0304947f,0.0918925f},{-0.277597f,0.0287942f,0.0918925f}, +{-0.313779f,0.00343053f,0.0918925f},{-0.306325f,0.00242484f,0.0918925f},{-0.322729f,1.62449e-016f,0.0918925f}, +{-0.322648f,-0.00186868f,0.0918925f},{-0.300045f,0.00545321f,0.0918925f},{-0.300232f,0.012073f,0.0918925f}, +{-0.299018f,0.0121253f,0.0918925f},{-0.304719f,-0.0124909f,0.0918925f},{-0.311257f,-0.0113881f,0.0918925f}, +{-0.31155f,-0.010881f,0.0918925f},{-0.30713f,-0.01512f,0.0918925f},{-0.295577f,-0.0186287f,0.0918925f}, +{0.0152596f,-0.313231f,0.0918925f},{-0.316075f,-0.0108798f,0.0918925f},{-0.316367f,-0.0113857f,0.0918925f}, +{-0.318741f,-0.00606332f,0.0918925f},{-0.00105623f,-0.313362f,0.0918925f},{-0.00227064f,-0.313414f,0.0918925f}, +{0.00348669f,-0.296915f,0.0918925f},{0.00409933f,-0.297483f,0.0918925f},{-0.316548f,-0.0119409f,0.0918925f}, +{-0.319917f,-0.0057111f,0.0918925f},{-0.298492f,0.00484444f,0.0918925f},{-0.297858f,0.0124909f,0.0918925f}, +{-0.297802f,0.00437403f,0.0918925f},{-0.301289f,0.0121187f,0.0918925f},{-0.300871f,0.00557763f,0.0918925f}, +{-0.301707f,0.00557747f,0.0918925f},{-0.0274641f,-0.326484f,0.0918925f},{-0.314104f,0.0153056f,0.0918925f}, +{-0.314676f,0.0151842f,0.0918925f},{-0.319701f,0.0324249f,0.0918925f},{-0.00343053f,-0.313779f,0.0918925f}, +{-0.0102613f,-0.312169f,0.0918925f},{-0.0211319f,-0.332012f,0.0918925f},{-0.0233837f,-0.330334f,0.0918925f}, +{-0.305907f,0.00314874f,0.0918925f},{-0.311077f,0.013106f,0.0918925f},{-0.0131452f,-0.29683f,0.0918925f}, +{-0.0140418f,-0.296008f,0.0918925f},{-0.292548f,0.0362489f,0.0918925f},{-0.2953f,0.0368031f,0.0918925f}, +{-0.306322f,0.0197119f,0.0918925f},{-0.289055f,0.0153056f,0.0918925f},{-0.291499f,0.0131075f,0.0918925f}, +{-0.296008f,0.0140418f,0.0918925f},{-0.302534f,0.00545274f,0.0918925f},{-0.303332f,0.00520628f,0.0918925f}, +{-0.332012f,0.0211319f,0.0918925f},{-0.316367f,0.0136627f,0.0918925f},{-0.316548f,0.0131075f,0.0918925f}, +{-0.313518f,-0.0097434f,0.0918925f},{-0.27258f,0.0243605f,0.0918925f},{-0.286209f,0.0136603f,0.0918925f}, +{-0.286501f,0.0141674f,0.0918925f},{-0.255913f,0.000431293f,0.0918925f},{-0.279929f,0.00186868f,0.0918925f}, +{-0.280169f,0.00299304f,0.0918925f},{-0.266037f,0.0199275f,0.0918925f},{-0.280722f,0.00409024f,0.0918925f}, +{-0.334835f,0.0162821f,0.0918925f},{-0.335965f,0.0137123f,0.0918925f},{-0.31521f,-0.0101017f,0.0918925f}, +{-0.279848f,6.36295e-017f,0.0918925f},{-0.305379f,0.0205661f,0.0918925f},{-0.314628f,0.0348205f,0.0918925f}, +{-0.311971f,0.0357253f,0.0918925f},{-0.336898f,0.0110641f,0.0918925f},{-0.31194f,-0.0104475f,0.0918925f}, +{0.0128186f,0.316594f,0.0918925f},{0.0187595f,0.333514f,0.0918925f},{0.0133893f,0.316472f,0.0918925f}, +{-0.291319f,-0.0113857f,0.0918925f},{0.036428f,0.309253f,0.0918925f},{0.0369213f,0.306489f,0.0918925f}, +{0.0211196f,0.304282f,0.0918925f},{-0.291026f,-0.0108798f,0.0918925f},{-0.243259f,-0.0139831f,0.0918925f}, +{-0.281577f,0.005033f,0.0918925f},{-0.28266f,0.0057111f,0.0918925f},{-0.111865f,-0.0139831f,0.0918925f}, +{-0.111865f,0.0139831f,0.0918925f},{-0.254935f,0.0154692f,0.0918925f},{-0.254583f,0.00139831f,0.0918925f}, +{-0.255016f,0.00132937f,0.0918925f},{-0.296262f,0.00242058f,0.0918925f},{-0.29594f,0.00165192f,0.0918925f}, +{-0.251049f,0.0146388f,0.0918925f},{-0.297189f,0.00380587f,0.0918925f},{-0.247144f,-0.0141452f,0.0918925f}, +{-0.253763f,0.00113282f,0.0918925f},{-0.254152f,0.00133028f,0.0918925f},{-0.262471f,0.0181265f,0.0918925f}, +{-0.258757f,0.0166349f,0.0918925f},{-0.255708f,0.000817561f,0.0918925f},{-0.253462f,0.000819718f,0.0918925f}, +{-0.247143f,0.0141453f,0.0918925f},{-0.243259f,0.0139831f,0.0918925f},{-0.253259f,0.000430548f,0.0918925f}, +{-0.258757f,-0.016635f,0.0918925f},{-0.25105f,-0.0146388f,0.0918925f},{-0.254936f,-0.0154693f,0.0918925f}, +{-0.0956018f,0.0235109f,0.0918925f},{-0.0986812f,-0.0194438f,0.0918925f},{-0.0564469f,0.0658638f,0.0918925f}, +{-0.0339921f,0.0687596f,0.0918925f},{-0.0322907f,0.0681947f,0.0918925f},{-0.0933567f,0.0303842f,0.0918925f}, +{-0.0932205f,0.0326272f,0.0918925f},{-0.0357264f,0.0692143f,0.0918925f},{-0.0374861f,0.069557f,0.0918925f}, +{-0.0937848f,0.0280785f,0.0918925f},{0.0175821f,0.0556727f,0.0918925f},{-0.0167528f,0.0540841f,0.0918925f}, +{-0.0175819f,0.0556734f,0.0918925f},{0.0937848f,-0.0280785f,0.0918925f},{0.0663166f,-0.028225f,0.0918925f}, +{0.0945295f,-0.0257644f,0.0918925f},{-0.079125f,0.0926561f,0.0918925f},{-0.079703f,0.0835236f,0.0918925f}, +{-0.0802367f,0.0837612f,0.0918925f},{-0.0516079f,-0.0157041f,0.0918925f},{-0.0813929f,0.0838832f,0.0918925f}, +{-0.0836927f,0.0908391f,0.0918925f},{-0.0814392f,0.0919114f,0.0918925f},{-0.0768194f,0.0930843f,0.0918925f}, +{-0.0792292f,0.0831785f,0.0918925f},{-0.0829714f,0.0831813f,0.0918925f},{-0.0877597f,0.0877597f,0.0918925f}, +{-0.0824989f,0.0835243f,0.0918925f},{-0.0745764f,0.0932205f,0.0918925f},{-0.0785464f,0.0822379f,0.0918925f}, +{-0.0788389f,0.082745f,0.0918925f},{-0.0836562f,0.0822403f,0.0918925f},{-0.0838367f,0.0816851f,0.0918925f}, +{-0.0894455f,0.0858243f,0.0918925f},{-0.0783664f,0.0816836f,0.0918925f},{-0.0919114f,0.0814392f,0.0918925f}, +{-0.0908383f,0.0836959f,0.0918925f},{-0.092657f,0.0791278f,0.0918925f},{-0.0808074f,0.0838826f,0.0918925f}, +{-0.0388582f,0.0838826f,0.0918925f},{-0.0394436f,0.0838832f,0.0918925f},{-0.0326272f,0.0932205f,0.0918925f}, +{-0.0930856f,0.0768218f,0.0918925f},{-0.0339921f,-0.0151388f,0.0918925f},{-0.0322907f,-0.0157037f,0.0918925f}, +{-0.0464129f,-0.0143416f,0.0918925f},{0.0322905f,0.0681943f,0.0918925f},{0.0339919f,0.0687593f,0.0918925f}, +{0.0932205f,-0.0745764f,0.0918925f},{0.0825006f,-0.07868f,0.0918925f},{0.0819669f,-0.0784424f,0.0918925f}, +{-0.0163644f,0.102748f,0.0918925f},{0.0152921f,0.105002f,0.0918925f},{0.0163653f,0.102745f,0.0918925f}, +{-0.0194438f,0.0986812f,0.0918925f},{0.0177581f,0.100617f,0.0918925f},{-0.0152921f,0.105002f,0.0918925f}, +{0.0145465f,0.107313f,0.0918925f},{0.0141179f,0.109619f,0.0918925f},{-0.0145474f,0.107316f,0.0918925f}, +{-0.0141193f,0.109622f,0.0918925f},{0.0139831f,0.111865f,0.0918925f},{0.00348669f,0.305663f,0.0918925f}, +{0.00343053f,0.313779f,0.0918925f},{0.0140418f,0.296008f,0.0918925f},{0.0122331f,0.291546f,0.0918925f}, +{0.0131452f,0.29683f,0.0918925f},{0.0372093f,0.303697f,0.0918925f},{0.0372859f,0.30089f,0.0918925f}, +{0.0214407f,0.301289f,0.0918925f},{0.0152596f,0.314395f,0.0918925f},{0.0309479f,0.322088f,0.0918925f}, +{0.0324249f,0.319701f,0.0918925f},{0.00227064f,0.313414f,0.0918925f},{0.00124367f,0.306742f,0.0918925f}, +{0.00105623f,0.313362f,0.0918925f},{0.0292956f,0.324358f,0.0918925f},{0.0147871f,0.315456f,0.0918925f}, +{0.0274641f,0.326484f,0.0918925f},{-0.00553077f,0.302122f,0.0918925f},{-0.012073f,0.302345f,0.0918925f}, +{-0.00348695f,0.305661f,0.0918925f},{-0.002796f,0.306132f,0.0918925f},{0.0106546f,0.315892f,0.0918925f}, +{-0.0121253f,0.303559f,0.0918925f},{-0.0124909f,0.304719f,0.0918925f},{-0.00503626f,0.303713f,0.0918925f}, +{-0.0046188f,0.304437f,0.0918925f},{7.81291e-017f,0.322729f,0.0918925f},{0.00280586f,0.338471f,0.0918925f}, +{-0.00409889f,0.305092f,0.0918925f},{-0.00186868f,0.322648f,0.0918925f},{-0.00409024f,0.321855f,0.0918925f}, +{-0.00204334f,0.306495f,0.0918925f},{-0.00124497f,0.306741f,0.0918925f},{-5.8201e-009f,0.313407f,0.0918925f}, +{0.00041711f,0.306866f,0.0918925f},{-0.0152591f,0.314396f,0.0918925f},{-0.0150786f,0.314951f,0.0918925f}, +{-0.000418664f,0.306866f,0.0918925f},{-0.0131452f,0.305747f,0.0918925f},{-0.0143937f,0.290844f,0.0918925f}, +{-0.0139213f,0.291187f,0.0918925f},{-0.0133877f,0.291424f,0.0918925f},{-0.0122298f,0.291545f,0.0918925f}, +{0.0213591f,0.303157f,0.0918925f},{0.00279621f,0.306133f,0.0918925f},{0.0371496f,0.298086f,0.0918925f}, +{0.0186287f,0.307f,0.0918925f},{0.00409933f,0.305094f,0.0918925f},{0.01512f,0.295447f,0.0918925f}, +{0.013923f,0.291186f,0.0918925f},{0.0362489f,0.292548f,0.0918925f},{0.0152596f,0.289346f,0.0918925f}, +{0.0333688f,0.28465f,0.0918925f},{0.034526f,0.287207f,0.0918925f},{0.00082033f,0.257077f,0.0918925f}, +{0.000431051f,0.257275f,0.0918925f},{0.00299304f,0.280169f,0.0918925f},{0.00534833f,0.30294f,0.0918925f}, +{0.00553085f,0.302123f,0.0918925f},{0.00996978f,0.289903f,0.0918925f},{0.0269304f,0.275498f,0.0918925f}, +{0.0220151f,0.269417f,0.0918925f},{0.0320225f,0.282186f,0.0918925f},{0.0287942f,0.277597f,0.0918925f}, +{-0.0213591f,0.29942f,0.0918925f},{0.00606332f,0.283836f,0.0918925f},{-0.0579493f,-0.0190126f,0.0918925f}, +{-0.0593859f,-0.0200848f,0.0918925f},{-0.0139831f,0.111865f,0.0918925f},{-0.0106515f,0.290841f,0.0918925f}, +{-0.0141452f,0.247144f,0.0918925f},{0.00112134f,0.256764f,0.0918925f},{0.0166349f,0.258757f,0.0918925f}, +{0.00132352f,0.256375f,0.0918925f},{0.00186868f,0.279929f,0.0918925f},{2.7892e-017f,0.257343f,0.0918925f}, +{0.0154692f,0.254935f,0.0918925f},{-0.024361f,0.27258f,0.0918925f},{0.0146388f,0.251049f,0.0918925f}, +{-0.00343053f,0.288798f,0.0918925f},{-0.0102613f,0.290408f,0.0918925f},{0.0141453f,0.247143f,0.0918925f}, +{-0.0181266f,0.262471f,0.0918925f},{-0.000819963f,0.257072f,0.0918925f},{-0.016635f,0.258757f,0.0918925f}, +{-0.0139831f,0.243259f,0.0918925f},{-0.00112493f,0.256762f,0.0918925f},{-0.0013304f,0.256376f,0.0918925f}, +{-0.0146388f,0.25105f,0.0918925f},{-0.0177565f,0.10062f,0.0918925f},{0.0257644f,0.0945295f,0.0918925f}, +{0.0259491f,0.0648858f,0.0918925f},{0.0235109f,0.0956018f,0.0918925f},{0.0245125f,0.0638136f,0.0918925f}, +{0.0290135f,0.0667435f,0.0918925f},{0.0274515f,0.0658638f,0.0918925f},{0.0154086f,-0.033137f,0.0918925f}, +{-0.0154219f,-0.0331407f,0.0918925f},{0.0160285f,-0.0314546f,0.0918925f},{0.0357259f,0.069214f,0.0918925f}, +{0.0548845f,-0.0171541f,0.0918925f},{0.0564465f,-0.0180338f,0.0918925f},{0.089447f,0.0858213f,0.0918925f}, +{0.0838372f,0.0816836f,0.0918925f},{0.0836572f,0.0822379f,0.0918925f},{0.0836959f,0.0908383f,0.0918925f}, +{0.0808108f,0.0838832f,0.0918925f},{0.0814392f,0.0919114f,0.0918925f},{0.0829744f,0.0831785f,0.0918925f}, +{0.0825006f,0.0835236f,0.0918925f},{0.0877597f,0.0877597f,0.0918925f},{0.0819669f,0.0837612f,0.0918925f}, +{0.0858243f,0.0894455f,0.0918925f},{0.0930843f,0.0768194f,0.0918925f},{0.0908391f,0.0836927f,0.0918925f}, +{0.107313f,-0.0145465f,0.0918925f},{0.107316f,0.0145474f,0.0918925f},{0.109622f,0.0141193f,0.0918925f}, +{0.0932205f,0.0745764f,0.0918925f},{0.0932205f,0.0326272f,0.0918925f},{0.0919114f,0.0814392f,0.0918925f}, +{0.0926561f,0.079125f,0.0918925f},{0.0698583f,0.0437414f,0.0918925f},{0.0696868f,0.0455262f,0.0918925f}, +{0.0833647f,0.082745f,0.0918925f},{0.0932205f,-0.0326272f,0.0918925f},{0.100617f,-0.0177581f,0.0918925f}, +{0.102748f,0.0163644f,0.0918925f},{0.102745f,-0.0163653f,0.0918925f},{0.0653872f,-0.0266922f,0.0918925f}, +{0.0956018f,-0.0235109f,0.0918925f},{0.105002f,-0.0152921f,0.0918925f},{0.105002f,0.0152921f,0.0918925f}, +{0.111865f,0.0139831f,0.0918925f},{0.109619f,-0.0141179f,0.0918925f},{0.111865f,-0.0139831f,0.0918925f}, +{0.290637f,-0.0104475f,0.0918925f},{0.32971f,-0.0241396f,0.0918925f},{0.301289f,-0.0214407f,0.0918925f}, +{0.303157f,-0.0213591f,0.0918925f},{0.303208f,-0.0372381f,0.0918925f},{0.306637f,0.00165192f,0.0918925f}, +{0.306315f,0.00242058f,0.0918925f},{0.316076f,-0.010881f,0.0918925f},{0.315685f,-0.0104475f,0.0918925f}, +{0.279758f,-0.0304433f,0.0918925f},{0.312949f,-0.00986419f,0.0918925f},{0.314434f,-0.00445839f,0.0918925f}, +{0.313522f,-0.00974281f,0.0918925f},{0.304719f,0.0124909f,0.0918925f},{0.325832f,0.0280694f,0.0918925f}, +{0.315685f,0.0146009f,0.0918925f},{0.315212f,0.014946f,0.0918925f},{0.29719f,0.00380369f,0.0918925f}, +{0.297802f,0.0043727f,0.0918925f},{0.306569f,0.0140418f,0.0918925f},{0.305747f,0.0131452f,0.0918925f}, +{0.300044f,0.00545274f,0.0918925f},{0.299245f,0.00520628f,0.0918925f},{0.314107f,0.015305f,0.0918925f}, +{0.319039f,0.032792f,0.0918925f},{0.321418f,0.0313879f,0.0918925f},{0.332963f,0.0196753f,0.0918925f}, +{0.334333f,0.0172761f,0.0918925f},{0.316548f,0.013106f,0.0918925f},{0.302345f,0.012073f,0.0918925f}, +{0.301706f,0.00557763f,0.0918925f},{0.301289f,0.0121187f,0.0918925f},{0.338551f,0.00138096f,0.0918925f}, +{0.322648f,0.00186868f,0.0918925f},{0.338346f,0.00413651f,0.0918925f},{0.335521f,0.0147817f,0.0918925f}, +{0.321855f,0.00409024f,0.0918925f},{0.321f,0.005033f,0.0918925f},{0.338551f,-0.00138181f,0.0918925f}, +{0.322729f,-7.81484e-018f,0.0918925f},{0.287367f,-0.0101017f,0.0918925f},{0.286895f,-0.0104447f,0.0918925f}, +{0.306819f,0.000834183f,0.0918925f},{0.319038f,-0.0327925f,0.0918925f},{0.316562f,-0.0340166f,0.0918925f}, +{0.306322f,-0.0197119f,0.0918925f},{0.292244f,-0.0361745f,0.0918925f},{0.304282f,-0.0211196f,0.0918925f}, +{0.305959f,-0.0369915f,0.0918925f},{0.311258f,-0.0113857f,0.0918925f},{0.307f,-0.0186287f,0.0918925f}, +{0.313414f,-0.00227064f,0.0918925f},{0.313362f,-0.00105623f,0.0918925f},{0.323687f,-0.0298117f,0.0918925f}, +{0.325828f,-0.0280668f,0.0918925f},{0.29132f,-0.0113881f,0.0918925f},{0.291027f,-0.010881f,0.0918925f}, +{0.297858f,-0.0124909f,0.0918925f},{0.295447f,-0.01512f,0.0918925f},{0.289629f,-0.00986481f,0.0918925f}, +{0.289059f,-0.0097434f,0.0918925f},{0.331419f,-0.0219685f,0.0918925f},{0.316548f,-0.0119424f,0.0918925f}, +{0.277562f,-0.0287659f,0.0918925f},{0.275498f,-0.0269304f,0.0918925f},{0.27258f,-0.0243605f,0.0918925f}, +{0.269417f,-0.0220151f,0.0918925f},{0.316368f,-0.0113881f,0.0918925f},{0.338347f,-0.00413689f,0.0918925f}, +{0.305388f,0.00380587f,0.0918925f},{0.304775f,0.00437403f,0.0918925f},{0.31533f,-0.00528033f,0.0918925f}, +{0.337938f,0.00686904f,0.0918925f},{0.322408f,0.00299304f,0.0918925f},{0.304085f,0.00484444f,0.0918925f}, +{0.336521f,0.0122059f,0.0918925f},{0.303559f,0.0121253f,0.0918925f},{0.302532f,0.00545321f,0.0918925f}, +{0.0877597f,-0.0877597f,0.0918925f},{0.30087f,0.00557747f,0.0918925f},{0.316368f,0.0136603f,0.0918925f}, +{0.329709f,0.024138f,0.0918925f},{0.331418f,0.0219665f,0.0918925f},{0.28917f,-5.8201e-009f,0.0918925f}, +{0.314002f,0.0350539f,0.0918925f},{0.29667f,0.00314874f,0.0918925f},{0.254583f,0.00139831f,0.0918925f}, +{0.254936f,0.0154693f,0.0918925f},{0.255014f,0.00133028f,0.0918925f},{0.287247f,0.00528033f,0.0918925f}, +{0.288143f,0.00445839f,0.0918925f},{0.0678671f,-0.0314549f,0.0918925f},{0.0933567f,-0.0303842f,0.0918925f}, +{0.0684765f,-0.0331407f,0.0918925f},{0.266037f,0.019928f,0.0918925f},{0.279848f,1.74344e-017f,0.0918925f}, +{0.279929f,-0.00186868f,0.0918925f},{0.254935f,-0.0154692f,0.0918925f},{0.251049f,-0.0146388f,0.0918925f}, +{0.255906f,0.000430548f,0.0918925f},{0.262471f,0.0181266f,0.0918925f},{0.243259f,0.0139831f,0.0918925f}, +{0.253253f,0.000431293f,0.0918925f},{0.255704f,0.000819718f,0.0918925f},{0.258757f,0.016635f,0.0918925f}, +{0.25105f,0.0146388f,0.0918925f},{0.255403f,0.00113282f,0.0918925f},{0.218384f,0.000430548f,0.0918925f}, +{0.10062f,0.0177565f,0.0918925f},{0.0986812f,-0.0194438f,0.0918925f},{0.0986812f,0.0194438f,0.0918925f}, +{0.0643615f,-0.0252221f,0.0918925f},{0.0698583f,-0.040157f,0.0918925f},{-0.0372799f,-0.0790251f,0.0918925f}, +{-0.0377538f,-0.07868f,0.0918925f},{0.0814392f,-0.0919114f,0.0918925f},{0.079125f,-0.0926561f,0.0918925f}, +{0.0768194f,-0.0930843f,0.0918925f},{0.0836927f,-0.0908391f,0.0918925f},{0.0919114f,-0.0814392f,0.0918925f}, +{0.0908383f,-0.0836959f,0.0918925f},{0.0858213f,-0.089447f,0.0918925f},{0.0745764f,-0.0932205f,0.0918925f}, +{0.0894455f,-0.0858243f,0.0918925f},{0.0194438f,-0.0986812f,0.0918925f},{0.0213792f,-0.0969955f,0.0918925f}, +{0.0280757f,-0.0937839f,0.0918925f},{0.0257644f,-0.0945295f,0.0918925f},{-0.0583304f,-0.0794586f,0.0918925f}, +{-0.0235109f,-0.0956018f,0.0918925f},{-0.0326272f,-0.0932205f,0.0918925f},{-0.0152921f,-0.105002f,0.0918925f}, +{-0.0163653f,-0.102745f,0.0918925f},{0.0163644f,-0.102748f,0.0918925f},{-0.0177581f,-0.100617f,0.0918925f}, +{0.0177565f,-0.10062f,0.0918925f},{0.0141193f,-0.109622f,0.0918925f},{0.0152921f,-0.105002f,0.0918925f}, +{0.0139831f,-0.111865f,0.0918925f},{-0.0139831f,-0.111865f,0.0918925f},{0.00132352f,-0.255514f,0.0918925f}, +{0.0146388f,-0.25105f,0.0918925f},{0.0154693f,-0.254936f,0.0918925f},{-0.00996883f,-0.312677f,0.0918925f}, +{-0.0292956f,-0.324358f,0.0918925f},{-0.0187595f,-0.333514f,0.0918925f},{-0.00559549f,-0.338155f,0.0918925f}, +{-0.00835325f,-0.33763f,0.0918925f},{-0.0137123f,-0.335965f,0.0918925f},{-0.0110641f,-0.336898f,0.0918925f}, +{0.0121253f,-0.303559f,0.0918925f},{0.012073f,-0.302345f,0.0918925f},{-6.42929e-017f,-0.322729f,0.0918925f}, +{0.00186868f,-0.322648f,0.0918925f},{0.00996978f,-0.312674f,0.0918925f},{0.0057111f,-0.319917f,0.0918925f}, +{0.00553085f,-0.300454f,0.0918925f},{0.00534833f,-0.299637f,0.0918925f},{5.8201e-009f,-0.313407f,0.0918925f}, +{0.013923f,-0.311391f,0.0918925f},{0.01512f,-0.30713f,0.0918925f},{0.0122331f,-0.311031f,0.0918925f}, +{0.0131452f,-0.305747f,0.0918925f},{0.0140418f,-0.306569f,0.0918925f},{-0.0324249f,-0.319701f,0.0918925f}, +{-0.0337184f,-0.31721f,0.0918925f},{-0.0197119f,-0.306322f,0.0918925f},{-0.0186287f,-0.307f,0.0918925f}, +{-0.0152591f,-0.313229f,0.0918925f},{-0.0116591f,-0.311153f,0.0918925f},{-0.0111254f,-0.311391f,0.0918925f}, +{-0.0139213f,-0.31139f,0.0918925f},{-0.0122298f,-0.311032f,0.0918925f},{-0.0121253f,-0.299018f,0.0918925f}, +{-0.0124909f,-0.297858f,0.0918925f},{-0.00503626f,-0.298864f,0.0918925f},{-0.00186868f,-0.279929f,0.0918925f}, +{0.0102622f,-0.28712f,0.0918925f},{0.00584159f,-0.286169f,0.0918925f},{-0.0128153f,-0.285983f,0.0918925f}, +{-0.0097888f,-0.288183f,0.0918925f},{-0.0269304f,-0.275498f,0.0918925f},{-0.0147862f,-0.28712f,0.0918925f}, +{-0.0287942f,-0.277597f,0.0918925f},{-0.012073f,-0.300232f,0.0918925f},{-0.00553077f,-0.300455f,0.0918925f}, +{0.00279621f,-0.296444f,0.0918925f},{0.00343053f,-0.288798f,0.0918925f},{0.0211196f,-0.298295f,0.0918925f}, +{0.0213591f,-0.29942f,0.0918925f},{-0.00124497f,-0.295836f,0.0918925f},{-0.00204334f,-0.296082f,0.0918925f}, +{-5.8201e-009f,-0.28917f,0.0918925f},{0.00105623f,-0.289216f,0.0918925f},{0.00041711f,-0.295711f,0.0918925f}, +{-3.0178e-017f,-0.279848f,0.0918925f},{0.0122331f,-0.285983f,0.0918925f},{-0.0166349f,-0.258757f,0.0918925f}, +{-0.0154692f,-0.254935f,0.0918925f},{0.019928f,-0.266037f,0.0918925f},{-0.0146388f,-0.251049f,0.0918925f}, +{-0.0013304f,-0.255513f,0.0918925f},{0.016635f,-0.258757f,0.0918925f},{0.0141452f,-0.247144f,0.0918925f}, +{0.00112134f,-0.255125f,0.0918925f},{-0.000433147f,-0.254615f,0.0918925f},{-0.0139831f,-0.243259f,0.0918925f}, +{3.00981e-017f,-0.254546f,0.0918925f},{0.0139831f,-0.243259f,0.0918925f},{0.000431051f,-0.254614f,0.0918925f}, +{0.00132352f,-0.218226f,0.0918925f},{-0.0257644f,-0.0945295f,0.0918925f},{-0.0194438f,-0.0986812f,0.0918925f}, +{-0.0364172f,-0.08052f,0.0918925f},{-0.0365972f,-0.0799657f,0.0918925f},{-0.0368897f,-0.0794586f,0.0918925f}, +{-0.0956027f,-0.0235077f,0.0918925f},{-0.0969955f,-0.0213792f,0.0918925f},{-0.0632438f,-0.0238208f,0.0918925f}, +{-0.0945295f,0.0257644f,0.0918925f},{-0.0608844f,-0.0783204f,0.0918925f},{-0.0814392f,-0.0919114f,0.0918925f}, +{-0.0791278f,-0.092657f,0.0918925f},{-0.0768218f,-0.0930856f,0.0918925f},{-0.0614568f,-0.0784418f,0.0918925f}, +{-0.0591945f,-0.07868f,0.0918925f},{-0.0587207f,-0.0790251f,0.0918925f},{-0.0418875f,-0.0805185f,0.0918925f}, +{-0.0578579f,-0.08052f,0.0918925f},{-0.041707f,-0.0799633f,0.0918925f},{-0.0414146f,-0.0794574f,0.0918925f}, +{-0.0400161f,-0.0784418f,0.0918925f},{-0.0745764f,-0.0932205f,0.0918925f},{-0.0213822f,-0.0969939f,0.0918925f}, +{-0.0303842f,-0.0933567f,0.0918925f},{-0.0280785f,-0.0937848f,0.0918925f},{0.0833647f,-0.0794586f,0.0918925f}, +{0.0930856f,-0.0768218f,0.0918925f},{0.0836572f,-0.0799657f,0.0918925f},{0.0808108f,-0.0783204f,0.0918925f}, +{-0.0144962f,-0.0366018f,0.0918925f},{-0.0148999f,-0.0348554f,0.0918925f},{0.0148988f,-0.034856f,0.0918925f}, +{0.0145004f,-0.0366037f,0.0918925f},{0.0142141f,-0.0383731f,0.0918925f},{-0.0142116f,-0.0383722f,0.0918925f}, +{0.0167532f,-0.0298151f,0.0918925f},{-0.0167528f,-0.0298143f,0.0918925f},{0.0175821f,-0.0282257f,0.0918925f}, +{-0.0195369f,-0.0252221f,0.0918925f},{-0.0206547f,-0.0238204f,0.0918925f},{0.0206546f,-0.0238208f,0.0918925f}, +{0.0185115f,-0.0266927f,0.0918925f},{-0.0175819f,-0.028225f,0.0918925f},{-0.0185112f,-0.0266922f,0.0918925f}, +{0.0694022f,-0.0366018f,0.0918925f},{0.0696868f,-0.0383722f,0.0918925f},{-0.0392642f,-0.0141123f,0.0918925f}, +{-0.0410532f,-0.0139974f,0.0918925f},{0.0231475f,0.0626516f,0.0918925f},{0.0218598f,0.0614045f,0.0918925f}, +{0.0213822f,0.0969939f,0.0918925f},{0.0969939f,-0.0213822f,0.0918925f},{0.0632437f,-0.0238204f,0.0918925f}, +{0.0620385f,-0.0224931f,0.0918925f},{0.0516077f,-0.0157037f,0.0918925f},{0.0357259f,-0.0146844f,0.0918925f}, +{0.0339919f,-0.0151392f,0.0918925f},{-0.0218599f,-0.0224931f,0.0918925f},{0.0218598f,-0.0224939f,0.0918925f}, +{0.0290135f,-0.0171549f,0.0918925f},{0.0306287f,-0.016377f,0.0918925f},{0.0303842f,0.0933567f,0.0918925f}, +{0.0365982f,0.0822403f,0.0918925f},{0.0364177f,0.0816851f,0.0918925f},{0.0428452f,0.069901f,0.0918925f}, +{0.0410525f,0.069901f,0.0918925f},{-0.0290139f,0.0667443f,0.0918925f},{-0.0306291f,0.0675221f,0.0918925f}, +{-0.0418875f,0.0816851f,0.0918925f},{-0.0516079f,0.0681943f,0.0918925f},{-0.0428459f,0.069901f,0.0918925f}, +{-0.0410532f,0.069901f,0.0918925f},{-0.0392642f,0.0697861f,0.0918925f},{-0.0607509f,-0.0212468f,0.0918925f}, +{-0.0969939f,0.0213822f,0.0918925f},{-0.0620386f,-0.0224939f,0.0918925f},{-0.0643614f,-0.0252222f,0.0918925f}, +{-0.0653869f,-0.0266927f,0.0918925f},{-0.0945295f,-0.0257644f,0.0918925f},{-0.0678699f,-0.0314546f,0.0918925f}, +{-0.0933553f,-0.0303817f,0.0918925f},{-0.0684898f,-0.033137f,0.0918925f},{-0.0689996f,-0.034856f,0.0918925f}, +{-0.0696843f,-0.0383731f,0.0918925f},{-0.069398f,-0.0366037f,0.0918925f},{-0.0698582f,-0.0401574f,0.0918925f}, +{0.0140402f,-0.0401574f,0.0918925f},{-0.0140401f,-0.040157f,0.0918925f},{0.041888f,-0.08052f,0.0918925f}, +{0.0235077f,-0.0956027f,0.0918925f},{0.0368906f,-0.0794574f,0.0918925f},{0.0365982f,-0.0799633f,0.0918925f}, +{0.0364177f,-0.0805185f,0.0918925f},{0.037283f,-0.0790223f,0.0918925f},{0.0388615f,-0.0783204f,0.0918925f}, +{0.039447f,-0.078321f,0.0918925f},{0.0382891f,-0.0784418f,0.0918925f},{0.0377555f,-0.0786793f,0.0918925f}, +{0.041708f,-0.0799657f,0.0918925f},{0.0414155f,-0.0794586f,0.0918925f},{0.0405514f,-0.07868f,0.0918925f}, +{0.0400177f,-0.0784424f,0.0918925f},{0.0410252f,-0.0790251f,0.0918925f},{0.0326272f,-0.0932205f,0.0918925f}, +{0.0788398f,-0.0794574f,0.0918925f},{0.0785474f,-0.0799633f,0.0918925f},{0.0783669f,-0.0805185f,0.0918925f}, +{0.0797047f,-0.0786793f,0.0918925f},{0.0792323f,-0.0790223f,0.0918925f},{0.0813962f,-0.078321f,0.0918925f}, +{0.0829744f,-0.0790251f,0.0918925f},{0.0689986f,-0.0348554f,0.0918925f},{0.0671457f,-0.0298143f,0.0918925f}, +{0.0607507f,-0.021246f,0.0918925f},{0.048172f,0.0692143f,0.0918925f},{0.0464123f,0.069557f,0.0918925f}, +{0.0532694f,-0.0163764f,0.0918925f},{0.0593856f,-0.0200839f,0.0918925f},{0.0579489f,-0.0190117f,0.0918925f}, +{-0.0532697f,-0.016377f,0.0918925f},{-0.0548849f,-0.0171549f,0.0918925f},{0.0464123f,-0.0143415f,0.0918925f}, +{0.048172f,-0.0146841f,0.0918925f},{0.0499063f,-0.0151388f,0.0918925f},{0.0428452f,-0.0139974f,0.0918925f}, +{0.0446342f,-0.0141123f,0.0918925f},{0.0280785f,0.0937848f,0.0918925f},{0.0392635f,-0.0141124f,0.0918925f}, +{-0.0160313f,0.0524435f,0.0918925f},{0.0167532f,0.0540833f,0.0918925f},{0.0160285f,0.0524438f,0.0918925f}, +{0.0274515f,-0.0180347f,0.0918925f},{0.0322905f,-0.0157041f,0.0918925f},{-0.0140401f,0.0437414f,0.0918925f}, +{-0.0142116f,0.0455262f,0.0918925f},{0.0142141f,0.0455253f,0.0918925f},{0.0446342f,0.0697861f,0.0918925f}, +{0.037283f,0.0831813f,0.0918925f},{0.0326272f,0.0932205f,0.0918925f},{0.0377555f,0.0835243f,0.0918925f}, +{-0.0259495f,-0.0190117f,0.0918925f},{-0.0274519f,-0.0180338f,0.0918925f},{0.0374855f,0.0695568f,0.0918925f}, +{-0.0564469f,-0.0180347f,0.0918925f},{-0.0306291f,-0.0163764f,0.0918925f},{-0.0428459f,-0.0139975f,0.0918925f}, +{-0.0446349f,-0.0141124f,0.0918925f},{-0.0290139f,-0.0171541f,0.0918925f},{0.019537f,-0.0252222f,0.0918925f}, +{-0.0160313f,-0.0314549f,0.0918925f},{-0.0106515f,-0.311736f,0.0918925f},{0.0186287f,-0.295577f,0.0918925f}, +{0.00606332f,-0.318741f,0.0918925f},{0.00124367f,-0.295835f,0.0918925f},{0.00227064f,-0.289163f,0.0918925f}, +{0.0152596f,-0.288183f,0.0918925f},{0.0205661f,-0.297198f,0.0918925f},{0.0197119f,-0.296256f,0.0918925f}, +{0.0150796f,-0.287628f,0.0918925f},{0.024361f,-0.27258f,0.0918925f},{0.0143968f,-0.286688f,0.0918925f}, +{0.013923f,-0.286343f,0.0918925f},{-0.0046188f,-0.29814f,0.0918925f},{-0.0152591f,-0.288181f,0.0918925f}, +{-0.0304947f,-0.27983f,0.0918925f},{-0.0150786f,-0.287626f,0.0918925f},{-0.034526f,-0.287207f,0.0918925f}, +{-0.0354881f,-0.289845f,0.0918925f},{-0.0213591f,-0.303157f,0.0918925f},{-0.0372093f,-0.303697f,0.0918925f}, +{-0.0214407f,-0.301289f,0.0918925f},{-0.0211196f,-0.304282f,0.0918925f},{-0.0205661f,-0.305379f,0.0918925f}, +{-0.0357253f,-0.311971f,0.0918925f},{-0.0309479f,-0.322088f,0.0918925f},{-0.0255029f,-0.328493f,0.0918925f}, +{-0.00584159f,-0.316409f,0.0918925f},{-0.00280586f,-0.338471f,0.0918925f},{-0.0162821f,-0.334835f,0.0918925f}, +{0.005033f,-0.321f,0.0918925f},{0.0102622f,-0.312168f,0.0918925f},{0.00409024f,-0.321855f,0.0918925f}, +{0.00502626f,-0.298868f,0.0918925f},{0.0150796f,-0.312677f,0.0918925f},{0.319917f,0.0057111f,0.0918925f}, +{0.327844f,0.0261764f,0.0918925f},{0.316076f,0.0141674f,0.0918925f},{0.314678f,0.0151836f,0.0918925f}, +{0.323687f,0.0298108f,0.0918925f},{0.313522f,0.0153056f,0.0918925f},{0.291027f,0.0141674f,0.0918925f}, +{0.30713f,0.01512f,0.0918925f},{0.311551f,0.0141686f,0.0918925f},{0.289629f,0.0151836f,0.0918925f}, +{0.289059f,0.015305f,0.0918925f},{0.295577f,0.0186287f,0.0918925f},{0.288798f,0.00343053f,0.0918925f}, +{0.296252f,0.00242484f,0.0918925f},{0.295946f,0.00164777f,0.0918925f},{0.289163f,0.00227064f,0.0918925f}, +{0.311078f,0.0131075f,0.0918925f},{0.295758f,0.000833312f,0.0918925f},{0.289216f,0.00105623f,0.0918925f}, +{0.258757f,-0.0166349f,0.0918925f},{0.262471f,-0.0181265f,0.0918925f},{0.266037f,-0.0199275f,0.0918925f}, +{0.280169f,-0.00299304f,0.0918925f},{0.280722f,-0.00409024f,0.0918925f},{0.283836f,-0.00606332f,0.0918925f}, +{0.28621f,-0.0113857f,0.0918925f},{0.28266f,-0.0057111f,0.0918925f},{0.281577f,-0.005033f,0.0918925f}, +{0.307352f,-0.0174528f,0.0918925f},{0.282071f,-0.0319538f,0.0918925f},{0.297686f,-0.037113f,0.0918925f}, +{0.294948f,-0.0367442f,0.0918925f},{0.28449f,-0.0332889f,0.0918925f},{0.311551f,-0.0108798f,0.0918925f}, +{0.308686f,-0.0365475f,0.0918925f},{0.321418f,-0.0313882f,0.0918925f},{0.327834f,-0.0261674f,0.0918925f}, +{0.332963f,-0.0196768f,0.0918925f},{0.334333f,-0.0172772f,0.0918925f},{-0.0111254f,0.291186f,0.0918925f}, +{-0.0116591f,0.291424f,0.0918925f},{-0.0205661f,0.297198f,0.0918925f},{0.013923f,0.316235f,0.0918925f}, +{0.0255029f,0.328493f,0.0918925f},{0.0143968f,0.315889f,0.0918925f},{0.0233837f,0.330334f,0.0918925f}, +{0.0122331f,0.316594f,0.0918925f},{-0.0102613f,0.315456f,0.0918925f},{0.0102622f,0.315457f,0.0918925f}, +{0.00584159f,0.316409f,0.0918925f},{-0.0122298f,0.316594f,0.0918925f},{-0.0057111f,0.319917f,0.0918925f}, +{-0.0116591f,0.316472f,0.0918925f},{-0.005033f,0.321f,0.0918925f},{-0.0133877f,0.316473f,0.0918925f}, +{-0.0128153f,0.316594f,0.0918925f},{-0.0147862f,0.315457f,0.0918925f},{-0.01512f,0.30713f,0.0918925f}, +{-0.0147862f,0.290409f,0.0918925f},{-0.0152591f,0.289348f,0.0918925f},{-0.0186287f,0.295577f,0.0918925f}, +{-0.00105623f,0.289216f,0.0918925f},{-0.00227064f,0.289163f,0.0918925f},{0.0181265f,0.262471f,0.0918925f}, +{0.005033f,0.281577f,0.0918925f},{0.0057111f,0.28266f,0.0918925f},{0.0121253f,0.299018f,0.0918925f}, +{0.012073f,0.300232f,0.0918925f},{0.00502626f,0.303709f,0.0918925f},{0.0243605f,0.27258f,0.0918925f}, +{0.0304947f,0.27983f,0.0918925f},{0.0150796f,0.2899f,0.0918925f},{-0.303559f,-0.0121253f,0.0918925f}, +{-0.302345f,-0.012073f,0.0918925f},{-0.321855f,-0.00409024f,0.0918925f},{-0.295225f,-0.0174528f,0.0918925f}, +{-0.286892f,0.0146009f,0.0918925f},{-0.275498f,0.0269304f,0.0918925f},{-0.287899f,0.0151836f,0.0918925f}, +{-0.28847f,0.015305f,0.0918925f},{-0.282186f,0.0320225f,0.0918925f},{-0.289628f,0.0151842f,0.0918925f}, +{-0.290161f,0.0149467f,0.0918925f},{-0.289845f,0.0354881f,0.0918925f},{-0.291319f,0.0136627f,0.0918925f}, +{-0.295447f,0.01512f,0.0918925f},{-0.307352f,0.0174528f,0.0918925f},{-0.31194f,0.0146009f,0.0918925f}, +{-0.312414f,0.014946f,0.0918925f},{-0.298086f,0.0371496f,0.0918925f},{-0.301289f,0.0214407f,0.0918925f}, +{-0.30089f,0.0372859f,0.0918925f},{-0.303157f,0.0213591f,0.0918925f},{-0.303697f,0.0372093f,0.0918925f}, +{-0.304282f,0.0211196f,0.0918925f},{-0.324358f,0.0292956f,0.0918925f},{-0.31521f,0.0149467f,0.0918925f}, +{-0.330334f,0.0233837f,0.0918925f},{-0.316075f,0.0141686f,0.0918925f},{-0.333514f,0.0187595f,0.0918925f}, +{-0.316409f,0.00584159f,0.0918925f},{-0.296256f,-0.0197119f,0.0918925f},{-0.29942f,-0.0213591f,0.0918925f}, +{-0.298295f,-0.0211196f,0.0918925f},{-0.289216f,-0.00105623f,0.0918925f},{-0.289163f,-0.00227064f,0.0918925f}, +{-0.295758f,0.000834183f,0.0918925f},{-0.262471f,-0.0181266f,0.0918925f},{0.269418f,0.0220158f,0.0918925f}, +{0.290163f,-0.0101024f,0.0918925f},{0.288473f,-0.00974281f,0.0918925f},{0.287901f,-0.00986419f,0.0918925f}, +{0.301289f,-0.0121187f,0.0918925f},{0.287001f,0.0344436f,0.0918925f},{0.296256f,0.0197119f,0.0918925f}, +{0.28449f,0.0332908f,0.0918925f},{0.298295f,0.0211196f,0.0918925f},{0.292245f,0.036175f,0.0918925f}, +{0.294949f,0.0367459f,0.0918925f},{0.279758f,0.0304444f,0.0918925f},{0.282071f,0.0319552f,0.0918925f}, +{0.287901f,0.0151842f,0.0918925f},{0.286895f,0.0146037f,0.0918925f},{0.277563f,0.0287664f,0.0918925f}, +{0.287367f,0.0149467f,0.0918925f},{0.27258f,0.024361f,0.0918925f},{0.28621f,0.0136627f,0.0918925f}, +{0.286029f,0.0131075f,0.0918925f},{-0.0410221f,-0.0790223f,0.0918925f},{0.0802383f,-0.0784418f,0.0918925f}, +{0.0838372f,-0.08052f,0.0918925f},{0.092657f,-0.0791278f,0.0918925f},{0.0678671f,0.0524435f,0.0918925f}, +{0.0684765f,0.0507578f,0.0918925f},{0.0797047f,0.0835243f,0.0918925f},{0.0791278f,0.092657f,0.0918925f}, +{0.0802383f,0.0837618f,0.0918925f},{0.0694022f,0.0472966f,0.0918925f},{0.0689986f,0.0490431f,0.0918925f}, +{0.0516077f,0.0681947f,0.0918925f},{0.041888f,0.0816836f,0.0918925f},{0.0969955f,0.0213792f,0.0918925f}, +{0.0956027f,0.0235077f,0.0918925f},{0.0259491f,-0.0190126f,0.0918925f},{0.0813962f,0.0838826f,0.0918925f}, +{0.0768218f,0.0930856f,0.0918925f},{0.0745764f,0.0932205f,0.0918925f},{0.0792323f,0.0831813f,0.0918925f}, +{0.0785474f,0.0822403f,0.0918925f},{0.0788398f,0.0827462f,0.0918925f},{0.0709097f,0.0709097f,0.0918925f}, +{0.0783669f,0.0816851f,0.0918925f},{-0.0446349f,0.0697861f,0.0918925f},{-0.0932205f,0.0745764f,0.0918925f}, +{-0.0643614f,0.0586762f,0.0918925f},{-0.0653869f,0.0572057f,0.0918925f},{-0.0593859f,0.0638136f,0.0918925f}, +{-0.0620386f,0.0614045f,0.0918925f},{-0.0632438f,0.0600777f,0.0918925f},{-0.0464129f,0.0695568f,0.0918925f}, +{-0.0481725f,0.069214f,0.0918925f},{-0.0499065f,0.0687593f,0.0918925f},{-0.0819653f,0.0837618f,0.0918925f}, +{-0.0858213f,0.089447f,0.0918925f},{-0.0833638f,0.0827462f,0.0918925f},{-0.0257644f,0.0945295f,0.0918925f}, +{-0.0280757f,0.0937839f,0.0918925f},{-0.0364172f,0.0816836f,0.0918925f},{-0.0303817f,0.0933553f,0.0918925f}, +{0.0306287f,0.0675214f,0.0918925f},{-0.0235077f,0.0956027f,0.0918925f},{-0.0259495f,0.0648867f,0.0918925f}, +{-0.0365972f,0.0822379f,0.0918925f},{-0.0368897f,0.082745f,0.0918925f},{-0.0372799f,0.0831785f,0.0918925f}, +{-0.0382875f,0.0837612f,0.0918925f},{-0.0377538f,0.0835236f,0.0918925f},{-0.0400161f,0.0837618f,0.0918925f}, +{-0.0405497f,0.0835243f,0.0918925f},{-0.0414146f,0.0827462f,0.0918925f},{-0.0410221f,0.0831813f,0.0918925f}, +{-0.041707f,0.0822403f,0.0918925f},{0.0643615f,0.0586764f,0.0918925f},{0.0653872f,0.0572063f,0.0918925f}, +{0.0410252f,0.0831785f,0.0918925f},{0.0405514f,0.0835236f,0.0918925f},{0.0245125f,-0.0200848f,0.0918925f}, +{0.0231475f,-0.0212468f,0.0918925f},{0.0499063f,0.0687596f,0.0918925f},{0.0632437f,0.0600781f,0.0918925f}, +{0.0620385f,0.0614053f,0.0918925f},{0.0579489f,0.0648867f,0.0918925f},{0.0564465f,0.0658647f,0.0918925f}, +{0.0548845f,0.0667443f,0.0918925f},{0.041708f,0.0822379f,0.0918925f},{0.0414155f,0.082745f,0.0918925f}, +{0.0400177f,0.0837612f,0.0918925f},{0.0388615f,0.0838832f,0.0918925f},{0.039447f,0.0838826f,0.0918925f}, +{0.0382891f,0.0837618f,0.0918925f},{0.0368906f,0.0827462f,0.0918925f},{-0.0388582f,-0.078321f,0.0918925f}, +{-0.0382875f,-0.0784424f,0.0918925f},{-0.0394436f,-0.0783204f,0.0918925f},{-0.0405497f,-0.0786793f,0.0918925f}, +{0.0303817f,-0.0933553f,0.0918925f},{-0.0499065f,-0.0151392f,0.0918925f},{0.0392635f,0.0697861f,0.0918925f}, +{-0.0357264f,-0.0146841f,0.0918925f},{-0.0374861f,-0.0143415f,0.0918925f},{-0.0231477f,-0.021246f,0.0918925f}, +{-0.0245128f,-0.0200839f,0.0918925f},{0.0374855f,-0.0143416f,0.0918925f},{0.0410525f,-0.0139975f,0.0918925f}, +{0.0945295f,0.0257644f,0.0918925f},{0.0937839f,0.0280757f,0.0918925f},{0.0933553f,0.0303817f,0.0918925f}, +{0.0671457f,0.0540841f,0.0918925f},{0.0663166f,0.0556734f,0.0918925f},{0.0532694f,0.0675221f,0.0918925f}, +{0.0593856f,0.0638145f,0.0918925f},{-0.0195369f,0.0586764f,0.0918925f},{0.019537f,0.0586762f,0.0918925f}, +{-0.0185112f,0.0572063f,0.0918925f},{0.0185115f,0.0572057f,0.0918925f},{-0.0154219f,0.0507578f,0.0918925f}, +{0.0154086f,0.0507615f,0.0918925f},{-0.0148999f,0.0490431f,0.0918925f},{0.0145004f,0.0472947f,0.0918925f}, +{-0.0144962f,0.0472966f,0.0918925f},{0.0148988f,0.0490425f,0.0918925f},{0.0140402f,0.043741f,0.0918925f}, +{-0.0671452f,0.0540833f,0.0918925f},{-0.0678699f,0.0524438f,0.0918925f},{-0.0481725f,-0.0146844f,0.0918925f}, +{-0.0274519f,0.0658647f,0.0918925f},{-0.0245128f,0.0638145f,0.0918925f},{-0.0213792f,0.0969955f,0.0918925f}, +{-0.0231477f,0.0626525f,0.0918925f},{-0.0218599f,0.0614053f,0.0918925f},{-0.0532697f,0.0675214f,0.0918925f}, +{-0.0548849f,0.0667435f,0.0918925f},{-0.0579493f,0.0648858f,0.0918925f},{-0.0607509f,0.0626516f,0.0918925f}, +{-0.0663164f,0.0556727f,0.0918925f},{-0.0684898f,0.0507615f,0.0918925f},{-0.0689996f,0.0490425f,0.0918925f}, +{-0.0696843f,0.0455253f,0.0918925f},{-0.069398f,0.0472947f,0.0918925f},{-0.0698582f,0.043741f,0.0918925f}, +{-0.21663f,0.00133028f,0.0918925f},{-0.217061f,0.00139831f,0.0918925f},{-0.218391f,0.000431293f,0.0918925f}, +{-0.218186f,0.000817561f,0.0918925f},{-0.21594f,0.000819718f,0.0918925f},{-0.215737f,0.000430548f,0.0918925f}, +{-0.216241f,0.00113282f,0.0918925f},{-0.217881f,0.00112774f,0.0918925f},{-0.217494f,0.00132937f,0.0918925f}, +{0.00112134f,-0.217837f,0.0918925f},{0.00082033f,-0.217524f,0.0918925f},{0.000431051f,-0.217326f,0.0918925f}, +{3.13209e-017f,-0.217258f,0.0918925f},{-0.000819963f,-0.217529f,0.0918925f},{-0.000433147f,-0.217327f,0.0918925f}, +{-0.0013304f,-0.218225f,0.0918925f},{-0.00112493f,-0.217839f,0.0918925f},{-0.000819963f,-0.254817f,0.0918925f}, +{-0.00112493f,-0.255127f,0.0918925f},{-0.0141453f,-0.247143f,0.0918925f},{0.00082033f,-0.254812f,0.0918925f}, +{0.0128186f,-0.285984f,0.0918925f},{0.0220158f,-0.269418f,0.0918925f},{0.0133893f,-0.286105f,0.0918925f}, +{-0.0181265f,-0.262471f,0.0918925f},{0.00445839f,-0.288143f,0.0918925f},{0.00528033f,-0.287247f,0.0918925f}, +{0.0181266f,-0.262471f,0.0918925f},{0.247143f,-0.0141453f,0.0918925f},{0.243259f,-0.0139831f,0.0918925f}, +{0.25415f,0.00132937f,0.0918925f},{0.253763f,0.00112774f,0.0918925f},{0.247144f,0.0141452f,0.0918925f}, +{0.253458f,0.000817561f,0.0918925f},{0.000431051f,0.219987f,0.0918925f},{0.0139831f,0.243259f,0.0918925f}, +{0.00082033f,0.219789f,0.0918925f},{0.00112134f,0.219476f,0.0918925f},{0.00132352f,0.219087f,0.0918925f}, +{2.65983e-017f,0.220055f,0.0918925f},{-0.000819963f,0.219784f,0.0918925f},{-0.000433147f,0.219986f,0.0918925f}, +{-0.0013304f,0.219088f,0.0918925f},{-0.00112493f,0.219474f,0.0918925f},{-0.0154693f,0.254936f,0.0918925f}, +{-0.000433147f,0.257274f,0.0918925f},{5.35539e-017f,0.279848f,0.0918925f},{-0.0220158f,0.269418f,0.0918925f}, +{-0.019928f,0.266037f,0.0918925f},{0.216628f,0.00132937f,0.0918925f},{0.216241f,0.00112774f,0.0918925f}, +{0.217881f,0.00113282f,0.0918925f},{0.218182f,0.000819718f,0.0918925f},{0.217061f,0.00139831f,0.0918925f}, +{0.217492f,0.00133028f,0.0918925f},{0.215936f,0.000817561f,0.0918925f},{0.215731f,0.000431293f,0.0918925f}, +{-0.255403f,0.00112774f,0.0918925f},{-0.286029f,-0.0119424f,0.0918925f},{-0.286209f,-0.0113881f,0.0918925f}, +{-0.27258f,-0.024361f,0.0918925f},{-0.269418f,-0.0220158f,0.0918925f},{-0.266037f,-0.019928f,0.0918925f}, +{0.0111271f,-0.31139f,0.0918925f},{0.0106546f,-0.311733f,0.0918925f},{0.00299304f,-0.322408f,0.0918925f}, +{0.0147871f,-0.312169f,0.0918925f},{0.0143968f,-0.311736f,0.0918925f},{0.0174528f,-0.295225f,0.0918925f}, +{0.0124909f,-0.304719f,0.0918925f},{0.00978928f,-0.313229f,0.0918925f},{0.00204265f,-0.296082f,0.0918925f}, +{-0.000418664f,-0.295711f,0.0918925f},{0.00461423f,-0.29814f,0.0918925f},{0.0116607f,-0.311153f,0.0918925f}, +{0.0147871f,-0.287121f,0.0918925f},{0.0116607f,-0.286104f,0.0918925f},{0.0111271f,-0.286342f,0.0918925f}, +{0.0106546f,-0.286685f,0.0918925f},{-0.0102613f,-0.287121f,0.0918925f},{-0.00409889f,-0.297485f,0.0918925f}, +{-0.0106515f,-0.286688f,0.0918925f},{-0.0111254f,-0.286343f,0.0918925f},{-0.00606332f,-0.283836f,0.0918925f}, +{-0.0243605f,-0.27258f,0.0918925f},{-0.0139213f,-0.286342f,0.0918925f},{-0.0143937f,-0.286685f,0.0918925f}, +{-0.0368031f,-0.2953f,0.0918925f},{-0.0371496f,-0.298086f,0.0918925f},{-0.01512f,-0.295447f,0.0918925f}, +{-0.0150786f,-0.312674f,0.0918925f},{-0.0174528f,-0.307352f,0.0918925f},{-0.0147862f,-0.312168f,0.0918925f}, +{-0.0128153f,-0.311031f,0.0918925f},{-0.00534277f,-0.299641f,0.0918925f},{-0.00348695f,-0.296916f,0.0918925f}, +{0.00978928f,-0.288181f,0.0918925f},{-0.002796f,-0.296445f,0.0918925f},{-0.0116591f,-0.286105f,0.0918925f}, +{0.00996978f,-0.287626f,0.0918925f},{-0.00299304f,-0.280169f,0.0918925f},{-0.0133877f,-0.286104f,0.0918925f}, +{-0.0220151f,-0.269417f,0.0918925f},{-0.0199275f,-0.266037f,0.0918925f},{-0.00528033f,-0.31533f,0.0918925f}, +{-0.0097888f,-0.313231f,0.0918925f},{-0.00445839f,-0.314434f,0.0918925f},{-0.0133877f,-0.311153f,0.0918925f}, +{-0.0143937f,-0.311733f,0.0918925f},{-0.0372859f,-0.30089f,0.0918925f},{-0.0369213f,-0.306489f,0.0918925f}, +{-0.036428f,-0.309253f,0.0918925f},{-0.0348205f,-0.314628f,0.0918925f},{0.312416f,-0.0101017f,0.0918925f}, +{0.311943f,-0.0104447f,0.0918925f},{0.305379f,-0.0205661f,0.0918925f},{0.311371f,-0.0358991f,0.0918925f}, +{0.300444f,-0.0372784f,0.0918925f},{0.314002f,-0.035054f,0.0918925f},{0.33733f,-0.00956509f,0.0918925f}, +{0.335522f,-0.0147828f,0.0918925f},{0.336523f,-0.0122076f,0.0918925f},{0.315212f,-0.0101024f,0.0918925f}, +{0.316409f,-0.00584159f,0.0918925f},{0.337939f,-0.00686983f,0.0918925f},{0.313779f,-0.00343053f,0.0918925f}, +{0.311078f,-0.0119409f,0.0918925f},{0.287001f,-0.0344412f,0.0918925f},{0.28959f,-0.035405f,0.0918925f}, +{0.296008f,-0.0140418f,0.0918925f},{0.2915f,-0.0119424f,0.0918925f},{0.29683f,-0.0131452f,0.0918925f}, +{0.300232f,-0.012073f,0.0918925f},{0.299018f,-0.0121253f,0.0918925f},{0.286502f,-0.0108798f,0.0918925f}, +{0.286029f,-0.0119409f,0.0918925f},{0.300445f,0.0372813f,0.0918925f},{0.303207f,0.0372145f,0.0918925f}, +{0.286169f,0.00584159f,0.0918925f},{0.297687f,0.0371146f,0.0918925f},{0.29942f,0.0213591f,0.0918925f}, +{0.30596f,0.0369944f,0.0918925f},{0.298493f,0.00484368f,0.0918925f},{0.290637f,0.0146009f,0.0918925f}, +{0.2915f,0.013106f,0.0918925f},{0.308687f,0.036547f,0.0918925f},{0.289591f,0.0354067f,0.0918925f}, +{0.297198f,0.0205661f,0.0918925f},{0.288473f,0.0153056f,0.0918925f},{0.275498f,0.0269304f,0.0918925f}, +{0.286502f,0.0141686f,0.0918925f},{0.303331f,0.00520701f,0.0918925f},{0.305903f,0.00314864f,0.0918925f}, +{0.318741f,0.00606332f,0.0918925f},{0.337328f,0.00956357f,0.0918925f},{0.312416f,0.0149467f,0.0918925f}, +{0.312949f,0.0151842f,0.0918925f},{0.311943f,0.0146037f,0.0918925f},{0.311372f,0.035899f,0.0918925f}, +{0.311258f,0.0136627f,0.0918925f},{0.295225f,0.0174528f,0.0918925f},{0.290163f,0.014946f,0.0918925f}, +{5.8201e-009f,0.28917f,0.0918925f},{-0.00996883f,0.2899f,0.0918925f},{-0.00528033f,0.287247f,0.0918925f}, +{-0.0097888f,0.289346f,0.0918925f},{-0.00445839f,0.288143f,0.0918925f},{-0.00584159f,0.286169f,0.0918925f}, +{-0.0128153f,0.291546f,0.0918925f},{-0.0140418f,0.306569f,0.0918925f},{-0.0211196f,0.298295f,0.0918925f}, +{-0.0197119f,0.296256f,0.0918925f},{-0.0143937f,0.315892f,0.0918925f},{-0.0139213f,0.316235f,0.0918925f}, +{-0.0150786f,0.289903f,0.0918925f},{-0.0174528f,0.295225f,0.0918925f},{-0.00534277f,0.302936f,0.0918925f}, +{0.00996978f,0.314951f,0.0918925f},{0.00978928f,0.314396f,0.0918925f},{0.00445839f,0.314434f,0.0918925f}, +{0.00528033f,0.31533f,0.0918925f},{-0.0106515f,0.315889f,0.0918925f},{-0.0097888f,0.314395f,0.0918925f}, +{0.0116607f,0.316473f,0.0918925f},{0.0111271f,0.316235f,0.0918925f},{0.0137123f,0.335965f,0.0918925f}, +{0.0110641f,0.336898f,0.0918925f},{-0.00299304f,0.322408f,0.0918925f},{0.0102622f,0.290409f,0.0918925f}, +{0.0111271f,0.291187f,0.0918925f},{0.0106546f,0.290844f,0.0918925f},{0.0199275f,0.266037f,0.0918925f}, +{0.0147871f,0.290408f,0.0918925f},{0.0143968f,0.290841f,0.0918925f},{0.0354881f,0.289845f,0.0918925f}, +{0.0174528f,0.307352f,0.0918925f},{0.0368031f,0.2953f,0.0918925f},{0.0124909f,0.297858f,0.0918925f}, +{0.00978928f,0.289348f,0.0918925f},{0.00204265f,0.306496f,0.0918925f},{0.0150796f,0.314949f,0.0918925f}, +{0.00461423f,0.304437f,0.0918925f},{0.0116607f,0.291424f,0.0918925f},{0.0205661f,0.305379f,0.0918925f}, +{0.0357253f,0.311971f,0.0918925f},{0.0337184f,0.31721f,0.0918925f},{0.0197119f,0.306322f,0.0918925f}, +{0.0211319f,0.332012f,0.0918925f},{0.0162821f,0.334835f,0.0918925f},{0.00835325f,0.33763f,0.0918925f}, +{0.00559549f,0.338155f,0.0918925f},{-0.00606332f,0.318741f,0.0918925f},{-0.0111254f,0.316235f,0.0918925f}, +{-0.290161f,-0.0101017f,0.0918925f},{-0.290634f,-0.0104447f,0.0918925f},{-0.297198f,-0.0205661f,0.0918925f}, +{-0.286501f,-0.010881f,0.0918925f},{-0.289628f,-0.00986419f,0.0918925f},{-0.288143f,-0.00445839f,0.0918925f}, +{-0.289055f,-0.00974281f,0.0918925f},{-0.286892f,-0.0104475f,0.0918925f},{-0.283836f,0.00606332f,0.0918925f}, +{-0.286029f,0.013106f,0.0918925f},{-0.288798f,-0.00343053f,0.0918925f},{-0.291499f,-0.0119409f,0.0918925f}, +{-0.299246f,0.00520701f,0.0918925f},{-0.269417f,0.0220151f,0.0918925f},{-0.296674f,0.00314864f,0.0918925f}, +{-0.287247f,-0.00528033f,0.0918925f},{-0.286169f,-0.00584159f,0.0918925f},{-0.28847f,-0.0097434f,0.0918925f}, +{-0.290634f,0.0146037f,0.0918925f},{-0.291026f,0.0141686f,0.0918925f},{-0.305387f,0.00380369f,0.0918925f}, +{-0.328493f,0.0255029f,0.0918925f},{-0.326484f,0.0274641f,0.0918925f},{-0.315682f,0.0146037f,0.0918925f}, +{-0.338471f,0.00280586f,0.0918925f},{-0.338155f,0.00559549f,0.0918925f},{-0.33763f,0.00835325f,0.0918925f}, +{-0.314434f,0.00445839f,0.0918925f},{-0.314104f,-0.00974281f,0.0918925f},{-0.306631f,0.00164777f,0.0918925f}, +{-0.304776f,0.0043727f,0.0918925f},{-0.29683f,0.0131452f,0.0918925f},{-0.31155f,0.0141674f,0.0918925f}, +{-0.304085f,0.00484368f,0.0918925f},{-0.306489f,0.0369213f,0.0918925f},{-0.309253f,0.036428f,0.0918925f}, +{-0.31721f,0.0337184f,0.0918925f},{-0.322088f,0.0309479f,0.0918925f},{-0.301289f,-0.0121187f,0.0918925f}, +{-0.306569f,-0.0140418f,0.0918925f},{-0.311077f,-0.0119424f,0.0918925f},{-0.305747f,-0.0131452f,0.0918925f}, +{-0.314676f,-0.00986419f,0.0918925f},{-0.315682f,-0.0104447f,0.0918925f},{-0.31533f,0.00528033f,0.0918925f}, +{-0.322408f,-0.00299304f,0.0918925f},{-0.321f,-0.005033f,0.0918925f},{0.314107f,-0.0097434f,0.0918925f}, +{0.313407f,5.8201e-009f,0.0918925f},{0.314678f,-0.00986481f,0.0918925f},{0.29132f,0.0136603f,0.0918925f}, +{0.316563f,0.0340163f,0.0918925f},{0.00409024f,0.280722f,0.0918925f},{-0.287366f,-0.0101024f,0.0918925f}, +{-0.28917f,5.8201e-009f,0.0918925f},{-0.287899f,-0.00986481f,0.0918925f},{-0.00409024f,-0.280722f,0.0918925f}, +{-0.00996883f,-0.287628f,0.0918925f},{0.0128186f,0.291545f,0.0918925f},{0.0348205f,0.314628f,0.0918925f}, +{0.0121187f,0.301289f,0.0918925f},{0.0133893f,0.291424f,0.0918925f},{-0.311257f,0.0136603f,0.0918925f}, +{-0.0121187f,-0.301289f,0.0918925f},{-0.00996883f,0.314949f,0.0918925f},{-0.313407f,-5.8201e-009f,0.0918925f}, +{-0.0121187f,0.301289f,0.0918925f},{0.0128186f,-0.311032f,0.0918925f},{0.0121187f,-0.301289f,0.0918925f}, +{0.0133893f,-0.311153f,0.0918925f},{0.0607507f,0.0626525f,0.0918925f} +}; +static GLfloat normals [22155][3] = { +{0.999998f,0.00196876f,-9.24455e-016f},{0.965341f,-0.260991f,9.65861e-017f},{0.964306f,0.26479f,-7.4874e-016f}, +{0.865368f,0.501136f,0.0f},{0.867335f,-0.497725f,0.0f},{0.506909f,-0.862f,-5.55448e-015f}, +{0.258065f,-0.966128f,2.28729e-015f},{0.718867f,-0.695147f,-9.80072e-016f},{0.873911f,-0.486086f,0.0f}, +{0.258065f,-0.966128f,-3.05132e-015f},{7.00858e-015f,-1.0f,0.0f},{1.40172e-014f,-1.0f,0.0f}, +{0.999712f,-0.0239869f,-3.77413e-016f},{0.956928f,-0.290324f,-1.0624e-015f},{0.969751f,0.244096f,7.01312e-016f}, +{0.873911f,0.486086f,0.0f},{0.849592f,-0.52744f,0.0f},{0.499432f,-0.866353f,8.15683e-015f}, +{0.254108f,-0.967176f,-5.91491e-015f},{0.709621f,-0.704584f,7.54622e-015f},{0.865368f,-0.501136f,0.0f}, +{0.0f,-1.0f,0.0f},{1.18424e-015f,1.0f,1.4803e-015f},{0.194654f,0.980872f,-4.34694e-015f}, +{-1.18424e-015f,1.0f,1.4803e-015f},{-0.384009f,0.923329f,-2.06797e-015f},{-0.382179f,0.924088f,-2.06073e-015f}, +{-0.196168f,0.98057f,-1.46061e-015f},{-0.194653f,0.980872f,-5.09094e-015f},{-0.555293f,0.831655f,2.44935e-015f}, +{-0.707075f,0.707139f,2.06083e-015f},{-0.707765f,0.706447f,-1.38061e-015f},{-0.831545f,0.555458f,-3.09244e-016f}, +{-0.831851f,0.554999f,-1.04211e-015f},{-0.556611f,0.830773f,-3.07448e-016f},{-1.0f,-1.4803e-016f,0.0f}, +{-0.980825f,0.19489f,6.04239e-016f},{-0.98085f,0.194766f,-2.58442e-016f},{-0.924075f,0.382212f,1.80893e-016f}, +{-0.923954f,0.382504f,2.12633e-015f},{-1.0f,-1.66533e-016f,0.0f},{0.196168f,0.98057f,-1.81492e-017f}, +{0.382179f,0.924088f,2.66513e-015f},{0.384009f,0.923329f,-2.7336e-015f},{0.556611f,0.830773f,4.91917e-015f}, +{0.555293f,0.831655f,-5.13749e-017f},{0.707766f,0.706447f,-2.0915e-015f},{0.707075f,0.707139f,0.0f}, +{0.831545f,0.555458f,1.64449e-015f},{0.831851f,0.554999f,3.13233e-015f},{0.924075f,0.382212f,2.26315e-015f}, +{0.923954f,0.382504f,2.09391e-015f},{0.98085f,0.194766f,1.81494e-016f},{0.980825f,0.19489f,0.0f}, +{1.0f,7.40149e-017f,0.0f},{0.194654f,0.980872f,-5.22038e-015f},{-0.384009f,0.923329f,-2.90287e-015f}, +{-0.382179f,0.924088f,-2.05189e-015f},{-0.196168f,0.98057f,-1.16115e-015f},{-0.194653f,0.980872f,-5.08194e-015f}, +{-0.555293f,0.831655f,2.46219e-015f},{-0.707075f,0.707139f,1.9627e-015f},{-0.707765f,0.706447f,-1.17598e-015f}, +{-0.831545f,0.555458f,4.25627e-015f},{-0.831851f,0.554999f,-1.00122e-015f},{-0.556611f,0.830773f,1.04527e-016f}, +{-1.0f,2.36848e-015f,0.0f},{-0.980825f,0.19489f,-1.05575e-015f},{-0.98085f,0.194766f,-2.81743e-015f}, +{-0.924075f,0.382212f,4.08156e-015f},{-0.923954f,0.382504f,5.81678e-015f},{0.196168f,0.98057f,0.0f}, +{0.382179f,0.924088f,3.86733e-015f},{0.556611f,0.830773f,3.27127e-015f},{0.555293f,0.831655f,1.644e-015f}, +{0.707075f,0.707139f,2.09336e-015f},{0.831545f,0.555458f,4.10635e-015f},{0.831851f,0.554999f,5.74903e-015f}, +{0.923954f,0.382504f,7.73578e-015f},{0.98085f,0.194766f,0.0f},{0.980825f,0.19489f,-5.80765e-015f}, +{1.0f,1.4803e-016f,0.0f},{1.0f,0.0f,0.0f},{2.36848e-015f,1.0f,2.96059e-015f}, +{0.194654f,0.980872f,-2.90396e-015f},{-2.36848e-015f,1.0f,2.96059e-015f},{-0.384009f,0.923329f,6.90506e-015f}, +{-0.382179f,0.924088f,1.3856e-015f},{-0.196168f,0.98057f,2.91215e-015f},{-0.194653f,0.980872f,-1.46099e-015f}, +{-0.555293f,0.831655f,-9.90657e-015f},{-0.707075f,0.707139f,4.01536e-015f},{-0.707765f,0.706447f,-3.98705e-015f}, +{-0.831545f,0.555458f,-4.559e-015f},{-0.831851f,0.554999f,-1.44976e-015f},{-0.556611f,0.830773f,1.79963e-015f}, +{-1.0f,-7.40149e-017f,0.0f},{-0.980825f,0.19489f,-6.37078e-016f},{-0.98085f,0.194766f,4.68159e-016f}, +{-0.924075f,0.382212f,-2.81417e-015f},{-0.923954f,0.382504f,2.58471e-015f},{-1.0f,-8.32667e-017f,0.0f}, +{0.196168f,0.98057f,9.0746e-018f},{0.382179f,0.924088f,-5.43634e-015f},{0.384009f,0.923329f,0.0f}, +{0.556611f,0.830773f,9.78684e-015f},{0.555293f,0.831655f,0.0f},{0.707766f,0.706447f,-4.11753e-015f}, +{0.707075f,0.707139f,-4.1871e-015f},{0.831545f,0.555458f,9.86691e-015f},{0.831851f,0.554999f,-3.13233e-015f}, +{0.924075f,0.382212f,0.0f},{0.923954f,0.382504f,1.70966e-016f},{0.98085f,0.194766f,-1.81494e-016f}, +{0.980825f,0.19489f,-1.81489e-016f},{0.194654f,0.980872f,-2.03953e-015f},{-0.384009f,0.923329f,6.83401e-015f}, +{-0.382179f,0.924088f,1.08506e-015f},{-0.196168f,0.98057f,2.61268e-015f},{-0.194653f,0.980872f,-1.45198e-015f}, +{-0.555293f,0.831655f,-1.12873e-014f},{-0.707075f,0.707139f,6.67295e-015f},{-0.707765f,0.706447f,-5.10024e-015f}, +{-0.831545f,0.555458f,-7.65076e-015f},{-0.831851f,0.554999f,2.55421e-016f},{-0.556611f,0.830773f,3.2866e-015f}, +{-1.0f,0.0f,0.0f},{-0.980825f,0.19489f,-4.16548e-015f},{-0.98085f,0.194766f,-4.00449e-015f}, +{-0.924075f,0.382212f,-2.98516e-015f},{-0.923954f,0.382504f,2.15596e-015f},{0.196168f,0.98057f,-1.16155e-015f}, +{0.382179f,0.924088f,-4.34023e-015f},{0.384009f,0.923329f,-1.1369e-015f},{0.556611f,0.830773f,8.19043e-015f}, +{0.707766f,0.706447f,-6.27842e-015f},{0.831545f,0.555458f,1.23288e-014f},{0.831851f,0.554999f,-5.74903e-015f}, +{0.924075f,0.382212f,5.47162e-015f},{0.923954f,0.382504f,0.0f},{1.0f,-2.36848e-015f,0.0f}, +{-1.11022e-016f,1.0f,-2.46519e-030f},{0.194654f,0.980872f,9.51248e-016f},{-8.55798e-017f,1.0f,-2.50285e-030f}, +{-0.384009f,0.923329f,2.80418e-017f},{-0.382179f,0.924088f,-4.08548e-016f},{-0.196168f,0.98057f,-4.24234e-016f}, +{-0.194653f,0.980872f,-2.57762e-017f},{-0.555293f,0.831655f,-1.38085e-015f},{-0.707075f,0.707139f,2.68038e-015f}, +{-0.707765f,0.706447f,-1.1513e-015f},{-0.831545f,0.555458f,-3.26839e-015f},{-0.831851f,0.554999f,1.655e-015f}, +{-0.556611f,0.830773f,1.3746e-015f},{-0.980825f,0.19489f,-3.69749e-015f},{-0.98085f,0.194766f,-4.67541e-015f}, +{-0.924075f,0.382212f,-4.42657e-017f},{-0.923954f,0.382504f,-4.39043e-016f},{0.196168f,0.98057f,-1.23359e-015f}, +{0.382179f,0.924088f,1.04983e-015f},{0.384009f,0.923329f,-1.10337e-015f},{0.556611f,0.830773f,-1.58124e-015f}, +{0.555293f,0.831655f,1.76503e-015f},{0.707766f,0.706447f,-2.16446e-015f},{0.707075f,0.707139f,-1.46822e-016f}, +{0.831545f,0.555458f,2.45291e-015f},{0.831851f,0.554999f,-2.41485e-015f},{0.924075f,0.382212f,5.47867e-015f}, +{0.923954f,0.382504f,-1.28171e-017f},{0.98085f,0.194766f,-4.03904e-018f},{0.980825f,0.19489f,-5.81213e-015f}, +{-3.70074e-017f,1.0f,-1.71194e-033f},{0.194654f,0.980872f,9.00454e-018f},{-4.16334e-017f,1.0f,-1.92593e-033f}, +{-0.384009f,0.923329f,-1.03189e-016f},{-0.382179f,0.924088f,-9.4335e-017f},{-0.196168f,0.98057f,-9.07461e-018f}, +{-0.194653f,0.980872f,-9.97534e-017f},{-0.555293f,0.831655f,-8.97873e-017f},{-0.707075f,0.707139f,-8.87483e-021f}, +{-0.707765f,0.706447f,5.72963e-017f},{-0.831545f,0.555458f,6.3335e-017f},{-0.831851f,0.554999f,-1.05011e-016f}, +{-0.556611f,0.830773f,-3.8431e-017f},{-0.980825f,0.19489f,1.298e-016f},{-0.98085f,0.194766f,8.73054e-017f}, +{-0.924075f,0.382212f,4.8286e-017f},{-0.923954f,0.382504f,-4.12339e-017f},{0.196168f,0.98057f,7.25718e-017f}, +{0.382179f,0.924088f,1.47781e-017f},{0.556611f,0.830773f,-7.6862e-017f},{0.707766f,0.706447f,0.0f}, +{0.707075f,0.707139f,-6.54235e-017f},{0.831545f,0.555458f,0.0f},{0.831851f,0.554999f,-1.53923e-016f}, +{0.923954f,0.382504f,-1.53271e-016f},{0.961369f,-0.275264f,-5.33819e-015f},{0.939639f,-0.342168f,2.53256e-016f}, +{0.978324f,-0.207082f,-3.06688e-015f},{0.990413f,-0.138135f,5.26556e-015f},{0.997621f,-0.068939f,2.88059e-015f}, +{1.0f,-8.02768e-016f,0.0f},{0.913294f,-0.4073f,-1.80878e-015f},{0.882564f,-0.470193f,-2.7841e-015f}, +{0.847736f,-0.530418f,0.0f},{0.809153f,-0.587599f,0.0f},{-0.0920911f,-0.995751f,0.0f}, +{-0.0918041f,-0.995777f,0.0f},{0.0605578f,-0.998165f,0.0f},{-0.241953f,-0.970288f,0.0f}, +{-0.242471f,-0.970159f,0.0f},{-0.387096f,-0.92204f,0.0f},{-0.386523f,-0.92228f,0.0f}, +{-0.522668f,-0.852537f,0.0f},{-0.522154f,-0.852851f,0.0f},{-0.645678f,-0.76361f,0.0f}, +{-0.646072f,-0.763276f,0.0f},{-0.754469f,-0.656336f,0.0f},{-0.754213f,-0.65663f,0.0f}, +{-0.84535f,-0.534213f,0.0f},{-0.845231f,-0.5344f,0.0f},{-0.916608f,-0.399787f,0.0f}, +{0.0602701f,-0.998182f,0.0f},{0.211672f,-0.977341f,0.0f},{0.21115f,-0.977454f,0.0f}, +{0.357746f,-0.933819f,0.0f},{0.357166f,-0.934041f,0.0f},{0.494924f,-0.868936f,0.0f}, +{0.495448f,-0.868638f,0.0f},{0.621613f,-0.783324f,0.0f},{0.621208f,-0.783646f,0.0f}, +{0.733337f,-0.679865f,0.0f},{0.733072f,-0.680151f,0.0f},{0.82791f,-0.560861f,0.0f}, +{0.828034f,-0.560677f,0.0f},{0.903508f,-0.428571f,0.0f},{-0.657856f,-0.753144f,0.0f}, +{-0.520449f,-0.853893f,0.0f},{-0.657957f,-0.753056f,0.0f},{-0.776263f,-0.63041f,0.0f}, +{-0.776125f,-0.630579f,0.0f},{-0.872027f,-0.489458f,0.0f},{-0.871886f,-0.489709f,0.0f}, +{-0.942365f,-0.334588f,0.0f},{-0.942433f,-0.334396f,0.0f},{-0.985518f,-0.169572f,0.0f}, +{-0.985476f,-0.169813f,0.0f},{-1.0f,6.88373e-017f,0.0f},{-0.520564f,-0.853823f,0.0f}, +{-0.367913f,-0.92986f,0.0f},{-0.368116f,-0.92978f,0.0f},{-0.204975f,-0.978767f,0.0f}, +{-0.204694f,-0.978826f,0.0f},{-0.0356397f,-0.999365f,0.0f},{-0.0358431f,-0.999357f,0.0f}, +{0.134513f,-0.990912f,0.0f},{0.13427f,-0.990945f,0.0f},{0.300596f,-0.953752f,0.0f}, +{-0.792435f,-0.609957f,0.0f},{-0.792259f,-0.610185f,0.0f},{-0.69035f,-0.723475f,0.0f}, +{-0.87573f,-0.482801f,0.0f},{-0.875988f,-0.482333f,0.0f},{-0.939116f,-0.343601f,0.0f}, +{-0.938902f,-0.344184f,0.0f},{-0.980413f,-0.196955f,0.0f},{-0.980294f,-0.197546f,0.0f}, +{-0.998928f,-0.0463011f,0.0f},{-0.998951f,-0.0457846f,0.0f},{-0.994322f,0.106415f,0.0f}, +{-0.994363f,0.106027f,0.0f},{-0.966649f,0.256106f,0.0f},{-0.966705f,0.255892f,0.0f}, +{-0.916608f,0.399787f,0.0f},{-0.690559f,-0.723276f,0.0f},{-0.57228f,-0.820058f,0.0f}, +{-0.572718f,-0.819753f,0.0f},{-0.441003f,-0.897506f,0.0f},{-0.44156f,-0.897232f,0.0f}, +{-0.300123f,-0.953901f,0.0f},{-0.299547f,-0.954081f,0.0f},{-0.151186f,-0.988505f,0.0f}, +{-0.151697f,-0.988427f,0.0f},{0.00064926f,-1.0f,0.0f},{0.000259834f,-1.0f,0.0f}, +{0.152209f,-0.988348f,0.0f},{0.152428f,-0.988315f,0.0f},{0.961369f,-0.275264f,1.42615e-015f}, +{0.939639f,-0.342168f,-2.66114e-015f},{0.978324f,-0.207082f,-4.59815e-016f},{0.990413f,-0.138135f,-2.85529e-015f}, +{0.997621f,-0.068939f,3.76161e-015f},{1.0f,-1.00346e-016f,0.0f},{0.913294f,-0.4073f,1.05976e-015f}, +{0.847736f,-0.530418f,2.5098e-015f},{-0.968457f,-0.249181f,0.0f},{-0.983089f,-0.183127f,0.0f}, +{-0.993204f,-0.116388f,0.0f},{-0.998778f,-0.0494258f,0.0f},{-0.99985f,0.0173044f,0.0f}, +{-0.99985f,0.0173044f,0.0f},{-0.949392f,-0.314094f,0.0f},{-0.926039f,-0.377427f,0.0f}, +{-0.898602f,-0.438764f,0.0f},{-0.867335f,-0.497725f,0.0f},{-0.959254f,-0.282544f,0.0f}, +{-0.976164f,-0.217036f,0.0f},{-0.988582f,-0.150687f,0.0f},{-0.996469f,-0.0839576f,0.0f}, +{-0.99985f,-0.0173044f,0.0f},{-0.99985f,-0.0173045f,0.0f},{-0.937954f,-0.346759f,0.0f}, +{-0.912424f,-0.409245f,0.0f},{-0.882881f,-0.469596f,0.0f},{-0.849592f,-0.52744f,0.0f}, +{-0.998778f,0.0494258f,0.0f},{-0.968457f,0.249181f,0.0f},{-0.983089f,0.183127f,0.0f}, +{-0.993204f,0.116388f,0.0f},{-0.926039f,0.377427f,0.0f},{-0.898602f,0.438764f,0.0f}, +{-0.949392f,0.314094f,0.0f},{-0.867335f,0.497725f,0.0f},{-0.867335f,0.497725f,0.0f}, +{0.0f,1.0f,0.0f},{0.999811f,0.0194669f,0.0f},{0.998538f,-0.0540524f,0.0f}, +{0.995686f,0.0927821f,0.0f},{0.986243f,0.165305f,0.0f},{0.986243f,0.165305f,0.0f}, +{0.971639f,0.236469f,0.0f},{0.971639f,0.236469f,0.0f},{0.952114f,0.305744f,0.0f}, +{0.927972f,0.372649f,0.0f},{0.927972f,0.372649f,0.0f},{0.899577f,0.436762f,0.0f}, +{0.867335f,0.497725f,0.0f},{0.998538f,-0.0540524f,0.0f},{0.99188f,-0.127181f,0.0f}, +{0.99188f,-0.127181f,0.0f},{0.979932f,-0.199334f,0.0f},{0.979932f,-0.199333f,0.0f}, +{0.962874f,-0.26995f,0.0f},{0.962874f,-0.269949f,0.0f},{0.940964f,-0.338508f,0.0f}, +{0.940964f,-0.338508f,0.0f},{0.914521f,-0.404537f,0.0f},{0.914521f,-0.404537f,0.0f}, +{0.883925f,-0.467629f,0.0f},{0.883925f,-0.467629f,0.0f},{0.849592f,-0.52744f,0.0f}, +{-0.996469f,0.0839576f,0.0f},{-0.959254f,0.282544f,0.0f},{-0.976164f,0.217036f,0.0f}, +{-0.988582f,0.150687f,0.0f},{-0.912424f,0.409245f,0.0f},{-0.882881f,0.469596f,0.0f}, +{-0.937954f,0.346759f,0.0f},{-0.849592f,0.52744f,0.0f},{-0.849592f,0.52744f,0.0f}, +{9.54098e-018f,1.0f,0.0f},{0.998538f,0.0540524f,0.0f},{0.999811f,-0.0194669f,0.0f}, +{0.99188f,0.127181f,0.0f},{0.979932f,0.199334f,0.0f},{0.979932f,0.199334f,0.0f}, +{0.962874f,0.26995f,0.0f},{0.962874f,0.269949f,0.0f},{0.940964f,0.338508f,0.0f}, +{0.940964f,0.338508f,0.0f},{0.914521f,0.404537f,0.0f},{0.883925f,0.467629f,0.0f}, +{0.849592f,0.52744f,0.0f},{0.999811f,-0.0194669f,0.0f},{0.995686f,-0.0927821f,0.0f}, +{0.995686f,-0.0927822f,0.0f},{0.986243f,-0.165305f,0.0f},{0.986243f,-0.165305f,0.0f}, +{0.971639f,-0.236469f,0.0f},{0.971639f,-0.236469f,0.0f},{0.952114f,-0.305744f,0.0f}, +{0.952114f,-0.305744f,0.0f},{0.927972f,-0.372649f,0.0f},{0.927972f,-0.372649f,0.0f}, +{0.899577f,-0.436762f,0.0f},{0.899577f,-0.436762f,0.0f},{0.867335f,-0.497725f,0.0f}, +{1.0f,9.53287e-016f,0.0f},{0.997621f,0.068939f,0.0f},{0.961369f,0.275264f,3.04084e-016f}, +{0.978324f,0.207082f,-2.28333e-015f},{0.990413f,0.138135f,-2.93221e-015f},{0.882564f,0.470193f,-5.05182e-015f}, +{0.913294f,0.4073f,-3.19261e-015f},{0.939639f,0.342168f,5.36697e-016f},{0.847736f,0.530418f,6.88954e-016f}, +{0.809153f,0.587599f,0.0f},{1.0f,8.02768e-016f,0.0f},{0.94476f,0.327762f,0.0f}, +{0.882975f,0.469421f,0.0f},{0.882376f,0.470545f,0.0f},{0.797544f,0.603261f,0.0f}, +{0.797239f,0.603663f,0.0f},{0.692511f,0.721407f,0.0f},{0.692894f,0.721039f,0.0f}, +{0.571027f,0.820932f,0.0f},{0.570592f,0.821233f,0.0f},{0.434522f,0.900661f,0.0f}, +{0.434952f,0.900454f,0.0f},{0.287641f,0.957738f,0.0f},{0.288064f,0.957611f,0.0f}, +{0.133924f,0.990992f,0.0f},{0.133632f,0.991031f,0.0f},{-0.0235175f,0.999723f,0.0f}, +{-0.0237111f,0.999719f,0.0f},{-0.180697f,0.983539f,0.0f},{-0.180207f,0.983629f,0.0f}, +{-0.332466f,0.943115f,0.0f},{-0.333066f,0.942903f,0.0f},{-0.477082f,0.878859f,0.0f}, +{-0.47651f,0.879169f,0.0f},{-0.609201f,0.793016f,0.0f},{-0.608742f,0.793368f,0.0f}, +{-0.725859f,0.687844f,0.0f},{-0.726169f,0.687517f,0.0f},{-0.825089f,0.565003f,0.0f}, +{-0.82494f,0.565221f,0.0f},{-0.903508f,0.428571f,0.0f},{0.945177f,0.326559f,0.0f}, +{0.984817f,0.173596f,0.0f},{0.984729f,0.174093f,0.0f},{0.99986f,0.0167358f,0.0f}, +{0.999851f,0.0172664f,0.0f},{0.990076f,-0.140534f,0.0f},{0.99015f,-0.140011f,0.0f}, +{0.955854f,-0.293842f,0.0f},{0.955714f,-0.294298f,0.0f},{0.897616f,-0.440778f,0.0f}, +{0.897811f,-0.440382f,0.0f},{0.817237f,-0.576301f,0.0f},{0.817407f,-0.57606f,0.0f}, +{0.716558f,-0.697528f,0.0f},{0.716693f,-0.697389f,0.0f},{0.598295f,-0.801276f,0.0f}, +{0.597896f,-0.801574f,0.0f},{0.464451f,-0.885599f,0.0f},{0.465014f,-0.885303f,0.0f}, +{0.32015f,-0.947367f,0.0f},{0.319533f,-0.947575f,0.0f},{0.166733f,-0.986002f,0.0f}, +{0.167304f,-0.985905f,0.0f},{0.00983556f,-0.999952f,0.0f},{0.0102859f,-0.999947f,0.0f}, +{-0.146993f,-0.989138f,0.0f},{-0.147254f,-0.989099f,0.0f},{-0.300595f,-0.953752f,0.0f}, +{-0.300596f,-0.953752f,0.0f},{-2.28983e-015f,1.0f,8.32667e-017f},{-2.28983e-015f,1.0f,0.0f}, +{-2.22045e-015f,1.0f,0.0f},{-2.22045e-015f,1.0f,8.32667e-017f},{-0.845231f,0.5344f,0.0f}, +{-0.522153f,0.852852f,0.0f},{-0.522668f,0.852537f,0.0f},{-0.645678f,0.76361f,0.0f}, +{-0.754213f,0.65663f,0.0f},{-0.646072f,0.763276f,0.0f},{-0.754469f,0.656336f,0.0f}, +{-0.0920911f,0.995751f,0.0f},{-0.241953f,0.970288f,0.0f},{-0.0918041f,0.995777f,0.0f}, +{-0.387096f,0.92204f,0.0f},{-0.386523f,0.92228f,0.0f},{-0.242471f,0.970159f,0.0f}, +{0.211672f,0.977341f,0.0f},{0.357746f,0.933819f,0.0f},{0.357166f,0.934041f,0.0f}, +{0.0605578f,0.998165f,0.0f},{0.21115f,0.977454f,0.0f},{0.0602701f,0.998182f,0.0f}, +{0.495448f,0.868638f,0.0f},{0.621613f,0.783324f,0.0f},{0.621208f,0.783646f,0.0f}, +{0.494924f,0.868936f,0.0f},{0.733072f,0.680151f,0.0f},{0.733337f,0.679865f,0.0f}, +{0.828034f,0.560677f,0.0f},{0.82791f,0.560861f,0.0f},{0.903508f,0.428571f,0.0f}, +{-0.84535f,0.534213f,0.0f},{-0.990276f,0.13912f,4.54011e-017f},{-0.997566f,0.0697293f,1.60177e-015f}, +{-0.997566f,0.0697342f,0.0f},{-1.0f,-2.07578e-015f,-1.4803e-015f},{-1.0f,-2.02806e-015f,-1.4803e-015f}, +{-0.990274f,0.139127f,-3.66475e-016f},{-0.978162f,0.207842f,5.24967e-016f},{-0.978164f,0.207833f,3.07655e-016f}, +{-0.939737f,0.341898f,-3.47773e-016f},{-0.961291f,0.275537f,6.37877e-016f},{-0.961289f,0.275544f,-1.52727e-015f}, +{-0.939735f,0.341905f,-2.37226e-015f},{-0.883033f,0.46931f,2.77887e-015f},{-0.913605f,0.406602f,-3.38102e-016f}, +{-0.883029f,0.469318f,3.10571e-015f},{-0.848158f,0.529743f,2.82283e-015f},{-0.913609f,0.406593f,-1.20376e-015f}, +{-0.848155f,0.529748f,3.45062e-015f},{-0.809153f,0.587599f,0.0f},{-0.997566f,-0.0697342f,-4.56646e-016f}, +{-0.997566f,-0.0697293f,-4.12881e-016f},{-0.990276f,-0.13912f,-3.60924e-017f},{-0.990274f,-0.139127f,-1.04149e-015f}, +{-0.978162f,-0.207842f,4.88599e-016f},{-0.978164f,-0.207833f,1.561e-015f},{-0.961289f,-0.275544f,-1.12821e-015f}, +{-0.961291f,-0.275536f,-1.92629e-015f},{-0.939737f,-0.341898f,-9.44673e-016f},{-0.939735f,-0.341905f,1.30061e-015f}, +{-0.913605f,-0.406602f,-9.66815e-016f},{-0.913609f,-0.406593f,3.57334e-015f},{-0.883029f,-0.469318f,8.53281e-016f}, +{-0.883033f,-0.46931f,1.45735e-015f},{-0.848158f,-0.529743f,7.38791e-015f},{-0.848155f,-0.529748f,-1.31471e-015f}, +{-0.809153f,-0.587599f,0.0f},{-0.985476f,0.169813f,0.0f},{-1.0f,1.78369e-011f,0.0f}, +{-0.776263f,0.630409f,0.0f},{-0.872027f,0.489458f,0.0f},{-0.776125f,0.630579f,0.0f}, +{-0.871886f,0.489709f,0.0f},{-0.942433f,0.334396f,0.0f},{-0.942365f,0.334588f,0.0f}, +{-0.520564f,0.853823f,0.0f},{-0.367913f,0.92986f,0.0f},{-0.368116f,0.92978f,0.0f}, +{-0.657856f,0.753144f,0.0f},{-0.520449f,0.853893f,0.0f},{-0.657957f,0.753056f,0.0f}, +{-0.204975f,0.978767f,0.0f},{-0.0356397f,0.999365f,0.0f},{-0.0358431f,0.999357f,0.0f}, +{-0.204694f,0.978826f,0.0f},{0.13427f,0.990945f,0.0f},{0.134513f,0.990912f,0.0f}, +{0.300596f,0.953752f,0.0f},{-0.985518f,0.169572f,0.0f},{-0.990276f,0.13912f,3.04173e-018f}, +{-0.997566f,0.0697293f,-7.25445e-016f},{-0.997566f,0.0697342f,-1.94658e-015f},{-1.0f,-8.49997e-016f,7.40149e-016f}, +{-1.0f,-8.58945e-016f,7.40149e-016f},{-0.990274f,0.139127f,9.99482e-016f},{-0.978162f,0.207842f,-1.31242e-016f}, +{-0.978164f,0.207833f,-7.23987e-016f},{-0.939737f,0.341898f,1.07513e-015f},{-0.961291f,0.275537f,4.9842e-017f}, +{-0.961289f,0.275544f,-1.06724e-015f},{-0.939735f,0.341905f,4.42483e-016f},{-0.883033f,0.46931f,-5.00468e-016f}, +{-0.913605f,0.406602f,-9.39994e-016f},{-0.883029f,0.469318f,-3.26786e-016f},{-0.848158f,0.529743f,-3.13882e-016f}, +{-0.913609f,0.406593f,1.31525e-015f},{-0.848155f,0.529748f,3.92093e-016f},{-0.997566f,-0.0697342f,-8.82967e-016f}, +{-0.997566f,-0.0697293f,-1.86325e-015f},{-0.990276f,-0.13912f,5.61064e-016f},{-0.990274f,-0.139127f,-7.12127e-016f}, +{-0.978162f,-0.207842f,1.37216e-015f},{-0.978164f,-0.207833f,7.76865e-016f},{-0.961289f,-0.275544f,-2.27402e-016f}, +{-0.961291f,-0.275536f,5.04744e-016f},{-0.939737f,-0.341898f,1.28058e-015f},{-0.939735f,-0.341905f,-4.46437e-016f}, +{-0.913605f,-0.406602f,-3.06567e-015f},{-0.913609f,-0.406593f,-3.10301e-016f},{-0.883029f,-0.469318f,2.3739e-015f}, +{-0.883033f,-0.46931f,-1.98045e-016f},{-0.848158f,-0.529743f,-1.16918e-015f},{-0.848155f,-0.529748f,-6.74661e-017f}, +{-0.966705f,-0.255892f,0.0f},{-0.980294f,0.197546f,0.0f},{-0.980413f,0.196955f,0.0f}, +{-0.998928f,0.0463011f,0.0f},{-0.994363f,-0.106027f,0.0f},{-0.998951f,0.0457847f,0.0f}, +{-0.994322f,-0.106415f,0.0f},{-0.792435f,0.609957f,0.0f},{-0.87573f,0.482801f,0.0f}, +{-0.792259f,0.610185f,0.0f},{-0.939116f,0.343601f,0.0f},{-0.938902f,0.344184f,0.0f}, +{-0.875988f,0.482333f,0.0f},{-0.57228f,0.820058f,0.0f},{-0.441003f,0.897506f,0.0f}, +{-0.44156f,0.897232f,0.0f},{-0.69035f,0.723475f,0.0f},{-0.572718f,0.819753f,0.0f}, +{-0.690559f,0.723276f,0.0f},{-0.299547f,0.954081f,0.0f},{-0.151186f,0.988505f,0.0f}, +{-0.151697f,0.988427f,0.0f},{-0.300122f,0.953901f,0.0f},{0.000259834f,1.0f,0.0f}, +{0.000649324f,1.0f,0.0f},{0.152428f,0.988315f,0.0f},{0.152209f,0.988348f,0.0f}, +{-0.966649f,-0.256106f,0.0f},{4.44835e-016f,-1.0f,0.0f},{4.44835e-016f,-1.0f,2.25528e-032f}, +{0.882975f,-0.469421f,0.0f},{0.94476f,-0.327762f,0.0f},{0.945177f,-0.326558f,0.0f}, +{0.984729f,-0.174093f,0.0f},{0.984817f,-0.173596f,0.0f},{0.99986f,-0.0167358f,0.0f}, +{0.999851f,-0.0172664f,0.0f},{0.99015f,0.140011f,0.0f},{0.990076f,0.140534f,0.0f}, +{0.955714f,0.294298f,0.0f},{0.955854f,0.293842f,0.0f},{0.897616f,0.440778f,0.0f}, +{0.897811f,0.440382f,0.0f},{0.817407f,0.57606f,0.0f},{0.817237f,0.576301f,0.0f}, +{0.716693f,0.697389f,0.0f},{0.716558f,0.697528f,0.0f},{0.597896f,0.801574f,0.0f}, +{0.598295f,0.801276f,0.0f},{0.465014f,0.885303f,0.0f},{0.464451f,0.885599f,0.0f}, +{0.319533f,0.947575f,0.0f},{0.32015f,0.947367f,0.0f},{0.166733f,0.986002f,0.0f}, +{0.167304f,0.985905f,0.0f},{0.0102858f,0.999947f,0.0f},{0.00983533f,0.999952f,0.0f}, +{-0.147254f,0.989099f,0.0f},{-0.146993f,0.989138f,0.0f},{-0.300596f,0.953752f,0.0f}, +{0.882376f,-0.470545f,0.0f},{0.797239f,-0.603663f,0.0f},{0.797544f,-0.603261f,0.0f}, +{0.692511f,-0.721407f,0.0f},{0.692894f,-0.721039f,0.0f},{0.570593f,-0.821233f,0.0f}, +{0.571027f,-0.820931f,0.0f},{0.434952f,-0.900454f,0.0f},{0.434522f,-0.900661f,0.0f}, +{0.287641f,-0.957738f,0.0f},{0.288064f,-0.957611f,0.0f},{0.133632f,-0.991031f,0.0f}, +{0.133924f,-0.990992f,0.0f},{-0.023711f,-0.999719f,0.0f},{-0.0235174f,-0.999723f,0.0f}, +{-0.180207f,-0.983629f,0.0f},{-0.180697f,-0.983539f,0.0f},{-0.333066f,-0.942903f,0.0f}, +{-0.332466f,-0.943115f,0.0f},{-0.47651f,-0.879169f,0.0f},{-0.477082f,-0.878859f,0.0f}, +{-0.609201f,-0.793016f,0.0f},{-0.608742f,-0.793368f,0.0f},{-0.726169f,-0.687517f,0.0f}, +{-0.725859f,-0.687844f,0.0f},{-0.82494f,-0.565221f,0.0f},{-0.825089f,-0.565003f,0.0f}, +{-0.903508f,-0.428572f,0.0f},{-0.903508f,-0.428571f,0.0f},{1.0f,4.36505e-015f,0.0f}, +{0.997621f,0.068939f,-5.80505e-015f},{0.961369f,0.275264f,2.84622e-015f},{0.961369f,0.275264f,-3.04084e-016f}, +{0.978324f,0.207082f,-2.58988e-015f},{0.990413f,0.138135f,-1.46611e-015f},{0.882564f,0.470193f,-4.24366e-015f}, +{0.913294f,0.4073f,5.21937e-015f},{0.939639f,0.342168f,-2.1809e-015f},{0.847736f,0.530418f,5.12961e-015f}, +{1.0f,4.01384e-015f,0.0f},{1.0f,-1.21154e-014f,0.0f},{1.0f,-1.32168e-014f,0.0f}, +{0.985476f,0.169813f,0.0f},{0.942365f,0.334588f,0.0f},{0.985518f,0.169572f,0.0f}, +{0.871886f,0.489709f,0.0f},{0.942433f,0.334396f,0.0f},{0.872027f,0.489458f,0.0f}, +{0.776125f,0.630579f,0.0f},{0.657856f,0.753144f,0.0f},{0.776263f,0.63041f,0.0f}, +{0.520449f,0.853893f,0.0f},{0.657957f,0.753055f,0.0f},{0.520564f,0.853823f,0.0f}, +{0.367913f,0.92986f,0.0f},{0.204694f,0.978826f,0.0f},{0.368116f,0.92978f,0.0f}, +{0.0356397f,0.999365f,0.0f},{0.204975f,0.978767f,0.0f},{0.0358431f,0.999357f,0.0f}, +{-0.134513f,0.990912f,0.0f},{-0.13427f,0.990945f,0.0f},{0.985476f,-0.169813f,0.0f}, +{0.985518f,-0.169572f,0.0f},{0.942365f,-0.334588f,0.0f},{0.871886f,-0.489709f,0.0f}, +{0.942433f,-0.334396f,0.0f},{0.776125f,-0.630579f,0.0f},{0.872027f,-0.489458f,0.0f}, +{0.776263f,-0.63041f,0.0f},{0.657856f,-0.753144f,0.0f},{0.520449f,-0.853893f,0.0f}, +{0.657957f,-0.753055f,0.0f},{0.367913f,-0.92986f,0.0f},{0.520564f,-0.853823f,0.0f}, +{0.368116f,-0.92978f,0.0f},{0.204694f,-0.978826f,0.0f},{0.0356397f,-0.999365f,0.0f}, +{0.204975f,-0.978767f,0.0f},{-0.134513f,-0.990912f,0.0f},{0.0358431f,-0.999357f,0.0f}, +{-0.13427f,-0.990945f,0.0f},{-0.300595f,-0.953752f,0.0f},{-4.44089e-016f,-1.0f,0.0f}, +{0.0f,0.0f,1.0f},{0.0f,-8.67362e-019f,1.0f},{0.0f,-1.73472e-018f,1.0f}, +{0.0f,1.73472e-018f,1.0f},{0.0f,0.0f,-1.0f},{-1.0f,-1.52656e-016f,0.0f}, +{-0.980825f,-0.19489f,1.45281e-019f},{-0.98085f,-0.194766f,1.81637e-016f},{-0.707075f,-0.707139f,-1.96173e-016f}, +{-0.707766f,-0.706447f,-6.53208e-017f},{-0.831545f,-0.555458f,-8.35793e-018f},{-0.831851f,-0.554999f,-8.37482e-018f}, +{-0.924075f,-0.382212f,-1.1598e-017f},{-0.923954f,-0.382504f,6.09686e-018f},{-0.196168f,-0.98057f,3.23122e-017f}, +{-0.194654f,-0.980872f,-4.92519e-017f},{4.20972e-017f,-1.0f,-3.82702e-017f},{-0.555293f,-0.831655f,-6.45083e-017f}, +{-0.382179f,-0.924088f,-8.45327e-018f},{-0.384009f,-0.923329f,-9.41977e-017f},{0.384009f,-0.923329f,-1.56138e-016f}, +{0.555293f,-0.831655f,-1.12494e-016f},{0.382179f,-0.924088f,9.4505e-017f},{0.196168f,-0.98057f,-2.71773e-017f}, +{0.194653f,-0.980872f,6.34884e-017f},{4.54604e-017f,-1.0f,-3.82702e-017f},{0.707765f,-0.706447f,1.01783e-016f}, +{0.831545f,-0.555458f,-2.48815e-017f},{0.707075f,-0.707139f,9.34854e-017f},{0.556611f,-0.830773f,-8.68647e-017f}, +{0.831851f,-0.554999f,-8.49237e-019f},{0.923954f,-0.382504f,-9.704e-017f},{0.980825f,-0.19489f,1.73729e-016f}, +{0.924075f,-0.382212f,1.6343e-016f},{0.98085f,-0.194766f,1.40245e-016f},{1.0f,-7.40149e-017f,0.0f}, +{-0.556611f,-0.830773f,-1.92896e-016f},{-1.0f,1.4803e-016f,0.0f},{-0.980825f,-0.19489f,-4.38694e-018f}, +{-0.98085f,-0.194766f,4.18233e-018f},{-0.707075f,-0.707139f,-4.93567e-017f},{-0.707766f,-0.706447f,-2.15703e-015f}, +{-0.831545f,-0.555458f,-5.07927e-017f},{-0.831851f,-0.554999f,-4.9305e-015f},{-0.924075f,-0.382212f,3.43955e-017f}, +{-0.923954f,-0.382504f,-5.46969e-015f},{-0.196168f,-0.98057f,-3.58397e-016f},{-0.194654f,-0.980872f,-7.12354e-016f}, +{1.16112e-016f,-1.0f,-3.82702e-017f},{-0.555293f,-0.831655f,1.61234e-015f},{-0.382179f,-0.924088f,1.08551e-016f}, +{-0.384009f,-0.923329f,-1.31452e-015f},{0.384009f,-0.923329f,-3.29687e-016f},{0.555293f,-0.831655f,-1.59609e-015f}, +{0.382179f,-0.924088f,-1.27979e-015f},{0.196168f,-0.98057f,-1.20008e-015f},{0.194653f,-0.980872f,-1.9888e-016f}, +{8.70936e-017f,-1.0f,-3.82702e-017f},{0.707765f,-0.706447f,2.35803e-015f},{0.831545f,-0.555458f,3.17694e-015f}, +{0.707075f,-0.707139f,-9.84182e-016f},{0.556611f,-0.830773f,1.53785e-015f},{0.831851f,-0.554999f,1.40897e-015f}, +{0.923954f,-0.382504f,-2.22899e-015f},{0.980825f,-0.19489f,3.27834e-015f},{0.924075f,-0.382212f,3.28529e-015f}, +{0.98085f,-0.194766f,-9.75854e-016f},{1.0f,2.36848e-015f,0.0f},{-0.556611f,-0.830773f,1.67042e-015f}, +{-0.980825f,-0.19489f,0.0f},{-0.98085f,-0.194766f,0.0f},{-0.707075f,-0.707139f,1.25613e-014f}, +{-0.707766f,-0.706447f,-6.27842e-015f},{-0.831545f,-0.555458f,0.0f},{-0.831851f,-0.554999f,-4.92555e-015f}, +{-0.924075f,-0.382212f,0.0f},{-0.923954f,-0.382504f,-5.47091e-015f},{-0.196168f,-0.98057f,-2.90387e-016f}, +{-0.194654f,-0.980872f,2.32767e-015f},{-2.36848e-015f,-1.0f,5.92119e-015f},{-0.555293f,-0.831655f,1.644e-015f}, +{-0.382179f,-0.924088f,0.0f},{-0.384009f,-0.923329f,-1.1369e-015f},{0.384009f,-0.923329f,-1.65103e-015f}, +{0.555293f,-0.831655f,-4.10619e-015f},{0.382179f,-0.924088f,5.70815e-015f},{0.196168f,-0.98057f,-1.30674e-015f}, +{0.194653f,-0.980872f,4.0678e-015f},{2.2084e-031f,-1.0f,5.92119e-015f},{0.707765f,-0.706447f,1.05014e-015f}, +{0.831545f,-0.555458f,1.1685e-014f},{0.707075f,-0.707139f,-5.88803e-015f},{0.556611f,-0.830773f,8.27016e-016f}, +{0.831851f,-0.554999f,2.82305e-015f},{0.923954f,-0.382504f,-2.11639e-015f},{0.980825f,-0.19489f,1.50995e-015f}, +{0.924075f,-0.382212f,3.07935e-015f},{0.98085f,-0.194766f,-2.25716e-015f},{-0.556611f,-0.830773f,1.6479e-015f}, +{-0.707075f,-0.707139f,1.24959e-014f},{-0.707766f,-0.706447f,-4.18301e-015f},{-0.831851f,-0.554999f,1.53923e-016f}, +{-0.924075f,-0.382212f,1.70988e-016f},{-0.923954f,-0.382504f,-1.70966e-016f},{-0.196168f,-0.98057f,0.0f}, +{-0.194654f,-0.980872f,2.89496e-015f},{-0.555293f,-0.831655f,5.13749e-017f},{-0.382179f,-0.924088f,-3.53586e-017f}, +{-0.384009f,-0.923329f,-3.5528e-017f},{0.384009f,-0.923329f,-1.34904e-015f},{0.555293f,-0.831655f,-2.51357e-015f}, +{0.382179f,-0.924088f,6.82195e-015f},{0.196168f,-0.98057f,9.07461e-018f},{0.194653f,-0.980872f,4.37396e-015f}, +{0.707765f,-0.706447f,-1.17623e-015f},{0.831545f,-0.555458f,8.7231e-015f},{0.707075f,-0.707139f,-4.93948e-015f}, +{0.556611f,-0.830773f,-6.85704e-016f},{0.831851f,-0.554999f,1.51229e-015f},{0.923954f,-0.382504f,1.13336e-017f}, +{0.980825f,-0.19489f,-1.84175e-015f},{0.924075f,-0.382212f,-4.11823e-017f},{0.98085f,-0.194766f,-1.37362e-015f}, +{-0.556611f,-0.830773f,-5.14968e-017f},{-1.0f,-2.36848e-015f,0.0f},{-0.980825f,-0.19489f,1.15398e-015f}, +{-0.98085f,-0.194766f,-5.8078e-015f},{-0.707075f,-0.707139f,-4.18672e-015f},{-0.707766f,-0.706447f,-3.90231e-018f}, +{-0.831545f,-0.555458f,-1.64449e-015f},{-0.831851f,-0.554999f,-1.64313e-015f},{-0.923954f,-0.382504f,0.0f}, +{-0.194654f,-0.980872f,1.16384e-015f},{-1.18424e-015f,-1.0f,2.96059e-015f},{-0.555293f,-0.831655f,-4.92439e-015f}, +{-0.382179f,-0.924088f,-3.86733e-015f},{-0.384009f,-0.923329f,0.0f},{0.384009f,-0.923329f,7.37719e-016f}, +{0.555293f,-0.831655f,6.15548e-015f},{0.382179f,-0.924088f,-1.29612e-015f},{0.196168f,-0.98057f,2.90388e-016f}, +{0.194653f,-0.980872f,8.70064e-016f},{1.1042e-031f,-1.0f,2.96059e-015f},{0.707765f,-0.706447f,5.22145e-016f}, +{0.831545f,-0.555458f,-4.18055e-015f},{0.707075f,-0.707139f,-2.09354e-015f},{0.556611f,-0.830773f,-3.39113e-015f}, +{0.831851f,-0.554999f,3.13065e-015f},{0.923954f,-0.382504f,-1.37855e-015f},{0.980825f,-0.19489f,1.62549e-015f}, +{0.924075f,-0.382212f,4.51372e-015f},{0.98085f,-0.194766f,-1.82655e-015f},{1.0f,-1.4803e-016f,0.0f}, +{-0.556611f,-0.830773f,0.0f},{-0.98085f,-0.194766f,1.81494e-016f},{-0.707075f,-0.707139f,-6.54176e-017f}, +{-0.707766f,-0.706447f,2.0915e-015f},{-0.196168f,-0.98057f,-9.0746e-018f},{-0.194654f,-0.980872f,1.45198e-015f}, +{-0.382179f,-0.924088f,-2.77121e-015f},{0.384009f,-0.923329f,-7.36693e-016f},{0.555293f,-0.831655f,6.1298e-015f}, +{0.382179f,-0.924088f,7.10482e-016f},{0.196168f,-0.98057f,0.0f},{0.194653f,-0.980872f,7.25991e-016f}, +{0.707765f,-0.706447f,1.02144e-015f},{0.831545f,-0.555458f,-2.93013e-016f},{0.707075f,-0.707139f,-1.89729e-015f}, +{0.556611f,-0.830773f,-1.57586e-015f},{0.831851f,-0.554999f,1.11762e-015f},{0.923954f,-0.382504f,-1.18487e-015f}, +{0.980825f,-0.19489f,-5.42824e-018f},{0.924075f,-0.382212f,-3.75468e-016f},{0.98085f,-0.194766f,1.1167e-015f}, +{0.964306f,-0.26479f,-8.54143e-016f},{0.965341f,0.260991f,-9.92332e-016f},{0.999998f,-0.00196876f,9.33927e-016f}, +{-0.801458f,-0.598051f,5.32077e-015f},{-0.917689f,-0.397299f,-1.49105e-015f},{-0.917616f,-0.397468f,-6.24691e-015f}, +{-0.801348f,-0.598198f,-1.4703e-015f},{-0.641892f,-0.766795f,-2.89037e-015f},{-0.642216f,-0.766524f,1.1573e-014f}, +{-0.230441f,-0.973086f,-3.46847e-015f},{-0.448409f,-0.893828f,8.3968e-015f},{-0.448005f,-0.894031f,-2.52105e-015f}, +{-0.230122f,-0.973162f,-4.53038e-015f},{-0.98448f,-0.175498f,-1.45732e-015f},{-0.998433f,0.0559597f,2.95596e-015f}, +{-0.984554f,-0.175082f,-1.87817e-015f},{-0.998408f,0.0564113f,2.28784e-015f},{-0.958688f,0.28446f,3.99223e-015f}, +{-0.958595f,0.284774f,3.98982e-015f},{0.718867f,0.695147f,4.38213e-015f},{0.718867f,0.695147f,-2.66034e-016f}, +{0.258065f,0.966128f,4.76769e-016f},{-1.40172e-014f,1.0f,0.0f},{0.506909f,0.862f,6.5491e-015f}, +{-2.10257e-014f,1.0f,0.0f},{0.969751f,-0.244096f,-3.5888e-016f},{0.956928f,0.290324f,-2.78281e-016f}, +{0.999712f,0.0239869f,-1.31722e-016f},{-0.925087f,0.379756f,3.80183e-015f},{-0.810449f,0.58581f,4.06854e-015f}, +{-0.810565f,0.585648f,-2.66995e-016f},{-0.925162f,0.379572f,1.89621e-015f},{-0.988265f,0.152747f,3.03551e-015f}, +{-0.996526f,-0.0832844f,-3.77295e-016f},{-0.996566f,-0.0828045f,-1.86673e-015f},{-0.988334f,0.152299f,-2.57409e-015f}, +{-0.949486f,-0.313809f,-5.48639e-015f},{-0.949377f,-0.314139f,1.66453e-015f},{-0.651023f,0.759058f,-4.17468e-015f}, +{-0.455278f,0.890349f,1.28807e-015f},{-0.650679f,0.759353f,-3.53307e-015f},{-0.45485f,0.890568f,-1.28999e-015f}, +{-0.234187f,0.972192f,1.38667e-015f},{-0.233849f,0.972273f,0.0f},{-5.08163e-016f,1.0f,0.0f}, +{-0.810565f,-0.585648f,-2.93375e-015f},{-0.925162f,-0.379572f,-6.84758e-016f},{-0.925087f,-0.379756f,1.3694e-015f}, +{-0.810449f,-0.58581f,-4.73361e-015f},{-0.651023f,-0.759058f,-1.72543e-015f},{-0.45485f,-0.890568f,-8.32791e-016f}, +{-0.455278f,-0.890349f,2.46088e-015f},{-0.650679f,-0.759353f,-3.9742e-015f},{4.0653e-015f,-1.0f,0.0f}, +{-0.234187f,-0.972192f,4.48967e-016f},{-0.233849f,-0.972273f,-2.92082e-015f},{-0.988265f,-0.152747f,1.23682e-015f}, +{-0.996566f,0.0828045f,2.45151e-016f},{-0.988334f,-0.152299f,4.16364e-015f},{-0.996526f,0.0832843f,4.93142e-016f}, +{-0.949486f,0.313809f,0.0f},{-0.949377f,0.314139f,-9.30039e-016f},{-0.917616f,0.397468f,1.07392e-015f}, +{-0.801348f,0.598198f,7.5915e-016f},{-0.801458f,0.598051f,3.66985e-015f},{-0.917689f,0.397299f,3.03814e-015f}, +{-0.984554f,0.175082f,-5.42488e-016f},{-0.98448f,0.175498f,-2.04441e-015f},{-0.958688f,-0.28446f,9.93802e-016f}, +{-0.998433f,-0.0559597f,8.52548e-017f},{-0.998408f,-0.0564112f,5.09934e-015f},{-0.958595f,-0.284774f,-3.46074e-015f}, +{-0.642216f,0.766524f,-1.23434e-015f},{-0.448409f,0.893828f,-1.65391e-016f},{-0.641892f,0.766795f,-1.41886e-016f}, +{-0.448005f,0.894031f,-1.65429e-016f},{-0.230441f,0.973086f,-1.04236e-015f},{-0.230122f,0.973162f,1.04144e-015f}, +{-2.5659e-016f,1.0f,0.0f},{0.709621f,0.704584f,3.94851e-016f},{0.254108f,0.967176f,9.46083e-017f}, +{0.499432f,0.866353f,4.18692e-016f},{-3.8902e-016f,1.0f,0.0f},{0.43334f,-0.90123f,-1.30162e-016f}, +{0.628551f,-0.777768f,1.84857e-017f},{0.788356f,-0.61522f,9.057e-018f},{0.788356f,-0.61522f,1.5327e-016f}, +{0.217989f,-0.975951f,2.24194e-018f},{5.05322e-016f,-1.0f,0.0f},{-0.104301f,0.994546f,1.88853e-016f}, +{-0.313328f,0.949645f,2.55439e-016f},{-0.508034f,0.861337f,-3.91932e-016f},{-0.675985f,0.736915f,5.02496e-017f}, +{0.104717f,0.994502f,9.68824e-018f},{0.104717f,0.994502f,-3.48663e-016f},{-0.508034f,-0.861337f,2.55007e-015f}, +{-0.313328f,-0.949645f,5.86924e-016f},{-0.104301f,-0.994546f,3.32457e-015f},{0.104717f,-0.994502f,-2.20034e-016f}, +{-0.675985f,-0.736915f,1.93154e-015f},{-0.104301f,0.994546f,-2.9348e-015f},{-0.313328f,0.949645f,-2.10139e-015f}, +{-0.508034f,0.861337f,2.51193e-016f},{-0.675985f,0.736915f,-2.46257e-015f},{-0.508034f,0.861337f,-1.08628e-015f}, +{0.104717f,0.994502f,-2.94432e-015f},{-0.508034f,-0.861337f,-2.36206e-015f},{-0.313328f,-0.949645f,8.49252e-015f}, +{-0.104301f,-0.994546f,3.30527e-015f},{0.104717f,-0.994502f,-8.68343e-015f},{-0.675985f,-0.736915f,2.50165e-016f}, +{0.628551f,0.777768f,-2.30266e-015f},{0.433341f,0.90123f,8.09474e-015f},{0.217989f,0.975951f,-9.69688e-015f}, +{0.788356f,0.61522f,7.28566e-015f},{-0.43334f,0.90123f,2.77046e-015f},{-0.628551f,0.777768f,1.84916e-015f}, +{-0.788356f,0.61522f,-2.91035e-015f},{-0.217989f,0.975951f,1.29075e-015f},{1.10775e-015f,1.0f,0.0f}, +{0.104301f,-0.994546f,-8.67894e-015f},{0.313328f,-0.949645f,4.68109e-015f},{0.508034f,-0.861337f,-8.439e-015f}, +{0.675985f,-0.736915f,-1.0665e-015f},{-0.104717f,-0.994502f,1.73559e-014f},{0.508034f,0.861337f,2.93947e-016f}, +{0.313328f,0.949645f,-4.18867e-015f},{0.104301f,0.994546f,-1.47222e-015f},{-0.104717f,0.994502f,7.95314e-016f}, +{0.675985f,0.736915f,-4.00264e-015f},{0.104301f,-0.994546f,-1.54397e-016f},{0.313328f,-0.949645f,7.14982e-018f}, +{0.508034f,-0.861337f,-9.40051e-017f},{0.675985f,-0.736915f,1.6011e-015f},{-0.104717f,-0.994502f,3.10024e-016f}, +{0.508034f,0.861337f,0.0f},{0.313328f,0.949645f,-1.4405e-016f},{0.104301f,0.994546f,-4.17183e-016f}, +{-0.104717f,0.994502f,2.05762e-016f},{0.675985f,0.736915f,0.0f},{0.675985f,0.736915f,2.27403e-015f}, +{-0.628551f,-0.777768f,1.89686e-015f},{-0.433341f,-0.90123f,1.60368e-015f},{-0.217989f,-0.975951f,5.05612e-016f}, +{-0.217989f,-0.975951f,4.12034e-016f},{6.12323e-017f,-1.0f,0.0f},{-0.788356f,-0.61522f,2.39092e-015f}, +{-0.980872f,0.194654f,-1.44073e-016f},{-1.0f,-2.96059e-016f,-3.28692e-031f},{-0.923329f,-0.384009f,-2.13958e-016f}, +{-0.924088f,-0.382179f,9.40449e-016f},{-0.98057f,-0.196168f,-7.62016e-016f},{-0.980872f,-0.194653f,6.1653e-016f}, +{-0.831655f,-0.555293f,6.67161e-016f},{-0.707139f,-0.707075f,-4.57955e-016f},{-0.706447f,-0.707765f,4.57334e-016f}, +{-0.555458f,-0.831545f,8.32431e-017f},{-0.554999f,-0.831851f,-2.05391e-016f},{-0.830773f,-0.556611f,-3.85076e-016f}, +{-0.19489f,-0.980825f,-3.63028e-018f},{-0.194766f,-0.98085f,-2.22141e-016f},{-0.382212f,-0.924075f,5.86375e-016f}, +{-0.382504f,-0.923954f,-2.95917e-016f},{-1.85037e-017f,-1.0f,0.0f},{-0.98057f,0.196168f,-1.01605e-015f}, +{-0.924088f,0.382179f,-1.22649e-015f},{-0.923329f,0.384009f,-1.99588e-016f},{-0.830773f,0.556611f,-1.04527e-016f}, +{-0.831655f,0.555293f,-4.10999e-016f},{-0.706447f,0.707766f,5.22876e-016f},{-0.707139f,0.707075f,5.23388e-016f}, +{-0.555458f,0.831545f,-6.15467e-016f},{-0.554999f,0.831851f,-4.10782e-016f},{-0.382212f,0.924075f,-1.36791e-015f}, +{-0.382504f,0.923954f,0.0f},{-0.194766f,0.98085f,-8.7013e-016f},{-0.19489f,0.980825f,0.0f}, +{-3.33067e-016f,1.0f,0.0f},{-2.96059e-016f,1.0f,0.0f},{-0.980872f,0.194654f,0.0f}, +{-0.923329f,-0.384009f,7.57929e-018f},{-0.924088f,-0.382179f,2.41708e-016f},{-0.98057f,-0.196168f,-1.26994e-016f}, +{-0.980872f,-0.194653f,-9.14525e-017f},{-0.831655f,-0.555293f,4.10524e-016f},{-0.707139f,-0.707075f,1.14487e-016f}, +{-0.706447f,-0.707765f,-5.72353e-016f},{-0.555458f,-0.831545f,-9.69264e-018f},{-0.554999f,-0.831851f,4.97064e-016f}, +{-0.830773f,-0.556611f,5.13819e-016f},{-2.96059e-016f,-1.0f,0.0f},{-0.19489f,-0.980825f,-1.02781e-015f}, +{-0.194766f,-0.98085f,8.39508e-016f},{-0.382212f,-0.924075f,4.37371e-016f},{-0.382504f,-0.923954f,1.06278e-016f}, +{-5.92119e-016f,-1.0f,0.0f},{-0.98057f,0.196168f,-7.25968e-017f},{-0.924088f,0.382179f,0.0f}, +{-0.923329f,0.384009f,-1.42112e-016f},{-0.830773f,0.556611f,-5.13435e-016f},{-0.831655f,0.555293f,2.055e-016f}, +{-0.706447f,0.707766f,-1.04673e-015f},{-0.707139f,0.707075f,2.6167e-016f},{-0.555458f,0.831545f,6.15467e-016f}, +{-0.382212f,0.924075f,0.0f},{-0.194766f,0.98085f,7.25975e-016f},{-0.19489f,0.980825f,-8.70204e-016f}, +{-1.85037e-017f,1.0f,0.0f},{-0.144611f,0.989489f,-3.80291e-017f},{0.0759712f,0.99711f,-5.623e-017f}, +{-0.358149f,0.933664f,-9.55933e-016f},{-0.358149f,0.933664f,1.99014e-016f},{-0.549837f,0.835272f,0.0f}, +{0.2878f,0.957691f,0.0f},{0.707107f,-0.707107f,0.0f},{0.54721f,-0.836995f,0.0f}, +{0.368095f,-0.929788f,0.0f},{0.181963f,-0.983305f,0.0f},{1.53707e-012f,-1.0f,0.0f}, +{8.42952e-008f,-1.0f,0.0f},{0.836995f,-0.54721f,0.0f},{0.929788f,-0.368095f,0.0f}, +{0.983305f,-0.181963f,0.0f},{1.0f,3.07487e-012f,0.0f},{1.0f,3.07526e-012f,0.0f}, +{-0.739259f,0.673422f,0.0f},{-0.710614f,0.703582f,0.0f},{-0.739259f,0.673421f,0.0f}, +{-0.766626f,0.642094f,0.0f},{-0.766624f,0.642096f,0.0f},{-0.792665f,0.609658f,0.0f}, +{-0.792663f,0.60966f,0.0f},{-0.817331f,0.576168f,0.0f},{-0.817333f,0.576166f,0.0f}, +{-0.840587f,0.541677f,0.0f},{-0.840585f,0.54168f,0.0f},{-0.862386f,0.506252f,0.0f}, +{-0.862384f,0.506254f,0.0f},{-0.882691f,0.469953f,0.0f},{-0.882693f,0.46995f,0.0f}, +{-0.901473f,0.432835f,0.0f},{-0.901471f,0.432838f,0.0f},{-0.918693f,0.394972f,0.0f}, +{-0.918692f,0.394974f,0.0f},{-0.934323f,0.356428f,0.0f},{-0.934324f,0.356425f,0.0f}, +{-0.948338f,0.317262f,0.0f},{-0.948337f,0.317264f,0.0f},{-0.960711f,0.277549f,0.0f}, +{-0.960711f,0.277552f,0.0f},{-0.971422f,0.237359f,0.0f},{-0.971423f,0.237356f,0.0f}, +{-0.980453f,0.196753f,0.0f},{-0.980453f,0.196756f,0.0f},{-0.987787f,0.155809f,0.0f}, +{-0.987787f,0.155812f,0.0f},{-0.993412f,0.114599f,0.0f},{-0.993412f,0.114596f,0.0f}, +{-0.997318f,0.0731848f,0.0f},{-0.997318f,0.073187f,0.0f},{-0.999499f,0.0316463f,0.0f}, +{-0.999499f,0.0316489f,0.0f},{-0.999951f,-0.00994395f,0.0f},{-0.999951f,-0.00994627f,0.0f}, +{-0.998672f,-0.0515206f,0.0f},{-0.710614f,0.703582f,0.0f},{-0.680741f,0.732525f,0.0f}, +{-0.680739f,0.732526f,0.0f},{-0.649687f,0.760202f,0.0f},{-0.649688f,0.760201f,0.0f}, +{-0.61751f,0.786563f,0.0f},{-0.617513f,0.786561f,0.0f},{-0.584268f,0.811561f,0.0f}, +{-0.584265f,0.811563f,0.0f},{-0.55001f,0.835158f,0.0f},{-0.550013f,0.835156f,0.0f}, +{-0.514803f,0.857309f,0.0f},{-0.514806f,0.857307f,0.0f},{-0.478708f,0.877974f,0.0f}, +{-0.478705f,0.877976f,0.0f},{-0.441779f,0.897124f,0.0f},{-0.441782f,0.897123f,0.0f}, +{-0.404088f,0.91472f,0.0f},{-0.404092f,0.914719f,0.0f},{-0.365702f,0.930732f,0.0f}, +{-0.365699f,0.930733f,0.0f},{-0.326677f,0.945136f,0.0f},{-0.326679f,0.945135f,0.0f}, +{-0.287089f,0.957904f,0.0f},{-0.287092f,0.957903f,0.0f},{-0.247008f,0.969013f,0.0f}, +{-0.247006f,0.969014f,0.0f},{-0.206494f,0.978448f,0.0f},{-0.206496f,0.978447f,0.0f}, +{-0.165625f,0.986189f,0.0f},{-0.165628f,0.986188f,0.0f},{-0.124472f,0.992223f,0.0f}, +{-0.12447f,0.992223f,0.0f},{-0.0830991f,0.996541f,0.0f},{-0.0831017f,0.996541f,0.0f}, +{-0.041585f,0.999135f,0.0f},{-0.0415873f,0.999135f,0.0f},{-1.92868e-016f,1.0f,0.0f}, +{-8.64379e-008f,1.0f,0.0f},{-0.0572333f,0.998361f,1.89979e-016f},{3.3736e-016f,1.0f,0.0f}, +{-0.114279f,0.993449f,0.0f},{-0.707107f,0.707107f,0.0f},{-0.822154f,0.569266f,0.0f}, +{-0.910446f,0.413628f,0.0f},{-0.821945f,0.569567f,0.0f},{-0.910644f,0.413191f,0.0f}, +{-0.969699f,0.244303f,0.0f},{-0.969779f,0.243984f,0.0f},{-0.997734f,0.0672808f,0.0f}, +{-0.993705f,-0.11203f,0.0f},{-0.997765f,0.0668255f,0.0f},{-0.957691f,-0.2878f,0.0f}, +{-0.993663f,-0.112396f,0.0f},{-0.569266f,0.822154f,0.0f},{-0.569567f,0.821945f,0.0f}, +{-0.413628f,0.910446f,0.0f},{-0.244303f,0.969699f,0.0f},{-0.413191f,0.910644f,0.0f}, +{-0.243985f,0.969779f,0.0f},{-0.0672808f,0.997734f,0.0f},{-0.0668255f,0.997765f,0.0f}, +{0.11203f,0.993705f,0.0f},{0.112396f,0.993663f,0.0f},{-0.823338f,-0.567551f,2.91569e-016f}, +{-0.877128f,-0.480256f,-1.36506e-015f},{-0.877118f,-0.480275f,1.00957e-015f},{-0.823334f,-0.567558f,5.00925e-017f}, +{-0.760897f,-0.648872f,1.44361e-016f},{-0.921684f,-0.387941f,1.25621e-016f},{-0.921695f,-0.387915f,6.82191e-016f}, +{-0.956563f,-0.291525f,-6.81027e-016f},{-0.956571f,-0.291499f,-7.61943e-016f},{-0.981386f,-0.192047f,6.553e-016f}, +{-0.98139f,-0.192025f,1.77659e-017f},{-0.995897f,-0.0904984f,-8.37279e-018f},{-0.995893f,-0.0905325f,-1.67519e-017f}, +{-0.999929f,0.0119218f,1.48019e-015f},{-0.993449f,0.114279f,0.0f},{-0.999926f,0.0121699f,0.0f}, +{-0.690461f,-0.723369f,-9.58068e-017f},{-0.760892f,-0.648879f,1.7081e-016f},{-0.690446f,-0.723384f,-1.49808e-016f}, +{-0.612765f,-0.790265f,1.16954e-016f},{-0.612743f,-0.790282f,-1.7266e-016f},{-0.528625f,-0.848856f,3.32998e-016f}, +{-0.438929f,-0.898522f,-5.4393e-016f},{-0.528601f,-0.84887f,4.57239e-016f},{-0.438908f,-0.898532f,-2.60926e-016f}, +{-0.344602f,-0.938749f,1.75687e-016f},{-0.34457f,-0.938761f,5.73784e-016f},{-0.246664f,-0.969101f,-5.54286e-016f}, +{-0.146104f,-0.989269f,0.0f},{-0.246424f,-0.969162f,-8.55909e-016f},{0.505064f,-0.863082f,-2.96041e-016f}, +{0.342733f,-0.939433f,-1.39064e-015f},{0.653412f,-0.757002f,-4.80673e-016f},{0.174993f,-0.98457f,-7.12538e-016f}, +{0.00988645f,-0.999951f,0.0f},{0.780028f,-0.625744f,-1.42742e-017f},{0.879277f,-0.47631f,-1.99991e-016f}, +{0.948437f,-0.316965f,-3.53543e-016f},{0.987776f,-0.155878f,8.15532e-017f},{1.0f,-1.95899e-012f,0.0f}, +{1.0f,-1.95907e-012f,0.0f},{-0.181963f,-0.983305f,0.0f},{-4.18691e-016f,-1.0f,0.0f}, +{-2.09346e-016f,-1.0f,0.0f},{-0.707107f,-0.707107f,0.0f},{-0.54721f,-0.836995f,0.0f}, +{-0.368095f,-0.929788f,0.0f},{-0.929788f,-0.368095f,0.0f},{-0.983305f,-0.181963f,0.0f}, +{-0.836995f,-0.54721f,0.0f},{-1.0f,-2.61682e-016f,0.0f},{-1.0f,-8.42937e-008f,0.0f}, +{-0.901678f,-0.432409f,-4.8007e-016f},{-0.823027f,-0.568002f,1.63014e-016f},{-0.957351f,-0.288928f,2.01882e-015f}, +{-0.957351f,-0.288928f,0.0f},{-0.989708f,-0.143098f,7.32531e-016f},{-0.72348f,-0.690346f,-1.05257e-015f}, +{-1.0f,-4.36853e-016f,0.0f},{-1.0f,-9.28313e-016f,0.0f},{-0.60671f,-0.794923f,-3.38738e-016f}, +{-0.477546f,-0.878607f,-8.64155e-016f},{-0.341342f,-0.939939f,-3.74916e-016f},{-0.203325f,-0.979111f,0.0f}, +{-0.791675f,-0.610942f,0.0f},{-0.765522f,-0.64341f,0.0f},{-0.738038f,-0.674759f,0.0f}, +{-0.765522f,-0.643409f,0.0f},{-0.709271f,-0.704936f,0.0f},{-0.738039f,-0.674758f,0.0f}, +{-0.709273f,-0.704934f,0.0f},{-0.679272f,-0.733887f,0.0f},{-0.648092f,-0.761562f,0.0f}, +{-0.679273f,-0.733885f,0.0f},{-0.615785f,-0.787914f,0.0f},{-0.648094f,-0.761561f,0.0f}, +{-0.615787f,-0.787913f,0.0f},{-0.582409f,-0.812896f,0.0f},{-0.54802f,-0.836465f,0.0f}, +{-0.58241f,-0.812895f,0.0f},{-0.512678f,-0.858581f,0.0f},{-0.548021f,-0.836464f,0.0f}, +{-0.51268f,-0.85858f,0.0f},{-0.476445f,-0.879204f,0.0f},{-0.439385f,-0.898299f,0.0f}, +{-0.476447f,-0.879203f,0.0f},{-0.40156f,-0.915833f,0.0f},{-0.439387f,-0.898298f,0.0f}, +{-0.401562f,-0.915832f,0.0f},{-0.363038f,-0.931774f,0.0f},{-0.323885f,-0.946097f,0.0f}, +{-0.36304f,-0.931774f,0.0f},{-0.284168f,-0.958774f,0.0f},{-0.323886f,-0.946096f,0.0f}, +{-0.28417f,-0.958774f,0.0f},{-0.243959f,-0.969786f,0.0f},{-0.24396f,-0.969785f,0.0f}, +{-0.816453f,-0.577412f,0.0f},{-0.816452f,-0.577413f,0.0f},{-0.839811f,-0.542879f,0.0f}, +{-0.861709f,-0.507402f,0.0f},{-0.83981f,-0.54288f,0.0f},{-0.88211f,-0.471044f,0.0f}, +{-0.861708f,-0.507404f,0.0f},{-0.882109f,-0.471046f,0.0f},{-0.900977f,-0.433866f,0.0f}, +{-0.918278f,-0.395935f,0.0f},{-0.900976f,-0.433869f,0.0f},{-0.933984f,-0.357316f,0.0f}, +{-0.918278f,-0.395937f,0.0f},{-0.933983f,-0.357318f,0.0f},{-0.948065f,-0.318075f,0.0f}, +{-0.960499f,-0.278282f,0.0f},{-0.948065f,-0.318077f,0.0f},{-0.971264f,-0.238005f,0.0f}, +{-0.960499f,-0.278284f,0.0f},{-0.971263f,-0.238007f,0.0f},{-0.98034f,-0.197314f,0.0f}, +{-0.987713f,-0.15628f,0.0f},{-0.98034f,-0.197316f,0.0f},{-0.993368f,-0.114975f,0.0f}, +{-0.987712f,-0.156283f,0.0f},{-0.993368f,-0.114977f,0.0f},{-0.997297f,-0.0734701f,0.0f}, +{-0.999493f,-0.0318375f,0.0f},{-0.997297f,-0.0734722f,0.0f},{-0.999951f,0.00985025f,0.0f}, +{-0.999493f,-0.0318392f,0.0f},{-0.999951f,0.00984923f,0.0f},{-0.998672f,0.0515206f,0.0f}, +{-0.5f,-0.866025f,0.0f},{-0.5f,-0.866025f,-4.07254e-016f},{0.997498f,-0.0706974f,4.22047e-015f}, +{0.999099f,-0.042441f,-4.49972e-015f},{0.999099f,-0.0424415f,-8.87378e-015f},{0.9999f,0.0141508f,-1.48015e-015f}, +{0.9999f,-0.014151f,0.0f},{0.9999f,-0.0141508f,-7.42169e-015f},{0.997498f,-0.0706979f,1.47659e-015f}, +{0.995098f,-0.0988972f,5.89216e-015f},{0.995098f,-0.0988976f,5.59937e-015f},{0.9919f,-0.127018f,-1.17465e-014f}, +{0.9919f,-0.127018f,-1.72436e-014f},{0.987909f,-0.155036f,-5.3906e-015f},{0.987909f,-0.155037f,5.84959e-015f}, +{0.983126f,-0.182932f,-2.36905e-015f},{0.983126f,-0.182931f,8.73191e-015f},{0.971202f,-0.238259f,8.626e-015f}, +{0.96407f,-0.265648f,-7.28139e-015f},{0.96407f,-0.265647f,-1.29898e-014f},{0.977555f,-0.210679f,-4.54082e-015f}, +{0.977555f,-0.21068f,0.0f},{0.971202f,-0.238258f,-1.29121e-014f},{0.956167f,-0.292823f,-1.73386e-015f}, +{0.956167f,-0.292823f,0.0f},{0.947497f,-0.319764f,5.61031e-015f},{0.947497f,-0.319764f,-1.89338e-015f}, +{0.938069f,-0.346449f,0.0f},{0.938069f,-0.346449f,7.60587e-015f},{0.927889f,-0.372856f,9.90971e-015f}, +{0.905308f,-0.424755f,5.3605e-015f},{0.905309f,-0.424755f,3.304e-016f},{0.916966f,-0.398966f,4.7247e-015f}, +{0.916966f,-0.398965f,5.42953e-015f},{0.927889f,-0.372857f,-7.70196e-015f},{0.892926f,-0.450204f,0.0f}, +{0.892926f,-0.450204f,5.33148e-015f},{0.879828f,-0.475292f,1.04193e-014f},{0.879828f,-0.475292f,1.04193e-014f}, +{0.866025f,-0.5f,0.0f},{0.9999f,0.014151f,8.90184e-015f},{0.999099f,0.042441f,-1.04784e-014f}, +{0.999099f,0.0424415f,-1.61429e-014f},{0.997498f,0.0706974f,8.65025e-015f},{0.995098f,0.0988972f,2.94608e-015f}, +{0.997498f,0.0706979f,-1.09175e-014f},{0.995098f,0.0988976f,1.39984e-015f},{0.9919f,0.127018f,-1.06363e-014f}, +{0.9919f,0.127018f,9.63801e-015f},{0.987909f,0.155036f,-7.40539e-015f},{0.983126f,0.182931f,-7.57272e-015f}, +{0.987909f,0.155037f,-2.5165e-015f},{0.983126f,0.182932f,2.18298e-015f},{0.977555f,0.210679f,7.64703e-015f}, +{0.977555f,0.21068f,-4.23518e-015f},{0.971202f,0.238258f,-1.03144e-014f},{0.96407f,0.265647f,-7.60334e-015f}, +{0.971202f,0.238259f,1.75636e-015f},{0.96407f,0.265648f,1.0869e-014f},{0.956167f,0.292823f,5.12754e-015f}, +{0.956167f,0.292823f,-8.24033e-015f},{0.947497f,0.319764f,3.07966e-016f},{0.938069f,0.346449f,-1.05337e-014f}, +{0.947497f,0.319764f,-8.2576e-015f},{0.938069f,0.346449f,-1.87656e-015f},{0.927889f,0.372856f,3.1746e-015f}, +{0.927889f,0.372857f,-3.31849e-015f},{0.916966f,0.398965f,3.06056e-015f},{0.905309f,0.424755f,7.49538e-015f}, +{0.916966f,0.398966f,4.02549e-015f},{0.905308f,0.424755f,1.46943e-015f},{0.892926f,0.450204f,-1.18685e-014f}, +{0.892926f,0.450204f,1.25672e-015f},{0.879828f,0.475292f,4.58408e-015f},{0.866025f,0.5f,0.0f}, +{0.879828f,0.475292f,1.83809e-015f},{0.5f,0.866025f,0.0f},{0.78179f,0.623541f,-1.15728e-015f}, +{0.807718f,0.589568f,-2.39133e-015f},{0.807717f,0.589571f,9.60223e-017f},{0.754434f,0.656376f,-5.72909e-015f}, +{0.754433f,0.656377f,-7.23689e-015f},{0.7257f,0.688011f,1.01846e-015f},{0.832169f,0.554522f,1.64171e-015f}, +{0.781789f,0.623543f,4.8494e-015f},{0.832171f,0.554519f,4.10543e-015f},{0.855102f,0.51846f,-9.96661e-016f}, +{0.855104f,0.518456f,1.53494e-015f},{0.876475f,0.481448f,-5.18977e-015f},{0.876473f,0.48145f,-4.02026e-015f}, +{0.896244f,0.443562f,-2.65341e-015f},{0.896245f,0.443559f,-3.96662e-015f},{0.914379f,0.40486f,0.0f}, +{0.930841f,0.365425f,0.0f},{0.914377f,0.404864f,-2.39728e-015f},{0.930842f,0.365423f,0.0f}, +{0.945605f,0.325317f,-3.67284e-015f},{0.945604f,0.32532f,0.0f},{0.97944f,0.201738f,3.58358e-015f}, +{0.969926f,0.243399f,-1.44121e-015f},{0.97944f,0.201735f,-3.41043e-015f},{0.95864f,0.284621f,7.36158e-015f}, +{0.958641f,0.284618f,-5.6763e-015f},{0.969926f,0.243401f,5.74311e-015f},{0.987165f,0.159705f,9.45645e-016f}, +{0.993087f,0.117381f,-1.03704e-014f},{0.987165f,0.159703f,-4.89956e-015f},{0.993087f,0.117378f,-6.9502e-016f}, +{0.997196f,0.07484f,0.0f},{0.999483f,0.0321655f,6.29904e-015f},{0.999482f,0.032168f,-5.91813e-015f}, +{0.997195f,0.0748434f,-8.86324e-016f},{0.999944f,-0.0105685f,-5.7957e-015f},{0.999944f,-0.0105657f,5.92086e-015f}, +{0.99858f,-0.0532826f,0.0f},{0.99858f,-0.05328f,0.0f},{0.995391f,-0.0958981f,0.0f}, +{0.695642f,0.718389f,-2.12686e-015f},{0.725699f,0.688012f,-3.16696e-015f},{0.69564f,0.718391f,6.73571e-017f}, +{0.664312f,0.747455f,3.69231e-016f},{0.66431f,0.747457f,-4.91688e-015f},{0.631769f,0.775156f,-3.61476e-016f}, +{0.598073f,0.801442f,-8.85326e-016f},{0.631767f,0.775159f,-5.10676e-016f},{0.59807f,0.801444f,-2.51436e-015f}, +{0.563284f,0.826264f,-2.63707e-016f},{0.563281f,0.826266f,-4.79448e-015f},{0.527466f,0.849576f,2.47204e-015f}, +{0.490685f,0.871337f,-7.45068e-016f},{0.527463f,0.849578f,6.28814e-016f},{0.490682f,0.871339f,-4.66609e-016f}, +{0.453007f,0.891507f,-5.36872e-018f},{0.453005f,0.891508f,1.90646e-015f},{0.414503f,0.910048f,-9.01947e-016f}, +{0.375241f,0.926927f,-7.55498e-016f},{0.414499f,0.91005f,-3.44627e-015f},{0.375238f,0.926928f,-8.26493e-018f}, +{0.335293f,0.942114f,7.4317e-016f},{0.335291f,0.942115f,-1.38718e-015f},{0.294734f,0.955579f,-6.60361e-018f}, +{0.253636f,0.9673f,1.39186e-016f},{0.294731f,0.95558f,-4.80822e-016f},{0.253634f,0.9673f,-1.1694e-015f}, +{0.212076f,0.977253f,-1.09093e-015f},{0.212073f,0.977254f,-1.42807e-015f},{0.170128f,0.985422f,-8.58064e-016f}, +{0.127868f,0.991791f,1.21011e-015f},{0.170124f,0.985423f,3.47036e-015f},{0.127866f,0.991791f,2.85545e-016f}, +{0.0853758f,0.996349f,-4.87227e-016f},{0.0853729f,0.996349f,3.21028e-015f},{0.0427275f,0.999087f,-3.76158e-016f}, +{1.41083e-016f,1.0f,0.0f},{0.0427249f,0.999087f,-2.9625e-015f},{1.54309e-016f,1.0f,0.0f}, +{1.0f,5.04647e-017f,0.0f},{1.0f,5.3829e-017f,0.0f},{0.998532f,0.0541567f,0.0f}, +{0.994135f,0.108145f,0.0f},{0.998534f,0.0541301f,0.0f},{0.986822f,0.161808f,0.0f}, +{0.99414f,0.108105f,0.0f},{0.986829f,0.161767f,0.0f},{0.976616f,0.214992f,0.0f}, +{0.963545f,0.267546f,0.0f},{0.976622f,0.214964f,0.0f},{0.947644f,0.319328f,0.0f}, +{0.963549f,0.267531f,0.0f},{0.947653f,0.319303f,0.0f},{0.928963f,0.370172f,0.0f}, +{0.90756f,0.419923f,0.0f},{0.928977f,0.370136f,0.0f},{0.883495f,0.46844f,0.0f}, +{0.907577f,0.419887f,0.0f},{0.883512f,0.468409f,0.0f},{0.856841f,0.515581f,0.0f}, +{0.827674f,0.56121f,0.0f},{0.856854f,0.515559f,0.0f},{0.796076f,0.605197f,0.0f}, +{0.827681f,0.561199f,0.0f},{0.796082f,0.605188f,0.0f},{0.762141f,0.647411f,0.0f}, +{0.725973f,0.687723f,0.0f},{0.762151f,0.6474f,0.0f},{0.687676f,0.726018f,0.0f}, +{0.725983f,0.687712f,0.0f},{0.687687f,0.726007f,0.0f},{0.647361f,0.762183f,0.0f}, +{0.605148f,0.796113f,0.0f},{0.647375f,0.762171f,0.0f},{0.56116f,0.827707f,0.0f}, +{0.605164f,0.796101f,0.0f},{0.561178f,0.827695f,0.0f},{0.515527f,0.856873f,0.0f}, +{0.468383f,0.883526f,0.0f},{0.515545f,0.856862f,0.0f},{0.419866f,0.907586f,0.0f}, +{0.4684f,0.883516f,0.0f},{0.419884f,0.907578f,0.0f},{0.370116f,0.928986f,0.0f}, +{0.319279f,0.947661f,0.0f},{0.370136f,0.928977f,0.0f},{0.267507f,0.963556f,0.0f}, +{0.319301f,0.947653f,0.0f},{0.267528f,0.96355f,0.0f},{0.214954f,0.976624f,0.0f}, +{0.16177f,0.986829f,0.0f},{0.214973f,0.97662f,0.0f},{0.108111f,0.994139f,0.0f}, +{0.161786f,0.986826f,0.0f},{0.108145f,0.994135f,0.0f},{0.0538298f,0.99855f,0.0f}, +{-2.15316e-016f,1.0f,0.0f},{0.0538044f,0.998551f,0.0f},{-2.35502e-016f,1.0f,0.0f}, +{0.998532f,-0.0541566f,0.0f},{0.998534f,-0.0541302f,0.0f},{0.994135f,-0.108145f,0.0f}, +{0.986822f,-0.161808f,0.0f},{0.99414f,-0.108105f,0.0f},{0.976616f,-0.214992f,0.0f}, +{0.986829f,-0.161767f,0.0f},{0.976622f,-0.214964f,0.0f},{0.963545f,-0.267546f,0.0f}, +{0.947644f,-0.319328f,0.0f},{0.963549f,-0.267531f,0.0f},{0.928963f,-0.370172f,0.0f}, +{0.947653f,-0.319303f,0.0f},{0.928977f,-0.370136f,0.0f},{0.90756f,-0.419923f,0.0f}, +{0.883495f,-0.46844f,0.0f},{0.907577f,-0.419887f,0.0f},{0.856841f,-0.515581f,0.0f}, +{0.883512f,-0.468409f,0.0f},{0.856854f,-0.515559f,0.0f},{0.827674f,-0.56121f,0.0f}, +{0.796076f,-0.605197f,0.0f},{0.827681f,-0.561199f,0.0f},{0.762141f,-0.647411f,0.0f}, +{0.796082f,-0.605188f,0.0f},{0.762151f,-0.6474f,0.0f},{0.725973f,-0.687723f,0.0f}, +{0.687676f,-0.726018f,0.0f},{0.725983f,-0.687712f,0.0f},{0.647361f,-0.762183f,0.0f}, +{0.687687f,-0.726007f,0.0f},{0.647375f,-0.762171f,0.0f},{0.605148f,-0.796113f,0.0f}, +{0.56116f,-0.827707f,0.0f},{0.605164f,-0.796101f,0.0f},{0.515527f,-0.856873f,0.0f}, +{0.561178f,-0.827695f,0.0f},{0.515545f,-0.856862f,0.0f},{0.468383f,-0.883526f,0.0f}, +{0.419866f,-0.907586f,0.0f},{0.468401f,-0.883516f,0.0f},{0.370116f,-0.928986f,0.0f}, +{0.419884f,-0.907578f,0.0f},{0.370136f,-0.928977f,0.0f},{0.319279f,-0.947661f,0.0f}, +{0.267507f,-0.963556f,0.0f},{0.319301f,-0.947653f,0.0f},{0.214954f,-0.976624f,0.0f}, +{0.267528f,-0.96355f,0.0f},{0.214973f,-0.97662f,0.0f},{0.16177f,-0.986829f,0.0f}, +{0.108111f,-0.994139f,0.0f},{0.161786f,-0.986826f,0.0f},{0.0538298f,-0.99855f,0.0f}, +{0.108145f,-0.994135f,0.0f},{0.0538045f,-0.998551f,0.0f},{1.19209e-007f,-1.0f,0.0f}, +{0.69564f,-0.718391f,-2.2967e-015f},{0.66431f,-0.747457f,4.30948e-015f},{0.664312f,-0.747455f,-2.35972e-015f}, +{0.725699f,-0.688012f,-2.11837e-015f},{0.7257f,-0.688011f,-4.7761e-015f},{0.754433f,-0.656377f,-3.42054e-015f}, +{0.631769f,-0.775156f,1.02241e-015f},{0.695642f,-0.718389f,1.63365e-016f},{0.631766f,-0.775159f,1.30928e-015f}, +{0.598073f,-0.801442f,-4.02386e-016f},{0.59807f,-0.801444f,3.14782e-015f},{0.563281f,-0.826266f,2.05014e-015f}, +{0.563284f,-0.826264f,2.15457e-016f},{0.527466f,-0.849576f,3.68245e-015f},{0.527463f,-0.849578f,-9.04405e-017f}, +{0.490682f,-0.871339f,2.82586e-015f},{0.453007f,-0.891507f,-1.11336e-015f},{0.490685f,-0.871337f,-3.98744e-016f}, +{0.453005f,-0.891508f,8.87668e-016f},{0.414499f,-0.91005f,3.62163e-016f},{0.414503f,-0.910048f,-2.33213e-015f}, +{0.294734f,-0.955579f,1.39294e-015f},{0.335291f,-0.942115f,1.29026e-015f},{0.294731f,-0.95558f,9.56661e-016f}, +{0.375241f,-0.926927f,3.09815e-015f},{0.375238f,-0.926928f,3.53892e-016f},{0.335293f,-0.942114f,1.78659e-015f}, +{0.253636f,-0.9673f,4.48455e-017f},{0.212075f,-0.977253f,9.31315e-017f},{0.253634f,-0.9673f,-3.87537e-015f}, +{0.212073f,-0.977254f,1.53976e-015f},{0.170124f,-0.985423f,-1.33727e-015f},{0.127866f,-0.991791f,1.31222e-015f}, +{0.127868f,-0.991791f,-1.43479e-015f},{0.170128f,-0.985422f,-1.08544e-015f},{0.0853729f,-0.996349f,-2.96511e-015f}, +{0.0853758f,-0.996349f,1.45956e-015f},{0.0427249f,-0.999087f,-1.45746e-015f},{0.0427275f,-0.999087f,2.97938e-015f}, +{1.41083e-016f,-1.0f,0.0f},{1.54309e-016f,-1.0f,0.0f},{0.781789f,-0.623543f,-8.12728e-016f}, +{0.754434f,-0.656376f,-2.4015e-015f},{0.78179f,-0.623541f,-9.35104e-016f},{0.807717f,-0.589571f,-3.8494e-015f}, +{0.807718f,-0.589569f,8.37214e-016f},{0.832169f,-0.554522f,-3.65599e-015f},{0.855102f,-0.51846f,-4.07623e-015f}, +{0.832171f,-0.554519f,2.81113e-015f},{0.855104f,-0.518456f,2.96789e-016f},{0.876473f,-0.48145f,3.95802e-015f}, +{0.876475f,-0.481448f,6.89284e-016f},{0.896244f,-0.443562f,7.12651e-016f},{0.914377f,-0.404864f,-1.93578e-015f}, +{0.896245f,-0.443559f,5.43092e-015f},{0.914379f,-0.40486f,-5.84661e-015f},{0.930841f,-0.365425f,1.20115e-015f}, +{0.930842f,-0.365423f,3.55128e-015f},{0.945604f,-0.32532f,2.23888e-015f},{0.95864f,-0.284621f,5.39664e-015f}, +{0.945605f,-0.325317f,4.0151e-015f},{0.958641f,-0.284618f,-2.22393e-015f},{0.969926f,-0.243401f,4.33048e-015f}, +{0.969926f,-0.243399f,4.23515e-015f},{0.97944f,-0.201738f,4.2777e-015f},{0.987165f,-0.159705f,5.95984e-015f}, +{0.97944f,-0.201735f,6.68731e-016f},{0.987165f,-0.159703f,-8.70338e-015f},{0.993087f,-0.117381f,-6.76187e-015f}, +{0.993087f,-0.117378f,7.13795e-015f},{0.997195f,-0.0748434f,-4.49833e-016f},{0.999482f,-0.0321679f,5.88869e-015f}, +{0.997196f,-0.07484f,-1.11652e-015f},{0.999483f,-0.0321656f,-2.74195e-016f},{0.999944f,0.0105657f,5.2388e-015f}, +{0.999944f,0.0105686f,-6.15843e-016f},{0.99858f,0.05328f,7.92959e-015f},{0.995391f,0.0958981f,0.0f}, +{0.99858f,0.0532825f,4.50329e-015f},{0.5f,-0.866025f,0.0f},{-0.9999f,-0.0141122f,0.0f}, +{-0.9999f,0.0141124f,0.0f},{-0.9999f,-0.0141125f,0.0f},{-0.999104f,-0.0423259f,0.0f}, +{-0.999104f,-0.0423254f,0.0f},{-0.997511f,-0.0705055f,0.0f},{-0.997511f,-0.0705051f,0.0f}, +{-0.995124f,-0.0986284f,0.0f},{-0.995124f,-0.0986291f,0.0f},{-0.991944f,-0.126674f,0.0f}, +{-0.991944f,-0.126673f,0.0f},{-0.987974f,-0.154618f,0.0f},{-0.987974f,-0.154617f,0.0f}, +{-0.983217f,-0.182438f,0.0f},{-0.983217f,-0.182439f,0.0f},{-0.977677f,-0.210114f,0.0f}, +{-0.977677f,-0.210113f,0.0f},{-0.971358f,-0.237622f,0.0f},{-0.971358f,-0.237622f,0.0f}, +{-0.964265f,-0.26494f,0.0f},{-0.964265f,-0.264941f,0.0f},{-0.956403f,-0.292049f,0.0f}, +{-0.956404f,-0.292048f,0.0f},{-0.94778f,-0.318924f,0.0f},{-0.947781f,-0.318923f,0.0f}, +{-0.938403f,-0.345544f,0.0f},{-0.938402f,-0.345545f,0.0f},{-0.928277f,-0.371891f,0.0f}, +{-0.928277f,-0.37189f,0.0f},{-0.917411f,-0.39794f,0.0f},{-0.917412f,-0.397939f,0.0f}, +{-0.905816f,-0.423672f,0.0f},{-0.905815f,-0.423672f,0.0f},{-0.893498f,-0.449067f,0.0f}, +{-0.893498f,-0.449067f,0.0f},{-0.880469f,-0.474105f,0.0f},{-0.880469f,-0.474104f,0.0f}, +{-0.866738f,-0.498763f,0.0f},{-0.866738f,-0.498764f,0.0f},{-0.852317f,-0.523026f,0.0f}, +{-0.9999f,0.0141122f,0.0f},{-0.999104f,0.0423254f,0.0f},{-0.999104f,0.0423259f,0.0f}, +{-0.997511f,0.0705055f,0.0f},{-0.997511f,0.0705051f,0.0f},{-0.995124f,0.0986291f,0.0f}, +{-0.995124f,0.0986285f,0.0f},{-0.991944f,0.126673f,0.0f},{-0.991944f,0.126674f,0.0f}, +{-0.987974f,0.154618f,0.0f},{-0.987974f,0.154617f,0.0f},{-0.983217f,0.182439f,0.0f}, +{-0.983217f,0.182438f,0.0f},{-0.977677f,0.210113f,0.0f},{-0.977677f,0.210114f,0.0f}, +{-0.971358f,0.237622f,0.0f},{-0.971358f,0.237622f,0.0f},{-0.964265f,0.264941f,0.0f}, +{-0.964265f,0.26494f,0.0f},{-0.956404f,0.292048f,0.0f},{-0.956403f,0.292049f,0.0f}, +{-0.94778f,0.318924f,0.0f},{-0.947781f,0.318923f,0.0f},{-0.938402f,0.345545f,0.0f}, +{-0.938403f,0.345544f,0.0f},{-0.928277f,0.37189f,0.0f},{-0.928277f,0.371891f,0.0f}, +{-0.917411f,0.39794f,0.0f},{-0.917412f,0.397939f,0.0f},{-0.905815f,0.423672f,0.0f}, +{-0.905816f,0.423672f,0.0f},{-0.893498f,0.449067f,0.0f},{-0.893498f,0.449067f,0.0f}, +{-0.880469f,0.474104f,0.0f},{-0.880469f,0.474104f,0.0f},{-0.866738f,0.498764f,0.0f}, +{-0.866738f,0.498764f,0.0f},{-0.852317f,0.523026f,0.0f},{-0.5f,0.866025f,0.0f}, +{-0.5f,0.866025f,-7.6671e-016f},{0.0f,-4.33681e-019f,1.0f},{0.0f,4.33681e-019f,1.0f}, +{-0.884642f,0.466272f,2.20644e-016f},{-0.777982f,0.628286f,5.89571e-016f},{-0.778033f,0.628223f,-5.53502e-016f}, +{-0.957996f,0.286781f,1.48116e-016f},{-0.88468f,0.466199f,-5.1317e-016f},{-0.958053f,0.286593f,-1.63827e-016f}, +{-0.995238f,-0.0974696f,3.44802e-016f},{-0.995356f,0.0962625f,-1.06856e-016f},{-0.995222f,-0.097635f,-4.56953e-017f}, +{-0.995334f,0.0964852f,-1.31963e-016f},{-0.642168f,0.766564f,0.0f},{-0.482138f,0.876095f,-7.37654e-016f}, +{-0.642017f,0.76669f,-1.10523e-015f},{-0.481942f,0.876203f,7.37698e-016f},{-0.303947f,0.952689f,0.0f}, +{-0.303789f,0.952739f,0.0f},{-0.715999f,0.698102f,1.29175e-016f},{-0.945908f,0.324434f,-5.70109e-016f}, +{-0.945908f,0.324434f,-3.35048e-016f},{-0.851699f,0.524032f,7.27349e-016f},{3.33067e-016f,-1.0f,0.0f}, +{0.19489f,-0.980825f,0.0f},{0.194766f,-0.98085f,-8.7013e-016f},{0.707139f,-0.707075f,5.23388e-016f}, +{0.706447f,-0.707766f,5.22876e-016f},{0.555458f,-0.831545f,-6.15467e-016f},{0.554999f,-0.831851f,-4.10782e-016f}, +{0.382212f,-0.924075f,-1.36791e-015f},{0.382504f,-0.923954f,0.0f},{0.98057f,-0.196168f,-1.01605e-015f}, +{0.980872f,-0.194654f,-1.44073e-016f},{0.831655f,-0.555293f,-4.10999e-016f},{0.924088f,-0.382179f,-1.22649e-015f}, +{0.923329f,-0.384009f,-1.99588e-016f},{0.923329f,0.384009f,-2.13958e-016f},{0.831655f,0.555293f,6.67161e-016f}, +{0.924088f,0.382179f,9.40449e-016f},{0.98057f,0.196168f,-7.62016e-016f},{0.980872f,0.194653f,6.1653e-016f}, +{1.0f,2.96059e-016f,-3.28692e-031f},{0.706447f,0.707765f,4.57334e-016f},{0.555458f,0.831545f,8.32431e-017f}, +{0.707139f,0.707075f,-4.57955e-016f},{0.830773f,0.556611f,-3.85076e-016f},{0.554999f,0.831851f,-2.05391e-016f}, +{0.382504f,0.923954f,-2.95917e-016f},{0.19489f,0.980825f,-3.63028e-018f},{0.382212f,0.924075f,5.86375e-016f}, +{0.194766f,0.98085f,-2.22141e-016f},{1.85037e-017f,1.0f,0.0f},{0.830773f,-0.556611f,-1.04527e-016f}, +{2.96059e-016f,-1.0f,0.0f},{1.85037e-017f,-1.0f,0.0f},{0.19489f,-0.980825f,-8.70204e-016f}, +{0.194766f,-0.98085f,7.25975e-016f},{0.707139f,-0.707075f,2.6167e-016f},{0.706447f,-0.707766f,-1.04673e-015f}, +{0.555458f,-0.831545f,6.15467e-016f},{0.382212f,-0.924075f,0.0f},{0.98057f,-0.196168f,-7.25968e-017f}, +{0.980872f,-0.194654f,0.0f},{0.831655f,-0.555293f,2.055e-016f},{0.924088f,-0.382179f,0.0f}, +{0.923329f,-0.384009f,-1.42112e-016f},{0.923329f,0.384009f,7.57929e-018f},{0.831655f,0.555293f,4.10524e-016f}, +{0.924088f,0.382179f,2.41708e-016f},{0.98057f,0.196168f,-1.26994e-016f},{0.980872f,0.194653f,-9.14525e-017f}, +{0.706447f,0.707765f,-5.72353e-016f},{0.555458f,0.831545f,-9.69264e-018f},{0.707139f,0.707075f,1.14487e-016f}, +{0.830773f,0.556611f,5.13819e-016f},{0.554999f,0.831851f,4.97064e-016f},{0.382504f,0.923954f,1.06278e-016f}, +{0.19489f,0.980825f,-1.02781e-015f},{0.382212f,0.924075f,4.37371e-016f},{0.194766f,0.98085f,8.39508e-016f}, +{2.96059e-016f,1.0f,0.0f},{5.92119e-016f,1.0f,0.0f},{0.830773f,-0.556611f,-5.13435e-016f}, +{0.144611f,-0.989489f,-3.80291e-017f},{-0.0759712f,-0.99711f,-5.623e-017f},{0.358149f,-0.933664f,-9.55933e-016f}, +{0.358149f,-0.933664f,1.99014e-016f},{0.549837f,-0.835272f,0.0f},{-0.2878f,-0.957691f,0.0f}, +{-0.54721f,0.836995f,0.0f},{-0.368095f,0.929788f,0.0f},{-0.181963f,0.983305f,0.0f}, +{-1.53707e-012f,1.0f,0.0f},{-8.42952e-008f,1.0f,0.0f},{-0.836995f,0.54721f,0.0f}, +{-0.929788f,0.368095f,0.0f},{-0.983305f,0.181963f,0.0f},{-1.0f,-3.07487e-012f,0.0f}, +{-1.0f,-3.07526e-012f,0.0f},{0.739259f,-0.673422f,0.0f},{0.710614f,-0.703582f,0.0f}, +{0.739259f,-0.673421f,0.0f},{0.766626f,-0.642094f,0.0f},{0.766624f,-0.642096f,0.0f}, +{0.792665f,-0.609658f,0.0f},{0.792663f,-0.60966f,0.0f},{0.817331f,-0.576168f,0.0f}, +{0.817333f,-0.576166f,0.0f},{0.840587f,-0.541677f,0.0f},{0.840585f,-0.54168f,0.0f}, +{0.862386f,-0.506252f,0.0f},{0.862384f,-0.506254f,0.0f},{0.882691f,-0.469953f,0.0f}, +{0.882693f,-0.46995f,0.0f},{0.901473f,-0.432835f,0.0f},{0.901471f,-0.432838f,0.0f}, +{0.918693f,-0.394972f,0.0f},{0.918692f,-0.394974f,0.0f},{0.934323f,-0.356428f,0.0f}, +{0.934324f,-0.356425f,0.0f},{0.948338f,-0.317262f,0.0f},{0.948337f,-0.317264f,0.0f}, +{0.960711f,-0.277549f,0.0f},{0.960711f,-0.277552f,0.0f},{0.971422f,-0.237359f,0.0f}, +{0.971423f,-0.237356f,0.0f},{0.980453f,-0.196753f,0.0f},{0.980453f,-0.196756f,0.0f}, +{0.987787f,-0.155809f,0.0f},{0.987787f,-0.155812f,0.0f},{0.993412f,-0.114599f,0.0f}, +{0.993412f,-0.114596f,0.0f},{0.997318f,-0.0731848f,0.0f},{0.997318f,-0.073187f,0.0f}, +{0.999499f,-0.0316463f,0.0f},{0.999499f,-0.0316489f,0.0f},{0.999951f,0.00994395f,0.0f}, +{0.999951f,0.00994627f,0.0f},{0.998672f,0.0515206f,0.0f},{0.710614f,-0.703582f,0.0f}, +{0.680741f,-0.732525f,0.0f},{0.680739f,-0.732526f,0.0f},{0.649687f,-0.760202f,0.0f}, +{0.649688f,-0.760201f,0.0f},{0.61751f,-0.786563f,0.0f},{0.617513f,-0.786561f,0.0f}, +{0.584268f,-0.811561f,0.0f},{0.584265f,-0.811563f,0.0f},{0.55001f,-0.835158f,0.0f}, +{0.550013f,-0.835156f,0.0f},{0.514803f,-0.857309f,0.0f},{0.514806f,-0.857307f,0.0f}, +{0.478708f,-0.877974f,0.0f},{0.478705f,-0.877976f,0.0f},{0.441779f,-0.897124f,0.0f}, +{0.441782f,-0.897123f,0.0f},{0.404088f,-0.91472f,0.0f},{0.404092f,-0.914719f,0.0f}, +{0.365702f,-0.930732f,0.0f},{0.365699f,-0.930733f,0.0f},{0.326677f,-0.945136f,0.0f}, +{0.326679f,-0.945135f,0.0f},{0.287089f,-0.957904f,0.0f},{0.287092f,-0.957903f,0.0f}, +{0.247008f,-0.969013f,0.0f},{0.247006f,-0.969014f,0.0f},{0.206494f,-0.978448f,0.0f}, +{0.206496f,-0.978447f,0.0f},{0.165625f,-0.986189f,0.0f},{0.165628f,-0.986188f,0.0f}, +{0.124472f,-0.992223f,0.0f},{0.12447f,-0.992223f,0.0f},{0.0830991f,-0.996541f,0.0f}, +{0.0831017f,-0.996541f,0.0f},{0.041585f,-0.999135f,0.0f},{0.0415873f,-0.999135f,0.0f}, +{1.92868e-016f,-1.0f,0.0f},{8.64379e-008f,-1.0f,0.0f},{0.0572333f,-0.998361f,1.89979e-016f}, +{-3.3736e-016f,-1.0f,0.0f},{0.114279f,-0.993449f,0.0f},{0.822154f,-0.569266f,0.0f}, +{0.910446f,-0.413628f,0.0f},{0.821945f,-0.569567f,0.0f},{0.910644f,-0.413191f,0.0f}, +{0.969699f,-0.244303f,0.0f},{0.969779f,-0.243984f,0.0f},{0.997734f,-0.0672808f,0.0f}, +{0.993705f,0.11203f,0.0f},{0.997765f,-0.0668255f,0.0f},{0.957691f,0.2878f,0.0f}, +{0.993663f,0.112396f,0.0f},{0.569266f,-0.822154f,0.0f},{0.569567f,-0.821945f,0.0f}, +{0.413628f,-0.910446f,0.0f},{0.244303f,-0.969699f,0.0f},{0.413191f,-0.910644f,0.0f}, +{0.243985f,-0.969779f,0.0f},{0.0672808f,-0.997734f,0.0f},{0.0668255f,-0.997765f,0.0f}, +{-0.11203f,-0.993705f,0.0f},{-0.112396f,-0.993663f,0.0f},{0.823338f,0.567551f,2.91569e-016f}, +{0.877128f,0.480256f,-1.36506e-015f},{0.877118f,0.480275f,1.00957e-015f},{0.823334f,0.567558f,5.00925e-017f}, +{0.760897f,0.648872f,1.44361e-016f},{0.921684f,0.387941f,1.25621e-016f},{0.921695f,0.387915f,6.82191e-016f}, +{0.956563f,0.291525f,-6.81027e-016f},{0.956571f,0.291499f,-7.61943e-016f},{0.981386f,0.192047f,6.553e-016f}, +{0.98139f,0.192025f,1.77659e-017f},{0.995897f,0.0904984f,-8.37279e-018f},{0.995893f,0.0905325f,-1.67519e-017f}, +{0.999929f,-0.0119218f,1.48019e-015f},{0.993449f,-0.114279f,0.0f},{0.999926f,-0.0121699f,0.0f}, +{0.690461f,0.723369f,-9.58068e-017f},{0.760892f,0.648879f,1.7081e-016f},{0.690446f,0.723384f,-1.49808e-016f}, +{0.612765f,0.790265f,1.16954e-016f},{0.612743f,0.790282f,-1.7266e-016f},{0.528625f,0.848856f,3.32998e-016f}, +{0.438929f,0.898522f,-5.4393e-016f},{0.528601f,0.84887f,4.57239e-016f},{0.438908f,0.898532f,-2.60926e-016f}, +{0.344602f,0.938749f,1.75687e-016f},{0.34457f,0.938761f,5.73784e-016f},{0.246664f,0.969101f,-5.54286e-016f}, +{0.146104f,0.989269f,0.0f},{0.246424f,0.969162f,-8.55909e-016f},{-0.505064f,0.863082f,-2.96041e-016f}, +{-0.342733f,0.939433f,-1.39064e-015f},{-0.653412f,0.757002f,-4.80673e-016f},{-0.174993f,0.98457f,-7.12538e-016f}, +{-0.00988645f,0.999951f,0.0f},{-0.780028f,0.625744f,-1.42742e-017f},{-0.879277f,0.47631f,-1.99991e-016f}, +{-0.948437f,0.316965f,-3.53543e-016f},{-0.987776f,0.155878f,8.15532e-017f},{-1.0f,1.95899e-012f,0.0f}, +{-1.0f,1.95907e-012f,0.0f},{0.181963f,0.983305f,0.0f},{4.18691e-016f,1.0f,0.0f}, +{2.09346e-016f,1.0f,0.0f},{0.707107f,0.707107f,0.0f},{0.54721f,0.836995f,0.0f}, +{0.368095f,0.929788f,0.0f},{0.929788f,0.368095f,0.0f},{0.983305f,0.181963f,0.0f}, +{0.836995f,0.54721f,0.0f},{1.0f,2.61682e-016f,0.0f},{1.0f,8.42937e-008f,0.0f}, +{0.901678f,0.432409f,-4.8007e-016f},{0.823027f,0.568002f,1.63014e-016f},{0.957351f,0.288928f,2.01882e-015f}, +{0.957351f,0.288928f,0.0f},{0.989708f,0.143098f,7.32531e-016f},{0.72348f,0.690346f,-1.05257e-015f}, +{1.0f,4.36853e-016f,0.0f},{1.0f,9.28313e-016f,0.0f},{0.60671f,0.794923f,-3.38738e-016f}, +{0.477546f,0.878607f,-8.64155e-016f},{0.341342f,0.939939f,-3.74916e-016f},{0.203325f,0.979111f,0.0f}, +{0.791675f,0.610942f,0.0f},{0.765522f,0.64341f,0.0f},{0.738038f,0.674759f,0.0f}, +{0.765522f,0.643409f,0.0f},{0.709271f,0.704936f,0.0f},{0.738039f,0.674758f,0.0f}, +{0.709273f,0.704934f,0.0f},{0.679272f,0.733887f,0.0f},{0.648092f,0.761562f,0.0f}, +{0.679273f,0.733885f,0.0f},{0.615785f,0.787914f,0.0f},{0.648094f,0.761561f,0.0f}, +{0.615787f,0.787913f,0.0f},{0.582409f,0.812896f,0.0f},{0.54802f,0.836465f,0.0f}, +{0.58241f,0.812895f,0.0f},{0.512678f,0.858581f,0.0f},{0.548021f,0.836464f,0.0f}, +{0.51268f,0.85858f,0.0f},{0.476445f,0.879204f,0.0f},{0.439385f,0.898299f,0.0f}, +{0.476447f,0.879203f,0.0f},{0.40156f,0.915833f,0.0f},{0.439387f,0.898298f,0.0f}, +{0.401562f,0.915832f,0.0f},{0.363038f,0.931774f,0.0f},{0.323885f,0.946097f,0.0f}, +{0.36304f,0.931774f,0.0f},{0.284168f,0.958774f,0.0f},{0.323886f,0.946096f,0.0f}, +{0.28417f,0.958774f,0.0f},{0.243959f,0.969786f,0.0f},{0.24396f,0.969785f,0.0f}, +{0.816453f,0.577412f,0.0f},{0.816452f,0.577413f,0.0f},{0.839811f,0.542879f,0.0f}, +{0.861709f,0.507402f,0.0f},{0.83981f,0.54288f,0.0f},{0.88211f,0.471044f,0.0f}, +{0.861708f,0.507404f,0.0f},{0.882109f,0.471046f,0.0f},{0.900977f,0.433866f,0.0f}, +{0.918278f,0.395935f,0.0f},{0.900976f,0.433869f,0.0f},{0.933984f,0.357316f,0.0f}, +{0.918278f,0.395937f,0.0f},{0.933983f,0.357318f,0.0f},{0.948065f,0.318075f,0.0f}, +{0.960499f,0.278282f,0.0f},{0.948065f,0.318077f,0.0f},{0.971264f,0.238005f,0.0f}, +{0.960499f,0.278284f,0.0f},{0.971263f,0.238007f,0.0f},{0.98034f,0.197314f,0.0f}, +{0.987713f,0.15628f,0.0f},{0.98034f,0.197316f,0.0f},{0.993368f,0.114975f,0.0f}, +{0.987712f,0.156283f,0.0f},{0.993368f,0.114977f,0.0f},{0.997297f,0.0734701f,0.0f}, +{0.999493f,0.0318375f,0.0f},{0.997297f,0.0734722f,0.0f},{0.999951f,-0.00985025f,0.0f}, +{0.999493f,0.0318392f,0.0f},{0.999951f,-0.00984923f,0.0f},{0.998672f,-0.0515206f,0.0f}, +{0.5f,0.866025f,-4.07254e-016f},{-0.997498f,0.0706974f,4.22047e-015f},{-0.999099f,0.042441f,-4.49972e-015f}, +{-0.999099f,0.0424415f,-8.87378e-015f},{-0.9999f,-0.0141508f,-1.48015e-015f},{-0.9999f,0.014151f,0.0f}, +{-0.9999f,0.0141508f,-7.42169e-015f},{-0.997498f,0.0706979f,1.47659e-015f},{-0.995098f,0.0988972f,5.89216e-015f}, +{-0.995098f,0.0988976f,5.59937e-015f},{-0.9919f,0.127018f,-1.17465e-014f},{-0.9919f,0.127018f,-1.72436e-014f}, +{-0.987909f,0.155036f,-5.3906e-015f},{-0.987909f,0.155037f,5.84959e-015f},{-0.983126f,0.182932f,-2.36905e-015f}, +{-0.983126f,0.182931f,8.73191e-015f},{-0.971202f,0.238259f,8.626e-015f},{-0.96407f,0.265648f,-7.28139e-015f}, +{-0.96407f,0.265647f,-1.29898e-014f},{-0.977555f,0.210679f,-4.54082e-015f},{-0.977555f,0.21068f,0.0f}, +{-0.971202f,0.238258f,-1.29121e-014f},{-0.956167f,0.292823f,-1.73386e-015f},{-0.956167f,0.292823f,0.0f}, +{-0.947497f,0.319764f,5.61031e-015f},{-0.947497f,0.319764f,-1.89338e-015f},{-0.938069f,0.346449f,0.0f}, +{-0.938069f,0.346449f,7.60587e-015f},{-0.927889f,0.372856f,9.90971e-015f},{-0.905308f,0.424755f,5.3605e-015f}, +{-0.905309f,0.424755f,3.304e-016f},{-0.916966f,0.398966f,4.7247e-015f},{-0.916966f,0.398965f,5.42953e-015f}, +{-0.927889f,0.372857f,-7.70196e-015f},{-0.892926f,0.450204f,0.0f},{-0.892926f,0.450204f,5.33148e-015f}, +{-0.879828f,0.475292f,1.04193e-014f},{-0.879828f,0.475292f,1.04193e-014f},{-0.866025f,0.5f,0.0f}, +{-0.9999f,-0.014151f,8.90184e-015f},{-0.999099f,-0.042441f,-1.04784e-014f},{-0.999099f,-0.0424415f,-1.61429e-014f}, +{-0.997498f,-0.0706974f,8.65025e-015f},{-0.995098f,-0.0988972f,2.94608e-015f},{-0.997498f,-0.0706979f,-1.09175e-014f}, +{-0.995098f,-0.0988976f,1.39984e-015f},{-0.9919f,-0.127018f,-1.06363e-014f},{-0.9919f,-0.127018f,9.63801e-015f}, +{-0.987909f,-0.155036f,-7.40539e-015f},{-0.983126f,-0.182931f,-7.57272e-015f},{-0.987909f,-0.155037f,-2.5165e-015f}, +{-0.983126f,-0.182932f,2.18298e-015f},{-0.977555f,-0.210679f,7.64703e-015f},{-0.977555f,-0.21068f,-4.23518e-015f}, +{-0.971202f,-0.238258f,-1.03144e-014f},{-0.96407f,-0.265647f,-7.60334e-015f},{-0.971202f,-0.238259f,1.75636e-015f}, +{-0.96407f,-0.265648f,1.0869e-014f},{-0.956167f,-0.292823f,5.12754e-015f},{-0.956167f,-0.292823f,-8.24033e-015f}, +{-0.947497f,-0.319764f,3.07966e-016f},{-0.938069f,-0.346449f,-1.05337e-014f},{-0.947497f,-0.319764f,-8.2576e-015f}, +{-0.938069f,-0.346449f,-1.87656e-015f},{-0.927889f,-0.372856f,3.1746e-015f},{-0.927889f,-0.372857f,-3.31849e-015f}, +{-0.916966f,-0.398965f,3.06056e-015f},{-0.905309f,-0.424755f,7.49538e-015f},{-0.916966f,-0.398966f,4.02549e-015f}, +{-0.905308f,-0.424755f,1.46943e-015f},{-0.892926f,-0.450204f,-1.18685e-014f},{-0.892926f,-0.450204f,1.25672e-015f}, +{-0.879828f,-0.475292f,4.58408e-015f},{-0.866025f,-0.5f,0.0f},{-0.879828f,-0.475292f,1.83809e-015f}, +{-0.78179f,-0.623541f,-1.15728e-015f},{-0.807718f,-0.589568f,-2.39133e-015f},{-0.807717f,-0.589571f,9.60223e-017f}, +{-0.754434f,-0.656376f,-5.72909e-015f},{-0.754433f,-0.656377f,-7.23689e-015f},{-0.7257f,-0.688011f,1.01846e-015f}, +{-0.832169f,-0.554522f,1.64171e-015f},{-0.781789f,-0.623543f,4.8494e-015f},{-0.832171f,-0.554519f,4.10543e-015f}, +{-0.855102f,-0.51846f,-9.96661e-016f},{-0.855104f,-0.518456f,1.53494e-015f},{-0.876475f,-0.481448f,-5.18977e-015f}, +{-0.876473f,-0.48145f,-4.02026e-015f},{-0.896244f,-0.443562f,-2.65341e-015f},{-0.896245f,-0.443559f,-3.96662e-015f}, +{-0.914379f,-0.40486f,0.0f},{-0.930841f,-0.365425f,0.0f},{-0.914377f,-0.404864f,-2.39728e-015f}, +{-0.930842f,-0.365423f,0.0f},{-0.945605f,-0.325317f,-3.67284e-015f},{-0.945604f,-0.32532f,0.0f}, +{-0.97944f,-0.201738f,3.58358e-015f},{-0.969926f,-0.243399f,-1.44121e-015f},{-0.97944f,-0.201735f,-3.41043e-015f}, +{-0.95864f,-0.284621f,7.36158e-015f},{-0.958641f,-0.284618f,-5.6763e-015f},{-0.969926f,-0.243401f,5.74311e-015f}, +{-0.987165f,-0.159705f,9.45645e-016f},{-0.993087f,-0.117381f,-1.03704e-014f},{-0.987165f,-0.159703f,-4.89956e-015f}, +{-0.993087f,-0.117378f,-6.9502e-016f},{-0.997196f,-0.07484f,0.0f},{-0.999483f,-0.0321655f,6.29904e-015f}, +{-0.999482f,-0.032168f,-5.91813e-015f},{-0.997195f,-0.0748434f,-8.86324e-016f},{-0.999944f,0.0105685f,-5.7957e-015f}, +{-0.999944f,0.0105657f,5.92086e-015f},{-0.99858f,0.0532826f,0.0f},{-0.99858f,0.05328f,0.0f}, +{-0.995391f,0.0958981f,0.0f},{-0.695642f,-0.718389f,-2.12686e-015f},{-0.725699f,-0.688012f,-3.16696e-015f}, +{-0.69564f,-0.718391f,6.73571e-017f},{-0.664312f,-0.747455f,3.69231e-016f},{-0.66431f,-0.747457f,-4.91688e-015f}, +{-0.631769f,-0.775156f,-3.61476e-016f},{-0.598073f,-0.801442f,-8.85326e-016f},{-0.631767f,-0.775159f,-5.10676e-016f}, +{-0.59807f,-0.801444f,-2.51436e-015f},{-0.563284f,-0.826264f,-2.63707e-016f},{-0.563281f,-0.826266f,-4.79448e-015f}, +{-0.527466f,-0.849576f,2.47204e-015f},{-0.490685f,-0.871337f,-7.45068e-016f},{-0.527463f,-0.849578f,6.28814e-016f}, +{-0.490682f,-0.871339f,-4.66609e-016f},{-0.453007f,-0.891507f,-5.36872e-018f},{-0.453005f,-0.891508f,1.90646e-015f}, +{-0.414503f,-0.910048f,-9.01947e-016f},{-0.375241f,-0.926927f,-7.55498e-016f},{-0.414499f,-0.91005f,-3.44627e-015f}, +{-0.375238f,-0.926928f,-8.26493e-018f},{-0.335293f,-0.942114f,7.4317e-016f},{-0.335291f,-0.942115f,-1.38718e-015f}, +{-0.294734f,-0.955579f,-6.60361e-018f},{-0.253636f,-0.9673f,1.39186e-016f},{-0.294731f,-0.95558f,-4.80822e-016f}, +{-0.253634f,-0.9673f,-1.1694e-015f},{-0.212076f,-0.977253f,-1.09093e-015f},{-0.212073f,-0.977254f,-1.42807e-015f}, +{-0.170128f,-0.985422f,-8.58064e-016f},{-0.127868f,-0.991791f,1.21011e-015f},{-0.170124f,-0.985423f,3.47036e-015f}, +{-0.127866f,-0.991791f,2.85545e-016f},{-0.0853758f,-0.996349f,-4.87227e-016f},{-0.0853729f,-0.996349f,3.21028e-015f}, +{-0.0427275f,-0.999087f,-3.76158e-016f},{-1.41083e-016f,-1.0f,0.0f},{-0.0427249f,-0.999087f,-2.9625e-015f}, +{-1.54309e-016f,-1.0f,0.0f},{-1.0f,-5.04647e-017f,0.0f},{-1.0f,-5.3829e-017f,0.0f}, +{-0.998532f,-0.0541567f,0.0f},{-0.994135f,-0.108145f,0.0f},{-0.998534f,-0.0541301f,0.0f}, +{-0.986822f,-0.161808f,0.0f},{-0.99414f,-0.108105f,0.0f},{-0.986829f,-0.161767f,0.0f}, +{-0.976616f,-0.214992f,0.0f},{-0.963545f,-0.267546f,0.0f},{-0.976622f,-0.214964f,0.0f}, +{-0.947644f,-0.319328f,0.0f},{-0.963549f,-0.267531f,0.0f},{-0.947653f,-0.319303f,0.0f}, +{-0.928963f,-0.370172f,0.0f},{-0.90756f,-0.419923f,0.0f},{-0.928977f,-0.370136f,0.0f}, +{-0.883495f,-0.46844f,0.0f},{-0.907577f,-0.419887f,0.0f},{-0.883512f,-0.468409f,0.0f}, +{-0.856841f,-0.515581f,0.0f},{-0.827674f,-0.56121f,0.0f},{-0.856854f,-0.515559f,0.0f}, +{-0.796076f,-0.605197f,0.0f},{-0.827681f,-0.561199f,0.0f},{-0.796082f,-0.605188f,0.0f}, +{-0.762141f,-0.647411f,0.0f},{-0.725973f,-0.687723f,0.0f},{-0.762151f,-0.6474f,0.0f}, +{-0.687676f,-0.726018f,0.0f},{-0.725983f,-0.687712f,0.0f},{-0.687687f,-0.726007f,0.0f}, +{-0.647361f,-0.762183f,0.0f},{-0.605148f,-0.796113f,0.0f},{-0.647375f,-0.762171f,0.0f}, +{-0.56116f,-0.827707f,0.0f},{-0.605164f,-0.796101f,0.0f},{-0.561178f,-0.827695f,0.0f}, +{-0.515527f,-0.856873f,0.0f},{-0.468383f,-0.883526f,0.0f},{-0.515545f,-0.856862f,0.0f}, +{-0.419866f,-0.907586f,0.0f},{-0.4684f,-0.883516f,0.0f},{-0.419884f,-0.907578f,0.0f}, +{-0.370116f,-0.928986f,0.0f},{-0.319279f,-0.947661f,0.0f},{-0.370136f,-0.928977f,0.0f}, +{-0.267507f,-0.963556f,0.0f},{-0.319301f,-0.947653f,0.0f},{-0.267528f,-0.96355f,0.0f}, +{-0.214954f,-0.976624f,0.0f},{-0.16177f,-0.986829f,0.0f},{-0.214973f,-0.97662f,0.0f}, +{-0.108111f,-0.994139f,0.0f},{-0.161786f,-0.986826f,0.0f},{-0.108145f,-0.994135f,0.0f}, +{-0.0538298f,-0.99855f,0.0f},{2.15316e-016f,-1.0f,0.0f},{-0.0538044f,-0.998551f,0.0f}, +{2.35502e-016f,-1.0f,0.0f},{-0.998532f,0.0541566f,0.0f},{-0.998534f,0.0541302f,0.0f}, +{-0.994135f,0.108145f,0.0f},{-0.986822f,0.161808f,0.0f},{-0.99414f,0.108105f,0.0f}, +{-0.976616f,0.214992f,0.0f},{-0.986829f,0.161767f,0.0f},{-0.976622f,0.214964f,0.0f}, +{-0.963545f,0.267546f,0.0f},{-0.947644f,0.319328f,0.0f},{-0.963549f,0.267531f,0.0f}, +{-0.928963f,0.370172f,0.0f},{-0.947653f,0.319303f,0.0f},{-0.928977f,0.370136f,0.0f}, +{-0.90756f,0.419923f,0.0f},{-0.883495f,0.46844f,0.0f},{-0.907577f,0.419887f,0.0f}, +{-0.856841f,0.515581f,0.0f},{-0.883512f,0.468409f,0.0f},{-0.856854f,0.515559f,0.0f}, +{-0.827674f,0.56121f,0.0f},{-0.796076f,0.605197f,0.0f},{-0.827681f,0.561199f,0.0f}, +{-0.762141f,0.647411f,0.0f},{-0.796082f,0.605188f,0.0f},{-0.762151f,0.6474f,0.0f}, +{-0.725973f,0.687723f,0.0f},{-0.687676f,0.726018f,0.0f},{-0.725983f,0.687712f,0.0f}, +{-0.647361f,0.762183f,0.0f},{-0.687687f,0.726007f,0.0f},{-0.647375f,0.762171f,0.0f}, +{-0.605148f,0.796113f,0.0f},{-0.56116f,0.827707f,0.0f},{-0.605164f,0.796101f,0.0f}, +{-0.515527f,0.856873f,0.0f},{-0.561178f,0.827695f,0.0f},{-0.515545f,0.856862f,0.0f}, +{-0.468383f,0.883526f,0.0f},{-0.419866f,0.907586f,0.0f},{-0.468401f,0.883516f,0.0f}, +{-0.370116f,0.928986f,0.0f},{-0.419884f,0.907578f,0.0f},{-0.370136f,0.928977f,0.0f}, +{-0.319279f,0.947661f,0.0f},{-0.267507f,0.963556f,0.0f},{-0.319301f,0.947653f,0.0f}, +{-0.214954f,0.976624f,0.0f},{-0.267528f,0.96355f,0.0f},{-0.214973f,0.97662f,0.0f}, +{-0.16177f,0.986829f,0.0f},{-0.108111f,0.994139f,0.0f},{-0.161786f,0.986826f,0.0f}, +{-0.0538298f,0.99855f,0.0f},{-0.108145f,0.994135f,0.0f},{-0.0538045f,0.998551f,0.0f}, +{-1.19209e-007f,1.0f,0.0f},{-0.69564f,0.718391f,-2.2967e-015f},{-0.66431f,0.747457f,4.30948e-015f}, +{-0.664312f,0.747455f,-2.35972e-015f},{-0.725699f,0.688012f,-2.11837e-015f},{-0.7257f,0.688011f,-4.7761e-015f}, +{-0.754433f,0.656377f,-3.42054e-015f},{-0.631769f,0.775156f,1.02241e-015f},{-0.695642f,0.718389f,1.63365e-016f}, +{-0.631766f,0.775159f,1.30928e-015f},{-0.598073f,0.801442f,-4.02386e-016f},{-0.59807f,0.801444f,3.14782e-015f}, +{-0.563281f,0.826266f,2.05014e-015f},{-0.563284f,0.826264f,2.15457e-016f},{-0.527466f,0.849576f,3.68245e-015f}, +{-0.527463f,0.849578f,-9.04405e-017f},{-0.490682f,0.871339f,2.82586e-015f},{-0.453007f,0.891507f,-1.11336e-015f}, +{-0.490685f,0.871337f,-3.98744e-016f},{-0.453005f,0.891508f,8.87668e-016f},{-0.414499f,0.91005f,3.62163e-016f}, +{-0.414503f,0.910048f,-2.33213e-015f},{-0.294734f,0.955579f,1.39294e-015f},{-0.335291f,0.942115f,1.29026e-015f}, +{-0.294731f,0.95558f,9.56661e-016f},{-0.375241f,0.926927f,3.09815e-015f},{-0.375238f,0.926928f,3.53892e-016f}, +{-0.335293f,0.942114f,1.78659e-015f},{-0.253636f,0.9673f,4.48455e-017f},{-0.212075f,0.977253f,9.31315e-017f}, +{-0.253634f,0.9673f,-3.87537e-015f},{-0.212073f,0.977254f,1.53976e-015f},{-0.170124f,0.985423f,-1.33727e-015f}, +{-0.127866f,0.991791f,1.31222e-015f},{-0.127868f,0.991791f,-1.43479e-015f},{-0.170128f,0.985422f,-1.08544e-015f}, +{-0.0853729f,0.996349f,-2.96511e-015f},{-0.0853758f,0.996349f,1.45956e-015f},{-0.0427249f,0.999087f,-1.45746e-015f}, +{-0.0427275f,0.999087f,2.97938e-015f},{-1.41083e-016f,1.0f,0.0f},{-1.54309e-016f,1.0f,0.0f}, +{-0.781789f,0.623543f,-8.12728e-016f},{-0.754434f,0.656376f,-2.4015e-015f},{-0.78179f,0.623541f,-9.35104e-016f}, +{-0.807717f,0.589571f,-3.8494e-015f},{-0.807718f,0.589569f,8.37214e-016f},{-0.832169f,0.554522f,-3.65599e-015f}, +{-0.855102f,0.51846f,-4.07623e-015f},{-0.832171f,0.554519f,2.81113e-015f},{-0.855104f,0.518456f,2.96789e-016f}, +{-0.876473f,0.48145f,3.95802e-015f},{-0.876475f,0.481448f,6.89284e-016f},{-0.896244f,0.443562f,7.12651e-016f}, +{-0.914377f,0.404864f,-1.93578e-015f},{-0.896245f,0.443559f,5.43092e-015f},{-0.914379f,0.40486f,-5.84661e-015f}, +{-0.930841f,0.365425f,1.20115e-015f},{-0.930842f,0.365423f,3.55128e-015f},{-0.945604f,0.32532f,2.23888e-015f}, +{-0.95864f,0.284621f,5.39664e-015f},{-0.945605f,0.325317f,4.0151e-015f},{-0.958641f,0.284618f,-2.22393e-015f}, +{-0.969926f,0.243401f,4.33048e-015f},{-0.969926f,0.243399f,4.23515e-015f},{-0.97944f,0.201738f,4.2777e-015f}, +{-0.987165f,0.159705f,5.95984e-015f},{-0.97944f,0.201735f,6.68731e-016f},{-0.987165f,0.159703f,-8.70338e-015f}, +{-0.993087f,0.117381f,-6.76187e-015f},{-0.993087f,0.117378f,7.13795e-015f},{-0.997195f,0.0748434f,-4.49833e-016f}, +{-0.999482f,0.0321679f,5.88869e-015f},{-0.997196f,0.07484f,-1.11652e-015f},{-0.999483f,0.0321656f,-2.74195e-016f}, +{-0.999944f,-0.0105657f,5.2388e-015f},{-0.999944f,-0.0105686f,-6.15843e-016f},{-0.99858f,-0.05328f,7.92959e-015f}, +{-0.995391f,-0.0958981f,0.0f},{-0.99858f,-0.0532825f,4.50329e-015f},{0.9999f,0.0141122f,0.0f}, +{0.9999f,-0.0141124f,0.0f},{0.9999f,0.0141125f,0.0f},{0.999104f,0.0423259f,0.0f}, +{0.999104f,0.0423254f,0.0f},{0.997511f,0.0705055f,0.0f},{0.997511f,0.0705051f,0.0f}, +{0.995124f,0.0986284f,0.0f},{0.995124f,0.0986291f,0.0f},{0.991944f,0.126674f,0.0f}, +{0.991944f,0.126673f,0.0f},{0.987974f,0.154618f,0.0f},{0.987974f,0.154617f,0.0f}, +{0.983217f,0.182438f,0.0f},{0.983217f,0.182439f,0.0f},{0.977677f,0.210114f,0.0f}, +{0.977677f,0.210113f,0.0f},{0.971358f,0.237622f,0.0f},{0.971358f,0.237622f,0.0f}, +{0.964265f,0.26494f,0.0f},{0.964265f,0.264941f,0.0f},{0.956403f,0.292049f,0.0f}, +{0.956404f,0.292048f,0.0f},{0.94778f,0.318924f,0.0f},{0.947781f,0.318923f,0.0f}, +{0.938403f,0.345544f,0.0f},{0.938402f,0.345545f,0.0f},{0.928277f,0.371891f,0.0f}, +{0.928277f,0.37189f,0.0f},{0.917411f,0.39794f,0.0f},{0.917412f,0.397939f,0.0f}, +{0.905816f,0.423672f,0.0f},{0.905815f,0.423672f,0.0f},{0.893498f,0.449067f,0.0f}, +{0.893498f,0.449067f,0.0f},{0.880469f,0.474105f,0.0f},{0.880469f,0.474104f,0.0f}, +{0.866738f,0.498763f,0.0f},{0.866738f,0.498764f,0.0f},{0.852317f,0.523026f,0.0f}, +{0.9999f,-0.0141122f,0.0f},{0.999104f,-0.0423254f,0.0f},{0.999104f,-0.0423259f,0.0f}, +{0.997511f,-0.0705055f,0.0f},{0.997511f,-0.0705051f,0.0f},{0.995124f,-0.0986291f,0.0f}, +{0.995124f,-0.0986285f,0.0f},{0.991944f,-0.126673f,0.0f},{0.991944f,-0.126674f,0.0f}, +{0.987974f,-0.154618f,0.0f},{0.987974f,-0.154617f,0.0f},{0.983217f,-0.182439f,0.0f}, +{0.983217f,-0.182438f,0.0f},{0.977677f,-0.210113f,0.0f},{0.977677f,-0.210114f,0.0f}, +{0.971358f,-0.237622f,0.0f},{0.971358f,-0.237622f,0.0f},{0.964265f,-0.264941f,0.0f}, +{0.964265f,-0.26494f,0.0f},{0.956404f,-0.292048f,0.0f},{0.956403f,-0.292049f,0.0f}, +{0.94778f,-0.318924f,0.0f},{0.947781f,-0.318923f,0.0f},{0.938402f,-0.345545f,0.0f}, +{0.938403f,-0.345544f,0.0f},{0.928277f,-0.37189f,0.0f},{0.928277f,-0.371891f,0.0f}, +{0.917411f,-0.39794f,0.0f},{0.917412f,-0.397939f,0.0f},{0.905815f,-0.423672f,0.0f}, +{0.905816f,-0.423672f,0.0f},{0.893498f,-0.449067f,0.0f},{0.893498f,-0.449067f,0.0f}, +{0.880469f,-0.474104f,0.0f},{0.880469f,-0.474104f,0.0f},{0.866738f,-0.498764f,0.0f}, +{0.866738f,-0.498764f,0.0f},{0.852317f,-0.523026f,0.0f},{0.5f,-0.866025f,-7.6671e-016f}, +{0.884642f,-0.466272f,2.20644e-016f},{0.777982f,-0.628286f,5.89571e-016f},{0.778033f,-0.628223f,-5.53502e-016f}, +{0.957996f,-0.286781f,1.48116e-016f},{0.88468f,-0.466199f,-5.1317e-016f},{0.958053f,-0.286593f,-1.63827e-016f}, +{0.995238f,0.0974696f,3.44802e-016f},{0.995356f,-0.0962625f,-1.06856e-016f},{0.995222f,0.097635f,-4.56953e-017f}, +{0.995334f,-0.0964852f,-1.31963e-016f},{0.642168f,-0.766564f,0.0f},{0.482138f,-0.876095f,-7.37654e-016f}, +{0.642017f,-0.76669f,-1.10523e-015f},{0.481942f,-0.876203f,7.37698e-016f},{0.303947f,-0.952689f,0.0f}, +{0.303789f,-0.952739f,0.0f},{0.715999f,-0.698102f,1.29175e-016f},{0.945908f,-0.324434f,-5.70109e-016f}, +{0.945908f,-0.324434f,-3.35048e-016f},{0.851699f,-0.524032f,7.27349e-016f},{0.194654f,0.980872f,-1.44073e-016f}, +{-2.96059e-016f,1.0f,-3.28692e-031f},{-0.384009f,0.923329f,-2.13958e-016f},{-0.382179f,0.924088f,9.40449e-016f}, +{-0.196168f,0.98057f,-7.62016e-016f},{-0.194653f,0.980872f,6.1653e-016f},{-0.555293f,0.831655f,6.67161e-016f}, +{-0.707075f,0.707139f,-4.57955e-016f},{-0.707765f,0.706447f,4.57334e-016f},{-0.831545f,0.555458f,8.32431e-017f}, +{-0.831851f,0.554999f,-2.05391e-016f},{-0.556611f,0.830773f,-3.85076e-016f},{-0.980825f,0.19489f,-3.63028e-018f}, +{-0.98085f,0.194766f,-2.22141e-016f},{-0.924075f,0.382212f,5.86375e-016f},{-0.923954f,0.382504f,-2.95917e-016f}, +{-1.0f,1.85037e-017f,0.0f},{0.196168f,0.98057f,-1.01605e-015f},{0.382179f,0.924088f,-1.22649e-015f}, +{0.384009f,0.923329f,-1.99588e-016f},{0.556611f,0.830773f,-1.04527e-016f},{0.555293f,0.831655f,-4.10999e-016f}, +{0.707766f,0.706447f,5.22876e-016f},{0.707075f,0.707139f,5.23388e-016f},{0.831545f,0.555458f,-6.15467e-016f}, +{0.831851f,0.554999f,-4.10782e-016f},{0.924075f,0.382212f,-1.36791e-015f},{0.98085f,0.194766f,-8.7013e-016f}, +{1.0f,3.33067e-016f,0.0f},{1.0f,2.96059e-016f,0.0f},{0.194654f,0.980872f,0.0f}, +{-0.384009f,0.923329f,7.57929e-018f},{-0.382179f,0.924088f,2.41708e-016f},{-0.196168f,0.98057f,-1.26994e-016f}, +{-0.194653f,0.980872f,-9.14525e-017f},{-0.555293f,0.831655f,4.10524e-016f},{-0.707075f,0.707139f,1.14487e-016f}, +{-0.707765f,0.706447f,-5.72353e-016f},{-0.831545f,0.555458f,-9.69264e-018f},{-0.831851f,0.554999f,4.97064e-016f}, +{-0.556611f,0.830773f,5.13819e-016f},{-1.0f,2.96059e-016f,0.0f},{-0.980825f,0.19489f,-1.02781e-015f}, +{-0.98085f,0.194766f,8.39508e-016f},{-0.924075f,0.382212f,4.37371e-016f},{-0.923954f,0.382504f,1.06278e-016f}, +{-1.0f,5.92119e-016f,0.0f},{0.196168f,0.98057f,-7.25968e-017f},{0.382179f,0.924088f,0.0f}, +{0.384009f,0.923329f,-1.42112e-016f},{0.556611f,0.830773f,-5.13435e-016f},{0.555293f,0.831655f,2.055e-016f}, +{0.707766f,0.706447f,-1.04673e-015f},{0.707075f,0.707139f,2.6167e-016f},{0.831545f,0.555458f,6.15467e-016f}, +{0.98085f,0.194766f,7.25975e-016f},{0.980825f,0.19489f,-8.70204e-016f},{1.0f,1.85037e-017f,0.0f}, +{0.989489f,0.144611f,-3.80291e-017f},{0.99711f,-0.0759712f,-5.623e-017f},{0.933664f,0.358149f,-9.55933e-016f}, +{0.933664f,0.358149f,1.99014e-016f},{0.835272f,0.549837f,0.0f},{0.957691f,-0.2878f,0.0f}, +{-1.0f,-1.53707e-012f,0.0f},{-1.0f,-8.42952e-008f,0.0f},{3.07487e-012f,-1.0f,0.0f}, +{3.07526e-012f,-1.0f,0.0f},{0.673422f,0.739259f,0.0f},{0.703582f,0.710614f,0.0f}, +{0.673421f,0.739259f,0.0f},{0.642094f,0.766626f,0.0f},{0.642096f,0.766624f,0.0f}, +{0.609658f,0.792665f,0.0f},{0.60966f,0.792663f,0.0f},{0.576168f,0.817331f,0.0f}, +{0.576166f,0.817333f,0.0f},{0.541677f,0.840587f,0.0f},{0.54168f,0.840585f,0.0f}, +{0.506252f,0.862386f,0.0f},{0.506254f,0.862384f,0.0f},{0.469953f,0.882691f,0.0f}, +{0.46995f,0.882693f,0.0f},{0.432835f,0.901473f,0.0f},{0.432838f,0.901471f,0.0f}, +{0.394972f,0.918693f,0.0f},{0.394974f,0.918692f,0.0f},{0.356428f,0.934323f,0.0f}, +{0.356425f,0.934324f,0.0f},{0.317262f,0.948338f,0.0f},{0.317264f,0.948337f,0.0f}, +{0.277549f,0.960711f,0.0f},{0.277552f,0.960711f,0.0f},{0.237359f,0.971422f,0.0f}, +{0.237356f,0.971423f,0.0f},{0.196753f,0.980453f,0.0f},{0.196756f,0.980453f,0.0f}, +{0.155809f,0.987787f,0.0f},{0.155812f,0.987787f,0.0f},{0.114599f,0.993412f,0.0f}, +{0.114596f,0.993412f,0.0f},{0.0731848f,0.997318f,0.0f},{0.073187f,0.997318f,0.0f}, +{0.0316463f,0.999499f,0.0f},{0.0316489f,0.999499f,0.0f},{-0.00994395f,0.999951f,0.0f}, +{-0.00994627f,0.999951f,0.0f},{-0.0515206f,0.998672f,0.0f},{0.703582f,0.710614f,0.0f}, +{0.732525f,0.680741f,0.0f},{0.732526f,0.680739f,0.0f},{0.760202f,0.649687f,0.0f}, +{0.760201f,0.649688f,0.0f},{0.786563f,0.61751f,0.0f},{0.786561f,0.617513f,0.0f}, +{0.811561f,0.584268f,0.0f},{0.811563f,0.584265f,0.0f},{0.835158f,0.55001f,0.0f}, +{0.835156f,0.550013f,0.0f},{0.857309f,0.514803f,0.0f},{0.857307f,0.514806f,0.0f}, +{0.877974f,0.478708f,0.0f},{0.877976f,0.478705f,0.0f},{0.897124f,0.441779f,0.0f}, +{0.897123f,0.441782f,0.0f},{0.91472f,0.404088f,0.0f},{0.914719f,0.404092f,0.0f}, +{0.930732f,0.365702f,0.0f},{0.930733f,0.365699f,0.0f},{0.945136f,0.326677f,0.0f}, +{0.945135f,0.326679f,0.0f},{0.957904f,0.287089f,0.0f},{0.957903f,0.287092f,0.0f}, +{0.969013f,0.247008f,0.0f},{0.969014f,0.247006f,0.0f},{0.978448f,0.206494f,0.0f}, +{0.978447f,0.206496f,0.0f},{0.986189f,0.165625f,0.0f},{0.986188f,0.165628f,0.0f}, +{0.992223f,0.124472f,0.0f},{0.992223f,0.12447f,0.0f},{0.996541f,0.0830991f,0.0f}, +{0.996541f,0.0831017f,0.0f},{0.999135f,0.041585f,0.0f},{0.999135f,0.0415873f,0.0f}, +{1.0f,1.92868e-016f,0.0f},{1.0f,8.64379e-008f,0.0f},{0.998361f,0.0572333f,1.89979e-016f}, +{1.0f,-3.3736e-016f,0.0f},{0.993449f,0.114279f,0.0f},{0.569266f,0.822154f,0.0f}, +{0.413628f,0.910446f,0.0f},{0.569567f,0.821945f,0.0f},{0.413191f,0.910644f,0.0f}, +{0.244303f,0.969699f,0.0f},{0.243984f,0.969779f,0.0f},{0.0672808f,0.997734f,0.0f}, +{-0.11203f,0.993705f,0.0f},{0.0668255f,0.997765f,0.0f},{-0.2878f,0.957691f,0.0f}, +{-0.112396f,0.993663f,0.0f},{0.822154f,0.569266f,0.0f},{0.821945f,0.569567f,0.0f}, +{0.910446f,0.413628f,0.0f},{0.969699f,0.244303f,0.0f},{0.910644f,0.413191f,0.0f}, +{0.969779f,0.243985f,0.0f},{0.997734f,0.0672808f,0.0f},{0.997765f,0.0668255f,0.0f}, +{0.993705f,-0.11203f,0.0f},{0.993663f,-0.112396f,0.0f},{-0.567551f,0.823338f,2.91569e-016f}, +{-0.480256f,0.877128f,-1.36506e-015f},{-0.480275f,0.877118f,1.00957e-015f},{-0.567558f,0.823334f,5.00925e-017f}, +{-0.648872f,0.760897f,1.44361e-016f},{-0.387941f,0.921684f,1.25621e-016f},{-0.387915f,0.921695f,6.82191e-016f}, +{-0.291525f,0.956563f,-6.81027e-016f},{-0.291499f,0.956571f,-7.61943e-016f},{-0.192047f,0.981386f,6.553e-016f}, +{-0.192025f,0.98139f,1.77659e-017f},{-0.0904984f,0.995897f,-8.37279e-018f},{-0.0905325f,0.995893f,-1.67519e-017f}, +{0.0119218f,0.999929f,1.48019e-015f},{0.114279f,0.993449f,0.0f},{0.0121699f,0.999926f,0.0f}, +{-0.723369f,0.690461f,-9.58068e-017f},{-0.648879f,0.760892f,1.7081e-016f},{-0.723384f,0.690446f,-1.49808e-016f}, +{-0.790265f,0.612765f,1.16954e-016f},{-0.790282f,0.612743f,-1.7266e-016f},{-0.848856f,0.528625f,3.32998e-016f}, +{-0.898522f,0.438929f,-5.4393e-016f},{-0.84887f,0.528601f,4.57239e-016f},{-0.898532f,0.438908f,-2.60926e-016f}, +{-0.938749f,0.344602f,1.75687e-016f},{-0.938761f,0.34457f,5.73784e-016f},{-0.969101f,0.246664f,-5.54286e-016f}, +{-0.989269f,0.146104f,0.0f},{-0.969162f,0.246424f,-8.55909e-016f},{-0.863082f,-0.505064f,-2.96041e-016f}, +{-0.939433f,-0.342733f,-1.39064e-015f},{-0.757002f,-0.653412f,-4.80673e-016f},{-0.98457f,-0.174993f,-7.12538e-016f}, +{-0.999951f,-0.00988645f,0.0f},{-0.625744f,-0.780028f,-1.42742e-017f},{-0.47631f,-0.879277f,-1.99991e-016f}, +{-0.316965f,-0.948437f,-3.53543e-016f},{-0.155878f,-0.987776f,8.15532e-017f},{-1.95899e-012f,-1.0f,0.0f}, +{-1.95907e-012f,-1.0f,0.0f},{-1.0f,4.18691e-016f,0.0f},{-1.0f,2.09346e-016f,0.0f}, +{-2.61682e-016f,1.0f,0.0f},{-8.42937e-008f,1.0f,0.0f},{-0.432409f,0.901678f,-4.8007e-016f}, +{-0.568002f,0.823027f,1.63014e-016f},{-0.288928f,0.957351f,2.01882e-015f},{-0.288928f,0.957351f,0.0f}, +{-0.143098f,0.989708f,7.32531e-016f},{-0.690346f,0.72348f,-1.05257e-015f},{-4.36853e-016f,1.0f,0.0f}, +{-9.28313e-016f,1.0f,0.0f},{-0.794923f,0.60671f,-3.38738e-016f},{-0.878607f,0.477546f,-8.64155e-016f}, +{-0.939939f,0.341342f,-3.74916e-016f},{-0.979111f,0.203325f,0.0f},{-0.610942f,0.791675f,0.0f}, +{-0.64341f,0.765522f,0.0f},{-0.674759f,0.738038f,0.0f},{-0.643409f,0.765522f,0.0f}, +{-0.704936f,0.709271f,0.0f},{-0.674758f,0.738039f,0.0f},{-0.704934f,0.709273f,0.0f}, +{-0.733887f,0.679272f,0.0f},{-0.761562f,0.648092f,0.0f},{-0.733885f,0.679273f,0.0f}, +{-0.787914f,0.615785f,0.0f},{-0.761561f,0.648094f,0.0f},{-0.787913f,0.615787f,0.0f}, +{-0.812896f,0.582409f,0.0f},{-0.836465f,0.54802f,0.0f},{-0.812895f,0.58241f,0.0f}, +{-0.858581f,0.512678f,0.0f},{-0.836464f,0.548021f,0.0f},{-0.85858f,0.51268f,0.0f}, +{-0.879204f,0.476445f,0.0f},{-0.898299f,0.439385f,0.0f},{-0.879203f,0.476447f,0.0f}, +{-0.915833f,0.40156f,0.0f},{-0.898298f,0.439387f,0.0f},{-0.915832f,0.401562f,0.0f}, +{-0.931774f,0.363038f,0.0f},{-0.946097f,0.323885f,0.0f},{-0.931774f,0.36304f,0.0f}, +{-0.958774f,0.284168f,0.0f},{-0.946096f,0.323886f,0.0f},{-0.958774f,0.28417f,0.0f}, +{-0.969786f,0.243959f,0.0f},{-0.969785f,0.24396f,0.0f},{-0.577412f,0.816453f,0.0f}, +{-0.577413f,0.816452f,0.0f},{-0.542879f,0.839811f,0.0f},{-0.507402f,0.861709f,0.0f}, +{-0.54288f,0.83981f,0.0f},{-0.471044f,0.88211f,0.0f},{-0.507404f,0.861708f,0.0f}, +{-0.471046f,0.882109f,0.0f},{-0.433866f,0.900977f,0.0f},{-0.395935f,0.918278f,0.0f}, +{-0.433869f,0.900976f,0.0f},{-0.357316f,0.933984f,0.0f},{-0.395937f,0.918278f,0.0f}, +{-0.357318f,0.933983f,0.0f},{-0.318075f,0.948065f,0.0f},{-0.278282f,0.960499f,0.0f}, +{-0.318077f,0.948065f,0.0f},{-0.238005f,0.971264f,0.0f},{-0.278284f,0.960499f,0.0f}, +{-0.238007f,0.971263f,0.0f},{-0.197314f,0.98034f,0.0f},{-0.15628f,0.987713f,0.0f}, +{-0.197316f,0.98034f,0.0f},{-0.114975f,0.993368f,0.0f},{-0.156283f,0.987712f,0.0f}, +{-0.114977f,0.993368f,0.0f},{-0.0734701f,0.997297f,0.0f},{-0.0318375f,0.999493f,0.0f}, +{-0.0734722f,0.997297f,0.0f},{0.00985025f,0.999951f,0.0f},{-0.0318392f,0.999493f,0.0f}, +{0.00984923f,0.999951f,0.0f},{0.0515206f,0.998672f,0.0f},{-0.866025f,0.5f,-4.07254e-016f}, +{-0.0706974f,-0.997498f,4.22047e-015f},{-0.042441f,-0.999099f,-4.49972e-015f},{-0.0424415f,-0.999099f,-8.87378e-015f}, +{0.0141508f,-0.9999f,-1.48015e-015f},{-0.014151f,-0.9999f,0.0f},{-0.0141508f,-0.9999f,-7.42169e-015f}, +{-0.0706979f,-0.997498f,1.47659e-015f},{-0.0988972f,-0.995098f,5.89216e-015f},{-0.0988976f,-0.995098f,5.59937e-015f}, +{-0.127018f,-0.9919f,-1.17465e-014f},{-0.127018f,-0.9919f,-1.72436e-014f},{-0.155036f,-0.987909f,-5.3906e-015f}, +{-0.155037f,-0.987909f,5.84959e-015f},{-0.182932f,-0.983126f,-2.36905e-015f},{-0.182931f,-0.983126f,8.73191e-015f}, +{-0.238259f,-0.971202f,8.626e-015f},{-0.265648f,-0.96407f,-7.28139e-015f},{-0.265647f,-0.96407f,-1.29898e-014f}, +{-0.210679f,-0.977555f,-4.54082e-015f},{-0.21068f,-0.977555f,0.0f},{-0.238258f,-0.971202f,-1.29121e-014f}, +{-0.292823f,-0.956167f,-1.73386e-015f},{-0.292823f,-0.956167f,0.0f},{-0.319764f,-0.947497f,5.61031e-015f}, +{-0.319764f,-0.947497f,-1.89338e-015f},{-0.346449f,-0.938069f,0.0f},{-0.346449f,-0.938069f,7.60587e-015f}, +{-0.372856f,-0.927889f,9.90971e-015f},{-0.424755f,-0.905308f,5.3605e-015f},{-0.424755f,-0.905309f,3.304e-016f}, +{-0.398966f,-0.916966f,4.7247e-015f},{-0.398965f,-0.916966f,5.42953e-015f},{-0.372857f,-0.927889f,-7.70196e-015f}, +{-0.450204f,-0.892926f,0.0f},{-0.450204f,-0.892926f,5.33148e-015f},{-0.475292f,-0.879828f,1.04193e-014f}, +{-0.475292f,-0.879828f,1.04193e-014f},{0.014151f,-0.9999f,8.90184e-015f},{0.042441f,-0.999099f,-1.04784e-014f}, +{0.0424415f,-0.999099f,-1.61429e-014f},{0.0706974f,-0.997498f,8.65025e-015f},{0.0988972f,-0.995098f,2.94608e-015f}, +{0.0706979f,-0.997498f,-1.09175e-014f},{0.0988976f,-0.995098f,1.39984e-015f},{0.127018f,-0.9919f,-1.06363e-014f}, +{0.127018f,-0.9919f,9.63801e-015f},{0.155036f,-0.987909f,-7.40539e-015f},{0.182931f,-0.983126f,-7.57272e-015f}, +{0.155037f,-0.987909f,-2.5165e-015f},{0.182932f,-0.983126f,2.18298e-015f},{0.210679f,-0.977555f,7.64703e-015f}, +{0.21068f,-0.977555f,-4.23518e-015f},{0.238258f,-0.971202f,-1.03144e-014f},{0.265647f,-0.96407f,-7.60334e-015f}, +{0.238259f,-0.971202f,1.75636e-015f},{0.265648f,-0.96407f,1.0869e-014f},{0.292823f,-0.956167f,5.12754e-015f}, +{0.292823f,-0.956167f,-8.24033e-015f},{0.319764f,-0.947497f,3.07966e-016f},{0.346449f,-0.938069f,-1.05337e-014f}, +{0.319764f,-0.947497f,-8.2576e-015f},{0.346449f,-0.938069f,-1.87656e-015f},{0.372856f,-0.927889f,3.1746e-015f}, +{0.372857f,-0.927889f,-3.31849e-015f},{0.398965f,-0.916966f,3.06056e-015f},{0.424755f,-0.905309f,7.49538e-015f}, +{0.398966f,-0.916966f,4.02549e-015f},{0.424755f,-0.905308f,1.46943e-015f},{0.450204f,-0.892926f,-1.18685e-014f}, +{0.450204f,-0.892926f,1.25672e-015f},{0.475292f,-0.879828f,4.58408e-015f},{0.475292f,-0.879828f,1.83809e-015f}, +{0.623541f,-0.78179f,-1.15728e-015f},{0.589568f,-0.807718f,-2.39133e-015f},{0.589571f,-0.807717f,9.60223e-017f}, +{0.656376f,-0.754434f,-5.72909e-015f},{0.656377f,-0.754433f,-7.23689e-015f},{0.688011f,-0.7257f,1.01846e-015f}, +{0.554522f,-0.832169f,1.64171e-015f},{0.623543f,-0.781789f,4.8494e-015f},{0.554519f,-0.832171f,4.10543e-015f}, +{0.51846f,-0.855102f,-9.96661e-016f},{0.518456f,-0.855104f,1.53494e-015f},{0.481448f,-0.876475f,-5.18977e-015f}, +{0.48145f,-0.876473f,-4.02026e-015f},{0.443562f,-0.896244f,-2.65341e-015f},{0.443559f,-0.896245f,-3.96662e-015f}, +{0.40486f,-0.914379f,0.0f},{0.365425f,-0.930841f,0.0f},{0.404864f,-0.914377f,-2.39728e-015f}, +{0.365423f,-0.930842f,0.0f},{0.325317f,-0.945605f,-3.67284e-015f},{0.32532f,-0.945604f,0.0f}, +{0.201738f,-0.97944f,3.58358e-015f},{0.243399f,-0.969926f,-1.44121e-015f},{0.201735f,-0.97944f,-3.41043e-015f}, +{0.284621f,-0.95864f,7.36158e-015f},{0.284618f,-0.958641f,-5.6763e-015f},{0.243401f,-0.969926f,5.74311e-015f}, +{0.159705f,-0.987165f,9.45645e-016f},{0.117381f,-0.993087f,-1.03704e-014f},{0.159703f,-0.987165f,-4.89956e-015f}, +{0.117378f,-0.993087f,-6.9502e-016f},{0.07484f,-0.997196f,0.0f},{0.0321655f,-0.999483f,6.29904e-015f}, +{0.032168f,-0.999482f,-5.91813e-015f},{0.0748434f,-0.997195f,-8.86324e-016f},{-0.0105685f,-0.999944f,-5.7957e-015f}, +{-0.0105657f,-0.999944f,5.92086e-015f},{-0.0532826f,-0.99858f,0.0f},{-0.05328f,-0.99858f,0.0f}, +{-0.0958981f,-0.995391f,0.0f},{0.718389f,-0.695642f,-2.12686e-015f},{0.688012f,-0.725699f,-3.16696e-015f}, +{0.718391f,-0.69564f,6.73571e-017f},{0.747455f,-0.664312f,3.69231e-016f},{0.747457f,-0.66431f,-4.91688e-015f}, +{0.775156f,-0.631769f,-3.61476e-016f},{0.801442f,-0.598073f,-8.85326e-016f},{0.775159f,-0.631767f,-5.10676e-016f}, +{0.801444f,-0.59807f,-2.51436e-015f},{0.826264f,-0.563284f,-2.63707e-016f},{0.826266f,-0.563281f,-4.79448e-015f}, +{0.849576f,-0.527466f,2.47204e-015f},{0.871337f,-0.490685f,-7.45068e-016f},{0.849578f,-0.527463f,6.28814e-016f}, +{0.871339f,-0.490682f,-4.66609e-016f},{0.891507f,-0.453007f,-5.36872e-018f},{0.891508f,-0.453005f,1.90646e-015f}, +{0.910048f,-0.414503f,-9.01947e-016f},{0.926927f,-0.375241f,-7.55498e-016f},{0.91005f,-0.414499f,-3.44627e-015f}, +{0.926928f,-0.375238f,-8.26493e-018f},{0.942114f,-0.335293f,7.4317e-016f},{0.942115f,-0.335291f,-1.38718e-015f}, +{0.955579f,-0.294734f,-6.60361e-018f},{0.9673f,-0.253636f,1.39186e-016f},{0.95558f,-0.294731f,-4.80822e-016f}, +{0.9673f,-0.253634f,-1.1694e-015f},{0.977253f,-0.212076f,-1.09093e-015f},{0.977254f,-0.212073f,-1.42807e-015f}, +{0.985422f,-0.170128f,-8.58064e-016f},{0.991791f,-0.127868f,1.21011e-015f},{0.985423f,-0.170124f,3.47036e-015f}, +{0.991791f,-0.127866f,2.85545e-016f},{0.996349f,-0.0853758f,-4.87227e-016f},{0.996349f,-0.0853729f,3.21028e-015f}, +{0.999087f,-0.0427275f,-3.76158e-016f},{1.0f,-1.41083e-016f,0.0f},{0.999087f,-0.0427249f,-2.9625e-015f}, +{1.0f,-1.54309e-016f,0.0f},{5.04647e-017f,-1.0f,0.0f},{5.3829e-017f,-1.0f,0.0f}, +{0.0541567f,-0.998532f,0.0f},{0.108145f,-0.994135f,0.0f},{0.0541301f,-0.998534f,0.0f}, +{0.161808f,-0.986822f,0.0f},{0.108105f,-0.99414f,0.0f},{0.161767f,-0.986829f,0.0f}, +{0.214992f,-0.976616f,0.0f},{0.267546f,-0.963545f,0.0f},{0.214964f,-0.976622f,0.0f}, +{0.319328f,-0.947644f,0.0f},{0.267531f,-0.963549f,0.0f},{0.319303f,-0.947653f,0.0f}, +{0.370172f,-0.928963f,0.0f},{0.419923f,-0.90756f,0.0f},{0.370136f,-0.928977f,0.0f}, +{0.46844f,-0.883495f,0.0f},{0.419887f,-0.907577f,0.0f},{0.468409f,-0.883512f,0.0f}, +{0.515581f,-0.856841f,0.0f},{0.56121f,-0.827674f,0.0f},{0.515559f,-0.856854f,0.0f}, +{0.605197f,-0.796076f,0.0f},{0.561199f,-0.827681f,0.0f},{0.605188f,-0.796082f,0.0f}, +{0.647411f,-0.762141f,0.0f},{0.687723f,-0.725973f,0.0f},{0.6474f,-0.762151f,0.0f}, +{0.726018f,-0.687676f,0.0f},{0.687712f,-0.725983f,0.0f},{0.726007f,-0.687687f,0.0f}, +{0.762183f,-0.647361f,0.0f},{0.796113f,-0.605148f,0.0f},{0.762171f,-0.647375f,0.0f}, +{0.827707f,-0.56116f,0.0f},{0.796101f,-0.605164f,0.0f},{0.827695f,-0.561178f,0.0f}, +{0.856873f,-0.515527f,0.0f},{0.883526f,-0.468383f,0.0f},{0.856862f,-0.515545f,0.0f}, +{0.907586f,-0.419866f,0.0f},{0.883516f,-0.4684f,0.0f},{0.907578f,-0.419884f,0.0f}, +{0.928986f,-0.370116f,0.0f},{0.947661f,-0.319279f,0.0f},{0.928977f,-0.370136f,0.0f}, +{0.963556f,-0.267507f,0.0f},{0.947653f,-0.319301f,0.0f},{0.96355f,-0.267528f,0.0f}, +{0.976624f,-0.214954f,0.0f},{0.986829f,-0.16177f,0.0f},{0.97662f,-0.214973f,0.0f}, +{0.994139f,-0.108111f,0.0f},{0.986826f,-0.161786f,0.0f},{0.994135f,-0.108145f,0.0f}, +{0.99855f,-0.0538298f,0.0f},{1.0f,2.15316e-016f,0.0f},{0.998551f,-0.0538044f,0.0f}, +{1.0f,2.35502e-016f,0.0f},{-0.0541566f,-0.998532f,0.0f},{-0.0541302f,-0.998534f,0.0f}, +{-0.108145f,-0.994135f,0.0f},{-0.161808f,-0.986822f,0.0f},{-0.108105f,-0.99414f,0.0f}, +{-0.214992f,-0.976616f,0.0f},{-0.161767f,-0.986829f,0.0f},{-0.214964f,-0.976622f,0.0f}, +{-0.267546f,-0.963545f,0.0f},{-0.319328f,-0.947644f,0.0f},{-0.267531f,-0.963549f,0.0f}, +{-0.370172f,-0.928963f,0.0f},{-0.319303f,-0.947653f,0.0f},{-0.370136f,-0.928977f,0.0f}, +{-0.419923f,-0.90756f,0.0f},{-0.46844f,-0.883495f,0.0f},{-0.419887f,-0.907577f,0.0f}, +{-0.515581f,-0.856841f,0.0f},{-0.468409f,-0.883512f,0.0f},{-0.515559f,-0.856854f,0.0f}, +{-0.56121f,-0.827674f,0.0f},{-0.605197f,-0.796076f,0.0f},{-0.561199f,-0.827681f,0.0f}, +{-0.647411f,-0.762141f,0.0f},{-0.605188f,-0.796082f,0.0f},{-0.6474f,-0.762151f,0.0f}, +{-0.687723f,-0.725973f,0.0f},{-0.726018f,-0.687676f,0.0f},{-0.687712f,-0.725983f,0.0f}, +{-0.762183f,-0.647361f,0.0f},{-0.726007f,-0.687687f,0.0f},{-0.762171f,-0.647375f,0.0f}, +{-0.796113f,-0.605148f,0.0f},{-0.827707f,-0.56116f,0.0f},{-0.796101f,-0.605164f,0.0f}, +{-0.856873f,-0.515527f,0.0f},{-0.827695f,-0.561178f,0.0f},{-0.856862f,-0.515545f,0.0f}, +{-0.883526f,-0.468383f,0.0f},{-0.907586f,-0.419866f,0.0f},{-0.883516f,-0.468401f,0.0f}, +{-0.928986f,-0.370116f,0.0f},{-0.907578f,-0.419884f,0.0f},{-0.928977f,-0.370136f,0.0f}, +{-0.947661f,-0.319279f,0.0f},{-0.963556f,-0.267507f,0.0f},{-0.947653f,-0.319301f,0.0f}, +{-0.976624f,-0.214954f,0.0f},{-0.96355f,-0.267528f,0.0f},{-0.97662f,-0.214973f,0.0f}, +{-0.986829f,-0.16177f,0.0f},{-0.994139f,-0.108111f,0.0f},{-0.986826f,-0.161786f,0.0f}, +{-0.99855f,-0.0538298f,0.0f},{-0.994135f,-0.108145f,0.0f},{-0.998551f,-0.0538045f,0.0f}, +{-1.0f,-1.19209e-007f,0.0f},{-0.718391f,-0.69564f,-2.2967e-015f},{-0.747457f,-0.66431f,4.30948e-015f}, +{-0.747455f,-0.664312f,-2.35972e-015f},{-0.688012f,-0.725699f,-2.11837e-015f},{-0.688011f,-0.7257f,-4.7761e-015f}, +{-0.656377f,-0.754433f,-3.42054e-015f},{-0.775156f,-0.631769f,1.02241e-015f},{-0.718389f,-0.695642f,1.63365e-016f}, +{-0.775159f,-0.631766f,1.30928e-015f},{-0.801442f,-0.598073f,-4.02386e-016f},{-0.801444f,-0.59807f,3.14782e-015f}, +{-0.826266f,-0.563281f,2.05014e-015f},{-0.826264f,-0.563284f,2.15457e-016f},{-0.849576f,-0.527466f,3.68245e-015f}, +{-0.849578f,-0.527463f,-9.04405e-017f},{-0.871339f,-0.490682f,2.82586e-015f},{-0.891507f,-0.453007f,-1.11336e-015f}, +{-0.871337f,-0.490685f,-3.98744e-016f},{-0.891508f,-0.453005f,8.87668e-016f},{-0.91005f,-0.414499f,3.62163e-016f}, +{-0.910048f,-0.414503f,-2.33213e-015f},{-0.955579f,-0.294734f,1.39294e-015f},{-0.942115f,-0.335291f,1.29026e-015f}, +{-0.95558f,-0.294731f,9.56661e-016f},{-0.926927f,-0.375241f,3.09815e-015f},{-0.926928f,-0.375238f,3.53892e-016f}, +{-0.942114f,-0.335293f,1.78659e-015f},{-0.9673f,-0.253636f,4.48455e-017f},{-0.977253f,-0.212075f,9.31315e-017f}, +{-0.9673f,-0.253634f,-3.87537e-015f},{-0.977254f,-0.212073f,1.53976e-015f},{-0.985423f,-0.170124f,-1.33727e-015f}, +{-0.991791f,-0.127866f,1.31222e-015f},{-0.991791f,-0.127868f,-1.43479e-015f},{-0.985422f,-0.170128f,-1.08544e-015f}, +{-0.996349f,-0.0853729f,-2.96511e-015f},{-0.996349f,-0.0853758f,1.45956e-015f},{-0.999087f,-0.0427249f,-1.45746e-015f}, +{-0.999087f,-0.0427275f,2.97938e-015f},{-1.0f,-1.41083e-016f,0.0f},{-1.0f,-1.54309e-016f,0.0f}, +{-0.623543f,-0.781789f,-8.12728e-016f},{-0.656376f,-0.754434f,-2.4015e-015f},{-0.623541f,-0.78179f,-9.35104e-016f}, +{-0.589571f,-0.807717f,-3.8494e-015f},{-0.589569f,-0.807718f,8.37214e-016f},{-0.554522f,-0.832169f,-3.65599e-015f}, +{-0.51846f,-0.855102f,-4.07623e-015f},{-0.554519f,-0.832171f,2.81113e-015f},{-0.518456f,-0.855104f,2.96789e-016f}, +{-0.48145f,-0.876473f,3.95802e-015f},{-0.481448f,-0.876475f,6.89284e-016f},{-0.443562f,-0.896244f,7.12651e-016f}, +{-0.404864f,-0.914377f,-1.93578e-015f},{-0.443559f,-0.896245f,5.43092e-015f},{-0.40486f,-0.914379f,-5.84661e-015f}, +{-0.365425f,-0.930841f,1.20115e-015f},{-0.365423f,-0.930842f,3.55128e-015f},{-0.32532f,-0.945604f,2.23888e-015f}, +{-0.284621f,-0.95864f,5.39664e-015f},{-0.325317f,-0.945605f,4.0151e-015f},{-0.284618f,-0.958641f,-2.22393e-015f}, +{-0.243401f,-0.969926f,4.33048e-015f},{-0.243399f,-0.969926f,4.23515e-015f},{-0.201738f,-0.97944f,4.2777e-015f}, +{-0.159705f,-0.987165f,5.95984e-015f},{-0.201735f,-0.97944f,6.68731e-016f},{-0.159703f,-0.987165f,-8.70338e-015f}, +{-0.117381f,-0.993087f,-6.76187e-015f},{-0.117378f,-0.993087f,7.13795e-015f},{-0.0748434f,-0.997195f,-4.49833e-016f}, +{-0.0321679f,-0.999482f,5.88869e-015f},{-0.07484f,-0.997196f,-1.11652e-015f},{-0.0321656f,-0.999483f,-2.74195e-016f}, +{0.0105657f,-0.999944f,5.2388e-015f},{0.0105686f,-0.999944f,-6.15843e-016f},{0.05328f,-0.99858f,7.92959e-015f}, +{0.0958981f,-0.995391f,0.0f},{0.0532825f,-0.99858f,4.50329e-015f},{-0.0141122f,0.9999f,0.0f}, +{0.0141124f,0.9999f,0.0f},{-0.0141125f,0.9999f,0.0f},{-0.0423259f,0.999104f,0.0f}, +{-0.0423254f,0.999104f,0.0f},{-0.0705055f,0.997511f,0.0f},{-0.0705051f,0.997511f,0.0f}, +{-0.0986284f,0.995124f,0.0f},{-0.0986291f,0.995124f,0.0f},{-0.126674f,0.991944f,0.0f}, +{-0.126673f,0.991944f,0.0f},{-0.154618f,0.987974f,0.0f},{-0.154617f,0.987974f,0.0f}, +{-0.182438f,0.983217f,0.0f},{-0.182439f,0.983217f,0.0f},{-0.210114f,0.977677f,0.0f}, +{-0.210113f,0.977677f,0.0f},{-0.237622f,0.971358f,0.0f},{-0.237622f,0.971358f,0.0f}, +{-0.26494f,0.964265f,0.0f},{-0.264941f,0.964265f,0.0f},{-0.292049f,0.956403f,0.0f}, +{-0.292048f,0.956404f,0.0f},{-0.318924f,0.94778f,0.0f},{-0.318923f,0.947781f,0.0f}, +{-0.345544f,0.938403f,0.0f},{-0.345545f,0.938402f,0.0f},{-0.371891f,0.928277f,0.0f}, +{-0.37189f,0.928277f,0.0f},{-0.39794f,0.917411f,0.0f},{-0.397939f,0.917412f,0.0f}, +{-0.423672f,0.905816f,0.0f},{-0.423672f,0.905815f,0.0f},{-0.449067f,0.893498f,0.0f}, +{-0.449067f,0.893498f,0.0f},{-0.474105f,0.880469f,0.0f},{-0.474104f,0.880469f,0.0f}, +{-0.498763f,0.866738f,0.0f},{-0.498764f,0.866738f,0.0f},{-0.523026f,0.852317f,0.0f}, +{0.0141122f,0.9999f,0.0f},{0.0423254f,0.999104f,0.0f},{0.0423259f,0.999104f,0.0f}, +{0.0705055f,0.997511f,0.0f},{0.0705051f,0.997511f,0.0f},{0.0986291f,0.995124f,0.0f}, +{0.0986285f,0.995124f,0.0f},{0.126673f,0.991944f,0.0f},{0.126674f,0.991944f,0.0f}, +{0.154618f,0.987974f,0.0f},{0.154617f,0.987974f,0.0f},{0.182439f,0.983217f,0.0f}, +{0.182438f,0.983217f,0.0f},{0.210113f,0.977677f,0.0f},{0.210114f,0.977677f,0.0f}, +{0.237622f,0.971358f,0.0f},{0.237622f,0.971358f,0.0f},{0.264941f,0.964265f,0.0f}, +{0.26494f,0.964265f,0.0f},{0.292048f,0.956404f,0.0f},{0.292049f,0.956403f,0.0f}, +{0.318924f,0.94778f,0.0f},{0.318923f,0.947781f,0.0f},{0.345545f,0.938402f,0.0f}, +{0.345544f,0.938403f,0.0f},{0.37189f,0.928277f,0.0f},{0.371891f,0.928277f,0.0f}, +{0.39794f,0.917411f,0.0f},{0.397939f,0.917412f,0.0f},{0.423672f,0.905815f,0.0f}, +{0.423672f,0.905816f,0.0f},{0.449067f,0.893498f,0.0f},{0.449067f,0.893498f,0.0f}, +{0.474104f,0.880469f,0.0f},{0.474104f,0.880469f,0.0f},{0.498764f,0.866738f,0.0f}, +{0.498764f,0.866738f,0.0f},{0.523026f,0.852317f,0.0f},{0.866025f,0.5f,-7.6671e-016f}, +{-4.33681e-019f,0.0f,1.0f},{4.33681e-019f,0.0f,1.0f},{0.466272f,0.884642f,2.20644e-016f}, +{0.628286f,0.777982f,5.89571e-016f},{0.628223f,0.778033f,-5.53502e-016f},{0.286781f,0.957996f,1.48116e-016f}, +{0.466199f,0.88468f,-5.1317e-016f},{0.286593f,0.958053f,-1.63827e-016f},{-0.0974696f,0.995238f,3.44802e-016f}, +{0.0962625f,0.995356f,-1.06856e-016f},{-0.097635f,0.995222f,-4.56953e-017f},{0.0964852f,0.995334f,-1.31963e-016f}, +{0.766564f,0.642168f,0.0f},{0.876095f,0.482138f,-7.37654e-016f},{0.76669f,0.642017f,-1.10523e-015f}, +{0.876203f,0.481942f,7.37698e-016f},{0.952689f,0.303947f,0.0f},{0.952739f,0.303789f,0.0f}, +{0.698102f,0.715999f,1.29175e-016f},{0.324434f,0.945908f,-5.70109e-016f},{0.324434f,0.945908f,-3.35048e-016f}, +{0.524032f,0.851699f,7.27349e-016f},{-1.0f,-3.33067e-016f,0.0f},{-0.98085f,-0.194766f,-8.7013e-016f}, +{-0.707075f,-0.707139f,5.23388e-016f},{-0.707766f,-0.706447f,5.22876e-016f},{-0.831545f,-0.555458f,-6.15467e-016f}, +{-0.831851f,-0.554999f,-4.10782e-016f},{-0.924075f,-0.382212f,-1.36791e-015f},{-0.196168f,-0.98057f,-1.01605e-015f}, +{-0.194654f,-0.980872f,-1.44073e-016f},{-0.555293f,-0.831655f,-4.10999e-016f},{-0.382179f,-0.924088f,-1.22649e-015f}, +{-0.384009f,-0.923329f,-1.99588e-016f},{0.384009f,-0.923329f,-2.13958e-016f},{0.555293f,-0.831655f,6.67161e-016f}, +{0.382179f,-0.924088f,9.40449e-016f},{0.196168f,-0.98057f,-7.62016e-016f},{0.194653f,-0.980872f,6.1653e-016f}, +{2.96059e-016f,-1.0f,-3.28692e-031f},{0.707765f,-0.706447f,4.57334e-016f},{0.831545f,-0.555458f,8.32431e-017f}, +{0.707075f,-0.707139f,-4.57955e-016f},{0.556611f,-0.830773f,-3.85076e-016f},{0.831851f,-0.554999f,-2.05391e-016f}, +{0.923954f,-0.382504f,-2.95917e-016f},{0.980825f,-0.19489f,-3.63028e-018f},{0.924075f,-0.382212f,5.86375e-016f}, +{0.98085f,-0.194766f,-2.22141e-016f},{1.0f,-1.85037e-017f,0.0f},{-0.556611f,-0.830773f,-1.04527e-016f}, +{-1.0f,-2.96059e-016f,0.0f},{-1.0f,-1.85037e-017f,0.0f},{-0.980825f,-0.19489f,-8.70204e-016f}, +{-0.98085f,-0.194766f,7.25975e-016f},{-0.707075f,-0.707139f,2.6167e-016f},{-0.707766f,-0.706447f,-1.04673e-015f}, +{-0.831545f,-0.555458f,6.15467e-016f},{-0.196168f,-0.98057f,-7.25968e-017f},{-0.194654f,-0.980872f,0.0f}, +{-0.555293f,-0.831655f,2.055e-016f},{-0.384009f,-0.923329f,-1.42112e-016f},{0.384009f,-0.923329f,7.57929e-018f}, +{0.555293f,-0.831655f,4.10524e-016f},{0.382179f,-0.924088f,2.41708e-016f},{0.196168f,-0.98057f,-1.26994e-016f}, +{0.194653f,-0.980872f,-9.14525e-017f},{0.707765f,-0.706447f,-5.72353e-016f},{0.831545f,-0.555458f,-9.69264e-018f}, +{0.707075f,-0.707139f,1.14487e-016f},{0.556611f,-0.830773f,5.13819e-016f},{0.831851f,-0.554999f,4.97064e-016f}, +{0.923954f,-0.382504f,1.06278e-016f},{0.980825f,-0.19489f,-1.02781e-015f},{0.924075f,-0.382212f,4.37371e-016f}, +{0.98085f,-0.194766f,8.39508e-016f},{1.0f,-2.96059e-016f,0.0f},{1.0f,-5.92119e-016f,0.0f}, +{-0.556611f,-0.830773f,-5.13435e-016f},{-0.989489f,-0.144611f,-3.80291e-017f},{-0.99711f,0.0759712f,-5.623e-017f}, +{-0.933664f,-0.358149f,-9.55933e-016f},{-0.933664f,-0.358149f,1.99014e-016f},{-0.835272f,-0.549837f,0.0f}, +{-0.957691f,0.2878f,0.0f},{1.0f,1.53707e-012f,0.0f},{1.0f,8.42952e-008f,0.0f}, +{-3.07487e-012f,1.0f,0.0f},{-3.07526e-012f,1.0f,0.0f},{-0.673422f,-0.739259f,0.0f}, +{-0.703582f,-0.710614f,0.0f},{-0.673421f,-0.739259f,0.0f},{-0.642094f,-0.766626f,0.0f}, +{-0.642096f,-0.766624f,0.0f},{-0.609658f,-0.792665f,0.0f},{-0.60966f,-0.792663f,0.0f}, +{-0.576168f,-0.817331f,0.0f},{-0.576166f,-0.817333f,0.0f},{-0.541677f,-0.840587f,0.0f}, +{-0.54168f,-0.840585f,0.0f},{-0.506252f,-0.862386f,0.0f},{-0.506254f,-0.862384f,0.0f}, +{-0.469953f,-0.882691f,0.0f},{-0.46995f,-0.882693f,0.0f},{-0.432835f,-0.901473f,0.0f}, +{-0.432838f,-0.901471f,0.0f},{-0.394972f,-0.918693f,0.0f},{-0.394974f,-0.918692f,0.0f}, +{-0.356428f,-0.934323f,0.0f},{-0.356425f,-0.934324f,0.0f},{-0.317262f,-0.948338f,0.0f}, +{-0.317264f,-0.948337f,0.0f},{-0.277549f,-0.960711f,0.0f},{-0.277552f,-0.960711f,0.0f}, +{-0.237359f,-0.971422f,0.0f},{-0.237356f,-0.971423f,0.0f},{-0.196753f,-0.980453f,0.0f}, +{-0.196756f,-0.980453f,0.0f},{-0.155809f,-0.987787f,0.0f},{-0.155812f,-0.987787f,0.0f}, +{-0.114599f,-0.993412f,0.0f},{-0.114596f,-0.993412f,0.0f},{-0.0731848f,-0.997318f,0.0f}, +{-0.073187f,-0.997318f,0.0f},{-0.0316463f,-0.999499f,0.0f},{-0.0316489f,-0.999499f,0.0f}, +{0.00994395f,-0.999951f,0.0f},{0.00994627f,-0.999951f,0.0f},{0.0515206f,-0.998672f,0.0f}, +{-0.703582f,-0.710614f,0.0f},{-0.732525f,-0.680741f,0.0f},{-0.732526f,-0.680739f,0.0f}, +{-0.760202f,-0.649687f,0.0f},{-0.760201f,-0.649688f,0.0f},{-0.786563f,-0.61751f,0.0f}, +{-0.786561f,-0.617513f,0.0f},{-0.811561f,-0.584268f,0.0f},{-0.811563f,-0.584265f,0.0f}, +{-0.835158f,-0.55001f,0.0f},{-0.835156f,-0.550013f,0.0f},{-0.857309f,-0.514803f,0.0f}, +{-0.857307f,-0.514806f,0.0f},{-0.877974f,-0.478708f,0.0f},{-0.877976f,-0.478705f,0.0f}, +{-0.897124f,-0.441779f,0.0f},{-0.897123f,-0.441782f,0.0f},{-0.91472f,-0.404088f,0.0f}, +{-0.914719f,-0.404092f,0.0f},{-0.930732f,-0.365702f,0.0f},{-0.930733f,-0.365699f,0.0f}, +{-0.945136f,-0.326677f,0.0f},{-0.945135f,-0.326679f,0.0f},{-0.957904f,-0.287089f,0.0f}, +{-0.957903f,-0.287092f,0.0f},{-0.969013f,-0.247008f,0.0f},{-0.969014f,-0.247006f,0.0f}, +{-0.978448f,-0.206494f,0.0f},{-0.978447f,-0.206496f,0.0f},{-0.986189f,-0.165625f,0.0f}, +{-0.986188f,-0.165628f,0.0f},{-0.992223f,-0.124472f,0.0f},{-0.992223f,-0.12447f,0.0f}, +{-0.996541f,-0.0830991f,0.0f},{-0.996541f,-0.0831017f,0.0f},{-0.999135f,-0.041585f,0.0f}, +{-0.999135f,-0.0415873f,0.0f},{-1.0f,-1.92868e-016f,0.0f},{-1.0f,-8.64379e-008f,0.0f}, +{-0.998361f,-0.0572333f,1.89979e-016f},{-1.0f,3.3736e-016f,0.0f},{-0.993449f,-0.114279f,0.0f}, +{-0.569266f,-0.822154f,0.0f},{-0.413628f,-0.910446f,0.0f},{-0.569567f,-0.821945f,0.0f}, +{-0.413191f,-0.910644f,0.0f},{-0.244303f,-0.969699f,0.0f},{-0.243984f,-0.969779f,0.0f}, +{-0.0672808f,-0.997734f,0.0f},{0.11203f,-0.993705f,0.0f},{-0.0668255f,-0.997765f,0.0f}, +{0.2878f,-0.957691f,0.0f},{0.112396f,-0.993663f,0.0f},{-0.822154f,-0.569266f,0.0f}, +{-0.821945f,-0.569567f,0.0f},{-0.910446f,-0.413628f,0.0f},{-0.969699f,-0.244303f,0.0f}, +{-0.910644f,-0.413191f,0.0f},{-0.969779f,-0.243985f,0.0f},{-0.997734f,-0.0672808f,0.0f}, +{-0.997765f,-0.0668255f,0.0f},{-0.993705f,0.11203f,0.0f},{-0.993663f,0.112396f,0.0f}, +{0.567551f,-0.823338f,2.91569e-016f},{0.480256f,-0.877128f,-1.36506e-015f},{0.480275f,-0.877118f,1.00957e-015f}, +{0.567558f,-0.823334f,5.00925e-017f},{0.648872f,-0.760897f,1.44361e-016f},{0.387941f,-0.921684f,1.25621e-016f}, +{0.387915f,-0.921695f,6.82191e-016f},{0.291525f,-0.956563f,-6.81027e-016f},{0.291499f,-0.956571f,-7.61943e-016f}, +{0.192047f,-0.981386f,6.553e-016f},{0.192025f,-0.98139f,1.77659e-017f},{0.0904984f,-0.995897f,-8.37279e-018f}, +{0.0905325f,-0.995893f,-1.67519e-017f},{-0.0119218f,-0.999929f,1.48019e-015f},{-0.114279f,-0.993449f,0.0f}, +{-0.0121699f,-0.999926f,0.0f},{0.723369f,-0.690461f,-9.58068e-017f},{0.648879f,-0.760892f,1.7081e-016f}, +{0.723384f,-0.690446f,-1.49808e-016f},{0.790265f,-0.612765f,1.16954e-016f},{0.790282f,-0.612743f,-1.7266e-016f}, +{0.848856f,-0.528625f,3.32998e-016f},{0.898522f,-0.438929f,-5.4393e-016f},{0.84887f,-0.528601f,4.57239e-016f}, +{0.898532f,-0.438908f,-2.60926e-016f},{0.938749f,-0.344602f,1.75687e-016f},{0.938761f,-0.34457f,5.73784e-016f}, +{0.969101f,-0.246664f,-5.54286e-016f},{0.989269f,-0.146104f,0.0f},{0.969162f,-0.246424f,-8.55909e-016f}, +{0.863082f,0.505064f,-2.96041e-016f},{0.939433f,0.342733f,-1.39064e-015f},{0.757002f,0.653412f,-4.80673e-016f}, +{0.98457f,0.174993f,-7.12538e-016f},{0.999951f,0.00988645f,0.0f},{0.625744f,0.780028f,-1.42742e-017f}, +{0.47631f,0.879277f,-1.99991e-016f},{0.316965f,0.948437f,-3.53543e-016f},{0.155878f,0.987776f,8.15532e-017f}, +{1.95899e-012f,1.0f,0.0f},{1.95907e-012f,1.0f,0.0f},{1.0f,-4.18691e-016f,0.0f}, +{1.0f,-2.09346e-016f,0.0f},{2.61682e-016f,-1.0f,0.0f},{8.42937e-008f,-1.0f,0.0f}, +{0.432409f,-0.901678f,-4.8007e-016f},{0.568002f,-0.823027f,1.63014e-016f},{0.288928f,-0.957351f,2.01882e-015f}, +{0.288928f,-0.957351f,0.0f},{0.143098f,-0.989708f,7.32531e-016f},{0.690346f,-0.72348f,-1.05257e-015f}, +{4.36853e-016f,-1.0f,0.0f},{9.28313e-016f,-1.0f,0.0f},{0.794923f,-0.60671f,-3.38738e-016f}, +{0.878607f,-0.477546f,-8.64155e-016f},{0.939939f,-0.341342f,-3.74916e-016f},{0.979111f,-0.203325f,0.0f}, +{0.610942f,-0.791675f,0.0f},{0.64341f,-0.765522f,0.0f},{0.674759f,-0.738038f,0.0f}, +{0.643409f,-0.765522f,0.0f},{0.704936f,-0.709271f,0.0f},{0.674758f,-0.738039f,0.0f}, +{0.704934f,-0.709273f,0.0f},{0.733887f,-0.679272f,0.0f},{0.761562f,-0.648092f,0.0f}, +{0.733885f,-0.679273f,0.0f},{0.787914f,-0.615785f,0.0f},{0.761561f,-0.648094f,0.0f}, +{0.787913f,-0.615787f,0.0f},{0.812896f,-0.582409f,0.0f},{0.836465f,-0.54802f,0.0f}, +{0.812895f,-0.58241f,0.0f},{0.858581f,-0.512678f,0.0f},{0.836464f,-0.548021f,0.0f}, +{0.85858f,-0.51268f,0.0f},{0.879204f,-0.476445f,0.0f},{0.898299f,-0.439385f,0.0f}, +{0.879203f,-0.476447f,0.0f},{0.915833f,-0.40156f,0.0f},{0.898298f,-0.439387f,0.0f}, +{0.915832f,-0.401562f,0.0f},{0.931774f,-0.363038f,0.0f},{0.946097f,-0.323885f,0.0f}, +{0.931774f,-0.36304f,0.0f},{0.958774f,-0.284168f,0.0f},{0.946096f,-0.323886f,0.0f}, +{0.958774f,-0.28417f,0.0f},{0.969786f,-0.243959f,0.0f},{0.969785f,-0.24396f,0.0f}, +{0.577412f,-0.816453f,0.0f},{0.577413f,-0.816452f,0.0f},{0.542879f,-0.839811f,0.0f}, +{0.507402f,-0.861709f,0.0f},{0.54288f,-0.83981f,0.0f},{0.471044f,-0.88211f,0.0f}, +{0.507404f,-0.861708f,0.0f},{0.471046f,-0.882109f,0.0f},{0.433866f,-0.900977f,0.0f}, +{0.395935f,-0.918278f,0.0f},{0.433869f,-0.900976f,0.0f},{0.357316f,-0.933984f,0.0f}, +{0.395937f,-0.918278f,0.0f},{0.357318f,-0.933983f,0.0f},{0.318075f,-0.948065f,0.0f}, +{0.278282f,-0.960499f,0.0f},{0.318077f,-0.948065f,0.0f},{0.238005f,-0.971264f,0.0f}, +{0.278284f,-0.960499f,0.0f},{0.238007f,-0.971263f,0.0f},{0.197314f,-0.98034f,0.0f}, +{0.15628f,-0.987713f,0.0f},{0.197316f,-0.98034f,0.0f},{0.114975f,-0.993368f,0.0f}, +{0.156283f,-0.987712f,0.0f},{0.114977f,-0.993368f,0.0f},{0.0734701f,-0.997297f,0.0f}, +{0.0318375f,-0.999493f,0.0f},{0.0734722f,-0.997297f,0.0f},{-0.00985025f,-0.999951f,0.0f}, +{0.0318392f,-0.999493f,0.0f},{-0.00984923f,-0.999951f,0.0f},{-0.0515206f,-0.998672f,0.0f}, +{0.866025f,-0.5f,-4.07254e-016f},{0.0706974f,0.997498f,4.22047e-015f},{0.042441f,0.999099f,-4.49972e-015f}, +{0.0424415f,0.999099f,-8.87378e-015f},{-0.0141508f,0.9999f,-1.48015e-015f},{0.014151f,0.9999f,0.0f}, +{0.0141508f,0.9999f,-7.42169e-015f},{0.0706979f,0.997498f,1.47659e-015f},{0.0988972f,0.995098f,5.89216e-015f}, +{0.0988976f,0.995098f,5.59937e-015f},{0.127018f,0.9919f,-1.17465e-014f},{0.127018f,0.9919f,-1.72436e-014f}, +{0.155036f,0.987909f,-5.3906e-015f},{0.155037f,0.987909f,5.84959e-015f},{0.182932f,0.983126f,-2.36905e-015f}, +{0.182931f,0.983126f,8.73191e-015f},{0.238259f,0.971202f,8.626e-015f},{0.265648f,0.96407f,-7.28139e-015f}, +{0.265647f,0.96407f,-1.29898e-014f},{0.210679f,0.977555f,-4.54082e-015f},{0.21068f,0.977555f,0.0f}, +{0.238258f,0.971202f,-1.29121e-014f},{0.292823f,0.956167f,-1.73386e-015f},{0.292823f,0.956167f,0.0f}, +{0.319764f,0.947497f,5.61031e-015f},{0.319764f,0.947497f,-1.89338e-015f},{0.346449f,0.938069f,0.0f}, +{0.346449f,0.938069f,7.60587e-015f},{0.372856f,0.927889f,9.90971e-015f},{0.424755f,0.905308f,5.3605e-015f}, +{0.424755f,0.905309f,3.304e-016f},{0.398966f,0.916966f,4.7247e-015f},{0.398965f,0.916966f,5.42953e-015f}, +{0.372857f,0.927889f,-7.70196e-015f},{0.450204f,0.892926f,0.0f},{0.450204f,0.892926f,5.33148e-015f}, +{0.475292f,0.879828f,1.04193e-014f},{0.475292f,0.879828f,1.04193e-014f},{-0.014151f,0.9999f,8.90184e-015f}, +{-0.042441f,0.999099f,-1.04784e-014f},{-0.0424415f,0.999099f,-1.61429e-014f},{-0.0706974f,0.997498f,8.65025e-015f}, +{-0.0988972f,0.995098f,2.94608e-015f},{-0.0706979f,0.997498f,-1.09175e-014f},{-0.0988976f,0.995098f,1.39984e-015f}, +{-0.127018f,0.9919f,-1.06363e-014f},{-0.127018f,0.9919f,9.63801e-015f},{-0.155036f,0.987909f,-7.40539e-015f}, +{-0.182931f,0.983126f,-7.57272e-015f},{-0.155037f,0.987909f,-2.5165e-015f},{-0.182932f,0.983126f,2.18298e-015f}, +{-0.210679f,0.977555f,7.64703e-015f},{-0.21068f,0.977555f,-4.23518e-015f},{-0.238258f,0.971202f,-1.03144e-014f}, +{-0.265647f,0.96407f,-7.60334e-015f},{-0.238259f,0.971202f,1.75636e-015f},{-0.265648f,0.96407f,1.0869e-014f}, +{-0.292823f,0.956167f,5.12754e-015f},{-0.292823f,0.956167f,-8.24033e-015f},{-0.319764f,0.947497f,3.07966e-016f}, +{-0.346449f,0.938069f,-1.05337e-014f},{-0.319764f,0.947497f,-8.2576e-015f},{-0.346449f,0.938069f,-1.87656e-015f}, +{-0.372856f,0.927889f,3.1746e-015f},{-0.372857f,0.927889f,-3.31849e-015f},{-0.398965f,0.916966f,3.06056e-015f}, +{-0.424755f,0.905309f,7.49538e-015f},{-0.398966f,0.916966f,4.02549e-015f},{-0.424755f,0.905308f,1.46943e-015f}, +{-0.450204f,0.892926f,-1.18685e-014f},{-0.450204f,0.892926f,1.25672e-015f},{-0.475292f,0.879828f,4.58408e-015f}, +{-0.475292f,0.879828f,1.83809e-015f},{-0.623541f,0.78179f,-1.15728e-015f},{-0.589568f,0.807718f,-2.39133e-015f}, +{-0.589571f,0.807717f,9.60223e-017f},{-0.656376f,0.754434f,-5.72909e-015f},{-0.656377f,0.754433f,-7.23689e-015f}, +{-0.688011f,0.7257f,1.01846e-015f},{-0.554522f,0.832169f,1.64171e-015f},{-0.623543f,0.781789f,4.8494e-015f}, +{-0.554519f,0.832171f,4.10543e-015f},{-0.51846f,0.855102f,-9.96661e-016f},{-0.518456f,0.855104f,1.53494e-015f}, +{-0.481448f,0.876475f,-5.18977e-015f},{-0.48145f,0.876473f,-4.02026e-015f},{-0.443562f,0.896244f,-2.65341e-015f}, +{-0.443559f,0.896245f,-3.96662e-015f},{-0.40486f,0.914379f,0.0f},{-0.365425f,0.930841f,0.0f}, +{-0.404864f,0.914377f,-2.39728e-015f},{-0.365423f,0.930842f,0.0f},{-0.325317f,0.945605f,-3.67284e-015f}, +{-0.32532f,0.945604f,0.0f},{-0.201738f,0.97944f,3.58358e-015f},{-0.243399f,0.969926f,-1.44121e-015f}, +{-0.201735f,0.97944f,-3.41043e-015f},{-0.284621f,0.95864f,7.36158e-015f},{-0.284618f,0.958641f,-5.6763e-015f}, +{-0.243401f,0.969926f,5.74311e-015f},{-0.159705f,0.987165f,9.45645e-016f},{-0.117381f,0.993087f,-1.03704e-014f}, +{-0.159703f,0.987165f,-4.89956e-015f},{-0.117378f,0.993087f,-6.9502e-016f},{-0.07484f,0.997196f,0.0f}, +{-0.0321655f,0.999483f,6.29904e-015f},{-0.032168f,0.999482f,-5.91813e-015f},{-0.0748434f,0.997195f,-8.86324e-016f}, +{0.0105685f,0.999944f,-5.7957e-015f},{0.0105657f,0.999944f,5.92086e-015f},{0.0532826f,0.99858f,0.0f}, +{0.05328f,0.99858f,0.0f},{0.0958981f,0.995391f,0.0f},{-0.718389f,0.695642f,-2.12686e-015f}, +{-0.688012f,0.725699f,-3.16696e-015f},{-0.718391f,0.69564f,6.73571e-017f},{-0.747455f,0.664312f,3.69231e-016f}, +{-0.747457f,0.66431f,-4.91688e-015f},{-0.775156f,0.631769f,-3.61476e-016f},{-0.801442f,0.598073f,-8.85326e-016f}, +{-0.775159f,0.631767f,-5.10676e-016f},{-0.801444f,0.59807f,-2.51436e-015f},{-0.826264f,0.563284f,-2.63707e-016f}, +{-0.826266f,0.563281f,-4.79448e-015f},{-0.849576f,0.527466f,2.47204e-015f},{-0.871337f,0.490685f,-7.45068e-016f}, +{-0.849578f,0.527463f,6.28814e-016f},{-0.871339f,0.490682f,-4.66609e-016f},{-0.891507f,0.453007f,-5.36872e-018f}, +{-0.891508f,0.453005f,1.90646e-015f},{-0.910048f,0.414503f,-9.01947e-016f},{-0.926927f,0.375241f,-7.55498e-016f}, +{-0.91005f,0.414499f,-3.44627e-015f},{-0.926928f,0.375238f,-8.26493e-018f},{-0.942114f,0.335293f,7.4317e-016f}, +{-0.942115f,0.335291f,-1.38718e-015f},{-0.955579f,0.294734f,-6.60361e-018f},{-0.9673f,0.253636f,1.39186e-016f}, +{-0.95558f,0.294731f,-4.80822e-016f},{-0.9673f,0.253634f,-1.1694e-015f},{-0.977253f,0.212076f,-1.09093e-015f}, +{-0.977254f,0.212073f,-1.42807e-015f},{-0.985422f,0.170128f,-8.58064e-016f},{-0.991791f,0.127868f,1.21011e-015f}, +{-0.985423f,0.170124f,3.47036e-015f},{-0.991791f,0.127866f,2.85545e-016f},{-0.996349f,0.0853758f,-4.87227e-016f}, +{-0.996349f,0.0853729f,3.21028e-015f},{-0.999087f,0.0427275f,-3.76158e-016f},{-1.0f,1.41083e-016f,0.0f}, +{-0.999087f,0.0427249f,-2.9625e-015f},{-1.0f,1.54309e-016f,0.0f},{-5.04647e-017f,1.0f,0.0f}, +{-5.3829e-017f,1.0f,0.0f},{-0.0541567f,0.998532f,0.0f},{-0.108145f,0.994135f,0.0f}, +{-0.0541301f,0.998534f,0.0f},{-0.161808f,0.986822f,0.0f},{-0.108105f,0.99414f,0.0f}, +{-0.161767f,0.986829f,0.0f},{-0.214992f,0.976616f,0.0f},{-0.267546f,0.963545f,0.0f}, +{-0.214964f,0.976622f,0.0f},{-0.319328f,0.947644f,0.0f},{-0.267531f,0.963549f,0.0f}, +{-0.319303f,0.947653f,0.0f},{-0.370172f,0.928963f,0.0f},{-0.419923f,0.90756f,0.0f}, +{-0.370136f,0.928977f,0.0f},{-0.46844f,0.883495f,0.0f},{-0.419887f,0.907577f,0.0f}, +{-0.468409f,0.883512f,0.0f},{-0.515581f,0.856841f,0.0f},{-0.56121f,0.827674f,0.0f}, +{-0.515559f,0.856854f,0.0f},{-0.605197f,0.796076f,0.0f},{-0.561199f,0.827681f,0.0f}, +{-0.605188f,0.796082f,0.0f},{-0.647411f,0.762141f,0.0f},{-0.687723f,0.725973f,0.0f}, +{-0.6474f,0.762151f,0.0f},{-0.726018f,0.687676f,0.0f},{-0.687712f,0.725983f,0.0f}, +{-0.726007f,0.687687f,0.0f},{-0.762183f,0.647361f,0.0f},{-0.796113f,0.605148f,0.0f}, +{-0.762171f,0.647375f,0.0f},{-0.827707f,0.56116f,0.0f},{-0.796101f,0.605164f,0.0f}, +{-0.827695f,0.561178f,0.0f},{-0.856873f,0.515527f,0.0f},{-0.883526f,0.468383f,0.0f}, +{-0.856862f,0.515545f,0.0f},{-0.907586f,0.419866f,0.0f},{-0.883516f,0.4684f,0.0f}, +{-0.907578f,0.419884f,0.0f},{-0.928986f,0.370116f,0.0f},{-0.947661f,0.319279f,0.0f}, +{-0.928977f,0.370136f,0.0f},{-0.963556f,0.267507f,0.0f},{-0.947653f,0.319301f,0.0f}, +{-0.96355f,0.267528f,0.0f},{-0.976624f,0.214954f,0.0f},{-0.986829f,0.16177f,0.0f}, +{-0.97662f,0.214973f,0.0f},{-0.994139f,0.108111f,0.0f},{-0.986826f,0.161786f,0.0f}, +{-0.994135f,0.108145f,0.0f},{-0.99855f,0.0538298f,0.0f},{-1.0f,-2.15316e-016f,0.0f}, +{-0.998551f,0.0538044f,0.0f},{-1.0f,-2.35502e-016f,0.0f},{0.0541566f,0.998532f,0.0f}, +{0.0541302f,0.998534f,0.0f},{0.108145f,0.994135f,0.0f},{0.161808f,0.986822f,0.0f}, +{0.108105f,0.99414f,0.0f},{0.214992f,0.976616f,0.0f},{0.161767f,0.986829f,0.0f}, +{0.214964f,0.976622f,0.0f},{0.267546f,0.963545f,0.0f},{0.319328f,0.947644f,0.0f}, +{0.267531f,0.963549f,0.0f},{0.370172f,0.928963f,0.0f},{0.319303f,0.947653f,0.0f}, +{0.370136f,0.928977f,0.0f},{0.419923f,0.90756f,0.0f},{0.46844f,0.883495f,0.0f}, +{0.419887f,0.907577f,0.0f},{0.515581f,0.856841f,0.0f},{0.468409f,0.883512f,0.0f}, +{0.515559f,0.856854f,0.0f},{0.56121f,0.827674f,0.0f},{0.605197f,0.796076f,0.0f}, +{0.561199f,0.827681f,0.0f},{0.647411f,0.762141f,0.0f},{0.605188f,0.796082f,0.0f}, +{0.6474f,0.762151f,0.0f},{0.687723f,0.725973f,0.0f},{0.726018f,0.687676f,0.0f}, +{0.687712f,0.725983f,0.0f},{0.762183f,0.647361f,0.0f},{0.726007f,0.687687f,0.0f}, +{0.762171f,0.647375f,0.0f},{0.796113f,0.605148f,0.0f},{0.827707f,0.56116f,0.0f}, +{0.796101f,0.605164f,0.0f},{0.856873f,0.515527f,0.0f},{0.827695f,0.561178f,0.0f}, +{0.856862f,0.515545f,0.0f},{0.883526f,0.468383f,0.0f},{0.907586f,0.419866f,0.0f}, +{0.883516f,0.468401f,0.0f},{0.928986f,0.370116f,0.0f},{0.907578f,0.419884f,0.0f}, +{0.928977f,0.370136f,0.0f},{0.947661f,0.319279f,0.0f},{0.963556f,0.267507f,0.0f}, +{0.947653f,0.319301f,0.0f},{0.976624f,0.214954f,0.0f},{0.96355f,0.267528f,0.0f}, +{0.97662f,0.214973f,0.0f},{0.986829f,0.16177f,0.0f},{0.994139f,0.108111f,0.0f}, +{0.986826f,0.161786f,0.0f},{0.99855f,0.0538298f,0.0f},{0.994135f,0.108145f,0.0f}, +{0.998551f,0.0538045f,0.0f},{1.0f,1.19209e-007f,0.0f},{0.718391f,0.69564f,-2.2967e-015f}, +{0.747457f,0.66431f,4.30948e-015f},{0.747455f,0.664312f,-2.35972e-015f},{0.688012f,0.725699f,-2.11837e-015f}, +{0.688011f,0.7257f,-4.7761e-015f},{0.656377f,0.754433f,-3.42054e-015f},{0.775156f,0.631769f,1.02241e-015f}, +{0.718389f,0.695642f,1.63365e-016f},{0.775159f,0.631766f,1.30928e-015f},{0.801442f,0.598073f,-4.02386e-016f}, +{0.801444f,0.59807f,3.14782e-015f},{0.826266f,0.563281f,2.05014e-015f},{0.826264f,0.563284f,2.15457e-016f}, +{0.849576f,0.527466f,3.68245e-015f},{0.849578f,0.527463f,-9.04405e-017f},{0.871339f,0.490682f,2.82586e-015f}, +{0.891507f,0.453007f,-1.11336e-015f},{0.871337f,0.490685f,-3.98744e-016f},{0.891508f,0.453005f,8.87668e-016f}, +{0.91005f,0.414499f,3.62163e-016f},{0.910048f,0.414503f,-2.33213e-015f},{0.955579f,0.294734f,1.39294e-015f}, +{0.942115f,0.335291f,1.29026e-015f},{0.95558f,0.294731f,9.56661e-016f},{0.926927f,0.375241f,3.09815e-015f}, +{0.926928f,0.375238f,3.53892e-016f},{0.942114f,0.335293f,1.78659e-015f},{0.9673f,0.253636f,4.48455e-017f}, +{0.977253f,0.212075f,9.31315e-017f},{0.9673f,0.253634f,-3.87537e-015f},{0.977254f,0.212073f,1.53976e-015f}, +{0.985423f,0.170124f,-1.33727e-015f},{0.991791f,0.127866f,1.31222e-015f},{0.991791f,0.127868f,-1.43479e-015f}, +{0.985422f,0.170128f,-1.08544e-015f},{0.996349f,0.0853729f,-2.96511e-015f},{0.996349f,0.0853758f,1.45956e-015f}, +{0.999087f,0.0427249f,-1.45746e-015f},{0.999087f,0.0427275f,2.97938e-015f},{1.0f,1.41083e-016f,0.0f}, +{1.0f,1.54309e-016f,0.0f},{0.623543f,0.781789f,-8.12728e-016f},{0.656376f,0.754434f,-2.4015e-015f}, +{0.623541f,0.78179f,-9.35104e-016f},{0.589571f,0.807717f,-3.8494e-015f},{0.589569f,0.807718f,8.37214e-016f}, +{0.554522f,0.832169f,-3.65599e-015f},{0.51846f,0.855102f,-4.07623e-015f},{0.554519f,0.832171f,2.81113e-015f}, +{0.518456f,0.855104f,2.96789e-016f},{0.48145f,0.876473f,3.95802e-015f},{0.481448f,0.876475f,6.89284e-016f}, +{0.443562f,0.896244f,7.12651e-016f},{0.404864f,0.914377f,-1.93578e-015f},{0.443559f,0.896245f,5.43092e-015f}, +{0.40486f,0.914379f,-5.84661e-015f},{0.365425f,0.930841f,1.20115e-015f},{0.365423f,0.930842f,3.55128e-015f}, +{0.32532f,0.945604f,2.23888e-015f},{0.284621f,0.95864f,5.39664e-015f},{0.325317f,0.945605f,4.0151e-015f}, +{0.284618f,0.958641f,-2.22393e-015f},{0.243401f,0.969926f,4.33048e-015f},{0.243399f,0.969926f,4.23515e-015f}, +{0.201738f,0.97944f,4.2777e-015f},{0.159705f,0.987165f,5.95984e-015f},{0.201735f,0.97944f,6.68731e-016f}, +{0.159703f,0.987165f,-8.70338e-015f},{0.117381f,0.993087f,-6.76187e-015f},{0.117378f,0.993087f,7.13795e-015f}, +{0.0748434f,0.997195f,-4.49833e-016f},{0.0321679f,0.999482f,5.88869e-015f},{0.07484f,0.997196f,-1.11652e-015f}, +{0.0321656f,0.999483f,-2.74195e-016f},{-0.0105657f,0.999944f,5.2388e-015f},{-0.0105686f,0.999944f,-6.15843e-016f}, +{-0.05328f,0.99858f,7.92959e-015f},{-0.0958981f,0.995391f,0.0f},{-0.0532825f,0.99858f,4.50329e-015f}, +{0.0141122f,-0.9999f,0.0f},{-0.0141124f,-0.9999f,0.0f},{0.0141125f,-0.9999f,0.0f}, +{0.0423259f,-0.999104f,0.0f},{0.0423254f,-0.999104f,0.0f},{0.0705055f,-0.997511f,0.0f}, +{0.0705051f,-0.997511f,0.0f},{0.0986284f,-0.995124f,0.0f},{0.0986291f,-0.995124f,0.0f}, +{0.126674f,-0.991944f,0.0f},{0.126673f,-0.991944f,0.0f},{0.154618f,-0.987974f,0.0f}, +{0.154617f,-0.987974f,0.0f},{0.182438f,-0.983217f,0.0f},{0.182439f,-0.983217f,0.0f}, +{0.210114f,-0.977677f,0.0f},{0.210113f,-0.977677f,0.0f},{0.237622f,-0.971358f,0.0f}, +{0.237622f,-0.971358f,0.0f},{0.26494f,-0.964265f,0.0f},{0.264941f,-0.964265f,0.0f}, +{0.292049f,-0.956403f,0.0f},{0.292048f,-0.956404f,0.0f},{0.318924f,-0.94778f,0.0f}, +{0.318923f,-0.947781f,0.0f},{0.345544f,-0.938403f,0.0f},{0.345545f,-0.938402f,0.0f}, +{0.371891f,-0.928277f,0.0f},{0.37189f,-0.928277f,0.0f},{0.39794f,-0.917411f,0.0f}, +{0.397939f,-0.917412f,0.0f},{0.423672f,-0.905816f,0.0f},{0.423672f,-0.905815f,0.0f}, +{0.449067f,-0.893498f,0.0f},{0.449067f,-0.893498f,0.0f},{0.474105f,-0.880469f,0.0f}, +{0.474104f,-0.880469f,0.0f},{0.498763f,-0.866738f,0.0f},{0.498764f,-0.866738f,0.0f}, +{0.523026f,-0.852317f,0.0f},{-0.0141122f,-0.9999f,0.0f},{-0.0423254f,-0.999104f,0.0f}, +{-0.0423259f,-0.999104f,0.0f},{-0.0705055f,-0.997511f,0.0f},{-0.0705051f,-0.997511f,0.0f}, +{-0.0986291f,-0.995124f,0.0f},{-0.0986285f,-0.995124f,0.0f},{-0.126673f,-0.991944f,0.0f}, +{-0.126674f,-0.991944f,0.0f},{-0.154618f,-0.987974f,0.0f},{-0.154617f,-0.987974f,0.0f}, +{-0.182439f,-0.983217f,0.0f},{-0.182438f,-0.983217f,0.0f},{-0.210113f,-0.977677f,0.0f}, +{-0.210114f,-0.977677f,0.0f},{-0.237622f,-0.971358f,0.0f},{-0.237622f,-0.971358f,0.0f}, +{-0.264941f,-0.964265f,0.0f},{-0.26494f,-0.964265f,0.0f},{-0.292048f,-0.956404f,0.0f}, +{-0.292049f,-0.956403f,0.0f},{-0.318924f,-0.94778f,0.0f},{-0.318923f,-0.947781f,0.0f}, +{-0.345545f,-0.938402f,0.0f},{-0.345544f,-0.938403f,0.0f},{-0.37189f,-0.928277f,0.0f}, +{-0.371891f,-0.928277f,0.0f},{-0.39794f,-0.917411f,0.0f},{-0.397939f,-0.917412f,0.0f}, +{-0.423672f,-0.905815f,0.0f},{-0.423672f,-0.905816f,0.0f},{-0.449067f,-0.893498f,0.0f}, +{-0.449067f,-0.893498f,0.0f},{-0.474104f,-0.880469f,0.0f},{-0.474104f,-0.880469f,0.0f}, +{-0.498764f,-0.866738f,0.0f},{-0.498764f,-0.866738f,0.0f},{-0.523026f,-0.852317f,0.0f}, +{-0.866025f,-0.5f,-7.6671e-016f},{-0.466272f,-0.884642f,2.20644e-016f},{-0.628286f,-0.777982f,5.89571e-016f}, +{-0.628223f,-0.778033f,-5.53502e-016f},{-0.286781f,-0.957996f,1.48116e-016f},{-0.466199f,-0.88468f,-5.1317e-016f}, +{-0.286593f,-0.958053f,-1.63827e-016f},{0.0974696f,-0.995238f,3.44802e-016f},{-0.0962625f,-0.995356f,-1.06856e-016f}, +{0.097635f,-0.995222f,-4.56953e-017f},{-0.0964852f,-0.995334f,-1.31963e-016f},{-0.766564f,-0.642168f,0.0f}, +{-0.876095f,-0.482138f,-7.37654e-016f},{-0.76669f,-0.642017f,-1.10523e-015f},{-0.876203f,-0.481942f,7.37698e-016f}, +{-0.952689f,-0.303947f,0.0f},{-0.952739f,-0.303789f,0.0f},{-0.698102f,-0.715999f,1.29175e-016f}, +{-0.324434f,-0.945908f,-5.70109e-016f},{-0.324434f,-0.945908f,-3.35048e-016f},{-0.524032f,-0.851699f,7.27349e-016f}, +{-4.59243e-017f,1.0f,0.0f},{-4.12983e-017f,1.0f,0.0f},{0.173688f,0.984801f,0.0f}, +{0.342031f,0.939689f,0.0f},{0.173343f,0.984861f,0.0f},{0.341751f,0.939791f,0.0f}, +{0.499517f,0.866304f,0.0f},{0.642133f,0.766593f,0.0f},{0.50031f,0.865846f,0.0f}, +{0.64411f,0.764933f,0.0f},{0.765765f,0.64312f,0.0f},{0.766272f,0.642516f,0.0f}, +{0.865946f,0.500137f,0.0f},{0.939669f,0.342084f,0.0f},{0.866231f,0.499643f,0.0f}, +{0.939879f,0.341507f,0.0f},{0.984809f,0.173642f,0.0f},{0.984871f,0.173291f,0.0f}, +{-0.173688f,0.984801f,0.0f},{-0.342031f,0.939689f,0.0f},{-0.173343f,0.984861f,0.0f}, +{-0.499517f,0.866304f,0.0f},{-0.341751f,0.939791f,0.0f},{-0.50031f,0.865846f,0.0f}, +{-0.642133f,0.766593f,0.0f},{-0.64411f,0.764933f,0.0f},{-0.765765f,0.64312f,0.0f}, +{-0.865946f,0.500137f,0.0f},{-0.766272f,0.642516f,0.0f},{-0.866231f,0.499643f,0.0f}, +{-0.939669f,0.342084f,0.0f},{-0.939879f,0.341507f,0.0f},{-0.984809f,0.173642f,0.0f}, +{-0.984871f,0.173291f,0.0f},{-1.0f,7.40149e-017f,0.0f},{-1.0f,8.32667e-017f,0.0f}, +{0.130634f,0.991431f,0.0f},{0.258991f,0.96588f,0.0f},{0.130461f,0.991453f,0.0f}, +{0.382876f,0.9238f,0.0f},{0.258717f,0.965953f,0.0f},{0.382576f,0.923924f,0.0f}, +{0.500177f,0.865923f,0.0f},{0.608898f,0.793249f,0.0f},{0.499909f,0.866078f,0.0f}, +{0.707182f,0.707032f,0.0f},{0.608701f,0.7934f,0.0f},{0.70708f,0.707133f,0.0f}, +{0.793414f,0.608682f,0.0f},{0.866063f,0.499935f,0.0f},{0.793302f,0.608828f,0.0f}, +{0.923898f,0.38264f,0.0f},{0.865926f,0.500171f,0.0f},{0.965902f,0.258907f,0.0f}, +{0.923984f,0.382431f,0.0f},{0.966265f,0.257551f,0.0f},{0.991435f,0.130601f,0.0f}, +{0.99153f,0.129881f,0.0f},{1.0f,8.88178e-017f,0.0f},{-0.130634f,0.991431f,0.0f}, +{-0.258991f,0.96588f,0.0f},{-0.130461f,0.991453f,0.0f},{-0.258717f,0.965953f,0.0f}, +{-0.382876f,0.9238f,0.0f},{-0.500177f,0.865923f,0.0f},{-0.382576f,0.923924f,0.0f}, +{-0.608898f,0.793249f,0.0f},{-0.499909f,0.866078f,0.0f},{-0.608701f,0.7934f,0.0f}, +{-0.707182f,0.707032f,0.0f},{-0.793414f,0.608682f,0.0f},{-0.70708f,0.707134f,0.0f}, +{-0.866063f,0.499936f,0.0f},{-0.793302f,0.608828f,0.0f},{-0.865926f,0.500171f,0.0f}, +{-0.923898f,0.38264f,0.0f},{-0.965902f,0.258907f,0.0f},{-0.923984f,0.382431f,0.0f}, +{-0.966265f,0.257551f,0.0f},{-0.991435f,0.130601f,0.0f},{-0.99153f,0.129881f,0.0f}, +{0.913335f,0.40721f,7.99247e-017f},{0.808642f,0.588301f,3.74072e-017f},{0.809321f,0.587366f,1.2922e-016f}, +{0.913805f,0.406154f,-3.28816e-017f},{0.977984f,0.208678f,5.8208e-017f},{0.978488f,0.206306f,5.99861e-018f}, +{0.999999f,-0.00162857f,2.63678e-019f},{0.97822f,-0.207569f,-8.05697e-017f},{1.0f,0.000654662f,6.93738e-017f}, +{0.977876f,-0.209184f,1.45735e-017f},{0.913594f,-0.406629f,-1.15091e-016f},{0.913137f,-0.407652f,-4.53528e-017f}, +{0.809021f,-0.58778f,2.29704e-017f},{0.80856f,-0.588414f,1.22753e-016f},{0.669069f,-0.7432f,-6.9929e-017f}, +{0.668748f,-0.743489f,-3.64576e-017f},{0.669713f,0.74262f,-6.87062e-017f},{0.500567f,0.865698f,-4.63117e-017f}, +{0.66791f,0.744242f,7.06215e-018f},{0.498589f,0.866839f,1.14269e-016f},{0.30935f,0.950948f,-5.56503e-016f}, +{0.30778f,0.951458f,-4.71214e-016f},{0.104646f,0.99451f,-2.03385e-016f},{-0.104522f,0.994523f,-3.87388e-016f}, +{0.103531f,0.994626f,-1.84043e-016f},{-0.105302f,0.99444f,1.94848e-017f},{-0.309096f,0.951031f,0.0f}, +{-0.309506f,0.950897f,-5.72701e-017f},{0.900926f,0.433972f,8.6404e-017f},{0.826202f,0.563374f,-2.43165e-017f}, +{0.826294f,0.563239f,2.43374e-017f},{0.955531f,0.294892f,6.11214e-017f},{0.900997f,0.433825f,-3.70517e-017f}, +{0.955592f,0.294693f,-3.87521e-016f},{0.988805f,0.149217f,6.64494e-017f},{0.988837f,0.149001f,-2.17435e-016f}, +{1.0f,1.20654e-005f,-2.79068e-022f},{1.0f,0.000192253f,1.7787e-020f},{0.988875f,-0.148747f,1.44115e-016f}, +{0.900667f,-0.43451f,4.63232e-017f},{0.826465f,-0.562987f,2.00756e-016f},{0.901106f,-0.4336f,5.63359e-017f}, +{0.988831f,-0.14904f,-1.04015e-016f},{0.955631f,-0.294565f,-1.19073e-016f},{0.95558f,-0.294731f,1.85876e-017f}, +{0.825308f,-0.564682f,7.07051e-017f},{0.733215f,-0.679997f,6.20149e-017f},{0.733055f,-0.68017f,8.707e-017f}, +{0.623408f,-0.781897f,1.16904e-016f},{0.623556f,-0.781778f,-3.96622e-018f},{0.733149f,0.680068f,2.61498e-016f}, +{0.623627f,0.781722f,-1.73901e-016f},{0.733007f,0.680221f,-2.51732e-016f},{0.623458f,0.781857f,-4.04708e-016f}, +{0.500166f,0.865929f,9.25494e-017f},{0.500011f,0.866019f,-9.25205e-017f},{0.365619f,0.930764f,-6.76531e-017f}, +{0.222715f,0.974884f,0.0f},{0.365343f,0.930873f,-3.0745e-016f},{0.222546f,0.974922f,-3.60794e-016f}, +{0.0750445f,0.99718f,1.84515e-016f},{0.0740373f,0.997255f,0.0f},{-0.0743287f,0.997234f,0.0f}, +{-0.222287f,0.974981f,-4.43078e-016f},{-0.0763749f,0.997079f,2.82644e-017f},{-0.222517f,0.974929f,8.23479e-017f}, +{-0.365262f,0.930905f,-3.44504e-016f},{-0.365439f,0.930835f,0.0f},{0.809321f,-0.587366f,1.2922e-016f}, +{0.913805f,-0.406154f,8.45439e-017f},{0.913335f,-0.40721f,-7.99247e-017f},{0.808642f,-0.588301f,2.03856e-017f}, +{0.669713f,-0.74262f,8.75691e-017f},{0.66791f,-0.744242f,1.34181e-016f},{0.498589f,-0.866839f,2.64187e-016f}, +{0.30935f,-0.950948f,-3.88237e-017f},{0.500567f,-0.865698f,3.37814e-017f},{0.30778f,-0.951458f,4.53145e-017f}, +{0.104646f,-0.99451f,7.86897e-017f},{0.103531f,-0.994626f,8.15879e-017f},{-0.104522f,-0.994523f,4.82678e-017f}, +{-0.105302f,-0.99444f,-1.17707e-017f},{-0.309096f,-0.951031f,-6.56523e-017f},{-0.309506f,-0.950897f,3.18526e-017f}, +{0.977984f,-0.208678f,1.93066e-017f},{1.0f,-0.000654662f,0.0f},{0.978488f,-0.206306f,2.00144e-016f}, +{0.999999f,0.00162868f,-1.85338e-016f},{0.97822f,0.207569f,-7.6816e-017f},{0.977876f,0.209183f,-1.29178e-016f}, +{0.913594f,0.406629f,-7.52414e-017f},{0.809021f,0.58778f,1.49699e-016f},{0.913137f,0.407652f,2.44395e-016f}, +{0.80856f,0.588414f,3.67371e-016f},{0.669069f,0.7432f,2.75039e-016f},{0.668748f,0.743489f,-2.75146e-016f}, +{0.826294f,-0.563239f,6.1666e-017f},{0.900997f,-0.433825f,3.08521e-018f},{0.900926f,-0.433972f,-5.64113e-017f}, +{0.733149f,-0.680068f,-2.56587e-016f},{0.826202f,-0.563374f,-1.46813e-016f},{0.733007f,-0.680221f,1.63368e-016f}, +{0.623628f,-0.781722f,-7.95359e-017f},{0.623458f,-0.781857f,-7.21018e-018f},{0.50001f,-0.866019f,1.15651e-017f}, +{0.500166f,-0.865929f,1.23064e-016f},{0.365619f,-0.930764f,1.23884e-016f},{0.0740373f,-0.997256f,1.28434e-018f}, +{-0.0743287f,-0.997234f,-3.03579e-016f},{0.0750446f,-0.99718f,-2.99946e-016f},{0.365343f,-0.930873f,5.04555e-017f}, +{0.222715f,-0.974884f,4.70292e-017f},{0.222546f,-0.974922f,3.93084e-017f},{-0.0763749f,-0.997079f,-3.81629e-016f}, +{-0.222287f,-0.974981f,-8.52052e-017f},{-0.222517f,-0.974929f,8.99959e-017f},{-0.365439f,-0.930835f,-2.28984e-016f}, +{-0.365262f,-0.930905f,2.02233e-016f},{0.955531f,-0.294892f,-6.63033e-017f},{0.988805f,-0.149216f,9.47978e-018f}, +{0.955592f,-0.294693f,-1.98923e-016f},{0.988837f,-0.149002f,-1.41928e-016f},{1.0f,-0.000192142f,-2.31296e-017f}, +{1.0f,-1.21766e-005f,-2.31342e-017f},{0.988875f,0.148747f,1.00792e-016f},{0.955631f,0.294565f,1.09011e-016f}, +{0.988831f,0.14904f,5.5156e-017f},{0.95558f,0.294731f,6.48678e-017f},{0.901106f,0.4336f,0.0f}, +{0.900667f,0.43451f,0.0f},{0.826465f,0.562987f,-2.46579e-016f},{0.733215f,0.679997f,-2.85567e-016f}, +{0.825308f,0.564682f,3.81782e-017f},{0.733055f,0.68017f,3.19535e-016f},{0.623556f,0.781778f,2.88453e-017f}, +{0.623408f,0.781897f,0.0f},{-0.104013f,-0.994576f,-5.73969e-018f},{0.105163f,-0.994455f,-5.04765e-018f}, +{0.104013f,-0.994576f,-5.37603e-017f},{-0.105163f,-0.994455f,-2.56228e-017f},{-0.308272f,-0.951298f,-1.34015e-017f}, +{-0.310578f,-0.950548f,7.65272e-018f},{-0.50141f,-0.86521f,-4.26767e-017f},{-0.66887f,-0.743379f,-1.02395e-016f}, +{-0.499433f,-0.866353f,-6.51189e-017f},{-0.670096f,-0.742274f,-1.6733e-017f},{-0.808947f,-0.587881f,-4.74286e-017f}, +{-0.809606f,-0.586974f,-1.22396e-016f},{-0.913543f,-0.406743f,1.98726e-016f},{-0.913862f,-0.406026f,6.87164e-017f}, +{-0.978165f,-0.20783f,2.25061e-016f},{-0.978254f,-0.207408f,-6.67845e-017f},{-1.0f,2.22045e-016f,0.0f}, +{0.308272f,-0.951298f,-2.63823e-017f},{0.499433f,-0.866353f,-1.48319e-016f},{0.310578f,-0.950548f,8.91888e-017f}, +{0.50141f,-0.86521f,1.30238e-016f},{0.66887f,-0.743379f,-2.55902e-017f},{0.670096f,-0.742274f,9.43118e-018f}, +{0.808947f,-0.587881f,-2.24438e-017f},{0.913543f,-0.406743f,2.2274e-018f},{0.809606f,-0.586974f,-2.2055e-017f}, +{0.913862f,-0.406026f,2.39531e-018f},{0.978165f,-0.20783f,5.02738e-019f},{0.978254f,-0.207408f,-3.61477e-016f}, +{1.0f,-9.4369e-016f,0.0f},{1.0f,-4.44089e-016f,0.0f},{-0.0746326f,-0.997211f,3.23205e-017f}, +{0.074795f,-0.997199f,-1.38399e-017f},{0.0746326f,-0.997211f,-5.99401e-017f},{-0.222381f,-0.97496f,0.0f}, +{-0.074795f,-0.997199f,-4.61297e-017f},{-0.222585f,-0.974913f,4.11864e-017f},{-0.365177f,-0.930938f,-9.83825e-017f}, +{-0.365379f,-0.930859f,1.2274e-017f},{-0.49999f,-0.866031f,-4.93565e-017f},{-0.499833f,-0.866122f,-4.3155e-017f}, +{-0.623256f,-0.782018f,1.09954e-016f},{-0.82663f,-0.562746f,3.25403e-018f},{-0.900794f,-0.434246f,1.50224e-016f}, +{-0.826061f,-0.563581f,1.56111e-016f},{-0.623488f,-0.781833f,4.15463e-017f},{-0.732917f,-0.680318f,6.65918e-017f}, +{-0.733034f,-0.680192f,2.58522e-016f},{-0.901683f,-0.432397f,-2.442e-016f},{-0.955502f,-0.294984f,1.58495e-016f}, +{-0.955572f,-0.294759f,-5.2973e-017f},{-0.988846f,-0.148938f,8.9777e-017f},{-0.988818f,-0.149126f,7.06523e-017f}, +{-1.0f,1.11022e-016f,0.0f},{0.222381f,-0.97496f,-4.11488e-017f},{0.365177f,-0.930938f,-6.75713e-017f}, +{0.222585f,-0.974913f,-8.23729e-017f},{0.365379f,-0.930859f,-6.76088e-017f},{0.499834f,-0.866121f,1.7262e-016f}, +{0.499989f,-0.866031f,-8.0124e-017f},{0.623256f,-0.782018f,0.0f},{0.732917f,-0.680318f,0.0f}, +{0.623488f,-0.781833f,0.0f},{0.733034f,-0.680192f,-2.71277e-016f},{0.826061f,-0.563581f,0.0f}, +{0.82663f,-0.562746f,-1.04129e-016f},{0.900794f,-0.434246f,3.33361e-016f},{0.955502f,-0.294984f,0.0f}, +{0.901683f,-0.432397f,0.0f},{0.955572f,-0.294759f,5.45414e-017f},{0.988818f,-0.149126f,0.0f}, +{0.988846f,-0.148938f,2.75591e-017f},{1.0f,-4.996e-016f,0.0f},{1.0f,-6.66134e-016f,0.0f}, +{-0.913335f,-0.40721f,-4.22502e-017f},{-0.808642f,-0.588301f,-1.70216e-017f},{-0.809321f,-0.587366f,-2.37904e-016f}, +{-0.913805f,-0.406154f,-3.28816e-017f},{-0.977984f,-0.208678f,-4.85547e-017f},{-0.978488f,-0.206306f,5.48077e-017f}, +{-0.999999f,0.00162857f,4.59202e-017f},{-0.97822f,0.207569f,6.16976e-017f},{-1.0f,-0.000654662f,-1.21137e-019f}, +{-0.977876f,0.209184f,-1.1309e-017f},{-0.913594f,0.406629f,-1.82302e-017f},{-0.913137f,0.407652f,-6.61902e-017f}, +{-0.809021f,0.58778f,3.39878e-018f},{-0.80856f,0.588414f,-4.63496e-017f},{-0.669069f,0.7432f,-3.99078e-017f}, +{-0.668748f,0.743489f,-1.35216e-017f},{-0.669713f,-0.74262f,1.44158e-016f},{-0.500567f,-0.865698f,1.60186e-016f}, +{-0.66791f,-0.744242f,1.44775e-016f},{-0.498589f,-0.866839f,-1.14269e-016f},{-0.30935f,-0.950948f,-2.04581e-016f}, +{-0.30778f,-0.951458f,0.0f},{-0.104646f,-0.99451f,-1.84021e-016f},{0.104522f,-0.994523f,-3.87388e-016f}, +{-0.103531f,-0.994626f,3.68086e-016f},{0.105302f,-0.99444f,-3.68017e-016f},{0.309096f,-0.951031f,0.0f}, +{0.309506f,-0.950897f,-4.09173e-016f},{-0.900926f,-0.433972f,-8.03009e-017f},{-0.826202f,-0.563374f,2.29317e-016f}, +{-0.826294f,-0.563239f,5.21101e-017f},{-0.955531f,-0.294892f,6.76768e-017f},{-0.900997f,-0.433825f,-2.43906e-016f}, +{-0.955592f,-0.294693f,-1.2269e-016f},{-0.988805f,-0.149217f,-6.90265e-018f},{-0.988837f,-0.149001f,1.19057e-016f}, +{-1.0f,-1.20654e-005f,4.62596e-017f},{-1.0f,-0.000192253f,9.25097e-017f},{-0.988875f,0.148747f,1.64758e-016f}, +{-0.900667f,0.43451f,-2.6511e-016f},{-0.826465f,0.562987f,-1.78554e-016f},{-0.901106f,0.4336f,8.0232e-017f}, +{-0.988831f,0.14904f,9.49325e-017f},{-0.955631f,0.294565f,-1.18836e-017f},{-0.95558f,0.294731f,1.83741e-016f}, +{-0.825308f,0.564682f,1.30735e-016f},{-0.733215f,0.679997f,-5.59715e-017f},{-0.733055f,0.68017f,3.51996e-017f}, +{-0.623408f,0.781897f,1.10427e-016f},{-0.623556f,0.781778f,-6.84852e-018f},{-0.733149f,-0.680068f,-1.16016e-016f}, +{-0.623627f,-0.781722f,-2.89295e-016f},{-0.733007f,-0.680221f,0.0f},{-0.623458f,-0.781857f,2.30726e-016f}, +{-0.500166f,-0.865929f,-1.85099e-016f},{-0.500011f,-0.866019f,-9.25205e-017f},{-0.365619f,-0.930764f,-5.16678e-016f}, +{-0.222715f,-0.974884f,1.8039e-016f},{-0.365343f,-0.930873f,-6.7602e-017f},{-0.222546f,-0.974922f,-3.60794e-016f}, +{-0.0750445f,-0.99718f,3.96803e-016f},{-0.0740373f,-0.997255f,0.0f},{0.0743287f,-0.997234f,0.0f}, +{0.222287f,-0.974981f,-8.22628e-017f},{0.0763749f,-0.997079f,0.0f},{0.222517f,-0.974929f,-3.60796e-016f}, +{0.365262f,-0.930905f,-3.44504e-016f},{0.365439f,-0.930835f,0.0f},{-0.809321f,0.587366f,-1.63027e-016f}, +{-0.913805f,0.406154f,2.48937e-016f},{-0.913335f,0.40721f,9.15149e-018f},{-0.808642f,0.588301f,3.40432e-017f}, +{-0.669713f,0.74262f,1.58275e-016f},{-0.66791f,0.744242f,-1.89796e-017f},{-0.498589f,0.866839f,-9.04411e-018f}, +{-0.30935f,0.950948f,1.30911e-016f},{-0.500567f,0.865698f,-4.94443e-017f},{-0.30778f,0.951458f,2.91257e-017f}, +{-0.104646f,0.99451f,1.16829e-016f},{-0.103531f,0.994626f,-6.18321e-017f},{0.104522f,0.994523f,3.11622e-017f}, +{0.105302f,0.99444f,2.24587e-017f},{0.309096f,0.951031f,-1.31801e-016f},{0.309506f,0.950897f,3.8811e-017f}, +{-0.977984f,0.208678f,-9.04817e-017f},{-1.0f,0.000654662f,-1.21137e-019f},{-0.978488f,0.206306f,5.2354e-017f}, +{-0.999999f,-0.00162868f,-1.85338e-016f},{-0.97822f,-0.207569f,-9.05036e-017f},{-0.977876f,-0.209183f,-5.1765e-017f}, +{-0.913594f,-0.406629f,-7.52414e-017f},{-0.809021f,-0.58778f,-1.49699e-016f},{-0.913137f,-0.407652f,7.54309e-017f}, +{-0.80856f,-0.588414f,1.49614e-016f},{-0.669069f,-0.7432f,3.98842e-016f},{-0.668748f,-0.743489f,0.0f}, +{-0.826294f,0.563239f,-1.23332e-016f},{-0.900997f,0.433825f,6.25192e-017f},{-0.900926f,0.433972f,-6.10305e-018f}, +{-0.733149f,0.680068f,1.0888e-016f},{-0.826202f,0.563374f,3.30128e-017f},{-0.733007f,0.680221f,2.90247e-017f}, +{-0.623628f,0.781722f,2.82083e-016f},{-0.623458f,0.781857f,3.62854e-017f},{-0.50001f,0.866019f,2.14764e-016f}, +{-0.500166f,0.865929f,-6.03025e-017f},{-0.365619f,0.930764f,5.46844e-017f},{-0.0740373f,0.997256f,-1.62533e-016f}, +{0.0743287f,0.997234f,-1.15704e-016f},{-0.0750446f,0.99718f,2.87654e-016f},{-0.365343f,0.930873f,-1.82809e-016f}, +{-0.222715f,0.974884f,-6.76461e-017f},{-0.222546f,0.974922f,2.62874e-016f},{0.0763749f,0.997079f,-2.1338e-016f}, +{0.222287f,0.974981f,-2.68797e-016f},{0.222517f,0.974929f,-7.60189e-017f},{0.365439f,0.930835f,-1.46759e-016f}, +{0.365262f,0.930905f,2.96533e-016f},{-0.955531f,0.294892f,7.66671e-017f},{-0.988805f,0.149216f,6.38722e-017f}, +{-0.955592f,0.294693f,-1.10513e-016f},{-0.988837f,0.149002f,2.28714e-017f},{-1.0f,0.000192142f,0.0f}, +{-1.0f,1.21766e-005f,2.31342e-017f},{-0.988875f,-0.148747f,-4.57447e-017f},{-0.955631f,-0.294565f,1.53218e-016f}, +{-0.988831f,-0.14904f,0.0f},{-0.95558f,-0.294731f,0.0f},{-0.901106f,-0.4336f,-8.3369e-017f}, +{-0.900667f,-0.43451f,4.16642e-017f},{-0.826465f,-0.562987f,-3.82317e-017f},{-0.733215f,-0.679997f,0.0f}, +{-0.825308f,-0.564682f,-1.70796e-016f},{-0.733055f,-0.68017f,-6.78212e-017f},{-0.623556f,-0.781778f,-2.88453e-017f}, +{-0.623408f,-0.781897f,-2.88384e-017f},{0.104013f,0.994576f,7.26654e-018f},{-0.105163f,0.994455f,-2.43825e-017f}, +{-0.104013f,0.994576f,8.93001e-017f},{0.105163f,0.994455f,1.32311e-017f},{0.308272f,0.951298f,-7.55182e-017f}, +{0.310578f,0.950548f,-4.45961e-018f},{0.50141f,0.86521f,-6.50915e-017f},{0.66887f,0.743379f,1.15799e-016f}, +{0.499433f,0.866353f,-4.79524e-017f},{0.670096f,0.742274f,-6.82852e-017f},{0.808947f,0.587881f,-6.27019e-017f}, +{0.809606f,0.586974f,-1.8867e-016f},{0.913543f,0.406743f,2.68879e-016f},{0.913862f,0.406026f,5.33518e-018f}, +{0.978165f,0.20783f,-6.04996e-017f},{0.978254f,0.207408f,1.68043e-016f},{1.0f,2.498e-016f,0.0f}, +{-0.308272f,0.951298f,-7.04878e-018f},{-0.499433f,0.866353f,6.84015e-018f},{-0.310578f,0.950548f,5.99884e-018f}, +{-0.50141f,0.86521f,6.84674e-018f},{-0.66887f,0.743379f,7.13059e-018f},{-0.670096f,0.742274f,1.31123e-016f}, +{-0.808947f,0.587881f,6.66802e-018f},{-0.913543f,0.406743f,-3.42154e-016f},{-0.809606f,0.586974f,2.02398e-017f}, +{-0.913862f,0.406026f,-4.06525e-018f},{-0.978165f,0.20783f,6.87323e-019f},{-0.978254f,0.207408f,-3.6134e-016f}, +{-1.0f,-3.88578e-016f,0.0f},{-1.0f,4.44089e-016f,0.0f},{0.0746326f,0.997211f,-1.85107e-017f}, +{-0.074795f,0.997199f,-2.76797e-017f},{-0.0746326f,0.997211f,-4.61303e-017f},{0.222381f,0.97496f,-1.06824e-016f}, +{0.074795f,0.997199f,4.61297e-017f},{0.222585f,0.974913f,-2.05932e-017f},{0.365177f,0.930938f,3.37857e-017f}, +{0.365379f,0.930859f,-6.76088e-017f},{0.49999f,0.866031f,-1.32579e-016f},{0.499833f,0.866122f,1.49498e-016f}, +{0.623256f,0.782018f,-1.46129e-016f},{0.82663f,0.562746f,-2.18847e-016f},{0.900794f,0.434246f,8.55296e-017f}, +{0.826061f,0.563581f,1.43299e-016f},{0.623488f,0.781833f,2.1746e-017f},{0.732917f,0.680318f,-1.16232e-016f}, +{0.733034f,0.680192f,2.20413e-016f},{0.901683f,0.432397f,-2.49017e-016f},{0.955502f,0.294984f,-5.72353e-017f}, +{0.955572f,0.294759f,-1.44419e-016f},{0.988846f,0.148938f,-1.64846e-016f},{1.0f,-1.11022e-016f,0.0f}, +{0.988818f,0.149126f,-1.13952e-016f},{1.0f,-2.35922e-016f,0.0f},{-0.222381f,0.97496f,0.0f}, +{-0.365177f,0.930938f,-6.75713e-017f},{-0.222585f,0.974913f,-4.90112e-017f},{-0.365379f,0.930859f,6.76088e-017f}, +{-0.499834f,0.866121f,-1.04843e-016f},{-0.499989f,0.866031f,0.0f},{-0.623256f,0.782018f,2.30651e-016f}, +{-0.732917f,0.680318f,-3.97118e-016f},{-0.623488f,0.781833f,-7.23341e-017f},{-0.733034f,0.680192f,0.0f}, +{-0.826061f,0.563581f,0.0f},{-0.82663f,0.562746f,2.01786e-016f},{-0.900794f,0.434246f,-4.13713e-016f}, +{-0.955502f,0.294984f,-3.53607e-016f},{-0.901683f,0.432397f,0.0f},{-0.955572f,0.294759f,-3.53633e-016f}, +{-0.988818f,0.149126f,-3.65936e-016f},{-0.988846f,0.148938f,2.75591e-017f},{-1.0f,-2.498e-016f,0.0f}, +{4.59243e-017f,1.0f,0.0f},{4.12983e-017f,1.0f,0.0f},{-0.173688f,0.984801f,0.0f}, +{-0.342031f,0.939689f,0.0f},{-0.173343f,0.984861f,0.0f},{-0.341751f,0.939791f,0.0f}, +{-0.499517f,0.866304f,0.0f},{-0.642133f,0.766593f,0.0f},{-0.50031f,0.865846f,0.0f}, +{-0.765765f,0.64312f,0.0f},{-0.766272f,0.642516f,0.0f},{-0.865946f,0.500137f,0.0f}, +{-0.939669f,0.342084f,0.0f},{-0.866231f,0.499643f,0.0f},{-0.939879f,0.341507f,0.0f}, +{-0.984809f,0.173642f,0.0f},{-0.984871f,0.173291f,0.0f},{0.173688f,0.984801f,0.0f}, +{0.342031f,0.939689f,0.0f},{0.173343f,0.984861f,0.0f},{0.499517f,0.866304f,0.0f}, +{0.341751f,0.939791f,0.0f},{0.50031f,0.865846f,0.0f},{0.642133f,0.766593f,0.0f}, +{0.765765f,0.64312f,0.0f},{0.865946f,0.500137f,0.0f},{0.766272f,0.642516f,0.0f}, +{0.866231f,0.499643f,0.0f},{0.939669f,0.342084f,0.0f},{0.939879f,0.341507f,0.0f}, +{0.984809f,0.173642f,0.0f},{0.984871f,0.173291f,0.0f},{1.0f,8.32667e-017f,0.0f}, +{4.24548e-017f,1.0f,0.0f},{-0.0981573f,0.995171f,0.0f},{-0.0979559f,0.995191f,0.0f}, +{-0.195278f,0.980748f,0.0f},{-0.290455f,0.956889f,0.0f},{-0.194999f,0.980803f,0.0f}, +{-0.382807f,0.923829f,0.0f},{-0.290209f,0.956963f,0.0f},{-0.382668f,0.923886f,0.0f}, +{-0.471474f,0.88188f,0.0f},{-0.555711f,0.831376f,0.0f},{-0.471468f,0.881883f,0.0f}, +{-0.634547f,0.772884f,0.0f},{-0.555621f,0.831435f,0.0f},{-0.634433f,0.772978f,0.0f}, +{-0.707246f,0.706968f,0.0f},{-0.773125f,0.634253f,0.0f},{-0.707144f,0.70707f,0.0f}, +{-0.83156f,0.555435f,0.0f},{-0.773048f,0.634347f,0.0f},{-0.831507f,0.555514f,0.0f}, +{-0.881988f,0.471271f,0.0f},{-0.923925f,0.382573f,0.0f},{-0.881956f,0.471332f,0.0f}, +{-0.956966f,0.290201f,0.0f},{-0.923909f,0.382613f,0.0f},{-0.956961f,0.290216f,0.0f}, +{-0.980794f,0.195045f,0.0f},{-0.995188f,0.0979878f,0.0f},{-0.980794f,0.195048f,0.0f}, +{-1.0f,5.55112e-017f,0.0f},{-0.995188f,0.0979889f,0.0f},{0.0981573f,0.995171f,0.0f}, +{0.195278f,0.980748f,0.0f},{0.0979559f,0.995191f,0.0f},{0.290455f,0.956889f,0.0f}, +{0.194999f,0.980803f,0.0f},{0.290209f,0.956963f,0.0f},{0.382806f,0.923829f,0.0f}, +{0.471474f,0.88188f,0.0f},{0.382668f,0.923886f,0.0f},{0.555711f,0.831376f,0.0f}, +{0.471468f,0.881883f,0.0f},{0.555621f,0.831435f,0.0f},{0.634547f,0.772884f,0.0f}, +{0.707246f,0.706968f,0.0f},{0.634433f,0.772978f,0.0f},{0.773125f,0.634253f,0.0f}, +{0.707144f,0.70707f,0.0f},{0.773048f,0.634347f,0.0f},{0.83156f,0.555435f,0.0f}, +{0.881988f,0.471271f,0.0f},{0.831507f,0.555514f,0.0f},{0.923925f,0.382573f,0.0f}, +{0.881956f,0.471332f,0.0f},{0.923909f,0.382613f,0.0f},{0.956966f,0.290201f,0.0f}, +{0.980794f,0.195045f,0.0f},{0.956961f,0.290216f,0.0f},{0.995188f,0.0979878f,0.0f}, +{0.980794f,0.195048f,0.0f},{0.995188f,0.0979889f,0.0f},{1.0f,4.00033e-013f,0.0f}, +{0.991431f,-0.130634f,-1.5026e-016f},{0.991453f,-0.130461f,6.85852e-017f},{1.0f,1.04594e-016f,-3.83638e-017f}, +{0.991431f,0.130634f,-3.21402e-016f},{0.991453f,0.130461f,-2.89173e-016f},{1.0f,1.11699e-016f,-3.83638e-017f}, +{0.923924f,0.382576f,2.83996e-016f},{0.9238f,0.382876f,8.53933e-017f},{0.866078f,0.499909f,2.08963e-017f}, +{0.96588f,0.258991f,-8.55181e-017f},{0.965953f,0.258717f,-5.34314e-017f},{0.865923f,0.500177f,-5.73979e-017f}, +{0.793249f,0.608898f,1.92916e-016f},{0.7934f,0.608701f,4.93259e-016f},{0.707134f,0.70708f,4.70843e-017f}, +{0.707032f,0.707182f,-1.83528e-017f},{0.608682f,0.793414f,1.24226e-016f},{0.608828f,0.793302f,-1.11741e-017f}, +{0.500171f,0.865926f,1.14799e-016f},{0.499936f,0.866063f,-2.19067e-016f},{0.382431f,0.923984f,1.50382e-016f}, +{0.38264f,0.923898f,2.91616e-016f},{0.257551f,0.966265f,2.03303e-016f},{0.258907f,0.965902f,-1.91601e-016f}, +{-1.77636e-016f,1.0f,0.0f},{0.130601f,0.991435f,-1.66716e-016f},{0.129881f,0.99153f,1.2663e-016f}, +{0.965953f,-0.258717f,-3.26128e-016f},{0.96588f,-0.258991f,1.67594e-016f},{0.923924f,-0.382575f,3.19072e-016f}, +{0.866078f,-0.499909f,5.5648e-017f},{0.9238f,-0.382876f,5.08067e-016f},{0.865923f,-0.500177f,-5.77672e-016f}, +{0.7934f,-0.608701f,3.62925e-016f},{0.793249f,-0.608898f,3.6309e-016f},{0.707134f,-0.70708f,2.68425e-016f}, +{0.608828f,-0.793302f,-3.58676e-017f},{0.707032f,-0.707182f,-8.0417e-017f},{0.608682f,-0.793414f,-3.58121e-017f}, +{0.500171f,-0.865926f,-3.26581e-017f},{0.499936f,-0.866063f,8.52937e-016f},{0.382431f,-0.923984f,1.98887e-017f}, +{0.258907f,-0.965902f,-4.21509e-018f},{0.38264f,-0.923897f,-3.73789e-018f},{0.257551f,-0.966265f,-4.04087e-018f}, +{0.130601f,-0.991435f,1.01608e-018f},{0.129881f,-0.99153f,1.04991e-018f},{-3.9968e-016f,-1.0f,0.0f}, +{-3.55271e-016f,-1.0f,0.0f},{0.130634f,0.991431f,2.24771e-017f},{-6.81879e-017f,1.0f,-3.5727e-016f}, +{0.130461f,0.991453f,4.82088e-017f},{-0.130634f,0.991431f,-8.9037e-017f},{-2.8908e-017f,1.0f,-3.5727e-016f}, +{-0.130461f,0.991453f,-1.21252e-016f},{-0.382576f,0.923924f,-2.393e-016f},{-0.499909f,0.866078f,-4.33042e-017f}, +{-0.382876f,0.9238f,-9.77137e-017f},{-0.258991f,0.96588f,2.71446e-017f},{-0.258717f,0.965953f,-4.91388e-018f}, +{-0.500177f,0.865923f,3.49703e-017f},{-0.608701f,0.7934f,-4.24266e-016f},{-0.608898f,0.793249f,-1.2395e-016f}, +{-0.70708f,0.707134f,-3.52173e-017f},{-0.707182f,0.707032f,7.38213e-017f},{-0.793302f,0.608828f,3.61888e-017f}, +{-0.793414f,0.608682f,-9.92222e-017f},{-0.865926f,0.500171f,-1.27451e-016f},{-0.923984f,0.382431f,-1.43542e-016f}, +{-0.866063f,0.499936f,2.37252e-016f},{-0.923898f,0.38264f,-2.84771e-016f},{-0.965902f,0.258907f,1.93798e-016f}, +{-0.966265f,0.257551f,-2.0112e-016f},{-1.0f,-1.77636e-016f,0.0f},{-0.99153f,0.129881f,-1.26366e-016f}, +{-0.991435f,0.130601f,1.66981e-016f},{0.258717f,0.965953f,5.79845e-016f},{0.382575f,0.923924f,5.8645e-017f}, +{0.258991f,0.96588f,8.61504e-017f},{0.499909f,0.866078f,-1.08244e-016f},{0.382876f,0.9238f,-1.30347e-016f}, +{0.500177f,0.865923f,7.38772e-016f},{0.608701f,0.7934f,-1.95732e-016f},{0.70708f,0.707134f,-3.63162e-016f}, +{0.608898f,0.793249f,-1.95892e-016f},{0.793302f,0.608828f,-3.00139e-017f},{0.707182f,0.707032f,7.29313e-017f}, +{0.793414f,0.608682f,-3.00317e-017f},{0.865926f,0.500171f,-8.48302e-018f},{0.923984f,0.382431f,5.81523e-018f}, +{0.866063f,0.499936f,-8.32361e-016f},{0.965902f,0.258907f,-3.62871e-018f},{0.923897f,0.38264f,5.83784e-018f}, +{0.966265f,0.257551f,-3.69043e-018f},{0.991435f,0.130601f,-1.6072e-018f},{1.0f,-3.9968e-016f,0.0f}, +{0.99153f,0.129881f,-1.61926e-018f},{1.0f,-3.55271e-016f,0.0f},{-0.991453f,0.130461f,-1.07072e-016f}, +{-1.0f,-1.34854e-016f,-1.10604e-016f},{-0.997004f,0.0773514f,-4.85361e-018f},{-0.984529f,-0.17522f,8.76624e-017f}, +{-0.998781f,-0.0493566f,-2.22428e-016f},{-0.991431f,-0.130634f,-2.6656e-016f},{-0.9238f,-0.382876f,3.55937e-016f}, +{-0.865923f,-0.500177f,4.04041e-018f},{-0.909095f,-0.416588f,2.40191e-017f},{-0.954476f,-0.298289f,8.81846e-017f}, +{-0.96588f,-0.258991f,2.25831e-017f},{-0.793249f,-0.608898f,2.61332e-018f},{-0.775518f,-0.631325f,1.12436e-017f}, +{-0.849113f,-0.528211f,-2.89297e-017f},{-0.707032f,-0.707182f,2.19638e-016f},{-0.608682f,-0.793414f,3.18903e-016f}, +{-0.592379f,-0.805659f,7.30288e-018f},{-0.689484f,-0.724301f,-1.76238e-016f},{-0.499936f,-0.866063f,6.507e-017f}, +{-0.38264f,-0.923898f,2.20941e-016f},{-0.485846f,-0.874044f,2.27593e-017f},{-0.257551f,-0.966265f,1.69139e-016f}, +{-0.250953f,-0.967999f,3.56251e-016f},{-0.370923f,-0.928664f,-1.56513e-017f},{-0.126499f,-0.991967f,2.38761e-016f}, +{-0.129881f,-0.99153f,1.18458e-016f},{1.77636e-016f,-1.0f,0.0f},{-0.979208f,0.202861f,-5.41817e-017f}, +{-0.945695f,0.325055f,-2.584e-016f},{-0.965953f,0.258717f,-1.0161e-016f},{-0.923924f,0.382575f,-9.44417e-017f}, +{-0.897003f,0.442024f,5.64015e-016f},{-0.833912f,0.551898f,-3.53721e-016f},{-0.866078f,0.499909f,2.10067e-017f}, +{-0.757439f,0.652906f,3.44065e-016f},{-0.7934f,0.608701f,3.22157e-016f},{-0.707134f,0.70708f,2.17729e-017f}, +{-0.668817f,0.743427f,2.1497e-017f},{-0.569477f,0.822007f,4.2577e-016f},{-0.608828f,0.793302f,2.07916e-017f}, +{-0.461029f,0.887385f,4.62743e-017f},{-0.500171f,0.865926f,-8.66628e-016f},{-0.382431f,0.923984f,-7.93122e-018f}, +{-0.345178f,0.938537f,9.19408e-016f},{-0.221677f,0.97512f,9.65517e-016f},{-0.258907f,0.965902f,-4.49664e-018f}, +{-0.0988218f,0.995105f,2.20458e-019f},{-0.130601f,0.991435f,-1.82934e-018f},{-3.77476e-016f,1.0f,0.0f}, +{0.994576f,0.104013f,-2.37446e-016f},{0.994455f,-0.105163f,2.4662e-016f},{0.950548f,-0.310578f,3.73545e-016f}, +{0.980872f,-0.194653f,3.75714e-016f},{0.924088f,-0.382179f,3.99499e-016f},{0.742274f,-0.670096f,9.66286e-016f}, +{0.831655f,-0.555293f,7.03883e-016f},{0.86521f,-0.50141f,8.23015e-016f},{0.586974f,-0.809606f,8.82738e-016f}, +{0.707139f,-0.707075f,7.98094e-016f},{0.555458f,-0.831545f,1.00906e-015f},{0.406026f,-0.913862f,9.73266e-016f}, +{0.207408f,-0.978254f,1.11318e-015f},{0.382504f,-0.923954f,1.10236e-015f},{-9.4369e-016f,-1.0f,1.18424e-015f}, +{-4.44089e-016f,-1.0f,1.18424e-015f},{0.19489f,-0.980825f,1.0979e-015f},{0.98057f,0.196168f,-3.04887e-016f}, +{0.951298f,0.308272f,-4.35477e-016f},{0.923329f,0.384009f,-5.11603e-016f},{0.830773f,0.556611f,-7.00357e-016f}, +{0.866353f,0.499433f,-5.27324e-016f},{0.706447f,0.707766f,-8.90548e-016f},{0.743379f,0.66887f,-7.97616e-016f}, +{0.587881f,0.808947f,-9.57986e-016f},{0.554999f,0.831851f,-9.44127e-016f},{0.382212f,0.924075f,-1.23111e-015f}, +{0.406743f,0.913543f,-1.27729e-015f},{0.194766f,0.98085f,-1.13273e-015f},{0.20783f,0.978165f,-1.01358e-015f}, +{6.57384e-032f,1.0f,-1.18424e-015f},{0.0f,1.0f,-1.18424e-015f},{0.197004f,0.475871f,-0.857167f}, +{0.286082f,0.428277f,-0.857167f},{-2.0793e-011f,-0.515038f,-0.857167f},{0.100376f,0.505162f,-0.857167f}, +{8.71248e-012f,0.515038f,-0.857167f},{0.364203f,0.36417f,-0.857167f},{0.428334f,0.285997f,-0.857167f}, +{0.475941f,0.196837f,-0.857167f},{0.505186f,0.100254f,-0.857167f},{0.515038f,-1.86582e-015f,-0.857167f}, +{0.47555f,-0.19778f,-0.857167f},{0.505031f,-0.101034f,-0.857167f},{0.363847f,-0.364526f,-0.857167f}, +{0.42788f,-0.286676f,-0.857167f},{0.196854f,-0.475934f,-0.857167f},{0.285846f,-0.428435f,-0.857167f}, +{1.26614e-015f,-0.515038f,-0.857167f},{0.100312f,-0.505175f,-0.857167f},{0.994576f,0.104013f,-5.34124e-017f}, +{0.994455f,-0.105163f,4.1204e-017f},{0.950548f,-0.310578f,3.38367e-016f},{0.980872f,-0.194653f,1.90615e-016f}, +{0.924088f,-0.382179f,2.52153e-016f},{0.742274f,-0.670096f,8.23884e-016f},{0.831655f,-0.555293f,6.83239e-016f}, +{0.86521f,-0.50141f,6.78022e-016f},{0.586974f,-0.809606f,9.23936e-016f},{0.707139f,-0.707075f,8.43888e-016f}, +{0.555458f,-0.831545f,1.05336e-015f},{0.406026f,-0.913862f,1.11933e-015f},{0.207408f,-0.978254f,1.18377e-015f}, +{0.382504f,-0.923954f,1.10248e-015f},{-5.55112e-017f,-1.0f,1.18424e-015f},{0.0f,-1.0f,1.18424e-015f}, +{0.19489f,-0.980825f,1.11609e-015f},{0.98057f,0.196168f,-1.96021e-016f},{0.951298f,0.308272f,-3.17474e-016f}, +{0.923329f,0.384009f,-5.08887e-016f},{0.830773f,0.556611f,-6.79452e-016f},{0.866353f,0.499433f,-4.53393e-016f}, +{0.706447f,0.707766f,-7.3349e-016f},{0.743379f,0.66887f,-6.87574e-016f},{0.587881f,0.808947f,-9.74348e-016f}, +{0.554999f,0.831851f,-9.8511e-016f},{0.382212f,0.924075f,-1.09432e-015f},{0.406743f,0.913543f,-9.4662e-016f}, +{0.194766f,0.98085f,-9.87533e-016f},{4.16334e-016f,1.0f,-1.18424e-015f},{0.0f,-0.515038f,-0.857167f}, +{8.71235e-012f,0.515038f,-0.857167f},{0.515038f,-2.11803e-015f,-0.857167f},{7.89703e-016f,-0.515038f,-0.857167f}, +{1.0f,6.57384e-032f,7.40149e-017f},{0.994576f,0.104013f,-1.89091e-016f},{0.994455f,-0.105163f,2.07702e-016f}, +{0.950548f,-0.310578f,3.67798e-016f},{0.980872f,-0.194653f,1.0721e-016f},{0.924088f,-0.382179f,4.00133e-016f}, +{0.742274f,-0.670096f,8.8302e-016f},{0.831655f,-0.555293f,6.21707e-016f},{0.586974f,-0.809606f,8.44444e-016f}, +{0.707139f,-0.707075f,7.32676e-016f},{0.555458f,-0.831545f,8.05154e-016f},{0.406026f,-0.913862f,1.0147e-015f}, +{0.207408f,-0.978254f,9.49547e-016f},{0.382504f,-0.923954f,1.06648e-015f},{9.15934e-016f,-1.0f,1.03621e-015f}, +{0.0f,-1.0f,1.03621e-015f},{0.19489f,-0.980825f,1.15631e-015f},{0.98057f,0.196168f,-2.3231e-016f}, +{0.923329f,0.384009f,-2.61233e-016f},{0.866353f,0.499433f,-7.19693e-016f},{0.706447f,0.707766f,-7.33587e-016f}, +{0.743379f,0.66887f,-5.83047e-016f},{0.587881f,0.808947f,-1.07773e-015f},{0.554999f,0.831851f,-1.10825e-015f}, +{0.20783f,0.978165f,-1.18915e-015f},{-3.88578e-016f,1.0f,-1.18424e-015f},{4.44089e-016f,1.0f,-1.18424e-015f}, +{8.71311e-012f,0.515038f,-0.857167f},{0.515038f,-7.70404e-016f,-0.857167f},{5.42398e-016f,-0.515038f,-0.857167f}, +{1.0f,-2.22045e-016f,-7.40149e-017f},{0.994576f,0.104013f,-4.57139e-017f},{0.994455f,-0.105163f,1.02395e-017f}, +{0.950548f,-0.310578f,2.38582e-016f},{0.980872f,-0.194653f,1.6512e-016f},{0.924088f,-0.382179f,4.96816e-016f}, +{0.742274f,-0.670096f,7.74955e-016f},{0.831655f,-0.555293f,7.08878e-016f},{0.86521f,-0.50141f,4.90092e-016f}, +{0.586974f,-0.809606f,1.02824e-015f},{0.707139f,-0.707075f,9.74729e-016f},{0.555458f,-0.831545f,9.46272e-016f}, +{0.406026f,-0.913862f,1.24486e-015f},{0.207408f,-0.978254f,1.21316e-015f},{0.382504f,-0.923954f,1.12889e-015f}, +{4.44089e-016f,-1.0f,1.18424e-015f},{0.19489f,-0.980825f,1.27861e-015f},{0.98057f,0.196168f,-1.59733e-016f}, +{0.951298f,0.308272f,-2.94657e-016f},{0.923329f,0.384009f,-5.23098e-016f},{0.830773f,0.556611f,-7.61847e-016f}, +{0.706447f,0.707766f,-8.38163e-016f},{0.743379f,0.66887f,-7.3708e-016f},{0.587881f,0.808947f,-8.38238e-016f}, +{0.554999f,0.831851f,-9.44031e-016f},{0.194766f,0.98085f,-1.19039e-015f},{0.20783f,0.978165f,-1.12761e-015f}, +{-4.996e-016f,1.0f,-1.18424e-015f},{-4.44089e-016f,1.0f,-1.18424e-015f},{2.0793e-011f,-0.515038f,-0.857167f}, +{8.7127e-012f,0.515038f,-0.857167f},{0.515038f,-8.60974e-016f,-0.857167f},{5.6139e-016f,-0.515038f,-0.857167f}, +{0.130634f,0.991431f,9.00714e-017f},{0.130461f,0.991453f,6.43735e-017f},{-4.44089e-017f,1.0f,1.11862e-030f}, +{-0.130634f,0.991431f,1.22301e-016f},{-0.130461f,0.991453f,3.21868e-017f},{-4.71845e-017f,1.0f,1.11999e-030f}, +{-0.382576f,0.923924f,1.78148e-017f},{-0.382876f,0.9238f,4.72309e-017f},{-0.499909f,0.866078f,-1.52008e-016f}, +{-0.258991f,0.96588f,-2.14995e-016f},{-0.258717f,0.965953f,-6.38297e-017f},{-0.500177f,0.865923f,-2.3022e-016f}, +{-0.608898f,0.793249f,1.50225e-016f},{-0.608701f,0.7934f,4.50529e-016f},{-0.70708f,0.707134f,6.5418e-017f}, +{-0.707182f,0.707032f,-4.36183e-017f},{-0.793414f,0.608682f,7.34055e-017f},{-0.793302f,0.608828f,-6.2017e-017f}, +{-0.865926f,0.500171f,1.08892e-016f},{-0.866063f,0.499936f,-2.24963e-016f},{-0.923984f,0.382431f,1.36579e-016f}, +{-0.923898f,0.38264f,2.77802e-016f},{-0.966265f,0.257551f,1.98912e-016f},{-0.965902f,0.258907f,-1.96021e-016f}, +{-0.991435f,0.130601f,-1.67248e-016f},{-0.99153f,0.129881f,1.26101e-016f},{0.258717f,0.965953f,-2.55319e-016f}, +{0.258991f,0.96588f,-1.19149e-016f},{0.382575f,0.923924f,1.67951e-030f},{0.499909f,0.866078f,2.46671e-016f}, +{0.382876f,0.9238f,1.88923e-016f},{0.500177f,0.865923f,-3.86789e-016f},{0.608701f,0.7934f,3.00353e-016f}, +{0.608898f,0.793249f,3.0045e-016f},{0.70708f,0.707134f,2.61666e-016f},{0.793302f,0.608828f,-7.51038e-017f}, +{0.707182f,0.707032f,1.87217e-030f},{0.793414f,0.608682f,1.78765e-030f},{0.865926f,0.500171f,1.61435e-030f}, +{0.866063f,0.499936f,8.23851e-016f},{0.923984f,0.382431f,1.3463e-030f},{0.965902f,0.258907f,9.865e-031f}, +{0.923897f,0.38264f,1.34684e-030f},{0.966265f,0.257551f,9.82132e-031f},{0.991435f,0.130601f,5.35361e-031f}, +{0.99153f,0.129881f,5.32617e-031f},{0.994856f,0.101296f,0.0f},{0.998601f,0.0528865f,0.0f}, +{0.994333f,0.106314f,0.0f},{0.977365f,0.211559f,0.0f},{0.977403f,0.211384f,0.0f}, +{0.964768f,0.263101f,0.0f},{0.998775f,0.049491f,0.0f},{1.0f,1.19209e-007f,0.0f}, +{1.0f,1.93784e-016f,0.0f},{0.987859f,0.155356f,0.0f},{0.987268f,0.159066f,0.0f}, +{0.943659f,0.330919f,0.0f},{0.962422f,0.27156f,0.0f},{0.949398f,0.314075f,0.0f}, +{0.866023f,0.500004f,0.0f},{0.89538f,0.445304f,0.0f},{0.887356f,0.461084f,0.0f}, +{0.921283f,0.388894f,0.0f},{0.931337f,0.364157f,0.0f},{0.910637f,0.413206f,0.0f}, +{0.802718f,0.596359f,0.0f},{0.769841f,0.638236f,0.0f},{0.797431f,0.60341f,0.0f}, +{0.861559f,0.507658f,0.0f},{0.833319f,0.552792f,0.0f},{0.833335f,0.552769f,0.0f}, +{0.697641f,0.716448f,0.0f},{0.671898f,0.740644f,0.0f},{0.716559f,0.697526f,0.0f}, +{0.734782f,0.678303f,0.0f},{0.758457f,0.651723f,0.0f},{0.541517f,0.84069f,0.0f}, +{0.609678f,0.792649f,0.0f},{0.574801f,0.818293f,0.0f},{0.658522f,0.752561f,0.0f}, +{0.437309f,0.899311f,0.0f},{0.388825f,0.921312f,0.0f},{0.388834f,0.921308f,0.0f}, +{0.484556f,0.87476f,0.0f},{0.467738f,0.883867f,0.0f},{0.237326f,0.97143f,0.0f}, +{0.239133f,0.970987f,0.0f},{0.288698f,0.95742f,0.0f},{0.305468f,0.952202f,0.0f}, +{0.339241f,0.940699f,0.0f},{0.103293f,0.994651f,0.0f},{0.132709f,0.991155f,0.0f}, +{0.079772f,0.996813f,0.0f},{0.185276f,0.982686f,0.0f},{0.171605f,0.985166f,0.0f}, +{0.0344868f,0.999405f,0.0f},{-0.0266303f,0.999645f,0.0f},{-0.03448f,0.999405f,0.0f}, +{0.0266126f,0.999646f,0.0f},{-0.132754f,0.991149f,0.0f},{-0.185314f,0.982679f,0.0f}, +{-0.171593f,0.985168f,0.0f},{-0.10328f,0.994652f,0.0f},{-0.0798119f,0.99681f,0.0f}, +{-0.339268f,0.94069f,0.0f},{-0.305468f,0.952202f,0.0f},{-0.288713f,0.957416f,0.0f}, +{-0.239168f,0.970978f,0.0f},{-0.237346f,0.971425f,0.0f},{-0.467738f,0.883867f,0.0f}, +{-0.388834f,0.921308f,0.0f},{-0.437338f,0.899297f,0.0f},{-0.388857f,0.921298f,0.0f}, +{-0.541517f,0.84069f,0.0f},{-0.530443f,0.847721f,0.0f},{-0.574807f,0.818289f,0.0f}, +{-0.484577f,0.874749f,0.0f},{-0.658536f,0.752549f,0.0f},{-0.697657f,0.716432f,0.0f}, +{-0.671898f,0.740644f,0.0f},{-0.609678f,0.792649f,0.0f},{-0.617547f,0.786534f,0.0f}, +{-0.734799f,0.678285f,0.0f},{-0.769857f,0.638216f,0.0f},{-0.758453f,0.651728f,0.0f}, +{-0.716553f,0.697532f,0.0f},{-0.797427f,0.603416f,0.0f},{-0.802733f,0.596339f,0.0f}, +{-0.833333f,0.552771f,0.0f},{-0.833328f,0.552779f,0.0f},{-0.861571f,0.507638f,0.0f}, +{-0.866021f,0.500008f,0.0f},{-0.887366f,0.461066f,0.0f},{-0.895373f,0.445318f,0.0f}, +{-0.921279f,0.388903f,0.0f},{-0.910645f,0.413189f,0.0f},{-0.931345f,0.364138f,0.0f}, +{-0.943631f,0.330998f,0.0f},{-0.949405f,0.314055f,0.0f},{-0.962355f,0.271796f,0.0f}, +{-0.977365f,0.211559f,0.0f},{-0.964773f,0.263083f,0.0f},{-0.98727f,0.159053f,0.0f}, +{-0.977407f,0.211368f,0.0f},{-0.994335f,0.106287f,0.0f},{-0.987859f,0.155356f,0.0f}, +{-0.994856f,0.101296f,0.0f},{-0.9986f,0.0529056f,0.0f},{-0.998775f,0.049491f,0.0f}, +{0.53043f,0.847729f,0.0f},{0.617538f,0.786541f,0.0f},{0.624695f,-9.46817e-016f,-0.780869f}, +{0.624695f,-9.5349e-016f,-0.780869f},{0.623357f,-0.040871f,-0.780869f},{0.409092f,0.47211f,-0.780869f}, +{0.411878f,0.469681f,-0.780869f},{0.380282f,0.495611f,-0.780869f},{0.441714f,0.441739f,-0.780869f}, +{0.362367f,0.508856f,-0.780869f},{0.347057f,0.519418f,-0.780869f},{0.312348f,0.541002f,-0.780869f}, +{0.312341f,0.541005f,-0.780869f},{0.347056f,0.519419f,-0.780869f},{0.276286f,0.560277f,-0.780869f}, +{0.276287f,0.560276f,-0.780869f},{0.239058f,0.577144f,-0.780869f},{0.239054f,0.577146f,-0.780869f}, +{0.200802f,0.591543f,-0.780869f},{0.200803f,0.591542f,-0.780869f},{0.161685f,0.603409f,-0.780869f}, +{0.161681f,0.60341f,-0.780869f},{0.121783f,0.612709f,-0.780869f},{0.121874f,0.612691f,-0.780869f}, +{0.0815751f,0.619346f,-0.780869f},{0.0813198f,0.61938f,-0.780869f},{0.0406682f,0.62337f,-0.780869f}, +{0.0408792f,0.623356f,-0.780869f},{6.31627e-017f,0.624695f,-0.780869f},{9.6494e-017f,0.624695f,-0.780869f}, +{0.452119f,0.431082f,-0.780869f},{0.469659f,0.411903f,-0.780869f},{0.491049f,0.386154f,-0.780869f}, +{0.495594f,0.380303f,-0.780869f},{0.519406f,0.347075f,-0.780869f},{0.525532f,0.337728f,-0.780869f}, +{0.540994f,0.31236f,-0.780869f},{0.555257f,0.286241f,-0.780869f},{0.560267f,0.276306f,-0.780869f}, +{0.579951f,0.232166f,-0.780869f},{0.577139f,0.239071f,-0.780869f},{0.603409f,0.161685f,-0.780869f}, +{0.612693f,0.121866f,-0.780869f},{0.613402f,0.118247f,-0.780869f},{0.599395f,0.175983f,-0.780869f}, +{0.591539f,0.200813f,-0.780869f},{0.613408f,0.118216f,-0.780869f},{0.603405f,0.161699f,-0.780869f}, +{0.612688f,0.12189f,-0.780869f},{0.621867f,0.0593712f,-0.780869f},{0.619348f,0.0815574f,-0.780869f}, +{0.623358f,0.0408492f,-0.780869f},{0.624695f,-9.55166e-016f,-0.780869f},{0.623358f,0.0408553f,-0.780869f}, +{0.619036f,-0.0838959f,-0.780869f},{0.623279f,-0.0420416f,-0.780869f},{0.619348f,-0.0815572f,-0.780869f}, +{0.589599f,-0.206439f,-0.780869f},{0.602157f,-0.166284f,-0.780869f},{0.591537f,-0.200819f,-0.780869f}, +{0.611985f,-0.125373f,-0.780869f},{0.612689f,-0.121886f,-0.780869f},{0.603406f,-0.161693f,-0.780869f}, +{0.556524f,-0.283768f,-0.780869f},{0.540992f,-0.312365f,-0.780869f},{0.536161f,-0.320586f,-0.780869f}, +{0.577134f,-0.239082f,-0.780869f},{0.560263f,-0.276314f,-0.780869f},{0.574364f,-0.245661f,-0.780869f}, +{0.495593f,-0.380304f,-0.780869f},{0.469657f,-0.411906f,-0.780869f},{0.488247f,-0.389691f,-0.780869f}, +{0.513369f,-0.355945f,-0.780869f},{0.519405f,-0.347077f,-0.780869f},{0.380275f,-0.495616f,-0.780869f}, +{0.400096f,-0.479758f,-0.780869f},{0.411873f,-0.469686f,-0.780869f},{0.431479f,-0.451741f,-0.780869f}, +{0.460909f,-0.421672f,-0.780869f},{0.441709f,-0.441743f,-0.780869f},{0.295665f,-0.550296f,-0.780869f}, +{0.332035f,-0.529147f,-0.780869f},{0.312348f,-0.541002f,-0.780869f},{0.366898f,-0.505599f,-0.780869f}, +{0.31233f,-0.541012f,-0.780869f},{0.276304f,-0.560268f,-0.780869f},{0.239076f,-0.577137f,-0.780869f}, +{0.239048f,-0.577148f,-0.780869f},{0.200811f,-0.591539f,-0.780869f},{0.276284f,-0.560278f,-0.780869f}, +{0.161687f,-0.603408f,-0.780869f},{0.161672f,-0.603412f,-0.780869f},{0.121883f,-0.612689f,-0.780869f}, +{0.200788f,-0.591547f,-0.780869f},{0.0815507f,-0.619349f,-0.780869f},{0.121867f,-0.612693f,-0.780869f}, +{0.0815307f,-0.619352f,-0.780869f},{0.0407198f,-0.623367f,-0.780869f},{0.0408636f,-0.623357f,-0.780869f}, +{-6.68781e-017f,-0.624695f,-0.780869f},{0.0f,-0.624695f,-0.780869f},{0.347044f,-0.519427f,-0.780869f}, +{0.121858f,-0.612694f,-0.780869f},{0.13845f,-0.60916f,-0.780869f},{0.161673f,-0.603412f,-0.780869f}, +{0.0815244f,-0.619353f,-0.780869f},{0.0972037f,-0.617086f,-0.780869f},{0.0554519f,-0.622229f,-0.780869f}, +{0.040847f,-0.623358f,-0.780869f},{-3.53852e-018f,-0.624695f,-0.780869f},{0.0134175f,-0.624551f,-0.780869f}, +{0.179217f,-0.598436f,-0.780869f},{0.219081f,-0.585019f,-0.780869f},{0.238818f,-0.577243f,-0.780869f}, +{0.20082f,-0.591536f,-0.780869f},{0.257958f,-0.568948f,-0.780869f},{0.276277f,-0.560281f,-0.780869f}, +{0.624695f,-9.4344e-016f,-0.780869f},{0.362343f,0.508873f,-0.780869f},{0.31234f,0.541006f,-0.780869f}, +{0.409076f,0.472124f,-0.780869f},{0.380283f,0.49561f,-0.780869f},{0.441721f,0.441731f,-0.780869f}, +{0.411883f,0.469676f,-0.780869f},{0.452096f,0.431107f,-0.780869f},{0.49103f,0.386178f,-0.780869f}, +{0.469665f,0.411897f,-0.780869f},{0.519411f,0.347068f,-0.780869f},{0.495597f,0.3803f,-0.780869f}, +{0.525513f,0.337758f,-0.780869f},{0.555239f,0.286275f,-0.780869f},{0.541001f,0.312349f,-0.780869f}, +{0.560272f,0.276296f,-0.780869f},{0.579937f,0.232201f,-0.780869f},{0.577143f,0.23906f,-0.780869f}, +{0.599383f,0.176024f,-0.780869f},{0.591542f,0.200803f,-0.780869f},{0.621866f,0.0593873f,-0.780869f}, +{0.619352f,0.0815289f,-0.780869f},{1.0f,1.19209e-007f,-8.82326e-023f},{1.0f,3.38566e-017f,-2.50589e-032f}, +{0.998307f,-0.058159f,4.30463e-017f},{0.993236f,-0.116116f,8.5943e-017f},{0.998309f,-0.0581378f,4.30306e-017f}, +{0.984803f,-0.173675f,1.28545e-016f},{0.99324f,-0.11608f,8.59168e-017f},{0.984811f,-0.173633f,2.57028e-016f}, +{0.973038f,-0.230643f,1.7071e-016f},{0.957982f,-0.286828f,0.0f},{0.973049f,-0.2306f,1.70678e-016f}, +{0.939685f,-0.342042f,5.06323e-016f},{0.957993f,-0.28679f,0.0f},{0.939696f,-0.342012f,5.0628e-016f}, +{0.918208f,-0.396098f,5.86343e-016f},{0.893624f,-0.448816f,6.64382e-016f},{0.918216f,-0.396079f,5.86315e-016f}, +{0.866013f,-0.500021f,7.40179e-016f},{0.893631f,-0.448803f,0.0f},{0.866023f,-0.500004f,7.40154e-016f}, +{0.835473f,-0.549532f,8.13471e-016f},{0.802106f,-0.597181f,8.84005e-016f},{0.835486f,-0.549512f,0.0f}, +{0.766027f,-0.642808f,9.51547e-016f},{0.802121f,-0.597162f,8.83977e-016f},{0.766041f,-0.642791f,0.0f}, +{0.727358f,-0.686258f,0.0f},{0.686227f,-0.727388f,0.0f},{0.727369f,-0.686246f,0.0f}, +{0.642773f,-0.766057f,0.0f},{0.686238f,-0.727377f,0.0f},{0.642785f,-0.766046f,1.13398e-015f}, +{0.597145f,-0.802133f,0.0f},{0.549498f,-0.835495f,0.0f},{0.597158f,-0.802124f,0.0f}, +{0.499989f,-0.866032f,0.0f},{0.549511f,-0.835486f,0.0f},{0.500008f,-0.866021f,0.0f}, +{0.448787f,-0.893639f,0.0f},{0.396067f,-0.918221f,0.0f},{0.448811f,-0.893627f,0.0f}, +{0.342011f,-0.939696f,0.0f},{0.396094f,-0.91821f,0.0f},{0.342035f,-0.939687f,0.0f}, +{0.286798f,-0.957991f,0.0f},{0.230613f,-0.973045f,0.0f},{0.286837f,-0.957979f,0.0f}, +{0.230535f,-0.973064f,0.0f},{0.173651f,-0.984807f,0.0f},{0.116108f,-0.993237f,0.0f}, +{0.173275f,-0.984873f,0.0f},{0.0581642f,-0.998307f,0.0f},{0.11595f,-0.993255f,0.0f}, +{1.30331e-016f,-1.0f,0.0f},{0.0581517f,-0.998308f,0.0f},{1.54466e-016f,-1.0f,0.0f}, +{0.998307f,0.0581591f,-4.30464e-017f},{0.993236f,0.116116f,-8.5943e-017f},{0.998309f,0.0581377f,-4.30305e-017f}, +{0.99324f,0.11608f,0.0f},{0.984803f,0.173675f,0.0f},{0.973038f,0.230643f,-1.7071e-016f}, +{0.984811f,0.173632f,-1.28514e-016f},{0.957982f,0.286828f,-2.12296e-016f},{0.973049f,0.2306f,-1.70678e-016f}, +{0.957994f,0.28679f,-2.12267e-016f},{0.939685f,0.342042f,-2.53162e-016f},{0.918208f,0.396098f,-2.93171e-016f}, +{0.939696f,0.342012f,-2.5314e-016f},{0.893624f,0.448817f,-3.32191e-016f},{0.918216f,0.396079f,-2.93157e-016f}, +{0.893631f,0.448803f,-1.66091e-016f},{0.866013f,0.500021f,-1.85045e-016f},{0.835473f,0.549532f,-2.03368e-016f}, +{0.866023f,0.500004f,-3.70077e-016f},{0.802106f,0.597181f,-2.21001e-016f},{0.835486f,0.549512f,-2.0336e-016f}, +{0.802121f,0.597162f,-2.20994e-016f},{0.766027f,0.642808f,-2.37887e-016f},{0.727358f,0.686259f,0.0f}, +{0.766042f,0.642791f,-2.3788e-016f},{0.686227f,0.727388f,-2.69188e-016f},{0.72737f,0.686246f,-2.53962e-016f}, +{0.686238f,0.727377f,-2.69184e-016f},{0.642773f,0.766057f,-1.41749e-016f},{0.597145f,0.802133f,-1.48424e-016f}, +{0.642785f,0.766046f,-1.41747e-016f},{0.549498f,0.835495f,-1.54598e-016f},{0.597158f,0.802124f,-2.96845e-016f}, +{0.549511f,0.835486f,-1.54596e-016f},{0.499989f,0.866032f,0.0f},{0.448787f,0.893639f,-1.65356e-016f}, +{0.500008f,0.866021f,-1.60246e-016f},{0.396067f,0.918222f,-8.49526e-017f},{0.448811f,0.893627f,-8.26771e-017f}, +{0.396094f,0.91821f,-8.49515e-017f},{0.342011f,0.939696f,-8.69394e-017f},{0.286798f,0.957991f,-4.4316e-017f}, +{0.342035f,0.939687f,-8.69385e-017f},{0.230613f,0.973045f,-4.50124e-017f},{0.286837f,0.957979f,-4.43155e-017f}, +{0.173651f,0.984807f,-2.27782e-017f},{0.230535f,0.973064f,-4.50133e-017f},{0.173275f,0.984873f,-2.27798e-017f}, +{0.116108f,0.993237f,-1.14866e-017f},{0.11595f,0.993255f,-1.14868e-017f},{0.0581641f,0.998307f,-2.88631e-018f}, +{0.0581517f,0.998308f,-2.88631e-018f},{3.49254e-012f,1.0f,-9.79579e-039f},{8.206e-017f,1.0f,0.0f}, +{1.0f,7.76449e-017f,-9.195e-032f},{1.0f,6.17846e-017f,-7.31676e-032f},{0.998629f,-0.052353f,6.19984e-017f}, +{0.994519f,-0.104553f,1.34134e-016f},{0.99863f,-0.052328f,6.19688e-017f},{0.987684f,-0.156459f,2.00725e-016f}, +{0.994523f,-0.104515f,1.23771e-016f},{0.987691f,-0.156421f,2.00676e-016f},{0.978143f,-0.207932f,2.66762e-016f}, +{0.965922f,-0.258835f,3.06522e-016f},{0.978149f,-0.207904f,2.46208e-016f},{0.951049f,-0.30904f,3.65977e-016f}, +{0.965925f,-0.258822f,3.06506e-016f},{0.951055f,-0.309021f,3.65954e-016f},{0.933568f,-0.3584f,4.2443e-016f}, +{0.913531f,-0.40677f,4.81712e-016f},{0.933581f,-0.358367f,3.89026e-016f},{0.890991f,-0.454022f,5.3767e-016f}, +{0.913546f,-0.406734f,5.2181e-016f},{0.891007f,-0.453989f,5.37631e-016f},{0.866009f,-0.500028f,5.92152e-016f}, +{0.838655f,-0.544663f,6.45011e-016f},{0.866024f,-0.500002f,6.41465e-016f},{0.809001f,-0.587808f,6.38096e-016f}, +{0.838665f,-0.544647f,5.91242e-016f},{0.809009f,-0.587797f,6.96091e-016f},{0.777125f,-0.629346f,7.45295e-016f}, +{0.74312f,-0.669158f,7.92442e-016f},{0.777137f,-0.629331f,8.07384e-016f},{0.70708f,-0.707134f,8.37415e-016f}, +{0.743137f,-0.66914f,6.60351e-016f},{0.707099f,-0.707115f,8.37392e-016f},{0.669102f,-0.74317f,8.80091e-016f}, +{0.629291f,-0.777169f,9.20353e-016f},{0.669122f,-0.743152f,1.02675e-015f},{0.587756f,-0.809038f,1.11778e-015f}, +{0.629312f,-0.777153f,9.20334e-016f},{0.587776f,-0.809023f,1.11776e-015f},{0.54461f,-0.838689f,9.93208e-016f}, +{0.499972f,-0.866041f,1.0256e-015f},{0.54463f,-0.838677f,9.93193e-016f},{0.453965f,-0.891019f,1.05518e-015f}, +{0.49999f,-0.866031f,1.02559e-015f},{0.45398f,-0.891012f,1.05517e-015f},{0.406714f,-0.913555f,9.01556e-016f}, +{0.358347f,-0.933588f,1.10559e-015f},{0.406729f,-0.913549f,9.01549e-016f},{0.308997f,-0.951063f,1.12628e-015f}, +{0.358363f,-0.933582f,1.10558e-015f},{0.309013f,-0.951058f,1.12628e-015f},{0.258801f,-0.965931f,1.33454e-015f}, +{0.207899f,-0.97815f,1.35142e-015f},{0.258815f,-0.965927f,1.14389e-015f},{0.156426f,-0.98769f,9.74716e-016f}, +{0.207911f,-0.978148f,1.15836e-015f},{0.156436f,-0.987688f,1.16966e-015f},{0.104524f,-0.994522f,1.17775e-015f}, +{0.0520121f,-0.998646f,9.85529e-016f},{0.104542f,-0.99452f,1.17775e-015f},{1.58603e-016f,-1.0f,1.18424e-015f}, +{0.0519994f,-0.998647f,1.18264e-015f},{1.19209e-007f,-1.0f,1.18424e-015f},{0.998629f,0.0523531f,-6.19985e-017f}, +{0.994519f,0.104553f,-1.13498e-016f},{0.99863f,0.0523281f,-6.19689e-017f},{0.994523f,0.104515f,-1.23771e-016f}, +{0.987684f,0.156459f,-1.85285e-016f},{0.978143f,0.207932f,-2.46241e-016f},{0.987691f,0.156421f,-1.92958e-016f}, +{0.965922f,0.258835f,-3.19294e-016f},{0.978149f,0.207904f,-2.46208e-016f},{0.965925f,0.258822f,-3.19278e-016f}, +{0.951049f,0.30904f,-3.81226e-016f},{0.933568f,0.3584f,-3.71377e-016f},{0.951055f,0.309021f,-3.65954e-016f}, +{0.913531f,0.40677f,-4.81712e-016f},{0.933581f,0.358367f,-4.24392e-016f},{0.913546f,0.406734f,-5.0174e-016f}, +{0.890991f,0.454022f,-5.71274e-016f},{0.866009f,0.500028f,-6.16825e-016f},{0.891007f,0.453989f,-5.71233e-016f}, +{0.838655f,0.544663f,-6.58448e-016f},{0.866024f,0.500002f,-5.92122e-016f},{0.838665f,0.544647f,-6.31554e-016f}, +{0.809001f,0.587808f,-6.52598e-016f},{0.777125f,0.629346f,-7.60822e-016f},{0.809009f,0.587797f,-6.8884e-016f}, +{0.74312f,0.669158f,-8.50225e-016f},{0.777137f,0.629331f,-7.60804e-016f},{0.743137f,0.66914f,-8.6671e-016f}, +{0.70708f,0.707134f,-7.50184e-016f},{0.669102f,0.74317f,-9.12177e-016f},{0.707099f,0.707115f,-8.72284e-016f}, +{0.629291f,0.77717f,-9.44321e-016f},{0.669122f,0.743152f,-8.75485e-016f},{0.629312f,0.777153f,-7.71738e-016f}, +{0.587756f,0.809038f,-9.38133e-016f},{0.54461f,0.838689f,-9.46651e-016f},{0.587776f,0.809024f,-9.58076e-016f}, +{0.499972f,0.866041f,-9.66841e-016f},{0.54463f,0.838677f,-9.46637e-016f},{0.49999f,0.866031f,-9.64159e-016f}, +{0.453965f,0.891019f,-1.1541e-015f},{0.406714f,0.913555f,-1.12976e-015f},{0.45398f,0.891012f,-1.12112e-015f}, +{0.358347f,0.933588f,-1.1459e-015f},{0.406729f,0.913549f,-1.1692e-015f},{0.358363f,0.933582f,-1.09407e-015f}, +{0.308997f,0.951063f,-1.12995e-015f},{0.258801f,0.965931f,-1.09251e-015f},{0.309013f,0.951058f,-1.10648e-015f}, +{0.207899f,0.97815f,-1.09633e-015f},{0.258815f,0.965927f,-1.11335e-015f},{0.207911f,0.978148f,-1.29222e-015f}, +{0.156426f,0.98769f,-1.07876e-015f},{0.104524f,0.994522f,-1.04604e-015f},{0.156436f,0.987688f,-1.27522e-015f}, +{0.0520121f,0.998646f,-1.21422e-015f},{0.104542f,0.99452f,-1.24232e-015f},{0.0519993f,0.998647f,-1.21422e-015f}, +{5.52976e-012f,1.0f,-1.18424e-015f},{-4.7581e-017f,1.0f,-1.18424e-015f},{0.0f,1.38778e-017f,1.0f}, +{0.0f,-1.38778e-017f,1.0f},{0.0f,-2.77556e-017f,1.0f},{0.0f,2.77556e-017f,1.0f}, +{0.0f,1.04083e-017f,1.0f},{0.0f,5.20417e-018f,1.0f},{0.0f,-2.12504e-017f,1.0f}, +{0.0f,6.93889e-018f,1.0f},{0.0f,-1.73472e-017f,1.0f},{0.0f,-1.04083e-017f,1.0f}, +{0.0f,-2.08167e-017f,1.0f},{0.0f,2.42861e-017f,1.0f},{0.0f,1.73472e-017f,1.0f}, +{0.0f,-2.25514e-017f,1.0f},{0.0f,-6.93889e-018f,1.0f},{0.0f,2.08167e-017f,1.0f}, +{0.0f,-5.20417e-018f,1.0f},{0.0f,3.46945e-018f,1.0f},{0.0f,-3.46945e-018f,1.0f}, +{0.0f,-2.42861e-017f,1.0f},{0.0f,5.55112e-017f,1.0f},{0.0f,-5.55112e-017f,1.0f}, +{0.15501f,-0.0448068f,0.986896f},{0.151564f,-0.0553554f,0.986896f},{0.307074f,-0.112152f,0.945054f}, +{0.668812f,-0.559936f,0.489042f},{0.705929f,-0.51235f,0.489042f},{0.622414f,-0.451736f,0.639168f}, +{0.652262f,-0.407453f,0.639168f},{0.739783f,-0.462125f,0.489042f},{0.490087f,-0.410306f,0.769067f}, +{0.374976f,-0.313934f,0.87226f},{0.460725f,-0.443021f,0.769067f},{0.235646f,-0.226591f,0.945054f}, +{0.305444f,-0.336696f,0.890696f},{0.352511f,-0.338965f,0.87226f},{0.104942f,-0.115679f,0.987727f}, +{0.207967f,-0.229246f,0.950892f},{0.116309f,-0.11184f,0.986896f},{0.678996f,-0.361149f,0.639168f}, +{0.770104f,-0.409608f,0.489042f},{0.702422f,-0.313158f,0.639168f},{6.07606e-008f,-5.84258e-008f,1.0f}, +{5.66367e-008f,-6.24316e-008f,1.0f},{0.801521f,-0.500692f,0.326914f},{0.837008f,-0.52286f,0.161356f}, +{0.834372f,-0.443791f,0.326914f},{0.833339f,-0.552763f,1.22111e-009f},{0.866025f,-0.5f,2.96063e-015f}, +{0.798705f,-0.579685f,0.161356f},{0.797438f,-0.603401f,1.88811e-015f},{0.75671f,-0.633525f,0.161356f}, +{0.871314f,-0.46344f,0.161356f},{0.895381f,-0.445302f,8.1345e-010f},{0.716504f,-0.697583f,3.07674e-011f}, +{0.758466f,-0.651713f,3.54258e-015f},{0.711375f,-0.684039f,0.161356f},{0.671898f,-0.740644f,0.0f}, +{0.66364f,-0.731542f,0.156297f},{0.901374f,-0.401856f,0.161356f},{0.921284f,-0.38889f,4.19485e-015f}, +{0.927004f,-0.338567f,0.161356f},{0.943637f,-0.330981f,3.15625e-010f},{0.962368f,-0.27175f,4.29443e-015f}, +{0.948083f,-0.27405f,0.161356f},{0.965371f,-0.208962f,0.156188f},{0.929369f,-0.201169f,0.309522f}, +{0.796673f,-0.355178f,0.489042f},{0.628743f,-0.604582f,0.489042f},{0.589688f,-0.493693f,0.639168f}, +{0.977365f,-0.211559f,2.52172e-015f},{0.863158f,-0.384819f,0.326914f},{0.61403f,-0.177489f,0.769067f}, +{0.574515f,-0.124358f,0.808992f},{0.469808f,-0.135801f,0.87226f},{0.691102f,-0.149594f,0.707107f}, +{0.738821f,-0.213561f,0.639168f},{9.17498e-016f,3.64703e-016f,1.0f},{2.19934e-015f,-9.00417e-016f,1.0f}, +{0.431766f,-0.229651f,0.87226f},{0.446663f,-0.199134f,0.87226f},{0.298584f,-0.133117f,0.945054f}, +{0.152759f,-0.0330659f,0.98771f},{0.907886f,-0.262431f,0.326914f},{0.870535f,-0.188434f,0.454599f}, +{0.837955f,-0.242217f,0.489042f},{0.887701f,-0.324213f,0.326914f},{0.764842f,-0.555108f,0.326914f}, +{0.724627f,-0.606665f,0.326914f},{0.681215f,-0.655037f,0.326914f},{0.639091f,-0.70448f,0.308658f}, +{0.79069f,-0.171151f,0.587806f},{0.819325f,-0.29924f,0.489042f},{0.59887f,-0.660144f,0.453393f}, +{0.314057f,-0.0907801f,0.945054f},{0.44313f,-0.0959191f,0.891311f},{0.722395f,-0.263838f,0.639168f}, +{0.517285f,-0.375435f,0.769067f},{0.55436f,-0.533057f,0.639168f},{0.54356f,-0.599175f,0.58782f}, +{0.583779f,-0.260264f,0.769067f},{0.600378f,-0.219275f,0.769067f},{0.56431f,-0.300149f,0.769067f}, +{0.542092f,-0.338632f,0.769067f},{0.475103f,-0.523714f,0.707107f},{0.459363f,-0.167772f,0.87226f}, +{0.414767f,-0.259095f,0.87226f},{0.395786f,-0.287254f,0.87226f},{0.394946f,-0.435355f,0.809002f}, +{0.301672f,-0.0652993f,0.951173f},{0.288626f,-0.153517f,0.945054f},{0.277263f,-0.1732f,0.945054f}, +{0.264575f,-0.192023f,0.945054f},{0.123721f,-0.103581f,0.986896f},{0.250663f,-0.209858f,0.945054f}, +{0.147374f,-0.0657031f,0.986896f},{0.142459f,-0.075772f,0.986896f},{0.13685f,-0.085487f,0.986896f}, +{0.130587f,-0.0947778f,0.986896f},{8.87339e-016f,-1.30421e-016f,1.0f},{2.79757e-015f,-1.76166e-015f,1.0f}, +{3.59024e-015f,-1.95786e-015f,1.0f},{7.32027e-016f,-1.12982e-015f,1.0f},{6.46328e-008f,-5.41113e-008f,1.0f}, +{0.0328513f,-0.944483f,0.326914f},{0.0907435f,-0.867527f,0.489042f},{0.0303209f,-0.871733f,0.489042f}, +{0.170294f,-0.972093f,0.161356f},{0.102669f,-0.981541f,0.161356f},{0.103293f,-0.994651f,6.83652e-010f}, +{0.080008f,-0.764894f,0.639168f},{0.0344869f,-0.999405f,-3.61854e-015f},{0.226672f,-0.917468f,0.326914f}, +{0.236707f,-0.958089f,0.161356f},{0.290467f,-0.905442f,0.309522f},{0.239133f,-0.970987f,1.70293e-010f}, +{0.301719f,-0.940516f,0.156188f},{0.0387014f,-0.156646f,0.986896f},{0.0278429f,-0.158936f,0.986896f}, +{0.0564107f,-0.32201f,0.945054f},{0.305468f,-0.952202f,1.00419e-015f},{0.171605f,-0.985166f,1.49536e-016f}, +{0.215998f,-0.673309f,0.707107f},{0.153305f,-0.62051f,0.769067f},{0.184461f,-0.746618f,0.639168f}, +{0.0508762f,-0.486388f,0.87226f},{0.0340097f,-0.32514f,0.945054f},{0.0169997f,-0.488746f,0.87226f}, +{0.117297f,-0.474766f,0.87226f},{0.17956f,-0.559723f,0.808992f},{0.0343058f,-0.9863f,0.161356f}, +{0.0983164f,-0.939926f,0.326914f},{-1.84702e-016f,-8.4923e-016f,1.0f},{-5.3061e-016f,-3.14148e-015f,1.0f}, +{-0.132707f,-0.757531f,0.639168f},{-0.209212f,-0.846799f,0.489042f},{-0.150513f,-0.859176f,0.489042f}, +{0.0477436f,-0.148826f,0.98771f},{-1.3262e-015f,8.93678e-016f,1.0f},{-0.0267338f,-0.768603f,0.639168f}, +{-0.0907434f,-0.867527f,0.489042f},{-0.030321f,-0.871733f,0.489042f},{0.0267338f,-0.768603f,0.639168f}, +{-0.153305f,-0.62051f,0.769067f},{-0.110292f,-0.62958f,0.769067f},{-0.0843867f,-0.481706f,0.87226f}, +{-0.0784104f,-0.317371f,0.945054f},{-0.138865f,-0.432871f,0.890696f},{-0.117297f,-0.474767f,0.87226f}, +{-0.080008f,-0.764894f,0.639168f},{-0.0477103f,-0.148722f,0.987727f},{-0.094549f,-0.294728f,0.950892f}, +{-0.0387014f,-0.156646f,0.986896f},{-0.0343058f,-0.9863f,0.161356f},{-0.0328514f,-0.944483f,0.326914f}, +{-2.02179e-008f,-8.18332e-008f,1.0f},{-2.5749e-008f,-8.02647e-008f,1.0f},{-0.0344801f,-0.999405f,1.75276e-009f}, +{-0.102669f,-0.981541f,0.161356f},{-0.10328f,-0.994652f,2.54736e-015f},{-0.170294f,-0.972093f,0.161356f}, +{-0.171593f,-0.985168f,5.72641e-011f},{-0.239168f,-0.970978f,-9.94311e-016f},{-0.236707f,-0.958089f,0.161356f}, +{-0.305468f,-0.952202f,1.57973e-015f},{0.272079f,-0.848123f,0.454599f},{0.209212f,-0.846799f,0.489042f}, +{0.163074f,-0.930878f,0.326914f},{-0.0983163f,-0.939926f,0.326914f},{-0.226672f,-0.917468f,0.326914f}, +{-0.163074f,-0.930878f,0.326914f},{-0.301713f,-0.9405f,0.156297f},{-0.290552f,-0.905709f,0.308658f}, +{0.247124f,-0.770333f,0.587806f},{0.150513f,-0.859176f,0.489042f},{-0.272267f,-0.848708f,0.453393f}, +{0.0784104f,-0.317371f,0.945054f},{0.138497f,-0.431722f,0.891311f},{0.132707f,-0.757531f,0.639168f}, +{-0.0664942f,-0.6357f,0.769067f},{-0.184461f,-0.746618f,0.639168f},{-0.247121f,-0.770324f,0.58782f}, +{0.0664942f,-0.6357f,0.769067f},{0.110292f,-0.62958f,0.769067f},{0.0222183f,-0.638781f,0.769067f}, +{-0.0222183f,-0.638781f,0.769067f},{-0.215998f,-0.673309f,0.707107f},{0.0843867f,-0.481706f,0.87226f}, +{-0.0169997f,-0.488746f,0.87226f},{-0.0508762f,-0.486388f,0.87226f},{-0.179556f,-0.559711f,0.809002f}, +{0.0942851f,-0.293905f,0.951173f},{0.011364f,-0.326716f,0.945054f},{-0.011364f,-0.326716f,0.945054f}, +{-0.0340097f,-0.32514f,0.945054f},{-0.0278429f,-0.158936f,0.986896f},{-0.0564107f,-0.32201f,0.945054f}, +{0.0167863f,-0.160481f,0.986896f},{0.00560897f,-0.161259f,0.986896f},{-0.00560897f,-0.161259f,0.986896f}, +{-0.0167863f,-0.160481f,0.986896f},{5.91466e-017f,2.9267e-015f,1.0f},{9.34451e-017f,7.88771e-016f,1.0f}, +{-2.08722e-016f,9.49885e-016f,1.0f},{-3.51097e-016f,1.29965e-015f,1.0f},{-1.45453e-008f,-8.30293e-008f,1.0f}, +{-0.837008f,-0.52286f,0.161356f},{-0.764842f,-0.555108f,0.326914f},{-0.801521f,-0.500692f,0.326914f}, +{-0.798705f,-0.579685f,0.161356f},{-0.833333f,-0.552772f,8.1345e-010f},{-0.797431f,-0.60341f,7.34316e-016f}, +{-0.705929f,-0.51235f,0.489042f},{-0.739783f,-0.462125f,0.489042f},{-0.622414f,-0.451736f,0.639168f}, +{-0.681215f,-0.655037f,0.326914f},{-0.711375f,-0.684039f,0.161356f},{-0.638902f,-0.704273f,0.309522f}, +{-0.598457f,-0.659689f,0.454599f},{-0.123721f,-0.103581f,0.986896f},{-0.250664f,-0.209858f,0.945054f}, +{-0.116309f,-0.11184f,0.986896f},{-0.663652f,-0.731554f,0.156188f},{-0.716527f,-0.69756f,1.21528e-015f}, +{-0.671898f,-0.740644f,0.0f},{-0.75671f,-0.633525f,0.161356f},{-0.758457f,-0.651723f,3.15624e-010f}, +{-0.352511f,-0.338965f,0.87226f},{-0.460725f,-0.443021f,0.769067f},{-0.394955f,-0.435365f,0.808992f}, +{-8.27806e-016f,-2.64658e-016f,1.0f},{-2.98591e-015f,-1.11122e-015f,1.0f},{-0.414767f,-0.259095f,0.87226f}, +{-0.395786f,-0.287254f,0.87226f},{-0.264575f,-0.192023f,0.945054f},{-0.105015f,-0.11576f,0.98771f}, +{-7.33106e-016f,6.65059e-016f,1.0f},{-0.55436f,-0.533057f,0.639168f},{-0.475103f,-0.523714f,0.707107f}, +{-0.722395f,-0.263838f,0.639168f},{-0.837955f,-0.242217f,0.489042f},{-0.819325f,-0.29924f,0.489042f}, +{-0.652262f,-0.407453f,0.639168f},{-0.314057f,-0.0907802f,0.945054f},{-0.44431f,-0.0961744f,0.890696f}, +{-0.469808f,-0.135801f,0.87226f},{-0.834372f,-0.443791f,0.326914f},{-0.871314f,-0.46344f,0.161356f}, +{-0.61403f,-0.177489f,0.769067f},{-0.600378f,-0.219275f,0.769067f},{-0.459363f,-0.167772f,0.87226f}, +{-0.796673f,-0.355178f,0.489042f},{-0.702422f,-0.313158f,0.639168f},{-0.678996f,-0.361149f,0.639168f}, +{-0.770104f,-0.409608f,0.489042f},{-0.152652f,-0.0330429f,0.987727f},{-0.302516f,-0.0654821f,0.950892f}, +{-0.15501f,-0.0448068f,0.986896f},{-0.866025f,-0.5f,2.38332e-016f},{-8.09785e-008f,-2.34074e-008f,1.0f}, +{-8.23857e-008f,-1.78331e-008f,1.0f},{-0.901374f,-0.401856f,0.161356f},{-0.895376f,-0.445311f,1.22111e-009f}, +{-0.927004f,-0.338567f,0.161356f},{-0.921279f,-0.388901f,-6.39659e-016f},{-0.943633f,-0.330994f,-1.23724e-015f}, +{-0.948083f,-0.27405f,0.161356f},{-0.962377f,-0.271719f,3.07701e-011f},{-0.977365f,-0.211559f,2.38885e-015f}, +{-0.965354f,-0.208959f,0.156297f},{-0.628743f,-0.604582f,0.489042f},{-0.724627f,-0.606665f,0.326914f}, +{-0.863158f,-0.384819f,0.326914f},{-0.887701f,-0.324213f,0.326914f},{-0.907886f,-0.262431f,0.326914f}, +{-0.929644f,-0.201229f,0.308658f},{-0.543566f,-0.599182f,0.587806f},{-0.668812f,-0.559936f,0.489042f}, +{-0.871136f,-0.188564f,0.453393f},{-0.235646f,-0.226591f,0.945054f},{-0.304634f,-0.335803f,0.891311f}, +{-0.589688f,-0.493693f,0.639168f},{-0.583779f,-0.260264f,0.769067f},{-0.738821f,-0.213561f,0.639168f}, +{-0.790681f,-0.171149f,0.58782f},{-0.517285f,-0.375435f,0.769067f},{-0.490087f,-0.410306f,0.769067f}, +{-0.542092f,-0.338632f,0.769067f},{-0.56431f,-0.300149f,0.769067f},{-0.691102f,-0.149594f,0.707107f}, +{-0.374976f,-0.313934f,0.87226f},{-0.431766f,-0.229651f,0.87226f},{-0.446663f,-0.199134f,0.87226f}, +{-0.574502f,-0.124355f,0.809002f},{-0.207387f,-0.228606f,0.951173f},{-0.277263f,-0.1732f,0.945054f}, +{-0.288626f,-0.153517f,0.945054f},{-0.298584f,-0.133117f,0.945054f},{-0.151564f,-0.0553554f,0.986896f}, +{-0.307074f,-0.112152f,0.945054f},{-0.130587f,-0.0947778f,0.986896f},{-0.13685f,-0.085487f,0.986896f}, +{-0.142459f,-0.075772f,0.986896f},{-0.147374f,-0.0657031f,0.986896f},{4.59728e-015f,2.88772e-015f,1.0f}, +{1.79512e-015f,9.7893e-016f,1.0f},{4.41022e-016f,5.0824e-016f,1.0f},{9.49983e-016f,9.53884e-016f,1.0f}, +{-7.91781e-008f,-2.8918e-008f,1.0f},{-0.871314f,0.46344f,0.161356f},{-0.863158f,0.384819f,0.326914f}, +{-0.834372f,0.443791f,0.326914f},{-0.901374f,0.401856f,0.161356f},{-0.895381f,0.445302f,8.13446e-010f}, +{-0.921284f,0.38889f,9.4659e-016f},{-0.796673f,0.355178f,0.489042f},{-0.770104f,0.409608f,0.489042f}, +{-0.702422f,0.313158f,0.639168f},{-0.907886f,0.262431f,0.326914f},{-0.948083f,0.27405f,0.161356f}, +{-0.929369f,0.201169f,0.309522f},{-0.870535f,0.188434f,0.454599f},{-0.151564f,0.0553554f,0.986896f}, +{-0.307074f,0.112152f,0.945054f},{-0.15501f,0.0448068f,0.986896f},{-0.965371f,0.208962f,0.156188f}, +{-0.962368f,0.27175f,-1.62219e-016f},{-0.977365f,0.211559f,-2.45529e-015f},{-0.927004f,0.338567f,0.161356f}, +{-0.943637f,0.330981f,3.15622e-010f},{-0.469808f,0.135801f,0.87226f},{-0.61403f,0.177489f,0.769067f}, +{-0.574515f,0.124358f,0.808992f},{-6.43103e-016f,5.84572e-016f,1.0f},{-2.4553e-015f,2.03026e-015f,1.0f}, +{-0.431766f,0.229651f,0.87226f},{-0.446663f,0.199134f,0.87226f},{-0.298584f,0.133117f,0.945054f}, +{-0.152759f,0.0330659f,0.98771f},{1.43705e-015f,7.01685e-016f,1.0f},{-0.738821f,0.213561f,0.639168f}, +{-0.691102f,0.149594f,0.707107f},{-0.589688f,0.493693f,0.639168f},{-0.628743f,0.604582f,0.489042f}, +{-0.668812f,0.559936f,0.489042f},{-0.678996f,0.361149f,0.639168f},{-0.235646f,0.226591f,0.945054f}, +{-0.305444f,0.336696f,0.890696f},{-0.352511f,0.338965f,0.87226f},{-0.801521f,0.500692f,0.326914f}, +{-0.837008f,0.52286f,0.161356f},{-0.460725f,0.443021f,0.769067f},{-0.490087f,0.410306f,0.769067f}, +{-0.374976f,0.313934f,0.87226f},{-0.705929f,0.51235f,0.489042f},{-0.622414f,0.451736f,0.639168f}, +{-0.652262f,0.407453f,0.639168f},{-0.739783f,0.462125f,0.489042f},{-0.104942f,0.115679f,0.987727f}, +{-0.207967f,0.229246f,0.950892f},{-0.116309f,0.11184f,0.986896f},{-0.866025f,0.5f,1.57009e-016f}, +{-6.07606e-008f,5.84258e-008f,1.0f},{-5.66367e-008f,6.24316e-008f,1.0f},{-0.798705f,0.579685f,0.161356f}, +{-0.833339f,0.552763f,1.22111e-009f},{-0.75671f,0.633525f,0.161356f},{-0.797438f,0.603401f,8.79779e-016f}, +{-0.758466f,0.651713f,-6.70447e-017f},{-0.711375f,0.684039f,0.161356f},{-0.716504f,0.697583f,3.07702e-011f}, +{-0.66364f,0.731542f,0.156297f},{-0.837955f,0.242217f,0.489042f},{-0.887701f,0.324213f,0.326914f}, +{-0.764842f,0.555108f,0.326914f},{-0.724627f,0.606665f,0.326914f},{-0.681215f,0.655037f,0.326914f}, +{-0.639091f,0.70448f,0.308658f},{-0.79069f,0.171151f,0.587806f},{-0.819325f,0.29924f,0.489042f}, +{-0.59887f,0.660144f,0.453393f},{-0.314057f,0.0907801f,0.945054f},{-0.44313f,0.0959191f,0.891311f}, +{-0.722395f,0.263838f,0.639168f},{-0.517285f,0.375435f,0.769067f},{-0.55436f,0.533057f,0.639168f}, +{-0.54356f,0.599175f,0.58782f},{-0.583779f,0.260264f,0.769067f},{-0.600378f,0.219275f,0.769067f}, +{-0.56431f,0.300149f,0.769067f},{-0.542092f,0.338632f,0.769067f},{-0.475103f,0.523714f,0.707107f}, +{-0.459363f,0.167772f,0.87226f},{-0.414767f,0.259095f,0.87226f},{-0.395786f,0.287254f,0.87226f}, +{-0.394946f,0.435355f,0.809002f},{-0.301672f,0.0652993f,0.951173f},{-0.288626f,0.153517f,0.945054f}, +{-0.277263f,0.1732f,0.945054f},{-0.264575f,0.192023f,0.945054f},{-0.123721f,0.103581f,0.986896f}, +{-0.250663f,0.209858f,0.945054f},{-0.147374f,0.0657031f,0.986896f},{-0.142459f,0.075772f,0.986896f}, +{-0.13685f,0.085487f,0.986896f},{-0.130587f,0.0947778f,0.986896f},{2.50503e-015f,-1.51457e-015f,1.0f}, +{6.36373e-016f,-4.75311e-016f,1.0f},{9.26985e-016f,-2.94184e-016f,1.0f},{1.30108e-015f,-3.45767e-016f,1.0f}, +{-6.46328e-008f,5.41113e-008f,1.0f},{-0.0328513f,0.944483f,0.326914f},{-0.0907435f,0.867527f,0.489042f}, +{-0.0303209f,0.871733f,0.489042f},{-0.170294f,0.972093f,0.161356f},{-0.102669f,0.981541f,0.161356f}, +{-0.103293f,0.994651f,6.83653e-010f},{-0.080008f,0.764894f,0.639168f},{-0.0344869f,0.999405f,-4.77516e-016f}, +{-0.226672f,0.917468f,0.326914f},{-0.236707f,0.958089f,0.161356f},{-0.290467f,0.905442f,0.309522f}, +{-0.239133f,0.970987f,1.70296e-010f},{-0.301719f,0.940516f,0.156188f},{-0.0387014f,0.156646f,0.986896f}, +{-0.0278429f,0.158936f,0.986896f},{-0.0564107f,0.32201f,0.945054f},{-0.305468f,0.952202f,1.19604e-015f}, +{-0.171605f,0.985166f,5.25413e-016f},{-0.215998f,0.673309f,0.707107f},{-0.153305f,0.62051f,0.769067f}, +{-0.184461f,0.746618f,0.639168f},{-0.0508762f,0.486388f,0.87226f},{-0.0340097f,0.32514f,0.945054f}, +{-0.0169997f,0.488746f,0.87226f},{-0.117297f,0.474766f,0.87226f},{-0.17956f,0.559723f,0.808992f}, +{-0.0343058f,0.9863f,0.161356f},{-0.0983164f,0.939926f,0.326914f},{1.84702e-016f,8.4923e-016f,1.0f}, +{5.3061e-016f,3.14148e-015f,1.0f},{0.132707f,0.757531f,0.639168f},{0.209212f,0.846799f,0.489042f}, +{0.150513f,0.859176f,0.489042f},{-0.0477436f,0.148826f,0.98771f},{1.3262e-015f,-8.93678e-016f,1.0f}, +{0.0267338f,0.768603f,0.639168f},{0.0907434f,0.867527f,0.489042f},{0.030321f,0.871733f,0.489042f}, +{-0.0267338f,0.768603f,0.639168f},{0.153305f,0.62051f,0.769067f},{0.110292f,0.62958f,0.769067f}, +{0.0843867f,0.481706f,0.87226f},{0.0784104f,0.317371f,0.945054f},{0.138865f,0.432871f,0.890696f}, +{0.117297f,0.474767f,0.87226f},{0.080008f,0.764894f,0.639168f},{0.0477103f,0.148722f,0.987727f}, +{0.094549f,0.294728f,0.950892f},{0.0387014f,0.156646f,0.986896f},{0.0343058f,0.9863f,0.161356f}, +{0.0328514f,0.944483f,0.326914f},{2.02179e-008f,8.18332e-008f,1.0f},{2.5749e-008f,8.02647e-008f,1.0f}, +{0.0344801f,0.999405f,1.75276e-009f},{0.102669f,0.981541f,0.161356f},{0.10328f,0.994652f,1.28179e-015f}, +{0.170294f,0.972093f,0.161356f},{0.171593f,0.985168f,5.7267e-011f},{0.239168f,0.970978f,-1.14452e-015f}, +{0.236707f,0.958089f,0.161356f},{0.305468f,0.952202f,1.19604e-015f},{-0.272079f,0.848123f,0.454599f}, +{-0.209212f,0.846799f,0.489042f},{-0.163074f,0.930878f,0.326914f},{0.0983163f,0.939926f,0.326914f}, +{0.226672f,0.917468f,0.326914f},{0.163074f,0.930878f,0.326914f},{0.301713f,0.9405f,0.156297f}, +{0.290552f,0.905709f,0.308658f},{-0.247124f,0.770333f,0.587806f},{-0.150513f,0.859176f,0.489042f}, +{0.272267f,0.848708f,0.453393f},{-0.0784104f,0.317371f,0.945054f},{-0.138497f,0.431722f,0.891311f}, +{-0.132707f,0.757531f,0.639168f},{0.0664942f,0.6357f,0.769067f},{0.184461f,0.746618f,0.639168f}, +{0.247121f,0.770324f,0.58782f},{-0.0664942f,0.6357f,0.769067f},{-0.110292f,0.62958f,0.769067f}, +{-0.0222183f,0.638781f,0.769067f},{0.0222183f,0.638781f,0.769067f},{0.215998f,0.673309f,0.707107f}, +{-0.0843867f,0.481706f,0.87226f},{0.0169997f,0.488746f,0.87226f},{0.0508762f,0.486388f,0.87226f}, +{0.179556f,0.559711f,0.809002f},{-0.0942851f,0.293905f,0.951173f},{-0.011364f,0.326716f,0.945054f}, +{0.011364f,0.326716f,0.945054f},{0.0340097f,0.32514f,0.945054f},{0.0278429f,0.158936f,0.986896f}, +{0.0564107f,0.32201f,0.945054f},{-0.0167863f,0.160481f,0.986896f},{-0.00560897f,0.161259f,0.986896f}, +{0.00560897f,0.161259f,0.986896f},{0.0167863f,0.160481f,0.986896f},{-5.91466e-017f,-2.9267e-015f,1.0f}, +{-9.34451e-017f,-7.88771e-016f,1.0f},{2.08722e-016f,-9.49885e-016f,1.0f},{3.51097e-016f,-1.29965e-015f,1.0f}, +{1.45453e-008f,8.30293e-008f,1.0f},{0.837008f,0.52286f,0.161356f},{0.764842f,0.555108f,0.326914f}, +{0.801521f,0.500692f,0.326914f},{0.798705f,0.579685f,0.161356f},{0.833333f,0.552772f,8.13449e-010f}, +{0.797431f,0.60341f,4.1114e-016f},{0.705929f,0.51235f,0.489042f},{0.739783f,0.462125f,0.489042f}, +{0.622414f,0.451736f,0.639168f},{0.681215f,0.655037f,0.326914f},{0.711375f,0.684039f,0.161356f}, +{0.638902f,0.704273f,0.309522f},{0.598457f,0.659689f,0.454599f},{0.123721f,0.103581f,0.986896f}, +{0.250664f,0.209858f,0.945054f},{0.116309f,0.11184f,0.986896f},{0.663652f,0.731554f,0.156188f}, +{0.716527f,0.69756f,2.35065e-015f},{0.75671f,0.633525f,0.161356f},{0.758457f,0.651723f,3.1562e-010f}, +{0.352511f,0.338965f,0.87226f},{0.460725f,0.443021f,0.769067f},{0.394955f,0.435365f,0.808992f}, +{8.27806e-016f,2.64658e-016f,1.0f},{2.98591e-015f,1.11122e-015f,1.0f},{0.414767f,0.259095f,0.87226f}, +{0.395786f,0.287254f,0.87226f},{0.264575f,0.192023f,0.945054f},{0.105015f,0.11576f,0.98771f}, +{7.33106e-016f,-6.65059e-016f,1.0f},{0.55436f,0.533057f,0.639168f},{0.475103f,0.523714f,0.707107f}, +{0.722395f,0.263838f,0.639168f},{0.837955f,0.242217f,0.489042f},{0.819325f,0.29924f,0.489042f}, +{0.652262f,0.407453f,0.639168f},{0.314057f,0.0907802f,0.945054f},{0.44431f,0.0961744f,0.890696f}, +{0.469808f,0.135801f,0.87226f},{0.834372f,0.443791f,0.326914f},{0.871314f,0.46344f,0.161356f}, +{0.61403f,0.177489f,0.769067f},{0.600378f,0.219275f,0.769067f},{0.459363f,0.167772f,0.87226f}, +{0.796673f,0.355178f,0.489042f},{0.702422f,0.313158f,0.639168f},{0.678996f,0.361149f,0.639168f}, +{0.770104f,0.409608f,0.489042f},{0.152652f,0.0330429f,0.987727f},{0.302516f,0.0654821f,0.950892f}, +{0.15501f,0.0448068f,0.986896f},{0.866025f,0.5f,1.11024e-015f},{8.09785e-008f,2.34074e-008f,1.0f}, +{8.23857e-008f,1.78331e-008f,1.0f},{0.901374f,0.401856f,0.161356f},{0.895376f,0.445311f,1.22111e-009f}, +{0.927004f,0.338567f,0.161356f},{0.921279f,0.388901f,-2.25333e-015f},{0.943633f,0.330994f,-1.1333e-015f}, +{0.948083f,0.27405f,0.161356f},{0.962377f,0.271719f,3.07706e-011f},{0.977365f,0.211559f,-6.64333e-017f}, +{0.965354f,0.208959f,0.156297f},{0.628743f,0.604582f,0.489042f},{0.724627f,0.606665f,0.326914f}, +{0.863158f,0.384819f,0.326914f},{0.887701f,0.324213f,0.326914f},{0.907886f,0.262431f,0.326914f}, +{0.929644f,0.201229f,0.308658f},{0.543566f,0.599182f,0.587806f},{0.668812f,0.559936f,0.489042f}, +{0.871136f,0.188564f,0.453393f},{0.235646f,0.226591f,0.945054f},{0.304634f,0.335803f,0.891311f}, +{0.589688f,0.493693f,0.639168f},{0.583779f,0.260264f,0.769067f},{0.738821f,0.213561f,0.639168f}, +{0.790681f,0.171149f,0.58782f},{0.517285f,0.375435f,0.769067f},{0.490087f,0.410306f,0.769067f}, +{0.542092f,0.338632f,0.769067f},{0.56431f,0.300149f,0.769067f},{0.691102f,0.149594f,0.707107f}, +{0.374976f,0.313934f,0.87226f},{0.431766f,0.229651f,0.87226f},{0.446663f,0.199134f,0.87226f}, +{0.574502f,0.124355f,0.809002f},{0.207387f,0.228606f,0.951173f},{0.277263f,0.1732f,0.945054f}, +{0.288626f,0.153517f,0.945054f},{0.298584f,0.133117f,0.945054f},{0.151564f,0.0553554f,0.986896f}, +{0.307074f,0.112152f,0.945054f},{0.130587f,0.0947778f,0.986896f},{0.13685f,0.085487f,0.986896f}, +{0.142459f,0.075772f,0.986896f},{0.147374f,0.0657031f,0.986896f},{-4.59728e-015f,-2.88772e-015f,1.0f}, +{-1.79512e-015f,-9.7893e-016f,1.0f},{-4.41022e-016f,-5.0824e-016f,1.0f},{-9.49983e-016f,-9.53884e-016f,1.0f}, +{7.91781e-008f,2.8918e-008f,1.0f},{3.46945e-018f,0.0f,-1.0f},{2.38524e-018f,0.0f,-1.0f}, +{1.95156e-018f,0.0f,-1.0f},{-5.42101e-019f,0.0f,-1.0f},{-4.33681e-019f,0.0f,-1.0f}, +{2.60209e-018f,0.0f,-1.0f},{-2.98156e-018f,0.0f,-1.0f},{-1.73472e-018f,0.0f,-1.0f}, +{1.73472e-018f,0.0f,-1.0f},{-1.6263e-019f,0.0f,-1.0f},{-7.70988e-019f,0.0f,-1.0f}, +{-3.46945e-018f,0.0f,-1.0f},{-2.60209e-018f,0.0f,-1.0f},{-2.20326e-031f,-1.17145e-015f,-1.0f}, +{-2.03378e-031f,-1.17145e-015f,-1.0f},{-1.95674e-031f,-1.17145e-015f,-1.0f},{-2.00297e-031f,-1.17145e-015f,-1.0f}, +{-1.57156e-031f,-1.17145e-015f,-1.0f},{-1.77186e-031f,-1.17145e-015f,-1.0f},{-1.89512e-031f,-1.17145e-015f,-1.0f}, +{-2.80415e-031f,-1.17145e-015f,-1.0f},{-2.39586e-031f,-1.17145e-015f,-1.0f},{-2.31112e-031f,-1.17145e-015f,-1.0f}, +{-1.91052e-031f,-1.17145e-015f,-1.0f},{-1.52534e-031f,-1.17145e-015f,-1.0f},{-2.77255e-031f,-1.17145e-015f,-1.0f}, +{-1.92514e-031f,-1.17145e-015f,-1.0f},{-2.11003e-031f,-1.17145e-015f,-1.0f},{-1.83349e-031f,-1.17145e-015f,-1.0f}, +{-2.09541e-031f,-1.17145e-015f,-1.0f},{-1.81808e-031f,-1.17145e-015f,-1.0f},{-2.0646e-031f,-1.17145e-015f,-1.0f}, +{-1.78726e-031f,-1.17145e-015f,-1.0f},{-2.51141e-031f,-1.17145e-015f,-1.0f},{-2.41897e-031f,-1.17145e-015f,-1.0f}, +{-2.65008e-031f,-1.17145e-015f,-1.0f},{-1.67941e-031f,-1.17145e-015f,-1.0f},{-2.18786e-031f,-1.17145e-015f,-1.0f}, +{-2.25719e-031f,-1.17145e-015f,-1.0f},{-1.75645e-031f,-1.17145e-015f,-1.0f},{-1.74104e-031f,-1.17145e-015f,-1.0f}, +{-1.38667e-031f,-1.17145e-015f,-1.0f},{-1.43289e-031f,-1.17145e-015f,-1.0f},{-1.41748e-031f,-1.17145e-015f,-1.0f}, +{-2.94282e-031f,-1.17145e-015f,-1.0f},{-2.32652e-031f,-1.17145e-015f,-1.0f},{-2.60386e-031f,-1.17145e-015f,-1.0f}, +{-1.37126e-031f,-1.17145e-015f,-1.0f},{-2.26489e-031f,-1.17145e-015f,-1.0f},{-2.24949e-031f,-1.17145e-015f,-1.0f}, +{-1.50993e-031f,-1.17145e-015f,-1.0f},{-1.47911e-031f,-1.17145e-015f,-1.0f},{-2.38815e-031f,-1.17145e-015f,-1.0f}, +{-2.15704e-031f,-1.17145e-015f,-1.0f},{-2.11082e-031f,-1.17145e-015f,-1.0f},{-2.12623e-031f,-1.17145e-015f,-1.0f}, +{-3.23556e-031f,-1.17145e-015f,-1.0f},{-2.36504e-031f,-1.17145e-015f,-1.0f},{-2.4883e-031f,-1.17145e-015f,-1.0f}, +{-2.14934e-031f,-1.17145e-015f,-1.0f},{-2.37275e-031f,-1.17145e-015f,-1.0f},{-2.71171e-031f,-1.17145e-015f,-1.0f}, +{-1.72563e-031f,-1.17145e-015f,-1.0f},{-1.87971e-031f,-1.17145e-015f,-1.0f},{-2.66549e-031f,-1.17145e-015f,-1.0f}, +{-2.51912e-031f,-1.17145e-015f,-1.0f},{-3.0969e-031f,-1.17145e-015f,-1.0f},{-2.76564e-031f,-1.17145e-015f,-1.0f}, +{-2.21867e-031f,-1.17145e-015f,-1.0f},{-1.55615e-031f,-1.17145e-015f,-1.0f},{-3.26638e-031f,-1.17145e-015f,-1.0f}, +{-2.98904e-031f,-1.17145e-015f,-1.0f},{-2.74252e-031f,-1.17145e-015f,-1.0f},{-1.46371e-031f,-1.17145e-015f,-1.0f}, +{-3.03527e-031f,-1.17145e-015f,-1.0f},{-2.96593e-031f,-1.17145e-015f,-1.0f},{-1.60237e-031f,-1.17145e-015f,-1.0f}, +{-2.68089e-031f,-1.17145e-015f,-1.0f},{-3.18934e-031f,-1.17145e-015f,-1.0f},{-2.81956e-031f,-1.17145e-015f,-1.0f}, +{-3.20475e-031f,-1.17145e-015f,-1.0f},{-2.41126e-031f,-1.17145e-015f,-1.0f},{-2.55763e-031f,-1.17145e-015f,-1.0f}, +{-1.54074e-031f,-1.17145e-015f,-1.0f},{-1.4483e-031f,-1.17145e-015f,-1.0f},{-1.35585e-031f,-1.17145e-015f,-1.0f}, +{-3.05838e-031f,-1.17145e-015f,-1.0f},{-2.58845e-031f,-1.17145e-015f,-1.0f},{-1.69482e-031f,-1.17145e-015f,-1.0f}, +{-1.49452e-031f,-1.17145e-015f,-1.0f},{-2.69551e-031f,-1.17145e-015f,-1.0f},{-3.92278e-031f,-1.17145e-015f,-1.0f}, +{-3.2802e-031f,-1.17145e-015f,-1.0f},{-1.71023e-031f,-1.17145e-015f,-1.0f},{-1.58697e-031f,-1.17145e-015f,-1.0f}, +{-2.64238e-031f,-1.17145e-015f,-1.0f},{-2.45749e-031f,-1.17145e-015f,-1.0f},{-2.54223e-031f,-1.17145e-015f,-1.0f}, +{-1.80267e-031f,-1.17145e-015f,-1.0f},{-1.63319e-031f,-1.17145e-015f,-1.0f},{-2.01837e-031f,-1.17145e-015f,-1.0f}, +{-2.17245e-031f,-1.17145e-015f,-1.0f},{-2.04919e-031f,-1.17145e-015f,-1.0f},{-2.2803e-031f,-1.17145e-015f,-1.0f}, +{-1.94134e-031f,-1.17145e-015f,-1.0f},{-2.14163e-031f,-1.17145e-015f,-1.0f},{-1.98756e-031f,-1.17145e-015f,-1.0f}, +{-2.23408e-031f,-1.17145e-015f,-1.0f},{-2.50371e-031f,-1.17145e-015f,-1.0f},{-2.44208e-031f,-1.17145e-015f,-1.0f}, +{-1.8643e-031f,-1.17145e-015f,-1.0f},{-1.97215e-031f,-1.17145e-015f,-1.0f},{-3.12001e-031f,-1.17145e-015f,-1.0f}, +{-2.99833e-031f,-1.17145e-015f,-1.0f},{-2.57304e-031f,-1.17145e-015f,-1.0f},{-2.6963e-031f,-1.17145e-015f,-1.0f}, +{-2.47289e-031f,-1.17145e-015f,-1.0f},{-2.47369e-031f,-1.17145e-015f,-1.0f},{-3.32959e-031f,-1.17145e-015f,-1.0f}, +{-2.01679e-031f,-1.17145e-015f,-1.0f},{-3.32721e-031f,-1.17145e-015f,-1.0f},{-2.62697e-031f,-1.17145e-015f,-1.0f}, +{-4.06836e-031f,-1.17145e-015f,-1.0f},{-2.87428e-031f,-1.17145e-015f,-1.0f},{-2.64929e-031f,-1.17145e-015f,-1.0f}, +{-1.664e-031f,-1.17145e-015f,-1.0f},{-3.01215e-031f,-1.17145e-015f,-1.0f},{-2.10232e-031f,-1.17145e-015f,-1.0f}, +{-2.94973e-031f,-1.17145e-015f,-1.0f},{-3.87656e-031f,-1.17145e-015f,-1.0f},{-3.62686e-031f,-1.17145e-015f,-1.0f}, +{-2.21097e-031f,-1.17145e-015f,-1.0f},{-2.61156e-031f,-1.17145e-015f,-1.0f},{-3.06608e-031f,-1.17145e-015f,-1.0f}, +{-3.08149e-031f,-1.17145e-015f,-1.0f},{-3.05067e-031f,-1.17145e-015f,-1.0f},{-2.93512e-031f,-1.17145e-015f,-1.0f}, +{-1.96445e-031f,-1.17145e-015f,-1.0f},{-2.95823e-031f,-1.17145e-015f,-1.0f},{-1.61778e-031f,-1.17145e-015f,-1.0f}, +{-2.87349e-031f,-1.17145e-015f,-1.0f},{-2.79645e-031f,-1.17145e-015f,-1.0f},{-2.92741e-031f,-1.17145e-015f,-1.0f}, +{-3.5129e-031f,-1.17145e-015f,-1.0f},{-2.84267e-031f,-1.17145e-015f,-1.0f},{-2.85038e-031f,-1.17145e-015f,-1.0f}, +{-2.34963e-031f,-1.17145e-015f,-1.0f},{-2.2726e-031f,-1.17145e-015f,-1.0f},{-2.02449e-031f,-1.17145e-015f,-1.0f}, +{-2.89819e-031f,-1.17145e-015f,-1.0f},{-3.02145e-031f,-1.17145e-015f,-1.0f},{-2.6562e-031f,-1.17145e-015f,-1.0f}, +{-2.44287e-031f,-1.17145e-015f,-1.0f},{-3.66776e-031f,-1.17145e-015f,-1.0f},{-3.23715e-031f,-1.17145e-015f,-1.0f}, +{-2.31723e-031f,-1.17145e-015f,-1.0f},{-2.20938e-031f,-1.17145e-015f,-1.0f},{-3.99211e-031f,-1.17145e-015f,-1.0f}, +{-2.30262e-031f,-1.17145e-015f,-1.0f},{-2.12702e-031f,-1.17145e-015f,-1.0f},{-2.62006e-031f,-1.17145e-015f,-1.0f}, +{-1.87812e-031f,-1.17145e-015f,-1.0f},{-3.71399e-031f,-1.17145e-015f,-1.0f},{-2.52682e-031f,-1.17145e-015f,-1.0f}, +{-2.98134e-031f,-1.17145e-015f,-1.0f},{-2.77334e-031f,-1.17145e-015f,-1.0f},{-2.44978e-031f,-1.17145e-015f,-1.0f}, +{-2.30341e-031f,-1.17145e-015f,-1.0f},{-1.4406e-031f,-1.17145e-015f,-1.0f},{-2.35734e-031f,-1.17145e-015f,-1.0f}, +{-2.72712e-031f,-1.17145e-015f,-1.0f},{-2.67319e-031f,-1.17145e-015f,-1.0f},{-1.47141e-031f,-1.17145e-015f,-1.0f}, +{-1.34815e-031f,-1.17145e-015f,-1.0f},{-2.54993e-031f,-1.17145e-015f,-1.0f},{-3.28949e-031f,-1.17145e-015f,-1.0f}, +{-3.7363e-031f,-1.17145e-015f,-1.0f},{-1.73175e-031f,-1.17145e-015f,-1.0f},{-2.34034e-031f,-1.17145e-015f,-1.0f}, +{-2.33423e-031f,-1.17145e-015f,-1.0f},{-2.46519e-031f,-1.17145e-015f,-1.0f},{-1.92593e-031f,-1.17145e-015f,-1.0f}, +{-7.67197e-032f,-1.17145e-015f,-1.0f},{-1.6486e-031f,-1.17145e-015f,-1.0f},{-1.84889e-031f,-1.17145e-015f,-1.0f}, +{-7.98012e-032f,-1.17145e-015f,-1.0f},{-1.40208e-031f,-1.17145e-015f,-1.0f},{-2.16475e-031f,-1.17145e-015f,-1.0f}, +{-2.88889e-031f,-1.17145e-015f,-1.0f},{-2.43438e-031f,-1.17145e-015f,-1.0f},{-3.00445e-031f,-1.17145e-015f,-1.0f}, +{-2.38045e-031f,-1.17145e-015f,-1.0f},{-3.22786e-031f,-1.17145e-015f,-1.0f},{-2.78875e-031f,-1.17145e-015f,-1.0f}, +{-2.56534e-031f,-1.17145e-015f,-1.0f},{0.0f,1.17961e-015f,1.0f},{0.0f,1.20737e-015f,1.0f}, +{0.0f,1.19349e-015f,1.0f},{1.38778e-017f,1.19349e-015f,1.0f},{1.04083e-017f,1.19349e-015f,1.0f}, +{-1.38778e-017f,1.16573e-015f,1.0f},{-5.20417e-018f,1.19349e-015f,1.0f},{8.67362e-018f,1.19349e-015f,1.0f}, +{1.38778e-017f,1.16573e-015f,1.0f},{-2.60209e-018f,1.16573e-015f,1.0f},{1.21431e-017f,1.16573e-015f,1.0f}, +{-1.38778e-017f,1.20737e-015f,1.0f},{5.63785e-018f,1.16573e-015f,1.0f},{3.46945e-018f,1.19349e-015f,1.0f}, +{-4.33681e-018f,1.16573e-015f,1.0f},{1.12757e-017f,1.19349e-015f,1.0f},{5.20417e-018f,1.19349e-015f,1.0f}, +{-1.21431e-017f,1.19349e-015f,1.0f},{0.0f,1.16573e-015f,1.0f},{-1.30917e-017f,1.22125e-015f,1.0f}, +{-3.08998e-018f,1.16573e-015f,1.0f},{1.0842e-017f,1.16573e-015f,1.0f},{-1.73472e-018f,1.19349e-015f,1.0f}, +{-5.20417e-018f,1.16573e-015f,1.0f},{-9.21572e-019f,1.16573e-015f,1.0f},{6.93889e-018f,1.16573e-015f,1.0f}, +{6.93889e-018f,1.17961e-015f,1.0f},{6.07153e-018f,1.19349e-015f,1.0f},{-1.30104e-017f,1.16573e-015f,1.0f}, +{-2.27741e-032f,1.19349e-015f,1.0f},{-6.93889e-018f,1.16573e-015f,1.0f},{-1.73472e-018f,1.17961e-015f,1.0f}, +{8.67362e-018f,1.16573e-015f,1.0f},{-1.04083e-017f,1.17961e-015f,1.0f},{-1.38778e-017f,1.15186e-015f,1.0f}, +{-1.04083e-017f,1.16573e-015f,1.0f},{6.93889e-018f,1.20737e-015f,1.0f},{1.04083e-017f,1.17961e-015f,1.0f}, +{1.73472e-018f,1.16573e-015f,1.0f},{-1.67556e-032f,1.20737e-015f,1.0f},{1.21431e-017f,1.19349e-015f,1.0f}, +{-1.21431e-017f,1.17961e-015f,1.0f},{-1.38778e-017f,1.19349e-015f,1.0f},{-1.12757e-017f,1.16573e-015f,1.0f}, +{-3.90313e-018f,1.16573e-015f,1.0f},{-1.73472e-018f,1.16573e-015f,1.0f},{-2.60209e-018f,1.19349e-015f,1.0f}, +{1.14925e-017f,1.22125e-015f,1.0f},{-2.1684e-018f,1.19349e-015f,1.0f},{-6.93889e-018f,1.20737e-015f,1.0f}, +{-6.93889e-018f,1.17961e-015f,1.0f},{4.33681e-018f,1.16573e-015f,1.0f},{-1.17094e-017f,1.16573e-015f,1.0f}, +{-7.88757e-018f,1.16573e-015f,1.0f},{6.93889e-018f,1.19349e-015f,1.0f},{-6.93889e-018f,1.19349e-015f,1.0f}, +{-1.51788e-018f,1.19349e-015f,1.0f},{-1.38778e-017f,1.17961e-015f,1.0f},{0.0f,1.22125e-015f,1.0f}, +{1.38778e-017f,1.20737e-015f,1.0f},{9.97466e-018f,1.19349e-015f,1.0f},{4.33681e-018f,1.19349e-015f,1.0f}, +{1.38778e-017f,1.17961e-015f,1.0f},{1.04083e-017f,1.16573e-015f,1.0f},{1.69482e-032f,1.22125e-015f,1.0f}, +{3.46945e-018f,1.16573e-015f,1.0f},{-2.77556e-017f,1.19349e-015f,1.0f},{6.54816e-032f,1.17961e-015f,1.0f}, +{2.77556e-017f,1.17961e-015f,1.0f},{2.77556e-017f,1.19349e-015f,1.0f},{2.77556e-017f,1.22125e-015f,1.0f}, +{2.77556e-017f,1.16573e-015f,1.0f},{6.6252e-032f,1.19349e-015f,1.0f},{-6.6252e-032f,1.19349e-015f,1.0f}, +{6.47112e-032f,1.16573e-015f,1.0f},{-0.0519993f,-0.998647f,1.21442e-015f},{-5.52964e-012f,-1.0f,1.18424e-015f}, +{2.37905e-016f,-1.0f,1.18424e-015f},{-0.207899f,-0.97815f,1.07201e-015f},{-0.156426f,-0.98769f,1.24943e-015f}, +{-0.207911f,-0.978148f,1.26828e-015f},{-0.156436f,-0.987688f,1.05591e-015f},{-0.104524f,-0.994522f,1.24233e-015f}, +{-0.104542f,-0.99452f,1.04524e-015f},{-0.358363f,-0.933582f,1.14589e-015f},{-0.406729f,-0.913549f,9.49444e-016f}, +{-0.358347f,-0.933588f,1.09983e-015f},{-0.258815f,-0.965927f,1.09287e-015f},{-0.309013f,-0.951058f,1.10648e-015f}, +{-0.258801f,-0.965931f,1.11634e-015f},{-0.54461f,-0.838689f,1.11736e-015f},{-0.499972f,-0.866041f,9.21437e-016f}, +{-0.54463f,-0.838677f,1.11734e-015f},{-0.453965f,-0.891019f,9.34273e-016f},{-0.406714f,-0.913555f,1.12976e-015f}, +{-0.45398f,-0.891012f,1.15409e-015f},{-0.669122f,-0.743152f,7.83812e-016f},{-0.707099f,-0.707115f,8.89729e-016f}, +{-0.669102f,-0.74317f,9.12177e-016f},{-0.587776f,-0.809024f,9.38116e-016f},{-0.629312f,-0.777153f,9.10747e-016f}, +{-0.587756f,-0.809038f,9.58094e-016f},{-0.809001f,-0.587808f,6.81602e-016f},{-0.777125f,-0.629346f,7.29768e-016f}, +{-0.809009f,-0.587797f,6.52585e-016f},{-0.74312f,-0.669158f,7.51169e-016f},{-0.70708f,-0.707134f,8.89753e-016f}, +{-0.743137f,-0.66914f,7.3464e-016f},{-0.891007f,-0.453989f,5.26431e-016f},{-0.913546f,-0.406734f,4.71636e-016f}, +{-0.890991f,-0.454022f,5.04065e-016f},{-0.838665f,-0.544647f,6.44992e-016f},{-0.866024f,-0.500002f,6.16793e-016f}, +{-0.838655f,-0.544663f,6.45011e-016f},{-0.965922f,-0.258835f,3.06522e-016f},{-0.951049f,-0.30904f,3.81226e-016f}, +{-0.965925f,-0.258822f,2.93736e-016f},{-0.933568f,-0.3584f,4.42115e-016f},{-0.913531f,-0.40677f,4.51605e-016f}, +{-0.933581f,-0.358367f,4.24392e-016f},{-0.987684f,-0.156459f,1.77565e-016f},{-0.994523f,-0.104515f,1.23771e-016f}, +{-0.994519f,-0.104553f,1.18657e-016f},{-0.978149f,-0.207904f,2.3595e-016f},{-0.987691f,-0.156421f,1.85239e-016f}, +{-0.978143f,-0.207932f,2.56501e-016f},{-0.998629f,0.052353f,-6.19984e-017f},{-0.99863f,0.052328f,-6.19688e-017f}, +{-1.0f,-3.17207e-017f,3.75648e-032f},{-1.0f,-1.58603e-017f,1.87824e-032f},{-0.998629f,-0.0523531f,5.94153e-017f}, +{-0.99863f,-0.0523281f,6.19689e-017f},{-0.978149f,0.207904f,-2.46208e-016f},{-0.987691f,0.156421f,-1.85239e-016f}, +{-0.978143f,0.207932f,-2.46241e-016f},{-0.994523f,0.104515f,-1.23771e-016f},{-0.994519f,0.104553f,-1.23816e-016f}, +{-0.987684f,0.156459f,-1.85285e-016f},{-0.951055f,0.309021f,-3.65954e-016f},{-0.951049f,0.30904f,-3.96476e-016f}, +{-0.933568f,0.3584f,-4.2443e-016f},{-0.965922f,0.258835f,-3.32066e-016f},{-0.965925f,0.258822f,-3.06506e-016f}, +{-0.913546f,0.406734f,-4.8167e-016f},{-0.890991f,0.454022f,-5.3767e-016f},{-0.891007f,0.453989f,-5.37631e-016f}, +{-0.913531f,0.40677f,-4.81712e-016f},{-0.933581f,0.358367f,-4.24392e-016f},{-0.838655f,0.544663f,-6.45011e-016f}, +{-0.809001f,0.587808f,-6.38096e-016f},{-0.838665f,0.544647f,-6.44992e-016f},{-0.866009f,0.500028f,-5.92152e-016f}, +{-0.866024f,0.500002f,-6.41465e-016f},{-0.777125f,0.629346f,-7.45295e-016f},{-0.74312f,0.669158f,-7.92442e-016f}, +{-0.777137f,0.629331f,-7.45278e-016f},{-0.809009f,0.587797f,-6.96091e-016f},{-0.70708f,0.707134f,-8.37415e-016f}, +{-0.669102f,0.74317f,-8.80091e-016f},{-0.707099f,0.707115f,-9.76958e-016f},{-0.743137f,0.66914f,-9.24491e-016f}, +{-0.669122f,0.743152f,-8.80069e-016f},{-0.629291f,0.777169f,-9.20353e-016f},{-0.587756f,0.809038f,-9.58094e-016f}, +{-0.629312f,0.777153f,-7.66945e-016f},{-0.54461f,0.838689f,-1.15874e-015f},{-0.587776f,0.809023f,-9.58076e-016f}, +{-0.54463f,0.838677f,-9.93193e-016f},{-0.499972f,0.866041f,-8.54666e-016f},{-0.453965f,0.891019f,-1.05518e-015f}, +{-0.49999f,0.866031f,-1.02559e-015f},{-0.406714f,0.913555f,-1.08187e-015f},{-0.45398f,0.891012f,-1.23103e-015f}, +{-0.406729f,0.913549f,-1.26217e-015f},{-0.358347f,0.933588f,-1.10559e-015f},{-0.308997f,0.951063f,-1.12628e-015f}, +{-0.358363f,0.933582f,-1.10558e-015f},{-0.258801f,0.965931f,-1.14389e-015f},{-0.309013f,0.951058f,-1.12628e-015f}, +{-0.258815f,0.965927f,-1.14389e-015f},{-0.207899f,0.97815f,-1.15836e-015f},{-0.156426f,0.98769f,-1.3646e-015f}, +{-0.207911f,0.978148f,-1.15836e-015f},{-0.104524f,0.994522f,-1.17775e-015f},{-0.156436f,0.987688f,-1.16966e-015f}, +{-0.104542f,0.99452f,-9.81457e-016f},{-0.0520121f,0.998646f,-1.18263e-015f},{8.72318e-017f,1.0f,-1.18424e-015f}, +{-0.0519994f,0.998647f,-1.18264e-015f},{-1.19209e-007f,1.0f,-1.18424e-015f},{-0.951055f,-0.309021f,3.65954e-016f}, +{-0.866009f,-0.500028f,5.92152e-016f},{-0.777137f,-0.629331f,7.76331e-016f},{-0.629291f,-0.77717f,8.91592e-016f}, +{-0.49999f,-0.866031f,9.64159e-016f},{-0.308997f,-0.951063f,1.10649e-015f},{-0.0520121f,-0.998646f,1.20806e-015f}, +{0.0f,-1.17614e-015f,-1.0f},{-3.46945e-018f,-1.17614e-015f,-1.0f},{3.46945e-018f,-1.1692e-015f,-1.0f}, +{3.46945e-018f,-1.17267e-015f,-1.0f},{-8.67362e-019f,-1.17961e-015f,-1.0f},{-1.73472e-018f,-1.17267e-015f,-1.0f}, +{3.46945e-018f,-1.17614e-015f,-1.0f},{8.67362e-019f,-1.17267e-015f,-1.0f},{2.60209e-018f,-1.17267e-015f,-1.0f}, +{0.0f,-1.17267e-015f,-1.0f},{2.38524e-018f,-1.17267e-015f,-1.0f},{-3.25261e-018f,-1.16573e-015f,-1.0f}, +{0.0f,-1.1692e-015f,-1.0f},{-3.46945e-018f,-1.17267e-015f,-1.0f},{-1.73472e-018f,-1.17614e-015f,-1.0f}, +{-3.23556e-032f,-1.16573e-015f,-1.0f},{-3.36103e-018f,-1.17267e-015f,-1.0f},{-3.41524e-018f,-1.17267e-015f,-1.0f}, +{1.76183e-018f,-1.17961e-015f,-1.0f},{-1.62741e-032f,-1.17267e-015f,-1.0f},{0.0f,-1.17961e-015f,-1.0f}, +{-3.14419e-018f,-1.17961e-015f,-1.0f},{1.04354e-018f,-1.17961e-015f,-1.0f},{-3.03577e-018f,-1.17961e-015f,-1.0f}, +{-1.73472e-018f,-1.1692e-015f,-1.0f},{1.63223e-032f,-1.17614e-015f,-1.0f},{2.60209e-018f,-1.1692e-015f,-1.0f}, +{1.73472e-018f,-1.17961e-015f,-1.0f},{3.46945e-018f,-1.16573e-015f,-1.0f},{1.40946e-018f,-1.17267e-015f,-1.0f}, +{2.60209e-018f,-1.17961e-015f,-1.0f},{-3.46945e-018f,-1.16573e-015f,-1.0f},{-2.60209e-018f,-1.17267e-015f,-1.0f}, +{1.95156e-018f,-1.17961e-015f,-1.0f},{3.03577e-018f,-1.17267e-015f,-1.0f},{1.73472e-018f,-1.17267e-015f,-1.0f}, +{1.30104e-018f,-1.17267e-015f,-1.0f},{8.67362e-019f,-1.17614e-015f,-1.0f},{-2.1684e-018f,-1.17267e-015f,-1.0f}, +{1.30104e-018f,-1.17614e-015f,-1.0f},{-1.51788e-018f,-1.17961e-015f,-1.0f},{8.67362e-019f,-1.16573e-015f,-1.0f}, +{1.95156e-018f,-1.17267e-015f,-1.0f},{2.1684e-018f,-1.17961e-015f,-1.0f},{1.58565e-018f,-1.16573e-015f,-1.0f}, +{-8.13705e-033f,-1.17267e-015f,-1.0f},{3.06626e-018f,-1.17267e-015f,-1.0f},{-3.46945e-018f,-1.1692e-015f,-1.0f}, +{1.84314e-018f,-1.17267e-015f,-1.0f},{3.46945e-018f,-1.17961e-015f,-1.0f},{0.0f,-1.16573e-015f,-1.0f}, +{6.93889e-018f,-1.17614e-015f,-1.0f},{-6.5289e-032f,-1.17614e-015f,-1.0f},{6.93889e-018f,-1.17267e-015f,-1.0f}, +{-6.93889e-018f,-1.17267e-015f,-1.0f},{6.47112e-032f,-1.16573e-015f,-1.0f},{-6.54816e-032f,-1.17961e-015f,-1.0f}, +{-6.93889e-018f,-1.17961e-015f,-1.0f},{6.93889e-018f,-1.17961e-015f,-1.0f},{-6.50964e-032f,-1.17267e-015f,-1.0f}, +{-6.93889e-018f,-1.16573e-015f,-1.0f},{8.67362e-019f,-1.17961e-015f,-1.0f},{-2.1684e-018f,-1.17961e-015f,-1.0f}, +{-8.67362e-019f,-1.17267e-015f,-1.0f},{-1.30104e-018f,-1.17267e-015f,-1.0f},{-0.0581517f,-0.998308f,0.0f}, +{-3.49231e-012f,-1.0f,5.38529e-027f},{1.49639e-016f,-1.0f,0.0f},{-0.230535f,-0.973064f,3.60106e-016f}, +{-0.230613f,-0.973045f,3.60099e-016f},{-0.173651f,-0.984807f,1.82226e-016f},{-0.116108f,-0.993237f,1.83786e-016f}, +{-0.173275f,-0.984873f,3.64476e-016f},{-0.11595f,-0.993255f,1.83789e-016f},{-0.396094f,-0.91821f,3.39806e-016f}, +{-0.448811f,-0.893627f,0.0f},{-0.396067f,-0.918222f,3.3981e-016f},{-0.286837f,-0.957979f,3.54524e-016f}, +{-0.342035f,-0.939687f,3.47754e-016f},{-0.286798f,-0.957991f,3.54528e-016f},{-0.597145f,-0.802133f,5.93698e-016f}, +{-0.549498f,-0.835495f,6.18391e-016f},{-0.597158f,-0.802124f,5.93691e-016f},{-0.499989f,-0.866032f,0.0f}, +{-0.448787f,-0.893639f,6.61426e-016f},{-0.500008f,-0.866021f,6.40984e-016f},{-0.72737f,-0.686246f,5.07924e-016f}, +{-0.766042f,-0.642791f,4.75761e-016f},{-0.727358f,-0.686259f,5.07933e-016f},{-0.642785f,-0.766046f,5.66988e-016f}, +{-0.686238f,-0.727377f,5.38367e-016f},{-0.642773f,-0.766057f,5.66996e-016f},{-0.866013f,-0.500021f,7.40179e-016f}, +{-0.835473f,-0.549532f,4.06735e-016f},{-0.866023f,-0.500004f,3.70077e-016f},{-0.802106f,-0.597181f,4.42003e-016f}, +{-0.802121f,-0.597162f,4.41988e-016f},{-0.835486f,-0.549512f,4.0672e-016f},{-0.939696f,-0.342012f,2.5314e-016f}, +{-0.957994f,-0.28679f,2.12267e-016f},{-0.939685f,-0.342042f,2.53162e-016f},{-0.918216f,-0.396079f,2.93157e-016f}, +{-0.918208f,-0.396098f,2.93171e-016f},{-0.893624f,-0.448817f,3.32191e-016f},{-0.993236f,-0.116116f,8.5943e-017f}, +{-0.984803f,-0.173675f,1.28545e-016f},{-0.99324f,-0.11608f,8.59167e-017f},{-0.973038f,-0.230643f,1.7071e-016f}, +{-0.957982f,-0.286828f,2.12296e-016f},{-0.973049f,-0.2306f,1.70678e-016f},{-1.0f,-1.19209e-007f,8.82326e-023f}, +{-0.998307f,0.058159f,-4.30463e-017f},{-0.998309f,0.0581378f,-4.30306e-017f},{-0.998309f,-0.0581377f,4.30305e-017f}, +{-1.0f,-2.65488e-017f,1.96501e-032f},{-0.998307f,-0.0581591f,4.30464e-017f},{-0.984803f,0.173675f,-1.28545e-016f}, +{-0.973038f,0.230643f,-1.7071e-016f},{-0.984811f,0.173633f,-1.28514e-016f},{-0.99324f,0.11608f,-8.59168e-017f}, +{-0.993236f,0.116116f,0.0f},{-0.918208f,0.396098f,0.0f},{-0.939696f,0.342012f,-5.0628e-016f}, +{-0.939685f,0.342042f,0.0f},{-0.957993f,0.28679f,0.0f},{-0.973049f,0.2306f,-1.70678e-016f}, +{-0.957982f,0.286828f,0.0f},{-0.866013f,0.500021f,-7.40179e-016f},{-0.893631f,0.448803f,0.0f}, +{-0.893624f,0.448816f,-6.64382e-016f},{-0.918216f,0.396079f,-5.86315e-016f},{-0.802121f,0.597162f,0.0f}, +{-0.835486f,0.549512f,0.0f},{-0.802106f,0.597181f,0.0f},{-0.866023f,0.500004f,0.0f}, +{-0.835473f,0.549532f,0.0f},{-0.727369f,0.686246f,0.0f},{-0.766041f,0.642791f,0.0f}, +{-0.727358f,0.686258f,0.0f},{-0.766027f,0.642808f,-9.51547e-016f},{-0.642773f,0.766057f,0.0f}, +{-0.686238f,0.727377f,0.0f},{-0.686227f,0.727388f,-1.07675e-015f},{-0.597145f,0.802133f,0.0f}, +{-0.642785f,0.766046f,0.0f},{-0.597158f,0.802124f,0.0f},{-0.549498f,0.835495f,0.0f}, +{-0.499989f,0.866032f,0.0f},{-0.549511f,0.835486f,0.0f},{-0.448787f,0.893639f,0.0f}, +{-0.500008f,0.866021f,0.0f},{-0.448811f,0.893627f,0.0f},{-0.396067f,0.918221f,0.0f}, +{-0.342011f,0.939696f,0.0f},{-0.396094f,0.91821f,0.0f},{-0.286798f,0.957991f,0.0f}, +{-0.342035f,0.939687f,0.0f},{-0.286837f,0.957979f,0.0f},{-0.230613f,0.973045f,0.0f}, +{-0.173651f,0.984807f,0.0f},{-0.230535f,0.973064f,0.0f},{-0.173275f,0.984873f,0.0f}, +{-0.116108f,0.993237f,0.0f},{-0.11595f,0.993255f,0.0f},{-0.0581642f,0.998307f,0.0f}, +{-7.72329e-017f,1.0f,0.0f},{-0.0581517f,0.998308f,0.0f},{-0.984811f,-0.173632f,1.28514e-016f}, +{-0.893631f,-0.448803f,3.32181e-016f},{-0.766027f,-0.642808f,4.75773e-016f},{-0.686227f,-0.727388f,5.38375e-016f}, +{-0.549511f,-0.835486f,6.18384e-016f},{-0.342011f,-0.939696f,3.47757e-016f},{-0.0581641f,-0.998307f,9.2362e-017f}, +{0.0f,1.17441e-015f,1.0f},{0.0f,1.17094e-015f,1.0f},{0.0f,1.17614e-015f,1.0f}, +{0.0f,1.17267e-015f,1.0f},{0.0f,1.17874e-015f,1.0f},{-6.93889e-018f,1.17094e-015f,1.0f}, +{0.0f,1.17571e-015f,1.0f},{0.0f,1.17354e-015f,1.0f},{6.51446e-032f,1.17354e-015f,1.0f}, +{6.49038e-032f,1.1692e-015f,1.0f},{0.0f,1.17788e-015f,1.0f},{-6.93889e-018f,1.17614e-015f,1.0f}, +{0.0f,1.1692e-015f,1.0f},{0.0f,1.16747e-015f,1.0f},{0.0f,1.17701e-015f,1.0f}, +{0.0f,1.17007e-015f,1.0f},{-3.46945e-018f,1.17961e-015f,1.0f},{3.46945e-018f,1.17267e-015f,1.0f}, +{6.93889e-018f,1.17267e-015f,1.0f},{-3.46945e-018f,1.17267e-015f,1.0f},{0.0f,1.17181e-015f,1.0f}, +{3.46945e-018f,1.17614e-015f,1.0f},{-3.46945e-018f,1.17614e-015f,1.0f},{0.0f,1.17116e-015f,1.0f}, +{0.0f,1.17462e-015f,1.0f},{0.0f,1.17311e-015f,1.0f},{0.0f,1.17213e-015f,1.0f}, +{0.0f,1.17332e-015f,1.0f},{0.0f,1.16834e-015f,1.0f},{0.0f,1.16912e-015f,1.0f}, +{0.0f,1.17528e-015f,1.0f},{0.0f,1.17831e-015f,1.0f},{-3.46945e-018f,1.1692e-015f,1.0f}, +{0.0f,1.17353e-015f,1.0f},{6.93889e-018f,1.17311e-015f,1.0f},{3.46945e-018f,1.1692e-015f,1.0f}, +{-3.46945e-018f,1.17353e-015f,1.0f},{-1.62741e-032f,1.17267e-015f,1.0f},{3.46945e-018f,1.17332e-015f,1.0f}, +{3.46945e-018f,1.17213e-015f,1.0f},{-3.46945e-018f,1.17831e-015f,1.0f},{-3.46945e-018f,1.17462e-015f,1.0f}, +{3.46945e-018f,1.17788e-015f,1.0f},{-3.46945e-018f,1.16747e-015f,1.0f},{-3.25482e-032f,1.17267e-015f,1.0f}, +{-3.46945e-018f,1.17571e-015f,1.0f},{3.24519e-032f,1.1692e-015f,1.0f},{-3.46945e-018f,1.17788e-015f,1.0f}, +{-1.63223e-032f,1.17614e-015f,1.0f},{-3.25964e-032f,1.17441e-015f,1.0f},{-3.46945e-018f,1.17701e-015f,1.0f}, +{-3.46945e-018f,1.17094e-015f,1.0f},{-3.46945e-018f,1.17181e-015f,1.0f},{-1.6226e-032f,1.1692e-015f,1.0f}, +{3.25482e-032f,1.17267e-015f,1.0f},{-0.0407198f,0.623367f,-0.780869f},{4.8247e-017f,0.624695f,-0.780869f}, +{-0.0408655f,0.623357f,-0.780869f},{-0.0815543f,0.619349f,-0.780869f},{-0.121867f,0.612693f,-0.780869f}, +{-0.0815307f,0.619352f,-0.780869f},{-0.200788f,0.591547f,-0.780869f},{-0.200806f,0.591541f,-0.780869f}, +{-0.239048f,0.577148f,-0.780869f},{-0.161674f,0.603411f,-0.780869f},{-0.161672f,0.603412f,-0.780869f}, +{-0.121853f,0.612696f,-0.780869f},{-0.312348f,0.541002f,-0.780869f},{-0.347061f,0.519415f,-0.780869f}, +{-0.362343f,0.508873f,-0.780869f},{-0.276303f,0.560268f,-0.780869f},{-0.469671f,0.41189f,-0.780869f}, +{-0.49103f,0.386178f,-0.780869f},{-0.452096f,0.431107f,-0.780869f},{-0.441727f,0.441726f,-0.780869f}, +{-0.409076f,0.472124f,-0.780869f},{-0.411889f,0.469671f,-0.780869f},{-0.603411f,0.161675f,-0.780869f}, +{-0.613402f,0.118247f,-0.780869f},{-0.599383f,0.176024f,-0.780869f},{-0.577143f,0.239059f,-0.780869f}, +{-0.579937f,0.232201f,-0.780869f},{-0.560271f,0.276297f,-0.780869f},{-0.624695f,-7.81403e-016f,-0.780869f}, +{-0.621866f,0.0593872f,-0.780869f},{-0.623358f,0.0408508f,-0.780869f},{-0.612694f,0.121862f,-0.780869f}, +{-0.619352f,0.0815295f,-0.780869f},{-0.619352f,-0.0815289f,-0.780869f},{-0.623278f,-0.0420472f,-0.780869f}, +{-0.619032f,-0.0839247f,-0.780869f},{-0.624695f,-7.85004e-016f,-0.780869f},{-0.603409f,-0.161685f,-0.780869f}, +{-0.602152f,-0.166305f,-0.780869f},{-0.591542f,-0.200803f,-0.780869f},{-0.611979f,-0.125401f,-0.780869f}, +{-0.612693f,-0.121866f,-0.780869f},{-0.574359f,-0.245674f,-0.780869f},{-0.55652f,-0.283777f,-0.780869f}, +{-0.560272f,-0.276296f,-0.780869f},{-0.577143f,-0.23906f,-0.780869f},{-0.589592f,-0.206458f,-0.780869f}, +{-0.541001f,-0.312349f,-0.780869f},{-0.536156f,-0.320594f,-0.780869f},{-0.519411f,-0.347068f,-0.780869f}, +{-0.495597f,-0.3803f,-0.780869f},{-0.513359f,-0.355958f,-0.780869f},{-0.460896f,-0.421686f,-0.780869f}, +{-0.469665f,-0.411897f,-0.780869f},{-0.488234f,-0.389707f,-0.780869f},{-0.400085f,-0.479767f,-0.780869f}, +{-0.411883f,-0.469676f,-0.780869f},{-0.431469f,-0.45175f,-0.780869f},{-0.441721f,-0.441731f,-0.780869f}, +{-0.366885f,-0.505608f,-0.780869f},{-0.347057f,-0.519418f,-0.780869f},{-0.380283f,-0.49561f,-0.780869f}, +{-0.276286f,-0.560277f,-0.780869f},{-0.312341f,-0.541005f,-0.780869f},{-0.312348f,-0.541002f,-0.780869f}, +{-0.332022f,-0.529155f,-0.780869f},{-0.276253f,-0.560293f,-0.780869f},{-0.295655f,-0.550302f,-0.780869f}, +{-0.257945f,-0.568954f,-0.780869f},{-0.219062f,-0.585026f,-0.780869f},{-0.239077f,-0.577136f,-0.780869f}, +{-0.17919f,-0.598444f,-0.780869f},{-0.200818f,-0.591537f,-0.780869f},{-0.161695f,-0.603406f,-0.780869f}, +{-0.138507f,-0.609147f,-0.780869f},{-0.0968651f,-0.617139f,-0.780869f},{-0.12188f,-0.61269f,-0.780869f}, +{-0.0554646f,-0.622228f,-0.780869f},{-0.0815436f,-0.61935f,-0.780869f},{-0.0408587f,-0.623357f,-0.780869f}, +{-0.0134154f,-0.624551f,-0.780869f},{-1.44741e-016f,-0.624695f,-0.780869f},{-1.32341e-016f,-0.624695f,-0.780869f}, +{-0.121874f,-0.612691f,-0.780869f},{-0.161679f,-0.60341f,-0.780869f},{-0.121867f,-0.612693f,-0.780869f}, +{-0.276294f,-0.560273f,-0.780869f},{-0.161681f,-0.60341f,-0.780869f},{-0.239058f,-0.577144f,-0.780869f}, +{-0.081532f,-0.619352f,-0.780869f},{-0.0815751f,-0.619346f,-0.780869f},{-0.0408495f,-0.623358f,-0.780869f}, +{-0.0406682f,-0.62337f,-0.780869f},{-1.34995e-016f,-0.624695f,-0.780869f},{-1.67499e-016f,-0.624695f,-0.780869f}, +{-0.20067f,-0.591587f,-0.780869f},{-0.200802f,-0.591543f,-0.780869f},{-0.23903f,-0.577156f,-0.780869f}, +{-0.591544f,0.200798f,-0.780869f},{-0.623358f,-0.0408492f,-0.780869f},{-0.525513f,0.337758f,-0.780869f}, +{-0.541f,0.31235f,-0.780869f},{-0.555239f,0.286275f,-0.780869f},{-0.519413f,0.347065f,-0.780869f}, +{-0.495602f,0.380292f,-0.780869f},{-0.441709f,0.441743f,-0.780869f},{-0.411873f,0.469686f,-0.780869f}, +{-0.409092f,0.47211f,-0.780869f},{-0.347044f,0.519427f,-0.780869f},{-0.31233f,0.541012f,-0.780869f}, +{-0.380288f,0.495606f,-0.780869f},{-0.239067f,0.57714f,-0.780869f},{-0.276284f,0.560278f,-0.780869f}, +{-0.312352f,0.540999f,-0.780869f},{5.94472e-017f,0.624695f,-0.780869f},{-0.623357f,0.040871f,-0.780869f}, +{-0.624695f,-7.73092e-016f,-0.780869f},{-0.624695f,-7.89776e-016f,-0.780869f},{-0.621867f,0.0593711f,-0.780869f}, +{-0.613408f,0.118216f,-0.780869f},{-0.619348f,0.0815572f,-0.780869f},{-0.603406f,0.161693f,-0.780869f}, +{-0.612689f,0.121886f,-0.780869f},{-0.599395f,0.175983f,-0.780869f},{-0.579951f,0.232166f,-0.780869f}, +{-0.591537f,0.200819f,-0.780869f},{-0.560263f,0.276314f,-0.780869f},{-0.577134f,0.239082f,-0.780869f}, +{-0.555257f,0.286241f,-0.780869f},{-0.525532f,0.337728f,-0.780869f},{-0.540992f,0.312365f,-0.780869f}, +{-0.519405f,0.347077f,-0.780869f},{-0.491049f,0.386154f,-0.780869f},{-0.495593f,0.380304f,-0.780869f}, +{-0.452119f,0.431082f,-0.780869f},{-0.469657f,0.411906f,-0.780869f},{-0.362366f,0.508856f,-0.780869f}, +{-0.380275f,0.495616f,-0.780869f},{0.998775f,-0.049491f,0.0f},{1.0f,1.2919e-016f,0.0f}, +{1.0f,1.37264e-016f,0.0f},{0.977407f,-0.211368f,0.0f},{0.98727f,-0.159053f,0.0f}, +{0.977365f,-0.211559f,0.0f},{0.994856f,-0.101296f,0.0f},{0.994335f,-0.106287f,0.0f}, +{0.9986f,-0.0529056f,0.0f},{0.964773f,-0.263083f,0.0f},{0.962355f,-0.271796f,0.0f}, +{0.949405f,-0.314055f,0.0f},{0.866021f,-0.500008f,0.0f},{0.861571f,-0.507638f,0.0f}, +{0.887366f,-0.461066f,0.0f},{0.921279f,-0.388903f,0.0f},{0.910645f,-0.413189f,0.0f}, +{0.931345f,-0.364138f,0.0f},{0.734799f,-0.678285f,0.0f},{0.758453f,-0.651728f,0.0f}, +{0.716553f,-0.697532f,0.0f},{0.802733f,-0.596339f,0.0f},{0.833328f,-0.552779f,0.0f}, +{0.797427f,-0.603416f,0.0f},{0.541517f,-0.84069f,0.0f},{0.530443f,-0.847721f,0.0f}, +{0.574807f,-0.818289f,0.0f},{0.609678f,-0.792649f,0.0f},{0.658536f,-0.752549f,0.0f}, +{0.288713f,-0.957416f,0.0f},{0.339268f,-0.94069f,0.0f},{0.305468f,-0.952202f,0.0f}, +{0.437338f,-0.899297f,0.0f},{0.467738f,-0.883867f,0.0f},{0.388834f,-0.921308f,0.0f}, +{0.132754f,-0.991149f,0.0f},{0.10328f,-0.994652f,0.0f},{0.0798119f,-0.99681f,0.0f}, +{0.237346f,-0.971425f,0.0f},{0.239168f,-0.970978f,0.0f},{0.185314f,-0.982679f,0.0f}, +{-0.171605f,-0.985166f,0.0f},{-0.132709f,-0.991155f,0.0f},{-0.103293f,-0.994651f,0.0f}, +{-0.0266126f,-0.999646f,0.0f},{0.0266303f,-0.999645f,0.0f},{-0.0344868f,-0.999405f,0.0f}, +{-0.339241f,-0.940699f,0.0f},{-0.388834f,-0.921308f,0.0f},{-0.388825f,-0.921312f,0.0f}, +{-0.237326f,-0.97143f,0.0f},{-0.239133f,-0.970987f,0.0f},{-0.288698f,-0.95742f,0.0f}, +{-0.467738f,-0.883867f,0.0f},{-0.484556f,-0.87476f,0.0f},{-0.437309f,-0.899311f,0.0f}, +{-0.617538f,-0.786541f,0.0f},{-0.609678f,-0.792649f,0.0f},{-0.658522f,-0.752561f,0.0f}, +{-0.541517f,-0.84069f,0.0f},{-0.574801f,-0.818293f,0.0f},{-0.53043f,-0.847729f,0.0f}, +{-0.716559f,-0.697526f,0.0f},{-0.758457f,-0.651723f,0.0f},{-0.734782f,-0.678303f,0.0f}, +{-0.697641f,-0.716448f,0.0f},{-0.797431f,-0.60341f,0.0f},{-0.833335f,-0.552769f,0.0f}, +{-0.802718f,-0.596359f,0.0f},{-0.769841f,-0.638236f,0.0f},{-0.861559f,-0.507658f,0.0f}, +{-0.833319f,-0.552792f,0.0f},{-0.866023f,-0.500004f,0.0f},{-0.89538f,-0.445304f,0.0f}, +{-0.887356f,-0.461084f,0.0f},{-0.910637f,-0.413206f,0.0f},{-0.921283f,-0.388894f,0.0f}, +{-0.931337f,-0.364157f,0.0f},{-0.943659f,-0.330919f,0.0f},{-0.949398f,-0.314075f,0.0f}, +{-0.962422f,-0.27156f,0.0f},{-0.964768f,-0.263101f,0.0f},{-0.977403f,-0.211384f,0.0f}, +{-0.977365f,-0.211559f,0.0f},{-0.987859f,-0.155356f,0.0f},{-0.987268f,-0.159066f,0.0f}, +{-0.994333f,-0.106314f,0.0f},{-0.994856f,-0.101296f,0.0f},{-0.998775f,-0.049491f,0.0f}, +{-0.998601f,-0.0528865f,0.0f},{-0.305468f,-0.952202f,0.0f},{-0.185276f,-0.982686f,0.0f}, +{-0.079772f,-0.996813f,0.0f},{0.03448f,-0.999405f,0.0f},{0.171593f,-0.985168f,0.0f}, +{0.388857f,-0.921298f,0.0f},{0.484577f,-0.874749f,0.0f},{0.617547f,-0.786534f,0.0f}, +{0.697657f,-0.716432f,0.0f},{0.769857f,-0.638216f,0.0f},{0.833333f,-0.552771f,0.0f}, +{0.895373f,-0.445318f,0.0f},{0.943631f,-0.330998f,0.0f},{0.987859f,-0.155356f,0.0f}, +{-1.0f,-3.77476e-016f,0.0f},{-0.991435f,-0.130601f,-6.19104e-019f},{-0.99153f,-0.129881f,4.88629e-016f}, +{-0.865926f,-0.500171f,-8.92478e-019f},{-0.866063f,-0.499936f,-3.17394e-017f},{-0.923984f,-0.382431f,-5.0236e-018f}, +{-0.923897f,-0.38264f,-5.01887e-018f},{-0.966265f,-0.257551f,-6.30898e-018f},{-0.965902f,-0.258907f,4.70296e-016f}, +{-0.608898f,-0.793249f,2.51569e-017f},{-0.608701f,-0.7934f,2.51781e-017f},{-0.500177f,-0.865923f,3.67732e-017f}, +{-0.793302f,-0.608828f,-3.85657e-016f},{-0.70708f,-0.707134f,-3.34256e-016f},{-0.707182f,-0.707032f,1.01847e-016f}, +{-0.130461f,-0.991453f,-9.90614e-017f},{-0.130634f,-0.991431f,7.15089e-017f},{-0.258717f,-0.965953f,-5.85053e-017f}, +{-0.258991f,-0.96588f,-1.13773e-016f},{-0.382876f,-0.9238f,2.9328e-017f},{-0.382575f,-0.923924f,1.23656e-016f}, +{0.258717f,-0.965953f,1.33133e-016f},{0.130634f,-0.991431f,1.36399e-016f},{0.258991f,-0.96588f,-1.45574e-016f}, +{4.20972e-017f,-1.0f,-4.25225e-017f},{4.54604e-017f,-1.0f,-4.25225e-017f},{0.130461f,-0.991453f,1.40227e-017f}, +{0.499909f,-0.866078f,4.49026e-016f},{0.500177f,-0.865923f,1.55049e-016f},{0.608701f,-0.7934f,7.79706e-016f}, +{0.382876f,-0.9238f,7.50444e-017f},{0.382576f,-0.923924f,3.75533e-017f},{0.70708f,-0.707134f,2.56512e-016f}, +{0.707182f,-0.707032f,2.34744e-016f},{0.793302f,-0.608828f,4.26281e-016f},{0.608898f,-0.793249f,-1.21382e-016f}, +{0.865926f,-0.500171f,4.61524e-016f},{0.793414f,-0.608682f,-9.08045e-016f},{0.866063f,-0.499936f,-1.12653e-016f}, +{0.923984f,-0.382431f,1.71788e-016f},{0.923898f,-0.38264f,-9.65732e-017f},{0.965902f,-0.258907f,1.47384e-016f}, +{0.991435f,-0.130601f,3.73071e-016f},{0.966265f,-0.257551f,2.10001e-016f},{0.99153f,-0.129881f,1.22154e-016f}, +{1.0f,4.44089e-017f,0.0f},{-0.499909f,-0.866078f,-7.00363e-017f},{-0.793414f,-0.608682f,-3.85722e-016f}, +{-1.0f,-3.55271e-016f,0.0f},{1.38778e-017f,0.0f,-1.0f},{-2.77556e-017f,0.0f,-1.0f}, +{-1.38778e-017f,0.0f,-1.0f},{-0.209488f,-0.470509f,-0.857167f},{-0.302781f,-0.416639f,-0.857167f}, +{2.0793e-011f,0.515038f,-0.857167f},{-0.107041f,-0.503792f,-0.857167f},{-8.71204e-012f,-0.515038f,-0.857167f}, +{-0.382869f,-0.344494f,-0.857167f},{-0.446205f,-0.257227f,-0.857167f},{-0.489955f,-0.158772f,-0.857167f}, +{-0.512244f,-0.0535708f,-0.857167f},{-0.512182f,0.054163f,-0.857167f},{-0.445616f,0.258245f,-0.857167f}, +{-0.489568f,0.159959f,-0.857167f},{-0.302314f,0.416978f,-0.857167f},{-0.382299f,0.345125f,-0.857167f}, +{-0.106823f,0.503838f,-0.857167f},{-0.209119f,0.470674f,-0.857167f},{-5.23815e-016f,0.515038f,-0.857167f}, +{-4.16334e-016f,-1.0f,1.18424e-015f},{-0.20783f,-0.978165f,1.30318e-015f},{-0.207408f,-0.978254f,1.12778e-015f}, +{-0.86521f,-0.50141f,5.93789e-016f},{-0.742274f,-0.670096f,7.38614e-016f},{-0.743379f,-0.66887f,6.87574e-016f}, +{-0.586974f,-0.809606f,9.58766e-016f},{-0.406026f,-0.913862f,1.01459e-015f},{-0.406743f,-0.913543f,1.08185e-015f}, +{-0.994455f,-0.105163f,9.16276e-017f},{-0.994576f,-0.104013f,8.25206e-017f},{-0.994576f,0.104013f,-1.92941e-016f}, +{-0.866353f,-0.499433f,6.65378e-016f},{-0.951298f,-0.308272f,3.87884e-016f},{-0.950548f,-0.310578f,3.92178e-016f}, +{-0.950548f,0.310578f,-2.2169e-016f},{-0.86521f,0.50141f,-5.89149e-016f},{-0.866353f,0.499433f,-4.58297e-016f}, +{-0.951298f,0.308272f,-3.65067e-016f},{-0.994455f,0.105163f,3.82381e-017f},{-0.742274f,0.670096f,-7.82968e-016f}, +{-0.586974f,0.809606f,-1.0039e-015f},{-0.587881f,0.808947f,-1.05167e-015f},{-0.743379f,0.66887f,-8.52637e-016f}, +{-0.406743f,0.913543f,-9.8396e-016f},{-0.406026f,0.913862f,-1.10276e-015f},{-0.207408f,0.978254f,-1.31418e-015f}, +{-0.20783f,0.978165f,-1.07945e-015f},{1.11022e-016f,1.0f,-1.18424e-015f},{-0.587881f,-0.808947f,1.0015e-015f}, +{0.0f,0.515038f,-0.857167f},{-8.71183e-012f,-0.515038f,-0.857167f},{-3.77792e-017f,0.515038f,-0.857167f}, +{-8.88178e-016f,-1.0f,1.03621e-015f},{-0.20783f,-0.978165f,1.18915e-015f},{-0.207408f,-0.978254f,8.68864e-016f}, +{-0.86521f,-0.50141f,6.20715e-016f},{-0.742274f,-0.670096f,5.34884e-016f},{-0.743379f,-0.66887f,7.4811e-016f}, +{-0.586974f,-0.809606f,9.2581e-016f},{-0.406026f,-0.913862f,9.46951e-016f},{-0.406743f,-0.913543f,9.4662e-016f}, +{-0.994455f,-0.105163f,2.02034e-016f},{-0.994576f,-0.104013f,3.2862e-016f},{-0.994576f,0.104013f,-8.63697e-017f}, +{-0.951298f,-0.308272f,4.83071e-016f},{-0.950548f,-0.310578f,5.78862e-016f},{-0.950548f,0.310578f,-2.74108e-016f}, +{-0.86521f,0.50141f,-4.47156e-016f},{-0.866353f,0.499433f,-5.98803e-016f},{-0.951298f,0.308272f,-2.31911e-016f}, +{-0.994455f,0.105163f,-2.45591e-018f},{-0.742274f,0.670096f,-7.15151e-016f},{-0.586974f,0.809606f,-8.90323e-016f}, +{-0.587881f,0.808947f,-9.67842e-016f},{-0.743379f,0.66887f,-8.40245e-016f},{-0.406743f,0.913543f,-1.02153e-015f}, +{-0.406026f,0.913862f,-1.22443e-015f},{-0.207408f,0.978254f,-1.05802e-015f},{-0.20783f,0.978165f,-1.06498e-015f}, +{-0.587881f,-0.808947f,9.57986e-016f},{-8.7128e-012f,-0.515038f,-0.857167f},{-6.8535e-016f,0.515038f,-0.857167f}, +{8.88178e-016f,-1.0f,1.18424e-015f},{-0.20783f,-0.978165f,1.15838e-015f},{-0.207408f,-0.978254f,1.15849e-015f}, +{-0.86521f,-0.50141f,4.286e-016f},{-0.742274f,-0.670096f,8.87405e-016f},{-0.743379f,-0.66887f,6.32553e-016f}, +{-0.586974f,-0.809606f,9.15321e-016f},{-0.406026f,-0.913862f,1.08223e-015f},{-0.994455f,-0.105163f,1.16754e-016f}, +{-0.994576f,-0.104013f,1.59983e-016f},{-0.994576f,0.104013f,-3.80152e-017f},{-0.866353f,-0.499433f,5.27324e-016f}, +{-0.951298f,-0.308272f,4.12661e-016f},{-0.950548f,-0.310578f,2.74456e-016f},{-0.950548f,0.310578f,-2.33532e-016f}, +{-0.86521f,0.50141f,-5.96335e-016f},{-0.866353f,0.499433f,-5.68061e-016f},{-0.951298f,0.308272f,-2.59452e-016f}, +{-0.994455f,0.105163f,-4.315e-017f},{-0.742274f,0.670096f,-7.2774e-016f},{-0.586974f,0.809606f,-8.55024e-016f}, +{-0.587881f,0.808947f,-1.02665e-015f},{-0.743379f,0.66887f,-8.66361e-016f},{-0.406743f,0.913543f,-1.10059e-015f}, +{-0.406026f,0.913862f,-1.082e-015f},{-0.207408f,0.978254f,-1.12807e-015f},{-0.20783f,0.978165f,-1.036e-015f}, +{-0.587881f,-0.808947f,9.14474e-016f},{-2.0793e-011f,0.515038f,-0.857167f},{-8.7129e-012f,-0.515038f,-0.857167f}, +{-1.52141e-016f,0.515038f,-0.857167f},{9.4369e-016f,-1.0f,1.18424e-015f},{-0.207408f,-0.978254f,1.18919e-015f}, +{-0.86521f,-0.50141f,6.68012e-016f},{-0.742274f,-0.670096f,6.83675e-016f},{-0.743379f,-0.66887f,7.92101e-016f}, +{-0.406743f,-0.913543f,1.27729e-015f},{-0.994455f,-0.105163f,1.98142e-016f},{-0.994576f,0.104013f,8.65335e-018f}, +{-0.866353f,-0.499433f,6.5557e-016f},{-0.951298f,-0.308272f,5.03928e-016f},{-0.950548f,-0.310578f,2.50076e-016f}, +{-0.950548f,0.310578f,-3.08937e-016f},{-0.86521f,0.50141f,-5.85418e-016f},{-0.866353f,0.499433f,-7.08567e-016f}, +{-0.951298f,0.308272f,-3.94078e-016f},{-0.994455f,0.105163f,-1.73016e-016f},{-0.742274f,0.670096f,-8.05095e-016f}, +{-0.586974f,0.809606f,-9.35358e-016f},{-0.587881f,0.808947f,-1.05156e-015f},{-0.743379f,0.66887f,-9.1452e-016f}, +{-0.406743f,0.913543f,-9.91265e-016f},{-0.406026f,0.913862f,-1.16514e-015f},{-0.207408f,0.978254f,-1.06396e-015f}, +{-0.20783f,0.978165f,-1.24775e-015f},{-2.77556e-017f,1.0f,-1.18424e-015f},{-0.587881f,-0.808947f,8.70962e-016f}, +{0.130601f,-0.991435f,5.91127e-019f},{0.504792f,-0.863241f,-2.02127e-017f},{0.386527f,-0.922278f,-4.5688e-016f}, +{0.500171f,-0.865926f,3.75867e-016f},{0.260319f,-0.965523f,4.84382e-016f},{0.258907f,-0.965902f,2.3813e-017f}, +{0.382431f,-0.923984f,-2.11599e-018f},{0.7934f,-0.608701f,-1.21624e-016f},{0.866078f,-0.499909f,1.59434e-016f}, +{0.799182f,-0.60109f,3.0223e-017f},{0.707134f,-0.70708f,1.81955e-016f},{0.712942f,-0.701223f,8.71811e-018f}, +{0.61424f,-0.78912f,-8.47292e-018f},{0.993331f,-0.115297f,-1.28837e-016f},{0.969421f,-0.245402f,2.2597e-016f}, +{0.991453f,-0.130461f,-2.87378e-016f},{0.928562f,-0.371177f,-2.17091e-016f},{0.923924f,-0.382575f,5.85909e-017f}, +{0.965953f,-0.258717f,4.84292e-017f},{0.988912f,0.1485f,-2.16513e-016f},{0.96588f,0.258991f,-9.27243e-017f}, +{0.960687f,0.277634f,-5.52567e-018f},{1.0f,1.50355e-016f,2.5559e-017f},{0.991431f,0.130634f,-3.04207e-017f}, +{0.999859f,0.0167995f,-1.01552e-016f},{0.865923f,0.500177f,3.07191e-017f},{0.793249f,0.608898f,-1.58893e-016f}, +{0.854627f,0.519243f,-3.82786e-017f},{0.9238f,0.382876f,-4.32254e-016f},{0.915665f,0.401942f,3.20545e-017f}, +{0.707032f,0.707182f,1.84414e-016f},{0.608682f,0.793414f,-2.94158e-016f},{0.6891f,0.724667f,4.12928e-016f}, +{0.778651f,0.627457f,2.23169e-016f},{0.587492f,0.80923f,-2.92371e-016f},{0.499936f,0.866063f,-2.28218e-016f}, +{0.38264f,0.923898f,-1.88485e-016f},{0.475687f,0.879615f,-4.6342e-016f},{0.257551f,0.966265f,1.03607e-016f}, +{0.354917f,0.934898f,2.24615e-016f},{0.228996f,0.973427f,1.38774e-016f},{0.129881f,0.99153f,1.04307e-015f}, +{-4.21885e-016f,1.0f,0.0f},{0.0984243f,0.995145f,-1.69533e-016f},{-3.55271e-016f,1.0f,0.0f}, +{0.87148f,-0.490431f,1.62194e-016f},{0.608828f,-0.793302f,-4.00663e-016f},{0.131224f,-0.991353f,6.10153e-019f}, +{-0.99153f,-0.129881f,-4.91015e-016f},{-0.991435f,-0.130601f,-1.80136e-018f},{-0.865926f,-0.500171f,9.3755e-018f}, +{-0.923984f,-0.382431f,-7.91631e-019f},{-0.866063f,-0.499936f,-2.14221e-017f},{-0.923897f,-0.38264f,-2.44199e-017f}, +{-0.965902f,-0.258907f,-6.02945e-018f},{-0.966265f,-0.257551f,-4.82672e-016f},{-0.608898f,-0.793249f,1.18364e-016f}, +{-0.500177f,-0.865923f,-3.15104e-016f},{-0.608701f,-0.7934f,1.1825e-016f},{-0.793302f,-0.608828f,4.1567e-016f}, +{-0.707182f,-0.707032f,-3.42282e-019f},{-0.70708f,-0.707134f,-1.74822e-016f},{-0.130461f,-0.991453f,-1.03638e-016f}, +{-0.258717f,-0.965953f,-2.02191e-016f},{-0.130634f,-0.991431f,-2.74129e-016f},{-0.258991f,-0.96588f,-8.2881e-017f}, +{-0.382575f,-0.923924f,-2.01887e-016f},{-0.382876f,-0.9238f,-2.21359e-016f},{0.258717f,-0.965953f,-1.28219e-016f}, +{0.258991f,-0.96588f,1.82327e-016f},{0.130634f,-0.991431f,-7.95915e-017f},{6.27272e-017f,-1.0f,-9.36404e-017f}, +{0.130461f,-0.991453f,4.92989e-017f},{6.65124e-017f,-1.0f,-9.36404e-017f},{0.499909f,-0.866078f,-4.39633e-017f}, +{0.608701f,-0.7934f,3.80682e-016f},{0.500177f,-0.865923f,-2.43429e-016f},{0.382876f,-0.9238f,3.63034e-016f}, +{0.382576f,-0.923924f,1.36738e-016f},{0.70708f,-0.707134f,-2.86707e-016f},{0.793302f,-0.608828f,-4.30606e-016f}, +{0.707182f,-0.707032f,-2.64966e-016f},{0.608898f,-0.793249f,1.17848e-016f},{0.865926f,-0.500171f,-4.80949e-016f}, +{0.793414f,-0.608682f,8.84924e-016f},{0.866063f,-0.499936f,1.39452e-016f},{0.923984f,-0.382431f,-2.16909e-016f}, +{0.965902f,-0.258907f,-1.76024e-016f},{0.923898f,-0.38264f,7.5049e-017f},{0.991435f,-0.130601f,-3.76626e-016f}, +{0.966265f,-0.257551f,7.3088e-016f},{0.99153f,-0.129881f,-1.25711e-016f},{-0.499909f,-0.866078f,3.84467e-017f}, +{-0.793414f,-0.608682f,4.15754e-016f},{6.93889e-018f,0.0f,1.0f},{1.21431e-017f,0.0f,1.0f}, +{1.04083e-017f,0.0f,1.0f},{-1.38778e-017f,0.0f,1.0f},{-6.93889e-018f,0.0f,1.0f}, +{-1.04083e-017f,0.0f,1.0f},{1.73472e-018f,0.0f,1.0f},{-7.15573e-018f,0.0f,1.0f}, +{1.38778e-017f,0.0f,1.0f},{7.77156e-018f,0.0f,1.0f},{8.67362e-019f,0.0f,1.0f}, +{-8.67362e-018f,0.0f,1.0f},{9.97466e-018f,0.0f,1.0f},{3.46945e-018f,0.0f,1.0f}, +{-3.46945e-018f,0.0f,1.0f},{2.77556e-017f,0.0f,1.0f},{-0.130601f,0.991435f,1.77338e-018f}, +{-0.129881f,0.99153f,4.90961e-016f},{-0.500171f,0.865926f,3.08732e-017f},{-0.499936f,0.866063f,-5.81242e-020f}, +{-0.382431f,0.923984f,-6.34795e-018f},{-0.38264f,0.923897f,-6.29986e-018f},{-0.257551f,0.966265f,7.30839e-018f}, +{-0.258907f,0.965902f,4.8417e-016f},{-0.793249f,0.608898f,-1.1018e-016f},{-0.7934f,0.608701f,-1.10088e-016f}, +{-0.865923f,0.500177f,5.07923e-017f},{-0.608828f,0.793302f,-4.19108e-016f},{-0.707134f,0.70708f,-2.39145e-016f}, +{-0.707032f,0.707182f,2.2457e-017f},{-0.991453f,0.130461f,-2.76358e-016f},{-0.991431f,0.130634f,-1.05855e-016f}, +{-0.965953f,0.258717f,-1.6536e-016f},{-0.96588f,0.258991f,1.75599e-017f},{-0.9238f,0.382876f,-1.3075e-017f}, +{-0.923924f,0.382575f,8.1385e-017f},{-0.965953f,-0.258717f,2.15452e-016f},{-0.991431f,-0.130634f,1.78952e-016f}, +{-0.96588f,-0.258991f,-6.31777e-017f},{-1.0f,-2.40099e-017f,-4.66812e-017f},{-1.0f,-2.36302e-017f,-4.66812e-017f}, +{-0.991453f,-0.130461f,1.78822e-016f},{-0.866078f,-0.499909f,4.22895e-016f},{-0.865923f,-0.500177f,-8.46537e-017f}, +{-0.7934f,-0.608701f,8.26127e-016f},{-0.9238f,-0.382876f,1.31423e-016f},{-0.923924f,-0.382576f,9.38593e-017f}, +{-0.707134f,-0.70708f,2.26071e-016f},{-0.707032f,-0.707182f,2.04322e-016f},{-0.608828f,-0.793302f,3.53949e-016f}, +{-0.793249f,-0.608898f,-7.49318e-017f},{-0.500171f,-0.865926f,4.69837e-016f},{-0.608682f,-0.793414f,-8.86489e-016f}, +{-0.499936f,-0.866063f,-1.50588e-016f},{-0.382431f,-0.923984f,1.81164e-016f},{-0.38264f,-0.923898f,-8.71966e-017f}, +{-0.258907f,-0.965902f,1.58845e-016f},{-0.130601f,-0.991435f,3.72533e-016f},{-0.257551f,-0.966265f,2.2141e-016f}, +{-0.129881f,-0.99153f,1.21619e-016f},{4.44089e-017f,-1.0f,0.0f},{-0.866078f,0.499909f,1.57789e-016f}, +{-0.608682f,0.793414f,-4.19223e-016f},{-1.04083e-017f,0.0f,-1.0f},{6.93889e-018f,0.0f,-1.0f}, +{4.33681e-019f,0.0f,-1.0f},{1.07336e-017f,0.0f,-1.0f},{-6.93889e-018f,0.0f,-1.0f}, +{-6.50521e-018f,0.0f,-1.0f},{3.68629e-018f,0.0f,-1.0f},{4.07082e-018f,0.0f,-1.0f}, +{1.04083e-017f,0.0f,-1.0f},{0.444478f,-0.89579f,0.0f},{0.418355f,-0.908284f,0.0f}, +{0.133376f,-0.991066f,0.0f},{0.198953f,-0.980009f,0.0f},{0.145378f,-0.989376f,0.0f}, +{0.331391f,-0.943493f,0.0f},{0.263225f,-0.964735f,0.0f},{0.325799f,-0.945439f,0.0f}, +{-0.133376f,-0.991066f,0.0f},{-0.145378f,-0.989376f,0.0f},{-0.198953f,-0.980009f,0.0f}, +{0.0486891f,-0.998814f,0.0f},{-0.0486892f,-0.998814f,0.0f},{-6.76475e-016f,-1.0f,0.0f}, +{-0.325799f,-0.945439f,0.0f},{-0.331391f,-0.943493f,0.0f},{-0.386322f,-0.922364f,0.0f}, +{-0.263225f,-0.964735f,0.0f},{-0.24003f,-0.970766f,0.0f},{-0.444478f,-0.89579f,0.0f}, +{-0.418355f,-0.908283f,0.0f},{-0.0669122f,-0.997759f,0.0f},{0.0669122f,-0.997759f,0.0f}, +{0.24003f,-0.970766f,0.0f},{0.386322f,-0.922364f,0.0f},{-0.866025f,-0.5f,2.22045e-016f}, +{0.418355f,0.908283f,1.34453e-014f},{0.444478f,0.89579f,0.0f},{0.133376f,0.991066f,-3.66768e-015f}, +{0.198953f,0.980009f,-2.17606e-014f},{0.145378f,0.989376f,-1.12533e-014f},{0.263225f,0.964735f,-1.42809e-014f}, +{0.325799f,0.945439f,-9.40905e-015f},{0.331391f,0.943493f,6.98325e-015f},{-0.133376f,0.991066f,-5.62492e-015f}, +{-0.145378f,0.989376f,6.811e-015f},{-0.198953f,0.980009f,7.43077e-015f},{0.0486892f,0.998814f,-1.75808e-015f}, +{-0.0486891f,0.998814f,1.80313e-015f},{-3.75252e-016f,1.0f,-3.47178e-031f},{-0.325799f,0.945439f,-1.5311e-015f}, +{-0.331391f,0.943493f,-1.06169e-014f},{-0.386322f,0.922364f,-5.1396e-015f},{-0.263225f,0.964735f,1.93732e-015f}, +{-0.444478f,0.89579f,-3.54644e-016f},{-0.418355f,0.908284f,8.06481e-016f},{-0.24003f,0.970766f,-1.54398e-014f}, +{0.24003f,0.970766f,7.18511e-015f},{-0.0669122f,0.997759f,-3.81626e-015f},{0.0669122f,0.997759f,-2.47625e-016f}, +{0.386322f,0.922364f,-3.96751e-015f},{0.866025f,-0.5f,-2.29443e-016f},{0.0f,3.46945e-018f,-1.0f}, +{0.0f,-6.93889e-018f,-1.0f},{0.0f,6.93889e-018f,-1.0f},{0.0f,1.38778e-017f,-1.0f}, +{0.577419f,0.816448f,0.0f},{0.784136f,0.620589f,0.0f},{0.720693f,0.693254f,0.0f}, +{0.651394f,0.75874f,0.0f},{0.889343f,0.457241f,0.0f},{0.929514f,0.368787f,0.0f}, +{0.840654f,0.541573f,0.0f},{0.960722f,0.277511f,0.0f},{0.982785f,0.184754f,0.0f}, +{0.995774f,0.0918355f,0.0f},{1.0f,-6.52539e-016f,0.0f},{1.0f,-8.70052e-016f,0.0f}, +{-1.0f,6.03291e-016f,0.0f},{-0.995774f,-0.0918355f,1.81234e-017f},{-0.929514f,-0.368787f,-6.50222e-015f}, +{-0.960722f,-0.277511f,-1.39324e-014f},{-0.982785f,-0.184754f,2.2208e-017f},{-0.784136f,-0.620589f,4.14066e-015f}, +{-0.840654f,-0.541573f,4.26223e-015f},{-0.889343f,-0.457241f,7.28708e-015f},{-0.651394f,-0.75874f,8.81315e-015f}, +{-0.720693f,-0.693254f,-3.17985e-015f},{-0.577419f,-0.816448f,1.49179e-015f},{-1.0f,5.36259e-016f,0.0f}, +{1.83187e-015f,1.0f,0.0f},{1.83187e-015f,1.0f,8.62817e-032f},{0.0f,5.20417e-018f,-1.0f}, +{0.0f,-8.67362e-019f,-1.0f},{0.0f,-3.46945e-018f,-1.0f},{0.0f,-1.73472e-018f,-1.0f}, +{0.0f,-5.20417e-018f,-1.0f},{-0.995774f,0.0918355f,0.0f},{-1.0f,2.90017e-016f,0.0f}, +{-1.0f,3.99573e-013f,0.0f},{-0.929514f,0.368787f,0.0f},{-0.960722f,0.277511f,0.0f}, +{-0.982785f,0.184754f,0.0f},{-0.840654f,0.541573f,0.0f},{-0.784136f,0.620589f,0.0f}, +{-0.889343f,0.457241f,0.0f},{-0.720693f,0.693255f,0.0f},{-0.651394f,0.75874f,0.0f}, +{-0.577419f,0.816448f,0.0f},{1.33227e-015f,1.0f,-1.97215e-031f},{1.33227e-015f,1.0f,-1.04999e-032f}, +{0.577419f,-0.816448f,0.0f},{0.784136f,-0.620589f,2.05619e-015f},{0.720693f,-0.693255f,-2.6671e-015f}, +{0.651394f,-0.75874f,7.94521e-016f},{0.929514f,-0.368787f,3.27627e-015f},{0.889343f,-0.457241f,2.56146e-015f}, +{0.840654f,-0.541573f,8.97402e-016f},{0.982785f,-0.184754f,-5.16503e-015f},{0.960722f,-0.277511f,1.0602e-014f}, +{0.995774f,-0.0918355f,1.43378e-014f},{1.0f,-3.35162e-017f,0.0f},{0.0f,-1.38778e-017f,-1.0f}, +{-0.995188f,-0.0979889f,0.0f},{-1.0f,-3.99915e-013f,0.0f},{-0.923925f,-0.382573f,0.0f}, +{-0.956966f,-0.290201f,0.0f},{-0.923909f,-0.382613f,0.0f},{-0.956961f,-0.290216f,0.0f}, +{-0.980794f,-0.195045f,0.0f},{-0.980794f,-0.195048f,0.0f},{-0.773048f,-0.634347f,0.0f}, +{-0.707144f,-0.70707f,0.0f},{-0.773125f,-0.634253f,0.0f},{-0.831507f,-0.555514f,0.0f}, +{-0.83156f,-0.555435f,0.0f},{-0.881988f,-0.471271f,0.0f},{-0.471474f,-0.88188f,0.0f}, +{-0.555711f,-0.831376f,0.0f},{-0.471468f,-0.881883f,0.0f},{-0.634547f,-0.772884f,0.0f}, +{-0.634433f,-0.772978f,0.0f},{-0.555621f,-0.831435f,0.0f},{-0.194999f,-0.980803f,0.0f}, +{-0.0979559f,-0.995191f,0.0f},{-0.195278f,-0.980748f,0.0f},{-0.290209f,-0.956963f,0.0f}, +{-0.290455f,-0.956889f,0.0f},{-0.382806f,-0.923829f,0.0f},{0.195278f,-0.980748f,0.0f}, +{0.0979559f,-0.995191f,0.0f},{0.0981573f,-0.995171f,0.0f},{-5.55112e-017f,-1.0f,0.0f}, +{-0.0981573f,-0.995171f,0.0f},{-5.20417e-017f,-1.0f,0.0f},{0.382668f,-0.923886f,0.0f}, +{0.290209f,-0.956963f,0.0f},{0.382807f,-0.923829f,0.0f},{0.194999f,-0.980803f,0.0f}, +{0.290455f,-0.956889f,0.0f},{0.555621f,-0.831435f,0.0f},{0.555711f,-0.831376f,0.0f}, +{0.634547f,-0.772884f,0.0f},{0.471474f,-0.88188f,0.0f},{0.471468f,-0.881883f,0.0f}, +{0.707144f,-0.70707f,0.0f},{0.707246f,-0.706968f,0.0f},{0.773125f,-0.634253f,0.0f}, +{0.634433f,-0.772978f,0.0f},{0.83156f,-0.555435f,0.0f},{0.773048f,-0.634347f,0.0f}, +{0.881988f,-0.471271f,0.0f},{0.831507f,-0.555514f,0.0f},{0.881956f,-0.471332f,0.0f}, +{0.923925f,-0.382573f,0.0f},{0.956966f,-0.290201f,0.0f},{0.923909f,-0.382613f,0.0f}, +{0.980794f,-0.195045f,0.0f},{0.956961f,-0.290216f,0.0f},{0.980794f,-0.195048f,0.0f}, +{0.995188f,-0.0979878f,0.0f},{0.995188f,-0.0979889f,0.0f},{-0.382668f,-0.923886f,0.0f}, +{-0.707246f,-0.706968f,0.0f},{-0.881956f,-0.471332f,0.0f},{-0.995188f,-0.0979878f,0.0f}, +{-0.984809f,-0.173642f,0.0f},{-1.0f,1.57282e-016f,0.0f},{-0.765765f,-0.64312f,0.0f}, +{-0.766272f,-0.642516f,0.0f},{-0.865946f,-0.500137f,0.0f},{-0.939669f,-0.342084f,0.0f}, +{-0.866231f,-0.499643f,0.0f},{-0.939879f,-0.341507f,0.0f},{-0.341751f,-0.939791f,0.0f}, +{-0.173343f,-0.984861f,0.0f},{-0.342031f,-0.939689f,0.0f},{-0.642133f,-0.766593f,0.0f}, +{-0.499517f,-0.866304f,0.0f},{-0.50031f,-0.865846f,0.0f},{0.342031f,-0.939689f,0.0f}, +{0.173343f,-0.984861f,0.0f},{0.173688f,-0.984801f,0.0f},{-3.70074e-017f,-1.0f,0.0f}, +{-3.23815e-017f,-1.0f,0.0f},{0.64411f,-0.764933f,0.0f},{0.642133f,-0.766593f,0.0f}, +{0.50031f,-0.865846f,0.0f},{0.499517f,-0.866304f,0.0f},{0.766272f,-0.642516f,0.0f}, +{0.865946f,-0.500137f,0.0f},{0.765765f,-0.64312f,0.0f},{0.866231f,-0.499643f,0.0f}, +{0.939669f,-0.342084f,0.0f},{0.984809f,-0.173642f,0.0f},{0.939879f,-0.341507f,0.0f}, +{0.984871f,-0.173291f,0.0f},{0.341751f,-0.939791f,0.0f},{-0.173688f,-0.984801f,0.0f}, +{-0.64411f,-0.764933f,0.0f},{-0.984871f,-0.173291f,0.0f},{2.08167e-017f,0.0f,-1.0f}, +{2.34188e-017f,0.0f,-1.0f},{-2.08167e-017f,0.0f,-1.0f},{-8.67362e-018f,0.0f,-1.0f}, +{1.0842e-017f,0.0f,-1.0f},{2.77556e-017f,0.0f,-1.0f},{0.991152f,0.132731f,1.7726e-016f}, +{0.964765f,0.263112f,-1.21714e-017f},{0.964793f,0.263012f,1.90689e-016f},{0.99116f,0.132673f,1.95676e-016f}, +{1.0f,1.97655e-016f,1.82867e-032f},{0.921309f,0.388832f,-3.40953e-016f},{0.921362f,0.388705f,-1.79812e-017f}, +{0.861557f,0.507661f,-3.1884e-016f},{0.786578f,0.617491f,0.0f},{0.786661f,0.617385f,0.0f}, +{0.861635f,0.507528f,3.65825e-016f},{0.697798f,0.716295f,-2.58237e-016f},{0.697683f,0.716407f,0.0f}, +{0.596508f,0.802607f,0.0f},{0.596433f,0.802663f,2.92927e-016f},{0.484069f,0.87503f,-8.09565e-017f}, +{0.484772f,0.874641f,8.09205e-017f},{0.363152f,0.93173f,-2.68786e-016f},{0.364466f,0.931217f,0.0f}, +{0.237459f,0.971397f,-1.79745e-016f},{0.23745f,0.9714f,0.0f},{0.106383f,0.994325f,0.0f}, +{0.99116f,-0.132673f,-6.13738e-018f},{0.991152f,-0.132731f,0.0f},{0.964765f,-0.263112f,1.82571e-017f}, +{0.964793f,-0.263012f,-2.55617e-016f},{0.921309f,-0.388832f,3.31959e-016f},{0.921362f,-0.388705f,-4.08234e-016f}, +{0.861635f,-0.507528f,-2.55532e-016f},{0.861557f,-0.507661f,1.6992e-016f},{0.786578f,-0.617491f,1.74792e-016f}, +{0.786661f,-0.617385f,3.63904e-016f},{0.697683f,-0.716407f,-9.89883e-017f},{0.697798f,-0.716295f,-4.85478e-016f}, +{0.596508f,-0.802607f,1.06491e-016f},{0.596433f,-0.802663f,-1.43821e-016f},{0.484069f,-0.87503f,8.44299e-017f}, +{0.484771f,-0.874641f,2.17811e-016f},{0.363151f,-0.93173f,-1.71313e-016f},{0.364466f,-0.931217f,3.52312e-017f}, +{0.237459f,-0.971397f,2.12946e-016f},{0.23745f,-0.9714f,-2.36429e-016f},{0.106383f,-0.994325f,0.0f}, +{0.211559f,-0.977365f,0.0f},{0.211559f,0.977365f,0.0f},{0.0f,1.11022e-016f,1.0f}, +{1.0f,-3.60822e-016f,0.0f},{0.988818f,-0.149126f,-3.65936e-016f},{0.988846f,-0.148938f,0.0f}, +{0.826061f,-0.563581f,2.57135e-016f},{0.82663f,-0.562746f,1.52957e-016f},{0.900794f,-0.434246f,-2.47032e-016f}, +{0.901683f,-0.432397f,2.46854e-016f},{0.955572f,-0.294759f,-1.22275e-016f},{0.955502f,-0.294984f,5.4583e-017f}, +{0.499989f,-0.866031f,2.99023e-016f},{0.499834f,-0.866121f,1.94153e-016f},{0.365379f,-0.930859f,0.0f}, +{0.623256f,-0.782018f,-1.74079e-016f},{0.623488f,-0.781833f,-2.60037e-016f},{-0.074795f,-0.997199f,-8.53395e-017f}, +{-0.0746326f,-0.997211f,-1.24581e-016f},{0.0746326f,-0.997211f,1.77616e-016f},{0.074795f,-0.997199f,-2.90618e-016f}, +{0.222585f,-0.974913f,1.10791e-016f},{0.222381f,-0.97496f,-1.80404e-016f},{-0.499833f,-0.866122f,-3.08968e-016f}, +{-0.365177f,-0.930938f,2.3519e-016f},{-0.365379f,-0.930859f,-6.59594e-016f},{-0.222381f,-0.97496f,3.7743e-016f}, +{-0.222585f,-0.974913f,3.77471e-016f},{-0.732917f,-0.680318f,5.87241e-017f},{-0.623488f,-0.781833f,1.35626e-016f}, +{-0.733034f,-0.680192f,-1.83291e-016f},{-0.49999f,-0.866031f,7.951e-017f},{-0.623256f,-0.782018f,7.67051e-017f}, +{-0.82663f,-0.562746f,1.92502e-016f},{-0.826061f,-0.563581f,-1.66735e-016f},{-0.901683f,-0.432397f,-1.42043e-016f}, +{-0.900794f,-0.434246f,-2.48163e-016f},{-0.955502f,-0.294984f,9.93362e-017f},{-0.955572f,-0.294759f,2.96611e-017f}, +{-0.988846f,-0.148938f,-6.23501e-017f},{-0.988818f,-0.149126f,4.18655e-017f},{-1.0f,2.77556e-017f,0.0f}, +{0.365177f,-0.930938f,6.75713e-017f},{0.733034f,-0.680192f,1.35639e-016f},{1.11022e-016f,0.0f,1.0f}, +{2.22045e-016f,0.0f,1.0f},{-1.11022e-016f,0.0f,1.0f},{-2.22045e-016f,0.0f,1.0f}, +{0.978165f,-0.20783f,-8.09482e-019f},{0.978254f,-0.207408f,-8.06289e-019f},{0.50141f,-0.86521f,-7.86e-017f}, +{0.670096f,-0.742274f,1.47663e-017f},{0.66887f,-0.743379f,1.38533e-016f},{0.809606f,-0.586974f,2.23009e-019f}, +{0.913862f,-0.406026f,-1.6746e-016f},{0.913543f,-0.406743f,-1.67403e-016f},{0.105163f,-0.994455f,9.95328e-018f}, +{0.104013f,-0.994576f,6.55702e-017f},{-0.104013f,-0.994576f,3.02706e-017f},{0.499433f,-0.866353f,-3.2041e-017f}, +{0.308272f,-0.951298f,8.49254e-017f},{0.310578f,-0.950548f,-4.50449e-017f},{-0.310578f,-0.950548f,4.10929e-017f}, +{-0.50141f,-0.86521f,6.38835e-017f},{-0.499433f,-0.866353f,-5.80911e-017f},{-0.308272f,-0.951298f,1.12332e-016f}, +{-0.105163f,-0.994455f,-7.34256e-018f},{-0.670096f,-0.742274f,-2.88671e-017f},{-0.809606f,-0.586974f,1.0557e-016f}, +{-0.808947f,-0.587881f,-2.02787e-016f},{-0.66887f,-0.743379f,-8.46456e-017f},{-0.913543f,-0.406743f,-2.46108e-016f}, +{-0.913862f,-0.406026f,1.48066e-016f},{-0.978254f,-0.207408f,-1.1019e-016f},{-0.978165f,-0.20783f,2.68975e-016f}, +{-1.0f,-4.44089e-016f,0.0f},{0.808947f,-0.587881f,-3.12756e-016f},{0.0f,-2.22045e-016f,1.0f}, +{0.0f,4.44089e-016f,1.0f},{0.0f,-4.44089e-016f,1.0f},{0.0f,2.22045e-016f,1.0f}, +{0.0f,1.66533e-016f,1.0f},{0.0f,6.245e-017f,1.0f},{0.0f,-1.11022e-016f,1.0f}, +{0.0f,-3.1225e-017f,1.0f},{0.0f,-1.94289e-016f,1.0f},{0.0f,1.38778e-016f,1.0f}, +{0.0f,6.93889e-017f,1.0f},{0.380627f,0.924729f,-2.41539e-016f},{0.254521f,0.967067f,-1.78943e-016f}, +{0.254621f,0.967041f,-1.31824e-016f},{0.380681f,0.924706f,-3.4221e-016f},{0.5f,0.866025f,8.01234e-017f}, +{0.123916f,0.992293f,-4.58581e-017f},{0.124053f,0.992276f,2.06562e-016f},{-0.00886925f,0.999961f,0.0f}, +{-0.141474f,0.989942f,0.0f},{-0.141341f,0.989961f,3.66359e-016f},{-0.00871489f,0.999962f,1.61258e-018f}, +{-0.271431f,0.962458f,0.0f},{-0.271585f,0.962414f,0.0f},{-0.396824f,0.917895f,-3.39689e-016f}, +{-0.39691f,0.917858f,0.0f},{-0.515764f,0.856731f,-5.07925e-016f},{-0.515075f,0.857145f,3.17207e-016f}, +{-0.625326f,0.780364f,-2.88792e-016f},{-0.624225f,0.781245f,5.81092e-017f},{-0.722525f,0.691345f,-2.67388e-016f}, +{-0.722532f,0.691337f,5.11692e-016f},{-0.807919f,0.589293f,0.0f},{0.610478f,0.792033f,3.83186e-016f}, +{0.610525f,0.791997f,-2.59519e-016f},{0.710244f,0.703955f,7.17582e-016f},{0.710171f,0.704029f,-1.32545e-016f}, +{0.797393f,0.603461f,4.68602e-017f},{0.797309f,0.603571f,-1.40638e-016f},{0.87035f,0.492434f,-6.88718e-018f}, +{0.870426f,0.492299f,-2.01326e-016f},{0.928052f,0.372451f,4.36423e-017f},{0.928002f,0.372576f,-6.42341e-017f}, +{0.969268f,0.246008f,-7.27758e-017f},{0.969228f,0.246163f,-1.13338e-016f},{0.993332f,0.115288f,-1.39459e-017f}, +{0.993343f,0.115195f,7.5086e-017f},{0.999833f,-0.0182988f,-4.93539e-017f},{0.999847f,-0.017496f,-2.2592e-017f}, +{0.988478f,-0.151367f,6.80819e-017f},{0.98869f,-0.149972f,-2.29484e-016f},{0.959985f,-0.280053f,-4.92036e-018f}, +{0.959982f,-0.280063f,-1.73501e-017f},{0.914302f,-0.405032f,0.0f},{0.952202f,-0.305468f,0.0f}, +{-0.740644f,0.671898f,0.0f},{0.623556f,0.781778f,3.18161e-016f},{0.623408f,0.781897f,-5.76768e-017f}, +{0.901106f,0.4336f,1.21917e-016f},{0.900667f,0.43451f,1.19137e-016f},{0.826465f,0.562987f,3.82317e-017f}, +{0.825308f,0.564682f,0.0f},{0.733055f,0.68017f,3.39106e-017f},{0.733215f,0.679997f,-1.83813e-016f}, +{1.0f,-1.21766e-005f,-2.31274e-017f},{1.0f,-0.000192142f,6.946e-017f},{0.988837f,-0.149002f,1.05584e-016f}, +{0.955631f,0.294565f,9.87124e-017f},{0.988875f,0.148747f,-2.75237e-017f},{0.988831f,0.14904f,-7.33206e-017f}, +{0.826202f,-0.563374f,-1.79826e-016f},{0.826294f,-0.563239f,-7.55524e-017f},{0.900926f,-0.433972f,1.86017e-016f}, +{0.900997f,-0.433825f,-4.16795e-017f},{0.955592f,-0.294693f,-3.9043e-017f},{0.955531f,-0.294892f,-1.37788e-016f}, +{0.500166f,-0.865929f,2.67563e-018f},{0.623628f,-0.781722f,1.95335e-016f},{0.623458f,-0.781857f,-1.87816e-016f}, +{0.733149f,-0.680068f,-2.40741e-016f},{0.733007f,-0.680221f,1.4282e-016f},{0.222715f,-0.974884f,6.76696e-018f}, +{0.365343f,-0.930873f,-1.59166e-016f},{0.222546f,-0.974922f,8.82681e-017f},{0.50001f,-0.866019f,-4.87352e-017f}, +{0.365619f,-0.930764f,4.34431e-017f},{0.0740373f,-0.997256f,-5.34897e-016f},{0.0750446f,-0.99718f,1.55626e-017f}, +{-0.0763749f,-0.997079f,-2.39932e-016f},{-0.0743287f,-0.997234f,1.17298e-016f},{-0.222287f,-0.974981f,5.54047e-016f}, +{-0.222517f,-0.974929f,-4.69812e-016f},{-0.365439f,-0.930835f,2.29949e-016f},{-0.365262f,-0.930905f,-1.2259e-016f}, +{0.988805f,-0.149216f,0.0f},{0.95558f,0.294731f,0.0f},{-1.66533e-016f,0.0f,1.0f}, +{8.32667e-017f,0.0f,1.0f},{-1.38778e-016f,0.0f,1.0f},{-1.14492e-016f,0.0f,1.0f}, +{5.55112e-017f,0.0f,1.0f},{1.79544e-016f,0.0f,1.0f},{-6.50521e-017f,0.0f,1.0f}, +{-8.32667e-017f,0.0f,1.0f},{1.31839e-016f,0.0f,1.0f},{0.669069f,0.7432f,7.56184e-017f}, +{0.668748f,0.743489f,-1.99445e-016f},{0.999999f,0.00162868f,-1.50684e-019f},{0.977876f,0.209183f,0.0f}, +{0.97822f,0.207569f,1.9204e-017f},{0.913137f,0.407652f,-1.59913e-016f},{0.80856f,0.588414f,0.0f}, +{0.809021f,0.58778f,0.0f},{0.913805f,-0.406154f,3.28816e-017f},{0.913335f,-0.40721f,7.53489e-017f}, +{0.809321f,-0.587366f,2.10733e-016f},{1.0f,-0.000654662f,-4.60776e-017f},{0.978488f,-0.206306f,-7.63485e-017f}, +{0.66791f,-0.744242f,7.23873e-017f},{0.498589f,-0.866839f,-2.11766e-016f},{0.500567f,-0.865698f,2.02889e-016f}, +{0.669713f,-0.74262f,1.25295e-016f},{0.808642f,-0.588301f,5.44288e-017f},{0.30778f,-0.951458f,-1.03566e-016f}, +{0.103531f,-0.994626f,-3.39094e-016f},{0.104646f,-0.99451f,-1.43466e-016f},{0.30935f,-0.950948f,-2.09359e-017f}, +{-0.104522f,-0.994523f,6.2347e-017f},{-0.105302f,-0.99444f,-2.24253e-016f},{-0.309506f,-0.950897f,-2.31848e-016f}, +{-0.309096f,-0.951031f,1.16375e-016f},{0.0f,-2.08167e-016f,1.0f},{0.0f,-6.6116e-017f,1.0f}, +{0.0f,-2.15106e-016f,1.0f},{0.0f,-1.66533e-016f,1.0f},{0.0f,-1.00614e-016f,1.0f}, +{0.0f,4.33681e-017f,1.0f},{0.0f,7.56773e-017f,1.0f},{0.0f,1.30104e-018f,1.0f}, +{0.0f,4.16334e-017f,1.0f},{-0.610525f,0.791997f,-2.36613e-016f},{-0.710244f,0.703955f,3.90774e-016f}, +{-0.710171f,0.704029f,-1.1366e-018f},{-0.610478f,0.792033f,-3.15997e-016f},{-0.5f,0.866025f,5.73259e-016f}, +{-0.797393f,0.603461f,5.20424e-016f},{-0.797309f,0.603571f,-7.37659e-017f},{-0.870426f,0.492299f,2.11262e-017f}, +{-0.928052f,0.372451f,-3.61531e-016f},{-0.928002f,0.372576f,3.09595e-016f},{-0.87035f,0.492434f,1.01714e-016f}, +{-0.969228f,0.246163f,-1.79343e-016f},{-0.969268f,0.246008f,0.0f},{-0.993332f,0.115288f,-2.26469e-016f}, +{-0.993343f,0.115195f,-2.26436e-016f},{-0.999833f,-0.0182988f,0.0f},{-0.999847f,-0.017496f,0.0f}, +{-0.988478f,-0.151367f,0.0f},{-0.98869f,-0.149972f,-2.93946e-016f},{-0.959985f,-0.280053f,0.0f}, +{-0.959982f,-0.280063f,-2.07288e-016f},{-0.914302f,-0.405032f,0.0f},{-0.380681f,0.924706f,4.10153e-016f}, +{-0.380627f,0.924729f,1.00679e-016f},{-0.254521f,0.967067f,1.8483e-016f},{-0.254621f,0.967041f,7.06716e-017f}, +{-0.123916f,0.992293f,2.86613e-017f},{-0.124053f,0.992276f,1.20497e-016f},{0.00871499f,0.999962f,2.77948e-016f}, +{0.00886925f,0.999961f,-3.2052e-016f},{0.141474f,0.989942f,1.92975e-016f},{0.141341f,0.989961f,4.7266e-016f}, +{0.271585f,0.962414f,-2.20758e-016f},{0.271431f,0.962458f,1.54073e-017f},{0.396824f,0.917895f,2.78137e-017f}, +{0.39691f,0.917858f,1.25083e-016f},{0.515764f,0.856731f,1.21216e-016f},{0.515076f,0.857145f,-1.12882e-016f}, +{0.625326f,0.780363f,3.65282e-016f},{0.624225f,0.781245f,6.22071e-016f},{0.722525f,0.691345f,-8.52362e-016f}, +{0.722532f,0.691337f,-2.70972e-016f},{0.807919f,0.589293f,0.0f},{0.740644f,0.671898f,0.0f}, +{-0.952202f,-0.305468f,0.0f},{-0.365262f,0.930905f,0.0f},{0.0750445f,0.99718f,-9.22577e-017f}, +{-0.0763749f,0.997079f,-7.81162e-017f},{-0.222517f,0.974929f,-9.0199e-017f},{-0.222287f,0.974981f,0.0f}, +{0.500011f,0.866019f,-3.57684e-016f},{0.500166f,0.865929f,-5.24921e-017f},{0.623458f,0.781857f,-3.03062e-016f}, +{0.222715f,0.974884f,-8.2421e-017f},{0.365619f,0.930764f,-1.1071e-016f},{0.365343f,0.930873f,-4.30615e-017f}, +{0.900997f,0.433825f,1.76752e-016f},{0.900926f,0.433972f,1.30891e-017f},{0.826294f,0.563239f,0.0f}, +{0.826202f,0.563374f,5.21225e-017f},{0.733007f,0.680221f,9.92833e-017f},{0.733149f,0.680068f,-1.7203e-016f}, +{1.0f,0.000192253f,2.31296e-016f},{0.988805f,0.149217f,1.37224e-016f},{0.988837f,0.149001f,-7.84832e-017f}, +{0.955531f,0.294892f,2.07369e-016f},{0.955592f,0.294693f,-1.03241e-017f},{0.955631f,-0.294565f,-1.87008e-016f}, +{0.988831f,-0.14904f,-4.18312e-017f},{0.95558f,-0.294731f,-2.50979e-016f},{1.0f,1.20654e-005f,1.85036e-016f}, +{0.988875f,-0.148747f,4.43526e-016f},{0.900667f,-0.43451f,-2.40435e-016f},{0.901106f,-0.4336f,-3.36518e-017f}, +{0.825308f,-0.564682f,-5.29981e-017f},{0.826465f,-0.562987f,-2.07468e-016f},{0.733215f,-0.679997f,1.78805e-016f}, +{0.733055f,-0.68017f,5.50139e-018f},{0.623408f,-0.781897f,1.42876e-016f},{0.623556f,-0.781778f,7.87981e-017f}, +{0.623627f,0.781722f,1.15394e-016f},{0.222546f,0.974922f,4.11793e-017f},{-5.55112e-017f,0.0f,1.0f}, +{1.02349e-016f,0.0f,1.0f},{-4.85723e-017f,0.0f,1.0f},{4.85723e-017f,0.0f,1.0f}, +{-9.71445e-017f,0.0f,1.0f},{-7.22079e-017f,0.0f,1.0f},{-8.23994e-017f,0.0f,1.0f}, +{-6.93889e-017f,0.0f,1.0f},{-0.309096f,0.951031f,-2.85971e-017f},{-0.309506f,0.950897f,-2.86351e-017f}, +{0.498589f,0.866839f,2.17532e-016f},{0.30778f,0.951458f,0.0f},{0.30935f,0.950948f,-1.16601e-016f}, +{0.103531f,0.994626f,-9.57856e-018f},{-0.105302f,0.99444f,0.0f},{-0.104522f,0.994523f,9.6702e-018f}, +{0.808642f,0.588301f,1.46265e-016f},{0.809321f,0.587366f,-1.69037e-017f},{0.500567f,0.865698f,2.99122e-016f}, +{0.669713f,0.74262f,5.52155e-017f},{0.66791f,0.744242f,-2.06569e-016f},{0.978488f,0.206306f,-4.52641e-017f}, +{0.999999f,-0.00162857f,1.61907e-016f},{1.0f,0.000654662f,5.80361e-017f},{0.977984f,0.208678f,9.65329e-018f}, +{0.913805f,0.406154f,4.2272e-017f},{0.977876f,-0.209184f,5.66326e-017f},{0.913137f,-0.407652f,-9.05162e-018f}, +{0.913594f,-0.406629f,-7.7272e-017f},{0.97822f,-0.207569f,-1.86995e-016f},{0.809021f,-0.58778f,-8.44062e-017f}, +{0.80856f,-0.588414f,-1.30045e-016f},{0.668748f,-0.743489f,2.63395e-016f},{0.669069f,-0.7432f,3.8159e-017f}, +{0.104646f,0.99451f,0.0f},{0.0f,-6.245e-017f,1.0f},{0.0f,3.05311e-016f,1.0f}, +{0.0f,-2.498e-016f,1.0f},{0.0f,3.33067e-016f,1.0f},{0.0f,-5.89806e-017f,1.0f}, +{0.0f,8.32667e-017f,1.0f},{0.0f,-9.71445e-017f,1.0f},{0.0f,9.02056e-017f,1.0f}, +{0.0f,7.84962e-017f,1.0f},{0.0f,-7.98865e-017f,1.0f},{0.0f,-6.50521e-018f,1.0f}, +{0.0f,6.07153e-017f,1.0f},{0.0f,7.63278e-017f,1.0f},{0.0f,1.04083e-016f,1.0f}, +{0.0f,-8.32667e-017f,1.0f},{-0.991152f,-0.132731f,0.0f},{-0.964765f,-0.263112f,1.90689e-016f}, +{-0.964793f,-0.263012f,-3.44878e-016f},{-0.99116f,-0.132673f,-1.83401e-016f},{-1.0f,1.18593e-015f,-3.70074e-016f}, +{-1.0f,1.0871e-015f,-3.70074e-016f},{-0.921309f,-0.388832f,3.76927e-016f},{-0.921362f,-0.388705f,-6.81945e-016f}, +{-0.861557f,-0.507661f,-4.69681e-017f},{-0.786578f,-0.617491f,2.91092e-016f},{-0.786661f,-0.617385f,5.25126e-016f}, +{-0.861635f,-0.507528f,4.69558e-017f},{-0.697798f,-0.716295f,-1.91966e-016f},{-0.697683f,-0.716407f,-3.24475e-016f}, +{-0.596508f,-0.802607f,0.0f},{-0.596433f,-0.802663f,-7.42612e-017f},{-0.484069f,-0.87503f,-8.09565e-017f}, +{-0.484772f,-0.874641f,8.09205e-017f},{-0.363152f,-0.93173f,0.0f},{-0.364466f,-0.931217f,1.7231e-016f}, +{-0.237459f,-0.971397f,0.0f},{-0.23745f,-0.9714f,-3.99709e-018f},{-0.106383f,-0.994325f,0.0f}, +{-0.99116f,0.132673f,6.13738e-018f},{-0.991152f,0.132731f,7.336e-016f},{-0.964765f,0.263112f,-1.84603e-016f}, +{-0.964793f,0.263012f,-1.07511e-016f},{-0.921309f,0.388832f,3.22966e-016f},{-0.921362f,0.388705f,3.99244e-016f}, +{-0.861635f,0.507528f,-1.40598e-016f},{-0.861557f,0.507661f,-2.16888e-016f},{-0.786578f,0.617491f,-1.02699e-016f}, +{-0.786661f,0.617385f,-3.86014e-016f},{-0.697683f,0.716407f,1.92347e-016f},{-0.697798f,0.716295f,3.33219e-016f}, +{-0.596508f,0.802607f,1.9824e-016f},{-0.596433f,0.802663f,4.53374e-016f},{-0.484069f,0.87503f,-1.87889e-016f}, +{-0.484771f,0.874641f,3.75811e-016f},{-0.363151f,0.93173f,1.53169e-016f},{-0.364466f,0.931217f,3.45313e-016f}, +{-0.237459f,0.971397f,7.34234e-017f},{-0.23745f,0.9714f,-2.07432e-017f},{-0.106383f,0.994325f,0.0f}, +{-0.211559f,0.977365f,0.0f},{-0.211559f,-0.977365f,0.0f},{-0.988818f,0.149126f,-2.10562e-016f}, +{-0.988846f,0.148938f,-1.82973e-016f},{-0.826061f,0.563581f,-4.09987e-016f},{-0.82663f,0.562746f,9.76567e-017f}, +{-0.900794f,0.434246f,-1.6668e-016f},{-0.901683f,0.432397f,2.46854e-016f},{-0.955572f,0.294759f,-2.85899e-016f}, +{-0.955502f,0.294984f,1.76803e-016f},{-0.499989f,0.866031f,4.62583e-017f},{-0.499834f,0.866121f,-3.32885e-016f}, +{-0.365379f,0.930859f,-3.41265e-016f},{-0.732917f,0.680318f,-9.73263e-018f},{-0.623256f,0.782018f,7.23512e-017f}, +{-0.623488f,0.781833f,1.44668e-016f},{0.074795f,0.997199f,-3.92098e-017f},{0.0746326f,0.997211f,2.62972e-016f}, +{-0.0746326f,0.997211f,-3.29817e-016f},{-0.074795f,0.997199f,3.22899e-017f},{-0.222585f,0.974913f,-2.70593e-016f}, +{-0.222381f,0.97496f,-3.32329e-016f},{0.499833f,0.866122f,3.99162e-016f},{0.365177f,0.930938f,-1.96765e-016f}, +{0.365379f,0.930859f,1.22944e-016f},{0.222381f,0.97496f,1.00489e-016f},{0.222585f,0.974913f,-2.00988e-016f}, +{0.732917f,0.680318f,-2.14863e-016f},{0.623488f,0.781833f,-1.75456e-016f},{0.733034f,0.680192f,2.66388e-016f}, +{0.49999f,0.866031f,-2.0031e-017f},{0.623256f,0.782018f,9.73741e-017f},{0.82663f,0.562746f,-2.18645e-016f}, +{0.826061f,0.563581f,1.09908e-016f},{0.901683f,0.432397f,4.54617e-017f},{0.900794f,0.434246f,2.11672e-017f}, +{0.955502f,0.294984f,5.1766e-017f},{0.955572f,0.294759f,1.0035e-016f},{0.988846f,0.148938f,-1.13814e-016f}, +{0.988818f,0.149126f,4.48123e-017f},{1.0f,-1.41553e-015f,0.0f},{-0.365177f,0.930938f,1.01357e-016f}, +{-0.733034f,0.680192f,-1.35639e-016f},{-2.77556e-017f,0.0f,1.0f},{-1.04083e-016f,0.0f,1.0f}, +{6.41848e-017f,0.0f,1.0f},{5.09575e-017f,0.0f,1.0f},{4.16334e-017f,0.0f,1.0f}, +{6.93889e-017f,0.0f,1.0f},{-1.0f,5.27356e-016f,0.0f},{-0.978165f,0.20783f,-1.81712e-016f}, +{-0.978254f,0.207408f,-7.34724e-019f},{-0.50141f,0.86521f,5.85773e-017f},{-0.670096f,0.742274f,1.03122e-017f}, +{-0.66887f,0.743379f,1.68759e-016f},{-0.809606f,0.586974f,1.43405e-016f},{-0.913862f,0.406026f,-1.65029e-016f}, +{-0.913543f,0.406743f,4.15074e-018f},{-0.105163f,0.994455f,2.55483e-017f},{-0.104013f,0.994576f,2.55461e-017f}, +{0.104013f,0.994576f,1.39018e-017f},{-0.499433f,0.866353f,5.88395e-017f},{-0.308272f,0.951298f,8.42303e-017f}, +{-0.310578f,0.950548f,-2.26885e-018f},{0.310578f,0.950548f,8.17184e-017f},{0.50141f,0.86521f,3.88522e-017f}, +{0.499433f,0.866353f,-1.92414e-017f},{0.308272f,0.951298f,1.58688e-017f},{0.105163f,0.994455f,-2.22445e-017f}, +{0.670096f,0.742274f,1.34233e-016f},{0.809606f,0.586974f,2.91734e-016f},{0.808947f,0.587881f,-2.32496e-016f}, +{0.66887f,0.743379f,-2.76854e-016f},{0.913543f,0.406743f,-3.89617e-017f},{0.913862f,0.406026f,1.84203e-017f}, +{0.978254f,0.207408f,-4.74736e-018f},{0.978165f,0.20783f,5.52614e-017f},{-0.808947f,0.587881f,-1.55945e-016f}, +{-1.0f,6.66134e-016f,0.0f},{0.0f,4.64039e-017f,1.0f},{-0.380627f,-0.924729f,1.71109e-016f}, +{-0.254521f,-0.967067f,-5.83926e-016f},{-0.254621f,-0.967041f,-4.71144e-017f},{-0.380681f,-0.924706f,-3.02246e-017f}, +{-0.5f,-0.866025f,-4.62593e-017f},{-0.123916f,-0.992293f,2.0654e-016f},{-0.124053f,-0.992276f,-2.06562e-016f}, +{0.00886925f,-0.999961f,-3.28228e-018f},{0.141474f,-0.989942f,-5.23559e-017f},{0.141341f,-0.989961f,3.66359e-016f}, +{0.00871489f,-0.999962f,3.68448e-016f},{0.271431f,-0.962458f,-3.56181e-016f},{0.271585f,-0.962414f,3.56165e-016f}, +{0.396824f,-0.917895f,0.0f},{0.39691f,-0.917858f,1.46886e-016f},{0.515764f,-0.856731f,-3.17054e-016f}, +{0.515075f,-0.857145f,-3.17207e-016f},{0.625326f,-0.780364f,0.0f},{0.624225f,-0.781245f,5.81092e-017f}, +{0.722525f,-0.691345f,0.0f},{0.722532f,-0.691337f,5.11692e-016f},{0.807919f,-0.589293f,0.0f}, +{-0.610478f,-0.792033f,5.52628e-016f},{-0.610525f,-0.791997f,-1.67896e-017f},{-0.710244f,-0.703955f,1.32004e-016f}, +{-0.710171f,-0.704029f,6.45675e-017f},{-0.797393f,-0.603461f,-1.76465e-016f},{-0.797309f,-0.603571f,3.34015e-016f}, +{-0.87035f,-0.492434f,-1.7694e-016f},{-0.870426f,-0.492299f,-1.13867e-016f},{-0.928052f,-0.372451f,-7.32957e-017f}, +{-0.928002f,-0.372576f,1.63892e-016f},{-0.969268f,-0.246008f,3.96598e-017f},{-0.969228f,-0.246163f,-1.20102e-016f}, +{-0.993332f,-0.115288f,2.08517e-016f},{-0.993343f,-0.115195f,-6.69385e-017f},{-0.999833f,0.0182988f,-8.64086e-017f}, +{-0.999847f,0.017496f,-7.9525e-017f},{-0.988478f,0.151367f,1.19056e-016f},{-0.98869f,0.149972f,-1.73927e-016f}, +{-0.959985f,0.280053f,-5.6139e-017f},{-0.959982f,0.280063f,-6.67141e-017f},{-0.914302f,0.405032f,0.0f}, +{-0.952202f,0.305468f,2.11431e-016f},{-0.952202f,0.305468f,1.05716e-016f},{0.740644f,-0.671898f,0.0f}, +{-0.623556f,-0.781778f,2.89316e-016f},{-0.900667f,-0.43451f,2.05393e-016f},{-0.826465f,-0.562987f,0.0f}, +{-0.825308f,-0.564682f,-1.32618e-016f},{-0.733055f,-0.68017f,0.0f},{-1.0f,1.21766e-005f,-6.93822e-017f}, +{-1.0f,0.000192142f,1.15648e-016f},{-0.988837f,0.149002f,1.41928e-016f},{-0.988875f,-0.148747f,1.64758e-016f}, +{-0.988831f,-0.14904f,1.46641e-016f},{-0.826202f,0.563374f,-1.42465e-016f},{-0.826294f,0.563239f,-2.46664e-016f}, +{-0.900926f,0.433972f,-1.44341e-016f},{-0.900997f,0.433825f,-1.8293e-016f},{-0.955592f,0.294693f,2.21025e-017f}, +{-0.955531f,0.294892f,-8.84043e-017f},{-0.500166f,0.865929f,8.54658e-017f},{-0.623628f,0.781722f,1.15799e-016f}, +{-0.623458f,0.781857f,-9.38496e-017f},{-0.733149f,0.680068f,-2.82023e-016f},{-0.733007f,0.680221f,2.48139e-016f}, +{-0.222715f,0.974884f,2.24527e-016f},{-0.365343f,0.930873f,-4.86352e-016f},{-0.222546f,0.974922f,-2.35147e-016f}, +{-0.50001f,0.866019f,-4.57607e-016f},{-0.365619f,0.930764f,-7.09272e-017f},{-0.0740373f,0.997256f,-8.24722e-016f}, +{-0.0750446f,0.99718f,1.54166e-016f},{0.0763749f,0.997079f,-4.98902e-017f},{0.0743287f,0.997234f,5.83357e-016f}, +{0.222287f,0.974981f,9.80286e-017f},{0.222517f,0.974929f,1.42064e-016f},{0.365439f,0.930835f,5.09861e-016f}, +{0.365262f,0.930905f,1.5733e-016f},{-0.988805f,0.149216f,-1.19093e-016f},{1.66533e-016f,0.0f,1.0f}, +{-0.669069f,-0.7432f,-6.19013e-017f},{-0.668748f,-0.743489f,1.37573e-016f},{-0.999999f,-0.00162868f,4.62592e-017f}, +{-0.977876f,-0.209183f,-3.87067e-017f},{-0.97822f,-0.207569f,3.8408e-017f},{-0.913137f,-0.407652f,-8.44822e-017f}, +{-0.80856f,-0.588414f,-7.48068e-017f},{-0.809021f,-0.58778f,1.83611e-016f},{-0.913805f,0.406154f,1.1273e-016f}, +{-0.913335f,0.40721f,1.17599e-016f},{-0.809321f,0.587366f,9.17809e-017f},{-1.0f,0.000654662f,4.63199e-017f}, +{-0.977984f,0.208678f,-4.52409e-017f},{-0.978488f,0.206306f,0.0f},{-0.66791f,0.744242f,2.59976e-016f}, +{-0.498589f,0.866839f,3.03496e-016f},{-0.500567f,0.865698f,-2.80802e-016f},{-0.669713f,0.74262f,-4.64706e-017f}, +{-0.808642f,0.588301f,-6.29396e-017f},{-0.30778f,0.951458f,-1.52132e-017f},{-0.103531f,0.994626f,-7.81241e-017f}, +{-0.104646f,0.99451f,-2.59082e-016f},{-0.30935f,0.950948f,-3.73917e-016f},{0.104522f,0.994523f,1.24387e-016f}, +{0.105302f,0.99444f,-4.17065e-017f},{0.309506f,0.950897f,1.46431e-016f},{0.309096f,0.951031f,1.48399e-016f}, +{-0.913594f,-0.406629f,8.45244e-017f},{0.610525f,-0.791997f,-1.1297e-016f},{0.710244f,-0.703955f,2.60516e-016f}, +{0.710171f,-0.704029f,3.2511e-016f},{0.610478f,-0.792033f,4.06072e-016f},{0.5f,-0.866025f,2.29636e-016f}, +{0.797393f,-0.603461f,7.37737e-017f},{0.797309f,-0.603571f,7.37659e-017f},{0.870426f,-0.492299f,-2.62718e-016f}, +{0.928052f,-0.372451f,-5.19725e-017f},{0.928002f,-0.372576f,-8.58574e-017f},{0.87035f,-0.492434f,2.03427e-016f}, +{0.969228f,-0.246163f,2.70442e-016f},{0.969268f,-0.246008f,9.10412e-017f},{0.993332f,-0.115288f,-4.26652e-017f}, +{0.993343f,-0.115195f,0.0f},{0.999833f,0.0182988f,-1.35438e-017f},{0.999847f,0.017496f,1.97958e-016f}, +{0.988478f,0.151367f,0.0f},{0.98869f,0.149972f,-2.93946e-016f},{0.959985f,0.280053f,0.0f}, +{0.959982f,0.280063f,-2.07288e-016f},{0.914302f,0.405032f,0.0f},{0.380681f,-0.924706f,-1.76101e-017f}, +{0.380627f,-0.924729f,-1.38377e-016f},{0.254521f,-0.967067f,-1.76609e-017f},{0.254621f,-0.967041f,5.8393e-016f}, +{0.123916f,-0.992293f,1.06136e-016f},{0.124053f,-0.992276f,3.32784e-016f},{-0.00871499f,-0.999962f,-1.40587e-016f}, +{-0.00886925f,-0.999961f,-2.79596e-016f},{-0.141474f,-0.989942f,-3.33647e-016f},{-0.141341f,-0.989961f,2.25705e-016f}, +{-0.271585f,-0.962414f,-4.06693e-016f},{-0.271431f,-0.962458f,-1.92792e-016f},{-0.396824f,-0.917895f,2.45566e-016f}, +{-0.39691f,-0.917858f,3.42831e-016f},{-0.515764f,-0.856731f,3.68103e-016f},{-0.515076f,-0.857145f,-2.27015e-016f}, +{-0.625326f,-0.780363f,1.50692e-016f},{-0.624225f,-0.781245f,7.84799e-016f},{-0.722525f,-0.691345f,-6.59161e-016f}, +{-0.722532f,-0.691337f,-3.47879e-016f},{-0.807919f,-0.589293f,0.0f},{-0.740644f,-0.671898f,0.0f}, +{0.952202f,0.305468f,0.0f},{0.365262f,-0.930905f,0.0f},{-0.0750445f,-0.99718f,0.0f}, +{-0.0740373f,-0.997255f,-9.22647e-017f},{0.0743287f,-0.997234f,-1.37536e-017f},{0.0763749f,-0.997079f,9.22484e-017f}, +{0.222517f,-0.974929f,0.0f},{-0.500166f,-0.865929f,4.00573e-017f},{-0.623458f,-0.781857f,0.0f}, +{-0.222715f,-0.974884f,-4.12105e-017f},{-0.365619f,-0.930764f,-8.6113e-017f},{-0.365343f,-0.930873f,-2.45868e-016f}, +{-0.900997f,-0.433825f,1.89872e-016f},{-0.900926f,-0.433972f,-2.26931e-016f},{-0.826294f,-0.563239f,6.342e-017f}, +{-0.826202f,-0.563374f,-1.025e-016f},{-0.733007f,-0.680221f,2.34917e-016f},{-0.733149f,-0.680068f,4.38439e-016f}, +{-1.0f,-0.000192253f,-1.61925e-016f},{-0.988805f,-0.149217f,-6.57636e-016f},{-0.988837f,-0.149001f,-2.20099e-016f}, +{-0.955531f,-0.294892f,2.17468e-016f},{-0.955592f,-0.294693f,4.48866e-016f},{-0.955631f,0.294565f,-2.04833e-016f}, +{-0.988831f,0.14904f,5.69462e-017f},{-0.95558f,0.294731f,2.37133e-016f},{-1.0f,-1.20654e-005f,1.85036e-016f}, +{-0.988875f,0.148747f,-7.37777e-017f},{-0.900667f,0.43451f,9.83788e-017f},{-0.901106f,0.4336f,-8.21154e-017f}, +{-0.825308f,0.564682f,-4.24488e-017f},{-0.826465f,0.562987f,-1.95228e-016f},{-0.733215f,0.679997f,9.80932e-017f}, +{-0.733055f,0.68017f,-2.6778e-016f},{-0.623408f,0.781897f,7.95767e-017f},{-0.623556f,0.781778f,-2.53269e-016f}, +{-0.623627f,-0.781722f,2.30789e-016f},{-0.222546f,-0.974922f,9.01984e-017f},{0.309096f,-0.951031f,1.47379e-016f}, +{0.309506f,-0.950897f,1.75951e-016f},{-0.498589f,-0.866839f,5.71343e-017f},{-0.30778f,-0.951458f,5.69507e-017f}, +{-0.30935f,-0.950948f,0.0f},{-0.103531f,-0.994626f,1.74464e-016f},{0.105302f,-0.99444f,-1.84008e-016f}, +{0.104522f,-0.994523f,0.0f},{-0.808642f,-0.588301f,5.77928e-017f},{-0.809321f,-0.587366f,-2.0535e-017f}, +{-0.913335f,-0.40721f,-2.79887e-017f},{-0.500567f,-0.865698f,1.3703e-016f},{-0.669713f,-0.74262f,1.37412e-016f}, +{-0.66791f,-0.744242f,-9.97533e-017f},{-0.978488f,-0.206306f,8.45297e-017f},{-0.999999f,0.00162857f,6.92005e-017f}, +{-1.0f,-0.000654662f,-8.10446e-017f},{-0.977984f,-0.208678f,-1.83989e-016f},{-0.913805f,-0.406154f,1.59697e-016f}, +{-0.977876f,0.209184f,-1.85957e-017f},{-0.913137f,0.407652f,6.751e-017f},{-0.913594f,0.406629f,-1.81309e-016f}, +{-0.97822f,0.207569f,1.21186e-016f},{-0.809021f,0.58778f,4.45898e-017f},{-0.80856f,0.588414f,-1.89321e-016f}, +{-0.668748f,0.743489f,-2.18469e-016f},{-0.669069f,0.7432f,-4.4842e-017f},{-0.104646f,-0.99451f,-1.93703e-016f}, +{0.99153f,-0.129881f,0.0f},{1.0f,9.4369e-017f,0.0f},{0.991435f,-0.130601f,0.0f}, +{0.866063f,-0.499936f,0.0f},{0.923898f,-0.38264f,0.0f},{0.865926f,-0.500171f,0.0f}, +{0.965902f,-0.258907f,0.0f},{0.966265f,-0.257551f,0.0f},{0.608701f,-0.7934f,0.0f}, +{0.499909f,-0.866078f,0.0f},{0.608898f,-0.793249f,0.0f},{0.70708f,-0.707134f,0.0f}, +{0.707182f,-0.707032f,0.0f},{0.793414f,-0.608682f,0.0f},{0.130634f,-0.991431f,0.0f}, +{0.258991f,-0.96588f,0.0f},{0.130461f,-0.991453f,0.0f},{0.382876f,-0.9238f,0.0f}, +{0.382576f,-0.923924f,0.0f},{0.258717f,-0.965953f,0.0f},{-0.130461f,-0.991453f,0.0f}, +{-0.258991f,-0.96588f,0.0f},{-0.258717f,-0.965953f,0.0f},{-0.130634f,-0.991431f,0.0f}, +{-0.500177f,-0.865923f,0.0f},{-0.608898f,-0.793249f,0.0f},{-0.499909f,-0.866078f,0.0f}, +{-0.382576f,-0.923924f,0.0f},{-0.382876f,-0.9238f,0.0f},{-0.707182f,-0.707032f,0.0f}, +{-0.793414f,-0.608682f,0.0f},{-0.70708f,-0.707133f,0.0f},{-0.608701f,-0.7934f,0.0f}, +{-0.793302f,-0.608828f,0.0f},{-0.866063f,-0.499935f,0.0f},{-0.923898f,-0.38264f,0.0f}, +{-0.865926f,-0.500171f,0.0f},{-0.923984f,-0.382431f,0.0f},{-0.965902f,-0.258907f,0.0f}, +{-0.991435f,-0.130601f,0.0f},{-0.966265f,-0.257551f,0.0f},{-0.99153f,-0.129881f,0.0f}, +{0.500177f,-0.865923f,0.0f},{0.793302f,-0.608828f,0.0f},{0.923984f,-0.382431f,0.0f}, +{0.984809f,-0.173642f,0.0f},{1.0f,1.57282e-016f,0.0f},{0.765765f,-0.64312f,0.0f}, +{0.766272f,-0.642516f,0.0f},{0.865946f,-0.500137f,0.0f},{0.939669f,-0.342084f,0.0f}, +{0.866231f,-0.499643f,0.0f},{0.939879f,-0.341507f,0.0f},{0.341751f,-0.939791f,0.0f}, +{0.173343f,-0.984861f,0.0f},{0.342031f,-0.939689f,0.0f},{0.642133f,-0.766593f,0.0f}, +{0.499517f,-0.866304f,0.0f},{0.50031f,-0.865846f,0.0f},{-0.342031f,-0.939689f,0.0f}, +{-0.173343f,-0.984861f,0.0f},{-0.173688f,-0.984801f,0.0f},{3.70074e-017f,-1.0f,0.0f}, +{3.23815e-017f,-1.0f,0.0f},{-0.642133f,-0.766593f,0.0f},{-0.50031f,-0.865846f,0.0f}, +{-0.499517f,-0.866304f,0.0f},{-0.766272f,-0.642516f,0.0f},{-0.865946f,-0.500137f,0.0f}, +{-0.765765f,-0.64312f,0.0f},{-0.866231f,-0.499643f,0.0f},{-0.939669f,-0.342084f,0.0f}, +{-0.984809f,-0.173642f,0.0f},{-0.939879f,-0.341507f,0.0f},{-0.984871f,-0.173291f,0.0f}, +{-0.341751f,-0.939791f,0.0f},{0.173688f,-0.984801f,0.0f},{0.984871f,-0.173291f,0.0f}, +{0.152121f,0.988362f,0.0f},{1.20609e-016f,1.0f,0.0f},{-0.134181f,0.990957f,0.0f}, +{0.424076f,0.905627f,0.0f},{0.307814f,0.951446f,0.0f},{0.587751f,0.809042f,0.0f}, +{0.66247f,0.749088f,0.0f},{0.950842f,0.309676f,0.0f},{0.807656f,0.589654f,0.0f}, +{0.846384f,0.532573f,0.0f},{0.961226f,0.275761f,0.0f},{-0.309304f,0.950963f,0.0f}, +{-0.409073f,0.912502f,0.0f},{-0.588229f,0.808694f,0.0f},{-0.811958f,0.583716f,0.0f}, +{-0.6509f,0.759164f,0.0f},{-0.952103f,0.305779f,0.0f},{-0.84017f,0.542323f,0.0f}, +{-0.962625f,0.270837f,0.0f},{-1.0f,-1.18424e-015f,0.0f},{-1.0f,1.11022e-015f,0.0f}, +{0.317028f,0.948416f,0.0f},{0.594315f,0.804232f,0.0f},{0.812715f,0.582662f,0.0f}, +{0.952238f,0.305357f,0.0f},{0.00550409f,0.999985f,0.0f},{-5.5717e-017f,1.0f,0.0f}, +{-0.306183f,0.951973f,0.0f},{-0.584702f,0.811248f,0.0f},{-0.80785f,0.589388f,0.0f}, +{-0.954037f,0.299688f,0.0f},{-1.0f,-5.92119e-016f,0.0f},{-1.0f,-6.66134e-016f,0.0f}, +{3.70074e-017f,1.0f,3.42388e-034f},{-0.307814f,0.951446f,5.69571e-018f},{4.16334e-017f,1.0f,3.85186e-034f}, +{0.587751f,0.809042f,2.78932e-017f},{0.309304f,0.950963f,3.37619e-017f},{0.588229f,0.808694f,1.0203e-017f}, +{0.307814f,0.951446f,-2.84786e-018f},{0.807656f,0.589654f,7.32347e-018f},{0.952103f,0.305779f,-2.03109e-017f}, +{0.950842f,0.309676f,-7.83488e-018f},{0.811958f,0.583716f,-2.06583e-017f},{1.0f,-1.66533e-016f,0.0f}, +{-0.587751f,0.809042f,-1.49703e-017f},{-0.588229f,0.808694f,-1.08844e-017f},{-0.811958f,0.583716f,-3.00485e-017f}, +{-0.807656f,0.589654f,-1.09108e-017f},{-0.952103f,0.305779f,0.0f},{-0.950842f,0.309676f,0.0f}, +{-1.0f,-6.93889e-017f,0.0f},{0.568191f,0.822897f,0.0f},{0.353989f,0.935249f,0.0f}, +{0.354494f,0.935058f,0.0f},{0.120012f,0.992772f,0.0f},{0.567703f,0.823234f,0.0f}, +{0.120619f,0.992699f,0.0f},{0.748241f,0.663427f,0.0f},{0.748664f,0.662949f,0.0f}, +{0.885281f,0.465056f,0.0f},{-0.12025f,0.992744f,0.0f},{0.885683f,0.46429f,0.0f}, +{0.970894f,0.239511f,0.0f},{0.971f,0.239079f,0.0f},{-0.12127f,0.99262f,0.0f}, +{-0.35609f,0.934452f,0.0f},{-0.354397f,0.935095f,0.0f},{-0.567931f,0.823076f,0.0f}, +{-0.569129f,0.822248f,0.0f},{-0.74925f,0.662288f,0.0f},{-0.748191f,0.663484f,0.0f}, +{-0.885933f,0.463813f,0.0f},{-0.885106f,0.465389f,0.0f},{-0.970869f,0.23961f,0.0f}, +{-0.971139f,0.238516f,0.0f},{-1.0f,1.45407e-013f,0.0f},{-1.0f,2.2119e-011f,0.0f}, +{0.0806869f,-0.224573f,-0.971111f},{0.115976f,-0.167824f,-0.978971f},{0.0936942f,-0.206583f,-0.973933f}, +{0.212777f,0.00431306f,-0.977091f},{0.17217f,-0.0544436f,-0.983562f},{0.210353f,-0.0150728f,-0.977509f}, +{0.24749f,0.000588626f,-0.96889f},{0.200182f,-0.0534267f,-0.978301f},{0.239984f,-0.0200864f,-0.970569f}, +{0.0134776f,0.00860874f,-0.999872f},{0.0558224f,0.0575724f,-0.996779f},{0.0228466f,0.0251275f,-0.999423f}, +{0.131908f,-0.119876f,-0.983987f},{0.135331f,-0.114692f,-0.98414f},{0.106577f,-0.0967618f,-0.989585f}, +{0.127565f,-0.127645f,-0.983582f},{0.0434816f,0.0682479f,-0.99672f},{0.0416591f,0.0621953f,-0.997194f}, +{0.0678076f,0.102888f,-0.992379f},{-0.0134804f,-0.00861069f,-0.999872f},{-0.0558295f,-0.0575731f,-0.996779f}, +{-0.0228463f,-0.0251269f,-0.999423f},{0.042481f,0.0700992f,-0.996635f},{0.0389583f,0.0679419f,-0.996928f}, +{0.0312083f,0.0653011f,-0.997377f},{-0.0488646f,0.0236813f,-0.998525f},{-0.0123869f,0.00381403f,-0.999916f}, +{-0.122955f,0.136635f,-0.982961f},{-0.0744603f,0.15616f,-0.984921f},{-0.11848f,0.146051f,-0.982157f}, +{-0.20018f,0.0534268f,-0.978301f},{-0.239985f,0.0200864f,-0.970569f},{-0.247488f,-0.000588612f,-0.968891f}, +{-0.0911775f,-0.0374113f,-0.995132f},{-0.164561f,0.091503f,-0.982113f},{-0.132869f,0.129057f,-0.982695f}, +{-0.128065f,0.138732f,-0.982015f},{-0.253059f,-0.0201007f,-0.967242f},{-0.207008f,0.0338838f,-0.977752f}, +{-0.0937007f,0.206583f,-0.973932f},{-0.126712f,0.149271f,-0.980644f},{-0.113835f,0.164764f,-0.979742f}, +{-0.0806854f,0.224573f,-0.971111f},{-0.115975f,0.167824f,-0.978971f},{-0.0476595f,0.282538f,-0.958071f}, +{-0.0601369f,0.245617f,-0.9675f},{-0.099067f,0.189505f,-0.976869f},{-0.0257387f,0.300652f,-0.953386f}, +{-0.0999932f,0.189498f,-0.976776f},{-0.108516f,0.173184f,-0.978893f},{-0.107387f,0.17428f,-0.978823f}, +{-0.155908f,0.110576f,-0.981563f},{-0.107733f,0.172359f,-0.979125f},{-0.0781727f,0.233122f,-0.9693f}, +{0.00667651f,0.0246582f,-0.999674f},{0.0165896f,0.0396375f,-0.999076f},{-0.105383f,0.17193f,-0.979456f}, +{0.0619015f,0.0809495f,-0.994794f},{0.00832976f,-0.0847504f,-0.996367f},{-0.0744356f,-0.126144f,-0.989215f}, +{-0.0300614f,-0.145127f,-0.988956f},{-0.0434816f,-0.068248f,-0.99672f},{-0.0678076f,-0.102888f,-0.992379f}, +{-0.0424824f,-0.0700993f,-0.996635f},{0.0309353f,0.0400397f,-0.998719f},{0.105381f,-0.171931f,-0.979456f}, +{0.118496f,-0.146014f,-0.98216f},{0.0744765f,-0.156159f,-0.98492f},{0.00348893f,-0.00830625f,-0.999959f}, +{0.0123794f,-0.00381472f,-0.999916f},{0.139631f,-0.110247f,-0.984047f},{0.139617f,-0.112341f,-0.983812f}, +{0.168792f,-0.0732426f,-0.982927f},{0.135427f,-0.123518f,-0.983058f},{0.131599f,-0.131651f,-0.982522f}, +{0.255848f,0.0391961f,-0.965922f},{0.0990662f,-0.189505f,-0.976869f},{0.207001f,-0.033884f,-0.977754f}, +{0.0257381f,-0.300652f,-0.953386f},{0.0601361f,-0.245617f,-0.9675f},{0.0476609f,-0.282538f,-0.958071f}, +{0.108819f,-0.168871f,-0.979613f},{0.0781673f,-0.233124f,-0.9693f},{0.107726f,-0.172348f,-0.979128f}, +{0.071609f,-0.249664f,-0.965681f},{0.0999793f,-0.189499f,-0.976777f},{0.18367f,0.0228704f,-0.982722f}, +{0.143043f,-0.0368726f,-0.989029f},{-0.0165949f,-0.039638f,-0.999076f},{-0.031216f,-0.0653017f,-0.997377f}, +{0.138156f,-0.116935f,-0.983483f},{0.15591f,-0.110576f,-0.981563f},{0.189495f,-0.0760762f,-0.97893f}, +{0.253055f,0.0201006f,-0.967243f},{0.113819f,-0.164768f,-0.979743f},{0.110674f,-0.169985f,-0.979212f}, +{0.142319f,-0.13279f,-0.980873f},{0.0638565f,-0.265747f,-0.961926f},{0.111105f,-0.162971f,-0.980355f}, +{0.11444f,-0.155086f,-0.98125f},{0.0654512f,-0.217303f,-0.973907f},{0.122963f,-0.13662f,-0.982962f}, +{-0.0416577f,-0.0621948f,-0.997194f},{-0.0619016f,-0.0809495f,-0.994794f},{0.074428f,0.126144f,-0.989216f}, +{-0.10656f,0.0967627f,-0.989587f},{0.030073f,0.145128f,-0.988956f},{-0.132285f,0.119253f,-0.984012f}, +{-0.127537f,0.127694f,-0.98358f},{0.112261f,0.173544f,-0.978407f},{0.114801f,0.194823f,-0.974097f}, +{0.037314f,0.0525697f,-0.99792f},{0.107531f,0.153096f,-0.982343f},{0.102693f,0.132768f,-0.985813f}, +{0.0488762f,-0.0236802f,-0.998524f},{0.0911884f,0.0374122f,-0.995131f},{-0.0343818f,-0.207914f,-0.977543f}, +{-0.114804f,-0.194823f,-0.974097f},{-0.112265f,-0.173544f,-0.978406f},{-0.10753f,-0.153096f,-0.982344f}, +{-0.0373124f,-0.0525692f,-0.99792f},{-0.0309343f,-0.0400395f,-0.998719f},{-0.102696f,-0.132768f,-0.985812f}, +{-0.00349236f,0.00830612f,-0.999959f},{-0.143026f,0.0368738f,-0.989032f},{-0.172172f,0.0544429f,-0.983561f}, +{-0.108774f,0.16898f,-0.979599f},{-0.0716214f,0.249662f,-0.965681f},{-0.110692f,0.169978f,-0.979211f}, +{-0.183652f,-0.0228691f,-0.982725f},{-0.111114f,0.16297f,-0.980354f},{-0.114446f,0.155082f,-0.98125f}, +{-0.00831784f,0.0847515f,-0.996367f},{0.0256814f,0.0524475f,-0.998293f},{0.0332888f,0.0620644f,-0.997517f}, +{-0.212779f,-0.0043133f,-0.977091f},{-0.168808f,0.0732415f,-0.982924f},{-0.136682f,0.120661f,-0.983239f}, +{-0.139069f,0.114346f,-0.983659f},{-0.210368f,0.0150721f,-0.977506f},{-0.117902f,0.15764f,-0.980433f}, +{0.126705f,-0.149271f,-0.980645f},{0.164554f,-0.0915033f,-0.982115f},{0.117888f,-0.157641f,-0.980434f}, +{0.127125f,-0.140533f,-0.981881f},{0.122423f,-0.149416f,-0.981166f},{0.108474f,-0.173236f,-0.978889f}, +{0.257551f,0.0589452f,-0.964465f},{0.107335f,-0.174359f,-0.978815f},{0.239876f,0.0787303f,-0.967606f}, +{0.151587f,0.0943229f,-0.983933f},{0.138183f,-0.110958f,-0.984172f},{-0.00668129f,-0.0246587f,-0.999674f}, +{0.0971757f,0.111226f,-0.989033f},{-0.0256865f,-0.0524476f,-0.998293f},{-0.0389615f,-0.067942f,-0.996928f}, +{-0.033293f,-0.0620642f,-0.997517f},{0.0343964f,0.207915f,-0.977542f},{-0.135944f,0.113842f,-0.984154f}, +{-0.097181f,-0.111227f,-0.989032f},{-0.065439f,0.217303f,-0.973908f},{-0.139838f,0.110719f,-0.983965f}, +{-0.13881f,0.110345f,-0.984152f},{-0.239861f,-0.0787291f,-0.96761f},{-0.151574f,-0.0943219f,-0.983935f}, +{-0.257556f,-0.0589451f,-0.964464f},{-0.255863f,-0.0391964f,-0.965918f},{-0.0638606f,0.265747f,-0.961925f}, +{-0.122911f,0.148539f,-0.981239f},{-0.189496f,0.0760762f,-0.97893f},{-0.14232f,0.13279f,-0.980873f}, +{-0.410005f,-0.780986f,0.471123f},{-0.431924f,-0.756474f,0.491109f},{-0.406453f,-0.879699f,0.246832f}, +{-0.444614f,-0.738683f,0.506622f},{-0.428298f,-0.85525f,0.291734f},{-0.420701f,-0.718444f,0.553939f}, +{-0.415692f,-0.815118f,0.403464f},{-0.437394f,-0.721373f,0.536943f},{-0.430102f,-0.824692f,0.367282f}, +{-0.434004f,-0.838017f,0.330708f},{-0.44473f,-0.728083f,0.521641f},{-0.268829f,-0.797562f,0.540024f}, +{-0.258175f,-0.722769f,0.641055f},{-0.275537f,-0.774815f,0.568982f},{-0.352408f,-0.728926f,0.58692f}, +{-0.277529f,-0.733033f,0.620999f},{-0.28748f,-0.816277f,0.501046f},{-0.249748f,-0.689892f,0.679467f}, +{-0.215302f,-0.725361f,0.653833f},{-0.256534f,-0.738897f,0.623074f},{-0.261868f,-0.698996f,0.665454f}, +{-0.271108f,-0.755933f,0.595873f},{-0.264635f,-0.709599f,0.653021f},{0.0526752f,-0.683243f,0.728289f}, +{0.0541363f,-0.696338f,0.715669f},{0.0539424f,-0.667359f,0.74278f},{-0.0721475f,-0.716045f,0.694315f}, +{-0.211833f,-0.683867f,0.698178f},{-0.0718111f,-0.680519f,0.729203f},{0.052782f,-0.660486f,0.748981f}, +{0.0443778f,-0.671599f,0.739585f},{0.0438809f,-0.654656f,0.754652f},{0.0375909f,-0.660388f,0.749983f}, +{0.0241761f,-0.649023f,0.760385f},{0.0363458f,-0.648963f,0.759951f},{0.022026f,-0.643221f,0.765363f}, +{0.00631787f,-0.636811f,0.770994f},{0.0031649f,-0.636821f,0.771005f},{-0.355684f,-0.818732f,0.45074f}, +{-0.371045f,-0.909063f,0.18955f},{-0.405078f,-0.583044f,0.704253f},{-0.421979f,-0.580905f,0.696048f}, +{-0.431996f,-0.756391f,0.491175f},{-0.432024f,-0.581257f,0.689562f},{-0.444614f,-0.738684f,0.506621f}, +{-0.352294f,-0.728943f,0.586967f},{-0.420702f,-0.718445f,0.553937f},{-0.410108f,-0.59918f,0.687601f}, +{-0.437394f,-0.721374f,0.536941f},{-0.44473f,-0.728085f,0.521639f},{-0.431774f,-0.585021f,0.686528f}, +{-0.258155f,-0.722817f,0.641008f},{-0.239661f,-0.63406f,0.735208f},{-0.264648f,-0.709547f,0.653073f}, +{-0.336563f,-0.618695f,0.709888f},{-0.25777f,-0.632115f,0.730743f},{-0.27756f,-0.733036f,0.620982f}, +{-0.238256f,-0.634072f,0.735654f},{-0.211913f,-0.683867f,0.698154f},{-0.249749f,-0.689931f,0.679427f}, +{-0.246966f,-0.633237f,0.733498f},{-0.261827f,-0.698956f,0.665513f},{-0.24717f,-0.633257f,0.733412f}, +{0.0527819f,-0.660487f,0.74898f},{0.0540166f,-0.667343f,0.742789f},{0.0563396f,-0.634508f,0.77086f}, +{-0.0720207f,-0.680531f,0.729171f},{-0.204102f,-0.636975f,0.743375f},{-0.0680582f,-0.640402f,0.765018f}, +{0.055102f,-0.63474f,0.770759f},{0.0438808f,-0.654657f,0.754651f},{0.0454974f,-0.635485f,0.770772f}, +{0.0363458f,-0.648964f,0.759951f},{0.0219575f,-0.643198f,0.765385f},{0.0371135f,-0.63602f,0.77078f}, +{0.0218202f,-0.636578f,0.770903f},{0.0020686f,-0.636823f,0.771008f},{-0.425392f,-0.590849f,0.685521f}, +{-0.355736f,-0.325002f,0.876256f},{-0.376871f,-0.358337f,0.854144f},{-0.422036f,-0.5809f,0.696018f}, +{-0.390634f,-0.386348f,0.835548f},{-0.336442f,-0.618721f,0.709923f},{-0.410108f,-0.59918f,0.687601f}, +{-0.370105f,-0.46456f,0.804491f},{-0.394435f,-0.412203f,0.821285f},{-0.392371f,-0.437394f,0.809155f}, +{-0.239634f,-0.634063f,0.735214f},{-0.218199f,-0.539451f,0.813254f},{-0.24719f,-0.633254f,0.733407f}, +{-0.276989f,-0.497609f,0.821986f},{-0.210792f,-0.522063f,0.826449f},{-0.257804f,-0.632111f,0.730734f}, +{-0.110113f,-0.595637f,0.795671f},{-0.204172f,-0.63697f,0.743359f},{-0.223171f,-0.580852f,0.782819f}, +{-0.238249f,-0.634073f,0.735655f},{-0.246939f,-0.633239f,0.733505f},{-0.224079f,-0.567772f,0.792101f}, +{0.055102f,-0.63474f,0.770759f},{0.0564151f,-0.634503f,0.770859f},{0.0620428f,-0.606196f,0.792892f}, +{-0.0682671f,-0.640405f,0.764997f},{0.0414768f,-0.59941f,0.799366f},{0.0507293f,-0.614526f,0.787264f}, +{0.0454974f,-0.635485f,0.770772f},{0.0411515f,-0.622011f,0.781926f},{0.0217483f,-0.63658f,0.770904f}, +{0.024754f,-0.629429f,0.776664f},{0.0031651f,-0.636821f,0.771005f},{-0.226089f,-0.554028f,0.80121f}, +{-0.260709f,-0.018211f,0.965246f},{-0.29234f,-0.0905301f,0.95202f},{-0.376958f,-0.35848f,0.854046f}, +{-0.394436f,-0.412236f,0.821268f},{-0.39064f,-0.386367f,0.835537f},{-0.316442f,-0.150845f,0.936541f}, +{-0.27707f,-0.497587f,0.821973f},{-0.369949f,-0.464644f,0.804515f},{-0.326359f,-0.302136f,0.895658f}, +{-0.392367f,-0.43742f,0.809143f},{-0.331158f,-0.203847f,0.921293f},{-0.218211f,-0.539469f,0.813239f}, +{-0.186125f,-0.436519f,0.880232f},{-0.226126f,-0.554148f,0.801116f},{-0.234204f,-0.351848f,0.906284f}, +{-0.172939f,-0.39662f,0.901546f},{-0.210966f,-0.521912f,0.826499f},{-0.205901f,-0.526859f,0.824636f}, +{-0.110847f,-0.595587f,0.795606f},{-0.223412f,-0.580769f,0.782812f},{-0.202182f,-0.499197f,0.842571f}, +{-0.224072f,-0.567787f,0.792092f},{-0.198592f,-0.469626f,0.86024f},{0.0682852f,-0.579246f,0.812288f}, +{0.0620078f,-0.606222f,0.792874f},{0.0488013f,-0.564062f,0.824289f},{0.0416336f,-0.599414f,0.799355f}, +{-0.0985182f,-0.5515f,0.828337f},{0.056183f,-0.594988f,0.801768f},{0.0507196f,-0.614534f,0.787258f}, +{0.0411442f,-0.622016f,0.781923f},{0.0457027f,-0.609128f,0.791754f},{0.0285242f,-0.622938f,0.781751f}, +{0.0246587f,-0.629464f,0.776638f},{0.00635625f,-0.636811f,0.770994f},{-0.340146f,-0.25357f,0.90554f}, +{0.0457539f,-0.608772f,0.792025f},{0.055249f,-0.594765f,0.801999f},{0.0450032f,-0.608898f,0.791971f}, +{0.0284547f,-0.622817f,0.78185f},{0.0279898f,-0.622836f,0.781851f},{0.0688727f,-0.562516f,0.823913f}, +{0.0490876f,-0.563156f,0.824891f},{-0.0496963f,-0.550993f,0.833029f},{0.0683527f,-0.578569f,0.812765f}, +{0.0665103f,-0.579246f,0.812435f},{0.0562578f,-0.594461f,0.802154f},{-0.198149f,-0.468103f,0.861172f}, +{-0.198042f,-0.472958f,0.85854f},{-0.201746f,-0.497665f,0.84358f},{-0.205766f,-0.525395f,0.825603f}, +{-0.175094f,-0.529826f,0.829835f},{-0.0989846f,-0.550287f,0.829087f},{-0.181766f,-0.361545f,0.914465f}, +{-0.172451f,-0.394113f,0.902738f},{-0.233674f,-0.349592f,0.907294f},{-0.188934f,-0.441329f,0.87723f}, +{-0.185572f,-0.434558f,0.881319f},{-0.174204f,-0.40436f,0.897856f},{-0.331082f,-0.265363f,0.90552f}, +{-0.339571f,-0.251639f,0.906294f},{-0.33003f,-0.216776f,0.918743f},{-0.32564f,-0.30016f,0.896584f}, +{-0.257875f,-0.314928f,0.913412f},{-0.31893f,-0.16631f,0.933073f},{-0.33061f,-0.202144f,0.921865f}, +{-0.315979f,-0.149463f,0.936919f},{-0.302605f,-0.112599f,0.946442f},{-0.292181f,-0.0899699f,0.952122f}, +{-0.277704f,-0.0515423f,0.959283f},{-0.246428f,0.0205104f,0.968944f},{-0.199807f,-0.50237f,0.84125f}, +{0.00685645f,-0.636809f,0.770991f},{-0.170684f,0.109551f,0.979217f},{-0.206616f,0.0629021f,0.976398f}, +{-0.158053f,0.126478f,0.979297f},{-0.129887f,0.173613f,0.976211f},{-0.114756f,0.190018f,0.975051f}, +{-0.0931162f,0.239086f,0.966523f},{-0.0916011f,0.208979f,0.973621f},{-0.0745052f,0.25458f,0.964177f}, +{-0.13862f,0.146005f,0.979524f},{-0.0499282f,0.270988f,0.961287f},{-0.176521f,0.0935066f,0.979845f}, +{-0.180908f,0.0771143f,0.980472f},{-0.221759f,0.0289222f,0.974672f},{-0.258471f,0.00236958f,0.966016f}, +{-0.114433f,-0.0158869f,0.993304f},{-0.212524f,-0.00500348f,0.977143f},{-0.0688181f,0.0517682f,0.996285f}, +{-0.273986f,-0.0489217f,0.960489f},{-0.271537f,-0.0316006f,0.961909f},{-0.225011f,0.0119369f,0.974283f}, +{-0.0428923f,-0.0491747f,0.997869f},{-8.55582e-007f,-7.949e-008f,1.0f},{-0.0482005f,-0.0683324f,0.996498f}, +{-0.186842f,-0.0802466f,0.979107f},{-0.0392859f,-0.028666f,0.998817f},{-0.102404f,-0.0919448f,0.990485f}, +{-0.057155f,-0.107856f,0.992522f},{0.0265899f,-0.119144f,0.992521f},{-0.0835213f,-0.178742f,0.980345f}, +{-0.00540807f,-0.0192356f,0.9998f},{-0.0535629f,-0.0874508f,0.994728f},{0.158051f,-0.126478f,0.979297f}, +{0.114754f,-0.190018f,0.975051f},{0.129893f,-0.173613f,0.97621f},{0.130935f,-0.127075f,0.983213f}, +{0.168995f,-0.0610101f,0.983727f},{0.0931203f,-0.239086f,0.966523f},{0.0745033f,-0.25458f,0.964177f}, +{0.0916021f,-0.208979f,0.973621f},{0.0499291f,-0.270988f,0.961287f},{0.136947f,-0.158154f,0.977872f}, +{0.170691f,-0.10955f,0.979216f},{0.190497f,-0.0828562f,0.978185f},{0.206614f,-0.0629022f,0.976398f}, +{0.102078f,-0.224388f,0.969139f},{0.142513f,-0.142376f,0.979499f},{0.176539f,-0.0935053f,0.979842f}, +{0.109046f,-0.209369f,0.971737f},{0.0142462f,-0.186808f,0.982293f},{0.180916f,-0.0771131f,0.980471f}, +{0.107117f,-0.19432f,0.975072f},{-0.00908038f,-0.0397896f,0.999167f},{0.0687977f,-0.0517701f,0.996286f}, +{-0.0984282f,-0.14449f,0.984599f},{-0.0930399f,-0.127037f,0.987525f},{-0.103308f,-0.162383f,0.981305f}, +{-0.0885006f,-0.108876f,0.990108f},{0.0090855f,0.03979f,0.999167f},{0.00541255f,0.0192361f,0.9998f}, +{-0.269586f,-0.0667669f,0.960659f},{-0.169012f,0.0610092f,0.983724f},{-0.217019f,0.04552f,0.975106f}, +{-0.267327f,-0.0147946f,0.963492f},{-0.190496f,0.0828563f,0.978185f},{-0.102063f,0.22439f,0.96914f}, +{-0.13693f,0.158156f,0.977874f},{-0.109036f,0.209371f,0.971738f},{-0.142505f,0.142378f,0.9795f}, +{-0.107128f,0.194321f,0.975071f},{-0.130951f,0.127075f,0.983211f},{-0.0142661f,0.186807f,0.982293f}, +{-0.0266103f,0.119142f,0.992521f},{0.083517f,0.178742f,0.980345f},{0.05716f,0.107856f,0.992522f}, +{0.103317f,0.162383f,0.981304f},{0.258468f,-0.00236961f,0.966017f},{0.246429f,-0.0205104f,0.968944f}, +{0.0535675f,0.0874512f,0.994727f},{0.0984279f,0.14449f,0.984599f},{0.0930396f,0.127037f,0.987525f}, +{0.0481988f,0.0683322f,0.996498f},{0.0885078f,0.108876f,0.990107f},{0.0428965f,0.0491751f,0.997869f}, +{0.102401f,0.0919447f,0.990485f},{0.0392909f,0.0286666f,0.998817f},{0.186822f,0.080245f,0.979111f}, +{0.114413f,0.0158852f,0.993306f},{0.269573f,0.0667658f,0.960663f},{0.212507f,0.00500236f,0.977147f}, +{0.273996f,0.0489219f,0.960486f},{0.225019f,-0.0119362f,0.974281f},{0.271553f,0.031601f,0.961904f}, +{0.221777f,-0.0289212f,0.974668f},{0.26733f,0.0147946f,0.963491f},{0.217025f,-0.0455199f,0.975104f}, +{0.138621f,-0.146005f,0.979524f},{-0.00317738f,0.636821f,0.771005f},{-0.0246739f,0.629441f,0.776656f}, +{-0.0279566f,0.623058f,0.781676f},{-0.0551303f,0.595408f,0.80153f},{-0.0449278f,0.609331f,0.791642f}, +{-0.0411546f,0.621971f,0.781958f},{0.0499248f,0.552325f,0.832133f},{-0.0687359f,0.563612f,0.823175f}, +{-0.0416737f,0.599286f,0.79945f},{-0.0663718f,0.580108f,0.811831f},{-0.0507229f,0.614466f,0.787311f}, +{-0.0620227f,0.606128f,0.792945f},{0.223995f,0.567518f,0.792306f},{0.226021f,0.553812f,0.801378f}, +{0.198662f,0.475091f,0.857217f},{0.110786f,0.595421f,0.795739f},{0.223354f,0.58056f,0.782983f}, +{0.175481f,0.531382f,0.828758f},{0.276897f,0.496956f,0.822413f},{0.182559f,0.364365f,0.913187f}, +{0.210821f,0.521383f,0.82687f},{0.174949f,0.407013f,0.896511f},{0.18964f,0.443733f,0.875864f}, +{0.218089f,0.539048f,0.81355f},{0.330803f,0.219259f,0.917875f},{0.331812f,0.268014f,0.904472f}, +{0.392167f,0.436574f,0.809696f},{0.25864f,0.317724f,0.912226f},{0.369772f,0.46392f,0.805014f}, +{0.394193f,0.411246f,0.821881f},{0.319671f,0.168505f,0.932425f},{0.390338f,0.385206f,0.836213f}, +{0.303211f,0.114345f,0.946038f},{0.278069f,0.0525963f,0.95912f},{0.376599f,0.357097f,0.854784f}, +{0.355321f,0.323311f,0.87705f},{0.200313f,0.50421f,0.840028f},{-0.00685578f,0.636809f,0.770991f}, +{-0.002068f,0.636823f,0.771008f},{-0.0217543f,0.63654f,0.770937f},{-0.0247724f,0.629382f,0.776701f}, +{-0.0411683f,0.621921f,0.781997f},{-0.0371196f,0.635941f,0.770844f},{-0.0415314f,0.599172f,0.799542f}, +{-0.0620694f,0.606014f,0.793029f},{-0.056447f,0.634304f,0.77102f},{-0.0507421f,0.614392f,0.787367f}, +{-0.0454985f,0.63537f,0.770866f},{-0.0551123f,0.634587f,0.770884f},{0.223077f,0.580496f,0.78311f}, +{0.238176f,0.633724f,0.735979f},{0.223957f,0.56733f,0.792452f},{0.0682119f,0.64016f,0.765207f}, +{0.204107f,0.63668f,0.743626f},{0.110027f,0.595341f,0.795904f},{0.239503f,0.633497f,0.735744f}, +{0.210588f,0.521305f,0.826979f},{0.21802f,0.538815f,0.813723f},{0.247067f,0.632772f,0.733864f}, +{0.22593f,0.553496f,0.801622f},{0.246834f,0.632828f,0.733895f},{0.392125f,0.436343f,0.809842f}, +{0.369882f,0.463619f,0.805137f},{0.409993f,0.598406f,0.688343f},{0.27676f,0.496749f,0.822584f}, +{0.257657f,0.631462f,0.731347f},{0.336306f,0.618008f,0.710608f},{0.425267f,0.589992f,0.686336f}, +{0.394147f,0.411029f,0.822012f},{0.431633f,0.584074f,0.687423f},{0.390294f,0.385037f,0.836312f}, +{0.376488f,0.356858f,0.854932f},{0.431864f,0.580207f,0.690546f},{0.42187f,0.579716f,0.697105f}, +{0.404919f,0.581686f,0.705466f},{-0.00315153f,0.636821f,0.771006f},{-0.021951f,0.643165f,0.765413f}, +{-0.0218263f,0.636538f,0.770937f},{-0.0363394f,0.6489f,0.760005f},{0.068003f,0.640157f,0.765229f}, +{-0.0563715f,0.63431f,0.771021f},{-0.0540317f,0.667183f,0.742932f},{-0.0438692f,0.654564f,0.754732f}, +{0.238183f,0.633724f,0.735978f},{0.249708f,0.689649f,0.679728f},{0.246861f,0.632825f,0.733889f}, +{0.0719912f,0.680332f,0.72936f},{0.211878f,0.683631f,0.698395f},{0.204036f,0.636685f,0.743641f}, +{0.258076f,0.722371f,0.641543f},{0.257623f,0.631466f,0.731355f},{0.239529f,0.633495f,0.735738f}, +{0.264571f,0.709164f,0.65352f},{0.247047f,0.632774f,0.733869f},{0.261762f,0.698625f,0.665885f}, +{0.420681f,0.717841f,0.554735f},{0.336426f,0.617982f,0.710574f},{0.277479f,0.732529f,0.621616f}, +{0.35224f,0.728388f,0.587689f},{0.437381f,0.720712f,0.537841f},{0.444724f,0.72736f,0.522654f}, +{0.421813f,0.57972f,0.697136f},{0.44462f,0.737892f,0.507768f},{0.432036f,0.755513f,0.492489f}, +{0.4101f,0.780009f,0.472656f},{-0.0527785f,0.660363f,0.74909f},{-0.00629327f,0.636811f,0.770994f}, +{-0.0241581f,0.649001f,0.760404f},{-0.0220195f,0.643189f,0.765391f},{-0.0375725f,0.660345f,0.750022f}, +{-0.0363395f,0.648899f,0.760006f},{0.0717815f,0.680319f,0.729392f},{-0.0539575f,0.667198f,0.742923f}, +{-0.0541337f,0.696227f,0.715778f},{-0.0527786f,0.660362f,0.749091f},{-0.0438693f,0.654563f,0.754733f}, +{-0.0443535f,0.671536f,0.739643f},{0.249707f,0.68961f,0.679768f},{0.256526f,0.738688f,0.623325f}, +{0.261803f,0.698666f,0.665827f},{0.0721451f,0.715903f,0.694462f},{0.215298f,0.725187f,0.654026f}, +{0.211798f,0.683631f,0.69842f},{0.268798f,0.79723f,0.540529f},{0.277449f,0.732527f,0.621633f}, +{0.258096f,0.722323f,0.641589f},{0.275504f,0.774529f,0.569388f},{0.264558f,0.709216f,0.653469f}, +{0.271082f,0.755688f,0.596197f},{0.415759f,0.814669f,0.4043f},{0.420681f,0.717839f,0.554738f}, +{0.355703f,0.818321f,0.451472f},{0.352353f,0.728371f,0.587642f},{0.287459f,0.815902f,0.501668f}, +{0.430194f,0.824211f,0.368252f},{0.444724f,0.727359f,0.522656f},{0.437381f,0.72071f,0.537843f}, +{0.434129f,0.83751f,0.331828f},{0.44462f,0.73789f,0.50777f},{0.431964f,0.755597f,0.492423f}, +{0.428471f,0.854721f,0.293028f},{0.406702f,0.879159f,0.248341f},{0.371402f,0.908545f,0.19133f}, +{-0.0526576f,0.683158f,0.728369f},{-0.0263917f,0.652054f,0.757713f},{-0.00909888f,0.636797f,0.770977f}, +{-0.0536109f,0.695352f,0.716667f},{-0.0443236f,0.671834f,0.739374f},{-0.0456191f,0.680563f,0.731268f}, +{-0.0392338f,0.666389f,0.744571f},{-0.0375531f,0.660552f,0.749841f},{-0.0242147f,0.649157f,0.760269f}, +{0.0720186f,0.716437f,0.693924f},{0.215375f,0.747931f,0.627863f},{0.215321f,0.725786f,0.653354f}, +{-0.0526197f,0.683545f,0.728009f},{-0.055364f,0.711835f,0.700162f},{-0.0540181f,0.69673f,0.715297f}, +{0.279233f,0.809709f,0.516139f},{0.275645f,0.775365f,0.568181f},{0.271283f,0.756476f,0.595104f}, +{0.274244f,0.786708f,0.553065f},{0.256648f,0.739281f,0.622571f},{0.258544f,0.76548f,0.589233f}, +{0.351817f,0.864019f,0.360134f},{0.287541f,0.81663f,0.500435f},{0.289026f,0.85903f,0.42253f}, +{0.268949f,0.797912f,0.539447f},{0.271782f,0.836894f,0.475123f},{0.430114f,0.824737f,0.367166f}, +{0.415694f,0.815277f,0.40314f},{0.415649f,0.87405f,0.251538f},{0.355825f,0.818985f,0.450169f}, +{0.404724f,0.863226f,0.301729f},{0.415023f,0.887621f,0.199712f},{0.434041f,0.837936f,0.330866f}, +{0.403094f,0.903754f,0.144024f},{0.428382f,0.85503f,0.292254f},{0.406518f,0.879434f,0.247668f}, +{0.372382f,0.924662f,0.079571f},{0.325495f,0.945544f,0.0f},{0.0705335f,0.735204f,0.674167f}, +{0.286908f,0.957958f,-0.000297298f},{0.286152f,0.958184f,-0.00027813f},{0.278077f,0.951596f,-0.130911f}, +{0.266505f,0.956115f,-0.121731f},{0.270116f,0.962828f,-0.00025761f},{0.23607f,0.971736f,-0.000235456f}, +{0.258612f,0.959649f,-0.110422f},{0.111685f,0.993744f,-0.000218645f},{0.15671f,0.982441f,-0.101255f}, +{0.0244862f,0.995607f,-0.0903677f},{0.00228008f,0.999997f,-0.000195691f},{0.00864389f,0.999963f,-0.000166398f}, +{0.0121337f,0.996969f,-0.076847f},{0.0172244f,0.999852f,-0.000133472f},{0.0209404f,0.99785f,-0.0620961f}, +{0.0225323f,0.998704f,-0.0456418f},{0.0196045f,0.999808f,-9.71639e-005f},{0.0193212f,0.999813f,-5.4502e-005f}, +{0.0204337f,0.99946f,-0.0257239f},{0.0176994f,0.999843f,0.0f},{0.0173199f,0.99985f,0.0f}, +{0.267273f,0.953349f,-0.140321f},{0.257069f,0.95479f,-0.149306f},{0.271589f,0.962413f,-0.00031666f}, +{0.280293f,0.959914f,-0.000331412f},{0.282163f,0.946687f,-0.155461f},{0.308726f,0.937469f,-0.16075f}, +{0.318966f,0.947766f,-0.000342471f},{0.324966f,0.931085f,-0.165762f},{0.355068f,0.93484f,-0.000351538f}, +{0.370564f,0.928807f,-0.000361614f},{0.330965f,0.928046f,-0.17086f},{0.326564f,0.928594f,-0.176266f}, +{0.376575f,0.926386f,-0.000372148f},{0.30552f,0.934514f,-0.182597f},{0.373027f,0.92782f,-0.000383596f}, +{0.354145f,0.935191f,-0.000397484f},{0.272835f,0.943202f,-0.189554f},{0.325394f,0.945578f,-0.00041274f}, +{0.0211408f,0.997288f,-0.0705025f},{0.0173199f,0.99985f,-1.50134e-014f},{0.0149749f,0.999888f,1.04413e-015f}, +{0.0190992f,0.976903f,-0.212829f},{0.012063f,0.997001f,-0.0764401f},{0.0270514f,0.98481f,-0.171517f}, +{0.0267385f,0.991726f,-0.125559f},{0.0225092f,0.998719f,-0.0453197f},{0.258403f,0.959761f,-0.109939f}, +{0.185186f,0.942002f,-0.279891f},{0.235359f,0.921009f,-0.310401f},{0.0245818f,0.995645f,-0.0899239f}, +{0.060169f,0.966375f,-0.25f},{0.156085f,0.982591f,-0.100754f},{0.242529f,0.898699f,-0.365402f}, +{0.221008f,0.893124f,-0.391771f},{0.26728f,0.953393f,-0.140014f},{0.245706f,0.907932f,-0.33954f}, +{0.27811f,0.951625f,-0.130631f},{0.266559f,0.95615f,-0.121342f},{0.222884f,0.865841f,-0.447931f}, +{0.308832f,0.937463f,-0.160577f},{0.220933f,0.874336f,-0.432117f},{0.282182f,0.946719f,-0.155229f}, +{0.25702f,0.954855f,-0.148975f},{0.223806f,0.882967f,-0.412649f},{0.225231f,0.858059f,-0.461525f}, +{0.330999f,0.928053f,-0.170754f},{0.32502f,0.931092f,-0.165619f},{0.216849f,0.852796f,-0.475096f}, +{0.32658f,0.928602f,-0.176192f},{0.305399f,0.934555f,-0.182588f},{0.192096f,0.850459f,-0.489713f}, +{0.155604f,0.848968f,-0.505015f},{0.0209039f,0.997875f,-0.0617066f},{0.0204365f,0.999463f,-0.0256194f}, +{0.0198325f,0.993882f,-0.108651f},{0.0149749f,0.999888f,0.0f},{0.0107279f,0.999942f,0.0f}, +{0.027494f,0.940471f,-0.338759f},{0.0270456f,0.9848f,-0.171575f},{0.0323478f,0.961911f,-0.271441f}, +{0.0289941f,0.980028f,-0.196733f},{0.0267423f,0.99172f,-0.125606f},{0.0211768f,0.997263f,-0.0708398f}, +{0.184752f,0.942124f,-0.279767f},{0.198008f,0.842424f,-0.501114f},{0.235436f,0.92105f,-0.310221f}, +{0.0190528f,0.976871f,-0.212979f},{0.0630398f,0.914688f,-0.399213f},{0.0602812f,0.96636f,-0.250028f}, +{0.19314f,0.786761f,-0.586263f},{0.167212f,0.763159f,-0.624203f},{0.24247f,0.898676f,-0.365499f}, +{0.245744f,0.907886f,-0.339635f},{0.201874f,0.8124f,-0.547041f},{0.0929333f,0.700686f,-0.707392f}, +{0.220911f,0.874312f,-0.432176f},{0.113967f,0.718951f,-0.685653f},{0.2238f,0.88298f,-0.412625f}, +{0.221072f,0.893172f,-0.391626f},{0.154471f,0.739263f,-0.65546f},{0.0875221f,0.684218f,-0.724006f}, +{0.225226f,0.858048f,-0.461549f},{0.222895f,0.86583f,-0.447948f},{0.073847f,0.669461f,-0.739168f}, +{0.216833f,0.852792f,-0.475111f},{0.191924f,0.850452f,-0.489793f},{0.0484461f,0.655515f,-0.753627f}, +{0.0158475f,0.640906f,-0.767455f},{0.155604f,0.848968f,-0.505015f},{0.164174f,0.877789f,-0.450038f}, +{0.0167192f,0.990338f,-0.137663f},{0.0107279f,0.999942f,-5.79815e-010f},{0.00505961f,0.999987f,0.0f}, +{0.033892f,0.890883f,-0.452967f},{0.0323469f,0.961882f,-0.271545f},{0.0355093f,0.932581f,-0.35921f}, +{0.0291785f,0.966258f,-0.255917f},{0.0290016f,0.980011f,-0.196817f},{0.0198883f,0.993822f,-0.10919f}, +{0.163842f,0.877955f,-0.449834f},{0.13651f,0.780866f,-0.609602f},{0.148479f,0.718253f,-0.679755f}, +{0.0274608f,0.940382f,-0.339011f},{0.0636188f,0.841289f,-0.536829f},{0.0631371f,0.914656f,-0.399272f}, +{0.125965f,0.609067f,-0.783052f},{0.0957412f,0.559997f,-0.822944f},{0.193061f,0.786669f,-0.586412f}, +{0.201887f,0.812292f,-0.547197f},{0.142438f,0.660203f,-0.737458f},{-0.0540079f,0.439944f,-0.896399f}, +{0.113812f,0.718888f,-0.685746f},{-0.0113659f,0.472513f,-0.88125f},{0.154497f,0.739288f,-0.655427f}, +{0.167295f,0.763303f,-0.624004f},{0.06617f,0.514496f,-0.854936f},{-0.0658654f,0.414517f,-0.907655f}, +{0.0875037f,0.684189f,-0.724037f},{0.0929309f,0.700662f,-0.707415f},{-0.0816251f,0.391685f,-0.916472f}, +{0.0738257f,0.669444f,-0.739185f},{0.0482842f,0.65544f,-0.753702f},{-0.101927f,0.369884f,-0.92347f}, +{-0.123605f,0.347635f,-0.929447f},{0.0158475f,0.640907f,-0.767455f},{0.198107f,0.842564f,-0.500839f}, +{0.0111543f,0.989269f,-0.145677f},{0.00505961f,0.999987f,-2.85058e-010f},{-0.00138151f,0.999999f,1.91845e-016f}, +{0.0382111f,0.850391f,-0.524762f},{0.0355133f,0.932523f,-0.359361f},{0.0352909f,0.91244f,-0.407687f}, +{0.0256877f,0.959016f,-0.282185f},{0.0291895f,0.966226f,-0.256037f},{0.0167928f,0.990238f,-0.138374f}, +{0.136305f,0.781126f,-0.609314f},{0.0955151f,0.684245f,-0.72297f},{0.0993674f,0.584646f,-0.805181f}, +{0.0338728f,0.890704f,-0.453319f},{0.0484155f,0.77454f,-0.630669f},{0.0636976f,0.841226f,-0.536918f}, +{0.0560249f,0.401556f,-0.914119f},{0.0268241f,0.326384f,-0.944856f},{0.125862f,0.608874f,-0.783218f}, +{0.0741101f,0.485701f,-0.870978f},{0.142412f,0.659992f,-0.737652f},{0.14861f,0.71855f,-0.679412f}, +{-0.0637993f,0.196022f,-0.978522f},{-0.0116501f,0.472378f,-0.881319f},{0.0662311f,0.514541f,-0.854904f}, +{0.00189659f,0.257578f,-0.966256f},{0.0958443f,0.56027f,-0.822746f},{-0.197306f,0.110962f,-0.974042f}, +{-0.0658928f,0.414469f,-0.907675f},{-0.0540224f,0.439905f,-0.896418f},{-0.164717f,0.144236f,-0.975738f}, +{-0.210934f,0.08502f,-0.973796f},{-0.081646f,0.391658f,-0.916481f},{-0.223578f,0.0624871f,-0.972681f}, +{-0.233506f,0.0413979f,-0.971474f},{-0.102042f,0.369768f,-0.923504f},{0.102044f,-0.369767f,-0.923504f}, +{0.123604f,-0.347635f,-0.929447f},{0.0658736f,-0.414472f,-0.907675f},{0.1973f,-0.110963f,-0.974043f}, +{0.210917f,-0.0850214f,-0.973799f},{0.0816379f,-0.391659f,-0.916482f},{0.223573f,-0.0624874f,-0.972682f}, +{0.233508f,-0.0413979f,-0.971473f},{-0.00190271f,-0.257578f,-0.966256f},{-0.0662188f,-0.51454f,-0.854906f}, +{-0.0958526f,-0.560269f,-0.822746f},{0.164734f,-0.144235f,-0.975735f},{0.0116715f,-0.472379f,-0.881318f}, +{0.0638166f,-0.19602f,-0.978521f},{-0.142412f,-0.659992f,-0.737652f},{-0.148611f,-0.71855f,-0.679412f}, +{-0.0741122f,-0.485701f,-0.870978f},{-0.125862f,-0.608874f,-0.783218f},{-0.0560238f,-0.401556f,-0.914119f}, +{-0.0268274f,-0.326385f,-0.944856f},{-0.0338724f,-0.890704f,-0.453319f},{-0.0484116f,-0.77454f,-0.630669f}, +{-0.0636956f,-0.841226f,-0.536918f},{-0.0955126f,-0.684245f,-0.72297f},{-0.0993696f,-0.584646f,-0.80518f}, +{-0.136306f,-0.781126f,-0.609313f},{-0.0355125f,-0.932523f,-0.35936f},{-0.0352907f,-0.91244f,-0.407686f}, +{-0.0382116f,-0.850391f,-0.524763f},{-0.0291876f,-0.966226f,-0.256036f},{-0.025686f,-0.959016f,-0.282185f}, +{-0.0111537f,-0.989269f,-0.145677f},{-0.0167921f,-0.990238f,-0.138374f},{-0.0050596f,-0.999987f,0.0f}, +{0.00138152f,-0.999999f,-1.73582e-014f},{0.05402f,-0.439909f,-0.896416f},{-0.0482827f,-0.65544f,-0.753702f}, +{-0.0158483f,-0.640906f,-0.767455f},{-0.0929347f,-0.700666f,-0.707411f},{0.0658462f,-0.414519f,-0.907655f}, +{-0.0875227f,-0.68419f,-0.724033f},{-0.0738342f,-0.669444f,-0.739184f},{0.0816169f,-0.391685f,-0.916472f}, +{0.101929f,-0.369884f,-0.92347f},{-0.0661576f,-0.514494f,-0.854938f},{-0.154485f,-0.739288f,-0.65543f}, +{-0.167303f,-0.763301f,-0.624004f},{0.0540055f,-0.439948f,-0.896398f},{-0.113792f,-0.718891f,-0.685745f}, +{0.0113873f,-0.472514f,-0.88125f},{-0.198106f,-0.842564f,-0.500839f},{-0.14848f,-0.718253f,-0.679755f}, +{-0.142438f,-0.660203f,-0.737458f},{-0.201887f,-0.812292f,-0.547197f},{-0.125965f,-0.609068f,-0.783051f}, +{-0.193061f,-0.786669f,-0.586412f},{-0.0274602f,-0.940382f,-0.33901f},{-0.0636168f,-0.841289f,-0.536829f}, +{-0.0631375f,-0.914656f,-0.399271f},{-0.136511f,-0.780866f,-0.609601f},{-0.163845f,-0.877955f,-0.449833f}, +{-0.0323448f,-0.961882f,-0.271544f},{-0.0355085f,-0.932581f,-0.359209f},{-0.0338916f,-0.890883f,-0.452967f}, +{-0.0289993f,-0.980011f,-0.196816f},{-0.0291766f,-0.966258f,-0.255917f},{-0.0167184f,-0.990338f,-0.137663f}, +{-0.0198877f,-0.993822f,-0.109189f},{-0.0107279f,-0.999942f,-3.47115e-014f},{-0.0050596f,-0.999987f,-3.47131e-014f}, +{-0.0957495f,-0.559996f,-0.822944f},{-0.191923f,-0.850452f,-0.489793f},{-0.155604f,-0.848968f,-0.505015f}, +{-0.222898f,-0.865832f,-0.447942f},{-0.0875411f,-0.68422f,-0.724003f},{-0.225241f,-0.858046f,-0.461544f}, +{-0.21684f,-0.85279f,-0.47511f},{-0.0738554f,-0.669461f,-0.739167f},{-0.0484446f,-0.655515f,-0.753627f}, +{-0.154458f,-0.739263f,-0.655463f},{-0.221079f,-0.89317f,-0.391626f},{-0.16722f,-0.763157f,-0.624202f}, +{-0.092937f,-0.70069f,-0.707387f},{-0.220895f,-0.874317f,-0.432174f},{-0.113948f,-0.718955f,-0.685653f}, +{-0.235433f,-0.92105f,-0.310221f},{-0.198007f,-0.842424f,-0.501114f},{-0.201874f,-0.8124f,-0.547041f}, +{-0.245744f,-0.907886f,-0.339635f},{-0.19314f,-0.786761f,-0.586263f},{-0.24247f,-0.898676f,-0.365499f}, +{-0.0190519f,-0.976871f,-0.212977f},{-0.0630402f,-0.914689f,-0.399213f},{-0.060284f,-0.966361f,-0.250026f}, +{-0.164177f,-0.877788f,-0.450037f},{-0.184757f,-0.942123f,-0.279767f},{-0.0270421f,-0.9848f,-0.171573f}, +{-0.0323457f,-0.961912f,-0.27144f},{-0.0274934f,-0.940472f,-0.338758f},{-0.0267396f,-0.99172f,-0.125605f}, +{-0.0289918f,-0.980029f,-0.196732f},{-0.0198319f,-0.993882f,-0.108651f},{-0.0211762f,-0.997263f,-0.0708397f}, +{-0.0149749f,-0.999888f,1.73785e-014f},{-0.0107279f,-0.999942f,-1.37458e-007f},{-0.223789f,-0.882982f,-0.412628f}, +{-0.406267f,-0.879976f,0.24615f},{-0.325496f,-0.945544f,-4.37825e-014f},{-0.430021f,-0.825224f,0.366179f}, +{-0.415042f,-0.887589f,0.199814f},{-0.433914f,-0.838449f,0.32973f},{-0.428207f,-0.855563f,0.290948f}, +{-0.403111f,-0.903734f,0.144105f},{-0.372393f,-0.924654f,0.0796197f},{-0.351815f,-0.863964f,0.360266f}, +{-0.287563f,-0.817015f,0.499794f},{-0.289017f,-0.858968f,0.422662f},{-0.415666f,-0.874009f,0.251654f}, +{-0.415625f,-0.815734f,0.402286f},{-0.404737f,-0.863176f,0.301853f},{-0.271311f,-0.756732f,0.594766f}, +{-0.274232f,-0.786642f,0.553165f},{-0.279221f,-0.809642f,0.516252f},{-0.27568f,-0.775661f,0.567759f}, +{-0.271774f,-0.836827f,0.475247f},{-0.268981f,-0.798255f,0.538923f},{-0.0705437f,-0.73515f,0.674224f}, +{-0.215371f,-0.747875f,0.627932f},{-0.0720223f,-0.716587f,0.693769f},{-0.258526f,-0.76542f,0.589319f}, +{-0.256658f,-0.7395f,0.622308f},{-0.215327f,-0.725968f,0.65315f},{0.0536227f,-0.695311f,0.716706f}, +{0.0553596f,-0.711787f,0.700211f},{0.0526367f,-0.683635f,0.727924f},{0.05402f,-0.696847f,0.715182f}, +{0.0443476f,-0.671901f,0.739312f},{0.0456343f,-0.680533f,0.731295f},{0.0375712f,-0.660597f,0.7498f}, +{0.0392392f,-0.666369f,0.744589f},{0.0263913f,-0.652044f,0.757722f},{0.0242326f,-0.64918f,0.760249f}, +{0.00909943f,-0.636797f,0.770977f},{-0.355806f,-0.819405f,0.449419f},{-0.305399f,-0.934555f,-0.182588f}, +{-0.272835f,-0.943202f,-0.189554f},{-0.325025f,-0.931091f,-0.165614f},{-0.225246f,-0.858058f,-0.46152f}, +{-0.33101f,-0.92805f,-0.170751f},{-0.326585f,-0.928601f,-0.176191f},{-0.216857f,-0.852794f,-0.475095f}, +{-0.192095f,-0.850459f,-0.489713f},{-0.223794f,-0.882969f,-0.412652f},{-0.282168f,-0.946723f,-0.15523f}, +{-0.257023f,-0.954853f,-0.148976f},{-0.222888f,-0.865843f,-0.447925f},{-0.308825f,-0.937467f,-0.160573f}, +{-0.220917f,-0.874341f,-0.432116f},{-0.27811f,-0.951625f,-0.130631f},{-0.266557f,-0.95615f,-0.121342f}, +{-0.245706f,-0.907932f,-0.33954f},{-0.267282f,-0.953392f,-0.140014f},{-0.242529f,-0.8987f,-0.365402f}, +{-0.221015f,-0.893122f,-0.391771f},{-0.156094f,-0.98259f,-0.100754f},{-0.0601717f,-0.966375f,-0.249998f}, +{-0.185191f,-0.942001f,-0.279891f},{-0.235357f,-0.921009f,-0.310401f},{-0.258402f,-0.959761f,-0.10994f}, +{-0.0120606f,-0.997001f,-0.0764369f},{-0.0270479f,-0.98481f,-0.171515f},{-0.0190983f,-0.976903f,-0.212827f}, +{-0.0245852f,-0.995645f,-0.089921f},{-0.0208988f,-0.997876f,-0.0617047f},{-0.0267358f,-0.991726f,-0.125558f}, +{-0.0211402f,-0.997288f,-0.0705024f},{-0.0225064f,-0.998719f,-0.0453191f},{-0.0173199f,-0.99985f,0.0f}, +{-0.020436f,-0.999463f,-0.0256193f},{-0.0149749f,-0.999888f,0.0f},{-0.354145f,-0.93519f,-0.000397467f}, +{-0.325394f,-0.945578f,-0.00041274f},{-0.37057f,-0.928805f,-0.000358322f},{-0.330975f,-0.928043f,-0.170857f}, +{-0.376582f,-0.926383f,-0.00037055f},{-0.37303f,-0.927819f,-0.00038323f},{-0.326569f,-0.928592f,-0.176265f}, +{-0.30552f,-0.934514f,-0.182597f},{-0.282148f,-0.946691f,-0.155461f},{-0.318954f,-0.94777f,-0.000340813f}, +{-0.280289f,-0.959916f,-0.000332774f},{-0.324972f,-0.931084f,-0.165758f},{-0.355065f,-0.934841f,-0.000347719f}, +{-0.308718f,-0.937472f,-0.160746f},{-0.286908f,-0.957958f,-0.000297201f},{-0.286152f,-0.958184f,-0.000278036f}, +{-0.278077f,-0.951596f,-0.130911f},{-0.271594f,-0.962412f,-0.000317168f},{-0.267276f,-0.953349f,-0.140321f}, +{-0.257072f,-0.954789f,-0.149307f},{-0.111694f,-0.993743f,-0.00021707f},{-0.156718f,-0.982439f,-0.101254f}, +{-0.236074f,-0.971735f,-0.000236761f},{-0.25861f,-0.95965f,-0.110423f},{-0.266503f,-0.956116f,-0.121731f}, +{-0.270112f,-0.962829f,-0.000258194f},{-0.00863986f,-0.999963f,-0.000162909f},{-0.0121313f,-0.996969f,-0.0768439f}, +{-0.00228269f,-0.999997f,-0.000191989f},{-0.0244896f,-0.995608f,-0.0903648f},{-0.0172187f,-0.999852f,-0.000131616f}, +{-0.0209353f,-0.997851f,-0.0620942f},{-0.0225295f,-0.998704f,-0.0456412f},{-0.0196018f,-0.999808f,-9.66914e-005f}, +{-0.0193208f,-0.999813f,-5.44735e-005f},{-0.0204332f,-0.99946f,-0.0257239f},{-0.0176994f,-0.999843f,0.0f}, +{0.0f,0.271326f,0.962488f},{0.0f,0.253151f,0.967427f},{0.0f,0.26258f,0.96491f}, +{0.0f,0.147431f,0.989072f},{0.0f,0.162743f,0.986669f},{0.0f,0.209863f,0.977731f}, +{0.0f,0.243346f,0.96994f},{0.0f,0.20324f,0.979129f},{0.0f,0.0844041f,0.996432f}, +{0.0f,0.0211631f,0.999776f},{0.0f,0.0519304f,0.998651f},{0.0f,0.0826965f,0.996575f}, +{0.0f,0.113463f,0.993542f},{0.0f,0.11544f,0.993314f},{0.0f,0.119575f,0.992825f}, +{0.0f,0.125688f,0.99207f},{0.0f,0.133439f,0.991057f},{0.0f,0.142487f,0.989797f}, +{0.0f,0.1524f,0.988319f},{6.49463e-018f,-0.123071f,-0.992398f},{-1.11865e-017f,-0.13416f,-0.99096f}, +{-3.82822e-018f,-0.134575f,-0.990903f},{1.60303e-018f,-0.113491f,-0.993539f},{7.81879e-018f,-0.0902913f,-0.995915f}, +{9.91352e-018f,-0.0774828f,-0.996994f},{1.03021e-017f,-0.0670916f,-0.997747f},{-1.68674e-018f,-0.0438914f,-0.999036f}, +{3.8365e-018f,-0.147436f,-0.989072f},{8.0814e-018f,-0.0206911f,-0.999786f},{8.05703e-018f,-0.160907f,-0.98697f}, +{1.33567e-017f,-0.190446f,-0.981698f},{0.0f,-0.300752f,-0.953702f},{0.0f,-0.299196f,-0.954192f}, +{-9.04092e-018f,-0.266455f,-0.963847f},{3.88234e-018f,-0.25387f,-0.967238f},{-1.05499e-017f,-0.246065f,-0.969253f}, +{3.20684e-018f,-0.294624f,-0.955613f},{-3.12775e-018f,-0.287357f,-0.957824f},{1.04562e-017f,-0.277782f,-0.960644f}, +{1.18742e-017f,-0.240601f,-0.970624f},{-6.77626e-018f,1.0f,1.27676e-015f},{-6.77626e-018f,1.0f,1.27052e-015f}, +{0.0f,1.0f,1.27676e-015f},{-3.2255e-018f,1.0f,1.2844e-015f},{-2.22261e-018f,1.0f,1.27052e-015f}, +{-2.05998e-018f,1.0f,1.27052e-015f},{2.92735e-018f,1.0f,1.2844e-015f},{0.0f,1.0f,1.27052e-015f}, +{1.0f,-2.22045e-016f,0.0f},{1.0f,4.44089e-016f,0.0f},{1.0f,8.88178e-016f,0.0f}, +{0.44501f,-0.895526f,0.0f},{0.287138f,-0.957889f,0.0f},{0.264225f,-0.964461f,0.0f}, +{0.0777153f,-0.996976f,0.0f},{0.484196f,-0.87496f,0.0f},{0.615293f,-0.788298f,0.0f}, +{0.658728f,-0.752381f,0.0f},{0.777371f,-0.629043f,0.0f},{0.803054f,-0.595906f,0.0f}, +{0.899416f,-0.437093f,0.0f},{0.910992f,-0.412424f,0.0f},{0.974657f,-0.223703f,0.0f}, +{0.977683f,-0.210088f,0.0f},{1.0f,1.04131e-014f,0.0f},{1.0f,5.20654e-015f,0.0f}, +{0.62939f,0.77709f,1.00199e-015f},{0.608066f,0.793886f,8.62015e-016f},{0.773996f,0.63319f,7.65657e-016f}, +{1.0f,-6.28037e-016f,-6.81933e-031f},{1.0f,2.51215e-015f,2.72773e-030f},{0.975403f,0.22043f,2.71985e-016f}, +{0.902955f,0.429735f,5.30243e-016f},{0.974096f,0.226136f,2.90187e-016f},{0.89737f,0.44128f,5.88046e-016f}, +{0.786233f,0.61793f,7.01456e-016f},{0.439791f,0.8981f,9.6132e-016f},{0.22612f,0.974099f,1.13394e-015f}, +{0.422231f,0.906488f,1.14646e-015f},{0.216293f,0.976328f,1.13616e-015f},{3.14018e-016f,1.0f,1.18453e-015f}, +{0.0f,0.636824f,0.771009f},{4.41885e-018f,0.636824f,0.771009f},{0.0764224f,-0.976094f,0.203472f}, +{0.0777152f,-0.996976f,2.3946e-009f},{0.0777152f,-0.996976f,1.82309e-009f},{5.69588e-006f,0.0519161f,0.998651f}, +{0.0391237f,-0.456027f,0.889106f},{1.35909e-005f,0.0825944f,0.996583f},{0.0691877f,-0.861638f,0.502785f}, +{0.0509221f,-0.636981f,0.769196f},{0.0777152f,-0.996976f,6.33733e-010f},{0.0777152f,-0.996976f,-2.35021e-015f}, +{0.0749912f,-0.917412f,0.390808f},{0.0700812f,-0.856741f,0.510962f},{0.0305668f,-0.282672f,0.95873f}, +{0.0398436f,-0.436736f,0.898707f},{0.0583498f,-0.663385f,0.746f},{0.0286465f,-0.347654f,0.937185f}, +{0.0674458f,-0.854338f,0.515323f},{1.67095e-011f,0.113462f,0.993542f},{3.90358e-007f,0.0211583f,0.999776f}, +{0.0777152f,-0.996976f,1.22379e-009f},{0.707107f,0.115053f,0.697684f},{0.702691f,-0.041302f,0.710295f}, +{0.918265f,-0.13998f,0.3704f},{0.664219f,-0.196116f,0.721354f},{0.76718f,-0.515388f,0.381851f}, +{0.863385f,-0.335631f,0.376721f},{0.490492f,-0.464798f,0.737143f},{0.467108f,-0.794304f,0.388447f}, +{0.632878f,-0.671315f,0.385748f},{0.0777152f,-0.996976f,8.89301e-008f},{0.289241f,-0.957256f,8.65022e-007f}, +{0.278854f,-0.87754f,0.390082f},{0.256675f,-0.171643f,0.951135f},{0.309894f,-0.101729f,0.945313f}, +{-4.90387e-007f,0.133372f,0.991066f},{0.113588f,-0.26464f,0.957634f},{0.216859f,-0.631152f,0.744728f}, +{0.189962f,-0.227046f,0.955178f},{0.368095f,0.151307f,0.917394f},{0.366433f,0.0644563f,0.928209f}, +{-1.36278e-016f,0.162743f,0.986669f},{-4.77403e-007f,0.152368f,0.988324f},{0.929788f,0.0598835f,0.363191f}, +{0.977729f,-0.20987f,1.07918e-005f},{1.0f,1.37117e-008f,8.31709e-008f},{0.34688f,-0.0217202f,0.937658f}, +{-1.01854e-006f,0.142402f,0.989809f},{0.362795f,-0.563926f,0.741867f},{0.592707f,-0.339591f,0.730326f}, +{-7.18981e-007f,0.115426f,0.993316f},{0.0305691f,-0.282671f,0.95873f},{1.58673e-014f,0.113463f,0.993542f}, +{0.0583523f,-0.663385f,0.746f},{0.911397f,-0.411528f,6.3595e-006f},{0.0749922f,-0.917412f,0.390808f}, +{0.804305f,-0.594217f,4.18309e-006f},{-1.78317e-007f,0.125613f,0.992079f},{0.660117f,-0.751163f,2.58675e-006f}, +{1.33025e-007f,0.11953f,0.992831f},{0.485516f,-0.874228f,4.30103e-007f},{0.929788f,0.0599047f,0.363187f}, +{1.0f,-6.95989e-015f,-4.64483e-014f},{0.87226f,0.0993814f,0.478837f},{2.41719e-015f,0.203217f,0.979134f}, +{0.489042f,0.177258f,0.85406f},{0.87226f,0.119006f,0.474341f},{0.489042f,0.212261f,0.84604f}, +{0.368095f,0.151316f,0.917393f},{0.0f,0.162743f,0.986669f},{0.707107f,0.115076f,0.69768f}, +{0.640795f,0.750862f,0.159966f},{0.633896f,0.690083f,0.34923f},{0.773588f,0.633689f,4.47054e-006f}, +{0.87226f,0.119072f,0.474324f},{0.974072f,0.226237f,4.35889e-005f},{0.89728f,0.441461f,1.9127e-005f}, +{0.831026f,0.314908f,0.458507f},{0.608053f,0.793896f,1.75823e-008f},{0.56074f,0.604452f,0.56587f}, +{0.362672f,0.475573f,0.801436f},{0.412157f,0.425828f,0.805479f},{0.748579f,0.4929f,0.443484f}, +{0.489042f,0.2123f,0.84603f},{0.461687f,0.325164f,0.825296f},{2.66133e-006f,0.271328f,0.962487f}, +{3.42352e-007f,0.262654f,0.96489f},{-1.24911e-015f,0.243346f,0.96994f},{2.24678e-006f,0.253185f,0.967418f}, +{0.0486817f,-0.640323f,-0.766562f},{0.0370848f,-0.513173f,-0.857483f},{0.0666236f,-0.875571f,-0.478474f}, +{0.0775964f,-0.996904f,-0.0127208f},{0.0776561f,-0.996948f,-0.00805679f},{0.0653022f,-0.880476f,-0.469572f}, +{0.0659754f,-0.878213f,-0.473698f},{0.0660304f,-0.857586f,-0.510084f},{0.0777085f,-0.996974f,-0.00192217f}, +{0.0777145f,-0.996976f,-0.00043536f},{0.0758877f,-0.977579f,-0.196417f},{5.59703e-006f,-0.043964f,-0.999033f}, +{0.0257948f,-0.350245f,-0.936303f},{0.0365804f,-0.52637f,-0.849468f},{1.00329e-005f,-0.0672212f,-0.997738f}, +{0.0410888f,-0.616326f,-0.786418f},{0.0665963f,-0.902304f,-0.425926f},{0.036057f,-0.539132f,-0.841449f}, +{4.01696e-007f,-0.0206959f,-0.999786f},{3.419e-007f,-0.113495f,-0.993538f},{0.0776912f,-0.996967f,-0.00445871f}, +{1.17965e-005f,-0.0904433f,-0.995902f},{-6.16506e-018f,0.123071f,-0.992398f},{1.30823e-017f,0.13416f,-0.99096f}, +{4.86852e-018f,0.134575f,-0.990903f},{-8.07206e-018f,0.113491f,-0.993539f},{1.48949e-020f,0.0902913f,-0.995915f}, +{-3.75189e-018f,0.0774828f,-0.996994f},{5.48641e-018f,0.0670916f,-0.997747f},{-2.91677e-017f,0.0438914f,-0.999036f}, +{3.19289e-018f,0.147436f,-0.989072f},{-5.39916e-018f,0.0206911f,-0.999786f},{-1.04945e-017f,0.160907f,-0.98697f}, +{-2.1531e-018f,0.190446f,-0.981698f},{0.0f,0.300752f,-0.953702f},{-1.03859e-017f,0.299196f,-0.954192f}, +{-1.0491e-017f,0.266455f,-0.963847f},{-5.26397e-018f,0.25387f,-0.967238f},{1.44857e-017f,0.246065f,-0.969253f}, +{0.0f,0.294624f,-0.955613f},{1.04255e-017f,0.287357f,-0.957824f},{0.0f,0.277782f,-0.960644f}, +{5.2824e-018f,0.240601f,-0.970624f},{0.0f,-0.271326f,0.962488f},{0.0f,-0.253151f,0.967427f}, +{0.0f,-0.26258f,0.96491f},{0.0f,-0.147431f,0.989072f},{0.0f,-0.162743f,0.986669f}, +{0.0f,-0.209863f,0.977731f},{0.0f,-0.243346f,0.96994f},{0.0f,-0.20324f,0.979129f}, +{0.0f,-0.0844041f,0.996432f},{0.0f,-0.0211631f,0.999776f},{0.0f,-0.0519304f,0.998651f}, +{0.0f,-0.0826965f,0.996575f},{0.0f,-0.113463f,0.993542f},{0.0f,-0.115523f,0.993305f}, +{0.0f,-0.119556f,0.992828f},{0.0f,-0.125642f,0.992076f},{0.0f,-0.133401f,0.991062f}, +{0.0f,-0.142437f,0.989804f},{0.0f,-0.152342f,0.988328f},{0.0f,-1.0f,-1.26288e-015f}, +{0.0f,-1.0f,-1.26775e-015f},{-1.0f,-1.77636e-015f,0.0f},{-0.44501f,0.895526f,0.0f}, +{-0.287142f,0.957888f,0.0f},{-0.264225f,0.964461f,0.0f},{-0.0777153f,0.996976f,0.0f}, +{-0.484193f,0.874961f,0.0f},{-0.615293f,0.788298f,0.0f},{-0.658731f,0.752379f,0.0f}, +{-0.777371f,0.629043f,0.0f},{-0.803054f,0.595907f,0.0f},{-0.899416f,0.437093f,0.0f}, +{-0.910997f,0.412414f,0.0f},{-0.974657f,0.223703f,0.0f},{-0.977682f,0.210092f,0.0f}, +{-1.0f,-1.04131e-014f,0.0f},{-1.0f,-5.20654e-015f,0.0f},{-0.608066f,-0.793886f,-1.01875e-015f}, +{-0.773996f,-0.63319f,-7.50031e-016f},{-0.62939f,-0.77709f,-9.20484e-016f},{-0.89737f,-0.44128f,-5.60822e-016f}, +{-0.786233f,-0.61793f,-7.31954e-016f},{-0.975403f,-0.22043f,-2.72665e-016f},{-0.902955f,-0.429735f,-5.0373e-016f}, +{-0.974096f,-0.226136f,-2.80072e-016f},{-0.439791f,-0.8981f,-1.24113e-015f},{-0.22612f,-0.974099f,-1.15385e-015f}, +{-0.422231f,-0.906488f,-1.07376e-015f},{-0.216293f,-0.976328f,-1.15649e-015f},{-3.14018e-016f,-1.0f,-1.18453e-015f}, +{-4.24524e-018f,-0.636824f,0.771009f},{9.31099e-019f,-0.636824f,0.771009f},{-5.78592e-018f,-0.636824f,0.771009f}, +{-5.00079e-018f,-0.636824f,0.771009f},{0.0f,-0.636824f,0.771009f},{1.67186e-018f,-0.636824f,0.771009f}, +{4.01246e-018f,-0.636824f,0.771009f},{2.67498e-018f,-0.636824f,0.771009f},{5.34995e-018f,-0.636824f,0.771009f}, +{-2.00623e-018f,-0.636824f,0.771009f},{-3.77969e-018f,-0.636824f,0.771009f},{-2.75858e-018f,-0.636824f,0.771009f}, +{2.26987e-019f,-0.636824f,0.771009f},{-5.34995e-018f,-0.636824f,0.771009f},{2.20943e-018f,-0.636824f,0.771009f}, +{-0.076394f,0.975689f,0.205416f},{-0.0777152f,0.996976f,2.40026e-009f},{-0.0777152f,0.996976f,1.82763e-009f}, +{-5.69588e-006f,-0.0519161f,0.998651f},{-0.0391237f,0.456027f,0.889106f},{-1.3591e-005f,-0.0825944f,0.996583f}, +{-0.0691877f,0.861638f,0.502785f},{-0.050805f,0.635452f,0.770467f},{-0.0777152f,0.996976f,6.35071e-010f}, +{-0.0777152f,0.996976f,1.31007e-017f},{-0.0749912f,0.917412f,0.390808f},{-0.0700812f,0.856741f,0.510962f}, +{-0.0305668f,0.282672f,0.95873f},{-0.0398436f,0.436736f,0.898707f},{-0.0583498f,0.663385f,0.746f}, +{-0.0285025f,0.345792f,0.937878f},{-0.0673689f,0.853315f,0.517025f},{-1.67093e-011f,-0.113462f,0.993542f}, +{-3.90359e-007f,-0.0211583f,0.999776f},{-0.0777152f,0.996976f,1.22684e-009f},{-0.362409f,0.564161f,0.741878f}, +{-0.112973f,0.264855f,0.957648f},{-0.215685f,0.631536f,0.744744f},{-0.659094f,0.75206f,-1.94181e-007f}, +{-0.631911f,0.672214f,0.385768f},{-0.466608f,0.794595f,0.388454f},{-0.803414f,0.595421f,4.71637e-006f}, +{-0.0749922f,0.917412f,0.390808f},{-0.28767f,0.95773f,5.42362e-007f},{-0.277342f,0.878015f,0.390091f}, +{-0.346813f,0.0219211f,0.937678f},{1.10489e-006f,-0.133312f,0.991074f},{-0.309574f,0.102261f,0.94536f}, +{-0.0777152f,0.996976f,-3.03639e-015f},{-0.702528f,0.0424957f,0.710387f},{-0.929788f,-0.0598835f,0.363191f}, +{-0.707107f,-0.115053f,0.697684f},{-0.911187f,0.411994f,8.1719e-006f},{-0.863203f,0.336083f,0.376735f}, +{-0.766361f,0.516581f,0.381883f},{-0.918012f,0.141492f,0.37045f},{-0.664088f,0.196474f,0.721378f}, +{4.30608e-007f,-0.152291f,0.988336f},{7.6959e-007f,-0.142379f,0.989812f},{-0.366351f,-0.0637951f,0.928287f}, +{-0.48975f,0.465521f,0.73718f},{-0.18976f,0.227177f,0.955187f},{-0.368095f,-0.151307f,0.917394f}, +{1.2436e-015f,-0.162743f,0.986669f},{-0.484991f,0.874519f,1.45876e-006f},{-0.0583523f,0.663385f,0.746f}, +{-0.0305691f,0.282671f,0.95873f},{5.79189e-014f,-0.113463f,0.993542f},{9.38329e-007f,-0.115403f,0.993319f}, +{-0.256288f,0.172046f,0.951166f},{3.02192e-008f,-0.119516f,0.992832f},{-3.80451e-007f,-0.125569f,0.992085f}, +{-0.59209f,0.340547f,0.730382f},{-0.977393f,0.21143f,5.28771e-006f},{-0.929788f,-0.0599047f,0.363187f}, +{-1.0f,6.95989e-015f,-4.64483e-014f},{-0.87226f,-0.0993814f,0.478837f},{-1.63982e-015f,-0.203217f,0.979134f}, +{-0.489042f,-0.177258f,0.85406f},{-0.87226f,-0.119006f,0.474341f},{-0.489042f,-0.212261f,0.84604f}, +{-0.368095f,-0.151316f,0.917393f},{-3.30488e-015f,-0.162743f,0.986669f},{-0.707107f,-0.115076f,0.69768f}, +{-0.640795f,-0.750862f,0.159966f},{-0.633896f,-0.690083f,0.34923f},{-0.773588f,-0.633689f,4.47054e-006f}, +{-0.87226f,-0.119072f,0.474324f},{-0.974072f,-0.226237f,4.35889e-005f},{-0.89728f,-0.441461f,1.9127e-005f}, +{-0.831026f,-0.314908f,0.458507f},{-0.608053f,-0.793896f,1.75822e-008f},{-0.56074f,-0.604452f,0.56587f}, +{-0.362672f,-0.475573f,0.801436f},{-0.412157f,-0.425828f,0.805479f},{-0.748579f,-0.4929f,0.443484f}, +{-0.489042f,-0.2123f,0.84603f},{-0.461687f,-0.325164f,0.825296f},{-2.66133e-006f,-0.271328f,0.962487f}, +{-3.42352e-007f,-0.262654f,0.96489f},{-1.05425e-016f,-0.243346f,0.96994f},{-2.24678e-006f,-0.253185f,0.967418f}, +{-0.0666236f,0.875571f,-0.478474f},{-0.0486817f,0.640323f,-0.766562f},{-0.0370848f,0.513173f,-0.857483f}, +{-0.0257948f,0.350245f,-0.936303f},{-4.01482e-007f,0.0206959f,-0.999786f},{-5.59705e-006f,0.0439641f,-0.999033f}, +{-0.0410888f,0.616326f,-0.786418f},{-0.036057f,0.539132f,-0.841449f},{-3.41892e-007f,0.113495f,-0.993538f}, +{-0.0653022f,0.880476f,-0.469573f},{-0.0776561f,0.996948f,-0.00805682f},{-0.0659754f,0.878213f,-0.473698f}, +{-0.0665963f,0.902304f,-0.425926f},{-0.0775964f,0.996904f,-0.0127207f},{-0.0776912f,0.996967f,-0.00445868f}, +{-0.0660304f,0.857586f,-0.510084f},{-0.0365804f,0.52637f,-0.849468f},{-0.0777085f,0.996974f,-0.00192216f}, +{-0.0777145f,0.996976f,-0.000435368f},{-0.0758877f,0.977579f,-0.196417f},{-1.00329e-005f,0.0672213f,-0.997738f}, +{-1.17964e-005f,0.0904433f,-0.995902f},{0.970979f,-0.239165f,0.0f},{1.0f,-2.21189e-011f,0.0f}, +{0.35609f,-0.934452f,0.0f},{0.569129f,-0.822248f,0.0f},{0.568041f,-0.823f,0.0f}, +{0.885313f,-0.464996f,0.0f},{0.74925f,-0.662288f,0.0f},{0.885933f,-0.463813f,0.0f}, +{-0.119912f,-0.992785f,0.0f},{-0.354158f,-0.935185f,0.0f},{-0.120012f,-0.992772f,0.0f}, +{0.355204f,-0.934789f,0.0f},{0.120803f,-0.992676f,0.0f},{0.12127f,-0.99262f,0.0f}, +{-0.567216f,-0.823569f,0.0f},{-0.7483f,-0.663361f,0.0f},{-0.567703f,-0.823234f,0.0f}, +{-0.353989f,-0.935249f,0.0f},{-0.748241f,-0.663427f,0.0f},{-0.885185f,-0.465239f,0.0f}, +{-0.885281f,-0.465056f,0.0f},{-0.970894f,-0.239511f,0.0f},{-0.970844f,-0.239712f,0.0f}, +{0.748446f,-0.663196f,0.0f},{0.971139f,-0.238516f,0.0f},{0.0f,1.11022e-016f,-1.0f}, +{0.0f,-1.11022e-016f,-1.0f},{0.0f,-5.55112e-017f,-1.0f},{0.0f,5.55112e-017f,-1.0f}, +{1.0f,-1.38778e-017f,0.0f},{0.959454f,-0.281866f,3.5075e-017f},{0.959948f,-0.28018f,-4.21701e-019f}, +{0.142833f,-0.989747f,2.49501e-017f},{0.415948f,-0.909389f,-1.25209e-017f},{0.413963f,-0.910294f,-4.85725e-018f}, +{0.655247f,-0.755415f,1.3143e-017f},{0.844985f,-0.53479f,1.81431e-018f},{0.840053f,-0.542504f,1.76327e-018f}, +{-0.413963f,-0.910294f,-1.17305e-017f},{-0.142833f,-0.989747f,2.30199e-017f},{-0.415948f,-0.909389f,2.57792e-017f}, +{0.141528f,-0.989934f,-9.05295e-018f},{-0.141527f,-0.989934f,2.56689e-017f},{-0.840053f,-0.542504f,-5.88236e-019f}, +{-0.655247f,-0.755415f,2.43207e-017f},{-0.844985f,-0.53479f,-3.19936e-017f},{-0.655503f,-0.755193f,8.23455e-018f}, +{-0.959948f,-0.28018f,3.039e-017f},{-0.959454f,-0.281866f,-5.9836e-018f},{0.655503f,-0.755193f,1.3143e-017f}, +{0.962605f,-0.270909f,0.0f},{1.0f,-4.07586e-012f,0.0f},{0.309304f,-0.950963f,0.0f}, +{0.588229f,-0.808694f,0.0f},{0.409074f,-0.912501f,0.0f},{0.650924f,-0.759143f,0.0f}, +{0.811958f,-0.583716f,0.0f},{0.840179f,-0.542309f,0.0f},{-0.307814f,-0.951446f,0.0f}, +{-0.424076f,-0.905627f,0.0f},{-0.587751f,-0.809042f,0.0f},{0.134185f,-0.990956f,0.0f}, +{-0.152115f,-0.988363f,0.0f},{2.72147e-017f,-1.0f,0.0f},{-0.807656f,-0.589654f,0.0f}, +{-0.662432f,-0.749122f,0.0f},{-0.846367f,-0.5326f,0.0f},{-0.961254f,-0.275665f,0.0f}, +{-0.950842f,-0.309676f,0.0f},{0.952103f,-0.305779f,0.0f},{0.962289f,-0.272029f,0.0f}, +{1.0f,5.92119e-016f,0.0f},{1.0f,-1.60011e-012f,0.0f},{0.410952f,-0.911657f,0.0f}, +{0.650115f,-0.759835f,0.0f},{0.84148f,-0.540288f,0.0f},{-0.149984f,-0.988688f,0.0f}, +{-0.424076f,-0.905627f,0.0f},{0.137383f,-0.990518f,0.0f},{-0.661313f,-0.75011f,0.0f}, +{-0.844868f,-0.534974f,0.0f},{-0.960674f,-0.277678f,0.0f},{-1.0f,-1.19209e-007f,0.0f}, +{-0.988362f,0.152121f,0.0f},{-1.0f,1.20609e-016f,0.0f},{-0.990957f,-0.134181f,0.0f}, +{-0.905627f,0.424076f,0.0f},{-0.951446f,0.307814f,0.0f},{-0.809042f,0.587751f,0.0f}, +{-0.749088f,0.66247f,0.0f},{-0.309676f,0.950842f,0.0f},{-0.589654f,0.807656f,0.0f}, +{-0.532573f,0.846384f,0.0f},{-0.275761f,0.961226f,0.0f},{6.66134e-016f,1.0f,0.0f}, +{-0.950963f,-0.309304f,0.0f},{-0.912502f,-0.409073f,0.0f},{-0.808694f,-0.588229f,0.0f}, +{-0.583716f,-0.811958f,0.0f},{-0.759164f,-0.6509f,0.0f},{-0.305779f,-0.952103f,0.0f}, +{-0.542323f,-0.84017f,0.0f},{-0.270837f,-0.962625f,0.0f},{1.18424e-015f,-1.0f,0.0f}, +{-1.11022e-015f,-1.0f,0.0f},{-0.948416f,0.317028f,0.0f},{-0.804232f,0.594315f,0.0f}, +{-0.582662f,0.812715f,0.0f},{-0.305357f,0.952238f,0.0f},{-0.999985f,0.00550409f,0.0f}, +{-1.4803e-016f,1.0f,0.0f},{-1.19209e-007f,1.0f,0.0f},{-1.0f,-5.5717e-017f,0.0f}, +{-0.951973f,-0.306183f,0.0f},{-0.811248f,-0.584702f,0.0f},{-0.589388f,-0.80785f,0.0f}, +{-0.299688f,-0.954037f,0.0f},{5.92119e-016f,-1.0f,0.0f},{6.66134e-016f,-1.0f,0.0f}, +{-1.0f,3.70074e-017f,3.42388e-034f},{-0.951446f,-0.307814f,5.69571e-018f},{-1.0f,4.16334e-017f,3.85186e-034f}, +{-0.809042f,0.587751f,2.78932e-017f},{-0.950963f,0.309304f,3.37619e-017f},{-0.808694f,0.588229f,1.0203e-017f}, +{-0.951446f,0.307814f,-2.84786e-018f},{-0.589654f,0.807656f,7.32347e-018f},{-0.305779f,0.952103f,-2.03109e-017f}, +{1.4803e-016f,1.0f,0.0f},{-0.309676f,0.950842f,-7.83488e-018f},{-0.583716f,0.811958f,-2.06583e-017f}, +{1.66533e-016f,1.0f,0.0f},{-0.809042f,-0.587751f,-1.49703e-017f},{-0.808694f,-0.588229f,-1.08844e-017f}, +{-0.583716f,-0.811958f,-3.00485e-017f},{-0.589654f,-0.807656f,-1.09108e-017f},{-0.305779f,-0.952103f,0.0f}, +{-0.309676f,-0.950842f,0.0f},{6.93889e-017f,-1.0f,0.0f},{-0.822897f,0.568191f,0.0f}, +{-0.935249f,0.353989f,0.0f},{-0.935058f,0.354494f,0.0f},{-0.992772f,0.120012f,0.0f}, +{-0.823234f,0.567703f,0.0f},{-0.992699f,0.120619f,0.0f},{-0.663427f,0.748241f,0.0f}, +{-0.662949f,0.748664f,0.0f},{-0.465056f,0.885281f,0.0f},{-0.992744f,-0.12025f,0.0f}, +{-0.46429f,0.885683f,0.0f},{-0.239511f,0.970894f,0.0f},{-8.88178e-017f,1.0f,0.0f}, +{-0.239079f,0.971f,0.0f},{-0.99262f,-0.12127f,0.0f},{-0.934452f,-0.35609f,0.0f}, +{-0.935095f,-0.354397f,0.0f},{-0.823076f,-0.567931f,0.0f},{-0.822248f,-0.569129f,0.0f}, +{-0.662288f,-0.74925f,0.0f},{-0.663484f,-0.748191f,0.0f},{-0.463813f,-0.885933f,0.0f}, +{-0.465389f,-0.885106f,0.0f},{-0.23961f,-0.970869f,0.0f},{-0.238516f,-0.971139f,0.0f}, +{-1.45407e-013f,-1.0f,0.0f},{-2.2119e-011f,-1.0f,0.0f},{0.224573f,0.0806869f,-0.971111f}, +{0.167824f,0.115976f,-0.978971f},{0.206583f,0.0936942f,-0.973933f},{-0.00431306f,0.212777f,-0.977091f}, +{0.0544436f,0.17217f,-0.983562f},{0.0150728f,0.210353f,-0.977509f},{-0.000588626f,0.24749f,-0.96889f}, +{0.0534267f,0.200182f,-0.978301f},{0.0200864f,0.239984f,-0.970569f},{-0.00860874f,0.0134776f,-0.999872f}, +{-0.0575724f,0.0558224f,-0.996779f},{-0.0251275f,0.0228466f,-0.999423f},{0.119876f,0.131908f,-0.983987f}, +{0.114692f,0.135331f,-0.98414f},{0.0967618f,0.106577f,-0.989585f},{0.127645f,0.127565f,-0.983582f}, +{-0.0682479f,0.0434816f,-0.99672f},{-0.0621953f,0.0416591f,-0.997194f},{-0.102888f,0.0678076f,-0.992379f}, +{0.00861069f,-0.0134804f,-0.999872f},{0.0575731f,-0.0558295f,-0.996779f},{0.0251269f,-0.0228463f,-0.999423f}, +{-0.0700992f,0.042481f,-0.996635f},{-0.0679419f,0.0389583f,-0.996928f},{-0.0653011f,0.0312083f,-0.997377f}, +{-0.0236813f,-0.0488646f,-0.998525f},{-0.00381403f,-0.0123869f,-0.999916f},{-0.136635f,-0.122955f,-0.982961f}, +{-0.15616f,-0.0744603f,-0.984921f},{-0.146051f,-0.11848f,-0.982157f},{-0.0534268f,-0.20018f,-0.978301f}, +{-0.0200864f,-0.239985f,-0.970569f},{0.000588612f,-0.247488f,-0.968891f},{0.0374113f,-0.0911775f,-0.995132f}, +{-0.091503f,-0.164561f,-0.982113f},{-0.129057f,-0.132869f,-0.982695f},{-0.138732f,-0.128065f,-0.982015f}, +{0.0201007f,-0.253059f,-0.967242f},{-0.0338838f,-0.207008f,-0.977752f},{-0.206583f,-0.0937007f,-0.973932f}, +{-0.149271f,-0.126712f,-0.980644f},{-0.164764f,-0.113835f,-0.979742f},{-0.224573f,-0.0806854f,-0.971111f}, +{-0.167824f,-0.115975f,-0.978971f},{-0.282538f,-0.0476595f,-0.958071f},{-0.245617f,-0.0601369f,-0.9675f}, +{-0.189505f,-0.099067f,-0.976869f},{-0.300652f,-0.0257387f,-0.953386f},{-0.189498f,-0.0999932f,-0.976776f}, +{-0.173184f,-0.108516f,-0.978893f},{-0.17428f,-0.107387f,-0.978823f},{-0.110576f,-0.155908f,-0.981563f}, +{-0.172359f,-0.107733f,-0.979125f},{-0.233122f,-0.0781727f,-0.9693f},{-0.0246582f,0.00667651f,-0.999674f}, +{-0.0396375f,0.0165896f,-0.999076f},{-0.17193f,-0.105383f,-0.979456f},{-0.0809495f,0.0619015f,-0.994794f}, +{0.0847504f,0.00832976f,-0.996367f},{0.126144f,-0.0744356f,-0.989215f},{0.145127f,-0.0300614f,-0.988956f}, +{0.068248f,-0.0434816f,-0.99672f},{0.102888f,-0.0678076f,-0.992379f},{0.0700993f,-0.0424824f,-0.996635f}, +{-0.0400397f,0.0309353f,-0.998719f},{0.171931f,0.105381f,-0.979456f},{0.146014f,0.118496f,-0.98216f}, +{0.156159f,0.0744765f,-0.98492f},{0.00830625f,0.00348893f,-0.999959f},{0.00381472f,0.0123794f,-0.999916f}, +{0.110247f,0.139631f,-0.984047f},{0.112341f,0.139617f,-0.983812f},{0.0732426f,0.168792f,-0.982927f}, +{0.123518f,0.135427f,-0.983058f},{0.131651f,0.131599f,-0.982522f},{-0.0391961f,0.255848f,-0.965922f}, +{0.189505f,0.0990662f,-0.976869f},{0.033884f,0.207001f,-0.977754f},{0.300652f,0.0257381f,-0.953386f}, +{0.245617f,0.0601361f,-0.9675f},{0.282538f,0.0476609f,-0.958071f},{0.168871f,0.108819f,-0.979613f}, +{0.233124f,0.0781673f,-0.9693f},{0.172348f,0.107726f,-0.979128f},{0.249664f,0.071609f,-0.965681f}, +{0.189499f,0.0999793f,-0.976777f},{-0.0228704f,0.18367f,-0.982722f},{0.0368726f,0.143043f,-0.989029f}, +{0.039638f,-0.0165949f,-0.999076f},{0.0653017f,-0.031216f,-0.997377f},{0.116935f,0.138156f,-0.983483f}, +{0.110576f,0.15591f,-0.981563f},{0.0760762f,0.189495f,-0.97893f},{-0.0201006f,0.253055f,-0.967243f}, +{0.164768f,0.113819f,-0.979743f},{0.169985f,0.110674f,-0.979212f},{0.13279f,0.142319f,-0.980873f}, +{0.265747f,0.0638565f,-0.961926f},{0.162971f,0.111105f,-0.980355f},{0.155086f,0.11444f,-0.98125f}, +{0.217303f,0.0654512f,-0.973907f},{0.13662f,0.122963f,-0.982962f},{0.0621948f,-0.0416577f,-0.997194f}, +{0.0809495f,-0.0619016f,-0.994794f},{-0.126144f,0.074428f,-0.989216f},{-0.0967627f,-0.10656f,-0.989587f}, +{-0.145128f,0.030073f,-0.988956f},{-0.119253f,-0.132285f,-0.984012f},{-0.127694f,-0.127537f,-0.98358f}, +{-0.173544f,0.112261f,-0.978407f},{-0.194823f,0.114801f,-0.974097f},{-0.0525697f,0.037314f,-0.99792f}, +{-0.153096f,0.107531f,-0.982343f},{-0.132768f,0.102693f,-0.985813f},{0.0236802f,0.0488762f,-0.998524f}, +{-0.0374122f,0.0911884f,-0.995131f},{0.207914f,-0.0343818f,-0.977543f},{0.194823f,-0.114804f,-0.974097f}, +{0.173544f,-0.112265f,-0.978406f},{0.153096f,-0.10753f,-0.982344f},{0.0525692f,-0.0373124f,-0.99792f}, +{0.0400395f,-0.0309343f,-0.998719f},{0.132768f,-0.102696f,-0.985812f},{-0.00830612f,-0.00349236f,-0.999959f}, +{-0.0368738f,-0.143026f,-0.989032f},{-0.0544429f,-0.172172f,-0.983561f},{-0.16898f,-0.108774f,-0.979599f}, +{-0.249662f,-0.0716214f,-0.965681f},{-0.169978f,-0.110692f,-0.979211f},{0.0228691f,-0.183652f,-0.982725f}, +{-0.16297f,-0.111114f,-0.980354f},{-0.155082f,-0.114446f,-0.98125f},{-0.0847515f,-0.00831784f,-0.996367f}, +{-0.0524475f,0.0256814f,-0.998293f},{-0.0620644f,0.0332888f,-0.997517f},{0.0043133f,-0.212779f,-0.977091f}, +{-0.0732415f,-0.168808f,-0.982924f},{-0.120661f,-0.136682f,-0.983239f},{-0.114346f,-0.139069f,-0.983659f}, +{-0.0150721f,-0.210368f,-0.977506f},{-0.15764f,-0.117902f,-0.980433f},{0.149271f,0.126705f,-0.980645f}, +{0.0915033f,0.164554f,-0.982115f},{0.157641f,0.117888f,-0.980434f},{0.140533f,0.127125f,-0.981881f}, +{0.149416f,0.122423f,-0.981166f},{0.173236f,0.108474f,-0.978889f},{-0.0589452f,0.257551f,-0.964465f}, +{0.174359f,0.107335f,-0.978815f},{-0.0787303f,0.239876f,-0.967606f},{-0.0943229f,0.151587f,-0.983933f}, +{0.110958f,0.138183f,-0.984172f},{0.0246587f,-0.00668129f,-0.999674f},{-0.111226f,0.0971757f,-0.989033f}, +{0.0524476f,-0.0256865f,-0.998293f},{0.067942f,-0.0389615f,-0.996928f},{0.0620642f,-0.033293f,-0.997517f}, +{-0.207915f,0.0343964f,-0.977542f},{-0.113842f,-0.135944f,-0.984154f},{0.111227f,-0.097181f,-0.989032f}, +{-0.217303f,-0.065439f,-0.973908f},{-0.110719f,-0.139838f,-0.983965f},{-0.110345f,-0.13881f,-0.984152f}, +{0.0787291f,-0.239861f,-0.96761f},{0.0943219f,-0.151574f,-0.983935f},{0.0589451f,-0.257556f,-0.964464f}, +{0.0391964f,-0.255863f,-0.965918f},{-0.265747f,-0.0638606f,-0.961925f},{-0.148539f,-0.122911f,-0.981239f}, +{-0.0760762f,-0.189496f,-0.97893f},{-0.13279f,-0.14232f,-0.980873f},{0.780986f,-0.410005f,0.471123f}, +{0.756474f,-0.431924f,0.491109f},{0.879699f,-0.406453f,0.246832f},{0.738683f,-0.444614f,0.506622f}, +{0.85525f,-0.428298f,0.291734f},{0.718444f,-0.420701f,0.553939f},{0.815118f,-0.415692f,0.403464f}, +{0.721373f,-0.437394f,0.536943f},{0.824692f,-0.430102f,0.367282f},{0.838017f,-0.434004f,0.330708f}, +{0.728083f,-0.44473f,0.521641f},{0.797562f,-0.268829f,0.540024f},{0.722769f,-0.258175f,0.641055f}, +{0.774815f,-0.275537f,0.568982f},{0.728926f,-0.352408f,0.58692f},{0.733033f,-0.277529f,0.620999f}, +{0.816277f,-0.28748f,0.501046f},{0.689892f,-0.249748f,0.679467f},{0.725361f,-0.215302f,0.653833f}, +{0.738897f,-0.256534f,0.623074f},{0.698996f,-0.261868f,0.665454f},{0.755933f,-0.271108f,0.595873f}, +{0.709599f,-0.264635f,0.653021f},{0.683243f,0.0526752f,0.728289f},{0.696338f,0.0541363f,0.715669f}, +{0.667359f,0.0539424f,0.74278f},{0.716045f,-0.0721475f,0.694315f},{0.683867f,-0.211833f,0.698178f}, +{0.680519f,-0.0718111f,0.729203f},{0.660486f,0.052782f,0.748981f},{0.671599f,0.0443778f,0.739585f}, +{0.654656f,0.0438809f,0.754652f},{0.660388f,0.0375909f,0.749983f},{0.649023f,0.0241761f,0.760385f}, +{0.648963f,0.0363458f,0.759951f},{0.643221f,0.022026f,0.765363f},{0.636811f,0.00631787f,0.770994f}, +{0.636821f,0.0031649f,0.771005f},{0.818732f,-0.355684f,0.45074f},{0.909063f,-0.371045f,0.18955f}, +{0.583044f,-0.405078f,0.704253f},{0.580905f,-0.421979f,0.696048f},{0.756391f,-0.431996f,0.491175f}, +{0.581257f,-0.432024f,0.689562f},{0.738684f,-0.444614f,0.506621f},{0.728943f,-0.352294f,0.586967f}, +{0.718445f,-0.420702f,0.553937f},{0.59918f,-0.410108f,0.687601f},{0.721374f,-0.437394f,0.536941f}, +{0.728085f,-0.44473f,0.521639f},{0.585021f,-0.431774f,0.686528f},{0.722817f,-0.258155f,0.641008f}, +{0.63406f,-0.239661f,0.735208f},{0.709547f,-0.264648f,0.653073f},{0.618695f,-0.336563f,0.709888f}, +{0.632115f,-0.25777f,0.730743f},{0.733036f,-0.27756f,0.620982f},{0.634072f,-0.238256f,0.735654f}, +{0.683867f,-0.211913f,0.698154f},{0.689931f,-0.249749f,0.679427f},{0.633237f,-0.246966f,0.733498f}, +{0.698956f,-0.261827f,0.665513f},{0.633257f,-0.24717f,0.733412f},{0.660487f,0.0527819f,0.74898f}, +{0.667343f,0.0540166f,0.742789f},{0.634508f,0.0563396f,0.77086f},{0.680531f,-0.0720207f,0.729171f}, +{0.636975f,-0.204102f,0.743375f},{0.640402f,-0.0680582f,0.765018f},{0.63474f,0.055102f,0.770759f}, +{0.654657f,0.0438808f,0.754651f},{0.635485f,0.0454974f,0.770772f},{0.648964f,0.0363458f,0.759951f}, +{0.643198f,0.0219575f,0.765385f},{0.63602f,0.0371135f,0.77078f},{0.636578f,0.0218202f,0.770903f}, +{0.636823f,0.0020686f,0.771008f},{0.590849f,-0.425392f,0.685521f},{0.325002f,-0.355736f,0.876256f}, +{0.358337f,-0.376871f,0.854144f},{0.5809f,-0.422036f,0.696018f},{0.386348f,-0.390634f,0.835548f}, +{0.618721f,-0.336442f,0.709923f},{0.59918f,-0.410108f,0.687601f},{0.46456f,-0.370105f,0.804491f}, +{0.412203f,-0.394435f,0.821285f},{0.437394f,-0.392371f,0.809155f},{0.634063f,-0.239634f,0.735214f}, +{0.539451f,-0.218199f,0.813254f},{0.633254f,-0.24719f,0.733407f},{0.497609f,-0.276989f,0.821986f}, +{0.522063f,-0.210792f,0.826449f},{0.632111f,-0.257804f,0.730734f},{0.595637f,-0.110113f,0.795671f}, +{0.63697f,-0.204172f,0.743359f},{0.580852f,-0.223171f,0.782819f},{0.634073f,-0.238249f,0.735655f}, +{0.633239f,-0.246939f,0.733505f},{0.567772f,-0.224079f,0.792101f},{0.63474f,0.055102f,0.770759f}, +{0.634503f,0.0564151f,0.770859f},{0.606196f,0.0620428f,0.792892f},{0.640405f,-0.0682671f,0.764997f}, +{0.59941f,0.0414768f,0.799366f},{0.614526f,0.0507293f,0.787264f},{0.635485f,0.0454974f,0.770772f}, +{0.622011f,0.0411515f,0.781926f},{0.63658f,0.0217483f,0.770904f},{0.629429f,0.024754f,0.776664f}, +{0.636821f,0.0031651f,0.771005f},{0.554028f,-0.226089f,0.80121f},{0.018211f,-0.260709f,0.965246f}, +{0.0905301f,-0.29234f,0.95202f},{0.35848f,-0.376958f,0.854046f},{0.412236f,-0.394436f,0.821268f}, +{0.386367f,-0.39064f,0.835537f},{0.150845f,-0.316442f,0.936541f},{0.497587f,-0.27707f,0.821973f}, +{0.464644f,-0.369949f,0.804515f},{0.302136f,-0.326359f,0.895658f},{0.43742f,-0.392367f,0.809143f}, +{0.203847f,-0.331158f,0.921293f},{0.539469f,-0.218211f,0.813239f},{0.436519f,-0.186125f,0.880232f}, +{0.554148f,-0.226126f,0.801116f},{0.351848f,-0.234204f,0.906284f},{0.39662f,-0.172939f,0.901546f}, +{0.521912f,-0.210966f,0.826499f},{0.526859f,-0.205901f,0.824636f},{0.595587f,-0.110847f,0.795606f}, +{0.580769f,-0.223412f,0.782812f},{0.499197f,-0.202182f,0.842571f},{0.567787f,-0.224072f,0.792092f}, +{0.469626f,-0.198592f,0.86024f},{0.579246f,0.0682852f,0.812288f},{0.606222f,0.0620078f,0.792874f}, +{0.564062f,0.0488013f,0.824289f},{0.599414f,0.0416336f,0.799355f},{0.5515f,-0.0985182f,0.828337f}, +{0.594988f,0.056183f,0.801768f},{0.614534f,0.0507196f,0.787258f},{0.622016f,0.0411442f,0.781923f}, +{0.609128f,0.0457027f,0.791754f},{0.622938f,0.0285242f,0.781751f},{0.629464f,0.0246587f,0.776638f}, +{0.636811f,0.00635625f,0.770994f},{0.25357f,-0.340146f,0.90554f},{0.608772f,0.0457539f,0.792025f}, +{0.594765f,0.055249f,0.801999f},{0.608898f,0.0450032f,0.791971f},{0.622817f,0.0284547f,0.78185f}, +{0.622836f,0.0279898f,0.781851f},{0.562516f,0.0688727f,0.823913f},{0.563156f,0.0490876f,0.824891f}, +{0.550993f,-0.0496963f,0.833029f},{0.578569f,0.0683527f,0.812765f},{0.579246f,0.0665103f,0.812435f}, +{0.594461f,0.0562578f,0.802154f},{0.468103f,-0.198149f,0.861172f},{0.472958f,-0.198042f,0.85854f}, +{0.497665f,-0.201746f,0.84358f},{0.525395f,-0.205766f,0.825603f},{0.529826f,-0.175094f,0.829835f}, +{0.550287f,-0.0989846f,0.829087f},{0.361545f,-0.181766f,0.914465f},{0.394113f,-0.172451f,0.902738f}, +{0.349592f,-0.233674f,0.907294f},{0.441329f,-0.188934f,0.87723f},{0.434558f,-0.185572f,0.881319f}, +{0.40436f,-0.174204f,0.897856f},{0.265363f,-0.331082f,0.90552f},{0.251639f,-0.339571f,0.906294f}, +{0.216776f,-0.33003f,0.918743f},{0.30016f,-0.32564f,0.896584f},{0.314928f,-0.257875f,0.913412f}, +{0.16631f,-0.31893f,0.933073f},{0.202144f,-0.33061f,0.921865f},{0.149463f,-0.315979f,0.936919f}, +{0.112599f,-0.302605f,0.946442f},{0.0899699f,-0.292181f,0.952122f},{0.0515423f,-0.277704f,0.959283f}, +{-0.0205104f,-0.246428f,0.968944f},{0.50237f,-0.199807f,0.84125f},{0.636809f,0.00685645f,0.770991f}, +{-0.109551f,-0.170684f,0.979217f},{-0.0629021f,-0.206616f,0.976398f},{-0.126478f,-0.158053f,0.979297f}, +{-0.173613f,-0.129887f,0.976211f},{-0.190018f,-0.114756f,0.975051f},{-0.239086f,-0.0931162f,0.966523f}, +{-0.208979f,-0.0916011f,0.973621f},{-0.25458f,-0.0745052f,0.964177f},{-0.146005f,-0.13862f,0.979524f}, +{-0.270988f,-0.0499282f,0.961287f},{-0.0935066f,-0.176521f,0.979845f},{-0.0771143f,-0.180908f,0.980472f}, +{-0.0289222f,-0.221759f,0.974672f},{-0.00236958f,-0.258471f,0.966016f},{0.0158869f,-0.114433f,0.993304f}, +{0.00500348f,-0.212524f,0.977143f},{-0.0517682f,-0.0688181f,0.996285f},{0.0489217f,-0.273986f,0.960489f}, +{0.0316006f,-0.271537f,0.961909f},{-0.0119369f,-0.225011f,0.974283f},{0.0491747f,-0.0428923f,0.997869f}, +{7.949e-008f,-8.55582e-007f,1.0f},{0.0683324f,-0.0482005f,0.996498f},{0.0802466f,-0.186842f,0.979107f}, +{0.028666f,-0.0392859f,0.998817f},{0.0919448f,-0.102404f,0.990485f},{0.107856f,-0.057155f,0.992522f}, +{0.119144f,0.0265899f,0.992521f},{0.178742f,-0.0835213f,0.980345f},{0.0192356f,-0.00540807f,0.9998f}, +{0.0874508f,-0.0535629f,0.994728f},{0.126478f,0.158051f,0.979297f},{0.190018f,0.114754f,0.975051f}, +{0.173613f,0.129893f,0.97621f},{0.127075f,0.130935f,0.983213f},{0.0610101f,0.168995f,0.983727f}, +{0.239086f,0.0931203f,0.966523f},{0.25458f,0.0745033f,0.964177f},{0.208979f,0.0916021f,0.973621f}, +{0.270988f,0.0499291f,0.961287f},{0.158154f,0.136947f,0.977872f},{0.10955f,0.170691f,0.979216f}, +{0.0828562f,0.190497f,0.978185f},{0.0629022f,0.206614f,0.976398f},{0.224388f,0.102078f,0.969139f}, +{0.142376f,0.142513f,0.979499f},{0.0935053f,0.176539f,0.979842f},{0.209369f,0.109046f,0.971737f}, +{0.186808f,0.0142462f,0.982293f},{0.0771131f,0.180916f,0.980471f},{0.19432f,0.107117f,0.975072f}, +{0.0397896f,-0.00908038f,0.999167f},{0.0517701f,0.0687977f,0.996286f},{0.14449f,-0.0984282f,0.984599f}, +{0.127037f,-0.0930399f,0.987525f},{0.162383f,-0.103308f,0.981305f},{0.108876f,-0.0885006f,0.990108f}, +{-0.03979f,0.0090855f,0.999167f},{-0.0192361f,0.00541255f,0.9998f},{0.0667669f,-0.269586f,0.960659f}, +{-0.0610092f,-0.169012f,0.983724f},{-0.04552f,-0.217019f,0.975106f},{0.0147946f,-0.267327f,0.963492f}, +{-0.0828563f,-0.190496f,0.978185f},{-0.22439f,-0.102063f,0.96914f},{-0.158156f,-0.13693f,0.977874f}, +{-0.209371f,-0.109036f,0.971738f},{-0.142378f,-0.142505f,0.9795f},{-0.194321f,-0.107128f,0.975071f}, +{-0.127075f,-0.130951f,0.983211f},{-0.186807f,-0.0142661f,0.982293f},{-0.119142f,-0.0266103f,0.992521f}, +{-0.178742f,0.083517f,0.980345f},{-0.107856f,0.05716f,0.992522f},{-0.162383f,0.103317f,0.981304f}, +{0.00236961f,0.258468f,0.966017f},{0.0205104f,0.246429f,0.968944f},{-0.0874512f,0.0535675f,0.994727f}, +{-0.14449f,0.0984279f,0.984599f},{-0.127037f,0.0930396f,0.987525f},{-0.0683322f,0.0481988f,0.996498f}, +{-0.108876f,0.0885078f,0.990107f},{-0.0491751f,0.0428965f,0.997869f},{-0.0919447f,0.102401f,0.990485f}, +{-0.0286666f,0.0392909f,0.998817f},{-0.080245f,0.186822f,0.979111f},{-0.0158852f,0.114413f,0.993306f}, +{-0.0667658f,0.269573f,0.960663f},{-0.00500236f,0.212507f,0.977147f},{-0.0489219f,0.273996f,0.960486f}, +{0.0119362f,0.225019f,0.974281f},{-0.031601f,0.271553f,0.961904f},{0.0289212f,0.221777f,0.974668f}, +{-0.0147946f,0.26733f,0.963491f},{0.0455199f,0.217025f,0.975104f},{0.146005f,0.138621f,0.979524f}, +{-0.636821f,-0.00317738f,0.771005f},{-0.629441f,-0.0246739f,0.776656f},{-0.623058f,-0.0279566f,0.781676f}, +{-0.595408f,-0.0551303f,0.80153f},{-0.609331f,-0.0449278f,0.791642f},{-0.621971f,-0.0411546f,0.781958f}, +{-0.552325f,0.0499248f,0.832133f},{-0.563612f,-0.0687359f,0.823175f},{-0.599286f,-0.0416737f,0.79945f}, +{-0.580108f,-0.0663718f,0.811831f},{-0.614466f,-0.0507229f,0.787311f},{-0.606128f,-0.0620227f,0.792945f}, +{-0.567518f,0.223995f,0.792306f},{-0.553812f,0.226021f,0.801378f},{-0.475091f,0.198662f,0.857217f}, +{-0.595421f,0.110786f,0.795739f},{-0.58056f,0.223354f,0.782983f},{-0.531382f,0.175481f,0.828758f}, +{-0.496956f,0.276897f,0.822413f},{-0.364365f,0.182559f,0.913187f},{-0.521383f,0.210821f,0.82687f}, +{-0.407013f,0.174949f,0.896511f},{-0.443733f,0.18964f,0.875864f},{-0.539048f,0.218089f,0.81355f}, +{-0.219259f,0.330803f,0.917875f},{-0.268014f,0.331812f,0.904472f},{-0.436574f,0.392167f,0.809696f}, +{-0.317724f,0.25864f,0.912226f},{-0.46392f,0.369772f,0.805014f},{-0.411246f,0.394193f,0.821881f}, +{-0.168505f,0.319671f,0.932425f},{-0.385206f,0.390338f,0.836213f},{-0.114345f,0.303211f,0.946038f}, +{-0.0525963f,0.278069f,0.95912f},{-0.357097f,0.376599f,0.854784f},{-0.323311f,0.355321f,0.87705f}, +{-0.50421f,0.200313f,0.840028f},{-0.636809f,-0.00685578f,0.770991f},{-0.636823f,-0.002068f,0.771008f}, +{-0.63654f,-0.0217543f,0.770937f},{-0.629382f,-0.0247724f,0.776701f},{-0.621921f,-0.0411683f,0.781997f}, +{-0.635941f,-0.0371196f,0.770844f},{-0.599172f,-0.0415314f,0.799542f},{-0.606014f,-0.0620694f,0.793029f}, +{-0.634304f,-0.056447f,0.77102f},{-0.614392f,-0.0507421f,0.787367f},{-0.63537f,-0.0454985f,0.770866f}, +{-0.634587f,-0.0551123f,0.770884f},{-0.580496f,0.223077f,0.78311f},{-0.633724f,0.238176f,0.735979f}, +{-0.56733f,0.223957f,0.792452f},{-0.64016f,0.0682119f,0.765207f},{-0.63668f,0.204107f,0.743626f}, +{-0.595341f,0.110027f,0.795904f},{-0.633497f,0.239503f,0.735744f},{-0.521305f,0.210588f,0.826979f}, +{-0.538815f,0.21802f,0.813723f},{-0.632772f,0.247067f,0.733864f},{-0.553496f,0.22593f,0.801622f}, +{-0.632828f,0.246834f,0.733895f},{-0.436343f,0.392125f,0.809842f},{-0.463619f,0.369882f,0.805137f}, +{-0.598406f,0.409993f,0.688343f},{-0.496749f,0.27676f,0.822584f},{-0.631462f,0.257657f,0.731347f}, +{-0.618008f,0.336306f,0.710608f},{-0.589992f,0.425267f,0.686336f},{-0.411029f,0.394147f,0.822012f}, +{-0.584074f,0.431633f,0.687423f},{-0.385037f,0.390294f,0.836312f},{-0.356858f,0.376488f,0.854932f}, +{-0.580207f,0.431864f,0.690546f},{-0.579716f,0.42187f,0.697105f},{-0.581686f,0.404919f,0.705466f}, +{-0.636821f,-0.00315153f,0.771006f},{-0.643165f,-0.021951f,0.765413f},{-0.636538f,-0.0218263f,0.770937f}, +{-0.6489f,-0.0363394f,0.760005f},{-0.640157f,0.068003f,0.765229f},{-0.63431f,-0.0563715f,0.771021f}, +{-0.667183f,-0.0540317f,0.742932f},{-0.654564f,-0.0438692f,0.754732f},{-0.633724f,0.238183f,0.735978f}, +{-0.689649f,0.249708f,0.679728f},{-0.632825f,0.246861f,0.733889f},{-0.680332f,0.0719912f,0.72936f}, +{-0.683631f,0.211878f,0.698395f},{-0.636685f,0.204036f,0.743641f},{-0.722371f,0.258076f,0.641543f}, +{-0.631466f,0.257623f,0.731355f},{-0.633495f,0.239529f,0.735738f},{-0.709164f,0.264571f,0.65352f}, +{-0.632774f,0.247047f,0.733869f},{-0.698625f,0.261762f,0.665885f},{-0.717841f,0.420681f,0.554735f}, +{-0.617982f,0.336426f,0.710574f},{-0.732529f,0.277479f,0.621616f},{-0.728388f,0.35224f,0.587689f}, +{-0.720712f,0.437381f,0.537841f},{-0.72736f,0.444724f,0.522654f},{-0.57972f,0.421813f,0.697136f}, +{-0.737892f,0.44462f,0.507768f},{-0.755513f,0.432036f,0.492489f},{-0.780009f,0.4101f,0.472656f}, +{-0.660363f,-0.0527785f,0.74909f},{-0.636811f,-0.00629327f,0.770994f},{-0.649001f,-0.0241581f,0.760404f}, +{-0.643189f,-0.0220195f,0.765391f},{-0.660345f,-0.0375725f,0.750022f},{-0.648899f,-0.0363395f,0.760006f}, +{-0.680319f,0.0717815f,0.729392f},{-0.667198f,-0.0539575f,0.742923f},{-0.696227f,-0.0541337f,0.715778f}, +{-0.660362f,-0.0527786f,0.749091f},{-0.654563f,-0.0438693f,0.754733f},{-0.671536f,-0.0443535f,0.739643f}, +{-0.68961f,0.249707f,0.679768f},{-0.738688f,0.256526f,0.623325f},{-0.698666f,0.261803f,0.665827f}, +{-0.715903f,0.0721451f,0.694462f},{-0.725187f,0.215298f,0.654026f},{-0.683631f,0.211798f,0.69842f}, +{-0.79723f,0.268798f,0.540529f},{-0.732527f,0.277449f,0.621633f},{-0.722323f,0.258096f,0.641589f}, +{-0.774529f,0.275504f,0.569388f},{-0.709216f,0.264558f,0.653469f},{-0.755688f,0.271082f,0.596197f}, +{-0.814669f,0.415759f,0.4043f},{-0.717839f,0.420681f,0.554738f},{-0.818321f,0.355703f,0.451472f}, +{-0.728371f,0.352353f,0.587642f},{-0.815902f,0.287459f,0.501668f},{-0.824211f,0.430194f,0.368252f}, +{-0.727359f,0.444724f,0.522656f},{-0.72071f,0.437381f,0.537843f},{-0.83751f,0.434129f,0.331828f}, +{-0.73789f,0.44462f,0.50777f},{-0.755597f,0.431964f,0.492423f},{-0.854721f,0.428471f,0.293028f}, +{-0.879159f,0.406702f,0.248341f},{-0.908545f,0.371402f,0.19133f},{-0.683158f,-0.0526576f,0.728369f}, +{-0.652054f,-0.0263917f,0.757713f},{-0.636797f,-0.00909888f,0.770977f},{-0.695352f,-0.0536109f,0.716667f}, +{-0.671834f,-0.0443236f,0.739374f},{-0.680563f,-0.0456191f,0.731268f},{-0.666389f,-0.0392338f,0.744571f}, +{-0.660552f,-0.0375531f,0.749841f},{-0.649157f,-0.0242147f,0.760269f},{-0.716437f,0.0720186f,0.693924f}, +{-0.747931f,0.215375f,0.627863f},{-0.725786f,0.215321f,0.653354f},{-0.683545f,-0.0526197f,0.728009f}, +{-0.711835f,-0.055364f,0.700162f},{-0.69673f,-0.0540181f,0.715297f},{-0.809709f,0.279233f,0.516139f}, +{-0.775365f,0.275645f,0.568181f},{-0.756476f,0.271283f,0.595104f},{-0.786708f,0.274244f,0.553065f}, +{-0.739281f,0.256648f,0.622571f},{-0.76548f,0.258544f,0.589233f},{-0.864019f,0.351817f,0.360134f}, +{-0.81663f,0.287541f,0.500435f},{-0.85903f,0.289026f,0.42253f},{-0.797912f,0.268949f,0.539447f}, +{-0.836894f,0.271782f,0.475123f},{-0.824737f,0.430114f,0.367166f},{-0.815277f,0.415694f,0.40314f}, +{-0.87405f,0.415649f,0.251538f},{-0.818985f,0.355825f,0.450169f},{-0.863226f,0.404724f,0.301729f}, +{-0.887621f,0.415023f,0.199712f},{-0.837936f,0.434041f,0.330866f},{-0.903754f,0.403094f,0.144024f}, +{-0.85503f,0.428382f,0.292254f},{-0.879434f,0.406518f,0.247668f},{-0.924662f,0.372382f,0.079571f}, +{-0.945544f,0.325495f,0.0f},{-0.735204f,0.0705335f,0.674167f},{-0.957958f,0.286908f,-0.000297298f}, +{-0.958184f,0.286152f,-0.00027813f},{-0.951596f,0.278077f,-0.130911f},{-0.956115f,0.266505f,-0.121731f}, +{-0.962828f,0.270116f,-0.00025761f},{-0.971736f,0.23607f,-0.000235456f},{-0.959649f,0.258612f,-0.110422f}, +{-0.993744f,0.111685f,-0.000218645f},{-0.982441f,0.15671f,-0.101255f},{-0.995607f,0.0244862f,-0.0903677f}, +{-0.999997f,0.00228008f,-0.000195691f},{-0.999963f,0.00864389f,-0.000166398f},{-0.996969f,0.0121337f,-0.076847f}, +{-0.999852f,0.0172244f,-0.000133472f},{-0.99785f,0.0209404f,-0.0620961f},{-0.998704f,0.0225323f,-0.0456418f}, +{-0.999808f,0.0196045f,-9.71639e-005f},{-0.999813f,0.0193212f,-5.4502e-005f},{-0.99946f,0.0204337f,-0.0257239f}, +{-0.999843f,0.0176994f,0.0f},{-0.99985f,0.0173199f,0.0f},{-0.953349f,0.267273f,-0.140321f}, +{-0.95479f,0.257069f,-0.149306f},{-0.962413f,0.271589f,-0.00031666f},{-0.959914f,0.280293f,-0.000331412f}, +{-0.946687f,0.282163f,-0.155461f},{-0.937469f,0.308726f,-0.16075f},{-0.947766f,0.318966f,-0.000342471f}, +{-0.931085f,0.324966f,-0.165762f},{-0.93484f,0.355068f,-0.000351538f},{-0.928807f,0.370564f,-0.000361614f}, +{-0.928046f,0.330965f,-0.17086f},{-0.928594f,0.326564f,-0.176266f},{-0.926386f,0.376575f,-0.000372148f}, +{-0.934514f,0.30552f,-0.182597f},{-0.92782f,0.373027f,-0.000383596f},{-0.935191f,0.354145f,-0.000397484f}, +{-0.943202f,0.272835f,-0.189554f},{-0.945578f,0.325394f,-0.00041274f},{-0.997288f,0.0211408f,-0.0705025f}, +{-0.99985f,0.0173199f,-1.50134e-014f},{-0.999888f,0.0149749f,1.04413e-015f},{-0.976903f,0.0190992f,-0.212829f}, +{-0.997001f,0.012063f,-0.0764401f},{-0.98481f,0.0270514f,-0.171517f},{-0.991726f,0.0267385f,-0.125559f}, +{-0.998719f,0.0225092f,-0.0453197f},{-0.959761f,0.258403f,-0.109939f},{-0.942002f,0.185186f,-0.279891f}, +{-0.921009f,0.235359f,-0.310401f},{-0.995645f,0.0245818f,-0.0899239f},{-0.966375f,0.060169f,-0.25f}, +{-0.982591f,0.156085f,-0.100754f},{-0.898699f,0.242529f,-0.365402f},{-0.893124f,0.221008f,-0.391771f}, +{-0.953393f,0.26728f,-0.140014f},{-0.907932f,0.245706f,-0.33954f},{-0.951625f,0.27811f,-0.130631f}, +{-0.95615f,0.266559f,-0.121342f},{-0.865841f,0.222884f,-0.447931f},{-0.937463f,0.308832f,-0.160577f}, +{-0.874336f,0.220933f,-0.432117f},{-0.946719f,0.282182f,-0.155229f},{-0.954855f,0.25702f,-0.148975f}, +{-0.882967f,0.223806f,-0.412649f},{-0.858059f,0.225231f,-0.461525f},{-0.928053f,0.330999f,-0.170754f}, +{-0.931092f,0.32502f,-0.165619f},{-0.852796f,0.216849f,-0.475096f},{-0.928602f,0.32658f,-0.176192f}, +{-0.934555f,0.305399f,-0.182588f},{-0.850459f,0.192096f,-0.489713f},{-0.848968f,0.155604f,-0.505015f}, +{-0.997875f,0.0209039f,-0.0617066f},{-0.999463f,0.0204365f,-0.0256194f},{-0.993882f,0.0198325f,-0.108651f}, +{-0.999888f,0.0149749f,0.0f},{-0.999942f,0.0107279f,0.0f},{-0.940471f,0.027494f,-0.338759f}, +{-0.9848f,0.0270456f,-0.171575f},{-0.961911f,0.0323478f,-0.271441f},{-0.980028f,0.0289941f,-0.196733f}, +{-0.99172f,0.0267423f,-0.125606f},{-0.997263f,0.0211768f,-0.0708398f},{-0.942124f,0.184752f,-0.279767f}, +{-0.842424f,0.198008f,-0.501114f},{-0.92105f,0.235436f,-0.310221f},{-0.976871f,0.0190528f,-0.212979f}, +{-0.914688f,0.0630398f,-0.399213f},{-0.96636f,0.0602812f,-0.250028f},{-0.786761f,0.19314f,-0.586263f}, +{-0.763159f,0.167212f,-0.624203f},{-0.898676f,0.24247f,-0.365499f},{-0.907886f,0.245744f,-0.339635f}, +{-0.8124f,0.201874f,-0.547041f},{-0.700686f,0.0929333f,-0.707392f},{-0.874312f,0.220911f,-0.432176f}, +{-0.718951f,0.113967f,-0.685653f},{-0.88298f,0.2238f,-0.412625f},{-0.893172f,0.221072f,-0.391626f}, +{-0.739263f,0.154471f,-0.65546f},{-0.684218f,0.0875221f,-0.724006f},{-0.858048f,0.225226f,-0.461549f}, +{-0.86583f,0.222895f,-0.447948f},{-0.669461f,0.073847f,-0.739168f},{-0.852792f,0.216833f,-0.475111f}, +{-0.850452f,0.191924f,-0.489793f},{-0.655515f,0.0484461f,-0.753627f},{-0.640906f,0.0158475f,-0.767455f}, +{-0.848968f,0.155604f,-0.505015f},{-0.877789f,0.164174f,-0.450038f},{-0.990338f,0.0167192f,-0.137663f}, +{-0.999942f,0.0107279f,-5.79815e-010f},{-0.999987f,0.00505961f,0.0f},{-0.890883f,0.033892f,-0.452967f}, +{-0.961882f,0.0323469f,-0.271545f},{-0.932581f,0.0355093f,-0.35921f},{-0.966258f,0.0291785f,-0.255917f}, +{-0.980011f,0.0290016f,-0.196817f},{-0.993822f,0.0198883f,-0.10919f},{-0.877955f,0.163842f,-0.449834f}, +{-0.780866f,0.13651f,-0.609602f},{-0.718253f,0.148479f,-0.679755f},{-0.940382f,0.0274608f,-0.339011f}, +{-0.841289f,0.0636188f,-0.536829f},{-0.914656f,0.0631371f,-0.399272f},{-0.609067f,0.125965f,-0.783052f}, +{-0.559997f,0.0957412f,-0.822944f},{-0.786669f,0.193061f,-0.586412f},{-0.812292f,0.201887f,-0.547197f}, +{-0.660203f,0.142438f,-0.737458f},{-0.439944f,-0.0540079f,-0.896399f},{-0.718888f,0.113812f,-0.685746f}, +{-0.472513f,-0.0113659f,-0.88125f},{-0.739288f,0.154497f,-0.655427f},{-0.763303f,0.167295f,-0.624004f}, +{-0.514496f,0.06617f,-0.854936f},{-0.414517f,-0.0658654f,-0.907655f},{-0.684189f,0.0875037f,-0.724037f}, +{-0.700662f,0.0929309f,-0.707415f},{-0.391685f,-0.0816251f,-0.916472f},{-0.669444f,0.0738257f,-0.739185f}, +{-0.65544f,0.0482842f,-0.753702f},{-0.369884f,-0.101927f,-0.92347f},{-0.347635f,-0.123605f,-0.929447f}, +{-0.640907f,0.0158475f,-0.767455f},{-0.842564f,0.198107f,-0.500839f},{-0.989269f,0.0111543f,-0.145677f}, +{-0.999987f,0.00505961f,-2.85058e-010f},{-0.999999f,-0.00138151f,1.91845e-016f},{-0.850391f,0.0382111f,-0.524762f}, +{-0.932523f,0.0355133f,-0.359361f},{-0.91244f,0.0352909f,-0.407687f},{-0.959016f,0.0256877f,-0.282185f}, +{-0.966226f,0.0291895f,-0.256037f},{-0.990238f,0.0167928f,-0.138374f},{-0.781126f,0.136305f,-0.609314f}, +{-0.684245f,0.0955151f,-0.72297f},{-0.584646f,0.0993674f,-0.805181f},{-0.890704f,0.0338728f,-0.453319f}, +{-0.77454f,0.0484155f,-0.630669f},{-0.841226f,0.0636976f,-0.536918f},{-0.401556f,0.0560249f,-0.914119f}, +{-0.326384f,0.0268241f,-0.944856f},{-0.608874f,0.125862f,-0.783218f},{-0.485701f,0.0741101f,-0.870978f}, +{-0.659992f,0.142412f,-0.737652f},{-0.71855f,0.14861f,-0.679412f},{-0.196022f,-0.0637993f,-0.978522f}, +{-0.472378f,-0.0116501f,-0.881319f},{-0.514541f,0.0662311f,-0.854904f},{-0.257578f,0.00189659f,-0.966256f}, +{-0.56027f,0.0958443f,-0.822746f},{-0.110962f,-0.197306f,-0.974042f},{-0.414469f,-0.0658928f,-0.907675f}, +{-0.439905f,-0.0540224f,-0.896418f},{-0.144236f,-0.164717f,-0.975738f},{-0.08502f,-0.210934f,-0.973796f}, +{-0.391658f,-0.081646f,-0.916481f},{-0.0624871f,-0.223578f,-0.972681f},{-0.0413979f,-0.233506f,-0.971474f}, +{-0.369768f,-0.102042f,-0.923504f},{0.369767f,0.102044f,-0.923504f},{0.347635f,0.123604f,-0.929447f}, +{0.414472f,0.0658736f,-0.907675f},{0.110963f,0.1973f,-0.974043f},{0.0850214f,0.210917f,-0.973799f}, +{0.391659f,0.0816379f,-0.916482f},{0.0624874f,0.223573f,-0.972682f},{0.0413979f,0.233508f,-0.971473f}, +{0.257578f,-0.00190271f,-0.966256f},{0.51454f,-0.0662188f,-0.854906f},{0.560269f,-0.0958526f,-0.822746f}, +{0.144235f,0.164734f,-0.975735f},{0.472379f,0.0116715f,-0.881318f},{0.19602f,0.0638166f,-0.978521f}, +{0.659992f,-0.142412f,-0.737652f},{0.71855f,-0.148611f,-0.679412f},{0.485701f,-0.0741122f,-0.870978f}, +{0.608874f,-0.125862f,-0.783218f},{0.401556f,-0.0560238f,-0.914119f},{0.326385f,-0.0268274f,-0.944856f}, +{0.890704f,-0.0338724f,-0.453319f},{0.77454f,-0.0484116f,-0.630669f},{0.841226f,-0.0636956f,-0.536918f}, +{0.684245f,-0.0955126f,-0.72297f},{0.584646f,-0.0993696f,-0.80518f},{0.781126f,-0.136306f,-0.609313f}, +{0.932523f,-0.0355125f,-0.35936f},{0.91244f,-0.0352907f,-0.407686f},{0.850391f,-0.0382116f,-0.524763f}, +{0.966226f,-0.0291876f,-0.256036f},{0.959016f,-0.025686f,-0.282185f},{0.989269f,-0.0111537f,-0.145677f}, +{0.990238f,-0.0167921f,-0.138374f},{0.999987f,-0.0050596f,0.0f},{0.999999f,0.00138152f,-1.73582e-014f}, +{0.439909f,0.05402f,-0.896416f},{0.65544f,-0.0482827f,-0.753702f},{0.640906f,-0.0158483f,-0.767455f}, +{0.700666f,-0.0929347f,-0.707411f},{0.414519f,0.0658462f,-0.907655f},{0.68419f,-0.0875227f,-0.724033f}, +{0.669444f,-0.0738342f,-0.739184f},{0.391685f,0.0816169f,-0.916472f},{0.369884f,0.101929f,-0.92347f}, +{0.514494f,-0.0661576f,-0.854938f},{0.739288f,-0.154485f,-0.65543f},{0.763301f,-0.167303f,-0.624004f}, +{0.439948f,0.0540055f,-0.896398f},{0.718891f,-0.113792f,-0.685745f},{0.472514f,0.0113873f,-0.88125f}, +{0.842564f,-0.198106f,-0.500839f},{0.718253f,-0.14848f,-0.679755f},{0.660203f,-0.142438f,-0.737458f}, +{0.812292f,-0.201887f,-0.547197f},{0.609068f,-0.125965f,-0.783051f},{0.786669f,-0.193061f,-0.586412f}, +{0.940382f,-0.0274602f,-0.33901f},{0.841289f,-0.0636168f,-0.536829f},{0.914656f,-0.0631375f,-0.399271f}, +{0.780866f,-0.136511f,-0.609601f},{0.877955f,-0.163845f,-0.449833f},{0.961882f,-0.0323448f,-0.271544f}, +{0.932581f,-0.0355085f,-0.359209f},{0.890883f,-0.0338916f,-0.452967f},{0.980011f,-0.0289993f,-0.196816f}, +{0.966258f,-0.0291766f,-0.255917f},{0.990338f,-0.0167184f,-0.137663f},{0.993822f,-0.0198877f,-0.109189f}, +{0.999942f,-0.0107279f,-3.47115e-014f},{0.999987f,-0.0050596f,-3.47131e-014f},{0.559996f,-0.0957495f,-0.822944f}, +{0.850452f,-0.191923f,-0.489793f},{0.848968f,-0.155604f,-0.505015f},{0.865832f,-0.222898f,-0.447942f}, +{0.68422f,-0.0875411f,-0.724003f},{0.858046f,-0.225241f,-0.461544f},{0.85279f,-0.21684f,-0.47511f}, +{0.669461f,-0.0738554f,-0.739167f},{0.655515f,-0.0484446f,-0.753627f},{0.739263f,-0.154458f,-0.655463f}, +{0.89317f,-0.221079f,-0.391626f},{0.763157f,-0.16722f,-0.624202f},{0.70069f,-0.092937f,-0.707387f}, +{0.874317f,-0.220895f,-0.432174f},{0.718955f,-0.113948f,-0.685653f},{0.92105f,-0.235433f,-0.310221f}, +{0.842424f,-0.198007f,-0.501114f},{0.8124f,-0.201874f,-0.547041f},{0.907886f,-0.245744f,-0.339635f}, +{0.786761f,-0.19314f,-0.586263f},{0.898676f,-0.24247f,-0.365499f},{0.976871f,-0.0190519f,-0.212977f}, +{0.914689f,-0.0630402f,-0.399213f},{0.966361f,-0.060284f,-0.250026f},{0.877788f,-0.164177f,-0.450037f}, +{0.942123f,-0.184757f,-0.279767f},{0.9848f,-0.0270421f,-0.171573f},{0.961912f,-0.0323457f,-0.27144f}, +{0.940472f,-0.0274934f,-0.338758f},{0.99172f,-0.0267396f,-0.125605f},{0.980029f,-0.0289918f,-0.196732f}, +{0.993882f,-0.0198319f,-0.108651f},{0.997263f,-0.0211762f,-0.0708397f},{0.999888f,-0.0149749f,1.73785e-014f}, +{0.999942f,-0.0107279f,-1.37458e-007f},{0.882982f,-0.223789f,-0.412628f},{0.879976f,-0.406267f,0.24615f}, +{0.945544f,-0.325496f,-4.37825e-014f},{0.825224f,-0.430021f,0.366179f},{0.887589f,-0.415042f,0.199814f}, +{0.838449f,-0.433914f,0.32973f},{0.855563f,-0.428207f,0.290948f},{0.903734f,-0.403111f,0.144105f}, +{0.924654f,-0.372393f,0.0796197f},{0.863964f,-0.351815f,0.360266f},{0.817015f,-0.287563f,0.499794f}, +{0.858968f,-0.289017f,0.422662f},{0.874009f,-0.415666f,0.251654f},{0.815734f,-0.415625f,0.402286f}, +{0.863176f,-0.404737f,0.301853f},{0.756732f,-0.271311f,0.594766f},{0.786642f,-0.274232f,0.553165f}, +{0.809642f,-0.279221f,0.516252f},{0.775661f,-0.27568f,0.567759f},{0.836827f,-0.271774f,0.475247f}, +{0.798255f,-0.268981f,0.538923f},{0.73515f,-0.0705437f,0.674224f},{0.747875f,-0.215371f,0.627932f}, +{0.716587f,-0.0720223f,0.693769f},{0.76542f,-0.258526f,0.589319f},{0.7395f,-0.256658f,0.622308f}, +{0.725968f,-0.215327f,0.65315f},{0.695311f,0.0536227f,0.716706f},{0.711787f,0.0553596f,0.700211f}, +{0.683635f,0.0526367f,0.727924f},{0.696847f,0.05402f,0.715182f},{0.671901f,0.0443476f,0.739312f}, +{0.680533f,0.0456343f,0.731295f},{0.660597f,0.0375712f,0.7498f},{0.666369f,0.0392392f,0.744589f}, +{0.652044f,0.0263913f,0.757722f},{0.64918f,0.0242326f,0.760249f},{0.636797f,0.00909943f,0.770977f}, +{0.819405f,-0.355806f,0.449419f},{0.934555f,-0.305399f,-0.182588f},{0.943202f,-0.272835f,-0.189554f}, +{0.931091f,-0.325025f,-0.165614f},{0.858058f,-0.225246f,-0.46152f},{0.92805f,-0.33101f,-0.170751f}, +{0.928601f,-0.326585f,-0.176191f},{0.852794f,-0.216857f,-0.475095f},{0.850459f,-0.192095f,-0.489713f}, +{0.882969f,-0.223794f,-0.412652f},{0.946723f,-0.282168f,-0.15523f},{0.954853f,-0.257023f,-0.148976f}, +{0.865843f,-0.222888f,-0.447925f},{0.937467f,-0.308825f,-0.160573f},{0.874341f,-0.220917f,-0.432116f}, +{0.951625f,-0.27811f,-0.130631f},{0.95615f,-0.266557f,-0.121342f},{0.907932f,-0.245706f,-0.33954f}, +{0.953392f,-0.267282f,-0.140014f},{0.8987f,-0.242529f,-0.365402f},{0.893122f,-0.221015f,-0.391771f}, +{0.98259f,-0.156094f,-0.100754f},{0.966375f,-0.0601717f,-0.249998f},{0.942001f,-0.185191f,-0.279891f}, +{0.921009f,-0.235357f,-0.310401f},{0.959761f,-0.258402f,-0.10994f},{0.997001f,-0.0120606f,-0.0764369f}, +{0.98481f,-0.0270479f,-0.171515f},{0.976903f,-0.0190983f,-0.212827f},{0.995645f,-0.0245852f,-0.089921f}, +{0.997876f,-0.0208988f,-0.0617047f},{0.991726f,-0.0267358f,-0.125558f},{0.997288f,-0.0211402f,-0.0705024f}, +{0.998719f,-0.0225064f,-0.0453191f},{0.99985f,-0.0173199f,0.0f},{0.999463f,-0.020436f,-0.0256193f}, +{0.999888f,-0.0149749f,0.0f},{0.93519f,-0.354145f,-0.000397467f},{0.945578f,-0.325394f,-0.00041274f}, +{0.928805f,-0.37057f,-0.000358322f},{0.928043f,-0.330975f,-0.170857f},{0.926383f,-0.376582f,-0.00037055f}, +{0.927819f,-0.37303f,-0.00038323f},{0.928592f,-0.326569f,-0.176265f},{0.934514f,-0.30552f,-0.182597f}, +{0.946691f,-0.282148f,-0.155461f},{0.94777f,-0.318954f,-0.000340813f},{0.959916f,-0.280289f,-0.000332774f}, +{0.931084f,-0.324972f,-0.165758f},{0.934841f,-0.355065f,-0.000347719f},{0.937472f,-0.308718f,-0.160746f}, +{0.957958f,-0.286908f,-0.000297201f},{0.958184f,-0.286152f,-0.000278036f},{0.951596f,-0.278077f,-0.130911f}, +{0.962412f,-0.271594f,-0.000317168f},{0.953349f,-0.267276f,-0.140321f},{0.954789f,-0.257072f,-0.149307f}, +{0.993743f,-0.111694f,-0.00021707f},{0.982439f,-0.156718f,-0.101254f},{0.971735f,-0.236074f,-0.000236761f}, +{0.95965f,-0.25861f,-0.110423f},{0.956116f,-0.266503f,-0.121731f},{0.962829f,-0.270112f,-0.000258194f}, +{0.999963f,-0.00863986f,-0.000162909f},{0.996969f,-0.0121313f,-0.0768439f},{0.999997f,-0.00228269f,-0.000191989f}, +{0.995608f,-0.0244896f,-0.0903648f},{0.999852f,-0.0172187f,-0.000131616f},{0.997851f,-0.0209353f,-0.0620942f}, +{0.998704f,-0.0225295f,-0.0456412f},{0.999808f,-0.0196018f,-9.66914e-005f},{0.999813f,-0.0193208f,-5.44735e-005f}, +{0.99946f,-0.0204332f,-0.0257239f},{0.999843f,-0.0176994f,0.0f},{-0.271326f,0.0f,0.962488f}, +{-0.253151f,0.0f,0.967427f},{-0.26258f,0.0f,0.96491f},{-0.147431f,0.0f,0.989072f}, +{-0.162743f,0.0f,0.986669f},{-0.209863f,0.0f,0.977731f},{-0.243346f,0.0f,0.96994f}, +{-0.20324f,0.0f,0.979129f},{-0.0844041f,0.0f,0.996432f},{-0.0211631f,0.0f,0.999776f}, +{-0.0519304f,0.0f,0.998651f},{-0.0826965f,0.0f,0.996575f},{-0.113463f,0.0f,0.993542f}, +{-0.11544f,0.0f,0.993314f},{-0.119575f,0.0f,0.992825f},{-0.125688f,0.0f,0.99207f}, +{-0.133439f,0.0f,0.991057f},{-0.142487f,0.0f,0.989797f},{-0.1524f,0.0f,0.988319f}, +{0.123071f,6.49463e-018f,-0.992398f},{0.13416f,-1.11865e-017f,-0.99096f},{0.134575f,-3.82822e-018f,-0.990903f}, +{0.113491f,1.60303e-018f,-0.993539f},{0.0902913f,7.81879e-018f,-0.995915f},{0.0774828f,9.91352e-018f,-0.996994f}, +{0.0670916f,1.03021e-017f,-0.997747f},{0.0438914f,-1.68674e-018f,-0.999036f},{0.147436f,3.8365e-018f,-0.989072f}, +{0.0206911f,8.0814e-018f,-0.999786f},{0.160907f,8.05703e-018f,-0.98697f},{0.190446f,1.33567e-017f,-0.981698f}, +{0.300752f,0.0f,-0.953702f},{0.299196f,0.0f,-0.954192f},{0.266455f,-9.04092e-018f,-0.963847f}, +{0.25387f,3.88234e-018f,-0.967238f},{0.246065f,-1.05499e-017f,-0.969253f},{0.294624f,3.20684e-018f,-0.955613f}, +{0.287357f,-3.12775e-018f,-0.957824f},{0.277782f,1.04562e-017f,-0.960644f},{0.240601f,1.18742e-017f,-0.970624f}, +{-1.0f,-6.77626e-018f,1.27676e-015f},{-1.0f,-6.77626e-018f,1.27052e-015f},{-1.0f,0.0f,1.27676e-015f}, +{-1.0f,-3.2255e-018f,1.2844e-015f},{-1.0f,-2.22261e-018f,1.27052e-015f},{-1.0f,-2.05998e-018f,1.27052e-015f}, +{-1.0f,2.92735e-018f,1.2844e-015f},{-1.0f,0.0f,1.27052e-015f},{2.22045e-016f,1.0f,0.0f}, +{-4.44089e-016f,1.0f,0.0f},{4.44089e-016f,1.0f,0.0f},{-8.88178e-016f,1.0f,0.0f}, +{0.895526f,0.44501f,0.0f},{0.957889f,0.287138f,0.0f},{0.964461f,0.264225f,0.0f}, +{0.996976f,0.0777153f,0.0f},{0.87496f,0.484196f,0.0f},{0.788298f,0.615293f,0.0f}, +{0.752381f,0.658728f,0.0f},{0.629043f,0.777371f,0.0f},{0.595906f,0.803054f,0.0f}, +{0.437093f,0.899416f,0.0f},{0.412424f,0.910992f,0.0f},{0.223703f,0.974657f,0.0f}, +{0.210088f,0.977683f,0.0f},{-1.04131e-014f,1.0f,0.0f},{-5.20654e-015f,1.0f,0.0f}, +{-0.77709f,0.62939f,1.00199e-015f},{-0.793886f,0.608066f,8.62015e-016f},{-0.63319f,0.773996f,7.65657e-016f}, +{6.28037e-016f,1.0f,-6.81933e-031f},{-2.51215e-015f,1.0f,2.72773e-030f},{-0.22043f,0.975403f,2.71985e-016f}, +{-0.429735f,0.902955f,5.30243e-016f},{-0.226136f,0.974096f,2.90187e-016f},{-0.44128f,0.89737f,5.88046e-016f}, +{-0.61793f,0.786233f,7.01456e-016f},{-0.8981f,0.439791f,9.6132e-016f},{-0.974099f,0.22612f,1.13394e-015f}, +{-0.906488f,0.422231f,1.14646e-015f},{-0.976328f,0.216293f,1.13616e-015f},{-1.0f,3.14018e-016f,1.18453e-015f}, +{-0.636824f,0.0f,0.771009f},{-0.636824f,4.41885e-018f,0.771009f},{0.976094f,0.0764224f,0.203472f}, +{0.996976f,0.0777152f,2.3946e-009f},{0.996976f,0.0777152f,1.82309e-009f},{-0.0519161f,5.69588e-006f,0.998651f}, +{0.456027f,0.0391237f,0.889106f},{-0.0825944f,1.35909e-005f,0.996583f},{0.861638f,0.0691877f,0.502785f}, +{0.636981f,0.0509221f,0.769196f},{0.996976f,0.0777152f,6.33733e-010f},{0.996976f,0.0777152f,-2.35021e-015f}, +{0.917412f,0.0749912f,0.390808f},{0.856741f,0.0700812f,0.510962f},{0.282672f,0.0305668f,0.95873f}, +{0.436736f,0.0398436f,0.898707f},{0.663385f,0.0583498f,0.746f},{0.347654f,0.0286465f,0.937185f}, +{0.854338f,0.0674458f,0.515323f},{-0.113462f,1.67095e-011f,0.993542f},{-0.0211583f,3.90358e-007f,0.999776f}, +{0.996976f,0.0777152f,1.22379e-009f},{-0.115053f,0.707107f,0.697684f},{0.041302f,0.702691f,0.710295f}, +{0.13998f,0.918265f,0.3704f},{0.196116f,0.664219f,0.721354f},{0.515388f,0.76718f,0.381851f}, +{0.335631f,0.863385f,0.376721f},{0.464798f,0.490492f,0.737143f},{0.794304f,0.467108f,0.388447f}, +{0.671315f,0.632878f,0.385748f},{0.996976f,0.0777152f,8.89301e-008f},{0.957256f,0.289241f,8.65022e-007f}, +{0.87754f,0.278854f,0.390082f},{0.171643f,0.256675f,0.951135f},{0.101729f,0.309894f,0.945313f}, +{-0.133372f,-4.90387e-007f,0.991066f},{0.26464f,0.113588f,0.957634f},{0.631152f,0.216859f,0.744728f}, +{0.227046f,0.189962f,0.955178f},{-0.151307f,0.368095f,0.917394f},{-0.0644563f,0.366433f,0.928209f}, +{-0.162743f,-1.36278e-016f,0.986669f},{-0.152368f,-4.77403e-007f,0.988324f},{-0.0598835f,0.929788f,0.363191f}, +{0.20987f,0.977729f,1.07918e-005f},{-1.37117e-008f,1.0f,8.31709e-008f},{0.0217202f,0.34688f,0.937658f}, +{-0.142402f,-1.01854e-006f,0.989809f},{0.563926f,0.362795f,0.741867f},{0.339591f,0.592707f,0.730326f}, +{-0.115426f,-7.18981e-007f,0.993316f},{0.282671f,0.0305691f,0.95873f},{-0.113463f,1.58673e-014f,0.993542f}, +{0.663385f,0.0583523f,0.746f},{0.411528f,0.911397f,6.3595e-006f},{0.917412f,0.0749922f,0.390808f}, +{0.594217f,0.804305f,4.18309e-006f},{-0.125613f,-1.78317e-007f,0.992079f},{0.751163f,0.660117f,2.58675e-006f}, +{-0.11953f,1.33025e-007f,0.992831f},{0.874228f,0.485516f,4.30103e-007f},{-0.0599047f,0.929788f,0.363187f}, +{6.95989e-015f,1.0f,-4.64483e-014f},{-0.0993814f,0.87226f,0.478837f},{-0.203217f,2.41719e-015f,0.979134f}, +{-0.177258f,0.489042f,0.85406f},{-0.119006f,0.87226f,0.474341f},{-0.212261f,0.489042f,0.84604f}, +{-0.151316f,0.368095f,0.917393f},{-0.162743f,0.0f,0.986669f},{-0.115076f,0.707107f,0.69768f}, +{-0.750862f,0.640795f,0.159966f},{-0.690083f,0.633896f,0.34923f},{-0.633689f,0.773588f,4.47054e-006f}, +{-0.119072f,0.87226f,0.474324f},{-0.226237f,0.974072f,4.35889e-005f},{-0.441461f,0.89728f,1.9127e-005f}, +{-0.314908f,0.831026f,0.458507f},{-0.793896f,0.608053f,1.75823e-008f},{-0.604452f,0.56074f,0.56587f}, +{-0.475573f,0.362672f,0.801436f},{-0.425828f,0.412157f,0.805479f},{-0.4929f,0.748579f,0.443484f}, +{-0.2123f,0.489042f,0.84603f},{-0.325164f,0.461687f,0.825296f},{-0.271328f,2.66133e-006f,0.962487f}, +{-0.262654f,3.42352e-007f,0.96489f},{-0.243346f,-1.24911e-015f,0.96994f},{-0.253185f,2.24678e-006f,0.967418f}, +{0.640323f,0.0486817f,-0.766562f},{0.513173f,0.0370848f,-0.857483f},{0.875571f,0.0666236f,-0.478474f}, +{0.996904f,0.0775964f,-0.0127208f},{0.996948f,0.0776561f,-0.00805679f},{0.880476f,0.0653022f,-0.469572f}, +{0.878213f,0.0659754f,-0.473698f},{0.857586f,0.0660304f,-0.510084f},{0.996974f,0.0777085f,-0.00192217f}, +{0.996976f,0.0777145f,-0.00043536f},{0.977579f,0.0758877f,-0.196417f},{0.043964f,5.59703e-006f,-0.999033f}, +{0.350245f,0.0257948f,-0.936303f},{0.52637f,0.0365804f,-0.849468f},{0.0672212f,1.00329e-005f,-0.997738f}, +{0.616326f,0.0410888f,-0.786418f},{0.902304f,0.0665963f,-0.425926f},{0.539132f,0.036057f,-0.841449f}, +{0.0206959f,4.01696e-007f,-0.999786f},{0.113495f,3.419e-007f,-0.993538f},{0.996967f,0.0776912f,-0.00445871f}, +{0.0904433f,1.17965e-005f,-0.995902f},{-0.123071f,-6.16506e-018f,-0.992398f},{-0.13416f,1.30823e-017f,-0.99096f}, +{-0.134575f,4.86852e-018f,-0.990903f},{-0.113491f,-8.07206e-018f,-0.993539f},{-0.0902913f,1.48949e-020f,-0.995915f}, +{-0.0774828f,-3.75189e-018f,-0.996994f},{-0.0670916f,5.48641e-018f,-0.997747f},{-0.0438914f,-2.91677e-017f,-0.999036f}, +{-0.147436f,3.19289e-018f,-0.989072f},{-0.0206911f,-5.39916e-018f,-0.999786f},{-0.160907f,-1.04945e-017f,-0.98697f}, +{-0.190446f,-2.1531e-018f,-0.981698f},{-0.300752f,0.0f,-0.953702f},{-0.299196f,-1.03859e-017f,-0.954192f}, +{-0.266455f,-1.0491e-017f,-0.963847f},{-0.25387f,-5.26397e-018f,-0.967238f},{-0.246065f,1.44857e-017f,-0.969253f}, +{-0.294624f,0.0f,-0.955613f},{-0.287357f,1.04255e-017f,-0.957824f},{-0.277782f,0.0f,-0.960644f}, +{-0.240601f,5.2824e-018f,-0.970624f},{0.271326f,0.0f,0.962488f},{0.253151f,0.0f,0.967427f}, +{0.26258f,0.0f,0.96491f},{0.147431f,0.0f,0.989072f},{0.162743f,0.0f,0.986669f}, +{0.209863f,0.0f,0.977731f},{0.243346f,0.0f,0.96994f},{0.20324f,0.0f,0.979129f}, +{0.0844041f,0.0f,0.996432f},{0.0211631f,0.0f,0.999776f},{0.0519304f,0.0f,0.998651f}, +{0.0826965f,0.0f,0.996575f},{0.113463f,0.0f,0.993542f},{0.115523f,0.0f,0.993305f}, +{0.119556f,0.0f,0.992828f},{0.125642f,0.0f,0.992076f},{0.133401f,0.0f,0.991062f}, +{0.142437f,0.0f,0.989804f},{0.152342f,0.0f,0.988328f},{1.0f,0.0f,-1.26288e-015f}, +{1.0f,0.0f,-1.26775e-015f},{1.77636e-015f,-1.0f,0.0f},{-0.895526f,-0.44501f,0.0f}, +{-0.957888f,-0.287142f,0.0f},{-0.964461f,-0.264225f,0.0f},{-0.996976f,-0.0777153f,0.0f}, +{-0.874961f,-0.484193f,0.0f},{-0.788298f,-0.615293f,0.0f},{-0.752379f,-0.658731f,0.0f}, +{-0.629043f,-0.777371f,0.0f},{-0.595907f,-0.803054f,0.0f},{-0.437093f,-0.899416f,0.0f}, +{-0.412414f,-0.910997f,0.0f},{-0.223703f,-0.974657f,0.0f},{-0.210092f,-0.977682f,0.0f}, +{1.04131e-014f,-1.0f,0.0f},{5.20654e-015f,-1.0f,0.0f},{0.793886f,-0.608066f,-1.01875e-015f}, +{0.63319f,-0.773996f,-7.50031e-016f},{0.77709f,-0.62939f,-9.20484e-016f},{0.44128f,-0.89737f,-5.60822e-016f}, +{0.61793f,-0.786233f,-7.31954e-016f},{0.22043f,-0.975403f,-2.72665e-016f},{0.429735f,-0.902955f,-5.0373e-016f}, +{0.226136f,-0.974096f,-2.80072e-016f},{0.8981f,-0.439791f,-1.24113e-015f},{0.974099f,-0.22612f,-1.15385e-015f}, +{0.906488f,-0.422231f,-1.07376e-015f},{0.976328f,-0.216293f,-1.15649e-015f},{1.0f,-3.14018e-016f,-1.18453e-015f}, +{0.636824f,-4.24524e-018f,0.771009f},{0.636824f,9.31099e-019f,0.771009f},{0.636824f,-5.78592e-018f,0.771009f}, +{0.636824f,-5.00079e-018f,0.771009f},{0.636824f,0.0f,0.771009f},{0.636824f,1.67186e-018f,0.771009f}, +{0.636824f,4.01246e-018f,0.771009f},{0.636824f,2.67498e-018f,0.771009f},{0.636824f,5.34995e-018f,0.771009f}, +{0.636824f,-2.00623e-018f,0.771009f},{0.636824f,-3.77969e-018f,0.771009f},{0.636824f,-2.75858e-018f,0.771009f}, +{0.636824f,2.26987e-019f,0.771009f},{0.636824f,-5.34995e-018f,0.771009f},{0.636824f,2.20943e-018f,0.771009f}, +{-0.975689f,-0.076394f,0.205416f},{-0.996976f,-0.0777152f,2.40026e-009f},{-0.996976f,-0.0777152f,1.82763e-009f}, +{0.0519161f,-5.69588e-006f,0.998651f},{-0.456027f,-0.0391237f,0.889106f},{0.0825944f,-1.3591e-005f,0.996583f}, +{-0.861638f,-0.0691877f,0.502785f},{-0.635452f,-0.050805f,0.770467f},{-0.996976f,-0.0777152f,6.35071e-010f}, +{-0.996976f,-0.0777152f,1.31007e-017f},{-0.917412f,-0.0749912f,0.390808f},{-0.856741f,-0.0700812f,0.510962f}, +{-0.282672f,-0.0305668f,0.95873f},{-0.436736f,-0.0398436f,0.898707f},{-0.663385f,-0.0583498f,0.746f}, +{-0.345792f,-0.0285025f,0.937878f},{-0.853315f,-0.0673689f,0.517025f},{0.113462f,-1.67093e-011f,0.993542f}, +{0.0211583f,-3.90359e-007f,0.999776f},{-0.996976f,-0.0777152f,1.22684e-009f},{-0.564161f,-0.362409f,0.741878f}, +{-0.264855f,-0.112973f,0.957648f},{-0.631536f,-0.215685f,0.744744f},{-0.75206f,-0.659094f,-1.94181e-007f}, +{-0.672214f,-0.631911f,0.385768f},{-0.794595f,-0.466608f,0.388454f},{-0.595421f,-0.803414f,4.71637e-006f}, +{-0.917412f,-0.0749922f,0.390808f},{-0.95773f,-0.28767f,5.42362e-007f},{-0.878015f,-0.277342f,0.390091f}, +{-0.0219211f,-0.346813f,0.937678f},{0.133312f,1.10489e-006f,0.991074f},{-0.102261f,-0.309574f,0.94536f}, +{-0.996976f,-0.0777152f,-3.03639e-015f},{-0.0424957f,-0.702528f,0.710387f},{0.0598835f,-0.929788f,0.363191f}, +{0.115053f,-0.707107f,0.697684f},{-0.411994f,-0.911187f,8.1719e-006f},{-0.336083f,-0.863203f,0.376735f}, +{-0.516581f,-0.766361f,0.381883f},{-0.141492f,-0.918012f,0.37045f},{-0.196474f,-0.664088f,0.721378f}, +{0.152291f,4.30608e-007f,0.988336f},{0.142379f,7.6959e-007f,0.989812f},{0.0637951f,-0.366351f,0.928287f}, +{-0.465521f,-0.48975f,0.73718f},{-0.227177f,-0.18976f,0.955187f},{0.151307f,-0.368095f,0.917394f}, +{0.162743f,1.2436e-015f,0.986669f},{-0.874519f,-0.484991f,1.45876e-006f},{-0.663385f,-0.0583523f,0.746f}, +{-0.282671f,-0.0305691f,0.95873f},{0.113463f,5.79189e-014f,0.993542f},{0.115403f,9.38329e-007f,0.993319f}, +{-0.172046f,-0.256288f,0.951166f},{0.119516f,3.02192e-008f,0.992832f},{0.125569f,-3.80451e-007f,0.992085f}, +{-0.340547f,-0.59209f,0.730382f},{-0.21143f,-0.977393f,5.28771e-006f},{0.0599047f,-0.929788f,0.363187f}, +{-6.95989e-015f,-1.0f,-4.64483e-014f},{0.0993814f,-0.87226f,0.478837f},{0.203217f,-1.63982e-015f,0.979134f}, +{0.177258f,-0.489042f,0.85406f},{0.119006f,-0.87226f,0.474341f},{0.212261f,-0.489042f,0.84604f}, +{0.151316f,-0.368095f,0.917393f},{0.162743f,-3.30488e-015f,0.986669f},{0.115076f,-0.707107f,0.69768f}, +{0.750862f,-0.640795f,0.159966f},{0.690083f,-0.633896f,0.34923f},{0.633689f,-0.773588f,4.47054e-006f}, +{0.119072f,-0.87226f,0.474324f},{0.226237f,-0.974072f,4.35889e-005f},{0.441461f,-0.89728f,1.9127e-005f}, +{0.314908f,-0.831026f,0.458507f},{0.793896f,-0.608053f,1.75822e-008f},{0.604452f,-0.56074f,0.56587f}, +{0.475573f,-0.362672f,0.801436f},{0.425828f,-0.412157f,0.805479f},{0.4929f,-0.748579f,0.443484f}, +{0.2123f,-0.489042f,0.84603f},{0.325164f,-0.461687f,0.825296f},{0.271328f,-2.66133e-006f,0.962487f}, +{0.262654f,-3.42352e-007f,0.96489f},{0.243346f,-1.05425e-016f,0.96994f},{0.253185f,-2.24678e-006f,0.967418f}, +{-0.875571f,-0.0666236f,-0.478474f},{-0.640323f,-0.0486817f,-0.766562f},{-0.513173f,-0.0370848f,-0.857483f}, +{-0.350245f,-0.0257948f,-0.936303f},{-0.0206959f,-4.01482e-007f,-0.999786f},{-0.0439641f,-5.59705e-006f,-0.999033f}, +{-0.616326f,-0.0410888f,-0.786418f},{-0.539132f,-0.036057f,-0.841449f},{-0.113495f,-3.41892e-007f,-0.993538f}, +{-0.880476f,-0.0653022f,-0.469573f},{-0.996948f,-0.0776561f,-0.00805682f},{-0.878213f,-0.0659754f,-0.473698f}, +{-0.902304f,-0.0665963f,-0.425926f},{-0.996904f,-0.0775964f,-0.0127207f},{-0.996967f,-0.0776912f,-0.00445868f}, +{-0.857586f,-0.0660304f,-0.510084f},{-0.52637f,-0.0365804f,-0.849468f},{-0.996974f,-0.0777085f,-0.00192216f}, +{-0.996976f,-0.0777145f,-0.000435368f},{-0.977579f,-0.0758877f,-0.196417f},{-0.0672213f,-1.00329e-005f,-0.997738f}, +{-0.0904433f,-1.17964e-005f,-0.995902f},{0.239165f,0.970979f,0.0f},{2.21189e-011f,1.0f,0.0f}, +{-9.4369e-017f,1.0f,0.0f},{0.934452f,0.35609f,0.0f},{0.822248f,0.569129f,0.0f}, +{0.823f,0.568041f,0.0f},{0.464996f,0.885313f,0.0f},{0.662288f,0.74925f,0.0f}, +{0.463813f,0.885933f,0.0f},{0.992785f,-0.119912f,0.0f},{0.935185f,-0.354158f,0.0f}, +{0.992772f,-0.120012f,0.0f},{0.934789f,0.355204f,0.0f},{0.992676f,0.120803f,0.0f}, +{0.99262f,0.12127f,0.0f},{0.823569f,-0.567216f,0.0f},{0.663361f,-0.7483f,0.0f}, +{0.823234f,-0.567703f,0.0f},{0.935249f,-0.353989f,0.0f},{0.663427f,-0.748241f,0.0f}, +{0.465239f,-0.885185f,0.0f},{0.465056f,-0.885281f,0.0f},{0.239511f,-0.970894f,0.0f}, +{0.239712f,-0.970844f,0.0f},{0.663196f,0.748446f,0.0f},{0.238516f,0.971139f,0.0f}, +{-1.11022e-016f,0.0f,-1.0f},{1.11022e-016f,0.0f,-1.0f},{5.55112e-017f,0.0f,-1.0f}, +{-5.55112e-017f,0.0f,-1.0f},{1.38778e-017f,1.0f,0.0f},{0.281866f,0.959454f,3.5075e-017f}, +{0.28018f,0.959948f,-4.21701e-019f},{0.989747f,0.142833f,2.49501e-017f},{0.909389f,0.415948f,-1.25209e-017f}, +{0.910294f,0.413963f,-4.85725e-018f},{0.755415f,0.655247f,1.3143e-017f},{0.53479f,0.844985f,1.81431e-018f}, +{0.542504f,0.840053f,1.76327e-018f},{0.910294f,-0.413963f,-1.17305e-017f},{0.989747f,-0.142833f,2.30199e-017f}, +{0.909389f,-0.415948f,2.57792e-017f},{0.989934f,0.141528f,-9.05295e-018f},{0.989934f,-0.141527f,2.56689e-017f}, +{0.542504f,-0.840053f,-5.88236e-019f},{0.755415f,-0.655247f,2.43207e-017f},{0.53479f,-0.844985f,-3.19936e-017f}, +{0.755193f,-0.655503f,8.23455e-018f},{0.28018f,-0.959948f,3.039e-017f},{0.281866f,-0.959454f,-5.9836e-018f}, +{7.40149e-017f,-1.0f,0.0f},{0.755193f,0.655503f,1.3143e-017f},{7.40149e-017f,1.0f,0.0f}, +{0.270909f,0.962605f,0.0f},{4.07586e-012f,1.0f,0.0f},{0.950963f,0.309304f,0.0f}, +{0.808694f,0.588229f,0.0f},{0.912501f,0.409074f,0.0f},{0.759143f,0.650924f,0.0f}, +{0.583716f,0.811958f,0.0f},{0.542309f,0.840179f,0.0f},{0.951446f,-0.307814f,0.0f}, +{0.905627f,-0.424076f,0.0f},{0.809042f,-0.587751f,0.0f},{0.990956f,0.134185f,0.0f}, +{0.988363f,-0.152115f,0.0f},{1.0f,2.72147e-017f,0.0f},{0.589654f,-0.807656f,0.0f}, +{0.749122f,-0.662432f,0.0f},{0.5326f,-0.846367f,0.0f},{0.275665f,-0.961254f,0.0f}, +{0.309676f,-0.950842f,0.0f},{0.305779f,0.952103f,0.0f},{0.272029f,0.962289f,0.0f}, +{-5.92119e-016f,1.0f,0.0f},{1.60011e-012f,1.0f,0.0f},{0.911657f,0.410952f,0.0f}, +{0.759835f,0.650115f,0.0f},{0.540288f,0.84148f,0.0f},{0.988688f,-0.149984f,0.0f}, +{0.905627f,-0.424076f,0.0f},{0.990518f,0.137383f,0.0f},{1.0f,3.70074e-017f,0.0f}, +{0.75011f,-0.661313f,0.0f},{0.534974f,-0.844868f,0.0f},{0.277678f,-0.960674f,0.0f}, +{1.19209e-007f,-1.0f,0.0f},{-0.133225f,0.157091f,0.978557f},{-0.301804f,-0.0247052f,0.95305f}, +{-0.321243f,-0.00178462f,0.946995f},{-0.418489f,0.112883f,0.901179f},{-0.243083f,0.286628f,0.92669f}, +{-0.225214f,0.265559f,0.93742f},{-0.452261f,-0.283519f,0.845622f},{-0.645f,-0.47632f,0.597573f}, +{-0.656839f,-0.462361f,0.595638f},{-0.282442f,-0.0475355f,0.958106f},{-0.114411f,0.134906f,0.984231f}, +{-0.765511f,-0.605729f,0.216993f},{-0.76115f,-0.610871f,0.217916f},{-0.244062f,-0.0927915f,0.96531f}, +{-0.469014f,-0.263765f,0.842884f},{-0.263186f,-0.0702416f,0.962185f},{-0.739853f,-0.635983f,-0.219416f}, +{-0.748269f,-0.62606f,0.219416f},{-0.757174f,-0.642143f,0.119748f},{-0.756818f,-0.615978f,0.218624f}, +{-0.504783f,-0.428095f,-0.749619f},{-0.38664f,-0.360895f,-0.848684f},{-0.598628f,-0.530999f,-0.599736f}, +{-0.712963f,-0.604648f,-0.355084f},{0.038317f,-0.0451812f,-0.998244f},{-0.150369f,-0.203268f,-0.967508f}, +{-0.169153f,-0.181119f,-0.968805f},{0.0191669f,-0.0226006f,-0.999561f},{-0.18253f,-0.1548f,-0.970938f}, +{4.02562e-016f,-4.74676e-016f,-1.0f},{-0.170486f,0.201027f,0.964636f},{-0.340727f,0.0211908f,0.939923f}, +{-0.360228f,0.0441843f,0.931817f},{-0.151922f,0.179137f,0.972023f},{-0.379711f,0.0671573f,0.922665f}, +{-0.1889f,0.222739f,0.956402f},{-0.588114f,-0.123331f,0.79932f},{-0.399143f,0.0900703f,0.912454f}, +{-0.207148f,0.244256f,0.947327f},{-0.437715f,0.135553f,0.888837f},{-0.260738f,0.307446f,0.915146f}, +{-0.475662f,0.180297f,0.860952f},{-0.49431f,0.202286f,0.845422f},{-0.312267f,0.368206f,0.875736f}, +{-0.456785f,0.158038f,0.875426f},{-0.36133f,0.426058f,0.829407f},{-0.345274f,0.407126f,0.845597f}, +{-0.530776f,0.245284f,0.811242f},{-0.328915f,0.387836f,0.861045f},{-0.392475f,0.462782f,0.794856f}, +{-0.565895f,0.286694f,0.773026f},{-0.582863f,0.306702f,0.752465f},{-0.548521f,0.266208f,0.792627f}, +{-0.436576f,0.514784f,0.737834f},{-0.615454f,0.345131f,0.708591f},{-0.450527f,0.531233f,0.717508f}, +{-0.599393f,0.326194f,0.730976f},{-0.489956f,0.577725f,0.652822f},{-0.477228f,0.562717f,0.674983f}, +{-0.660525f,0.398276f,0.636461f},{-0.464081f,0.547216f,0.696551f},{-0.646047f,0.381204f,0.661292f}, +{-0.525514f,0.619653f,0.58298f},{-0.687723f,0.430346f,0.58467f},{-0.700401f,0.445295f,0.557808f}, +{-0.674425f,0.414666f,0.610904f},{-0.723827f,0.472918f,0.502416f},{-0.55692f,0.656685f,0.508532f}, +{-0.546929f,0.644904f,0.533824f},{-0.536457f,0.632556f,0.558647f},{-0.583927f,0.68853f,0.430066f}, +{-0.575427f,0.678508f,0.45663f},{-0.753955f,0.508443f,0.415977f},{-0.734548f,0.48556f,0.473994f}, +{-0.762629f,0.518671f,0.386494f},{-0.59938f,0.706751f,0.375828f},{-0.591913f,0.697947f,0.403124f}, +{-0.784509f,0.54447f,0.296814f},{-0.612728f,0.72249f,0.32027f},{-0.777905f,0.536683f,0.326857f}, +{-0.60632f,0.714934f,0.348202f},{-0.770612f,0.528084f,0.356769f},{-0.623923f,0.735691f,0.263588f}, +{-0.795672f,0.557633f,0.236543f},{-0.628701f,0.741325f,0.234887f},{-0.790429f,0.551451f,0.266692f}, +{-0.618597f,0.729411f,0.292057f},{-0.632927f,0.746308f,0.205979f},{-0.804162f,0.567644f,0.176364f}, +{-0.636597f,0.750636f,0.176891f},{-0.800246f,0.563026f,0.206418f},{-0.814352f,0.57966f,0.0287253f}, +{-0.646797f,0.762662f,3.14853e-016f},{-0.646513f,0.762327f,0.0296338f},{-0.639708f,0.754304f,0.147647f}, +{-0.807432f,0.5715f,0.146429f},{-0.812092f,0.576994f,0.0870897f},{-0.949862f,0.30322f,0.0762915f}, +{-0.951107f,0.304688f,0.0506043f},{-0.645661f,0.761323f,0.0592414f},{-0.642257f,0.757309f,0.118274f}, +{-0.644242f,0.75965f,0.0887967f},{-0.813513f,0.57867f,0.0577667f},{-0.81007f,0.574611f,0.116657f}, +{-0.997518f,-0.0606536f,0.0357603f},{-0.885978f,-0.463681f,0.00650573f},{-0.998038f,-0.0600411f,0.0177823f}, +{-0.942915f,0.295029f,0.154497f},{-0.939484f,0.290984f,0.180824f},{-0.996638f,-0.061691f,0.0539127f}, +{-0.948091f,0.301132f,0.102193f},{-0.995387f,-0.0631666f,0.0722163f},{-0.991729f,-0.0674795f,0.109178f}, +{-0.602655f,-0.797758f,-0.0197241f},{-0.603113f,-0.797218f,-0.0264206f},{-0.223622f,-0.973184f,-0.0539127f}, +{-0.885009f,-0.464825f,0.0264206f},{-0.885466f,-0.464285f,0.0197241f},{0.14403f,-0.986628f,-0.0762915f}, +{0.145275f,-0.988096f,-0.0506043f},{-0.0805097f,-0.996754f,-1.10368e-016f},{-0.222222f,-0.974834f,-0.0177823f}, +{0.14601f,-0.988963f,-0.0251637f},{0.438888f,-0.898083f,-0.0287253f},{0.427652f,-0.903943f,-3.00521e-016f}, +{0.17704f,-0.984204f,-5.39175e-016f},{0.646797f,-0.762662f,-6.22394e-016f},{-0.930885f,0.280844f,0.233625f}, +{-0.712441f,0.459492f,0.530373f},{-0.566422f,0.66789f,0.482793f},{-0.744593f,0.497404f,0.445162f}, +{-0.872541f,0.212049f,0.440122f},{-0.514109f,0.606205f,0.606801f},{-0.502253f,0.592225f,0.630089f}, +{-0.631014f,0.363479f,0.68535f},{-0.422243f,0.497882f,0.757512f},{-0.804404f,0.131706f,0.579299f}, +{-0.893848f,-0.182894f,0.409371f},{-0.902811f,-0.172326f,0.394f},{-0.407538f,0.480543f,0.776525f}, +{-0.377068f,0.444615f,0.812488f},{-0.295345f,0.348252f,0.889658f},{-0.278164f,0.327993f,0.902799f}, +{-0.512693f,0.223962f,0.828846f},{-0.844231f,-0.241401f,0.47854f},{-0.718971f,0.030968f,0.69435f}, +{-0.833475f,-0.254083f,0.490674f},{-0.0954963f,0.112603f,0.98904f},{-0.0764977f,0.0902013f,0.992981f}, +{-0.0574318f,0.06772f,0.99605f},{-0.621631f,-0.503876f,0.599736f},{-0.71354f,-0.605138f,0.353084f}, +{-0.225096f,-0.115155f,0.967508f},{-0.0383156f,0.0451794f,0.998244f},{-0.206312f,-0.137304f,0.968805f}, +{-0.019166f,0.0225994f,0.999561f},{-0.757056f,-0.642042f,-0.121027f},{-0.182011f,-0.154359f,0.971105f}, +{-2.03646e-016f,2.40127e-016f,1.0f},{-0.355998f,-0.301914f,0.884372f},{-0.506241f,-0.429332f,0.747926f}, +{-0.419192f,-0.322513f,0.848684f},{-0.627779f,-0.532405f,0.567836f},{-0.435647f,-0.30311f,0.847547f}, +{-0.485883f,-0.243875f,0.839311f},{-0.502844f,-0.223875f,0.834882f},{-0.519872f,-0.203796f,0.829578f}, +{-0.536941f,-0.18367f,0.823383f},{-0.554024f,-0.163527f,0.816282f},{-0.571091f,-0.143403f,0.808264f}, +{-0.752979f,-0.348998f,0.557873f},{-0.764881f,-0.334964f,0.550232f},{-0.605061f,-0.103347f,0.789443f}, +{-0.621904f,-0.0834874f,0.778631f},{-0.638609f,-0.0637896f,0.766883f},{-0.655145f,-0.0442908f,0.754203f}, +{-0.671482f,-0.0250283f,0.740598f},{-0.687585f,-0.0060395f,0.726078f},{-0.703426f,0.0126381f,0.710657f}, +{-0.73419f,0.0489141f,0.677179f},{-0.749055f,0.0664415f,0.659168f},{-0.763535f,0.0835161f,0.640343f}, +{-0.777605f,0.100105f,0.620734f},{-0.791236f,0.116178f,0.600374f},{-0.817087f,0.146661f,0.557547f}, +{-0.829264f,0.161019f,0.535159f},{-0.840913f,0.174755f,0.512177f},{-0.852019f,0.187851f,0.488646f}, +{-0.862566f,0.200287f,0.464612f},{-0.8723f,-0.47981f,0.0942108f},{-0.954853f,-0.110961f,0.275577f}, +{-0.870179f,-0.48231f,0.100821f},{-0.881933f,0.223123f,0.415224f},{-0.890732f,0.233499f,0.389967f}, +{-0.898933f,0.243169f,0.3644f},{-0.906532f,0.252128f,0.338573f},{-0.913525f,0.260374f,0.312533f}, +{-0.919913f,0.267907f,0.286331f},{-0.925699f,0.274729f,0.260012f},{-0.935477f,0.286259f,0.207214f}, +{-0.989305f,-0.070338f,0.127782f},{-0.94578f,0.298407f,0.128274f},{-0.951842f,0.305555f,0.0251637f}, +{-0.938627f,0.344933f,7.30221e-017f},{-0.822203f,0.569194f,2.30577e-016f},{-0.627461f,-0.532136f,-0.56844f}, +{-0.63326f,-0.490164f,0.598933f},{-0.66876f,-0.448305f,0.593113f},{-0.680746f,-0.434172f,0.589983f}, +{-0.692779f,-0.419983f,0.586235f},{-0.704841f,-0.40576f,0.581857f},{-0.716913f,-0.391526f,0.576839f}, +{-0.728974f,-0.377304f,0.571173f},{-0.741003f,-0.36312f,0.564853f},{-0.776686f,-0.321045f,0.541931f}, +{-0.804996f,-0.55917f,0.198267f},{-0.809271f,-0.554129f,0.194989f},{-0.788372f,-0.307265f,0.53297f}, +{-0.799916f,-0.293653f,0.523356f},{-0.811296f,-0.280235f,0.513095f},{-0.82249f,-0.267036f,0.502197f}, +{-0.837294f,-0.521086f,0.165552f},{-0.650828f,-0.740956f,-0.165552f},{-0.64719f,-0.745245f,-0.160482f}, +{-0.854735f,-0.229015f,0.465812f},{-0.864968f,-0.216949f,0.452509f},{-0.87491f,-0.205226f,0.438652f}, +{-0.884543f,-0.193867f,0.424264f},{-0.857299f,-0.497498f,0.132416f},{-0.630822f,-0.764545f,-0.132417f}, +{-0.627951f,-0.767931f,-0.126333f},{-0.911416f,-0.16218f,0.378179f},{-0.919648f,-0.152473f,0.361938f}, +{-0.927496f,-0.143219f,0.34531f},{-0.93495f,-0.134431f,0.328326f},{-0.941998f,-0.126119f,0.31102f}, +{-0.948635f,-0.118293f,0.293425f},{-0.960649f,-0.104127f,0.25751f},{-0.966018f,-0.097796f,0.239258f}, +{-0.97096f,-0.0919688f,0.220857f},{-0.975475f,-0.0866457f,0.20234f},{-0.979563f,-0.0818252f,0.183742f}, +{-0.983228f,-0.0775037f,0.165095f},{-0.986473f,-0.0736768f,0.146431f},{-0.993754f,-0.0650924f,0.0906466f}, +{-0.602333f,-0.798137f,-0.0130831f},{-0.996651f,0.0817741f,3.49386e-017f},{-0.370185f,-0.380298f,-0.847547f}, +{-0.752523f,-0.621043f,0.219122f},{-0.769896f,-0.600558f,0.215848f},{-0.718226f,-0.661484f,-0.215848f}, +{-0.713823f,-0.666676f,-0.214476f},{-0.774298f,-0.595367f,0.214476f},{-0.778711f,-0.590164f,0.212875f}, +{-0.783128f,-0.584956f,0.211039f},{-0.78754f,-0.579753f,0.208966f},{-0.791941f,-0.574564f,0.206653f}, +{-0.796323f,-0.569397f,0.2041f},{-0.800677f,-0.564263f,0.201304f},{-0.813495f,-0.549149f,0.191472f}, +{-0.674627f,-0.712894f,-0.191472f},{-0.670463f,-0.717803f,-0.187718f},{-0.817658f,-0.54424f,0.187718f}, +{-0.821754f,-0.539411f,0.183731f},{-0.825773f,-0.534672f,0.179515f},{-0.829707f,-0.530032f,0.175076f}, +{-0.83355f,-0.525501f,0.170419f},{-0.840932f,-0.516797f,0.160482f},{-0.844456f,-0.512642f,0.155219f}, +{-0.84786f,-0.508628f,0.14977f},{-0.851139f,-0.504761f,0.144146f},{-0.854287f,-0.501049f,0.138358f}, +{-0.860171f,-0.494112f,0.126333f},{-0.862897f,-0.490897f,0.120119f},{-0.865476f,-0.487856f,0.113788f}, +{-0.867904f,-0.484993f,0.107351f},{-0.874264f,-0.477494f,0.0875334f},{-0.613858f,-0.784549f,-0.0875334f}, +{-0.61205f,-0.786681f,-0.0808013f},{-0.876072f,-0.475362f,0.0808013f},{-0.877724f,-0.473415f,0.0740269f}, +{-0.879219f,-0.471651f,0.0672227f},{-0.88056f,-0.47007f,0.0604006f},{-0.881747f,-0.46867f,0.0535724f}, +{-0.882783f,-0.467448f,0.0467496f},{-0.88367f,-0.466403f,0.0399431f},{-0.884411f,-0.465529f,0.0331634f}, +{-0.885788f,-0.463905f,0.0130831f},{-0.983879f,-0.178833f,5.93908e-017f},{-0.731303f,-0.646064f,-0.218624f}, +{-0.726972f,-0.651171f,-0.217917f},{-0.735599f,-0.640999f,-0.219122f},{-0.722611f,-0.656314f,-0.216992f}, +{-0.70941f,-0.671879f,-0.212875f},{-0.704994f,-0.677087f,-0.211039f},{-0.700581f,-0.682289f,-0.208966f}, +{-0.491286f,-0.657571f,-0.571173f},{-0.479257f,-0.671755f,-0.564852f},{-0.69618f,-0.687479f,-0.206653f}, +{-0.691799f,-0.692645f,-0.2041f},{-0.687444f,-0.69778f,-0.201305f},{-0.683125f,-0.702872f,-0.198267f}, +{-0.67885f,-0.707913f,-0.194989f},{-0.666368f,-0.722632f,-0.183731f},{-0.39777f,-0.767839f,-0.502197f}, +{-0.386784f,-0.780792f,-0.490674f},{-0.662349f,-0.727371f,-0.179515f},{-0.658414f,-0.73201f,-0.175076f}, +{-0.654571f,-0.736542f,-0.170419f},{-0.643666f,-0.749401f,-0.155219f},{-0.335717f,-0.841008f,-0.424264f}, +{-0.326411f,-0.851981f,-0.409371f},{-0.640261f,-0.753415f,-0.14977f},{-0.636982f,-0.757282f,-0.144146f}, +{-0.633834f,-0.760993f,-0.138358f},{-0.625224f,-0.771146f,-0.120119f},{-0.28531f,-0.900444f,-0.328326f}, +{-0.278262f,-0.908756f,-0.311019f},{-0.622645f,-0.774187f,-0.113788f},{-0.620218f,-0.77705f,-0.107351f}, +{-0.617942f,-0.779732f,-0.100821f},{-0.615822f,-0.782232f,-0.0942108f},{-0.610398f,-0.788628f,-0.0740269f}, +{-0.608902f,-0.790392f,-0.0672227f},{-0.240697f,-0.95305f,-0.183742f},{-0.237032f,-0.957371f,-0.165095f}, +{-0.607562f,-0.791973f,-0.0604006f},{-0.606374f,-0.793373f,-0.0535724f},{-0.605338f,-0.794594f,-0.0467497f}, +{-0.604451f,-0.79564f,-0.0399431f},{-0.603711f,-0.796513f,-0.0331634f},{-0.602143f,-0.798361f,-0.00650573f}, +{-0.762662f,-0.646797f,-1.07812e-032f},{-0.904079f,-0.427366f,5.07106e-017f},{-0.575259f,-0.558555f,-0.597573f}, +{-0.563421f,-0.572514f,-0.595638f},{-0.587f,-0.544711f,-0.598933f},{-0.5515f,-0.58657f,-0.593113f}, +{-0.539514f,-0.600703f,-0.589983f},{-0.527481f,-0.614892f,-0.586235f},{-0.515419f,-0.629115f,-0.581857f}, +{-0.503347f,-0.643349f,-0.576839f},{-0.46728f,-0.685877f,-0.557873f},{-0.183928f,-0.599921f,-0.778631f}, +{-0.455379f,-0.699911f,-0.550232f},{-0.443573f,-0.71383f,-0.541931f},{-0.431888f,-0.727609f,-0.53297f}, +{-0.420344f,-0.741222f,-0.523356f},{-0.408963f,-0.75464f,-0.513095f},{-0.0716416f,-0.732322f,-0.677179f}, +{-0.376029f,-0.793474f,-0.47854f},{-0.365525f,-0.80586f,-0.465812f},{-0.355292f,-0.817926f,-0.452509f}, +{-0.34535f,-0.829649f,-0.438652f},{0.0112556f,-0.830069f,-0.557547f},{-0.317449f,-0.862549f,-0.394f}, +{-0.308844f,-0.872695f,-0.378179f},{-0.300612f,-0.882402f,-0.361938f},{-0.292763f,-0.891656f,-0.34531f}, +{0.0761008f,-0.90653f,-0.415224f},{-0.271625f,-0.916582f,-0.293425f},{-0.265406f,-0.923914f,-0.275577f}, +{-0.259611f,-0.930748f,-0.25751f},{-0.254241f,-0.937079f,-0.239258f},{-0.249299f,-0.942906f,-0.220857f}, +{-0.244785f,-0.948229f,-0.20234f},{-0.233786f,-0.961198f,-0.146431f},{0.133653f,-0.974392f,-0.180824f}, +{-0.230955f,-0.964537f,-0.127782f},{-0.228531f,-0.967395f,-0.109178f},{-0.226506f,-0.969782f,-0.0906466f}, +{-0.224873f,-0.971708f,-0.0722163f},{-0.222742f,-0.974221f,-0.0357604f},{-0.337862f,-0.941196f,-1.55829e-016f}, +{-0.569614f,-0.821913f,-4.03832e-017f},{-0.348737f,-0.295756f,-0.889332f},{-0.353571f,-0.399889f,-0.845622f}, +{-0.336818f,-0.419643f,-0.842884f},{-0.319949f,-0.439533f,-0.839311f},{-0.302988f,-0.459533f,-0.834882f}, +{-0.28596f,-0.479612f,-0.829578f},{-0.26889f,-0.499738f,-0.823383f},{-0.251808f,-0.519881f,-0.816282f}, +{-0.234741f,-0.540006f,-0.808264f},{-0.217718f,-0.560077f,-0.79932f},{-0.20077f,-0.580061f,-0.789443f}, +{0.0813202f,-0.476462f,-0.875426f},{0.295347f,-0.348255f,-0.889657f},{0.100197f,-0.49872f,-0.860952f}, +{-0.167223f,-0.619618f,-0.766883f},{-0.150686f,-0.639117f,-0.754203f},{-0.13435f,-0.65838f,-0.740598f}, +{-0.118247f,-0.677368f,-0.726078f},{-0.102406f,-0.696046f,-0.710657f},{-0.0868611f,-0.714376f,-0.69435f}, +{-0.0567769f,-0.749849f,-0.659168f},{0.207399f,-0.625125f,-0.752465f},{-0.0422963f,-0.766924f,-0.640343f}, +{-0.0282275f,-0.783513f,-0.620733f},{-0.0145961f,-0.799586f,-0.600374f},{-0.00142744f,-0.815114f,-0.579299f}, +{0.29896f,-0.733089f,-0.610904f},{0.51411f,-0.606206f,-0.606799f},{0.312259f,-0.74877f,-0.58467f}, +{0.0234316f,-0.844427f,-0.535159f},{0.0350815f,-0.858163f,-0.512177f},{0.0461876f,-0.871259f,-0.488646f}, +{0.0567343f,-0.883695f,-0.464612f},{0.0667093f,-0.895457f,-0.440122f},{0.0849003f,-0.916907f,-0.389967f}, +{0.378491f,-0.826866f,-0.415977f},{0.0931016f,-0.926577f,-0.3644f},{0.1007f,-0.935536f,-0.338573f}, +{0.107693f,-0.943782f,-0.312533f},{0.114081f,-0.951315f,-0.286331f},{0.119867f,-0.958137f,-0.260012f}, +{0.125053f,-0.964252f,-0.233625f},{0.129645f,-0.969667f,-0.207214f},{0.137083f,-0.978437f,-0.154497f}, +{0.139948f,-0.981815f,-0.128274f},{0.142259f,-0.98454f,-0.102193f},{-0.131403f,-0.225632f,-0.96531f}, +{-0.112279f,-0.248182f,-0.962185f},{-0.0930223f,-0.270888f,-0.958106f},{-0.0736605f,-0.293718f,-0.95305f}, +{-0.054222f,-0.316638f,-0.946995f},{-0.034737f,-0.339614f,-0.939923f},{-0.0152368f,-0.362607f,-0.931817f}, +{0.00424604f,-0.38558f,-0.922665f},{0.0236779f,-0.408493f,-0.912454f},{0.0430246f,-0.431306f,-0.901179f}, +{0.0622506f,-0.453976f,-0.888837f},{0.118846f,-0.520709f,-0.845422f},{0.137229f,-0.542385f,-0.828846f}, +{0.155311f,-0.563707f,-0.811242f},{0.173056f,-0.584631f,-0.792627f},{0.19043f,-0.605117f,-0.773026f}, +{0.392477f,-0.462784f,-0.794854f},{0.223929f,-0.644617f,-0.730976f},{0.239989f,-0.663554f,-0.708591f}, +{0.25555f,-0.681902f,-0.68535f},{0.270582f,-0.699627f,-0.661292f},{0.28506f,-0.716699f,-0.636461f}, +{0.324937f,-0.763719f,-0.557808f},{0.336976f,-0.777915f,-0.530373f},{0.348363f,-0.791341f,-0.502416f}, +{0.359084f,-0.803983f,-0.473994f},{0.369129f,-0.815827f,-0.445162f},{0.575428f,-0.678509f,-0.456627f}, +{0.387165f,-0.837094f,-0.386494f},{0.395148f,-0.846507f,-0.356769f},{0.40244f,-0.855106f,-0.326857f}, +{0.409044f,-0.862893f,-0.296814f},{0.414964f,-0.869874f,-0.266692f},{0.420207f,-0.876056f,-0.236543f}, +{0.424781f,-0.881449f,-0.206418f},{0.428697f,-0.886067f,-0.176364f},{0.431968f,-0.889923f,-0.146429f}, +{0.434606f,-0.893034f,-0.116657f},{0.436627f,-0.895417f,-0.0870897f},{0.438049f,-0.897093f,-0.0577667f}, +{0.0574334f,-0.067722f,-0.99605f},{0.0764992f,-0.090203f,-0.992981f},{0.0954975f,-0.112605f,-0.98904f}, +{0.114412f,-0.134908f,-0.98423f},{0.133227f,-0.157093f,-0.978556f},{0.151924f,-0.179139f,-0.972023f}, +{0.170488f,-0.201028f,-0.964635f},{0.188902f,-0.222741f,-0.956401f},{0.20715f,-0.244258f,-0.947326f}, +{0.225216f,-0.265561f,-0.937419f},{0.243085f,-0.28663f,-0.926689f},{0.260739f,-0.307448f,-0.915145f}, +{0.278165f,-0.327995f,-0.902798f},{0.312269f,-0.368208f,-0.875734f},{0.328917f,-0.387838f,-0.861043f}, +{0.345276f,-0.407127f,-0.845596f},{0.361331f,-0.426059f,-0.829405f},{0.37707f,-0.444617f,-0.812486f}, +{0.407539f,-0.480545f,-0.776523f},{0.422244f,-0.497883f,-0.757511f},{0.436577f,-0.514784f,-0.737833f}, +{0.450527f,-0.531233f,-0.717507f},{0.464082f,-0.547216f,-0.696551f},{0.477229f,-0.562718f,-0.674982f}, +{0.489956f,-0.577726f,-0.652821f},{0.502254f,-0.592226f,-0.630087f},{0.525515f,-0.619654f,-0.582978f}, +{0.536458f,-0.632557f,-0.558645f},{0.546929f,-0.644905f,-0.533822f},{0.556921f,-0.656686f,-0.508529f}, +{0.566423f,-0.667891f,-0.48279f},{0.583927f,-0.688531f,-0.430063f},{0.591914f,-0.697948f,-0.403122f}, +{0.59938f,-0.706752f,-0.375826f},{0.606321f,-0.714935f,-0.3482f},{0.612728f,-0.722491f,-0.320268f}, +{0.618598f,-0.729411f,-0.292055f},{0.623924f,-0.735692f,-0.263585f},{0.628702f,-0.741326f,-0.234884f}, +{0.632928f,-0.746309f,-0.205977f},{0.636597f,-0.750636f,-0.176888f},{0.639708f,-0.754304f,-0.147645f}, +{0.642257f,-0.757309f,-0.118272f},{0.644242f,-0.75965f,-0.0887941f},{0.645661f,-0.761323f,-0.0592391f}, +{0.646513f,-0.762327f,-0.0296323f},{0.632928f,-0.746309f,0.205977f},{0.428697f,-0.886067f,0.176364f}, +{0.424781f,-0.881449f,0.206418f},{0.395148f,-0.846507f,0.356769f},{0.59938f,-0.706752f,0.375826f}, +{0.606321f,-0.714935f,0.3482f},{0.434606f,-0.893034f,0.116657f},{0.436627f,-0.895417f,0.0870897f}, +{0.142259f,-0.98454f,0.102193f},{0.639708f,-0.754304f,0.147645f},{0.642257f,-0.757309f,0.118272f}, +{-0.222222f,-0.974834f,0.0177823f},{-0.337862f,-0.941196f,3.41808e-016f},{-0.602143f,-0.798361f,0.00650572f}, +{-0.223622f,-0.973184f,0.0539127f},{-0.224873f,-0.971708f,0.0722163f},{0.14403f,-0.986628f,0.0762915f}, +{-0.885978f,-0.463681f,-0.00650572f},{-0.983879f,-0.178833f,-4.69192e-016f},{-0.998038f,-0.0600412f,-0.0177823f}, +{-0.602655f,-0.797758f,0.0197241f},{-0.603113f,-0.797218f,0.0264206f},{-0.814352f,0.579659f,-0.0287252f}, +{-0.813513f,0.57867f,-0.0577667f},{-0.951842f,0.305555f,-0.0251636f},{-0.996651f,0.0817739f,-5.50975e-016f}, +{-0.646797f,0.762662f,-9.3359e-016f},{-0.822203f,0.569194f,-3.00566e-016f},{-0.645661f,0.761323f,-0.0592414f}, +{0.431968f,-0.889923f,0.146429f},{0.636597f,-0.750636f,0.176888f},{-0.646513f,0.762327f,-0.0296337f}, +{0.623924f,-0.735692f,0.263585f},{0.420207f,-0.876056f,0.236543f},{0.414964f,-0.869874f,0.266692f}, +{0.628702f,-0.741326f,0.234884f},{0.409044f,-0.862893f,0.296814f},{0.618598f,-0.729411f,0.292055f}, +{0.40244f,-0.855106f,0.326857f},{0.612728f,-0.722491f,0.320268f},{0.387165f,-0.837094f,0.386494f}, +{0.591914f,-0.697948f,0.403122f},{0.369129f,-0.815827f,0.445162f},{0.359084f,-0.803983f,0.473994f}, +{0.566423f,-0.667891f,0.48279f},{0.378491f,-0.826866f,0.415977f},{0.536458f,-0.632557f,0.558645f}, +{0.546929f,-0.644905f,0.533822f},{0.336976f,-0.777915f,0.530373f},{0.556921f,-0.656686f,0.508529f}, +{0.51411f,-0.606206f,0.606799f},{0.312259f,-0.74877f,0.58467f},{0.29896f,-0.733089f,0.610904f}, +{0.324937f,-0.763719f,0.557808f},{0.477229f,-0.562718f,0.674982f},{0.270582f,-0.699627f,0.661292f}, +{0.464082f,-0.547216f,0.696551f},{0.28506f,-0.716699f,0.636461f},{0.422243f,-0.497883f,0.757511f}, +{0.436577f,-0.514784f,0.737833f},{0.223929f,-0.644617f,0.730976f},{0.450527f,-0.531233f,0.717507f}, +{0.239989f,-0.663554f,0.708591f},{0.37707f,-0.444617f,0.812486f},{0.19043f,-0.605117f,0.773026f}, +{0.173056f,-0.584631f,0.792627f},{0.207399f,-0.625125f,0.752465f},{0.137229f,-0.542385f,0.828846f}, +{0.328917f,-0.387838f,0.861043f},{0.345276f,-0.407127f,0.845596f},{0.361331f,-0.426059f,0.829405f}, +{0.278165f,-0.327995f,0.902798f},{0.295347f,-0.348255f,0.889657f},{0.0813203f,-0.476461f,0.875426f}, +{0.118846f,-0.520709f,0.845422f},{0.0622506f,-0.453976f,0.888837f},{0.243085f,-0.28663f,0.926689f}, +{0.260739f,-0.307447f,0.915145f},{0.00424601f,-0.38558f,0.922665f},{0.20715f,-0.244258f,0.947326f}, +{0.023678f,-0.408493f,0.912454f},{0.225216f,-0.265561f,0.937419f},{0.0430246f,-0.431306f,0.901179f}, +{0.170488f,-0.201028f,0.964635f},{-0.0152368f,-0.362607f,0.931817f},{-0.034737f,-0.339614f,0.939923f}, +{0.188902f,-0.222741f,0.956401f},{0.133227f,-0.157093f,0.978556f},{-0.054222f,-0.316638f,0.946995f}, +{-0.0736605f,-0.293718f,0.95305f},{0.151924f,-0.179139f,0.972023f},{0.0954975f,-0.112605f,0.98904f}, +{0.114412f,-0.134908f,0.98423f},{-0.0930223f,-0.270888f,0.958106f},{-0.731303f,-0.646064f,0.218624f}, +{-0.575259f,-0.558555f,0.597573f},{-0.563421f,-0.572514f,0.595638f},{-0.169153f,-0.181119f,0.968805f}, +{0.0383171f,-0.0451812f,0.998244f},{-0.150369f,-0.203268f,0.967508f},{0.019167f,-0.0226006f,0.999561f}, +{-0.131403f,-0.225632f,0.96531f},{-0.112279f,-0.248181f,0.962185f},{-0.353571f,-0.399889f,0.845622f}, +{0.0574335f,-0.0677219f,0.99605f},{0.0764992f,-0.090203f,0.992981f},{-0.28596f,-0.479612f,0.829578f}, +{-0.539514f,-0.600703f,0.589983f},{-0.302988f,-0.459533f,0.834882f},{-0.726972f,-0.651171f,0.217917f}, +{-0.336818f,-0.419643f,0.842884f},{-0.756818f,-0.615978f,-0.218624f},{-0.752523f,-0.621043f,-0.219122f}, +{-0.735599f,-0.640999f,0.219122f},{-0.452261f,-0.283519f,-0.845622f},{-0.435647f,-0.30311f,-0.847547f}, +{-0.645f,-0.47632f,-0.597573f},{-0.506241f,-0.429332f,-0.747926f},{-0.621631f,-0.503876f,-0.599737f}, +{-0.419192f,-0.322513f,-0.848684f},{-0.206312f,-0.137304f,-0.968805f},{-0.355998f,-0.301914f,-0.884372f}, +{-0.182011f,-0.154359f,-0.971105f},{-0.0191661f,0.0225993f,-0.999561f},{-2.93527e-009f,-2.48934e-009f,1.0f}, +{-0.18253f,-0.1548f,0.970938f},{-0.251808f,-0.519881f,0.816282f},{0.155311f,-0.563707f,0.811242f}, +{0.312269f,-0.368208f,0.875734f},{0.100197f,-0.49872f,0.860952f},{-0.118246f,-0.677368f,0.726078f}, +{0.392477f,-0.462784f,0.794854f},{0.407539f,-0.480545f,0.776523f},{0.25555f,-0.681902f,0.68535f}, +{0.489956f,-0.577726f,0.652821f},{-0.0282274f,-0.783513f,0.620733f},{-0.34535f,-0.829649f,0.438652f}, +{-0.355292f,-0.817926f,0.452509f},{0.502254f,-0.592226f,0.630087f},{0.525515f,-0.619654f,0.582978f}, +{0.575428f,-0.678509f,0.456627f},{0.583927f,-0.688531f,0.430063f},{0.348363f,-0.791341f,0.502416f}, +{-0.300612f,-0.882402f,0.361938f},{0.0461875f,-0.871259f,0.488646f},{-0.292763f,-0.891656f,0.34531f}, +{0.114081f,-0.951315f,0.286331f},{0.644242f,-0.75965f,0.0887942f},{-0.762662f,-0.646797f,1.22271e-018f}, +{0.645661f,-0.761323f,0.059239f},{0.438049f,-0.897093f,0.0577667f},{0.14601f,-0.988963f,0.0251636f}, +{-0.0805097f,-0.996754f,5.00783e-016f},{0.646513f,-0.762327f,0.0296322f},{0.438888f,-0.898083f,0.0287252f}, +{0.427652f,-0.903943f,6.47993e-016f},{0.17704f,-0.984204f,6.55067e-016f},{0.646797f,-0.762662f,9.4456e-016f}, +{-0.569614f,-0.821913f,2.60919e-016f},{-0.904079f,-0.427366f,-2.0282e-016f},{0.145275f,-0.988096f,0.0506042f}, +{0.139948f,-0.981815f,0.128274f},{0.137083f,-0.978437f,0.154497f},{0.133653f,-0.974392f,0.180824f}, +{0.129646f,-0.969667f,0.207214f},{0.125053f,-0.964252f,0.233625f},{0.119867f,-0.958137f,0.260012f}, +{-0.249299f,-0.942906f,0.220857f},{-0.254241f,-0.937079f,0.239258f},{0.107693f,-0.943782f,0.312533f}, +{0.1007f,-0.935536f,0.338573f},{0.0931016f,-0.926577f,0.3644f},{0.0849004f,-0.916907f,0.389967f}, +{0.0761008f,-0.906531f,0.415224f},{0.0667093f,-0.895457f,0.440122f},{0.0567345f,-0.883695f,0.464612f}, +{0.0350815f,-0.858163f,0.512177f},{0.0234317f,-0.844426f,0.535159f},{0.0112556f,-0.830069f,0.557547f}, +{-0.00142745f,-0.815114f,0.579299f},{-0.0145962f,-0.799586f,0.600374f},{-0.0422964f,-0.766924f,0.640343f}, +{-0.0567769f,-0.749849f,0.659168f},{-0.0716415f,-0.732322f,0.677179f},{-0.0868612f,-0.714376f,0.69435f}, +{-0.102406f,-0.696046f,0.710657f},{-0.683125f,-0.702872f,0.198267f},{-0.431888f,-0.72761f,0.53297f}, +{-0.67885f,-0.707914f,0.194989f},{-0.13435f,-0.65838f,0.740598f},{-0.150686f,-0.639117f,0.754203f}, +{-0.167223f,-0.619618f,0.766883f},{-0.183928f,-0.599921f,0.778631f},{-0.20077f,-0.580061f,0.789443f}, +{-0.217718f,-0.560078f,0.79932f},{-0.234741f,-0.540005f,0.808264f},{-0.26889f,-0.499738f,0.823383f}, +{-0.527481f,-0.614892f,0.586235f},{-0.319949f,-0.439533f,0.839311f},{-0.370185f,-0.380298f,0.847547f}, +{-0.38664f,-0.360895f,0.848684f},{-0.348737f,-0.295756f,0.889332f},{-0.951107f,0.304688f,-0.0506042f}, +{-0.222742f,-0.974221f,0.0357603f},{-0.226506f,-0.969783f,0.0906467f},{-0.228531f,-0.967395f,0.109178f}, +{-0.230955f,-0.964537f,0.127782f},{-0.233786f,-0.961198f,0.146431f},{-0.237032f,-0.957371f,0.165095f}, +{-0.240697f,-0.95305f,0.183742f},{-0.244785f,-0.948229f,0.20234f},{-0.259611f,-0.930748f,0.25751f}, +{-0.615822f,-0.782232f,0.0942108f},{-0.617942f,-0.779732f,0.100821f},{-0.265406f,-0.923914f,0.275577f}, +{-0.271625f,-0.916582f,0.293425f},{-0.278261f,-0.908756f,0.31102f},{-0.28531f,-0.900444f,0.328326f}, +{-0.636982f,-0.757282f,0.144146f},{-0.851139f,-0.504761f,-0.144146f},{-0.84786f,-0.508627f,-0.14977f}, +{-0.308844f,-0.872695f,0.378179f},{-0.317449f,-0.862549f,0.394f},{-0.326411f,-0.851981f,0.409371f}, +{-0.335717f,-0.841008f,0.424264f},{-0.658414f,-0.73201f,0.175076f},{-0.829707f,-0.530032f,-0.175076f}, +{-0.825773f,-0.534672f,-0.179515f},{-0.365525f,-0.80586f,0.465812f},{-0.376029f,-0.793474f,0.47854f}, +{-0.386784f,-0.780792f,0.490674f},{-0.39777f,-0.767839f,0.502197f},{-0.408963f,-0.75464f,0.513095f}, +{-0.420343f,-0.741222f,0.523356f},{-0.443573f,-0.71383f,0.541931f},{-0.455379f,-0.699911f,0.550232f}, +{-0.46728f,-0.685877f,0.557873f},{-0.479257f,-0.671755f,0.564853f},{-0.491286f,-0.657571f,0.571173f}, +{-0.503347f,-0.643349f,0.576839f},{-0.515418f,-0.629115f,0.581857f},{-0.5515f,-0.58657f,0.593113f}, +{-0.748269f,-0.62606f,-0.219416f},{-0.587f,-0.544711f,0.598933f},{-0.598628f,-0.530999f,0.599736f}, +{-0.504783f,-0.428095f,0.749619f},{-0.603711f,-0.796513f,0.0331634f},{-0.602333f,-0.798137f,0.0130831f}, +{-0.604451f,-0.79564f,0.0399431f},{-0.88367f,-0.466402f,-0.0399431f},{-0.882783f,-0.467448f,-0.0467496f}, +{-0.605338f,-0.794594f,0.0467496f},{-0.606374f,-0.793373f,0.0535724f},{-0.607562f,-0.791973f,0.0604006f}, +{-0.608902f,-0.790392f,0.0672227f},{-0.610398f,-0.788628f,0.0740269f},{-0.61205f,-0.786681f,0.0808012f}, +{-0.613858f,-0.784549f,0.0875334f},{-0.620218f,-0.77705f,0.107351f},{-0.867904f,-0.484993f,-0.107351f}, +{-0.865476f,-0.487856f,-0.113788f},{-0.622646f,-0.774187f,0.113788f},{-0.625224f,-0.771146f,0.120119f}, +{-0.627951f,-0.767931f,0.126333f},{-0.630822f,-0.764545f,0.132417f},{-0.633834f,-0.760993f,0.138358f}, +{-0.640261f,-0.753415f,0.14977f},{-0.643666f,-0.749401f,0.155219f},{-0.64719f,-0.745245f,0.160482f}, +{-0.650827f,-0.740956f,0.165552f},{-0.654571f,-0.736542f,0.170419f},{-0.662349f,-0.727371f,0.179515f}, +{-0.666368f,-0.722632f,0.183731f},{-0.670463f,-0.717803f,0.187718f},{-0.674627f,-0.712894f,0.191472f}, +{-0.687445f,-0.69778f,0.201304f},{-0.800677f,-0.564263f,-0.201304f},{-0.796323f,-0.569397f,-0.2041f}, +{-0.691799f,-0.692645f,0.2041f},{-0.69618f,-0.687479f,0.206653f},{-0.700581f,-0.68229f,0.208966f}, +{-0.704994f,-0.677087f,0.211039f},{-0.70941f,-0.671879f,0.212875f},{-0.713823f,-0.666676f,0.214476f}, +{-0.718226f,-0.661484f,0.215848f},{-0.722611f,-0.656314f,0.216993f},{-0.739853f,-0.635983f,0.219416f}, +{-0.757174f,-0.642143f,-0.119748f},{-0.757056f,-0.642042f,0.121027f},{-0.712963f,-0.604648f,0.355084f}, +{-0.627461f,-0.532136f,0.56844f},{-0.885466f,-0.464285f,-0.0197242f},{-0.885009f,-0.464825f,-0.0264206f}, +{-0.885788f,-0.463905f,-0.013083f},{-0.884411f,-0.465529f,-0.0331634f},{-0.881747f,-0.46867f,-0.0535725f}, +{-0.88056f,-0.47007f,-0.0604006f},{-0.879219f,-0.471651f,-0.0672226f},{-0.979563f,-0.0818251f,-0.183742f}, +{-0.975475f,-0.0866458f,-0.20234f},{-0.877724f,-0.473414f,-0.074027f},{-0.876072f,-0.475362f,-0.0808012f}, +{-0.874264f,-0.477494f,-0.0875334f},{-0.8723f,-0.47981f,-0.0942108f},{-0.870179f,-0.482311f,-0.100821f}, +{-0.862897f,-0.490897f,-0.120119f},{-0.93495f,-0.134431f,-0.328326f},{-0.927496f,-0.143219f,-0.34531f}, +{-0.860171f,-0.494112f,-0.126333f},{-0.857299f,-0.497498f,-0.132416f},{-0.854287f,-0.501049f,-0.138358f}, +{-0.844456f,-0.512642f,-0.155219f},{-0.884543f,-0.193867f,-0.424264f},{-0.87491f,-0.205225f,-0.438652f}, +{-0.840931f,-0.516798f,-0.160482f},{-0.837294f,-0.521086f,-0.165552f},{-0.83355f,-0.525501f,-0.170419f}, +{-0.821754f,-0.539411f,-0.183731f},{-0.82249f,-0.267036f,-0.502197f},{-0.811296f,-0.280235f,-0.513095f}, +{-0.817658f,-0.54424f,-0.187718f},{-0.813495f,-0.549149f,-0.191472f},{-0.809271f,-0.554129f,-0.194989f}, +{-0.804996f,-0.55917f,-0.198267f},{-0.791941f,-0.574564f,-0.206653f},{-0.78754f,-0.579753f,-0.208966f}, +{-0.728974f,-0.377304f,-0.571173f},{-0.716913f,-0.391526f,-0.576839f},{-0.783128f,-0.584956f,-0.211039f}, +{-0.778711f,-0.590164f,-0.212874f},{-0.774298f,-0.595367f,-0.214476f},{-0.769896f,-0.600558f,-0.215847f}, +{-0.765511f,-0.605729f,-0.216993f},{-0.76115f,-0.610871f,-0.217917f},{-0.996638f,-0.061691f,-0.0539127f}, +{-0.995387f,-0.0631666f,-0.0722163f},{-0.997518f,-0.0606535f,-0.0357603f},{-0.993754f,-0.0650924f,-0.0906467f}, +{-0.991729f,-0.0674796f,-0.109178f},{-0.989305f,-0.0703379f,-0.127782f},{-0.986473f,-0.0736768f,-0.146431f}, +{-0.983228f,-0.0775037f,-0.165095f},{-0.97096f,-0.0919687f,-0.220857f},{-0.906532f,0.252128f,-0.338573f}, +{-0.966018f,-0.0977961f,-0.239258f},{-0.960649f,-0.104127f,-0.25751f},{-0.954853f,-0.110961f,-0.275577f}, +{-0.948635f,-0.118294f,-0.293425f},{-0.941998f,-0.126119f,-0.31102f},{-0.840913f,0.174755f,-0.512177f}, +{-0.919648f,-0.152473f,-0.361938f},{-0.911416f,-0.16218f,-0.378179f},{-0.902811f,-0.172326f,-0.394f}, +{-0.893848f,-0.182894f,-0.409371f},{-0.763536f,0.0835161f,-0.640343f},{-0.864968f,-0.216949f,-0.452509f}, +{-0.854735f,-0.229015f,-0.465812f},{-0.844231f,-0.241401f,-0.47854f},{-0.833475f,-0.254083f,-0.490674f}, +{-0.671482f,-0.0250282f,-0.740598f},{-0.799916f,-0.293653f,-0.523356f},{-0.788372f,-0.307266f,-0.53297f}, +{-0.776686f,-0.321045f,-0.541931f},{-0.764881f,-0.334964f,-0.550232f},{-0.752979f,-0.348998f,-0.557873f}, +{-0.741003f,-0.36312f,-0.564853f},{-0.704841f,-0.40576f,-0.581857f},{-0.519872f,-0.203796f,-0.829578f}, +{-0.692779f,-0.419983f,-0.586235f},{-0.680746f,-0.434172f,-0.589983f},{-0.66876f,-0.448305f,-0.593113f}, +{-0.656839f,-0.462361f,-0.595638f},{-0.63326f,-0.490164f,-0.598933f},{-0.71354f,-0.605138f,-0.353084f}, +{-0.938627f,0.344933f,-6.77795e-016f},{-0.949862f,0.30322f,-0.0762915f},{-0.948091f,0.301132f,-0.102193f}, +{-0.94578f,0.298407f,-0.128274f},{-0.942915f,0.295029f,-0.154497f},{-0.939484f,0.290984f,-0.180824f}, +{-0.935477f,0.286259f,-0.207214f},{-0.930885f,0.280844f,-0.233625f},{-0.925699f,0.274728f,-0.260012f}, +{-0.919913f,0.267907f,-0.286331f},{-0.913525f,0.260374f,-0.312533f},{-0.753955f,0.508443f,-0.415977f}, +{-0.575427f,0.678508f,-0.45663f},{-0.744593f,0.497404f,-0.445162f},{-0.898933f,0.243169f,-0.3644f}, +{-0.890732f,0.233499f,-0.389967f},{-0.881933f,0.223123f,-0.415224f},{-0.872541f,0.212048f,-0.440122f}, +{-0.862566f,0.200287f,-0.464612f},{-0.852019f,0.187851f,-0.488646f},{-0.829264f,0.161019f,-0.535159f}, +{-0.674425f,0.414665f,-0.610904f},{-0.817087f,0.146661f,-0.557547f},{-0.804404f,0.131706f,-0.579299f}, +{-0.791236f,0.116178f,-0.600374f},{-0.777605f,0.100105f,-0.620733f},{-0.582863f,0.306702f,-0.752465f}, +{-0.392475f,0.462782f,-0.794856f},{-0.565895f,0.286694f,-0.773026f},{-0.749055f,0.0664413f,-0.659168f}, +{-0.73419f,0.0489142f,-0.677179f},{-0.718971f,0.0309681f,-0.69435f},{-0.703426f,0.012638f,-0.710657f}, +{-0.687585f,-0.00603948f,-0.726078f},{-0.655146f,-0.0442909f,-0.754203f},{-0.456785f,0.158039f,-0.875426f}, +{-0.638609f,-0.0637896f,-0.766883f},{-0.621904f,-0.0834874f,-0.778631f},{-0.605061f,-0.103347f,-0.789443f}, +{-0.588114f,-0.123331f,-0.79932f},{-0.571091f,-0.143402f,-0.808264f},{-0.554024f,-0.163527f,-0.816282f}, +{-0.536942f,-0.18367f,-0.823383f},{-0.502844f,-0.223875f,-0.834882f},{-0.485883f,-0.243875f,-0.839311f}, +{-0.469014f,-0.263765f,-0.842884f},{-0.627779f,-0.532405f,-0.567836f},{-0.812092f,0.576994f,-0.0870897f}, +{-0.81007f,0.57461f,-0.116657f},{-0.807432f,0.5715f,-0.146429f},{-0.804162f,0.567644f,-0.176364f}, +{-0.800246f,0.563026f,-0.206418f},{-0.795672f,0.557633f,-0.236543f},{-0.790429f,0.551451f,-0.266692f}, +{-0.784509f,0.54447f,-0.296814f},{-0.777905f,0.536683f,-0.326857f},{-0.770612f,0.528084f,-0.356769f}, +{-0.762629f,0.518671f,-0.386494f},{-0.734548f,0.48556f,-0.473994f},{-0.723827f,0.472918f,-0.502416f}, +{-0.712441f,0.459492f,-0.530373f},{-0.700401f,0.445295f,-0.557808f},{-0.687723f,0.430346f,-0.58467f}, +{-0.514109f,0.606205f,-0.606801f},{-0.660525f,0.398276f,-0.636461f},{-0.646047f,0.381204f,-0.661292f}, +{-0.631014f,0.363479f,-0.68535f},{-0.615454f,0.345131f,-0.708591f},{-0.599393f,0.326194f,-0.730976f}, +{-0.548521f,0.266208f,-0.792627f},{-0.530776f,0.245284f,-0.811242f},{-0.512694f,0.223962f,-0.828846f}, +{-0.49431f,0.202286f,-0.845422f},{-0.475662f,0.180297f,-0.860952f},{-0.295345f,0.348252f,-0.889658f}, +{-0.437715f,0.135553f,-0.888837f},{-0.418489f,0.112883f,-0.901179f},{-0.399143f,0.0900703f,-0.912454f}, +{-0.379711f,0.0671571f,-0.922664f},{-0.360228f,0.0441843f,-0.931817f},{-0.340728f,0.0211909f,-0.939923f}, +{-0.321243f,-0.00178467f,-0.946995f},{-0.301804f,-0.0247052f,-0.95305f},{-0.282442f,-0.0475355f,-0.958106f}, +{-0.263186f,-0.0702415f,-0.962185f},{-0.244062f,-0.0927915f,-0.96531f},{-0.225096f,-0.115155f,-0.967508f}, +{-0.644242f,0.75965f,-0.0887968f},{-0.642257f,0.757309f,-0.118274f},{-0.639708f,0.754304f,-0.147647f}, +{-0.636597f,0.750636f,-0.176891f},{-0.632927f,0.746308f,-0.205979f},{-0.628701f,0.741325f,-0.234887f}, +{-0.623923f,0.735691f,-0.263588f},{-0.618597f,0.729411f,-0.292057f},{-0.612728f,0.72249f,-0.320271f}, +{-0.60632f,0.714934f,-0.348202f},{-0.59938f,0.706751f,-0.375828f},{-0.591913f,0.697947f,-0.403124f}, +{-0.583927f,0.68853f,-0.430066f},{-0.566422f,0.66789f,-0.482793f},{-0.55692f,0.656685f,-0.508532f}, +{-0.546929f,0.644904f,-0.533824f},{-0.536457f,0.632556f,-0.558647f},{-0.525514f,0.619653f,-0.58298f}, +{-0.502253f,0.592225f,-0.630088f},{-0.489956f,0.577725f,-0.652822f},{-0.477228f,0.562717f,-0.674983f}, +{-0.464081f,0.547216f,-0.696551f},{-0.450527f,0.531233f,-0.717508f},{-0.436576f,0.514783f,-0.737834f}, +{-0.422243f,0.497882f,-0.757512f},{-0.407538f,0.480543f,-0.776525f},{-0.377068f,0.444615f,-0.812488f}, +{-0.36133f,0.426058f,-0.829407f},{-0.345274f,0.407126f,-0.845597f},{-0.328915f,0.387836f,-0.861045f}, +{-0.312267f,0.368206f,-0.875736f},{-0.278164f,0.327993f,-0.902799f},{-0.260738f,0.307446f,-0.915146f}, +{-0.243083f,0.286628f,-0.92669f},{-0.225214f,0.265559f,-0.93742f},{-0.207148f,0.244256f,-0.947327f}, +{-0.1889f,0.222739f,-0.956402f},{-0.170486f,0.201027f,-0.964636f},{-0.151922f,0.179137f,-0.972023f}, +{-0.133225f,0.157091f,-0.978557f},{-0.114411f,0.134906f,-0.984231f},{-0.0954964f,0.112603f,-0.98904f}, +{-0.0764977f,0.0902013f,-0.992981f},{-0.0574318f,0.0677199f,-0.99605f},{-0.0383156f,0.0451794f,-0.998244f}, +{-0.336976f,0.777915f,-0.530373f},{-0.324937f,0.763719f,-0.557808f},{-0.536458f,0.632557f,-0.558645f}, +{-0.546929f,0.644905f,-0.533822f},{0.633834f,0.760993f,-0.138358f},{0.317449f,0.862549f,-0.394f}, +{0.308844f,0.872695f,-0.378179f},{-0.359084f,0.803983f,-0.473994f},{-0.556921f,0.656686f,-0.508529f}, +{-0.566423f,0.667891f,-0.48279f},{-0.348363f,0.791341f,-0.502416f},{-0.575428f,0.678509f,-0.456627f}, +{-0.583927f,0.688531f,-0.430063f},{-0.378491f,0.826866f,-0.415977f},{-0.369129f,0.815827f,-0.445162f}, +{-0.591914f,0.697948f,-0.403122f},{-0.387165f,0.837094f,-0.386494f},{-0.395148f,0.846507f,-0.356769f}, +{-0.59938f,0.706752f,-0.375826f},{-0.606321f,0.714935f,-0.3482f},{-0.40244f,0.855106f,-0.326857f}, +{0.259611f,0.930748f,-0.25751f},{-0.0931016f,0.926577f,-0.3644f},{0.254241f,0.937079f,-0.239258f}, +{-0.409044f,0.862893f,-0.296814f},{-0.612728f,0.722491f,-0.320268f},{-0.618598f,0.729411f,-0.292055f}, +{-0.414964f,0.869874f,-0.266692f},{-0.623924f,0.735692f,-0.263585f},{-0.420207f,0.876056f,-0.236543f}, +{-0.424781f,0.881449f,-0.206418f},{-0.632928f,0.746309f,-0.205977f},{-0.428697f,0.886067f,-0.176364f}, +{-0.628702f,0.741326f,-0.234884f},{-0.636597f,0.750636f,-0.176888f},{-0.431968f,0.889923f,-0.146429f}, +{-0.639708f,0.754304f,-0.147645f},{-0.434606f,0.893034f,-0.116657f},{-0.642257f,0.757309f,-0.118272f}, +{-0.436627f,0.895417f,-0.0870897f},{-0.14403f,0.986628f,-0.0762915f},{-0.142259f,0.98454f,-0.102193f}, +{0.646513f,-0.762327f,0.0296337f},{0.814352f,-0.57966f,0.0287252f},{0.951842f,-0.305555f,0.0251636f}, +{0.998038f,0.0600412f,0.0177823f},{0.996651f,-0.0817739f,4.44435e-016f},{0.822203f,-0.569194f,3.04136e-016f}, +{0.813513f,-0.57867f,0.0577667f},{0.812092f,-0.576994f,0.0870897f},{0.949862f,-0.30322f,0.0762915f}, +{-0.644242f,0.75965f,-0.0887942f},{0.223622f,0.973184f,-0.0539127f},{0.224873f,0.971708f,-0.0722163f}, +{0.603113f,0.797218f,-0.0264206f},{0.226506f,0.969783f,-0.0906467f},{0.602655f,0.797758f,-0.0197242f}, +{-0.645661f,0.761323f,-0.059239f},{-0.438049f,0.897093f,-0.0577667f},{0.0805097f,0.996754f,-4.48371e-016f}, +{0.222222f,0.974834f,-0.0177823f},{-0.14601f,0.988963f,-0.0251636f},{0.337862f,0.941196f,-4.29587e-016f}, +{0.602143f,0.798361f,-0.00650572f},{0.569614f,0.821913f,-3.05233e-016f},{-0.17704f,0.984204f,-6.14496e-016f}, +{-0.438888f,0.898083f,-0.0287252f},{-0.427652f,0.903943f,-9.46059e-016f},{-0.646513f,0.762327f,-0.0296322f}, +{0.885978f,0.463681f,0.00650572f},{0.983879f,0.178833f,5.48296e-016f},{-0.525515f,0.619654f,-0.582978f}, +{-0.51411f,0.606206f,-0.606799f},{-0.312259f,0.74877f,-0.58467f},{-0.29896f,0.733089f,-0.610904f}, +{-0.502254f,0.592226f,-0.630087f},{-0.489956f,0.577726f,-0.652821f},{-0.28506f,0.716699f,-0.636461f}, +{-0.270582f,0.699627f,-0.661292f},{-0.477229f,0.562718f,-0.674982f},{-0.464082f,0.547216f,-0.696551f}, +{-0.25555f,0.681902f,-0.68535f},{-0.450527f,0.531233f,-0.717507f},{-0.239989f,0.663554f,-0.708591f}, +{0.0567769f,0.749849f,-0.659168f},{0.355292f,0.817926f,-0.452509f},{0.365525f,0.80586f,-0.465812f}, +{-0.223929f,0.644617f,-0.730976f},{-0.436577f,0.514784f,-0.737833f},{-0.207399f,0.625125f,-0.752465f}, +{-0.422244f,0.497883f,-0.757511f},{-0.392477f,0.462784f,-0.794854f},{-0.407539f,0.480545f,-0.776523f}, +{-0.19043f,0.605117f,-0.773026f},{-0.37707f,0.444617f,-0.812486f},{-0.173056f,0.584631f,-0.792627f}, +{-0.361331f,0.426059f,-0.829405f},{-0.345276f,0.407127f,-0.845596f},{-0.155311f,0.563707f,-0.811242f}, +{-0.137229f,0.542385f,-0.828846f},{-0.328917f,0.387838f,-0.861043f},{-0.118846f,0.520709f,-0.845422f}, +{0.443573f,0.71383f,-0.541931f},{0.683126f,0.702872f,-0.198267f},{0.455379f,0.699911f,-0.550232f}, +{-0.312269f,0.368208f,-0.875734f},{-0.100197f,0.49872f,-0.860952f},{-0.0813203f,0.476461f,-0.875426f}, +{-0.295347f,0.348255f,-0.889657f},{-0.278165f,0.327995f,-0.902798f},{-0.260739f,0.307447f,-0.915145f}, +{-0.243085f,0.28663f,-0.926689f},{-0.0622506f,0.453976f,-0.888837f},{-0.0430246f,0.431306f,-0.901179f}, +{-0.225216f,0.265561f,-0.937419f},{-0.023678f,0.408493f,-0.912454f},{-0.20715f,0.244258f,-0.947326f}, +{-0.188902f,0.222741f,-0.956401f},{-0.00424602f,0.38558f,-0.922665f},{0.0152368f,0.362607f,-0.931817f}, +{-0.170488f,0.201028f,-0.964635f},{0.034737f,0.339614f,-0.939923f},{0.28596f,0.479612f,-0.829578f}, +{0.054222f,0.316638f,-0.946995f},{0.26889f,0.499738f,-0.823383f},{-0.151924f,0.179139f,-0.972023f}, +{0.0736605f,0.293718f,-0.95305f},{-0.133227f,0.157093f,-0.978556f},{0.112279f,0.248181f,-0.962185f}, +{0.319949f,0.439533f,-0.839311f},{0.336818f,0.419643f,-0.842884f},{-0.114412f,0.134908f,-0.98423f}, +{0.731303f,0.646064f,-0.218624f},{0.756818f,0.615978f,0.218624f},{0.735599f,0.640999f,-0.219122f}, +{0.718226f,0.661484f,-0.215848f},{0.722611f,0.656314f,-0.216993f},{0.5515f,0.58657f,-0.593113f}, +{0.452261f,0.283519f,0.845622f},{0.645f,0.47632f,0.597573f},{0.469014f,0.263765f,0.842884f}, +{0.419192f,0.322513f,0.848684f},{0.506241f,0.429332f,0.747926f},{0.621631f,0.503876f,0.599737f}, +{0.587f,0.544711f,-0.598933f},{0.575259f,0.558555f,-0.597573f},{0.355998f,0.301914f,0.884372f}, +{0.206312f,0.137304f,0.968805f},{0.182011f,0.154359f,0.971105f},{0.563421f,0.572514f,-0.595638f}, +{0.726972f,0.651171f,-0.217916f},{0.370185f,0.380298f,-0.847547f},{0.353571f,0.399889f,-0.845622f}, +{0.0191661f,-0.0225994f,0.999561f},{0.0930223f,0.270888f,-0.958106f},{-0.0954975f,0.112605f,-0.98904f}, +{-0.0764992f,0.090203f,-0.992981f},{0.131403f,0.225632f,-0.96531f},{0.150369f,0.203268f,-0.967508f}, +{-0.0574334f,0.0677219f,-0.99605f},{0.169153f,0.181119f,-0.968805f},{-0.019167f,0.0226006f,-0.999561f}, +{-0.0383172f,0.0451812f,-0.998244f},{0.18253f,0.1548f,-0.970938f},{0.904079f,0.427366f,1.81967e-016f}, +{-0.145275f,0.988096f,-0.0506042f},{-0.139948f,0.981815f,-0.128274f},{-0.137083f,0.978437f,-0.154497f}, +{-0.133653f,0.974392f,-0.180824f},{-0.129646f,0.969667f,-0.207214f},{-0.125053f,0.964252f,-0.233625f}, +{-0.119867f,0.958137f,-0.260012f},{-0.114081f,0.951315f,-0.286331f},{-0.107693f,0.943782f,-0.312533f}, +{-0.1007f,0.935536f,-0.338573f},{-0.0849004f,0.916907f,-0.389967f},{-0.0761008f,0.906531f,-0.415224f}, +{-0.0667092f,0.895457f,-0.440122f},{-0.0567345f,0.883695f,-0.464612f},{-0.0461876f,0.871259f,-0.488646f}, +{-0.0350814f,0.858163f,-0.512177f},{-0.0234317f,0.844426f,-0.535159f},{-0.0112556f,0.830069f,-0.557547f}, +{0.00142745f,0.815114f,-0.579299f},{0.0145961f,0.799586f,-0.600374f},{0.0282274f,0.783513f,-0.620733f}, +{0.0422964f,0.766924f,-0.640343f},{0.0716415f,0.732322f,-0.677179f},{0.0868611f,0.714376f,-0.69435f}, +{0.102406f,0.696046f,-0.710657f},{0.118246f,0.677368f,-0.726078f},{0.13435f,0.65838f,-0.740598f}, +{0.150686f,0.639117f,-0.754203f},{0.167223f,0.619618f,-0.766883f},{0.183928f,0.599921f,-0.778631f}, +{0.20077f,0.580061f,-0.789443f},{0.217718f,0.560078f,-0.79932f},{0.234741f,0.540005f,-0.808264f}, +{0.251808f,0.519881f,-0.816282f},{0.302988f,0.459533f,-0.834882f},{0.539514f,0.600703f,-0.589983f}, +{0.38664f,0.360895f,-0.848684f},{0.348737f,0.295756f,-0.889332f},{0.645661f,-0.761323f,0.0592414f}, +{0.222742f,0.974221f,-0.0357603f},{0.228531f,0.967395f,-0.109178f},{0.230955f,0.964537f,-0.127782f}, +{0.233786f,0.961198f,-0.146431f},{0.237032f,0.957371f,-0.165095f},{0.240697f,0.95305f,-0.183742f}, +{0.244785f,0.948229f,-0.20234f},{0.249299f,0.942906f,-0.220857f},{0.271625f,0.916582f,-0.293425f}, +{0.265406f,0.923914f,-0.275577f},{0.617942f,0.779732f,-0.100821f},{0.278261f,0.908756f,-0.31102f}, +{0.28531f,0.900444f,-0.328326f},{0.292763f,0.891656f,-0.34531f},{0.300612f,0.882402f,-0.361938f}, +{0.326411f,0.851981f,-0.409371f},{0.335717f,0.841008f,-0.424264f},{0.34535f,0.829649f,-0.438652f}, +{0.662349f,0.727371f,-0.179515f},{0.825773f,0.534672f,0.179515f},{0.666368f,0.722632f,-0.183731f}, +{0.376029f,0.793474f,-0.47854f},{0.386784f,0.780792f,-0.490674f},{0.39777f,0.767839f,-0.502197f}, +{0.408963f,0.75464f,-0.513095f},{0.420343f,0.741222f,-0.523356f},{0.431888f,0.72761f,-0.53297f}, +{0.46728f,0.685877f,-0.557873f},{0.479257f,0.671755f,-0.564853f},{0.491286f,0.657571f,-0.571173f}, +{0.503347f,0.643349f,-0.576839f},{0.515419f,0.629115f,-0.581857f},{0.527481f,0.614892f,-0.586235f}, +{0.757056f,0.642042f,-0.121027f},{0.739853f,0.635983f,-0.219416f},{0.748269f,0.62606f,0.219416f}, +{0.598628f,0.530999f,-0.599736f},{0.504783f,0.428095f,-0.749619f},{0.762662f,0.646797f,1.22271e-018f}, +{0.602333f,0.798137f,-0.013083f},{0.603711f,0.796513f,-0.0331634f},{0.604451f,0.79564f,-0.0399431f}, +{0.881747f,0.46867f,0.0535724f},{0.607562f,0.791973f,-0.0604006f},{0.606374f,0.793373f,-0.0535725f}, +{0.605338f,0.794594f,-0.0467496f},{0.608902f,0.790392f,-0.0672227f},{0.610398f,0.788628f,-0.0740269f}, +{0.61205f,0.786681f,-0.0808013f},{0.613858f,0.784549f,-0.0875334f},{0.615822f,0.782232f,-0.0942108f}, +{0.865476f,0.487856f,0.113788f},{0.625224f,0.771146f,-0.120119f},{0.622646f,0.774187f,-0.113788f}, +{0.620218f,0.77705f,-0.107351f},{0.627951f,0.767931f,-0.126333f},{0.630822f,0.764545f,-0.132417f}, +{0.84786f,0.508627f,0.14977f},{0.643666f,0.749401f,-0.155219f},{0.640261f,0.753415f,-0.14977f}, +{0.636982f,0.757282f,-0.144146f},{0.64719f,0.745245f,-0.160482f},{0.650827f,0.740956f,-0.165552f}, +{0.654571f,0.736542f,-0.170419f},{0.658414f,0.73201f,-0.175076f},{0.670463f,0.717803f,-0.187718f}, +{0.674627f,0.712894f,-0.191472f},{0.67885f,0.707914f,-0.194989f},{0.796323f,0.569397f,0.2041f}, +{0.69618f,0.687479f,-0.206653f},{0.691799f,0.692645f,-0.2041f},{0.687445f,0.69778f,-0.201304f}, +{0.700581f,0.682289f,-0.208966f},{0.704994f,0.677087f,-0.211039f},{0.70941f,0.671879f,-0.212874f}, +{0.713823f,0.666676f,-0.214476f},{0.63326f,0.490164f,0.598933f},{0.76115f,0.610871f,0.217917f}, +{0.712963f,0.604648f,-0.355084f},{0.627461f,0.532136f,-0.56844f},{0.885466f,0.464285f,0.0197241f}, +{0.885788f,0.463905f,0.0130831f},{0.885009f,0.464825f,0.0264206f},{0.884411f,0.465529f,0.0331634f}, +{0.88367f,0.466402f,0.0399431f},{0.882783f,0.467448f,0.0467496f},{0.88056f,0.47007f,0.0604006f}, +{0.876072f,0.475362f,0.0808012f},{0.877724f,0.473414f,0.074027f},{0.975475f,0.0866458f,0.20234f}, +{0.879219f,0.471651f,0.0672226f},{0.874264f,0.477494f,0.0875334f},{0.8723f,0.47981f,0.0942108f}, +{0.870179f,0.482311f,0.100821f},{0.867904f,0.484993f,0.107351f},{0.840913f,-0.174755f,0.512177f}, +{0.919648f,0.152473f,0.361938f},{0.852019f,-0.187851f,0.488646f},{0.862897f,0.490897f,0.120119f}, +{0.860171f,0.494112f,0.126333f},{0.857299f,0.497498f,0.132416f},{0.854287f,0.501049f,0.138358f}, +{0.851139f,0.504761f,0.144146f},{0.763536f,-0.0835161f,0.640343f},{0.864968f,0.216949f,0.452509f}, +{0.777605f,-0.100105f,0.620733f},{0.844456f,0.512642f,0.155219f},{0.840931f,0.516798f,0.160482f}, +{0.837294f,0.521086f,0.165552f},{0.83355f,0.525501f,0.170419f},{0.829707f,0.530032f,0.175076f}, +{0.813495f,0.549149f,0.191472f},{0.817658f,0.54424f,0.187718f},{0.811296f,0.280235f,0.513095f}, +{0.821754f,0.539411f,0.183731f},{0.809271f,0.554129f,0.194989f},{0.804996f,0.55917f,0.198267f}, +{0.800677f,0.564263f,0.201304f},{0.791941f,0.574564f,0.206653f},{0.778711f,0.590164f,0.212874f}, +{0.783128f,0.584956f,0.211039f},{0.716913f,0.391526f,0.576839f},{0.78754f,0.579753f,0.208966f}, +{0.774298f,0.595367f,0.214476f},{0.769896f,0.600558f,0.215847f},{0.765511f,0.605729f,0.216993f}, +{0.656839f,0.462361f,0.595638f},{0.752523f,0.621043f,0.219122f},{0.996638f,0.061691f,0.0539127f}, +{0.997518f,0.0606535f,0.0357603f},{0.995387f,0.0631668f,0.0722163f},{0.993754f,0.0650926f,0.0906467f}, +{0.991729f,0.0674794f,0.109178f},{0.989305f,0.0703379f,0.127782f},{0.986473f,0.073677f,0.146431f}, +{0.983228f,0.0775037f,0.165095f},{0.979563f,0.0818251f,0.183742f},{0.913525f,-0.260374f,0.312533f}, +{0.906532f,-0.252128f,0.338573f},{0.966018f,0.0977959f,0.239258f},{0.97096f,0.0919687f,0.220857f}, +{0.960649f,0.104127f,0.257509f},{0.954853f,0.110961f,0.275577f},{0.948635f,0.118293f,0.293425f}, +{0.941998f,0.126119f,0.31102f},{0.93495f,0.134431f,0.328326f},{0.927496f,0.143219f,0.34531f}, +{0.911416f,0.16218f,0.378179f},{0.902811f,0.172326f,0.394f},{0.893848f,0.182894f,0.409371f}, +{0.884543f,0.193867f,0.424264f},{0.87491f,0.205226f,0.438652f},{0.854735f,0.229015f,0.465812f}, +{0.844231f,0.241401f,0.47854f},{0.833475f,0.254083f,0.490674f},{0.82249f,0.267036f,0.502197f}, +{0.671482f,0.0250282f,0.740598f},{0.655145f,0.0442907f,0.754203f},{0.788372f,0.307265f,0.53297f}, +{0.799916f,0.293653f,0.523356f},{0.776686f,0.321045f,0.541931f},{0.764881f,0.334965f,0.550232f}, +{0.752979f,0.348998f,0.557873f},{0.741003f,0.36312f,0.564853f},{0.728974f,0.377304f,0.571173f}, +{0.704841f,0.40576f,0.581857f},{0.519872f,0.203796f,0.829578f},{0.502844f,0.223875f,0.834882f}, +{0.680746f,0.434172f,0.589983f},{0.692779f,0.419983f,0.586235f},{0.66876f,0.448305f,0.593113f}, +{0.71354f,0.605138f,0.353084f},{0.757174f,0.642143f,0.119748f},{0.938627f,-0.344933f,5.47231e-016f}, +{0.951107f,-0.304688f,0.0506042f},{0.948091f,-0.301132f,0.102193f},{0.94578f,-0.298407f,0.128274f}, +{0.81007f,-0.574611f,0.116657f},{0.942915f,-0.295029f,0.154497f},{0.939484f,-0.290984f,0.180824f}, +{0.935477f,-0.286259f,0.207214f},{0.930885f,-0.280844f,0.233625f},{0.925699f,-0.274728f,0.260012f}, +{0.919913f,-0.267907f,0.286331f},{0.575427f,-0.678508f,0.45663f},{0.744593f,-0.497404f,0.445162f}, +{0.753955f,-0.508443f,0.415977f},{0.898933f,-0.243169f,0.3644f},{0.890732f,-0.233499f,0.389967f}, +{0.881933f,-0.223123f,0.415224f},{0.872541f,-0.212048f,0.440122f},{0.862566f,-0.200287f,0.464612f}, +{0.674425f,-0.414666f,0.610904f},{0.829264f,-0.161019f,0.535159f},{0.687723f,-0.430346f,0.58467f}, +{0.817087f,-0.146661f,0.557547f},{0.804404f,-0.131706f,0.579299f},{0.791236f,-0.116178f,0.600374f}, +{0.582863f,-0.306702f,0.752465f},{0.392475f,-0.462782f,0.794856f},{0.565895f,-0.286694f,0.773026f}, +{0.749055f,-0.0664413f,0.659168f},{0.73419f,-0.0489142f,0.677179f},{0.718971f,-0.0309681f,0.69435f}, +{0.703426f,-0.012638f,0.710657f},{0.687585f,0.00603948f,0.726078f},{0.456785f,-0.158038f,0.875426f}, +{0.638609f,0.0637897f,0.766883f},{0.475662f,-0.180297f,0.860952f},{0.621904f,0.0834874f,0.778631f}, +{0.605061f,0.103347f,0.789443f},{0.588114f,0.123331f,0.79932f},{0.571091f,0.143402f,0.808264f}, +{0.554024f,0.163527f,0.816282f},{0.536942f,0.18367f,0.823383f},{0.485883f,0.243875f,0.839311f}, +{0.225096f,0.115155f,0.967508f},{0.244062f,0.0927915f,0.96531f},{0.435647f,0.30311f,0.847547f}, +{0.627779f,0.532405f,0.567837f},{0.807432f,-0.5715f,0.146429f},{0.804162f,-0.567644f,0.176364f}, +{0.800246f,-0.563026f,0.206418f},{0.795672f,-0.557633f,0.236543f},{0.790429f,-0.55145f,0.266692f}, +{0.784509f,-0.54447f,0.296814f},{0.777905f,-0.536683f,0.326857f},{0.770612f,-0.528084f,0.356769f}, +{0.762629f,-0.518671f,0.386494f},{0.734548f,-0.48556f,0.473994f},{0.723827f,-0.472918f,0.502416f}, +{0.712441f,-0.459492f,0.530373f},{0.700401f,-0.445295f,0.557808f},{0.514109f,-0.606205f,0.606801f}, +{0.660525f,-0.398276f,0.636461f},{0.646047f,-0.381204f,0.661292f},{0.631014f,-0.363479f,0.68535f}, +{0.615454f,-0.345131f,0.708591f},{0.599393f,-0.326193f,0.730976f},{0.548521f,-0.266208f,0.792627f}, +{0.530776f,-0.245284f,0.811242f},{0.512693f,-0.223962f,0.828846f},{0.49431f,-0.202286f,0.845422f}, +{0.295345f,-0.348252f,0.889658f},{0.437715f,-0.135553f,0.888837f},{0.418489f,-0.112882f,0.901179f}, +{0.399143f,-0.0900703f,0.912454f},{0.379711f,-0.0671572f,0.922665f},{0.360228f,-0.0441842f,0.931817f}, +{0.340728f,-0.0211909f,0.939923f},{0.321243f,0.00178458f,0.946995f},{0.301804f,0.0247052f,0.95305f}, +{0.282442f,0.0475356f,0.958106f},{0.263186f,0.0702416f,0.962185f},{0.644242f,-0.75965f,0.0887968f}, +{0.642257f,-0.757309f,0.118274f},{0.639708f,-0.754304f,0.147647f},{0.636597f,-0.750636f,0.176891f}, +{0.632927f,-0.746308f,0.205979f},{0.628701f,-0.741325f,0.234887f},{0.623923f,-0.735691f,0.263588f}, +{0.618597f,-0.729411f,0.292057f},{0.612728f,-0.72249f,0.320271f},{0.60632f,-0.714934f,0.348202f}, +{0.59938f,-0.706751f,0.375828f},{0.591913f,-0.697947f,0.403124f},{0.583927f,-0.68853f,0.430066f}, +{0.566422f,-0.66789f,0.482793f},{0.55692f,-0.656685f,0.508532f},{0.546929f,-0.644904f,0.533824f}, +{0.536457f,-0.632556f,0.558647f},{0.525514f,-0.619653f,0.58298f},{0.502253f,-0.592225f,0.630088f}, +{0.489956f,-0.577725f,0.652822f},{0.477228f,-0.562717f,0.674983f},{0.464081f,-0.547216f,0.696551f}, +{0.450527f,-0.531233f,0.717508f},{0.436576f,-0.514784f,0.737834f},{0.422243f,-0.497882f,0.757512f}, +{0.407538f,-0.480543f,0.776525f},{0.377068f,-0.444615f,0.812488f},{0.36133f,-0.426058f,0.829407f}, +{0.345274f,-0.407126f,0.845597f},{0.328915f,-0.387836f,0.861045f},{0.312267f,-0.368206f,0.875736f}, +{0.278164f,-0.327993f,0.902799f},{0.260738f,-0.307446f,0.915146f},{0.243083f,-0.286628f,0.92669f}, +{0.225214f,-0.265559f,0.93742f},{0.207148f,-0.244256f,0.947327f},{0.1889f,-0.222739f,0.956402f}, +{0.170486f,-0.201027f,0.964636f},{0.151922f,-0.179137f,0.972023f},{0.133225f,-0.157091f,0.978557f}, +{0.114411f,-0.134906f,0.984231f},{0.0954964f,-0.112603f,0.98904f},{0.0764977f,-0.0902013f,0.992981f}, +{0.0574318f,-0.0677199f,0.99605f},{0.0383156f,-0.0451794f,0.998244f},{0.864968f,0.216949f,-0.452509f}, +{0.854735f,0.229015f,-0.465812f},{0.83355f,0.525501f,-0.170419f},{0.512693f,-0.223962f,-0.828846f}, +{0.345274f,-0.407126f,-0.845597f},{0.328915f,-0.387836f,-0.861045f},{0.530776f,-0.245284f,-0.811242f}, +{0.49431f,-0.202286f,-0.845422f},{0.312267f,-0.368206f,-0.875736f},{0.475662f,-0.180297f,-0.860952f}, +{0.260738f,-0.307446f,-0.915146f},{0.456785f,-0.158038f,-0.875426f},{0.278164f,-0.327993f,-0.902799f}, +{0.295345f,-0.348252f,-0.889658f},{0.243083f,-0.286628f,-0.92669f},{0.437715f,-0.135553f,-0.888837f}, +{0.36133f,-0.426058f,-0.829407f},{0.418489f,-0.112883f,-0.901179f},{0.225214f,-0.265559f,-0.93742f}, +{0.399143f,-0.0900702f,-0.912454f},{0.638609f,0.0637896f,-0.766883f},{0.764881f,0.334964f,-0.550232f}, +{0.776686f,0.321045f,-0.541931f},{0.379711f,-0.0671572f,-0.922665f},{0.207148f,-0.244256f,-0.947327f}, +{0.360228f,-0.0441843f,-0.931817f},{0.1889f,-0.222739f,-0.956402f},{0.170486f,-0.201027f,-0.964636f}, +{0.340727f,-0.0211908f,-0.939923f},{0.151922f,-0.179137f,-0.972023f},{0.133225f,-0.157091f,-0.978557f}, +{0.114411f,-0.134906f,-0.984231f},{0.301804f,0.0247052f,-0.95305f},{0.321242f,0.00178461f,-0.946995f}, +{0.0954963f,-0.112603f,-0.98904f},{0.282442f,0.0475355f,-0.958106f},{0.0764977f,-0.0902013f,-0.992981f}, +{0.263186f,0.0702416f,-0.962185f},{0.18253f,0.1548f,0.970938f},{-0.019167f,0.0226005f,0.999561f}, +{0.244062f,0.0927915f,-0.96531f},{0.169153f,0.181119f,0.968805f},{0.452261f,0.283519f,-0.845622f}, +{0.469014f,0.263765f,-0.842884f},{0.131403f,0.225632f,0.96531f},{0.353571f,0.399889f,0.845622f}, +{0.150369f,0.203268f,0.967508f},{0.76115f,0.610871f,-0.217916f},{0.66876f,0.448305f,-0.593113f}, +{0.656839f,0.462361f,-0.595638f},{0.598628f,0.530999f,0.599736f},{0.739853f,0.635983f,0.219416f}, +{0.712963f,0.604648f,0.355084f},{0.504783f,0.428095f,0.749619f},{0.38664f,0.360895f,0.848684f}, +{0.0574318f,-0.06772f,-0.99605f},{0.645f,0.47632f,-0.597573f},{0.757056f,0.642042f,0.121027f}, +{0.748269f,0.62606f,-0.219416f},{0.206312f,0.137304f,-0.968805f},{0.355998f,0.301914f,-0.884372f}, +{0.419192f,0.322513f,-0.848684f},{0.0383156f,-0.0451794f,-0.998244f},{0.225096f,0.115155f,-0.967508f}, +{0.621631f,0.503876f,-0.599736f},{0.71354f,0.605138f,-0.353084f},{0.627779f,0.532405f,-0.567836f}, +{0.757174f,0.642143f,-0.119748f},{0.182011f,0.154359f,-0.971105f},{0.019166f,-0.0225994f,-0.999561f}, +{0.756818f,0.615978f,-0.218624f},{0.548521f,-0.266208f,-0.792627f},{0.377068f,-0.444615f,-0.812488f}, +{0.565895f,-0.286694f,-0.773026f},{0.582863f,-0.306702f,-0.752465f},{0.392475f,-0.462782f,-0.794856f}, +{0.407538f,-0.480543f,-0.776525f},{0.422243f,-0.497882f,-0.757512f},{0.436576f,-0.514784f,-0.737834f}, +{0.599393f,-0.326194f,-0.730976f},{0.615454f,-0.345131f,-0.708591f},{0.450527f,-0.531233f,-0.717508f}, +{0.631014f,-0.363479f,-0.68535f},{0.464081f,-0.547216f,-0.696551f},{0.646047f,-0.381204f,-0.661292f}, +{0.829264f,-0.161018f,-0.535159f},{0.902811f,0.172326f,-0.394f},{0.911416f,0.16218f,-0.378179f}, +{0.660525f,-0.398276f,-0.636461f},{0.477228f,-0.562717f,-0.674983f},{0.674424f,-0.414665f,-0.610904f}, +{0.489956f,-0.577725f,-0.652822f},{0.514109f,-0.606205f,-0.606801f},{0.502253f,-0.592225f,-0.630089f}, +{0.687723f,-0.430346f,-0.58467f},{0.525514f,-0.619653f,-0.58298f},{0.700401f,-0.445295f,-0.557808f}, +{0.536457f,-0.632556f,-0.558647f},{0.546929f,-0.644904f,-0.533824f},{0.712441f,-0.459492f,-0.530373f}, +{0.723827f,-0.472918f,-0.502416f},{0.55692f,-0.656685f,-0.508532f},{0.734548f,-0.48556f,-0.473994f}, +{0.960649f,0.104127f,-0.25751f},{0.872299f,0.47981f,-0.0942108f},{0.966018f,0.097796f,-0.239258f}, +{0.566422f,-0.66789f,-0.482793f},{0.744593f,-0.497404f,-0.445162f},{0.753955f,-0.508443f,-0.415977f}, +{0.575427f,-0.678508f,-0.45663f},{0.583927f,-0.68853f,-0.430066f},{0.591913f,-0.697947f,-0.403124f}, +{0.59938f,-0.706751f,-0.375828f},{0.762629f,-0.518671f,-0.386494f},{0.770612f,-0.528084f,-0.356769f}, +{0.60632f,-0.714934f,-0.348202f},{0.777905f,-0.536683f,-0.326857f},{0.612728f,-0.72249f,-0.32027f}, +{0.618597f,-0.729411f,-0.292057f},{0.784509f,-0.54447f,-0.296814f},{0.790429f,-0.551451f,-0.266692f}, +{0.623923f,-0.735691f,-0.263588f},{0.795672f,-0.557633f,-0.236543f},{0.939484f,-0.290984f,-0.180824f}, +{0.800246f,-0.563026f,-0.206418f},{0.935477f,-0.286259f,-0.207214f},{0.628701f,-0.741325f,-0.234887f}, +{0.804162f,-0.567644f,-0.176364f},{0.632927f,-0.746308f,-0.205979f},{0.998038f,0.0600411f,-0.0177823f}, +{0.885788f,0.463905f,-0.0130831f},{0.885978f,0.463681f,-0.00650573f},{0.636597f,-0.750636f,-0.176891f}, +{0.223622f,0.973184f,0.0539127f},{0.602655f,0.797758f,0.0197241f},{0.224873f,0.971708f,0.0722163f}, +{0.94578f,-0.298407f,-0.128274f},{0.948091f,-0.301132f,-0.102193f},{0.81007f,-0.574611f,-0.116657f}, +{-0.14403f,0.986628f,0.0762915f},{-0.142259f,0.98454f,0.102193f},{-0.14601f,0.988963f,0.0251637f}, +{0.0805097f,0.996754f,1.11285e-016f},{0.222222f,0.974834f,0.0177823f},{0.885008f,0.464825f,-0.0264206f}, +{0.996638f,0.0616911f,-0.0539127f},{0.995387f,0.0631666f,-0.0722163f},{-0.438888f,0.898083f,0.0287253f}, +{-0.17704f,0.984204f,4.07949e-016f},{0.884411f,0.465529f,-0.0331634f},{0.993754f,0.0650924f,-0.0906466f}, +{0.88367f,0.466403f,-0.0399431f},{-0.427653f,0.903943f,3.52919e-035f},{0.639708f,-0.754304f,-0.147647f}, +{0.807432f,-0.5715f,-0.146429f},{0.813513f,-0.57867f,-0.0577667f},{0.812092f,-0.576994f,-0.0870897f}, +{0.949862f,-0.30322f,-0.0762915f},{0.642257f,-0.757309f,-0.118274f},{0.644242f,-0.75965f,-0.0887967f}, +{0.645661f,-0.761323f,-0.0592414f},{0.646513f,-0.762327f,-0.0296338f},{0.814352f,-0.57966f,-0.0287253f}, +{0.506241f,0.429332f,-0.747926f},{0.435647f,0.30311f,-0.847547f},{0.485883f,0.243875f,-0.839311f}, +{0.502844f,0.223875f,-0.834882f},{0.519872f,0.203796f,-0.829578f},{0.536941f,0.18367f,-0.823383f}, +{0.554024f,0.163527f,-0.816282f},{0.571091f,0.143403f,-0.808264f},{0.588114f,0.12333f,-0.79932f}, +{0.605061f,0.103347f,-0.789443f},{0.621904f,0.0834874f,-0.778631f},{0.655145f,0.0442908f,-0.754203f}, +{0.671482f,0.0250283f,-0.740598f},{0.687585f,0.00603957f,-0.726078f},{0.703426f,-0.0126381f,-0.710657f}, +{0.718971f,-0.0309681f,-0.69435f},{0.73419f,-0.0489141f,-0.677179f},{0.749055f,-0.0664415f,-0.659168f}, +{0.763536f,-0.083516f,-0.640343f},{0.777605f,-0.100105f,-0.620734f},{0.791236f,-0.116178f,-0.600374f}, +{0.804404f,-0.131706f,-0.579299f},{0.817087f,-0.146661f,-0.557547f},{0.840913f,-0.174755f,-0.512177f}, +{0.852019f,-0.187851f,-0.488646f},{0.862566f,-0.200287f,-0.464612f},{0.872541f,-0.212049f,-0.440122f}, +{0.881933f,-0.223123f,-0.415224f},{0.890732f,-0.233499f,-0.389967f},{0.898933f,-0.243169f,-0.3644f}, +{0.906532f,-0.252128f,-0.338573f},{0.913525f,-0.260374f,-0.312533f},{0.919913f,-0.267907f,-0.286331f}, +{0.925699f,-0.274729f,-0.260012f},{0.930885f,-0.280844f,-0.233625f},{0.942915f,-0.295029f,-0.154497f}, +{0.991729f,0.0674795f,-0.109178f},{0.951842f,-0.305555f,-0.0251637f},{0.951107f,-0.304688f,-0.0506043f}, +{0.938627f,-0.344933f,-2.28355e-016f},{0.822203f,-0.569194f,-3.01839e-016f},{0.627461f,0.532136f,0.56844f}, +{0.633259f,0.490164f,-0.598933f},{0.680746f,0.434172f,-0.589983f},{0.692779f,0.419983f,-0.586235f}, +{0.704841f,0.40576f,-0.581857f},{0.716913f,0.391526f,-0.576839f},{0.728974f,0.377304f,-0.571173f}, +{0.741003f,0.36312f,-0.564853f},{0.752979f,0.348998f,-0.557873f},{0.799916f,0.293653f,-0.523356f}, +{0.788372f,0.307265f,-0.53297f},{0.809271f,0.554129f,-0.194989f},{0.811296f,0.280235f,-0.513095f}, +{0.82249f,0.267036f,-0.502197f},{0.833475f,0.254083f,-0.490674f},{0.844231f,0.241401f,-0.47854f}, +{0.87491f,0.205226f,-0.438652f},{0.884543f,0.193867f,-0.424264f},{0.893848f,0.182894f,-0.409371f}, +{0.86017f,0.494112f,-0.126333f},{0.627951f,0.767931f,0.126333f},{0.862897f,0.490897f,-0.120119f}, +{0.919648f,0.152473f,-0.361938f},{0.927496f,0.143219f,-0.34531f},{0.93495f,0.134431f,-0.328326f}, +{0.941998f,0.126119f,-0.31102f},{0.948635f,0.118293f,-0.293425f},{0.954853f,0.110961f,-0.275577f}, +{0.97096f,0.0919687f,-0.220857f},{0.975475f,0.0866457f,-0.20234f},{0.979563f,0.0818252f,-0.183742f}, +{0.983228f,0.0775037f,-0.165095f},{0.986473f,0.0736769f,-0.146431f},{0.989305f,0.0703379f,-0.127782f}, +{0.997518f,0.0606535f,-0.0357604f},{0.885466f,0.464285f,-0.0197241f},{0.996651f,-0.0817741f,-2.89047e-016f}, +{-0.0383171f,0.0451812f,0.998244f},{0.752523f,0.621043f,-0.219122f},{0.765511f,0.605729f,-0.216993f}, +{0.769896f,0.600558f,-0.215848f},{0.70941f,0.671879f,0.212874f},{0.783128f,0.584956f,-0.211039f}, +{0.778711f,0.590164f,-0.212875f},{0.774298f,0.595367f,-0.214476f},{0.78754f,0.579753f,-0.208966f}, +{0.791941f,0.574564f,-0.206653f},{0.796323f,0.569397f,-0.2041f},{0.800677f,0.564263f,-0.201305f}, +{0.804996f,0.55917f,-0.198267f},{0.670463f,0.717803f,0.187718f},{0.821754f,0.539411f,-0.183731f}, +{0.817658f,0.54424f,-0.187718f},{0.813495f,0.549149f,-0.191472f},{0.825773f,0.534672f,-0.179515f}, +{0.829707f,0.530032f,-0.175076f},{0.64719f,0.745245f,0.160482f},{0.844456f,0.512642f,-0.155219f}, +{0.840932f,0.516797f,-0.160482f},{0.837294f,0.521086f,-0.165552f},{0.84786f,0.508628f,-0.14977f}, +{0.851139f,0.504761f,-0.144146f},{0.854287f,0.501049f,-0.138358f},{0.857299f,0.497498f,-0.132417f}, +{0.865476f,0.487856f,-0.113788f},{0.867904f,0.484993f,-0.107351f},{0.870179f,0.48231f,-0.100821f}, +{0.61205f,0.786681f,0.0808013f},{0.877724f,0.473415f,-0.0740269f},{0.876072f,0.475362f,-0.0808013f}, +{0.874264f,0.477494f,-0.0875334f},{0.879219f,0.471651f,-0.0672227f},{0.88056f,0.47007f,-0.0604006f}, +{0.881747f,0.46867f,-0.0535724f},{0.882783f,0.467448f,-0.0467496f},{0.603113f,0.797218f,0.0264206f}, +{0.983879f,0.178833f,-2.6491e-016f},{0.731303f,0.646064f,0.218624f},{0.735599f,0.640999f,0.219122f}, +{0.726972f,0.651171f,0.217917f},{0.722611f,0.656314f,0.216992f},{0.718226f,0.661484f,0.215848f}, +{0.713823f,0.666676f,0.214476f},{0.704994f,0.677087f,0.211039f},{0.691799f,0.692645f,0.2041f}, +{0.69618f,0.687479f,0.206653f},{0.479257f,0.671755f,0.564852f},{0.700581f,0.682289f,0.208966f}, +{0.687444f,0.69778f,0.201305f},{0.683125f,0.702872f,0.198267f},{0.67885f,0.707913f,0.194989f}, +{0.674627f,0.712894f,0.191472f},{0.0716416f,0.732322f,0.677179f},{0.376029f,0.793474f,0.47854f}, +{0.0868611f,0.714376f,0.69435f},{0.666368f,0.722632f,0.183731f},{0.662349f,0.727371f,0.179515f}, +{0.658414f,0.73201f,0.175076f},{0.654571f,0.736542f,0.170419f},{0.650828f,0.740956f,0.165552f}, +{-0.0112556f,0.830069f,0.557547f},{0.317449f,0.862549f,0.394f},{0.00142744f,0.815114f,0.579299f}, +{0.643666f,0.749401f,0.155219f},{0.640261f,0.753415f,0.14977f},{0.636982f,0.757282f,0.144146f}, +{0.633834f,0.760993f,0.138358f},{0.630822f,0.764545f,0.132417f},{0.620218f,0.77705f,0.107351f}, +{0.622645f,0.774187f,0.113788f},{0.278262f,0.908756f,0.311019f},{0.625224f,0.771146f,0.120119f}, +{0.617942f,0.779732f,0.100821f},{0.615822f,0.782232f,0.0942108f},{0.613858f,0.784549f,0.0875334f}, +{0.610398f,0.788628f,0.0740269f},{0.606374f,0.793373f,0.0535724f},{0.607562f,0.791973f,0.0604006f}, +{0.237032f,0.957371f,0.165095f},{0.608902f,0.790392f,0.0672227f},{0.605338f,0.794594f,0.0467497f}, +{0.604451f,0.79564f,0.0399431f},{0.603711f,0.796513f,0.0331634f},{0.602333f,0.798137f,0.0130831f}, +{0.602143f,0.798361f,0.00650573f},{0.762662f,0.646797f,-2.05938e-033f},{0.904079f,0.427366f,-1.54031e-016f}, +{0.575259f,0.558555f,0.597573f},{0.587f,0.544711f,0.598933f},{0.563421f,0.572514f,0.595638f}, +{0.5515f,0.58657f,0.593113f},{0.539514f,0.600703f,0.589983f},{0.527481f,0.614892f,0.586235f}, +{0.515419f,0.629115f,0.581857f},{0.503347f,0.643349f,0.576839f},{0.491286f,0.657571f,0.571173f}, +{0.20077f,0.580061f,0.789443f},{0.183928f,0.599921f,0.778631f},{0.455379f,0.699911f,0.550232f}, +{0.46728f,0.685877f,0.557873f},{0.443574f,0.71383f,0.541931f},{0.431888f,0.72761f,0.53297f}, +{0.420343f,0.741222f,0.523356f},{0.408963f,0.75464f,0.513095f},{0.39777f,0.767839f,0.502197f}, +{0.386784f,0.780792f,0.490674f},{0.365525f,0.80586f,0.465812f},{0.355292f,0.817926f,0.452509f}, +{0.34535f,0.829649f,0.438652f},{0.335717f,0.841008f,0.424264f},{0.326411f,0.851981f,0.409371f}, +{0.308844f,0.872695f,0.378179f},{0.300612f,0.882402f,0.361938f},{0.292763f,0.891656f,0.34531f}, +{0.28531f,0.900444f,0.328326f},{-0.0761008f,0.90653f,0.415224f},{-0.0849005f,0.916907f,0.389967f}, +{0.265406f,0.923914f,0.275577f},{0.271625f,0.916582f,0.293425f},{0.259611f,0.930748f,0.257509f}, +{0.254241f,0.937079f,0.239258f},{0.249299f,0.942906f,0.220857f},{0.244785f,0.948229f,0.20234f}, +{0.240697f,0.95305f,0.183742f},{0.233786f,0.961198f,0.146431f},{-0.133653f,0.974392f,0.180824f}, +{-0.137083f,0.978437f,0.154497f},{0.228531f,0.967395f,0.109178f},{0.230955f,0.964537f,0.127782f}, +{0.226506f,0.969783f,0.0906467f},{0.222742f,0.974221f,0.0357604f},{0.337862f,0.941196f,1.5621e-016f}, +{0.569614f,0.821913f,6.56678e-035f},{0.348737f,0.295756f,0.889332f},{0.370185f,0.380298f,0.847547f}, +{0.336818f,0.419643f,0.842884f},{0.319949f,0.439533f,0.839311f},{0.112279f,0.248181f,0.962185f}, +{0.302988f,0.459533f,0.834882f},{0.28596f,0.479612f,0.829578f},{0.26889f,0.499738f,0.823383f}, +{0.251808f,0.519881f,0.816282f},{0.234741f,0.540006f,0.808264f},{0.217718f,0.560077f,0.79932f}, +{-0.295347f,0.348255f,0.889657f},{-0.100197f,0.49872f,0.860952f},{-0.0813203f,0.476461f,0.875426f}, +{0.167223f,0.619618f,0.766883f},{0.150686f,0.639117f,0.754203f},{0.13435f,0.65838f,0.740598f}, +{0.118247f,0.677368f,0.726078f},{0.102406f,0.696046f,0.710657f},{-0.207399f,0.625125f,0.752465f}, +{0.0567769f,0.749849f,0.659168f},{-0.19043f,0.605117f,0.773026f},{0.0422963f,0.766924f,0.640343f}, +{0.0282273f,0.783513f,0.620734f},{0.0145963f,0.799586f,0.600374f},{-0.29896f,0.733089f,0.610904f}, +{-0.51411f,0.606207f,0.606799f},{-0.312259f,0.74877f,0.58467f},{-0.0234316f,0.844427f,0.535159f}, +{-0.0350815f,0.858163f,0.512177f},{-0.0461876f,0.871259f,0.488646f},{-0.0567343f,0.883695f,0.464612f}, +{-0.0667093f,0.895457f,0.440122f},{-0.378491f,0.826866f,0.415977f},{-0.0931014f,0.926577f,0.3644f}, +{-0.369129f,0.815827f,0.445162f},{-0.1007f,0.935536f,0.338573f},{-0.107693f,0.943782f,0.312533f}, +{-0.114081f,0.951315f,0.286331f},{-0.119867f,0.958137f,0.260012f},{-0.125053f,0.964252f,0.233625f}, +{-0.129645f,0.969667f,0.207214f},{-0.139948f,0.981815f,0.128274f},{-0.438049f,0.897093f,0.0577667f}, +{-0.436627f,0.895417f,0.0870897f},{-0.145275f,0.988096f,0.0506043f},{0.0930223f,0.270888f,0.958106f}, +{0.0736606f,0.293718f,0.95305f},{0.054222f,0.316638f,0.946995f},{0.034737f,0.339614f,0.939923f}, +{0.015237f,0.362607f,0.931817f},{-0.00424604f,0.38558f,0.922665f},{-0.023678f,0.408493f,0.912454f}, +{-0.0430246f,0.431306f,0.901179f},{-0.0622507f,0.453976f,0.888837f},{-0.118846f,0.520709f,0.845422f}, +{-0.137229f,0.542385f,0.828846f},{-0.155311f,0.563707f,0.811242f},{-0.173056f,0.584631f,0.792627f}, +{-0.392477f,0.462784f,0.794854f},{-0.223929f,0.644617f,0.730976f},{-0.239989f,0.663554f,0.708591f}, +{-0.25555f,0.681902f,0.68535f},{-0.270582f,0.699627f,0.661292f},{-0.28506f,0.716699f,0.636461f}, +{-0.324936f,0.763719f,0.557808f},{-0.336976f,0.777915f,0.530373f},{-0.348363f,0.791341f,0.502416f}, +{-0.359084f,0.803983f,0.473994f},{-0.575428f,0.678509f,0.456627f},{-0.387165f,0.837094f,0.386494f}, +{-0.395148f,0.846507f,0.356769f},{-0.40244f,0.855106f,0.326857f},{-0.409044f,0.862893f,0.296814f}, +{-0.414964f,0.869874f,0.266692f},{-0.420207f,0.876056f,0.236543f},{-0.424781f,0.881449f,0.206418f}, +{-0.428697f,0.886067f,0.176364f},{-0.431967f,0.889923f,0.146429f},{-0.434606f,0.893034f,0.116657f}, +{-0.0574335f,0.0677219f,0.99605f},{-0.0764992f,0.090203f,0.992981f},{-0.0954975f,0.112605f,0.98904f}, +{-0.114412f,0.134908f,0.98423f},{-0.133227f,0.157093f,0.978556f},{-0.151924f,0.179139f,0.972023f}, +{-0.170488f,0.201028f,0.964635f},{-0.188902f,0.222741f,0.956401f},{-0.20715f,0.244258f,0.947326f}, +{-0.225216f,0.265561f,0.937419f},{-0.243085f,0.28663f,0.926689f},{-0.260739f,0.307448f,0.915145f}, +{-0.278165f,0.327995f,0.902798f},{-0.312269f,0.368208f,0.875734f},{-0.328917f,0.387838f,0.861043f}, +{-0.345276f,0.407127f,0.845596f},{-0.361331f,0.426059f,0.829405f},{-0.37707f,0.444617f,0.812486f}, +{-0.407539f,0.480545f,0.776523f},{-0.422244f,0.497883f,0.757511f},{-0.436577f,0.514784f,0.737833f}, +{-0.450527f,0.531233f,0.717507f},{-0.464082f,0.547216f,0.696551f},{-0.477229f,0.562718f,0.674982f}, +{-0.489956f,0.577726f,0.652821f},{-0.502254f,0.592226f,0.630087f},{-0.525515f,0.619654f,0.582978f}, +{-0.536458f,0.632557f,0.558645f},{-0.546929f,0.644905f,0.533822f},{-0.556921f,0.656686f,0.508529f}, +{-0.566423f,0.667891f,0.48279f},{-0.583927f,0.688531f,0.430063f},{-0.591914f,0.697948f,0.403122f}, +{-0.59938f,0.706752f,0.375826f},{-0.606321f,0.714935f,0.3482f},{-0.612728f,0.722491f,0.320268f}, +{-0.618598f,0.729411f,0.292055f},{-0.623923f,0.735692f,0.263585f},{-0.628702f,0.741326f,0.234884f}, +{-0.632928f,0.746309f,0.205977f},{-0.636597f,0.750636f,0.176888f},{-0.639708f,0.754304f,0.147645f}, +{-0.642257f,0.757309f,0.118272f},{-0.644242f,0.75965f,0.0887941f},{-0.645661f,0.761323f,0.0592391f}, +{-0.646513f,0.762327f,0.0296323f},{-5.74474e-016f,6.77383e-016f,1.0f},{7.92072e-017f,-9.33961e-017f,1.0f}, +{0.156255f,0.134204f,0.978557f},{-0.0265911f,0.301644f,0.95305f},{-0.00379251f,0.321225f,0.946995f}, +{0.110265f,0.419187f,0.901179f},{0.285103f,0.24487f,0.92669f},{0.264146f,0.22687f,0.93742f}, +{-0.286341f,0.45048f,0.845622f},{-0.480343f,0.642011f,0.597573f},{-0.466457f,0.653936f,0.595638f}, +{-0.0492999f,0.28214f,0.958106f},{0.134188f,0.115252f,0.984231f},{-0.610502f,0.76171f,0.216993f}, +{-0.615617f,0.757316f,0.217916f},{-0.0943152f,0.243477f,0.96531f},{-0.266692f,0.467356f,0.842884f}, +{-0.0718852f,0.262742f,0.962185f},{-0.640595f,0.735863f,-0.219416f},{-0.630724f,0.744341f,0.219416f}, +{-0.646863f,0.753146f,0.119748f},{-0.620697f,0.752953f,0.218624f},{-0.431242f,0.502097f,-0.749619f}, +{-0.363305f,0.384377f,-0.848684f},{-0.534731f,0.595298f,-0.599736f},{-0.609092f,0.70917f,-0.355084f}, +{-0.0449409f,-0.0385987f,-0.998244f},{-0.204204f,0.149095f,-0.967508f},{-0.182173f,0.168018f,-0.968805f}, +{-0.0224804f,-0.0193078f,-0.999561f},{-0.155937f,0.181559f,-0.970938f},{-4.72151e-016f,-4.05521e-016f,-1.0f}, +{0.199957f,0.171739f,0.964636f},{0.0190607f,0.340853f,0.939923f},{0.0419318f,0.360497f,0.931817f}, +{0.178184f,0.153039f,0.972023f},{0.0647826f,0.380123f,0.922665f},{0.221554f,0.190289f,0.956402f}, +{-0.127004f,0.587331f,0.79932f},{0.0875737f,0.399698f,0.912454f},{0.242957f,0.208671f,0.947327f}, +{0.132814f,0.438554f,0.888837f},{0.30581f,0.262654f,0.915146f},{0.17732f,0.47678f,0.860952f}, +{0.199192f,0.495565f,0.845422f},{0.366247f,0.314563f,0.875736f},{0.15518f,0.457764f,0.875426f}, +{0.423791f,0.363986f,0.829407f},{0.40496f,0.347812f,0.845597f},{0.241961f,0.532298f,0.811242f}, +{0.385773f,0.331333f,0.861045f},{0.46032f,0.39536f,0.794856f},{0.283151f,0.567676f,0.773026f}, +{0.303053f,0.584769f,0.752465f},{0.262774f,0.550174f,0.792627f},{0.512045f,0.439786f,0.737834f}, +{0.341277f,0.617599f,0.708591f},{0.528407f,0.453838f,0.717508f},{0.322441f,0.601421f,0.730976f}, +{0.574651f,0.493557f,0.652822f},{0.559724f,0.480736f,0.674983f},{0.39414f,0.663002f,0.636461f}, +{0.544304f,0.467493f,0.696551f},{0.377159f,0.648417f,0.661292f},{0.616356f,0.529376f,0.58298f}, +{0.426039f,0.6904f,0.58467f},{0.440909f,0.703171f,0.557808f},{0.410442f,0.677003f,0.610904f}, +{0.468385f,0.726769f,0.502416f},{0.653191f,0.561014f,0.508532f},{0.641473f,0.550949f,0.533824f}, +{0.629191f,0.5404f,0.558647f},{0.684866f,0.588219f,0.430066f},{0.674898f,0.579657f,0.45663f}, +{0.503721f,0.757119f,0.415977f},{0.480959f,0.737569f,0.473994f},{0.513894f,0.765856f,0.386494f}, +{0.702991f,0.603786f,0.375828f},{0.694233f,0.596264f,0.403124f},{0.539556f,0.787897f,0.296814f}, +{0.718646f,0.617231f,0.32027f},{0.53181f,0.781244f,0.326857f},{0.711131f,0.610777f,0.348202f}, +{0.523257f,0.773898f,0.356769f},{0.731777f,0.628509f,0.263588f},{0.552648f,0.799142f,0.236543f}, +{0.737381f,0.633323f,0.234887f},{0.546499f,0.79386f,0.266692f},{0.72553f,0.623144f,0.292057f}, +{0.742337f,0.63758f,0.205979f},{0.562606f,0.807694f,0.176364f},{0.746642f,0.641277f,0.176891f}, +{0.558013f,0.803749f,0.206418f},{0.574558f,0.81796f,0.0287253f},{0.758605f,0.651551f,3.14853e-016f}, +{0.758272f,0.651265f,0.0296338f},{0.75029f,0.64441f,0.147647f},{0.566442f,0.810988f,0.146429f}, +{0.571907f,0.815682f,0.0870897f},{0.297277f,0.951738f,0.0762915f},{0.298738f,0.952993f,0.0506043f}, +{0.757272f,0.650407f,0.0592414f},{0.75328f,0.646978f,0.118274f},{0.755608f,0.648977f,0.0887967f}, +{0.573574f,0.817114f,0.0577667f},{0.569536f,0.813646f,0.116657f},{-0.0668874f,0.997119f,0.0357603f}, +{-0.46921f,0.883063f,0.00650573f},{-0.0662782f,0.997643f,0.0177823f},{0.28913f,0.944741f,0.154497f}, +{0.285106f,0.941285f,0.180824f},{-0.0679193f,0.996233f,0.0539127f},{0.2952f,0.949955f,0.102193f}, +{-0.069387f,0.994972f,0.0722163f},{-0.073677f,0.991288f,0.109178f},{-0.801509f,0.597657f,-0.0197241f}, +{-0.800972f,0.598118f,-0.0264206f},{-0.974563f,0.217534f,-0.0539127f},{-0.470347f,0.882086f,0.0264206f}, +{-0.46981f,0.882547f,0.0197241f},{-0.985709f,-0.150194f,-0.0762915f},{-0.987169f,-0.151448f,-0.0506043f}, +{-0.997238f,0.0742779f,-1.10368e-016f},{-0.976204f,0.216125f,-0.0177823f},{-0.988031f,-0.152188f,-0.0251637f}, +{-0.895322f,-0.444493f,-0.0287253f},{-0.901253f,-0.433294f,-3.00521e-016f},{-0.983078f,-0.183188f,-5.39175e-016f}, +{-0.758605f,-0.651551f,-6.22394e-016f},{0.27502f,0.932622f,0.233625f},{0.45503f,0.715299f,0.530373f}, +{0.664336f,0.570586f,0.482793f},{0.49274f,0.747688f,0.445162f},{0.206591f,0.87385f,0.440122f}, +{0.60298f,0.517888f,0.606801f},{0.589074f,0.505945f,0.630089f},{0.359528f,0.633274f,0.68535f}, +{0.495233f,0.425347f,0.757512f},{0.126676f,0.805212f,0.579299f},{-0.188478f,0.892688f,0.409371f}, +{-0.177966f,0.901716f,0.394f},{0.477987f,0.410534f,0.776525f},{0.44225f,0.37984f,0.812488f}, +{0.346399f,0.297516f,0.889658f},{0.326248f,0.280208f,0.902799f},{0.220753f,0.514083f,0.828846f}, +{-0.246673f,0.842705f,0.47854f},{0.0264735f,0.71915f,0.69435f},{-0.259287f,0.831871f,0.490674f}, +{0.112004f,0.0961983f,0.98904f},{0.0897214f,0.07706f,0.992981f},{0.0673597f,0.0578539f,0.99605f}, +{-0.507751f,0.61847f,0.599736f},{-0.609586f,0.709744f,0.353084f},{-0.11656f,0.224371f,0.967508f}, +{0.044939f,0.0385972f,0.998244f},{-0.138591f,0.205449f,0.968805f},{0.0224791f,0.0193069f,0.999561f}, +{-0.646762f,0.753028f,-0.121027f},{-0.155494f,0.181042f,0.971105f},{2.38849e-016f,2.05143e-016f,1.0f}, +{-0.304133f,0.354104f,0.884372f},{-0.432488f,0.503548f,0.747926f},{-0.325126f,0.417168f,0.848684f}, +{-0.536319f,0.624439f,0.567836f},{-0.305827f,0.433744f,0.847547f},{-0.246907f,0.484349f,0.839311f}, +{-0.227014f,0.501435f,0.834882f},{-0.207042f,0.518588f,0.829578f},{-0.187022f,0.535783f,0.823383f}, +{-0.166987f,0.552991f,0.816282f},{-0.146969f,0.570184f,0.808264f},{-0.353698f,0.750783f,0.557873f}, +{-0.339739f,0.762773f,0.550232f},{-0.107127f,0.604404f,0.789443f},{-0.087373f,0.62137f,0.778631f}, +{-0.06778f,0.638198f,0.766883f},{-0.0483849f,0.654856f,0.754203f},{-0.0292249f,0.671312f,0.740598f}, +{-0.0103371f,0.687534f,0.726078f},{0.00824112f,0.703491f,0.710657f},{0.0443241f,0.734482f,0.677179f}, +{0.0617582f,0.749456f,0.659168f},{0.078742f,0.764043f,0.640343f},{0.0952429f,0.778215f,0.620734f}, +{0.111231f,0.791946f,0.600374f},{0.141551f,0.817988f,0.557547f},{0.155832f,0.830254f,0.535159f}, +{0.169496f,0.841989f,0.512177f},{0.182521f,0.853177f,0.488646f},{0.194892f,0.863801f,0.464612f}, +{-0.485253f,0.869283f,0.0942108f},{-0.116927f,0.954141f,0.275577f},{-0.48774f,0.867148f,0.100821f}, +{0.217606f,0.88331f,0.415224f},{0.227926f,0.892174f,0.389967f},{0.237545f,0.900436f,0.3644f}, +{0.246457f,0.90809f,0.338573f},{0.254659f,0.915135f,0.312533f},{0.262152f,0.92157f,0.286331f}, +{0.268937f,0.927398f,0.260012f},{0.280406f,0.937248f,0.207214f},{-0.0765203f,0.988846f,0.127782f}, +{0.292489f,0.947626f,0.128274f},{0.2996f,0.953733f,0.0251637f},{0.339059f,0.940765f,7.30221e-017f}, +{0.564043f,0.825745f,2.30577e-016f},{-0.536047f,0.624123f,-0.56844f},{-0.494113f,0.630183f,0.598933f}, +{-0.452476f,0.665945f,0.593113f},{-0.438418f,0.678019f,0.589983f},{-0.424305f,0.69014f,0.586235f}, +{-0.410157f,0.702291f,0.581857f},{-0.395999f,0.714451f,0.576839f},{-0.381854f,0.726601f,0.571173f}, +{-0.367745f,0.738719f,0.564853f},{-0.325893f,0.774664f,0.541931f},{-0.564191f,0.801485f,0.198267f}, +{-0.559177f,0.805792f,0.194989f},{-0.312187f,0.786436f,0.53297f},{-0.298647f,0.798065f,0.523356f}, +{-0.2853f,0.809529f,0.513095f},{-0.272171f,0.820805f,0.502197f},{-0.52631f,0.834021f,0.165552f}, +{-0.74501f,0.646183f,-0.165552f},{-0.749276f,0.642519f,-0.160482f},{-0.234353f,0.853287f,0.465812f}, +{-0.222351f,0.863595f,0.452509f},{-0.21069f,0.87361f,0.438652f},{-0.199392f,0.883313f,0.424264f}, +{-0.502847f,0.854173f,0.132416f},{-0.768473f,0.626031f,-0.132417f},{-0.771841f,0.623139f,-0.126333f}, +{-0.167874f,0.910384f,0.378179f},{-0.158218f,0.918677f,0.361938f},{-0.149013f,0.926583f,0.34531f}, +{-0.140272f,0.934091f,0.328326f},{-0.132004f,0.941192f,0.31102f},{-0.124221f,0.947877f,0.293425f}, +{-0.11013f,0.959979f,0.25751f},{-0.103832f,0.965388f,0.239258f},{-0.098036f,0.970367f,0.220857f}, +{-0.0927412f,0.974914f,0.20234f},{-0.0879463f,0.979032f,0.183742f},{-0.0836479f,0.982724f,0.165095f}, +{-0.0798413f,0.985994f,0.146431f},{-0.0713026f,0.993327f,0.0906466f},{-0.801887f,0.597333f,-0.0130831f}, +{0.0755429f,0.997143f,3.49386e-017f},{-0.382604f,0.367801f,-0.847547f},{-0.625735f,0.748626f,0.219122f}, +{-0.605359f,0.766127f,0.215847f},{-0.665961f,0.714077f,-0.215848f},{-0.671124f,0.709642f,-0.214476f}, +{-0.600195f,0.770562f,0.214476f},{-0.595019f,0.775007f,0.212875f},{-0.58984f,0.779456f,0.211039f}, +{-0.584664f,0.783901f,0.208966f},{-0.579503f,0.788334f,0.206653f},{-0.574364f,0.792748f,0.2041f}, +{-0.569256f,0.797135f,0.201304f},{-0.554223f,0.810046f,0.191472f},{-0.717096f,0.670158f,-0.191472f}, +{-0.721979f,0.665964f,-0.187718f},{-0.54934f,0.814241f,0.187718f},{-0.544537f,0.818366f,0.183731f}, +{-0.539823f,0.822414f,0.179515f},{-0.535208f,0.826378f,0.175076f},{-0.530701f,0.830249f,0.170419f}, +{-0.522044f,0.837685f,0.160482f},{-0.51791f,0.841235f,0.155219f},{-0.513917f,0.844665f,0.14977f}, +{-0.510071f,0.847968f,0.144146f},{-0.506379f,0.851139f,0.138358f},{-0.499479f,0.857065f,0.126333f}, +{-0.496281f,0.859812f,0.120119f},{-0.493256f,0.86241f,0.113788f},{-0.490408f,0.864856f,0.107351f}, +{-0.482949f,0.871262f,0.0875334f},{-0.78837f,0.608942f,-0.0875334f},{-0.790491f,0.60712f,-0.0808013f}, +{-0.480829f,0.873084f,0.0808013f},{-0.478892f,0.874747f,0.0740269f},{-0.477137f,0.876254f,0.0672227f}, +{-0.475565f,0.877605f,0.0604006f},{-0.474172f,0.878801f,0.0535724f},{-0.472957f,0.879844f,0.0467496f}, +{-0.471917f,0.880738f,0.0399431f},{-0.471048f,0.881484f,0.0331634f},{-0.469433f,0.882871f,0.0130831f}, +{-0.18498f,0.982742f,5.93908e-017f},{-0.650623f,0.727251f,-0.218624f},{-0.655703f,0.722888f,-0.217917f}, +{-0.645585f,0.731578f,-0.219122f},{-0.660818f,0.718494f,-0.216992f},{-0.6763f,0.705197f,-0.212875f}, +{-0.68148f,0.700748f,-0.211039f},{-0.686655f,0.696303f,-0.208966f},{-0.660628f,0.487166f,-0.571173f}, +{-0.674737f,0.475049f,-0.564852f},{-0.691817f,0.69187f,-0.206653f},{-0.696956f,0.687456f,-0.2041f}, +{-0.702063f,0.68307f,-0.201305f},{-0.707128f,0.678719f,-0.198267f},{-0.712143f,0.674412f,-0.194989f}, +{-0.726783f,0.661838f,-0.183731f},{-0.770311f,0.392963f,-0.502197f},{-0.783195f,0.381897f,-0.490674f}, +{-0.731497f,0.65779f,-0.179515f},{-0.736111f,0.653826f,-0.175076f},{-0.740619f,0.649955f,-0.170419f}, +{-0.753409f,0.638969f,-0.155219f},{-0.84309f,0.330454f,-0.424264f},{-0.854004f,0.32108f,-0.409371f}, +{-0.757402f,0.63554f,-0.14977f},{-0.761248f,0.632236f,-0.144146f},{-0.76494f,0.629065f,-0.138358f}, +{-0.775039f,0.620392f,-0.120119f},{-0.90221f,0.279676f,-0.328326f},{-0.910477f,0.272576f,-0.311019f}, +{-0.778063f,0.617794f,-0.113788f},{-0.780911f,0.615349f,-0.107351f},{-0.783579f,0.613057f,-0.100821f}, +{-0.786066f,0.610921f,-0.0942108f},{-0.792428f,0.605457f,-0.0740269f},{-0.794182f,0.60395f,-0.0672227f}, +{-0.954536f,0.234735f,-0.183742f},{-0.958834f,0.231043f,-0.165095f},{-0.795755f,0.602599f,-0.0604006f}, +{-0.797147f,0.601403f,-0.0535724f},{-0.798362f,0.60036f,-0.0467497f},{-0.799403f,0.599467f,-0.0399431f}, +{-0.800271f,0.59872f,-0.0331634f},{-0.802109f,0.597142f,-0.00650573f},{-0.651551f,0.758605f,-1.07812e-032f}, +{-0.433008f,0.90139f,5.07106e-017f},{-0.562139f,0.571757f,-0.597573f},{-0.576025f,0.559831f,-0.595638f}, +{-0.548369f,0.583584f,-0.598933f},{-0.590006f,0.547823f,-0.593113f},{-0.604064f,0.535749f,-0.589983f}, +{-0.618177f,0.523627f,-0.586235f},{-0.632324f,0.511476f,-0.581857f},{-0.646483f,0.499316f,-0.576839f}, +{-0.688784f,0.462984f,-0.557873f},{-0.601059f,0.180175f,-0.778631f},{-0.702743f,0.450995f,-0.550232f}, +{-0.716589f,0.439103f,-0.541931f},{-0.730295f,0.427331f,-0.53297f},{-0.743835f,0.415702f,-0.523356f}, +{-0.757182f,0.404239f,-0.513095f},{-0.732756f,0.0670628f,-0.677179f},{-0.795809f,0.371062f,-0.47854f}, +{-0.808129f,0.360481f,-0.465812f},{-0.820131f,0.350173f,-0.452509f},{-0.831792f,0.340158f,-0.438652f}, +{-0.829983f,-0.0164437f,-0.557547f},{-0.864516f,0.312051f,-0.394f},{-0.874608f,0.303383f,-0.378179f}, +{-0.884264f,0.29509f,-0.361938f},{-0.893469f,0.287184f,-0.34531f},{-0.906037f,-0.0817656f,-0.415224f}, +{-0.918261f,0.26589f,-0.293425f},{-0.925555f,0.259626f,-0.275577f},{-0.932352f,0.253788f,-0.25751f}, +{-0.93865f,0.248379f,-0.239258f},{-0.944446f,0.243401f,-0.220857f},{-0.949741f,0.238853f,-0.20234f}, +{-0.962641f,0.227774f,-0.146431f},{-0.973538f,-0.13974f,-0.180824f},{-0.965962f,0.224921f,-0.127782f}, +{-0.968805f,0.222479f,-0.109178f},{-0.971179f,0.22044f,-0.0906466f},{-0.973095f,0.218795f,-0.0722163f}, +{-0.975595f,0.216648f,-0.0357604f},{-0.943289f,0.331972f,-1.55829e-016f},{-0.825457f,0.564465f,-4.03832e-017f}, +{-0.29793f,0.346881f,-0.889332f},{-0.402091f,0.351065f,-0.845622f},{-0.42174f,0.334188f,-0.842884f}, +{-0.441525f,0.317195f,-0.839311f},{-0.461418f,0.30011f,-0.834882f},{-0.48139f,0.282956f,-0.829578f}, +{-0.501409f,0.265762f,-0.823383f},{-0.521445f,0.248554f,-0.816282f},{-0.541462f,0.231361f,-0.808264f}, +{-0.561427f,0.214213f,-0.79932f},{-0.581305f,0.197141f,-0.789443f},{-0.475944f,-0.0842967f,-0.875426f}, +{-0.346402f,-0.297518f,-0.889657f},{-0.498084f,-0.103313f,-0.860952f},{-0.620651f,0.163347f,-0.766883f}, +{-0.640047f,0.146689f,-0.754203f},{-0.659207f,0.130232f,-0.740598f},{-0.678094f,0.11401f,-0.726078f}, +{-0.696673f,0.0980537f,-0.710657f},{-0.714905f,0.0823942f,-0.69435f},{-0.75019f,0.0520888f,-0.659168f}, +{-0.623817f,-0.211302f,-0.752465f},{-0.767173f,0.0375018f,-0.640343f},{-0.783674f,0.0233296f,-0.620733f}, +{-0.799662f,0.00959801f,-0.600374f},{-0.815107f,-0.00366745f,-0.579299f},{-0.731206f,-0.303536f,-0.610904f}, +{-0.602981f,-0.517889f,-0.606799f},{-0.746803f,-0.316933f,-0.58467f},{-0.844264f,-0.0287092f,-0.535159f}, +{-0.857927f,-0.0404448f,-0.512177f},{-0.870953f,-0.0516324f,-0.488646f},{-0.883323f,-0.0622568f,-0.464612f}, +{-0.895022f,-0.072305f,-0.440122f},{-0.916358f,-0.0906297f,-0.389967f},{-0.824484f,-0.383652f,-0.415977f}, +{-0.925977f,-0.0988914f,-0.3644f},{-0.934889f,-0.106546f,-0.338573f},{-0.943091f,-0.11359f,-0.312533f}, +{-0.950583f,-0.120025f,-0.286331f},{-0.957369f,-0.125853f,-0.260012f},{-0.963451f,-0.131077f,-0.233625f}, +{-0.968838f,-0.135704f,-0.207214f},{-0.977561f,-0.143196f,-0.154497f},{-0.980921f,-0.146082f,-0.128274f}, +{-0.983632f,-0.14841f,-0.102193f},{-0.226448f,0.12999f,-0.96531f},{-0.248879f,0.110725f,-0.962185f}, +{-0.271464f,0.0913273f,-0.958106f},{-0.294173f,0.0718231f,-0.95305f},{-0.316971f,0.0522418f,-0.946995f}, +{-0.339824f,0.0326136f,-0.939923f},{-0.362695f,0.0129701f,-0.931817f},{-0.385546f,-0.00665603f,-0.922665f}, +{-0.408337f,-0.0262307f,-0.912454f},{-0.431028f,-0.0457197f,-0.901179f},{-0.453578f,-0.065087f,-0.888837f}, +{-0.519956f,-0.122098f,-0.845422f},{-0.541517f,-0.140616f,-0.828846f},{-0.562725f,-0.158831f,-0.811242f}, +{-0.583538f,-0.176707f,-0.792627f},{-0.603915f,-0.194209f,-0.773026f},{-0.460322f,-0.395362f,-0.794854f}, +{-0.643204f,-0.227954f,-0.730976f},{-0.662041f,-0.244132f,-0.708591f},{-0.680291f,-0.259807f,-0.68535f}, +{-0.697922f,-0.27495f,-0.661292f},{-0.714903f,-0.289535f,-0.636461f},{-0.761673f,-0.329704f,-0.557808f}, +{-0.775794f,-0.341832f,-0.530373f},{-0.789149f,-0.353302f,-0.502416f},{-0.801723f,-0.364102f,-0.473994f}, +{-0.813504f,-0.374221f,-0.445162f},{-0.674899f,-0.579658f,-0.456627f},{-0.834658f,-0.392389f,-0.386494f}, +{-0.844021f,-0.400431f,-0.356769f},{-0.852574f,-0.407777f,-0.326857f},{-0.860319f,-0.41443f,-0.296814f}, +{-0.867263f,-0.420393f,-0.266692f},{-0.873412f,-0.425675f,-0.236543f},{-0.878777f,-0.430282f,-0.206418f}, +{-0.88337f,-0.434227f,-0.176364f},{-0.887205f,-0.437522f,-0.146429f},{-0.8903f,-0.440179f,-0.116657f}, +{-0.892671f,-0.442216f,-0.0870897f},{-0.894338f,-0.443647f,-0.0577667f},{-0.0673617f,-0.0578556f,-0.99605f}, +{-0.0897231f,-0.0770615f,-0.992981f},{-0.112006f,-0.0961995f,-0.98904f},{-0.13419f,-0.115254f,-0.98423f}, +{-0.156257f,-0.134206f,-0.978556f},{-0.178186f,-0.153041f,-0.972023f},{-0.199959f,-0.171741f,-0.964635f}, +{-0.221556f,-0.19029f,-0.956401f},{-0.242959f,-0.208673f,-0.947326f},{-0.264148f,-0.226872f,-0.937419f}, +{-0.285105f,-0.244871f,-0.926689f},{-0.305812f,-0.262656f,-0.915145f},{-0.32625f,-0.28021f,-0.902798f}, +{-0.366249f,-0.314564f,-0.875734f},{-0.385775f,-0.331335f,-0.861043f},{-0.404961f,-0.347814f,-0.845596f}, +{-0.423793f,-0.363987f,-0.829405f},{-0.442252f,-0.379842f,-0.812486f},{-0.477988f,-0.410535f,-0.776523f}, +{-0.495234f,-0.425347f,-0.757511f},{-0.512046f,-0.439786f,-0.737833f},{-0.528407f,-0.453839f,-0.717507f}, +{-0.544305f,-0.467493f,-0.696551f},{-0.559724f,-0.480737f,-0.674982f},{-0.574652f,-0.493558f,-0.652821f}, +{-0.589075f,-0.505946f,-0.630087f},{-0.616357f,-0.529378f,-0.582978f},{-0.629192f,-0.540401f,-0.558645f}, +{-0.641474f,-0.55095f,-0.533822f},{-0.653193f,-0.561015f,-0.508529f},{-0.664337f,-0.570587f,-0.48279f}, +{-0.684867f,-0.58822f,-0.430063f},{-0.694234f,-0.596265f,-0.403122f},{-0.702992f,-0.603786f,-0.375826f}, +{-0.711132f,-0.610777f,-0.3482f},{-0.718647f,-0.617232f,-0.320268f},{-0.725531f,-0.623145f,-0.292055f}, +{-0.731777f,-0.62851f,-0.263585f},{-0.737381f,-0.633323f,-0.234884f},{-0.742338f,-0.63758f,-0.205977f}, +{-0.746642f,-0.641277f,-0.176888f},{-0.750291f,-0.64441f,-0.147645f},{-0.75328f,-0.646978f,-0.118272f}, +{-0.755608f,-0.648978f,-0.0887941f},{-0.757272f,-0.650407f,-0.0592391f},{-0.758272f,-0.651265f,-0.0296323f}, +{-0.742338f,-0.63758f,0.205977f},{-0.88337f,-0.434227f,0.176364f},{-0.878777f,-0.430282f,0.206418f}, +{-0.844021f,-0.400431f,0.356769f},{-0.702992f,-0.603786f,0.375826f},{-0.711132f,-0.610777f,0.3482f}, +{-0.8903f,-0.440179f,0.116657f},{-0.892671f,-0.442216f,0.0870897f},{-0.983632f,-0.14841f,0.102193f}, +{-0.750291f,-0.64441f,0.147645f},{-0.75328f,-0.646978f,0.118272f},{-0.976204f,0.216125f,0.0177823f}, +{-0.943289f,0.331972f,3.41808e-016f},{-0.80211f,0.597142f,0.00650572f},{-0.974563f,0.217534f,0.0539127f}, +{-0.973095f,0.218795f,0.0722163f},{-0.985709f,-0.150194f,0.0762915f},{-0.46921f,0.883063f,-0.00650572f}, +{-0.184979f,0.982742f,-4.69192e-016f},{-0.0662783f,0.997643f,-0.0177823f},{-0.801509f,0.597657f,0.0197241f}, +{-0.800972f,0.598118f,0.0264206f},{0.574558f,0.81796f,-0.0287252f},{0.573574f,0.817114f,-0.0577667f}, +{0.2996f,0.953733f,-0.0251636f},{0.0755427f,0.997143f,-5.50975e-016f},{0.758605f,0.651551f,-9.3359e-016f}, +{0.564043f,0.825745f,-3.00566e-016f},{0.757272f,0.650407f,-0.0592414f},{-0.887205f,-0.437522f,0.146429f}, +{-0.746642f,-0.641277f,0.176888f},{0.758271f,0.651265f,-0.0296337f},{-0.731777f,-0.62851f,0.263585f}, +{-0.873412f,-0.425675f,0.236543f},{-0.867263f,-0.420393f,0.266692f},{-0.737381f,-0.633323f,0.234884f}, +{-0.860319f,-0.41443f,0.296814f},{-0.725531f,-0.623145f,0.292055f},{-0.852574f,-0.407777f,0.326857f}, +{-0.718647f,-0.617232f,0.320268f},{-0.834658f,-0.392389f,0.386494f},{-0.694234f,-0.596265f,0.403122f}, +{-0.813504f,-0.374221f,0.445162f},{-0.801723f,-0.364102f,0.473994f},{-0.664337f,-0.570587f,0.48279f}, +{-0.824484f,-0.383652f,0.415977f},{-0.629192f,-0.540401f,0.558645f},{-0.641474f,-0.55095f,0.533822f}, +{-0.775794f,-0.341832f,0.530373f},{-0.653193f,-0.561015f,0.508529f},{-0.602981f,-0.517889f,0.606799f}, +{-0.746803f,-0.316933f,0.58467f},{-0.731206f,-0.303536f,0.610904f},{-0.761673f,-0.329704f,0.557808f}, +{-0.559724f,-0.480737f,0.674982f},{-0.697922f,-0.27495f,0.661292f},{-0.544305f,-0.467493f,0.696551f}, +{-0.714903f,-0.289535f,0.636461f},{-0.495234f,-0.425347f,0.757511f},{-0.512046f,-0.439786f,0.737833f}, +{-0.643204f,-0.227954f,0.730976f},{-0.528407f,-0.453839f,0.717507f},{-0.662041f,-0.244132f,0.708591f}, +{-0.442252f,-0.379842f,0.812486f},{-0.603915f,-0.194209f,0.773026f},{-0.583538f,-0.176707f,0.792627f}, +{-0.623817f,-0.211302f,0.752465f},{-0.541517f,-0.140616f,0.828846f},{-0.385775f,-0.331335f,0.861043f}, +{-0.404961f,-0.347814f,0.845596f},{-0.423793f,-0.363987f,0.829405f},{-0.32625f,-0.28021f,0.902798f}, +{-0.346402f,-0.297518f,0.889657f},{-0.475944f,-0.0842968f,0.875426f},{-0.519956f,-0.122098f,0.845422f}, +{-0.453578f,-0.065087f,0.888837f},{-0.285105f,-0.244871f,0.926689f},{-0.305812f,-0.262656f,0.915145f}, +{-0.385546f,-0.00665599f,0.922665f},{-0.242959f,-0.208673f,0.947326f},{-0.408337f,-0.0262308f,0.912454f}, +{-0.264148f,-0.226872f,0.937419f},{-0.431028f,-0.0457197f,0.901179f},{-0.199959f,-0.171741f,0.964635f}, +{-0.362695f,0.0129701f,0.931817f},{-0.339824f,0.0326136f,0.939923f},{-0.221556f,-0.19029f,0.956401f}, +{-0.156257f,-0.134206f,0.978556f},{-0.316971f,0.0522418f,0.946995f},{-0.294173f,0.0718231f,0.95305f}, +{-0.178186f,-0.153041f,0.972023f},{-0.112006f,-0.0961995f,0.98904f},{-0.13419f,-0.115254f,0.98423f}, +{-0.271464f,0.0913273f,0.958106f},{-0.650623f,0.727251f,0.218624f},{-0.562139f,0.571757f,0.597573f}, +{-0.576025f,0.559831f,0.595638f},{-0.182173f,0.168017f,0.968805f},{-0.0449408f,-0.0385988f,0.998244f}, +{-0.204204f,0.149095f,0.967508f},{-0.0224803f,-0.0193079f,0.999561f},{-0.226448f,0.12999f,0.96531f}, +{-0.248878f,0.110725f,0.962185f},{-0.402091f,0.351064f,0.845622f},{-0.0673616f,-0.0578556f,0.99605f}, +{-0.0897231f,-0.0770615f,0.992981f},{-0.48139f,0.282956f,0.829578f},{-0.604064f,0.535749f,0.589983f}, +{-0.461418f,0.30011f,0.834882f},{-0.655702f,0.722888f,0.217917f},{-0.42174f,0.334188f,0.842884f}, +{-0.620697f,0.752953f,-0.218624f},{-0.625735f,0.748626f,-0.219122f},{-0.645585f,0.731578f,0.219122f}, +{-0.286341f,0.45048f,-0.845622f},{-0.305827f,0.433744f,-0.847547f},{-0.480343f,0.642011f,-0.597573f}, +{-0.432488f,0.503548f,-0.747926f},{-0.507751f,0.61847f,-0.599737f},{-0.325127f,0.417168f,-0.848684f}, +{-0.138591f,0.205449f,-0.968805f},{-0.304133f,0.354104f,-0.884372f},{-0.155494f,0.181042f,-0.971105f}, +{0.0224791f,0.019307f,-0.999561f},{-2.50764e-009f,2.91966e-009f,1.0f},{-0.155937f,0.181559f,0.970938f}, +{-0.521445f,0.248554f,0.816282f},{-0.562725f,-0.158831f,0.811242f},{-0.366249f,-0.314564f,0.875734f}, +{-0.498084f,-0.103313f,0.860952f},{-0.678094f,0.11401f,0.726078f},{-0.460322f,-0.395362f,0.794854f}, +{-0.477988f,-0.410535f,0.776523f},{-0.680291f,-0.259807f,0.68535f},{-0.574652f,-0.493558f,0.652821f}, +{-0.783674f,0.0233295f,0.620733f},{-0.831792f,0.340158f,0.438652f},{-0.820131f,0.350173f,0.452509f}, +{-0.589075f,-0.505946f,0.630087f},{-0.616357f,-0.529378f,0.582978f},{-0.674899f,-0.579658f,0.456627f}, +{-0.684867f,-0.58822f,0.430063f},{-0.789149f,-0.353302f,0.502416f},{-0.884264f,0.29509f,0.361938f}, +{-0.870953f,-0.0516324f,0.488646f},{-0.893469f,0.287184f,0.34531f},{-0.950583f,-0.120025f,0.286331f}, +{-0.755608f,-0.648978f,0.0887942f},{-0.651551f,0.758605f,1.22271e-018f},{-0.757272f,-0.650407f,0.059239f}, +{-0.894338f,-0.443647f,0.0577667f},{-0.988031f,-0.152189f,0.0251636f},{-0.997238f,0.0742779f,5.00783e-016f}, +{-0.758272f,-0.651265f,0.0296322f},{-0.895322f,-0.444493f,0.0287252f},{-0.901253f,-0.433294f,6.47993e-016f}, +{-0.983078f,-0.183188f,6.55067e-016f},{-0.758605f,-0.651551f,9.4456e-016f},{-0.825457f,0.564465f,2.60919e-016f}, +{-0.433008f,0.90139f,-2.0282e-016f},{-0.987169f,-0.151448f,0.0506042f},{-0.980921f,-0.146082f,0.128274f}, +{-0.977561f,-0.143196f,0.154497f},{-0.973538f,-0.13974f,0.180824f},{-0.968838f,-0.135704f,0.207214f}, +{-0.963451f,-0.131077f,0.233625f},{-0.957369f,-0.125853f,0.260012f},{-0.944446f,0.243401f,0.220857f}, +{-0.93865f,0.248379f,0.239258f},{-0.943091f,-0.11359f,0.312533f},{-0.934889f,-0.106546f,0.338573f}, +{-0.925977f,-0.0988913f,0.3644f},{-0.916358f,-0.0906299f,0.389967f},{-0.906037f,-0.0817656f,0.415224f}, +{-0.895022f,-0.072305f,0.440122f},{-0.883323f,-0.0622569f,0.464612f},{-0.857927f,-0.0404447f,0.512177f}, +{-0.844263f,-0.0287093f,0.535159f},{-0.829983f,-0.0164437f,0.557547f},{-0.815107f,-0.00366744f,0.579299f}, +{-0.799662f,0.00959806f,0.600374f},{-0.767173f,0.0375019f,0.640343f},{-0.75019f,0.0520888f,0.659168f}, +{-0.732756f,0.0670627f,0.677179f},{-0.714905f,0.0823943f,0.69435f},{-0.696673f,0.0980537f,0.710657f}, +{-0.707128f,0.678719f,0.198267f},{-0.730295f,0.427331f,0.53297f},{-0.712143f,0.674412f,0.194989f}, +{-0.659207f,0.130232f,0.740598f},{-0.640047f,0.146689f,0.754203f},{-0.620651f,0.163347f,0.766883f}, +{-0.601058f,0.180175f,0.778631f},{-0.581305f,0.197141f,0.789443f},{-0.561427f,0.214213f,0.79932f}, +{-0.541462f,0.231361f,0.808264f},{-0.501409f,0.265762f,0.823383f},{-0.618177f,0.523627f,0.586235f}, +{-0.441525f,0.317195f,0.839311f},{-0.382604f,0.367801f,0.847547f},{-0.363305f,0.384377f,0.848684f}, +{-0.29793f,0.346881f,0.889332f},{0.298738f,0.952993f,-0.0506042f},{-0.975595f,0.216648f,0.0357603f}, +{-0.971179f,0.22044f,0.0906467f},{-0.968805f,0.222479f,0.109178f},{-0.965962f,0.224921f,0.127782f}, +{-0.962641f,0.227774f,0.146431f},{-0.958834f,0.231043f,0.165095f},{-0.954536f,0.234735f,0.183742f}, +{-0.949741f,0.238853f,0.20234f},{-0.932352f,0.253788f,0.25751f},{-0.786066f,0.610921f,0.0942108f}, +{-0.783579f,0.613057f,0.100821f},{-0.925555f,0.259626f,0.275577f},{-0.918261f,0.26589f,0.293425f}, +{-0.910478f,0.272576f,0.31102f},{-0.90221f,0.279676f,0.328326f},{-0.761248f,0.632237f,0.144146f}, +{-0.510071f,0.847968f,-0.144146f},{-0.513917f,0.844665f,-0.14977f},{-0.874608f,0.303383f,0.378179f}, +{-0.864516f,0.312051f,0.394f},{-0.854004f,0.32108f,0.409371f},{-0.84309f,0.330454f,0.424264f}, +{-0.736111f,0.653826f,0.175076f},{-0.535208f,0.826378f,-0.175076f},{-0.539823f,0.822414f,-0.179515f}, +{-0.808129f,0.360481f,0.465812f},{-0.795809f,0.371062f,0.47854f},{-0.783195f,0.381897f,0.490674f}, +{-0.770311f,0.392963f,0.502197f},{-0.757182f,0.404239f,0.513095f},{-0.743835f,0.415702f,0.523356f}, +{-0.716589f,0.439103f,0.541931f},{-0.702743f,0.450995f,0.550232f},{-0.688784f,0.462984f,0.557873f}, +{-0.674737f,0.475049f,0.564853f},{-0.660628f,0.487166f,0.571173f},{-0.646483f,0.499316f,0.576839f}, +{-0.632324f,0.511476f,0.581857f},{-0.590006f,0.547823f,0.593113f},{-0.630724f,0.744341f,-0.219416f}, +{-0.548369f,0.583584f,0.598933f},{-0.534731f,0.595298f,0.599736f},{-0.431242f,0.502097f,0.749619f}, +{-0.800271f,0.59872f,0.0331634f},{-0.801887f,0.597333f,0.0130831f},{-0.799403f,0.599466f,0.0399431f}, +{-0.471917f,0.880738f,-0.0399431f},{-0.472957f,0.879844f,-0.0467496f},{-0.798362f,0.60036f,0.0467496f}, +{-0.797147f,0.601403f,0.0535724f},{-0.795755f,0.602599f,0.0604006f},{-0.794182f,0.60395f,0.0672227f}, +{-0.792428f,0.605457f,0.0740269f},{-0.790491f,0.607121f,0.0808012f},{-0.78837f,0.608942f,0.0875334f}, +{-0.780911f,0.615348f,0.107351f},{-0.490408f,0.864856f,-0.107351f},{-0.493256f,0.86241f,-0.113788f}, +{-0.778063f,0.617794f,0.113788f},{-0.775039f,0.620392f,0.120119f},{-0.771841f,0.623139f,0.126333f}, +{-0.768473f,0.626031f,0.132417f},{-0.76494f,0.629065f,0.138358f},{-0.757402f,0.63554f,0.14977f}, +{-0.753409f,0.638969f,0.155219f},{-0.749276f,0.642519f,0.160482f},{-0.74501f,0.646183f,0.165552f}, +{-0.740619f,0.649955f,0.170419f},{-0.731497f,0.65779f,0.179515f},{-0.726783f,0.661838f,0.183731f}, +{-0.72198f,0.665964f,0.187718f},{-0.717096f,0.670158f,0.191472f},{-0.702063f,0.68307f,0.201304f}, +{-0.569257f,0.797135f,-0.201304f},{-0.574363f,0.792748f,-0.2041f},{-0.696956f,0.687456f,0.2041f}, +{-0.691817f,0.69187f,0.206653f},{-0.686655f,0.696303f,0.208966f},{-0.68148f,0.700748f,0.211039f}, +{-0.6763f,0.705197f,0.212875f},{-0.671124f,0.709642f,0.214476f},{-0.665961f,0.714077f,0.215848f}, +{-0.660818f,0.718494f,0.216993f},{-0.640595f,0.735863f,0.219416f},{-0.646863f,0.753146f,-0.119748f}, +{-0.646762f,0.753028f,0.121027f},{-0.609092f,0.70917f,0.355084f},{-0.536047f,0.624123f,0.56844f}, +{-0.46981f,0.882547f,-0.0197242f},{-0.470347f,0.882086f,-0.0264206f},{-0.469433f,0.882871f,-0.013083f}, +{-0.471048f,0.881484f,-0.0331634f},{-0.474172f,0.878801f,-0.0535725f},{-0.475565f,0.877605f,-0.0604006f}, +{-0.477137f,0.876254f,-0.0672226f},{-0.0879462f,0.979032f,-0.183742f},{-0.0927413f,0.974914f,-0.20234f}, +{-0.478891f,0.874747f,-0.074027f},{-0.480829f,0.873084f,-0.0808012f},{-0.482949f,0.871262f,-0.0875334f}, +{-0.485253f,0.869283f,-0.0942108f},{-0.48774f,0.867147f,-0.100821f},{-0.496281f,0.859812f,-0.120119f}, +{-0.140272f,0.934091f,-0.328326f},{-0.149013f,0.926583f,-0.34531f},{-0.499479f,0.857065f,-0.126333f}, +{-0.502847f,0.854173f,-0.132416f},{-0.506379f,0.851139f,-0.138358f},{-0.51791f,0.841235f,-0.155219f}, +{-0.199392f,0.883313f,-0.424264f},{-0.21069f,0.87361f,-0.438652f},{-0.522044f,0.837685f,-0.160482f}, +{-0.52631f,0.834021f,-0.165552f},{-0.530701f,0.830249f,-0.170419f},{-0.544537f,0.818366f,-0.183731f}, +{-0.272171f,0.820805f,-0.502197f},{-0.2853f,0.809529f,-0.513095f},{-0.54934f,0.814241f,-0.187718f}, +{-0.554223f,0.810046f,-0.191472f},{-0.559177f,0.805792f,-0.194989f},{-0.564191f,0.801485f,-0.198267f}, +{-0.579503f,0.788334f,-0.206653f},{-0.584664f,0.783901f,-0.208966f},{-0.381854f,0.726601f,-0.571173f}, +{-0.395999f,0.714451f,-0.576839f},{-0.58984f,0.779456f,-0.211039f},{-0.595019f,0.775007f,-0.212874f}, +{-0.600195f,0.770562f,-0.214476f},{-0.605359f,0.766127f,-0.215847f},{-0.610502f,0.76171f,-0.216993f}, +{-0.615617f,0.757316f,-0.217917f},{-0.0679193f,0.996233f,-0.0539127f},{-0.069387f,0.994972f,-0.0722163f}, +{-0.0668873f,0.997119f,-0.0357603f},{-0.0713025f,0.993327f,-0.0906467f},{-0.0736771f,0.991288f,-0.109178f}, +{-0.0765202f,0.988846f,-0.127782f},{-0.0798413f,0.985994f,-0.146431f},{-0.0836479f,0.982724f,-0.165095f}, +{-0.0980359f,0.970367f,-0.220857f},{0.246457f,0.90809f,-0.338573f},{-0.103832f,0.965388f,-0.239258f}, +{-0.11013f,0.959979f,-0.25751f},{-0.116927f,0.954141f,-0.275577f},{-0.124221f,0.947877f,-0.293425f}, +{-0.132004f,0.941192f,-0.31102f},{0.169495f,0.841989f,-0.512177f},{-0.158218f,0.918677f,-0.361938f}, +{-0.167874f,0.910384f,-0.378179f},{-0.177966f,0.901716f,-0.394f},{-0.188478f,0.892688f,-0.409371f}, +{0.078742f,0.764043f,-0.640343f},{-0.222351f,0.863595f,-0.452509f},{-0.234353f,0.853287f,-0.465812f}, +{-0.246673f,0.842705f,-0.47854f},{-0.259287f,0.831871f,-0.490674f},{-0.0292248f,0.671312f,-0.740598f}, +{-0.298647f,0.798065f,-0.523356f},{-0.312187f,0.786436f,-0.53297f},{-0.325893f,0.774664f,-0.541931f}, +{-0.339739f,0.762773f,-0.550232f},{-0.353698f,0.750783f,-0.557873f},{-0.367745f,0.738719f,-0.564853f}, +{-0.410157f,0.702291f,-0.581857f},{-0.207042f,0.518588f,-0.829578f},{-0.424305f,0.69014f,-0.586235f}, +{-0.438418f,0.678019f,-0.589983f},{-0.452476f,0.665945f,-0.593113f},{-0.466457f,0.653936f,-0.595638f}, +{-0.494113f,0.630183f,-0.598933f},{-0.609586f,0.709744f,-0.353084f},{0.339059f,0.940765f,-6.77795e-016f}, +{0.297277f,0.951738f,-0.0762915f},{0.2952f,0.949954f,-0.102193f},{0.29249f,0.947626f,-0.128274f}, +{0.28913f,0.944741f,-0.154497f},{0.285106f,0.941285f,-0.180824f},{0.280406f,0.937248f,-0.207214f}, +{0.27502f,0.932622f,-0.233625f},{0.268937f,0.927398f,-0.260012f},{0.262152f,0.92157f,-0.286331f}, +{0.254659f,0.915135f,-0.312533f},{0.503721f,0.757119f,-0.415977f},{0.674898f,0.579657f,-0.45663f}, +{0.492741f,0.747688f,-0.445162f},{0.237545f,0.900436f,-0.3644f},{0.227927f,0.892174f,-0.389967f}, +{0.217606f,0.88331f,-0.415224f},{0.206591f,0.87385f,-0.440122f},{0.194892f,0.863801f,-0.464612f}, +{0.182522f,0.853177f,-0.488646f},{0.155832f,0.830254f,-0.535159f},{0.410442f,0.677003f,-0.610904f}, +{0.141551f,0.817988f,-0.557547f},{0.126675f,0.805212f,-0.579299f},{0.111231f,0.791946f,-0.600374f}, +{0.095243f,0.778215f,-0.620733f},{0.303053f,0.584769f,-0.752465f},{0.46032f,0.39536f,-0.794856f}, +{0.283151f,0.567676f,-0.773026f},{0.0617581f,0.749456f,-0.659168f},{0.0443242f,0.734482f,-0.677179f}, +{0.0264735f,0.71915f,-0.69435f},{0.008241f,0.703491f,-0.710657f},{-0.0103371f,0.687534f,-0.726078f}, +{-0.048385f,0.654856f,-0.754203f},{0.15518f,0.457764f,-0.875426f},{-0.06778f,0.638198f,-0.766883f}, +{-0.0873729f,0.62137f,-0.778631f},{-0.107127f,0.604404f,-0.789443f},{-0.127004f,0.587331f,-0.79932f}, +{-0.146969f,0.570183f,-0.808264f},{-0.166987f,0.552991f,-0.816282f},{-0.187022f,0.535783f,-0.823383f}, +{-0.227014f,0.501435f,-0.834882f},{-0.246907f,0.484349f,-0.839311f},{-0.266692f,0.467356f,-0.842884f}, +{-0.536319f,0.624439f,-0.567836f},{0.571907f,0.815682f,-0.0870897f},{0.569536f,0.813646f,-0.116657f}, +{0.566442f,0.810988f,-0.146429f},{0.562606f,0.807694f,-0.176364f},{0.558013f,0.803749f,-0.206418f}, +{0.552648f,0.799142f,-0.236543f},{0.546499f,0.79386f,-0.266692f},{0.539556f,0.787897f,-0.296814f}, +{0.53181f,0.781244f,-0.326857f},{0.523257f,0.773898f,-0.356769f},{0.513894f,0.765856f,-0.386494f}, +{0.480959f,0.737569f,-0.473994f},{0.468385f,0.726769f,-0.502416f},{0.45503f,0.715299f,-0.530373f}, +{0.440909f,0.703171f,-0.557808f},{0.426039f,0.6904f,-0.58467f},{0.60298f,0.517888f,-0.606801f}, +{0.39414f,0.663001f,-0.636461f},{0.377159f,0.648417f,-0.661292f},{0.359528f,0.633274f,-0.68535f}, +{0.341277f,0.617599f,-0.708591f},{0.322441f,0.601421f,-0.730976f},{0.262774f,0.550174f,-0.792627f}, +{0.241961f,0.532298f,-0.811242f},{0.220753f,0.514083f,-0.828846f},{0.199192f,0.495565f,-0.845422f}, +{0.17732f,0.47678f,-0.860952f},{0.346399f,0.297516f,-0.889658f},{0.132814f,0.438554f,-0.888837f}, +{0.110265f,0.419187f,-0.901179f},{0.0875737f,0.399698f,-0.912454f},{0.0647825f,0.380123f,-0.922664f}, +{0.0419318f,0.360497f,-0.931817f},{0.0190608f,0.340853f,-0.939923f},{-0.00379256f,0.321225f,-0.946995f}, +{-0.0265911f,0.301644f,-0.95305f},{-0.0493f,0.28214f,-0.958106f},{-0.0718851f,0.262741f,-0.962185f}, +{-0.0943152f,0.243477f,-0.96531f},{-0.11656f,0.224371f,-0.967508f},{0.755608f,0.648978f,-0.0887968f}, +{0.75328f,0.646978f,-0.118274f},{0.75029f,0.64441f,-0.147647f},{0.746642f,0.641277f,-0.176891f}, +{0.742337f,0.63758f,-0.205979f},{0.737381f,0.633323f,-0.234887f},{0.731777f,0.628509f,-0.263588f}, +{0.72553f,0.623144f,-0.292057f},{0.718646f,0.617231f,-0.320271f},{0.711131f,0.610777f,-0.348202f}, +{0.702991f,0.603786f,-0.375828f},{0.694233f,0.596264f,-0.403124f},{0.684866f,0.588219f,-0.430066f}, +{0.664336f,0.570586f,-0.482793f},{0.653191f,0.561014f,-0.508532f},{0.641473f,0.550949f,-0.533824f}, +{0.629191f,0.5404f,-0.558647f},{0.616356f,0.529376f,-0.58298f},{0.589074f,0.505945f,-0.630088f}, +{0.574651f,0.493557f,-0.652822f},{0.559724f,0.480736f,-0.674983f},{0.544304f,0.467493f,-0.696551f}, +{0.528407f,0.453838f,-0.717508f},{0.512045f,0.439786f,-0.737834f},{0.495233f,0.425347f,-0.757512f}, +{0.477987f,0.410534f,-0.776525f},{0.44225f,0.37984f,-0.812488f},{0.423791f,0.363986f,-0.829407f}, +{0.40496f,0.347812f,-0.845597f},{0.385773f,0.331333f,-0.861045f},{0.366247f,0.314563f,-0.875736f}, +{0.326248f,0.280208f,-0.902799f},{0.30581f,0.262654f,-0.915146f},{0.285103f,0.24487f,-0.92669f}, +{0.264146f,0.22687f,-0.93742f},{0.242957f,0.208671f,-0.947327f},{0.221554f,0.190289f,-0.956402f}, +{0.199957f,0.171739f,-0.964636f},{0.178184f,0.153039f,-0.972023f},{0.156255f,0.134204f,-0.978557f}, +{0.134188f,0.115252f,-0.984231f},{0.112004f,0.0961983f,-0.98904f},{0.0897214f,0.07706f,-0.992981f}, +{0.0673596f,0.0578539f,-0.99605f},{0.044939f,0.0385973f,-0.998244f},{0.775794f,0.341832f,-0.530373f}, +{0.761673f,0.329704f,-0.557808f},{0.629192f,0.540401f,-0.558645f},{0.641474f,0.55095f,-0.533822f}, +{0.76494f,-0.629065f,-0.138358f},{0.864516f,-0.312051f,-0.394f},{0.874608f,-0.303383f,-0.378179f}, +{0.801723f,0.364102f,-0.473994f},{0.653193f,0.561015f,-0.508529f},{0.664337f,0.570587f,-0.48279f}, +{0.789149f,0.353302f,-0.502416f},{0.674899f,0.579658f,-0.456627f},{0.684867f,0.58822f,-0.430063f}, +{0.824484f,0.383652f,-0.415977f},{0.813504f,0.374221f,-0.445162f},{0.694234f,0.596265f,-0.403122f}, +{0.834658f,0.392389f,-0.386494f},{0.844021f,0.400431f,-0.356769f},{0.702992f,0.603786f,-0.375826f}, +{0.711132f,0.610777f,-0.3482f},{0.852574f,0.407777f,-0.326857f},{0.932352f,-0.253788f,-0.25751f}, +{0.925977f,0.0988914f,-0.3644f},{0.93865f,-0.248379f,-0.239258f},{0.860319f,0.41443f,-0.296814f}, +{0.718647f,0.617232f,-0.320268f},{0.725531f,0.623145f,-0.292055f},{0.867263f,0.420393f,-0.266692f}, +{0.731777f,0.62851f,-0.263585f},{0.873412f,0.425675f,-0.236543f},{0.878777f,0.430282f,-0.206418f}, +{0.742338f,0.63758f,-0.205977f},{0.88337f,0.434227f,-0.176364f},{0.737381f,0.633323f,-0.234884f}, +{0.746642f,0.641277f,-0.176888f},{0.887205f,0.437522f,-0.146429f},{0.750291f,0.64441f,-0.147645f}, +{0.8903f,0.440179f,-0.116657f},{0.75328f,0.646978f,-0.118272f},{0.892671f,0.442216f,-0.0870897f}, +{0.985709f,0.150194f,-0.0762915f},{0.983632f,0.14841f,-0.102193f},{-0.758272f,-0.651265f,0.0296337f}, +{-0.574558f,-0.81796f,0.0287252f},{-0.2996f,-0.953733f,0.0251636f},{0.0662783f,-0.997643f,0.0177823f}, +{-0.0755427f,-0.997143f,4.44435e-016f},{-0.564043f,-0.825745f,3.04136e-016f},{-0.573574f,-0.817114f,0.0577667f}, +{-0.571907f,-0.815682f,0.0870897f},{-0.297277f,-0.951738f,0.0762915f},{0.755608f,0.648978f,-0.0887942f}, +{0.974563f,-0.217534f,-0.0539127f},{0.973095f,-0.218795f,-0.0722163f},{0.800972f,-0.598118f,-0.0264206f}, +{0.971179f,-0.22044f,-0.0906467f},{0.801509f,-0.597657f,-0.0197242f},{0.757272f,0.650407f,-0.059239f}, +{0.894338f,0.443647f,-0.0577667f},{0.997238f,-0.0742779f,-4.48371e-016f},{0.976204f,-0.216125f,-0.0177823f}, +{0.988031f,0.152189f,-0.0251636f},{0.943289f,-0.331972f,-4.29587e-016f},{0.80211f,-0.597142f,-0.00650572f}, +{0.825457f,-0.564465f,-3.05233e-016f},{0.983078f,0.183188f,-6.14496e-016f},{0.895322f,0.444493f,-0.0287252f}, +{0.901253f,0.433294f,-9.46059e-016f},{0.758272f,0.651265f,-0.0296322f},{0.46921f,-0.883063f,0.00650572f}, +{0.184979f,-0.982742f,5.48296e-016f},{0.616357f,0.529378f,-0.582978f},{0.602981f,0.517889f,-0.606799f}, +{0.746803f,0.316933f,-0.58467f},{0.731206f,0.303536f,-0.610904f},{0.589075f,0.505946f,-0.630087f}, +{0.574652f,0.493558f,-0.652821f},{0.714903f,0.289535f,-0.636461f},{0.697922f,0.27495f,-0.661292f}, +{0.559724f,0.480737f,-0.674982f},{0.544305f,0.467493f,-0.696551f},{0.680291f,0.259807f,-0.68535f}, +{0.528407f,0.453839f,-0.717507f},{0.662041f,0.244132f,-0.708591f},{0.75019f,-0.0520889f,-0.659168f}, +{0.820131f,-0.350173f,-0.452509f},{0.808129f,-0.360481f,-0.465812f},{0.643204f,0.227954f,-0.730976f}, +{0.512046f,0.439786f,-0.737833f},{0.623817f,0.211302f,-0.752465f},{0.495234f,0.425347f,-0.757511f}, +{0.460322f,0.395362f,-0.794854f},{0.477988f,0.410535f,-0.776523f},{0.603915f,0.194209f,-0.773026f}, +{0.442252f,0.379842f,-0.812486f},{0.583538f,0.176707f,-0.792627f},{0.423793f,0.363987f,-0.829405f}, +{0.404961f,0.347814f,-0.845596f},{0.562725f,0.158831f,-0.811242f},{0.541517f,0.140616f,-0.828846f}, +{0.385775f,0.331335f,-0.861043f},{0.519956f,0.122098f,-0.845422f},{0.716589f,-0.439103f,-0.541931f}, +{0.707128f,-0.678719f,-0.198267f},{0.702743f,-0.450995f,-0.550232f},{0.366249f,0.314564f,-0.875734f}, +{0.498084f,0.103313f,-0.860952f},{0.475944f,0.0842968f,-0.875426f},{0.346402f,0.297518f,-0.889657f}, +{0.32625f,0.28021f,-0.902798f},{0.305812f,0.262656f,-0.915145f},{0.285105f,0.244871f,-0.926689f}, +{0.453578f,0.065087f,-0.888837f},{0.431028f,0.0457196f,-0.901179f},{0.264148f,0.226872f,-0.937419f}, +{0.408337f,0.0262308f,-0.912454f},{0.242959f,0.208673f,-0.947326f},{0.221556f,0.19029f,-0.956401f}, +{0.385546f,0.00665601f,-0.922665f},{0.362695f,-0.0129701f,-0.931817f},{0.199959f,0.171741f,-0.964635f}, +{0.339824f,-0.0326136f,-0.939923f},{0.48139f,-0.282956f,-0.829578f},{0.316971f,-0.0522418f,-0.946995f}, +{0.501409f,-0.265762f,-0.823383f},{0.178186f,0.153041f,-0.972023f},{0.294173f,-0.0718231f,-0.95305f}, +{0.156257f,0.134206f,-0.978556f},{0.248878f,-0.110725f,-0.962185f},{0.441525f,-0.317195f,-0.839311f}, +{0.42174f,-0.334188f,-0.842884f},{0.13419f,0.115253f,-0.98423f},{0.650623f,-0.727251f,-0.218624f}, +{0.620697f,-0.752953f,0.218624f},{0.645585f,-0.731578f,-0.219122f},{0.665961f,-0.714077f,-0.215848f}, +{0.660818f,-0.718494f,-0.216993f},{0.590006f,-0.547823f,-0.593113f},{0.286341f,-0.45048f,0.845622f}, +{0.480343f,-0.642011f,0.597573f},{0.266692f,-0.467356f,0.842884f},{0.325127f,-0.417168f,0.848684f}, +{0.432488f,-0.503548f,0.747926f},{0.507751f,-0.61847f,0.599737f},{0.548369f,-0.583584f,-0.598933f}, +{0.562139f,-0.571757f,-0.597573f},{0.304133f,-0.354104f,0.884372f},{0.138591f,-0.205449f,0.968805f}, +{0.155494f,-0.181043f,0.971105f},{0.576025f,-0.559831f,-0.595638f},{0.655703f,-0.722888f,-0.217916f}, +{0.382604f,-0.367801f,-0.847547f},{0.402091f,-0.351064f,-0.845622f},{-0.0224792f,-0.0193069f,0.999561f}, +{0.271464f,-0.0913273f,-0.958106f},{0.112006f,0.0961995f,-0.98904f},{0.0897231f,0.0770615f,-0.992981f}, +{0.226448f,-0.12999f,-0.96531f},{0.204204f,-0.149095f,-0.967508f},{0.0673616f,0.0578556f,-0.99605f}, +{0.182173f,-0.168017f,-0.968805f},{0.0224803f,0.0193079f,-0.999561f},{0.0449408f,0.0385988f,-0.998244f}, +{0.155937f,-0.181559f,-0.970938f},{0.433008f,-0.90139f,1.81967e-016f},{0.987169f,0.151448f,-0.0506042f}, +{0.980921f,0.146082f,-0.128274f},{0.977561f,0.143196f,-0.154497f},{0.973538f,0.13974f,-0.180824f}, +{0.968838f,0.135704f,-0.207214f},{0.963451f,0.131077f,-0.233625f},{0.957369f,0.125853f,-0.260012f}, +{0.950583f,0.120025f,-0.286331f},{0.943091f,0.11359f,-0.312533f},{0.934889f,0.106546f,-0.338573f}, +{0.916358f,0.0906299f,-0.389967f},{0.906037f,0.0817656f,-0.415224f},{0.895022f,0.072305f,-0.440122f}, +{0.883323f,0.0622569f,-0.464612f},{0.870953f,0.0516324f,-0.488646f},{0.857927f,0.0404447f,-0.512177f}, +{0.844263f,0.0287093f,-0.535159f},{0.829983f,0.0164437f,-0.557547f},{0.815107f,0.00366744f,-0.579299f}, +{0.799662f,-0.00959801f,-0.600374f},{0.783674f,-0.0233295f,-0.620733f},{0.767173f,-0.0375019f,-0.640343f}, +{0.732756f,-0.0670627f,-0.677179f},{0.714905f,-0.0823942f,-0.69435f},{0.696673f,-0.0980537f,-0.710657f}, +{0.678094f,-0.11401f,-0.726078f},{0.659207f,-0.130232f,-0.740598f},{0.640047f,-0.146689f,-0.754203f}, +{0.620651f,-0.163347f,-0.766883f},{0.601058f,-0.180175f,-0.778631f},{0.581305f,-0.197141f,-0.789443f}, +{0.561427f,-0.214213f,-0.79932f},{0.541462f,-0.231361f,-0.808264f},{0.521445f,-0.248554f,-0.816282f}, +{0.461418f,-0.30011f,-0.834882f},{0.604064f,-0.535749f,-0.589983f},{0.363305f,-0.384377f,-0.848684f}, +{0.29793f,-0.346881f,-0.889332f},{-0.757272f,-0.650407f,0.0592414f},{0.975595f,-0.216648f,-0.0357603f}, +{0.968805f,-0.222479f,-0.109178f},{0.965962f,-0.224921f,-0.127782f},{0.962641f,-0.227774f,-0.146431f}, +{0.958834f,-0.231043f,-0.165095f},{0.954536f,-0.234735f,-0.183742f},{0.949741f,-0.238853f,-0.20234f}, +{0.944446f,-0.243401f,-0.220857f},{0.918261f,-0.26589f,-0.293425f},{0.925555f,-0.259626f,-0.275577f}, +{0.783579f,-0.613057f,-0.100821f},{0.910478f,-0.272576f,-0.31102f},{0.90221f,-0.279676f,-0.328326f}, +{0.893469f,-0.287184f,-0.34531f},{0.884264f,-0.29509f,-0.361938f},{0.854004f,-0.32108f,-0.409371f}, +{0.84309f,-0.330454f,-0.424264f},{0.831792f,-0.340158f,-0.438652f},{0.731496f,-0.65779f,-0.179515f}, +{0.539823f,-0.822414f,0.179515f},{0.726783f,-0.661838f,-0.183731f},{0.795809f,-0.371062f,-0.47854f}, +{0.783195f,-0.381897f,-0.490674f},{0.770311f,-0.392963f,-0.502197f},{0.757182f,-0.404239f,-0.513095f}, +{0.743835f,-0.415702f,-0.523356f},{0.730295f,-0.427331f,-0.53297f},{0.688784f,-0.462984f,-0.557873f}, +{0.674737f,-0.475049f,-0.564853f},{0.660628f,-0.487166f,-0.571173f},{0.646483f,-0.499316f,-0.576839f}, +{0.632324f,-0.511476f,-0.581857f},{0.618177f,-0.523627f,-0.586235f},{0.646762f,-0.753028f,-0.121027f}, +{0.640595f,-0.735863f,-0.219416f},{0.630724f,-0.744341f,0.219416f},{0.534731f,-0.595298f,-0.599736f}, +{0.431242f,-0.502097f,-0.749619f},{0.651551f,-0.758605f,1.22271e-018f},{0.801887f,-0.597333f,-0.013083f}, +{0.800271f,-0.59872f,-0.0331634f},{0.799403f,-0.599466f,-0.0399431f},{0.474172f,-0.878801f,0.0535724f}, +{0.795755f,-0.6026f,-0.0604006f},{0.797147f,-0.601403f,-0.0535725f},{0.798362f,-0.60036f,-0.0467496f}, +{0.794182f,-0.60395f,-0.0672227f},{0.792428f,-0.605457f,-0.0740269f},{0.790491f,-0.607121f,-0.0808013f}, +{0.78837f,-0.608942f,-0.0875334f},{0.786066f,-0.610921f,-0.0942108f},{0.493256f,-0.86241f,0.113788f}, +{0.775039f,-0.620392f,-0.120119f},{0.778063f,-0.617794f,-0.113788f},{0.780911f,-0.615348f,-0.107351f}, +{0.771841f,-0.623139f,-0.126333f},{0.768473f,-0.626031f,-0.132417f},{0.513917f,-0.844665f,0.14977f}, +{0.753409f,-0.638969f,-0.155219f},{0.757402f,-0.63554f,-0.14977f},{0.761248f,-0.632237f,-0.144146f}, +{0.749276f,-0.642519f,-0.160482f},{0.74501f,-0.646183f,-0.165552f},{0.740619f,-0.649955f,-0.170419f}, +{0.736112f,-0.653826f,-0.175076f},{0.72198f,-0.665964f,-0.187718f},{0.717096f,-0.670158f,-0.191472f}, +{0.712143f,-0.674412f,-0.194989f},{0.574363f,-0.792748f,0.2041f},{0.691817f,-0.69187f,-0.206653f}, +{0.696956f,-0.687456f,-0.2041f},{0.702063f,-0.68307f,-0.201304f},{0.686655f,-0.696303f,-0.208966f}, +{0.68148f,-0.700748f,-0.211039f},{0.6763f,-0.705197f,-0.212874f},{0.671124f,-0.709642f,-0.214476f}, +{0.494113f,-0.630183f,0.598933f},{0.615617f,-0.757316f,0.217917f},{0.609092f,-0.70917f,-0.355084f}, +{0.536047f,-0.624123f,-0.56844f},{0.46981f,-0.882547f,0.0197241f},{0.469433f,-0.882871f,0.0130831f}, +{0.470347f,-0.882086f,0.0264206f},{0.471048f,-0.881484f,0.0331634f},{0.471917f,-0.880738f,0.0399431f}, +{0.472957f,-0.879844f,0.0467496f},{0.475565f,-0.877605f,0.0604006f},{0.480829f,-0.873084f,0.0808012f}, +{0.478891f,-0.874747f,0.074027f},{0.0927413f,-0.974914f,0.20234f},{0.477137f,-0.876254f,0.0672226f}, +{0.482949f,-0.871262f,0.0875334f},{0.485253f,-0.869283f,0.0942108f},{0.48774f,-0.867147f,0.100821f}, +{0.490408f,-0.864856f,0.107351f},{-0.169495f,-0.841989f,0.512177f},{0.158218f,-0.918677f,0.361938f}, +{-0.182522f,-0.853177f,0.488646f},{0.496281f,-0.859812f,0.120119f},{0.499479f,-0.857065f,0.126333f}, +{0.502847f,-0.854173f,0.132416f},{0.506379f,-0.851139f,0.138358f},{0.510071f,-0.847968f,0.144146f}, +{-0.078742f,-0.764043f,0.640343f},{0.222351f,-0.863595f,0.452509f},{-0.095243f,-0.778215f,0.620733f}, +{0.51791f,-0.841235f,0.155219f},{0.522044f,-0.837685f,0.160482f},{0.52631f,-0.834021f,0.165552f}, +{0.530701f,-0.830249f,0.170419f},{0.535208f,-0.826378f,0.175076f},{0.554223f,-0.810046f,0.191472f}, +{0.54934f,-0.814241f,0.187718f},{0.2853f,-0.809529f,0.513095f},{0.544537f,-0.818366f,0.183731f}, +{0.559177f,-0.805792f,0.194989f},{0.564191f,-0.801485f,0.198267f},{0.569257f,-0.797135f,0.201304f}, +{0.579503f,-0.788334f,0.206653f},{0.595019f,-0.775007f,0.212874f},{0.58984f,-0.779456f,0.211039f}, +{0.395999f,-0.714451f,0.576839f},{0.584664f,-0.783901f,0.208966f},{0.600195f,-0.770562f,0.214476f}, +{0.605359f,-0.766127f,0.215847f},{0.610502f,-0.76171f,0.216993f},{0.466457f,-0.653936f,0.595638f}, +{0.625735f,-0.748626f,0.219122f},{0.0679193f,-0.996233f,0.0539127f},{0.0668873f,-0.997119f,0.0357603f}, +{0.0693872f,-0.994972f,0.0722163f},{0.0713027f,-0.993327f,0.0906467f},{0.0736769f,-0.991288f,0.109178f}, +{0.0765202f,-0.988846f,0.127782f},{0.0798415f,-0.985994f,0.146431f},{0.0836479f,-0.982724f,0.165095f}, +{0.0879462f,-0.979032f,0.183742f},{-0.254659f,-0.915135f,0.312533f},{-0.246457f,-0.90809f,0.338573f}, +{0.103832f,-0.965388f,0.239258f},{0.0980359f,-0.970367f,0.220857f},{0.11013f,-0.959979f,0.257509f}, +{0.116927f,-0.954141f,0.275577f},{0.12422f,-0.947877f,0.293425f},{0.132004f,-0.941192f,0.31102f}, +{0.140272f,-0.934091f,0.328326f},{0.149013f,-0.926583f,0.34531f},{0.167874f,-0.910384f,0.378179f}, +{0.177966f,-0.901716f,0.394f},{0.188478f,-0.892688f,0.409371f},{0.199392f,-0.883313f,0.424264f}, +{0.21069f,-0.87361f,0.438652f},{0.234353f,-0.853287f,0.465812f},{0.246673f,-0.842705f,0.47854f}, +{0.259287f,-0.831871f,0.490674f},{0.272171f,-0.820805f,0.502197f},{0.0292248f,-0.671312f,0.740598f}, +{0.0483848f,-0.654856f,0.754203f},{0.312187f,-0.786436f,0.53297f},{0.298647f,-0.798065f,0.523356f}, +{0.325893f,-0.774664f,0.541931f},{0.339739f,-0.762773f,0.550232f},{0.353698f,-0.750783f,0.557873f}, +{0.367745f,-0.738719f,0.564853f},{0.381854f,-0.726601f,0.571173f},{0.410157f,-0.702291f,0.581857f}, +{0.207042f,-0.518588f,0.829578f},{0.227014f,-0.501435f,0.834882f},{0.438418f,-0.678019f,0.589983f}, +{0.424305f,-0.69014f,0.586235f},{0.452476f,-0.665945f,0.593113f},{0.609586f,-0.709744f,0.353084f}, +{0.646863f,-0.753146f,0.119748f},{-0.339059f,-0.940765f,5.47231e-016f},{-0.298738f,-0.952993f,0.0506042f}, +{-0.2952f,-0.949954f,0.102193f},{-0.29249f,-0.947626f,0.128274f},{-0.569536f,-0.813646f,0.116657f}, +{-0.28913f,-0.944741f,0.154497f},{-0.285106f,-0.941285f,0.180824f},{-0.280406f,-0.937248f,0.207214f}, +{-0.27502f,-0.932622f,0.233625f},{-0.268937f,-0.927398f,0.260012f},{-0.262152f,-0.92157f,0.286331f}, +{-0.674898f,-0.579657f,0.45663f},{-0.492741f,-0.747688f,0.445162f},{-0.503721f,-0.757119f,0.415977f}, +{-0.237545f,-0.900436f,0.3644f},{-0.227927f,-0.892174f,0.389967f},{-0.217606f,-0.88331f,0.415224f}, +{-0.206591f,-0.87385f,0.440122f},{-0.194892f,-0.863801f,0.464612f},{-0.410442f,-0.677003f,0.610904f}, +{-0.155832f,-0.830254f,0.535159f},{-0.426039f,-0.6904f,0.58467f},{-0.141551f,-0.817988f,0.557547f}, +{-0.126676f,-0.805212f,0.579299f},{-0.11123f,-0.791947f,0.600374f},{-0.303053f,-0.584769f,0.752465f}, +{-0.46032f,-0.39536f,0.794856f},{-0.283151f,-0.567676f,0.773026f},{-0.0617581f,-0.749456f,0.659168f}, +{-0.0443242f,-0.734482f,0.677179f},{-0.0264735f,-0.71915f,0.69435f},{-0.008241f,-0.703491f,0.710657f}, +{0.0103371f,-0.687534f,0.726078f},{-0.15518f,-0.457764f,0.875426f},{0.0677801f,-0.638198f,0.766883f}, +{-0.177321f,-0.476779f,0.860952f},{0.0873729f,-0.62137f,0.778631f},{0.107127f,-0.604404f,0.789443f}, +{0.127004f,-0.587331f,0.79932f},{0.146969f,-0.570183f,0.808264f},{0.166987f,-0.552991f,0.816282f}, +{0.187022f,-0.535783f,0.823383f},{0.246907f,-0.484349f,0.839311f},{0.11656f,-0.224372f,0.967508f}, +{0.0943152f,-0.243477f,0.96531f},{0.305827f,-0.433744f,0.847547f},{0.536319f,-0.624439f,0.567837f}, +{-0.566442f,-0.810988f,0.146429f},{-0.562606f,-0.807694f,0.176364f},{-0.558013f,-0.803749f,0.206418f}, +{-0.552648f,-0.799142f,0.236543f},{-0.546499f,-0.79386f,0.266692f},{-0.539556f,-0.787897f,0.296814f}, +{-0.53181f,-0.781244f,0.326857f},{-0.523257f,-0.773898f,0.356769f},{-0.513894f,-0.765856f,0.386494f}, +{-0.480959f,-0.737569f,0.473994f},{-0.468385f,-0.726769f,0.502416f},{-0.45503f,-0.715299f,0.530373f}, +{-0.440909f,-0.703171f,0.557808f},{-0.60298f,-0.517888f,0.606801f},{-0.39414f,-0.663001f,0.636461f}, +{-0.377159f,-0.648417f,0.661292f},{-0.359528f,-0.633274f,0.68535f},{-0.341277f,-0.617599f,0.708591f}, +{-0.322441f,-0.601421f,0.730976f},{-0.262774f,-0.550174f,0.792627f},{-0.241961f,-0.532298f,0.811242f}, +{-0.220753f,-0.514083f,0.828846f},{-0.199192f,-0.495565f,0.845422f},{-0.346399f,-0.297516f,0.889658f}, +{-0.132814f,-0.438554f,0.888837f},{-0.110264f,-0.419187f,0.901179f},{-0.0875737f,-0.399698f,0.912454f}, +{-0.0647826f,-0.380123f,0.922665f},{-0.0419317f,-0.360497f,0.931817f},{-0.0190608f,-0.340853f,0.939923f}, +{0.00379247f,-0.321225f,0.946995f},{0.0265911f,-0.301644f,0.95305f},{0.0493001f,-0.28214f,0.958106f}, +{0.0718852f,-0.262742f,0.962185f},{-0.755608f,-0.648977f,0.0887968f},{-0.75328f,-0.646978f,0.118274f}, +{-0.75029f,-0.64441f,0.147647f},{-0.746642f,-0.641277f,0.176891f},{-0.742337f,-0.63758f,0.205979f}, +{-0.737381f,-0.633323f,0.234887f},{-0.731777f,-0.628509f,0.263588f},{-0.72553f,-0.623144f,0.292057f}, +{-0.718646f,-0.617231f,0.320271f},{-0.711131f,-0.610777f,0.348202f},{-0.702991f,-0.603786f,0.375828f}, +{-0.694233f,-0.596264f,0.403124f},{-0.684866f,-0.588219f,0.430066f},{-0.664336f,-0.570586f,0.482793f}, +{-0.653191f,-0.561014f,0.508532f},{-0.641473f,-0.550949f,0.533824f},{-0.629191f,-0.5404f,0.558647f}, +{-0.616356f,-0.529376f,0.58298f},{-0.589074f,-0.505945f,0.630088f},{-0.574651f,-0.493557f,0.652822f}, +{-0.559723f,-0.480736f,0.674983f},{-0.544304f,-0.467493f,0.696551f},{-0.528406f,-0.453838f,0.717508f}, +{-0.512045f,-0.439786f,0.737834f},{-0.495233f,-0.425347f,0.757512f},{-0.477987f,-0.410534f,0.776525f}, +{-0.44225f,-0.37984f,0.812488f},{-0.423791f,-0.363986f,0.829407f},{-0.40496f,-0.347812f,0.845597f}, +{-0.385773f,-0.331333f,0.861045f},{-0.366247f,-0.314563f,0.875736f},{-0.326248f,-0.280208f,0.902799f}, +{-0.30581f,-0.262654f,0.915146f},{-0.285103f,-0.24487f,0.92669f},{-0.264146f,-0.22687f,0.93742f}, +{-0.242957f,-0.208671f,0.947327f},{-0.221554f,-0.190289f,0.956402f},{-0.199957f,-0.171739f,0.964636f}, +{-0.178184f,-0.153039f,0.972023f},{-0.156255f,-0.134204f,0.978557f},{-0.134188f,-0.115252f,0.984231f}, +{-0.112004f,-0.0961983f,0.98904f},{-0.0897214f,-0.07706f,0.992981f},{-0.0673596f,-0.0578539f,0.99605f}, +{-0.044939f,-0.0385973f,0.998244f},{0.222351f,-0.863595f,-0.452509f},{0.234353f,-0.853287f,-0.465812f}, +{0.530701f,-0.830249f,-0.170419f},{-0.220753f,-0.514083f,-0.828846f},{-0.40496f,-0.347812f,-0.845597f}, +{-0.385773f,-0.331333f,-0.861045f},{-0.241961f,-0.532298f,-0.811242f},{-0.199192f,-0.495565f,-0.845422f}, +{-0.366247f,-0.314563f,-0.875736f},{-0.17732f,-0.47678f,-0.860952f},{-0.30581f,-0.262654f,-0.915146f}, +{-0.15518f,-0.457764f,-0.875426f},{-0.326248f,-0.280208f,-0.902799f},{-0.346399f,-0.297516f,-0.889658f}, +{-0.285103f,-0.24487f,-0.92669f},{-0.132814f,-0.438554f,-0.888837f},{-0.423791f,-0.363986f,-0.829407f}, +{-0.110265f,-0.419187f,-0.901179f},{-0.264146f,-0.22687f,-0.93742f},{-0.0875736f,-0.399698f,-0.912454f}, +{0.06778f,-0.638198f,-0.766883f},{0.339739f,-0.762773f,-0.550232f},{0.325893f,-0.774664f,-0.541931f}, +{-0.0647826f,-0.380123f,-0.922665f},{-0.242957f,-0.208671f,-0.947327f},{-0.0419318f,-0.360497f,-0.931817f}, +{-0.221554f,-0.190289f,-0.956402f},{-0.199957f,-0.171739f,-0.964636f},{-0.0190607f,-0.340853f,-0.939923f}, +{-0.178184f,-0.153039f,-0.972023f},{-0.156255f,-0.134204f,-0.978557f},{-0.134188f,-0.115252f,-0.984231f}, +{0.0265912f,-0.301644f,-0.95305f},{0.0037925f,-0.321225f,-0.946995f},{-0.112004f,-0.0961983f,-0.98904f}, +{0.0492999f,-0.28214f,-0.958106f},{-0.0897213f,-0.07706f,-0.992981f},{0.0718852f,-0.262742f,-0.962185f}, +{0.155937f,-0.181559f,0.970938f},{0.0224803f,0.0193079f,0.999561f},{0.0943152f,-0.243477f,-0.96531f}, +{0.182173f,-0.168017f,0.968805f},{0.286341f,-0.45048f,-0.845622f},{0.266692f,-0.467356f,-0.842884f}, +{0.226448f,-0.12999f,0.96531f},{0.402091f,-0.351065f,0.845622f},{0.204204f,-0.149095f,0.967508f}, +{0.615617f,-0.757316f,-0.217916f},{0.452476f,-0.665945f,-0.593113f},{0.466457f,-0.653936f,-0.595638f}, +{0.534731f,-0.595298f,0.599736f},{0.640595f,-0.735863f,0.219416f},{0.609092f,-0.70917f,0.355084f}, +{0.431242f,-0.502097f,0.749619f},{0.363305f,-0.384377f,0.848684f},{-0.0673597f,-0.0578539f,-0.99605f}, +{0.480343f,-0.642011f,-0.597573f},{0.646762f,-0.753028f,0.121027f},{0.630724f,-0.744341f,-0.219416f}, +{0.138591f,-0.205449f,-0.968805f},{0.304133f,-0.354104f,-0.884372f},{0.325126f,-0.417168f,-0.848684f}, +{-0.044939f,-0.0385972f,-0.998244f},{0.11656f,-0.224371f,-0.967508f},{0.507751f,-0.61847f,-0.599736f}, +{0.609586f,-0.709744f,-0.353084f},{0.536319f,-0.624439f,-0.567836f},{0.646863f,-0.753146f,-0.119748f}, +{0.155494f,-0.181042f,-0.971105f},{-0.0224791f,-0.0193069f,-0.999561f},{0.620697f,-0.752953f,-0.218624f}, +{-0.262774f,-0.550174f,-0.792627f},{-0.44225f,-0.37984f,-0.812488f},{-0.283151f,-0.567676f,-0.773026f}, +{-0.303053f,-0.584769f,-0.752465f},{-0.46032f,-0.39536f,-0.794856f},{-0.477987f,-0.410534f,-0.776525f}, +{-0.495233f,-0.425347f,-0.757512f},{-0.512045f,-0.439786f,-0.737834f},{-0.322441f,-0.601421f,-0.730976f}, +{-0.341277f,-0.617599f,-0.708591f},{-0.528407f,-0.453838f,-0.717508f},{-0.359528f,-0.633274f,-0.68535f}, +{-0.544304f,-0.467493f,-0.696551f},{-0.377159f,-0.648417f,-0.661292f},{-0.155832f,-0.830254f,-0.535159f}, +{0.177966f,-0.901716f,-0.394f},{0.167874f,-0.910384f,-0.378179f},{-0.39414f,-0.663002f,-0.636461f}, +{-0.559724f,-0.480736f,-0.674983f},{-0.410442f,-0.677003f,-0.610904f},{-0.574651f,-0.493557f,-0.652822f}, +{-0.60298f,-0.517888f,-0.606801f},{-0.589074f,-0.505945f,-0.630089f},{-0.426039f,-0.6904f,-0.58467f}, +{-0.616356f,-0.529376f,-0.58298f},{-0.440909f,-0.703171f,-0.557808f},{-0.629191f,-0.5404f,-0.558647f}, +{-0.641473f,-0.550949f,-0.533824f},{-0.45503f,-0.715299f,-0.530373f},{-0.468385f,-0.726769f,-0.502416f}, +{-0.653191f,-0.561014f,-0.508532f},{-0.480959f,-0.737569f,-0.473994f},{0.11013f,-0.959979f,-0.25751f}, +{0.485253f,-0.869283f,-0.0942108f},{0.103832f,-0.965388f,-0.239258f},{-0.664336f,-0.570586f,-0.482793f}, +{-0.492741f,-0.747688f,-0.445162f},{-0.503721f,-0.757119f,-0.415977f},{-0.674898f,-0.579657f,-0.45663f}, +{-0.684866f,-0.588219f,-0.430066f},{-0.694233f,-0.596264f,-0.403124f},{-0.702991f,-0.603786f,-0.375828f}, +{-0.513894f,-0.765856f,-0.386494f},{-0.523257f,-0.773898f,-0.356769f},{-0.711131f,-0.610777f,-0.348202f}, +{-0.53181f,-0.781244f,-0.326857f},{-0.718646f,-0.617231f,-0.32027f},{-0.72553f,-0.623144f,-0.292057f}, +{-0.539556f,-0.787897f,-0.296814f},{-0.546499f,-0.79386f,-0.266692f},{-0.731777f,-0.628509f,-0.263588f}, +{-0.552648f,-0.799142f,-0.236543f},{-0.285106f,-0.941285f,-0.180824f},{-0.558013f,-0.803749f,-0.206418f}, +{-0.280406f,-0.937248f,-0.207214f},{-0.737381f,-0.633323f,-0.234887f},{-0.562606f,-0.807694f,-0.176364f}, +{-0.742337f,-0.63758f,-0.205979f},{0.0662782f,-0.997643f,-0.0177823f},{0.469433f,-0.882871f,-0.0130831f}, +{0.46921f,-0.883063f,-0.00650573f},{-0.746642f,-0.641277f,-0.176891f},{0.974563f,-0.217534f,0.0539127f}, +{0.801509f,-0.597657f,0.0197241f},{0.973095f,-0.218795f,0.0722163f},{-0.292489f,-0.947626f,-0.128274f}, +{-0.2952f,-0.949955f,-0.102193f},{-0.569536f,-0.813646f,-0.116657f},{0.985709f,0.150194f,0.0762915f}, +{0.983632f,0.14841f,0.102193f},{0.988031f,0.152188f,0.0251637f},{0.997238f,-0.0742779f,1.11285e-016f}, +{0.976204f,-0.216125f,0.0177823f},{0.470347f,-0.882086f,-0.0264206f},{0.0679194f,-0.996233f,-0.0539127f}, +{0.069387f,-0.994972f,-0.0722163f},{0.895322f,0.444493f,0.0287253f},{0.983078f,0.183188f,4.07949e-016f}, +{0.471048f,-0.881484f,-0.0331634f},{0.0713026f,-0.993327f,-0.0906466f},{0.471917f,-0.880738f,-0.0399431f}, +{0.901253f,0.433294f,3.52919e-035f},{-0.75029f,-0.64441f,-0.147647f},{-0.566442f,-0.810988f,-0.146429f}, +{-0.573574f,-0.817114f,-0.0577667f},{-0.571907f,-0.815682f,-0.0870897f},{-0.297277f,-0.951738f,-0.0762915f}, +{-0.75328f,-0.646978f,-0.118274f},{-0.755608f,-0.648977f,-0.0887967f},{-0.757272f,-0.650407f,-0.0592414f}, +{-0.758271f,-0.651265f,-0.0296338f},{-0.574558f,-0.81796f,-0.0287253f},{0.432488f,-0.503548f,-0.747926f}, +{0.305827f,-0.433744f,-0.847547f},{0.246907f,-0.484349f,-0.839311f},{0.227014f,-0.501435f,-0.834882f}, +{0.207042f,-0.518588f,-0.829578f},{0.187022f,-0.535783f,-0.823383f},{0.166987f,-0.552991f,-0.816282f}, +{0.146969f,-0.570184f,-0.808264f},{0.127004f,-0.587331f,-0.79932f},{0.107127f,-0.604404f,-0.789443f}, +{0.087373f,-0.62137f,-0.778631f},{0.0483849f,-0.654856f,-0.754203f},{0.0292249f,-0.671312f,-0.740598f}, +{0.0103372f,-0.687534f,-0.726078f},{-0.00824112f,-0.703491f,-0.710657f},{-0.0264736f,-0.71915f,-0.69435f}, +{-0.0443241f,-0.734482f,-0.677179f},{-0.0617582f,-0.749456f,-0.659168f},{-0.0787419f,-0.764043f,-0.640343f}, +{-0.0952429f,-0.778215f,-0.620734f},{-0.111231f,-0.791946f,-0.600374f},{-0.126676f,-0.805212f,-0.579299f}, +{-0.141551f,-0.817988f,-0.557547f},{-0.169496f,-0.841989f,-0.512177f},{-0.182522f,-0.853177f,-0.488646f}, +{-0.194892f,-0.863801f,-0.464612f},{-0.206591f,-0.87385f,-0.440122f},{-0.217606f,-0.88331f,-0.415224f}, +{-0.227926f,-0.892174f,-0.389967f},{-0.237545f,-0.900436f,-0.3644f},{-0.246457f,-0.90809f,-0.338573f}, +{-0.254659f,-0.915135f,-0.312533f},{-0.262152f,-0.92157f,-0.286331f},{-0.268937f,-0.927398f,-0.260012f}, +{-0.27502f,-0.932622f,-0.233625f},{-0.28913f,-0.944741f,-0.154497f},{0.073677f,-0.991288f,-0.109178f}, +{-0.2996f,-0.953733f,-0.0251637f},{-0.298737f,-0.952993f,-0.0506043f},{-0.339059f,-0.940765f,-2.28355e-016f}, +{-0.564043f,-0.825745f,-3.01839e-016f},{0.536047f,-0.624123f,0.56844f},{0.494113f,-0.630183f,-0.598933f}, +{0.438418f,-0.678019f,-0.589983f},{0.424305f,-0.69014f,-0.586235f},{0.410158f,-0.702291f,-0.581857f}, +{0.395999f,-0.714451f,-0.576839f},{0.381854f,-0.726601f,-0.571173f},{0.367745f,-0.738719f,-0.564853f}, +{0.353698f,-0.750783f,-0.557873f},{0.298647f,-0.798065f,-0.523356f},{0.312187f,-0.786436f,-0.53297f}, +{0.559177f,-0.805792f,-0.194989f},{0.2853f,-0.809529f,-0.513095f},{0.272171f,-0.820805f,-0.502197f}, +{0.259287f,-0.831871f,-0.490674f},{0.246673f,-0.842705f,-0.47854f},{0.21069f,-0.87361f,-0.438652f}, +{0.199392f,-0.883313f,-0.424264f},{0.188478f,-0.892688f,-0.409371f},{0.499479f,-0.857065f,-0.126333f}, +{0.771841f,-0.623139f,0.126333f},{0.496281f,-0.859812f,-0.120119f},{0.158218f,-0.918677f,-0.361938f}, +{0.149013f,-0.926583f,-0.34531f},{0.140272f,-0.934091f,-0.328326f},{0.132004f,-0.941192f,-0.31102f}, +{0.124221f,-0.947877f,-0.293425f},{0.116927f,-0.954141f,-0.275577f},{0.0980359f,-0.970367f,-0.220857f}, +{0.0927412f,-0.974914f,-0.20234f},{0.0879463f,-0.979032f,-0.183742f},{0.0836479f,-0.982724f,-0.165095f}, +{0.0798414f,-0.985994f,-0.146431f},{0.0765202f,-0.988846f,-0.127782f},{0.0668873f,-0.997119f,-0.0357604f}, +{0.46981f,-0.882547f,-0.0197241f},{-0.0755429f,-0.997143f,-2.89047e-016f},{0.0449408f,0.0385988f,0.998244f}, +{0.625735f,-0.748626f,-0.219122f},{0.610502f,-0.76171f,-0.216993f},{0.605359f,-0.766127f,-0.215847f}, +{0.6763f,-0.705197f,0.212874f},{0.58984f,-0.779456f,-0.211039f},{0.595019f,-0.775007f,-0.212875f}, +{0.600195f,-0.770562f,-0.214476f},{0.584664f,-0.783901f,-0.208966f},{0.579503f,-0.788334f,-0.206653f}, +{0.574364f,-0.792748f,-0.2041f},{0.569256f,-0.797135f,-0.201305f},{0.564191f,-0.801485f,-0.198267f}, +{0.721979f,-0.665964f,0.187718f},{0.544537f,-0.818366f,-0.183731f},{0.54934f,-0.814241f,-0.187718f}, +{0.554223f,-0.810046f,-0.191472f},{0.539823f,-0.822414f,-0.179515f},{0.535208f,-0.826378f,-0.175076f}, +{0.749276f,-0.642519f,0.160482f},{0.51791f,-0.841235f,-0.155219f},{0.522044f,-0.837685f,-0.160482f}, +{0.52631f,-0.834021f,-0.165552f},{0.513917f,-0.844665f,-0.14977f},{0.510071f,-0.847968f,-0.144146f}, +{0.506379f,-0.851139f,-0.138358f},{0.502846f,-0.854173f,-0.132417f},{0.493256f,-0.86241f,-0.113788f}, +{0.490408f,-0.864856f,-0.107351f},{0.48774f,-0.867148f,-0.100821f},{0.790491f,-0.60712f,0.0808013f}, +{0.478892f,-0.874747f,-0.0740269f},{0.480829f,-0.873084f,-0.0808013f},{0.482949f,-0.871262f,-0.0875334f}, +{0.477137f,-0.876254f,-0.0672227f},{0.475565f,-0.877605f,-0.0604006f},{0.474172f,-0.878801f,-0.0535724f}, +{0.472957f,-0.879844f,-0.0467496f},{0.800972f,-0.598118f,0.0264206f},{0.184979f,-0.982742f,-2.6491e-016f}, +{0.650623f,-0.727251f,0.218624f},{0.645585f,-0.731578f,0.219122f},{0.655703f,-0.722888f,0.217917f}, +{0.660818f,-0.718494f,0.216992f},{0.665961f,-0.714077f,0.215848f},{0.671124f,-0.709642f,0.214476f}, +{0.68148f,-0.700748f,0.211039f},{0.696956f,-0.687456f,0.2041f},{0.691817f,-0.69187f,0.206653f}, +{0.674737f,-0.475049f,0.564852f},{0.686655f,-0.696303f,0.208966f},{0.702063f,-0.68307f,0.201305f}, +{0.707128f,-0.678719f,0.198267f},{0.712143f,-0.674412f,0.194989f},{0.717096f,-0.670158f,0.191472f}, +{0.732756f,-0.0670628f,0.677179f},{0.795809f,-0.371062f,0.47854f},{0.714905f,-0.0823942f,0.69435f}, +{0.726783f,-0.661838f,0.183731f},{0.731497f,-0.65779f,0.179515f},{0.736111f,-0.653826f,0.175076f}, +{0.740619f,-0.649955f,0.170419f},{0.74501f,-0.646183f,0.165552f},{0.829983f,0.0164437f,0.557547f}, +{0.864516f,-0.312051f,0.394f},{0.815107f,0.00366745f,0.579299f},{0.753409f,-0.638969f,0.155219f}, +{0.757402f,-0.63554f,0.14977f},{0.761248f,-0.632236f,0.144146f},{0.76494f,-0.629065f,0.138358f}, +{0.768473f,-0.626031f,0.132417f},{0.780911f,-0.615349f,0.107351f},{0.778063f,-0.617794f,0.113788f}, +{0.910477f,-0.272576f,0.311019f},{0.775039f,-0.620392f,0.120119f},{0.783579f,-0.613057f,0.100821f}, +{0.786066f,-0.610921f,0.0942108f},{0.78837f,-0.608942f,0.0875334f},{0.792428f,-0.605457f,0.0740269f}, +{0.797147f,-0.601403f,0.0535724f},{0.795755f,-0.602599f,0.0604006f},{0.958834f,-0.231043f,0.165095f}, +{0.794182f,-0.60395f,0.0672227f},{0.798362f,-0.60036f,0.0467497f},{0.799403f,-0.599467f,0.0399431f}, +{0.800271f,-0.59872f,0.0331634f},{0.801887f,-0.597333f,0.0130831f},{0.802109f,-0.597142f,0.00650573f}, +{0.651551f,-0.758605f,-2.05938e-033f},{0.433008f,-0.90139f,-1.54031e-016f},{0.562139f,-0.571757f,0.597573f}, +{0.548369f,-0.583584f,0.598933f},{0.576025f,-0.559831f,0.595638f},{0.590006f,-0.547823f,0.593113f}, +{0.604064f,-0.535749f,0.589983f},{0.618177f,-0.523627f,0.586235f},{0.632325f,-0.511476f,0.581857f}, +{0.646483f,-0.499316f,0.576839f},{0.660628f,-0.487166f,0.571173f},{0.581305f,-0.197141f,0.789443f}, +{0.601058f,-0.180175f,0.778631f},{0.702743f,-0.450995f,0.550232f},{0.688784f,-0.462984f,0.557873f}, +{0.716589f,-0.439103f,0.541931f},{0.730295f,-0.427331f,0.53297f},{0.743835f,-0.415702f,0.523356f}, +{0.757182f,-0.404239f,0.513095f},{0.770311f,-0.392963f,0.502197f},{0.783195f,-0.381897f,0.490674f}, +{0.808129f,-0.360481f,0.465812f},{0.820131f,-0.350173f,0.452509f},{0.831792f,-0.340157f,0.438652f}, +{0.84309f,-0.330454f,0.424264f},{0.854004f,-0.32108f,0.409371f},{0.874608f,-0.303383f,0.378179f}, +{0.884264f,-0.29509f,0.361938f},{0.893469f,-0.287184f,0.34531f},{0.90221f,-0.279676f,0.328326f}, +{0.906037f,0.0817656f,0.415224f},{0.916358f,0.09063f,0.389967f},{0.925555f,-0.259626f,0.275577f}, +{0.918261f,-0.26589f,0.293425f},{0.932352f,-0.253788f,0.257509f},{0.93865f,-0.248379f,0.239258f}, +{0.944446f,-0.243401f,0.220857f},{0.949741f,-0.238853f,0.20234f},{0.954536f,-0.234735f,0.183742f}, +{0.962641f,-0.227774f,0.146431f},{0.973538f,0.13974f,0.180824f},{0.977561f,0.143196f,0.154497f}, +{0.968805f,-0.222479f,0.109178f},{0.965962f,-0.224922f,0.127782f},{0.971179f,-0.22044f,0.0906467f}, +{0.975595f,-0.216648f,0.0357604f},{0.943289f,-0.331972f,1.5621e-016f},{0.825457f,-0.564465f,6.56678e-035f}, +{0.29793f,-0.346881f,0.889332f},{0.382604f,-0.367801f,0.847547f},{0.42174f,-0.334188f,0.842884f}, +{0.441525f,-0.317195f,0.839311f},{0.248878f,-0.110725f,0.962185f},{0.461418f,-0.30011f,0.834882f}, +{0.48139f,-0.282956f,0.829578f},{0.501409f,-0.265762f,0.823383f},{0.521445f,-0.248554f,0.816282f}, +{0.541462f,-0.231361f,0.808264f},{0.561427f,-0.214213f,0.79932f},{0.346402f,0.297518f,0.889657f}, +{0.498084f,0.103313f,0.860952f},{0.475944f,0.0842968f,0.875426f},{0.620651f,-0.163347f,0.766883f}, +{0.640047f,-0.146689f,0.754203f},{0.659207f,-0.130232f,0.740598f},{0.678094f,-0.11401f,0.726078f}, +{0.696673f,-0.0980537f,0.710657f},{0.623817f,0.211302f,0.752465f},{0.75019f,-0.0520888f,0.659168f}, +{0.603915f,0.194209f,0.773026f},{0.767173f,-0.0375018f,0.640343f},{0.783674f,-0.0233294f,0.620734f}, +{0.799662f,-0.00959819f,0.600374f},{0.731206f,0.303536f,0.610904f},{0.602981f,0.517889f,0.606799f}, +{0.746803f,0.316933f,0.58467f},{0.844264f,0.0287092f,0.535159f},{0.857927f,0.0404448f,0.512177f}, +{0.870953f,0.0516324f,0.488646f},{0.883323f,0.0622568f,0.464612f},{0.895022f,0.072305f,0.440122f}, +{0.824484f,0.383652f,0.415977f},{0.925977f,0.0988912f,0.3644f},{0.813504f,0.374221f,0.445163f}, +{0.934889f,0.106546f,0.338573f},{0.943091f,0.11359f,0.312533f},{0.950583f,0.120025f,0.286331f}, +{0.957369f,0.125853f,0.260012f},{0.963451f,0.131077f,0.233625f},{0.968838f,0.135704f,0.207214f}, +{0.980921f,0.146082f,0.128274f},{0.894338f,0.443647f,0.0577667f},{0.892671f,0.442216f,0.0870897f}, +{0.987169f,0.151448f,0.0506043f},{0.271464f,-0.0913273f,0.958106f},{0.294173f,-0.0718233f,0.95305f}, +{0.316971f,-0.0522418f,0.946995f},{0.339824f,-0.0326136f,0.939923f},{0.362696f,-0.0129702f,0.931817f}, +{0.385546f,0.00665603f,0.922665f},{0.408337f,0.0262309f,0.912454f},{0.431028f,0.0457197f,0.901179f}, +{0.453578f,0.0650871f,0.888837f},{0.519956f,0.122098f,0.845422f},{0.541517f,0.140616f,0.828846f}, +{0.562725f,0.158831f,0.811242f},{0.583538f,0.176707f,0.792627f},{0.460322f,0.395362f,0.794854f}, +{0.643204f,0.227954f,0.730976f},{0.662041f,0.244132f,0.708591f},{0.680291f,0.259807f,0.68535f}, +{0.697922f,0.27495f,0.661292f},{0.714903f,0.289534f,0.636461f},{0.761673f,0.329704f,0.557808f}, +{0.775794f,0.341832f,0.530373f},{0.789149f,0.353302f,0.502416f},{0.801723f,0.364102f,0.473994f}, +{0.674899f,0.579658f,0.456627f},{0.834658f,0.392389f,0.386494f},{0.844021f,0.400431f,0.356769f}, +{0.852574f,0.407777f,0.326857f},{0.860319f,0.41443f,0.296814f},{0.867263f,0.420393f,0.266692f}, +{0.873412f,0.425675f,0.236543f},{0.878777f,0.430282f,0.206418f},{0.88337f,0.434227f,0.176364f}, +{0.887205f,0.437521f,0.146429f},{0.8903f,0.440179f,0.116657f},{0.0673616f,0.0578556f,0.99605f}, +{0.0897231f,0.0770615f,0.992981f},{0.112006f,0.0961995f,0.98904f},{0.13419f,0.115254f,0.98423f}, +{0.156257f,0.134206f,0.978556f},{0.178186f,0.153041f,0.972023f},{0.199959f,0.171741f,0.964635f}, +{0.221556f,0.19029f,0.956401f},{0.242959f,0.208673f,0.947326f},{0.264148f,0.226872f,0.937419f}, +{0.285105f,0.244871f,0.926689f},{0.305812f,0.262656f,0.915145f},{0.32625f,0.28021f,0.902798f}, +{0.366249f,0.314564f,0.875734f},{0.385775f,0.331335f,0.861043f},{0.404961f,0.347814f,0.845596f}, +{0.423793f,0.363987f,0.829405f},{0.442252f,0.379842f,0.812486f},{0.477988f,0.410535f,0.776523f}, +{0.495234f,0.425347f,0.757511f},{0.512046f,0.439786f,0.737833f},{0.528407f,0.453839f,0.717507f}, +{0.544305f,0.467493f,0.696551f},{0.559724f,0.480737f,0.674982f},{0.574652f,0.493558f,0.652821f}, +{0.589075f,0.505946f,0.630087f},{0.616357f,0.529378f,0.582978f},{0.629192f,0.540401f,0.558645f}, +{0.641474f,0.55095f,0.533822f},{0.653193f,0.561015f,0.508529f},{0.664337f,0.570587f,0.48279f}, +{0.684867f,0.58822f,0.430063f},{0.694234f,0.596265f,0.403122f},{0.702992f,0.603786f,0.375826f}, +{0.711132f,0.610777f,0.3482f},{0.718647f,0.617232f,0.320268f},{0.725531f,0.623145f,0.292055f}, +{0.731777f,0.62851f,0.263585f},{0.737381f,0.633323f,0.234884f},{0.742338f,0.63758f,0.205977f}, +{0.746642f,0.641277f,0.176888f},{0.750291f,0.64441f,0.147645f},{0.75328f,0.646978f,0.118272f}, +{0.755608f,0.648978f,0.0887941f},{0.757272f,0.650407f,0.0592391f},{0.758272f,0.651265f,0.0296323f}, +{6.73779e-016f,5.78696e-016f,1.0f},{-9.28992e-017f,-7.97894e-017f,1.0f},{0.00379251f,-0.321225f,0.946995f}, +{-0.110265f,-0.419187f,0.901179f},{0.286341f,-0.45048f,0.845622f},{0.480343f,-0.642011f,0.597573f}, +{0.466457f,-0.653936f,0.595638f},{0.0492999f,-0.28214f,0.958106f},{-0.134188f,-0.115252f,0.984231f}, +{0.610502f,-0.76171f,0.216993f},{0.615617f,-0.757316f,0.217916f},{0.0943152f,-0.243477f,0.96531f}, +{0.266692f,-0.467356f,0.842884f},{0.640595f,-0.735863f,-0.219416f},{0.630724f,-0.744341f,0.219416f}, +{0.620697f,-0.752953f,0.218624f},{0.431242f,-0.502097f,-0.749619f},{0.363305f,-0.384377f,-0.848684f}, +{0.534731f,-0.595298f,-0.599736f},{0.609092f,-0.70917f,-0.355084f},{0.0449409f,0.0385987f,-0.998244f}, +{0.204204f,-0.149095f,-0.967508f},{0.182173f,-0.168018f,-0.968805f},{0.0224804f,0.0193078f,-0.999561f}, +{0.155937f,-0.181559f,-0.970938f},{4.72151e-016f,4.05521e-016f,-1.0f},{-0.199957f,-0.171739f,0.964636f}, +{-0.0190607f,-0.340853f,0.939923f},{-0.0419318f,-0.360497f,0.931817f},{-0.178184f,-0.153039f,0.972023f}, +{-0.0647826f,-0.380123f,0.922665f},{-0.221554f,-0.190289f,0.956402f},{0.127004f,-0.587331f,0.79932f}, +{-0.0875737f,-0.399698f,0.912454f},{-0.242957f,-0.208671f,0.947327f},{-0.132814f,-0.438554f,0.888837f}, +{-0.30581f,-0.262654f,0.915146f},{-0.17732f,-0.47678f,0.860952f},{-0.199192f,-0.495565f,0.845422f}, +{-0.366247f,-0.314563f,0.875736f},{-0.15518f,-0.457764f,0.875426f},{-0.241961f,-0.532298f,0.811242f}, +{-0.385773f,-0.331333f,0.861045f},{-0.46032f,-0.39536f,0.794856f},{-0.262774f,-0.550174f,0.792627f}, +{-0.341277f,-0.617599f,0.708591f},{-0.528407f,-0.453838f,0.717508f},{-0.322441f,-0.601421f,0.730976f}, +{-0.559724f,-0.480736f,0.674983f},{-0.39414f,-0.663002f,0.636461f},{-0.544304f,-0.467493f,0.696551f}, +{-0.377159f,-0.648417f,0.661292f},{-0.440909f,-0.703171f,0.557808f},{-0.468385f,-0.726769f,0.502416f}, +{-0.684866f,-0.588219f,0.430066f},{-0.674898f,-0.579657f,0.45663f},{-0.480959f,-0.737569f,0.473994f}, +{-0.513894f,-0.765856f,0.386494f},{-0.702991f,-0.603786f,0.375828f},{-0.539556f,-0.787897f,0.296814f}, +{-0.718646f,-0.617231f,0.32027f},{-0.731777f,-0.628509f,0.263588f},{-0.552648f,-0.799142f,0.236543f}, +{-0.737381f,-0.633323f,0.234887f},{-0.546499f,-0.79386f,0.266692f},{-0.72553f,-0.623144f,0.292057f}, +{-0.742337f,-0.63758f,0.205979f},{-0.562606f,-0.807694f,0.176364f},{-0.558013f,-0.803749f,0.206418f}, +{-0.574558f,-0.81796f,0.0287253f},{-0.758605f,-0.651551f,3.14853e-016f},{-0.758272f,-0.651265f,0.0296338f}, +{-0.566442f,-0.810988f,0.146429f},{-0.297277f,-0.951738f,0.0762915f},{-0.298738f,-0.952993f,0.0506043f}, +{-0.757272f,-0.650407f,0.0592414f},{-0.755608f,-0.648977f,0.0887967f},{-0.573574f,-0.817114f,0.0577667f}, +{-0.569536f,-0.813646f,0.116657f},{0.0668874f,-0.997119f,0.0357603f},{0.46921f,-0.883063f,0.00650573f}, +{0.0662782f,-0.997643f,0.0177823f},{-0.28913f,-0.944741f,0.154497f},{-0.285106f,-0.941285f,0.180824f}, +{-0.2952f,-0.949955f,0.102193f},{0.069387f,-0.994972f,0.0722163f},{0.073677f,-0.991288f,0.109178f}, +{0.801509f,-0.597657f,-0.0197241f},{0.800972f,-0.598118f,-0.0264206f},{0.974563f,-0.217534f,-0.0539127f}, +{0.470347f,-0.882086f,0.0264206f},{0.46981f,-0.882547f,0.0197241f},{0.985709f,0.150194f,-0.0762915f}, +{0.987169f,0.151448f,-0.0506043f},{0.997238f,-0.0742779f,-1.10368e-016f},{0.976204f,-0.216125f,-0.0177823f}, +{0.988031f,0.152188f,-0.0251637f},{0.895322f,0.444493f,-0.0287253f},{0.901253f,0.433294f,-3.00521e-016f}, +{0.983078f,0.183188f,-5.39175e-016f},{0.758605f,0.651551f,-6.22394e-016f},{-0.27502f,-0.932622f,0.233625f}, +{-0.45503f,-0.715299f,0.530373f},{-0.664336f,-0.570586f,0.482793f},{-0.49274f,-0.747688f,0.445162f}, +{-0.206591f,-0.87385f,0.440122f},{-0.589074f,-0.505945f,0.630089f},{-0.126676f,-0.805212f,0.579299f}, +{0.188478f,-0.892688f,0.409371f},{0.177966f,-0.901716f,0.394f},{-0.477987f,-0.410534f,0.776525f}, +{-0.44225f,-0.37984f,0.812488f},{-0.326248f,-0.280208f,0.902799f},{-0.220753f,-0.514083f,0.828846f}, +{0.246673f,-0.842705f,0.47854f},{-0.0264735f,-0.71915f,0.69435f},{0.259287f,-0.831871f,0.490674f}, +{-0.112004f,-0.0961983f,0.98904f},{-0.0897214f,-0.07706f,0.992981f},{-0.0673597f,-0.0578539f,0.99605f}, +{0.507751f,-0.61847f,0.599736f},{0.609586f,-0.709744f,0.353084f},{0.11656f,-0.224371f,0.967508f}, +{-0.044939f,-0.0385972f,0.998244f},{0.138591f,-0.205449f,0.968805f},{-0.0224791f,-0.0193069f,0.999561f}, +{0.155494f,-0.181042f,0.971105f},{-2.38849e-016f,-2.05143e-016f,1.0f},{0.304133f,-0.354104f,0.884372f}, +{0.432488f,-0.503548f,0.747926f},{0.325126f,-0.417168f,0.848684f},{0.536319f,-0.624439f,0.567836f}, +{0.305827f,-0.433744f,0.847547f},{0.246907f,-0.484349f,0.839311f},{0.227014f,-0.501435f,0.834882f}, +{0.207042f,-0.518588f,0.829578f},{0.187022f,-0.535783f,0.823383f},{0.166987f,-0.552991f,0.816282f}, +{0.146969f,-0.570184f,0.808264f},{0.353698f,-0.750783f,0.557873f},{0.339739f,-0.762773f,0.550232f}, +{0.087373f,-0.62137f,0.778631f},{0.06778f,-0.638198f,0.766883f},{0.0483849f,-0.654856f,0.754203f}, +{0.0292249f,-0.671312f,0.740598f},{0.0103371f,-0.687534f,0.726078f},{-0.00824112f,-0.703491f,0.710657f}, +{-0.0443241f,-0.734482f,0.677179f},{-0.0617582f,-0.749456f,0.659168f},{-0.078742f,-0.764043f,0.640343f}, +{-0.0952429f,-0.778215f,0.620734f},{-0.111231f,-0.791946f,0.600374f},{-0.141551f,-0.817988f,0.557547f}, +{-0.169496f,-0.841989f,0.512177f},{-0.182521f,-0.853177f,0.488646f},{-0.194892f,-0.863801f,0.464612f}, +{0.116927f,-0.954141f,0.275577f},{0.48774f,-0.867148f,0.100821f},{-0.217606f,-0.88331f,0.415224f}, +{-0.227926f,-0.892174f,0.389967f},{-0.237545f,-0.900436f,0.3644f},{-0.246457f,-0.90809f,0.338573f}, +{-0.254659f,-0.915135f,0.312533f},{-0.262152f,-0.92157f,0.286331f},{-0.268937f,-0.927398f,0.260012f}, +{-0.280406f,-0.937248f,0.207214f},{0.0765203f,-0.988846f,0.127782f},{-0.292489f,-0.947626f,0.128274f}, +{-0.2996f,-0.953733f,0.0251637f},{-0.339059f,-0.940765f,7.30221e-017f},{-0.564043f,-0.825745f,2.30577e-016f}, +{0.536047f,-0.624123f,-0.56844f},{0.494113f,-0.630183f,0.598933f},{0.452476f,-0.665945f,0.593113f}, +{0.438418f,-0.678019f,0.589983f},{0.424305f,-0.69014f,0.586235f},{0.381854f,-0.726601f,0.571173f}, +{0.367745f,-0.738719f,0.564853f},{0.325893f,-0.774664f,0.541931f},{0.559177f,-0.805792f,0.194989f}, +{0.312187f,-0.786436f,0.53297f},{0.298647f,-0.798065f,0.523356f},{0.2853f,-0.809529f,0.513095f}, +{0.272171f,-0.820805f,0.502197f},{0.52631f,-0.834021f,0.165552f},{0.74501f,-0.646183f,-0.165552f}, +{0.749276f,-0.642519f,-0.160482f},{0.234353f,-0.853287f,0.465812f},{0.222351f,-0.863595f,0.452509f}, +{0.21069f,-0.87361f,0.438652f},{0.199392f,-0.883313f,0.424264f},{0.502847f,-0.854173f,0.132416f}, +{0.768473f,-0.626031f,-0.132417f},{0.771841f,-0.623139f,-0.126333f},{0.167874f,-0.910384f,0.378179f}, +{0.158218f,-0.918677f,0.361938f},{0.149013f,-0.926583f,0.34531f},{0.140272f,-0.934091f,0.328326f}, +{0.132004f,-0.941192f,0.31102f},{0.124221f,-0.947877f,0.293425f},{0.11013f,-0.959979f,0.25751f}, +{0.103832f,-0.965388f,0.239258f},{0.098036f,-0.970367f,0.220857f},{0.0927412f,-0.974914f,0.20234f}, +{0.0879463f,-0.979032f,0.183742f},{0.0798413f,-0.985994f,0.146431f},{0.0713026f,-0.993327f,0.0906466f}, +{0.801887f,-0.597333f,-0.0130831f},{-0.0755429f,-0.997143f,3.49386e-017f},{0.382604f,-0.367801f,-0.847547f}, +{0.605359f,-0.766127f,0.215847f},{0.665961f,-0.714077f,-0.215848f},{0.671124f,-0.709642f,-0.214476f}, +{0.595019f,-0.775007f,0.212875f},{0.584664f,-0.783901f,0.208966f},{0.579503f,-0.788334f,0.206653f}, +{0.574364f,-0.792748f,0.2041f},{0.569256f,-0.797135f,0.201304f},{0.554223f,-0.810046f,0.191472f}, +{0.717096f,-0.670158f,-0.191472f},{0.721979f,-0.665964f,-0.187718f},{0.54934f,-0.814241f,0.187718f}, +{0.544537f,-0.818366f,0.183731f},{0.535208f,-0.826378f,0.175076f},{0.530701f,-0.830249f,0.170419f}, +{0.522044f,-0.837685f,0.160482f},{0.513917f,-0.844665f,0.14977f},{0.510071f,-0.847968f,0.144146f}, +{0.506379f,-0.851139f,0.138358f},{0.499479f,-0.857065f,0.126333f},{0.496281f,-0.859812f,0.120119f}, +{0.493256f,-0.86241f,0.113788f},{0.490408f,-0.864856f,0.107351f},{0.482949f,-0.871262f,0.0875334f}, +{0.78837f,-0.608942f,-0.0875334f},{0.790491f,-0.60712f,-0.0808013f},{0.480829f,-0.873084f,0.0808013f}, +{0.478892f,-0.874747f,0.0740269f},{0.477137f,-0.876254f,0.0672227f},{0.474172f,-0.878801f,0.0535724f}, +{0.472957f,-0.879844f,0.0467496f},{0.471917f,-0.880738f,0.0399431f},{0.471048f,-0.881484f,0.0331634f}, +{0.469433f,-0.882871f,0.0130831f},{0.18498f,-0.982742f,5.93908e-017f},{0.650623f,-0.727251f,-0.218624f}, +{0.655703f,-0.722888f,-0.217917f},{0.645585f,-0.731578f,-0.219122f},{0.660818f,-0.718494f,-0.216992f}, +{0.6763f,-0.705197f,-0.212875f},{0.68148f,-0.700748f,-0.211039f},{0.686655f,-0.696303f,-0.208966f}, +{0.660628f,-0.487166f,-0.571173f},{0.674737f,-0.475049f,-0.564852f},{0.691817f,-0.69187f,-0.206653f}, +{0.696956f,-0.687456f,-0.2041f},{0.702063f,-0.68307f,-0.201305f},{0.707128f,-0.678719f,-0.198267f}, +{0.712143f,-0.674412f,-0.194989f},{0.726783f,-0.661838f,-0.183731f},{0.770311f,-0.392963f,-0.502197f}, +{0.783195f,-0.381897f,-0.490674f},{0.731497f,-0.65779f,-0.179515f},{0.736111f,-0.653826f,-0.175076f}, +{0.740619f,-0.649955f,-0.170419f},{0.753409f,-0.638969f,-0.155219f},{0.854004f,-0.32108f,-0.409371f}, +{0.757402f,-0.63554f,-0.14977f},{0.761248f,-0.632236f,-0.144146f},{0.76494f,-0.629065f,-0.138358f}, +{0.775039f,-0.620392f,-0.120119f},{0.90221f,-0.279676f,-0.328326f},{0.910477f,-0.272576f,-0.311019f}, +{0.778063f,-0.617794f,-0.113788f},{0.780911f,-0.615349f,-0.107351f},{0.783579f,-0.613057f,-0.100821f}, +{0.786066f,-0.610921f,-0.0942108f},{0.792428f,-0.605457f,-0.0740269f},{0.794182f,-0.60395f,-0.0672227f}, +{0.954536f,-0.234735f,-0.183742f},{0.795755f,-0.602599f,-0.0604006f},{0.797147f,-0.601403f,-0.0535724f}, +{0.798362f,-0.60036f,-0.0467497f},{0.799403f,-0.599467f,-0.0399431f},{0.800271f,-0.59872f,-0.0331634f}, +{0.802109f,-0.597142f,-0.00650573f},{0.651551f,-0.758605f,-1.07812e-032f},{0.433008f,-0.90139f,5.07106e-017f}, +{0.562139f,-0.571757f,-0.597573f},{0.576025f,-0.559831f,-0.595638f},{0.548369f,-0.583584f,-0.598933f}, +{0.590006f,-0.547823f,-0.593113f},{0.604064f,-0.535749f,-0.589983f},{0.632324f,-0.511476f,-0.581857f}, +{0.601059f,-0.180175f,-0.778631f},{0.702743f,-0.450995f,-0.550232f},{0.730295f,-0.427331f,-0.53297f}, +{0.743835f,-0.415702f,-0.523356f},{0.757182f,-0.404239f,-0.513095f},{0.732756f,-0.0670628f,-0.677179f}, +{0.795809f,-0.371062f,-0.47854f},{0.808129f,-0.360481f,-0.465812f},{0.820131f,-0.350173f,-0.452509f}, +{0.831792f,-0.340158f,-0.438652f},{0.829983f,0.0164437f,-0.557547f},{0.864516f,-0.312051f,-0.394f}, +{0.874608f,-0.303383f,-0.378179f},{0.884264f,-0.29509f,-0.361938f},{0.893469f,-0.287184f,-0.34531f}, +{0.906037f,0.0817656f,-0.415224f},{0.918261f,-0.26589f,-0.293425f},{0.925555f,-0.259626f,-0.275577f}, +{0.93865f,-0.248379f,-0.239258f},{0.949741f,-0.238853f,-0.20234f},{0.962641f,-0.227774f,-0.146431f}, +{0.973538f,0.13974f,-0.180824f},{0.965962f,-0.224921f,-0.127782f},{0.968805f,-0.222479f,-0.109178f}, +{0.971179f,-0.22044f,-0.0906466f},{0.973095f,-0.218795f,-0.0722163f},{0.975595f,-0.216648f,-0.0357604f}, +{0.943289f,-0.331972f,-1.55829e-016f},{0.825457f,-0.564465f,-4.03832e-017f},{0.402091f,-0.351065f,-0.845622f}, +{0.42174f,-0.334188f,-0.842884f},{0.441525f,-0.317195f,-0.839311f},{0.461418f,-0.30011f,-0.834882f}, +{0.48139f,-0.282956f,-0.829578f},{0.501409f,-0.265762f,-0.823383f},{0.521445f,-0.248554f,-0.816282f}, +{0.541462f,-0.231361f,-0.808264f},{0.561427f,-0.214213f,-0.79932f},{0.581305f,-0.197141f,-0.789443f}, +{0.475944f,0.0842967f,-0.875426f},{0.346402f,0.297518f,-0.889657f},{0.620651f,-0.163347f,-0.766883f}, +{0.640047f,-0.146689f,-0.754203f},{0.659207f,-0.130232f,-0.740598f},{0.678094f,-0.11401f,-0.726078f}, +{0.714905f,-0.0823942f,-0.69435f},{0.75019f,-0.0520888f,-0.659168f},{0.623817f,0.211302f,-0.752465f}, +{0.767173f,-0.0375018f,-0.640343f},{0.783674f,-0.0233296f,-0.620733f},{0.815107f,0.00366745f,-0.579299f}, +{0.731206f,0.303536f,-0.610904f},{0.746803f,0.316933f,-0.58467f},{0.844264f,0.0287092f,-0.535159f}, +{0.857927f,0.0404448f,-0.512177f},{0.870953f,0.0516324f,-0.488646f},{0.883323f,0.0622568f,-0.464612f}, +{0.895022f,0.072305f,-0.440122f},{0.916358f,0.0906297f,-0.389967f},{0.824484f,0.383652f,-0.415977f}, +{0.934889f,0.106546f,-0.338573f},{0.943091f,0.11359f,-0.312533f},{0.950583f,0.120025f,-0.286331f}, +{0.957369f,0.125853f,-0.260012f},{0.968838f,0.135704f,-0.207214f},{0.977561f,0.143196f,-0.154497f}, +{0.980921f,0.146082f,-0.128274f},{0.983632f,0.14841f,-0.102193f},{0.226448f,-0.12999f,-0.96531f}, +{0.248879f,-0.110725f,-0.962185f},{0.271464f,-0.0913273f,-0.958106f},{0.294173f,-0.0718231f,-0.95305f}, +{0.316971f,-0.0522418f,-0.946995f},{0.339824f,-0.0326136f,-0.939923f},{0.362695f,-0.0129701f,-0.931817f}, +{0.385546f,0.00665603f,-0.922665f},{0.408337f,0.0262307f,-0.912454f},{0.431028f,0.0457197f,-0.901179f}, +{0.453578f,0.065087f,-0.888837f},{0.519956f,0.122098f,-0.845422f},{0.541517f,0.140616f,-0.828846f}, +{0.562725f,0.158831f,-0.811242f},{0.583538f,0.176707f,-0.792627f},{0.643204f,0.227954f,-0.730976f}, +{0.662041f,0.244132f,-0.708591f},{0.680291f,0.259807f,-0.68535f},{0.697922f,0.27495f,-0.661292f}, +{0.761673f,0.329704f,-0.557808f},{0.775794f,0.341832f,-0.530373f},{0.789149f,0.353302f,-0.502416f}, +{0.801723f,0.364102f,-0.473994f},{0.852574f,0.407777f,-0.326857f},{0.860319f,0.41443f,-0.296814f}, +{0.873412f,0.425675f,-0.236543f},{0.878777f,0.430282f,-0.206418f},{0.887205f,0.437522f,-0.146429f}, +{0.8903f,0.440179f,-0.116657f},{0.892671f,0.442216f,-0.0870897f},{0.894338f,0.443647f,-0.0577667f}, +{0.0673617f,0.0578556f,-0.99605f},{0.13419f,0.115254f,-0.98423f},{0.156257f,0.134206f,-0.978556f}, +{0.178186f,0.153041f,-0.972023f},{0.199959f,0.171741f,-0.964635f},{0.221556f,0.19029f,-0.956401f}, +{0.242959f,0.208673f,-0.947326f},{0.264148f,0.226872f,-0.937419f},{0.285105f,0.244871f,-0.926689f}, +{0.305812f,0.262656f,-0.915145f},{0.32625f,0.28021f,-0.902798f},{0.423793f,0.363987f,-0.829405f}, +{0.477988f,0.410535f,-0.776523f},{0.528407f,0.453839f,-0.717507f},{0.559724f,0.480737f,-0.674982f}, +{0.589075f,0.505946f,-0.630087f},{0.616357f,0.529378f,-0.582978f},{0.653193f,0.561015f,-0.508529f}, +{0.684867f,0.58822f,-0.430063f},{0.694234f,0.596265f,-0.403122f},{0.725531f,0.623145f,-0.292055f}, +{0.731777f,0.62851f,-0.263585f},{0.737381f,0.633323f,-0.234884f},{0.746642f,0.641277f,-0.176888f}, +{0.750291f,0.64441f,-0.147645f},{0.75328f,0.646978f,-0.118272f},{0.755608f,0.648978f,-0.0887941f}, +{0.757272f,0.650407f,-0.0592391f},{0.758272f,0.651265f,-0.0296323f},{0.878777f,0.430282f,0.206418f}, +{0.844021f,0.400431f,0.356769f},{0.8903f,0.440179f,0.116657f},{0.892671f,0.442216f,0.0870897f}, +{0.983632f,0.14841f,0.102193f},{0.750291f,0.64441f,0.147645f},{0.75328f,0.646978f,0.118272f}, +{0.976204f,-0.216125f,0.0177823f},{0.943289f,-0.331972f,3.41808e-016f},{0.80211f,-0.597142f,0.00650572f}, +{0.974563f,-0.217534f,0.0539127f},{0.973095f,-0.218795f,0.0722163f},{0.985709f,0.150194f,0.0762915f}, +{0.46921f,-0.883063f,-0.00650572f},{0.184979f,-0.982742f,-4.69192e-016f},{0.0662783f,-0.997643f,-0.0177823f}, +{0.801509f,-0.597657f,0.0197241f},{0.800972f,-0.598118f,0.0264206f},{-0.574558f,-0.81796f,-0.0287252f}, +{-0.573574f,-0.817114f,-0.0577667f},{-0.2996f,-0.953733f,-0.0251636f},{-0.0755427f,-0.997143f,-5.50975e-016f}, +{-0.758605f,-0.651551f,-9.3359e-016f},{-0.564043f,-0.825745f,-3.00566e-016f},{-0.757272f,-0.650407f,-0.0592414f}, +{0.887205f,0.437522f,0.146429f},{0.746642f,0.641277f,0.176888f},{-0.758271f,-0.651265f,-0.0296337f}, +{0.731777f,0.62851f,0.263585f},{0.873412f,0.425675f,0.236543f},{0.867263f,0.420393f,0.266692f}, +{0.737381f,0.633323f,0.234884f},{0.860319f,0.41443f,0.296814f},{0.725531f,0.623145f,0.292055f}, +{0.852574f,0.407777f,0.326857f},{0.718647f,0.617232f,0.320268f},{0.694234f,0.596265f,0.403122f}, +{0.813504f,0.374221f,0.445162f},{0.801723f,0.364102f,0.473994f},{0.824484f,0.383652f,0.415977f}, +{0.775794f,0.341832f,0.530373f},{0.653193f,0.561015f,0.508529f},{0.602981f,0.517889f,0.606799f}, +{0.731206f,0.303536f,0.610904f},{0.761673f,0.329704f,0.557808f},{0.697922f,0.27495f,0.661292f}, +{0.544305f,0.467493f,0.696551f},{0.714903f,0.289535f,0.636461f},{0.512046f,0.439786f,0.737833f}, +{0.643204f,0.227954f,0.730976f},{0.528407f,0.453839f,0.717507f},{0.662041f,0.244132f,0.708591f}, +{0.583538f,0.176707f,0.792627f},{0.541517f,0.140616f,0.828846f},{0.32625f,0.28021f,0.902798f}, +{0.346402f,0.297518f,0.889657f},{0.475944f,0.0842968f,0.875426f},{0.519956f,0.122098f,0.845422f}, +{0.453578f,0.065087f,0.888837f},{0.285105f,0.244871f,0.926689f},{0.305812f,0.262656f,0.915145f}, +{0.385546f,0.00665599f,0.922665f},{0.242959f,0.208673f,0.947326f},{0.408337f,0.0262308f,0.912454f}, +{0.199959f,0.171741f,0.964635f},{0.362695f,-0.0129701f,0.931817f},{0.339824f,-0.0326136f,0.939923f}, +{0.221556f,0.19029f,0.956401f},{0.156257f,0.134206f,0.978556f},{0.316971f,-0.0522418f,0.946995f}, +{0.294173f,-0.0718231f,0.95305f},{0.178186f,0.153041f,0.972023f},{0.271464f,-0.0913273f,0.958106f}, +{0.650623f,-0.727251f,0.218624f},{0.576025f,-0.559831f,0.595638f},{0.182173f,-0.168017f,0.968805f}, +{0.0449408f,0.0385988f,0.998244f},{0.204204f,-0.149095f,0.967508f},{0.0224803f,0.0193079f,0.999561f}, +{0.226448f,-0.12999f,0.96531f},{0.248878f,-0.110725f,0.962185f},{0.402091f,-0.351064f,0.845622f}, +{0.0673616f,0.0578556f,0.99605f},{0.0897231f,0.0770615f,0.992981f},{0.48139f,-0.282956f,0.829578f}, +{0.604064f,-0.535749f,0.589983f},{0.461418f,-0.30011f,0.834882f},{0.655702f,-0.722888f,0.217917f}, +{0.42174f,-0.334188f,0.842884f},{0.620697f,-0.752953f,-0.218624f},{0.625735f,-0.748626f,-0.219122f}, +{0.645585f,-0.731578f,0.219122f},{0.286341f,-0.45048f,-0.845622f},{0.305827f,-0.433744f,-0.847547f}, +{0.480343f,-0.642011f,-0.597573f},{0.432488f,-0.503548f,-0.747926f},{0.507751f,-0.61847f,-0.599737f}, +{0.325127f,-0.417168f,-0.848684f},{0.138591f,-0.205449f,-0.968805f},{0.304133f,-0.354104f,-0.884372f}, +{0.155494f,-0.181042f,-0.971105f},{-0.0f,0.0f,-1.0f},{-0.0224791f,-0.019307f,-0.999561f}, +{2.50764e-009f,-2.91966e-009f,1.0f},{0.155937f,-0.181559f,0.970938f},{0.521445f,-0.248554f,0.816282f}, +{0.562725f,0.158831f,0.811242f},{0.498084f,0.103313f,0.860952f},{0.678094f,-0.11401f,0.726078f}, +{0.477988f,0.410535f,0.776523f},{0.783674f,-0.0233295f,0.620733f},{0.831792f,-0.340158f,0.438652f}, +{0.820131f,-0.350173f,0.452509f},{0.589075f,0.505946f,0.630087f},{0.616357f,0.529378f,0.582978f}, +{0.684867f,0.58822f,0.430063f},{0.789149f,0.353302f,0.502416f},{0.884264f,-0.29509f,0.361938f}, +{0.870953f,0.0516324f,0.488646f},{0.893469f,-0.287184f,0.34531f},{0.950583f,0.120025f,0.286331f}, +{0.755608f,0.648978f,0.0887942f},{0.757272f,0.650407f,0.059239f},{0.894338f,0.443647f,0.0577667f}, +{0.988031f,0.152189f,0.0251636f},{0.997238f,-0.0742779f,5.00783e-016f},{0.758272f,0.651265f,0.0296322f}, +{0.895322f,0.444493f,0.0287252f},{0.901253f,0.433294f,6.47993e-016f},{0.983078f,0.183188f,6.55067e-016f}, +{0.758605f,0.651551f,9.4456e-016f},{0.825457f,-0.564465f,2.60919e-016f},{0.433008f,-0.90139f,-2.0282e-016f}, +{0.987169f,0.151448f,0.0506042f},{0.980921f,0.146082f,0.128274f},{0.977561f,0.143196f,0.154497f}, +{0.973538f,0.13974f,0.180824f},{0.968838f,0.135704f,0.207214f},{0.963451f,0.131077f,0.233625f}, +{0.957369f,0.125853f,0.260012f},{0.944446f,-0.243401f,0.220857f},{0.93865f,-0.248379f,0.239258f}, +{0.934889f,0.106546f,0.338573f},{0.925977f,0.0988913f,0.3644f},{0.916358f,0.0906299f,0.389967f}, +{0.906037f,0.0817656f,0.415224f},{0.895022f,0.072305f,0.440122f},{0.883323f,0.0622569f,0.464612f}, +{0.857927f,0.0404447f,0.512177f},{0.844263f,0.0287093f,0.535159f},{0.829983f,0.0164437f,0.557547f}, +{0.815107f,0.00366744f,0.579299f},{0.799662f,-0.00959806f,0.600374f},{0.767173f,-0.0375019f,0.640343f}, +{0.732756f,-0.0670627f,0.677179f},{0.714905f,-0.0823943f,0.69435f},{0.696673f,-0.0980537f,0.710657f}, +{0.730295f,-0.427331f,0.53297f},{0.712143f,-0.674412f,0.194989f},{0.659207f,-0.130232f,0.740598f}, +{0.640047f,-0.146689f,0.754203f},{0.620651f,-0.163347f,0.766883f},{0.601058f,-0.180175f,0.778631f}, +{0.581305f,-0.197141f,0.789443f},{0.561427f,-0.214213f,0.79932f},{0.541462f,-0.231361f,0.808264f}, +{0.501409f,-0.265762f,0.823383f},{0.618177f,-0.523627f,0.586235f},{0.441525f,-0.317195f,0.839311f}, +{0.382604f,-0.367801f,0.847547f},{0.363305f,-0.384377f,0.848684f},{0.29793f,-0.346881f,0.889332f}, +{-0.298738f,-0.952993f,-0.0506042f},{0.975595f,-0.216648f,0.0357603f},{0.971179f,-0.22044f,0.0906467f}, +{0.968805f,-0.222479f,0.109178f},{0.965962f,-0.224921f,0.127782f},{0.962641f,-0.227774f,0.146431f}, +{0.954536f,-0.234735f,0.183742f},{0.949741f,-0.238853f,0.20234f},{0.932352f,-0.253788f,0.25751f}, +{0.783579f,-0.613057f,0.100821f},{0.925555f,-0.259626f,0.275577f},{0.918261f,-0.26589f,0.293425f}, +{0.910478f,-0.272576f,0.31102f},{0.90221f,-0.279676f,0.328326f},{0.761248f,-0.632237f,0.144146f}, +{0.510071f,-0.847968f,-0.144146f},{0.513917f,-0.844665f,-0.14977f},{0.874608f,-0.303383f,0.378179f}, +{0.864516f,-0.312051f,0.394f},{0.854004f,-0.32108f,0.409371f},{0.84309f,-0.330454f,0.424264f}, +{0.736111f,-0.653826f,0.175076f},{0.535208f,-0.826378f,-0.175076f},{0.539823f,-0.822414f,-0.179515f}, +{0.808129f,-0.360481f,0.465812f},{0.795809f,-0.371062f,0.47854f},{0.783195f,-0.381897f,0.490674f}, +{0.770311f,-0.392963f,0.502197f},{0.757182f,-0.404239f,0.513095f},{0.743835f,-0.415702f,0.523356f}, +{0.716589f,-0.439103f,0.541931f},{0.702743f,-0.450995f,0.550232f},{0.688784f,-0.462984f,0.557873f}, +{0.674737f,-0.475049f,0.564853f},{0.660628f,-0.487166f,0.571173f},{0.632324f,-0.511476f,0.581857f}, +{0.590006f,-0.547823f,0.593113f},{0.630724f,-0.744341f,-0.219416f},{0.548369f,-0.583584f,0.598933f}, +{0.534731f,-0.595298f,0.599736f},{0.431242f,-0.502097f,0.749619f},{0.800271f,-0.59872f,0.0331634f}, +{0.801887f,-0.597333f,0.0130831f},{0.799403f,-0.599466f,0.0399431f},{0.471917f,-0.880738f,-0.0399431f}, +{0.472957f,-0.879844f,-0.0467496f},{0.798362f,-0.60036f,0.0467496f},{0.797147f,-0.601403f,0.0535724f}, +{0.794182f,-0.60395f,0.0672227f},{0.792428f,-0.605457f,0.0740269f},{0.790491f,-0.607121f,0.0808012f}, +{0.78837f,-0.608942f,0.0875334f},{0.780911f,-0.615348f,0.107351f},{0.490408f,-0.864856f,-0.107351f}, +{0.493256f,-0.86241f,-0.113788f},{0.778063f,-0.617794f,0.113788f},{0.775039f,-0.620392f,0.120119f}, +{0.771841f,-0.623139f,0.126333f},{0.768473f,-0.626031f,0.132417f},{0.76494f,-0.629065f,0.138358f}, +{0.757402f,-0.63554f,0.14977f},{0.749276f,-0.642519f,0.160482f},{0.74501f,-0.646183f,0.165552f}, +{0.740619f,-0.649955f,0.170419f},{0.731497f,-0.65779f,0.179515f},{0.726783f,-0.661838f,0.183731f}, +{0.72198f,-0.665964f,0.187718f},{0.717096f,-0.670158f,0.191472f},{0.702063f,-0.68307f,0.201304f}, +{0.569257f,-0.797135f,-0.201304f},{0.574363f,-0.792748f,-0.2041f},{0.696956f,-0.687456f,0.2041f}, +{0.691817f,-0.69187f,0.206653f},{0.686655f,-0.696303f,0.208966f},{0.6763f,-0.705197f,0.212875f}, +{0.671124f,-0.709642f,0.214476f},{0.665961f,-0.714077f,0.215848f},{0.660818f,-0.718494f,0.216993f}, +{0.640595f,-0.735863f,0.219416f},{0.46981f,-0.882547f,-0.0197242f},{0.470347f,-0.882086f,-0.0264206f}, +{0.469433f,-0.882871f,-0.013083f},{0.471048f,-0.881484f,-0.0331634f},{0.474172f,-0.878801f,-0.0535725f}, +{0.475565f,-0.877605f,-0.0604006f},{0.477137f,-0.876254f,-0.0672226f},{0.0879462f,-0.979032f,-0.183742f}, +{0.0927413f,-0.974914f,-0.20234f},{0.478891f,-0.874747f,-0.074027f},{0.480829f,-0.873084f,-0.0808012f}, +{0.482949f,-0.871262f,-0.0875334f},{0.485253f,-0.869283f,-0.0942108f},{0.48774f,-0.867147f,-0.100821f}, +{0.496281f,-0.859812f,-0.120119f},{0.140272f,-0.934091f,-0.328326f},{0.149013f,-0.926583f,-0.34531f}, +{0.499479f,-0.857065f,-0.126333f},{0.502847f,-0.854173f,-0.132416f},{0.506379f,-0.851139f,-0.138358f}, +{0.51791f,-0.841235f,-0.155219f},{0.21069f,-0.87361f,-0.438652f},{0.522044f,-0.837685f,-0.160482f}, +{0.52631f,-0.834021f,-0.165552f},{0.530701f,-0.830249f,-0.170419f},{0.544537f,-0.818366f,-0.183731f}, +{0.272171f,-0.820805f,-0.502197f},{0.2853f,-0.809529f,-0.513095f},{0.54934f,-0.814241f,-0.187718f}, +{0.554223f,-0.810046f,-0.191472f},{0.559177f,-0.805792f,-0.194989f},{0.564191f,-0.801485f,-0.198267f}, +{0.579503f,-0.788334f,-0.206653f},{0.584664f,-0.783901f,-0.208966f},{0.381854f,-0.726601f,-0.571173f}, +{0.58984f,-0.779456f,-0.211039f},{0.595019f,-0.775007f,-0.212874f},{0.600195f,-0.770562f,-0.214476f}, +{0.605359f,-0.766127f,-0.215847f},{0.610502f,-0.76171f,-0.216993f},{0.615617f,-0.757316f,-0.217917f}, +{0.0679193f,-0.996233f,-0.0539127f},{0.069387f,-0.994972f,-0.0722163f},{0.0668873f,-0.997119f,-0.0357603f}, +{0.0713025f,-0.993327f,-0.0906467f},{0.0736771f,-0.991288f,-0.109178f},{0.0765202f,-0.988846f,-0.127782f}, +{0.0798413f,-0.985994f,-0.146431f},{-0.246457f,-0.90809f,-0.338573f},{0.103832f,-0.965388f,-0.239258f}, +{0.116927f,-0.954141f,-0.275577f},{0.124221f,-0.947877f,-0.293425f},{0.132004f,-0.941192f,-0.31102f}, +{-0.169495f,-0.841989f,-0.512177f},{0.158218f,-0.918677f,-0.361938f},{0.167874f,-0.910384f,-0.378179f}, +{0.177966f,-0.901716f,-0.394f},{0.188478f,-0.892688f,-0.409371f},{-0.078742f,-0.764043f,-0.640343f}, +{0.222351f,-0.863595f,-0.452509f},{0.234353f,-0.853287f,-0.465812f},{0.246673f,-0.842705f,-0.47854f}, +{0.259287f,-0.831871f,-0.490674f},{0.0292248f,-0.671312f,-0.740598f},{0.298647f,-0.798065f,-0.523356f}, +{0.312187f,-0.786436f,-0.53297f},{0.339739f,-0.762773f,-0.550232f},{0.367745f,-0.738719f,-0.564853f}, +{0.410157f,-0.702291f,-0.581857f},{0.207042f,-0.518588f,-0.829578f},{0.424305f,-0.69014f,-0.586235f}, +{0.438418f,-0.678019f,-0.589983f},{0.452476f,-0.665945f,-0.593113f},{0.494113f,-0.630183f,-0.598933f}, +{0.609586f,-0.709744f,-0.353084f},{-0.339059f,-0.940765f,-6.77795e-016f},{-0.297277f,-0.951738f,-0.0762915f}, +{-0.2952f,-0.949954f,-0.102193f},{-0.29249f,-0.947626f,-0.128274f},{-0.28913f,-0.944741f,-0.154497f}, +{-0.285106f,-0.941285f,-0.180824f},{-0.280406f,-0.937248f,-0.207214f},{-0.27502f,-0.932622f,-0.233625f}, +{-0.268937f,-0.927398f,-0.260012f},{-0.262152f,-0.92157f,-0.286331f},{-0.254659f,-0.915135f,-0.312533f}, +{-0.503721f,-0.757119f,-0.415977f},{-0.674898f,-0.579657f,-0.45663f},{-0.237545f,-0.900436f,-0.3644f}, +{-0.227927f,-0.892174f,-0.389967f},{-0.217606f,-0.88331f,-0.415224f},{-0.206591f,-0.87385f,-0.440122f}, +{-0.182522f,-0.853177f,-0.488646f},{-0.155832f,-0.830254f,-0.535159f},{-0.410442f,-0.677003f,-0.610904f}, +{-0.141551f,-0.817988f,-0.557547f},{-0.126675f,-0.805212f,-0.579299f},{-0.095243f,-0.778215f,-0.620733f}, +{-0.283151f,-0.567676f,-0.773026f},{-0.0617581f,-0.749456f,-0.659168f},{-0.0443242f,-0.734482f,-0.677179f}, +{-0.0264735f,-0.71915f,-0.69435f},{-0.008241f,-0.703491f,-0.710657f},{0.0103371f,-0.687534f,-0.726078f}, +{0.048385f,-0.654856f,-0.754203f},{-0.15518f,-0.457764f,-0.875426f},{0.0873729f,-0.62137f,-0.778631f}, +{0.107127f,-0.604404f,-0.789443f},{0.127004f,-0.587331f,-0.79932f},{0.146969f,-0.570183f,-0.808264f}, +{0.187022f,-0.535783f,-0.823383f},{0.227014f,-0.501435f,-0.834882f},{0.246907f,-0.484349f,-0.839311f}, +{0.266692f,-0.467356f,-0.842884f},{0.536319f,-0.624439f,-0.567836f},{-0.569536f,-0.813646f,-0.116657f}, +{-0.566442f,-0.810988f,-0.146429f},{-0.558013f,-0.803749f,-0.206418f},{-0.552648f,-0.799142f,-0.236543f}, +{-0.546499f,-0.79386f,-0.266692f},{-0.539556f,-0.787897f,-0.296814f},{-0.53181f,-0.781244f,-0.326857f}, +{-0.513894f,-0.765856f,-0.386494f},{-0.480959f,-0.737569f,-0.473994f},{-0.468385f,-0.726769f,-0.502416f}, +{-0.45503f,-0.715299f,-0.530373f},{-0.440909f,-0.703171f,-0.557808f},{-0.39414f,-0.663001f,-0.636461f}, +{-0.377159f,-0.648417f,-0.661292f},{-0.359528f,-0.633274f,-0.68535f},{-0.341277f,-0.617599f,-0.708591f}, +{-0.322441f,-0.601421f,-0.730976f},{-0.262774f,-0.550174f,-0.792627f},{-0.241961f,-0.532298f,-0.811242f}, +{-0.220753f,-0.514083f,-0.828846f},{-0.199192f,-0.495565f,-0.845422f},{-0.132814f,-0.438554f,-0.888837f}, +{-0.0875737f,-0.399698f,-0.912454f},{-0.0647825f,-0.380123f,-0.922664f},{-0.0419318f,-0.360497f,-0.931817f}, +{-0.0190608f,-0.340853f,-0.939923f},{0.00379256f,-0.321225f,-0.946995f},{0.0265911f,-0.301644f,-0.95305f}, +{0.0493f,-0.28214f,-0.958106f},{0.0718851f,-0.262741f,-0.962185f},{0.0943152f,-0.243477f,-0.96531f}, +{0.11656f,-0.224371f,-0.967508f},{-0.755608f,-0.648978f,-0.0887968f},{-0.742337f,-0.63758f,-0.205979f}, +{-0.737381f,-0.633323f,-0.234887f},{-0.731777f,-0.628509f,-0.263588f},{-0.72553f,-0.623144f,-0.292057f}, +{-0.718646f,-0.617231f,-0.320271f},{-0.711131f,-0.610777f,-0.348202f},{-0.702991f,-0.603786f,-0.375828f}, +{-0.684866f,-0.588219f,-0.430066f},{-0.629191f,-0.5404f,-0.558647f},{-0.589074f,-0.505945f,-0.630088f}, +{-0.544304f,-0.467493f,-0.696551f},{-0.512045f,-0.439786f,-0.737834f},{-0.477987f,-0.410534f,-0.776525f}, +{-0.44225f,-0.37984f,-0.812488f},{-0.385773f,-0.331333f,-0.861045f},{-0.366247f,-0.314563f,-0.875736f}, +{-0.326248f,-0.280208f,-0.902799f},{-0.30581f,-0.262654f,-0.915146f},{-0.221554f,-0.190289f,-0.956402f}, +{-0.199957f,-0.171739f,-0.964636f},{-0.178184f,-0.153039f,-0.972023f},{-0.134188f,-0.115252f,-0.984231f}, +{-0.112004f,-0.0961983f,-0.98904f},{-0.0897214f,-0.07706f,-0.992981f},{-0.0673596f,-0.0578539f,-0.99605f}, +{-0.044939f,-0.0385973f,-0.998244f},{-0.775794f,-0.341832f,-0.530373f},{-0.761673f,-0.329704f,-0.557808f}, +{-0.76494f,0.629065f,-0.138358f},{-0.864516f,0.312051f,-0.394f},{-0.874608f,0.303383f,-0.378179f}, +{-0.801723f,-0.364102f,-0.473994f},{-0.653193f,-0.561015f,-0.508529f},{-0.789149f,-0.353302f,-0.502416f}, +{-0.684867f,-0.58822f,-0.430063f},{-0.824484f,-0.383652f,-0.415977f},{-0.694234f,-0.596265f,-0.403122f}, +{-0.852574f,-0.407777f,-0.326857f},{-0.93865f,0.248379f,-0.239258f},{-0.860319f,-0.41443f,-0.296814f}, +{-0.725531f,-0.623145f,-0.292055f},{-0.731777f,-0.62851f,-0.263585f},{-0.873412f,-0.425675f,-0.236543f}, +{-0.878777f,-0.430282f,-0.206418f},{-0.737381f,-0.633323f,-0.234884f},{-0.746642f,-0.641277f,-0.176888f}, +{-0.887205f,-0.437522f,-0.146429f},{-0.750291f,-0.64441f,-0.147645f},{-0.8903f,-0.440179f,-0.116657f}, +{-0.75328f,-0.646978f,-0.118272f},{-0.892671f,-0.442216f,-0.0870897f},{-0.985709f,-0.150194f,-0.0762915f}, +{-0.983632f,-0.14841f,-0.102193f},{0.758272f,0.651265f,0.0296337f},{0.574558f,0.81796f,0.0287252f}, +{0.2996f,0.953733f,0.0251636f},{-0.0662783f,0.997643f,0.0177823f},{0.0755427f,0.997143f,4.44435e-016f}, +{0.564043f,0.825745f,3.04136e-016f},{0.573574f,0.817114f,0.0577667f},{0.297277f,0.951738f,0.0762915f}, +{-0.755608f,-0.648978f,-0.0887942f},{-0.974563f,0.217534f,-0.0539127f},{-0.973095f,0.218795f,-0.0722163f}, +{-0.800972f,0.598118f,-0.0264206f},{-0.971179f,0.22044f,-0.0906467f},{-0.801509f,0.597657f,-0.0197242f}, +{-0.757272f,-0.650407f,-0.059239f},{-0.894338f,-0.443647f,-0.0577667f},{-0.997238f,0.0742779f,-4.48371e-016f}, +{-0.976204f,0.216125f,-0.0177823f},{-0.988031f,-0.152189f,-0.0251636f},{-0.943289f,0.331972f,-4.29587e-016f}, +{-0.80211f,0.597142f,-0.00650572f},{-0.825457f,0.564465f,-3.05233e-016f},{-0.983078f,-0.183188f,-6.14496e-016f}, +{-0.895322f,-0.444493f,-0.0287252f},{-0.901253f,-0.433294f,-9.46059e-016f},{-0.758272f,-0.651265f,-0.0296322f}, +{-0.46921f,0.883063f,0.00650572f},{-0.184979f,0.982742f,5.48296e-016f},{-0.616357f,-0.529378f,-0.582978f}, +{-0.746803f,-0.316933f,-0.58467f},{-0.731206f,-0.303536f,-0.610904f},{-0.589075f,-0.505946f,-0.630087f}, +{-0.697922f,-0.27495f,-0.661292f},{-0.559724f,-0.480737f,-0.674982f},{-0.680291f,-0.259807f,-0.68535f}, +{-0.528407f,-0.453839f,-0.717507f},{-0.662041f,-0.244132f,-0.708591f},{-0.75019f,0.0520889f,-0.659168f}, +{-0.820131f,0.350173f,-0.452509f},{-0.808129f,0.360481f,-0.465812f},{-0.643204f,-0.227954f,-0.730976f}, +{-0.623817f,-0.211302f,-0.752465f},{-0.477988f,-0.410535f,-0.776523f},{-0.583538f,-0.176707f,-0.792627f}, +{-0.423793f,-0.363987f,-0.829405f},{-0.562725f,-0.158831f,-0.811242f},{-0.541517f,-0.140616f,-0.828846f}, +{-0.519956f,-0.122098f,-0.845422f},{-0.707128f,0.678719f,-0.198267f},{-0.702743f,0.450995f,-0.550232f}, +{-0.475944f,-0.0842968f,-0.875426f},{-0.346402f,-0.297518f,-0.889657f},{-0.32625f,-0.28021f,-0.902798f}, +{-0.305812f,-0.262656f,-0.915145f},{-0.285105f,-0.244871f,-0.926689f},{-0.453578f,-0.065087f,-0.888837f}, +{-0.431028f,-0.0457196f,-0.901179f},{-0.264148f,-0.226872f,-0.937419f},{-0.408337f,-0.0262308f,-0.912454f}, +{-0.242959f,-0.208673f,-0.947326f},{-0.221556f,-0.19029f,-0.956401f},{-0.385546f,-0.00665601f,-0.922665f}, +{-0.362695f,0.0129701f,-0.931817f},{-0.199959f,-0.171741f,-0.964635f},{-0.339824f,0.0326136f,-0.939923f}, +{-0.48139f,0.282956f,-0.829578f},{-0.316971f,0.0522418f,-0.946995f},{-0.501409f,0.265762f,-0.823383f}, +{-0.178186f,-0.153041f,-0.972023f},{-0.294173f,0.0718231f,-0.95305f},{-0.156257f,-0.134206f,-0.978556f}, +{-0.248878f,0.110725f,-0.962185f},{-0.441525f,0.317195f,-0.839311f},{-0.42174f,0.334188f,-0.842884f}, +{-0.13419f,-0.115253f,-0.98423f},{-0.650623f,0.727251f,-0.218624f},{-0.620697f,0.752953f,0.218624f}, +{-0.645585f,0.731578f,-0.219122f},{-0.665961f,0.714077f,-0.215848f},{-0.660818f,0.718494f,-0.216993f}, +{-0.590006f,0.547823f,-0.593113f},{-0.286341f,0.45048f,0.845622f},{-0.480343f,0.642011f,0.597573f}, +{-0.266692f,0.467356f,0.842884f},{-0.325127f,0.417168f,0.848684f},{-0.432488f,0.503548f,0.747926f}, +{-0.507751f,0.61847f,0.599737f},{-0.548369f,0.583584f,-0.598933f},{-0.562139f,0.571757f,-0.597573f}, +{-0.304133f,0.354104f,0.884372f},{-0.138591f,0.205449f,0.968805f},{-0.155494f,0.181043f,0.971105f}, +{-0.576025f,0.559831f,-0.595638f},{-0.655703f,0.722888f,-0.217916f},{-0.382604f,0.367801f,-0.847547f}, +{-0.402091f,0.351064f,-0.845622f},{0.0224792f,0.0193069f,0.999561f},{-0.271464f,0.0913273f,-0.958106f}, +{-0.226448f,0.12999f,-0.96531f},{-0.204204f,0.149095f,-0.967508f},{-0.0673616f,-0.0578556f,-0.99605f}, +{-0.182173f,0.168017f,-0.968805f},{-0.0224803f,-0.0193079f,-0.999561f},{-0.0449408f,-0.0385988f,-0.998244f}, +{-0.155937f,0.181559f,-0.970938f},{-0.433008f,0.90139f,1.81967e-016f},{-0.987169f,-0.151448f,-0.0506042f}, +{-0.980921f,-0.146082f,-0.128274f},{-0.977561f,-0.143196f,-0.154497f},{-0.973538f,-0.13974f,-0.180824f}, +{-0.968838f,-0.135704f,-0.207214f},{-0.957369f,-0.125853f,-0.260012f},{-0.950583f,-0.120025f,-0.286331f}, +{-0.943091f,-0.11359f,-0.312533f},{-0.934889f,-0.106546f,-0.338573f},{-0.916358f,-0.0906299f,-0.389967f}, +{-0.906037f,-0.0817656f,-0.415224f},{-0.895022f,-0.072305f,-0.440122f},{-0.883323f,-0.0622569f,-0.464612f}, +{-0.870953f,-0.0516324f,-0.488646f},{-0.857927f,-0.0404447f,-0.512177f},{-0.844263f,-0.0287093f,-0.535159f}, +{-0.829983f,-0.0164437f,-0.557547f},{-0.815107f,-0.00366744f,-0.579299f},{-0.783674f,0.0233295f,-0.620733f}, +{-0.767173f,0.0375019f,-0.640343f},{-0.732756f,0.0670627f,-0.677179f},{-0.714905f,0.0823942f,-0.69435f}, +{-0.678094f,0.11401f,-0.726078f},{-0.659207f,0.130232f,-0.740598f},{-0.640047f,0.146689f,-0.754203f}, +{-0.620651f,0.163347f,-0.766883f},{-0.601058f,0.180175f,-0.778631f},{-0.581305f,0.197141f,-0.789443f}, +{-0.561427f,0.214213f,-0.79932f},{-0.541462f,0.231361f,-0.808264f},{-0.521445f,0.248554f,-0.816282f}, +{-0.461418f,0.30011f,-0.834882f},{-0.604064f,0.535749f,-0.589983f},{-0.363305f,0.384377f,-0.848684f}, +{0.757272f,0.650407f,0.0592414f},{-0.975595f,0.216648f,-0.0357603f},{-0.968805f,0.222479f,-0.109178f}, +{-0.965962f,0.224921f,-0.127782f},{-0.962641f,0.227774f,-0.146431f},{-0.954536f,0.234735f,-0.183742f}, +{-0.949741f,0.238853f,-0.20234f},{-0.918261f,0.26589f,-0.293425f},{-0.925555f,0.259626f,-0.275577f}, +{-0.783579f,0.613057f,-0.100821f},{-0.910478f,0.272576f,-0.31102f},{-0.90221f,0.279676f,-0.328326f}, +{-0.893469f,0.287184f,-0.34531f},{-0.884264f,0.29509f,-0.361938f},{-0.854004f,0.32108f,-0.409371f}, +{-0.831792f,0.340158f,-0.438652f},{-0.731496f,0.65779f,-0.179515f},{-0.726783f,0.661838f,-0.183731f}, +{-0.795809f,0.371062f,-0.47854f},{-0.783195f,0.381897f,-0.490674f},{-0.770311f,0.392963f,-0.502197f}, +{-0.757182f,0.404239f,-0.513095f},{-0.743835f,0.415702f,-0.523356f},{-0.730295f,0.427331f,-0.53297f}, +{-0.674737f,0.475049f,-0.564853f},{-0.660628f,0.487166f,-0.571173f},{-0.632324f,0.511476f,-0.581857f}, +{-0.640595f,0.735863f,-0.219416f},{-0.630724f,0.744341f,0.219416f},{-0.534731f,0.595298f,-0.599736f}, +{-0.431242f,0.502097f,-0.749619f},{-0.801887f,0.597333f,-0.013083f},{-0.800271f,0.59872f,-0.0331634f}, +{-0.799403f,0.599466f,-0.0399431f},{-0.474172f,0.878801f,0.0535724f},{-0.795755f,0.6026f,-0.0604006f}, +{-0.797147f,0.601403f,-0.0535725f},{-0.798362f,0.60036f,-0.0467496f},{-0.794182f,0.60395f,-0.0672227f}, +{-0.792428f,0.605457f,-0.0740269f},{-0.790491f,0.607121f,-0.0808013f},{-0.78837f,0.608942f,-0.0875334f}, +{-0.786066f,0.610921f,-0.0942108f},{-0.493256f,0.86241f,0.113788f},{-0.775039f,0.620392f,-0.120119f}, +{-0.778063f,0.617794f,-0.113788f},{-0.780911f,0.615348f,-0.107351f},{-0.771841f,0.623139f,-0.126333f}, +{-0.768473f,0.626031f,-0.132417f},{-0.513917f,0.844665f,0.14977f},{-0.753409f,0.638969f,-0.155219f}, +{-0.757402f,0.63554f,-0.14977f},{-0.761248f,0.632237f,-0.144146f},{-0.749276f,0.642519f,-0.160482f}, +{-0.74501f,0.646183f,-0.165552f},{-0.740619f,0.649955f,-0.170419f},{-0.736112f,0.653826f,-0.175076f}, +{-0.72198f,0.665964f,-0.187718f},{-0.717096f,0.670158f,-0.191472f},{-0.712143f,0.674412f,-0.194989f}, +{-0.574363f,0.792748f,0.2041f},{-0.691817f,0.69187f,-0.206653f},{-0.696956f,0.687456f,-0.2041f}, +{-0.702063f,0.68307f,-0.201304f},{-0.686655f,0.696303f,-0.208966f},{-0.68148f,0.700748f,-0.211039f}, +{-0.6763f,0.705197f,-0.212874f},{-0.671124f,0.709642f,-0.214476f},{-0.494113f,0.630183f,0.598933f}, +{-0.615617f,0.757316f,0.217917f},{-0.609092f,0.70917f,-0.355084f},{-0.536047f,0.624123f,-0.56844f}, +{-0.46981f,0.882547f,0.0197241f},{-0.469433f,0.882871f,0.0130831f},{-0.470347f,0.882086f,0.0264206f}, +{-0.471048f,0.881484f,0.0331634f},{-0.471917f,0.880738f,0.0399431f},{-0.472957f,0.879844f,0.0467496f}, +{-0.480829f,0.873084f,0.0808012f},{-0.478891f,0.874747f,0.074027f},{-0.0927413f,0.974914f,0.20234f}, +{-0.477137f,0.876254f,0.0672226f},{-0.482949f,0.871262f,0.0875334f},{-0.48774f,0.867147f,0.100821f}, +{-0.490408f,0.864856f,0.107351f},{0.169495f,0.841989f,0.512177f},{-0.158218f,0.918677f,0.361938f}, +{0.182522f,0.853177f,0.488646f},{-0.496281f,0.859812f,0.120119f},{-0.499479f,0.857065f,0.126333f}, +{-0.502847f,0.854173f,0.132416f},{-0.506379f,0.851139f,0.138358f},{-0.510071f,0.847968f,0.144146f}, +{0.078742f,0.764043f,0.640343f},{-0.222351f,0.863595f,0.452509f},{0.095243f,0.778215f,0.620733f}, +{-0.522044f,0.837685f,0.160482f},{-0.52631f,0.834021f,0.165552f},{-0.530701f,0.830249f,0.170419f}, +{-0.535208f,0.826378f,0.175076f},{-0.554223f,0.810046f,0.191472f},{-0.54934f,0.814241f,0.187718f}, +{-0.2853f,0.809529f,0.513095f},{-0.544537f,0.818366f,0.183731f},{-0.559177f,0.805792f,0.194989f}, +{-0.569257f,0.797135f,0.201304f},{-0.579503f,0.788334f,0.206653f},{-0.595019f,0.775007f,0.212874f}, +{-0.584664f,0.783901f,0.208966f},{-0.605359f,0.766127f,0.215847f},{-0.610502f,0.76171f,0.216993f}, +{-0.466457f,0.653936f,0.595638f},{-0.0668873f,0.997119f,0.0357603f},{-0.0693872f,0.994972f,0.0722163f}, +{-0.0713027f,0.993327f,0.0906467f},{-0.0736769f,0.991288f,0.109178f},{-0.0765202f,0.988846f,0.127782f}, +{-0.0798415f,0.985994f,0.146431f},{-0.0879462f,0.979032f,0.183742f},{0.254659f,0.915135f,0.312533f}, +{0.246457f,0.90809f,0.338573f},{-0.103832f,0.965388f,0.239258f},{-0.0980359f,0.970367f,0.220857f}, +{-0.11013f,0.959979f,0.257509f},{-0.116927f,0.954141f,0.275577f},{-0.12422f,0.947877f,0.293425f}, +{-0.132004f,0.941192f,0.31102f},{-0.140272f,0.934091f,0.328326f},{-0.149013f,0.926583f,0.34531f}, +{-0.167874f,0.910384f,0.378179f},{-0.177966f,0.901716f,0.394f},{-0.188478f,0.892688f,0.409371f}, +{-0.199392f,0.883313f,0.424264f},{-0.21069f,0.87361f,0.438652f},{-0.234353f,0.853287f,0.465812f}, +{-0.246673f,0.842705f,0.47854f},{-0.259287f,0.831871f,0.490674f},{-0.272171f,0.820805f,0.502197f}, +{-0.0292248f,0.671312f,0.740598f},{-0.0483848f,0.654856f,0.754203f},{-0.312187f,0.786436f,0.53297f}, +{-0.298647f,0.798065f,0.523356f},{-0.325893f,0.774664f,0.541931f},{-0.339739f,0.762773f,0.550232f}, +{-0.353698f,0.750783f,0.557873f},{-0.367745f,0.738719f,0.564853f},{-0.381854f,0.726601f,0.571173f}, +{-0.207042f,0.518588f,0.829578f},{-0.227014f,0.501435f,0.834882f},{-0.438418f,0.678019f,0.589983f}, +{-0.424305f,0.69014f,0.586235f},{-0.452476f,0.665945f,0.593113f},{-0.609586f,0.709744f,0.353084f}, +{0.339059f,0.940765f,5.47231e-016f},{0.298738f,0.952993f,0.0506042f},{0.2952f,0.949954f,0.102193f}, +{0.29249f,0.947626f,0.128274f},{0.569536f,0.813646f,0.116657f},{0.28913f,0.944741f,0.154497f}, +{0.285106f,0.941285f,0.180824f},{0.280406f,0.937248f,0.207214f},{0.27502f,0.932622f,0.233625f}, +{0.268937f,0.927398f,0.260012f},{0.262152f,0.92157f,0.286331f},{0.674898f,0.579657f,0.45663f}, +{0.492741f,0.747688f,0.445162f},{0.237545f,0.900436f,0.3644f},{0.227927f,0.892174f,0.389967f}, +{0.217606f,0.88331f,0.415224f},{0.206591f,0.87385f,0.440122f},{0.194892f,0.863801f,0.464612f}, +{0.141551f,0.817988f,0.557547f},{0.126676f,0.805212f,0.579299f},{0.11123f,0.791947f,0.600374f}, +{0.46032f,0.39536f,0.794856f},{0.0617581f,0.749456f,0.659168f},{0.0443242f,0.734482f,0.677179f}, +{0.0264735f,0.71915f,0.69435f},{0.008241f,0.703491f,0.710657f},{-0.0103371f,0.687534f,0.726078f}, +{0.15518f,0.457764f,0.875426f},{-0.0677801f,0.638198f,0.766883f},{0.177321f,0.476779f,0.860952f}, +{-0.0873729f,0.62137f,0.778631f},{-0.127004f,0.587331f,0.79932f},{-0.146969f,0.570183f,0.808264f}, +{-0.166987f,0.552991f,0.816282f},{-0.187022f,0.535783f,0.823383f},{-0.246907f,0.484349f,0.839311f}, +{-0.11656f,0.224372f,0.967508f},{-0.0943152f,0.243477f,0.96531f},{-0.305827f,0.433744f,0.847547f}, +{-0.536319f,0.624439f,0.567837f},{0.566442f,0.810988f,0.146429f},{0.562606f,0.807694f,0.176364f}, +{0.558013f,0.803749f,0.206418f},{0.552648f,0.799142f,0.236543f},{0.546499f,0.79386f,0.266692f}, +{0.539556f,0.787897f,0.296814f},{0.513894f,0.765856f,0.386494f},{0.480959f,0.737569f,0.473994f}, +{0.468385f,0.726769f,0.502416f},{0.45503f,0.715299f,0.530373f},{0.440909f,0.703171f,0.557808f}, +{0.39414f,0.663001f,0.636461f},{0.377159f,0.648417f,0.661292f},{0.341277f,0.617599f,0.708591f}, +{0.322441f,0.601421f,0.730976f},{0.262774f,0.550174f,0.792627f},{0.241961f,0.532298f,0.811242f}, +{0.220753f,0.514083f,0.828846f},{0.199192f,0.495565f,0.845422f},{0.132814f,0.438554f,0.888837f}, +{0.110264f,0.419187f,0.901179f},{0.0875737f,0.399698f,0.912454f},{0.0647826f,0.380123f,0.922665f}, +{0.0419317f,0.360497f,0.931817f},{0.0190608f,0.340853f,0.939923f},{-0.00379247f,0.321225f,0.946995f}, +{-0.0493001f,0.28214f,0.958106f},{0.755608f,0.648977f,0.0887968f},{0.742337f,0.63758f,0.205979f}, +{0.737381f,0.633323f,0.234887f},{0.731777f,0.628509f,0.263588f},{0.72553f,0.623144f,0.292057f}, +{0.718646f,0.617231f,0.320271f},{0.702991f,0.603786f,0.375828f},{0.684866f,0.588219f,0.430066f}, +{0.664336f,0.570586f,0.482793f},{0.589074f,0.505945f,0.630088f},{0.559723f,0.480736f,0.674983f}, +{0.544304f,0.467493f,0.696551f},{0.528406f,0.453838f,0.717508f},{0.477987f,0.410534f,0.776525f}, +{0.44225f,0.37984f,0.812488f},{0.385773f,0.331333f,0.861045f},{0.366247f,0.314563f,0.875736f}, +{0.326248f,0.280208f,0.902799f},{0.30581f,0.262654f,0.915146f},{0.242957f,0.208671f,0.947327f}, +{0.221554f,0.190289f,0.956402f},{0.199957f,0.171739f,0.964636f},{0.178184f,0.153039f,0.972023f}, +{0.134188f,0.115252f,0.984231f},{0.112004f,0.0961983f,0.98904f},{0.0897214f,0.07706f,0.992981f}, +{0.0673596f,0.0578539f,0.99605f},{0.044939f,0.0385973f,0.998244f},{-0.222351f,0.863595f,-0.452509f}, +{-0.234353f,0.853287f,-0.465812f},{-0.530701f,0.830249f,-0.170419f},{0.220753f,0.514083f,-0.828846f}, +{0.385773f,0.331333f,-0.861045f},{0.241961f,0.532298f,-0.811242f},{0.199192f,0.495565f,-0.845422f}, +{0.366247f,0.314563f,-0.875736f},{0.30581f,0.262654f,-0.915146f},{0.15518f,0.457764f,-0.875426f}, +{0.326248f,0.280208f,-0.902799f},{0.132814f,0.438554f,-0.888837f},{0.0875736f,0.399698f,-0.912454f}, +{-0.339739f,0.762773f,-0.550232f},{0.0647826f,0.380123f,-0.922665f},{0.0419318f,0.360497f,-0.931817f}, +{0.221554f,0.190289f,-0.956402f},{0.199957f,0.171739f,-0.964636f},{0.0190607f,0.340853f,-0.939923f}, +{0.178184f,0.153039f,-0.972023f},{0.134188f,0.115252f,-0.984231f},{-0.0265912f,0.301644f,-0.95305f}, +{-0.0037925f,0.321225f,-0.946995f},{0.112004f,0.0961983f,-0.98904f},{-0.0492999f,0.28214f,-0.958106f}, +{0.0897213f,0.07706f,-0.992981f},{-0.0718852f,0.262742f,-0.962185f},{-0.155937f,0.181559f,0.970938f}, +{-0.0224803f,-0.0193079f,0.999561f},{-0.0943152f,0.243477f,-0.96531f},{-0.182173f,0.168017f,0.968805f}, +{-0.286341f,0.45048f,-0.845622f},{-0.266692f,0.467356f,-0.842884f},{-0.226448f,0.12999f,0.96531f}, +{-0.402091f,0.351065f,0.845622f},{-0.204204f,0.149095f,0.967508f},{-0.615617f,0.757316f,-0.217916f}, +{-0.452476f,0.665945f,-0.593113f},{-0.534731f,0.595298f,0.599736f},{-0.640595f,0.735863f,0.219416f}, +{-0.431242f,0.502097f,0.749619f},{-0.363305f,0.384377f,0.848684f},{0.0673597f,0.0578539f,-0.99605f}, +{-0.480343f,0.642011f,-0.597573f},{-0.630724f,0.744341f,-0.219416f},{-0.138591f,0.205449f,-0.968805f}, +{-0.304133f,0.354104f,-0.884372f},{-0.325126f,0.417168f,-0.848684f},{0.044939f,0.0385972f,-0.998244f}, +{-0.11656f,0.224371f,-0.967508f},{-0.507751f,0.61847f,-0.599736f},{-0.609586f,0.709744f,-0.353084f}, +{-0.536319f,0.624439f,-0.567836f},{-0.155494f,0.181042f,-0.971105f},{0.0224791f,0.0193069f,-0.999561f}, +{-0.620697f,0.752953f,-0.218624f},{0.262774f,0.550174f,-0.792627f},{0.44225f,0.37984f,-0.812488f}, +{0.283151f,0.567676f,-0.773026f},{0.477987f,0.410534f,-0.776525f},{0.512045f,0.439786f,-0.737834f}, +{0.322441f,0.601421f,-0.730976f},{0.341277f,0.617599f,-0.708591f},{0.359528f,0.633274f,-0.68535f}, +{0.544304f,0.467493f,-0.696551f},{0.377159f,0.648417f,-0.661292f},{0.155832f,0.830254f,-0.535159f}, +{-0.177966f,0.901716f,-0.394f},{-0.167874f,0.910384f,-0.378179f},{0.39414f,0.663002f,-0.636461f}, +{0.410442f,0.677003f,-0.610904f},{0.589074f,0.505945f,-0.630089f},{0.440909f,0.703171f,-0.557808f}, +{0.629191f,0.5404f,-0.558647f},{0.45503f,0.715299f,-0.530373f},{0.468385f,0.726769f,-0.502416f}, +{0.480959f,0.737569f,-0.473994f},{-0.485253f,0.869283f,-0.0942108f},{-0.103832f,0.965388f,-0.239258f}, +{0.503721f,0.757119f,-0.415977f},{0.674898f,0.579657f,-0.45663f},{0.684866f,0.588219f,-0.430066f}, +{0.702991f,0.603786f,-0.375828f},{0.513894f,0.765856f,-0.386494f},{0.711131f,0.610777f,-0.348202f}, +{0.53181f,0.781244f,-0.326857f},{0.718646f,0.617231f,-0.32027f},{0.72553f,0.623144f,-0.292057f}, +{0.539556f,0.787897f,-0.296814f},{0.546499f,0.79386f,-0.266692f},{0.731777f,0.628509f,-0.263588f}, +{0.552648f,0.799142f,-0.236543f},{0.285106f,0.941285f,-0.180824f},{0.558013f,0.803749f,-0.206418f}, +{0.280406f,0.937248f,-0.207214f},{0.737381f,0.633323f,-0.234887f},{0.742337f,0.63758f,-0.205979f}, +{-0.0662782f,0.997643f,-0.0177823f},{-0.469433f,0.882871f,-0.0130831f},{-0.46921f,0.883063f,-0.00650573f}, +{-0.974563f,0.217534f,0.0539127f},{-0.801509f,0.597657f,0.0197241f},{-0.973095f,0.218795f,0.0722163f}, +{0.292489f,0.947626f,-0.128274f},{0.2952f,0.949955f,-0.102193f},{0.569536f,0.813646f,-0.116657f}, +{-0.985709f,-0.150194f,0.0762915f},{-0.983632f,-0.14841f,0.102193f},{-0.988031f,-0.152188f,0.0251637f}, +{-0.997238f,0.0742779f,1.11285e-016f},{-0.976204f,0.216125f,0.0177823f},{-0.470347f,0.882086f,-0.0264206f}, +{-0.0679194f,0.996233f,-0.0539127f},{-0.069387f,0.994972f,-0.0722163f},{-0.895322f,-0.444493f,0.0287253f}, +{-0.983078f,-0.183188f,4.07949e-016f},{-0.471048f,0.881484f,-0.0331634f},{-0.0713026f,0.993327f,-0.0906466f}, +{-0.471917f,0.880738f,-0.0399431f},{-0.901253f,-0.433294f,3.52919e-035f},{0.566442f,0.810988f,-0.146429f}, +{0.573574f,0.817114f,-0.0577667f},{0.297277f,0.951738f,-0.0762915f},{0.755608f,0.648977f,-0.0887967f}, +{0.757272f,0.650407f,-0.0592414f},{0.758271f,0.651265f,-0.0296338f},{0.574558f,0.81796f,-0.0287253f}, +{-0.432488f,0.503548f,-0.747926f},{-0.305827f,0.433744f,-0.847547f},{-0.246907f,0.484349f,-0.839311f}, +{-0.227014f,0.501435f,-0.834882f},{-0.207042f,0.518588f,-0.829578f},{-0.187022f,0.535783f,-0.823383f}, +{-0.146969f,0.570184f,-0.808264f},{-0.127004f,0.587331f,-0.79932f},{-0.107127f,0.604404f,-0.789443f}, +{-0.087373f,0.62137f,-0.778631f},{-0.0483849f,0.654856f,-0.754203f},{-0.0292249f,0.671312f,-0.740598f}, +{-0.0103372f,0.687534f,-0.726078f},{0.00824112f,0.703491f,-0.710657f},{0.0264736f,0.71915f,-0.69435f}, +{0.0443241f,0.734482f,-0.677179f},{0.0617582f,0.749456f,-0.659168f},{0.0787419f,0.764043f,-0.640343f}, +{0.0952429f,0.778215f,-0.620734f},{0.126676f,0.805212f,-0.579299f},{0.141551f,0.817988f,-0.557547f}, +{0.169496f,0.841989f,-0.512177f},{0.182522f,0.853177f,-0.488646f},{0.206591f,0.87385f,-0.440122f}, +{0.217606f,0.88331f,-0.415224f},{0.227926f,0.892174f,-0.389967f},{0.237545f,0.900436f,-0.3644f}, +{0.246457f,0.90809f,-0.338573f},{0.254659f,0.915135f,-0.312533f},{0.262152f,0.92157f,-0.286331f}, +{0.268937f,0.927398f,-0.260012f},{0.27502f,0.932622f,-0.233625f},{0.28913f,0.944741f,-0.154497f}, +{-0.073677f,0.991288f,-0.109178f},{0.2996f,0.953733f,-0.0251637f},{0.298737f,0.952993f,-0.0506043f}, +{0.339059f,0.940765f,-2.28355e-016f},{0.564043f,0.825745f,-3.01839e-016f},{-0.494113f,0.630183f,-0.598933f}, +{-0.438418f,0.678019f,-0.589983f},{-0.424305f,0.69014f,-0.586235f},{-0.410158f,0.702291f,-0.581857f}, +{-0.381854f,0.726601f,-0.571173f},{-0.367745f,0.738719f,-0.564853f},{-0.298647f,0.798065f,-0.523356f}, +{-0.312187f,0.786436f,-0.53297f},{-0.559177f,0.805792f,-0.194989f},{-0.2853f,0.809529f,-0.513095f}, +{-0.272171f,0.820805f,-0.502197f},{-0.259287f,0.831871f,-0.490674f},{-0.246673f,0.842705f,-0.47854f}, +{-0.21069f,0.87361f,-0.438652f},{-0.188478f,0.892688f,-0.409371f},{-0.499479f,0.857065f,-0.126333f}, +{-0.771841f,0.623139f,0.126333f},{-0.496281f,0.859812f,-0.120119f},{-0.158218f,0.918677f,-0.361938f}, +{-0.149013f,0.926583f,-0.34531f},{-0.140272f,0.934091f,-0.328326f},{-0.132004f,0.941192f,-0.31102f}, +{-0.124221f,0.947877f,-0.293425f},{-0.116927f,0.954141f,-0.275577f},{-0.0927412f,0.974914f,-0.20234f}, +{-0.0879463f,0.979032f,-0.183742f},{-0.0798414f,0.985994f,-0.146431f},{-0.0765202f,0.988846f,-0.127782f}, +{-0.0668873f,0.997119f,-0.0357604f},{-0.46981f,0.882547f,-0.0197241f},{0.0755429f,0.997143f,-2.89047e-016f}, +{-0.0449408f,-0.0385988f,0.998244f},{-0.625735f,0.748626f,-0.219122f},{-0.610502f,0.76171f,-0.216993f}, +{-0.605359f,0.766127f,-0.215847f},{-0.6763f,0.705197f,0.212874f},{-0.58984f,0.779456f,-0.211039f}, +{-0.595019f,0.775007f,-0.212875f},{-0.600195f,0.770562f,-0.214476f},{-0.584664f,0.783901f,-0.208966f}, +{-0.579503f,0.788334f,-0.206653f},{-0.574364f,0.792748f,-0.2041f},{-0.569256f,0.797135f,-0.201305f}, +{-0.564191f,0.801485f,-0.198267f},{-0.721979f,0.665964f,0.187718f},{-0.544537f,0.818366f,-0.183731f}, +{-0.54934f,0.814241f,-0.187718f},{-0.554223f,0.810046f,-0.191472f},{-0.539823f,0.822414f,-0.179515f}, +{-0.535208f,0.826378f,-0.175076f},{-0.749276f,0.642519f,0.160482f},{-0.51791f,0.841235f,-0.155219f}, +{-0.522044f,0.837685f,-0.160482f},{-0.52631f,0.834021f,-0.165552f},{-0.513917f,0.844665f,-0.14977f}, +{-0.510071f,0.847968f,-0.144146f},{-0.506379f,0.851139f,-0.138358f},{-0.502846f,0.854173f,-0.132417f}, +{-0.493256f,0.86241f,-0.113788f},{-0.490408f,0.864856f,-0.107351f},{-0.48774f,0.867148f,-0.100821f}, +{-0.790491f,0.60712f,0.0808013f},{-0.478892f,0.874747f,-0.0740269f},{-0.480829f,0.873084f,-0.0808013f}, +{-0.482949f,0.871262f,-0.0875334f},{-0.477137f,0.876254f,-0.0672227f},{-0.475565f,0.877605f,-0.0604006f}, +{-0.474172f,0.878801f,-0.0535724f},{-0.472957f,0.879844f,-0.0467496f},{-0.800972f,0.598118f,0.0264206f}, +{-0.184979f,0.982742f,-2.6491e-016f},{-0.650623f,0.727251f,0.218624f},{-0.645585f,0.731578f,0.219122f}, +{-0.655703f,0.722888f,0.217917f},{-0.660818f,0.718494f,0.216992f},{-0.665961f,0.714077f,0.215848f}, +{-0.671124f,0.709642f,0.214476f},{-0.696956f,0.687456f,0.2041f},{-0.691817f,0.69187f,0.206653f}, +{-0.674737f,0.475049f,0.564852f},{-0.686655f,0.696303f,0.208966f},{-0.702063f,0.68307f,0.201305f}, +{-0.712143f,0.674412f,0.194989f},{-0.717096f,0.670158f,0.191472f},{-0.732756f,0.0670628f,0.677179f}, +{-0.795809f,0.371062f,0.47854f},{-0.714905f,0.0823942f,0.69435f},{-0.726783f,0.661838f,0.183731f}, +{-0.731497f,0.65779f,0.179515f},{-0.736111f,0.653826f,0.175076f},{-0.740619f,0.649955f,0.170419f}, +{-0.74501f,0.646183f,0.165552f},{-0.829983f,-0.0164437f,0.557547f},{-0.864516f,0.312051f,0.394f}, +{-0.815107f,-0.00366745f,0.579299f},{-0.757402f,0.63554f,0.14977f},{-0.761248f,0.632236f,0.144146f}, +{-0.76494f,0.629065f,0.138358f},{-0.768473f,0.626031f,0.132417f},{-0.780911f,0.615349f,0.107351f}, +{-0.778063f,0.617794f,0.113788f},{-0.910477f,0.272576f,0.311019f},{-0.775039f,0.620392f,0.120119f}, +{-0.783579f,0.613057f,0.100821f},{-0.78837f,0.608942f,0.0875334f},{-0.792428f,0.605457f,0.0740269f}, +{-0.797147f,0.601403f,0.0535724f},{-0.794182f,0.60395f,0.0672227f},{-0.798362f,0.60036f,0.0467497f}, +{-0.799403f,0.599467f,0.0399431f},{-0.800271f,0.59872f,0.0331634f},{-0.801887f,0.597333f,0.0130831f}, +{-0.802109f,0.597142f,0.00650573f},{-0.651551f,0.758605f,-2.05938e-033f},{-0.433008f,0.90139f,-1.54031e-016f}, +{-0.548369f,0.583584f,0.598933f},{-0.576025f,0.559831f,0.595638f},{-0.590006f,0.547823f,0.593113f}, +{-0.604064f,0.535749f,0.589983f},{-0.618177f,0.523627f,0.586235f},{-0.632325f,0.511476f,0.581857f}, +{-0.660628f,0.487166f,0.571173f},{-0.581305f,0.197141f,0.789443f},{-0.601058f,0.180175f,0.778631f}, +{-0.702743f,0.450995f,0.550232f},{-0.688784f,0.462984f,0.557873f},{-0.716589f,0.439103f,0.541931f}, +{-0.730295f,0.427331f,0.53297f},{-0.743835f,0.415702f,0.523356f},{-0.757182f,0.404239f,0.513095f}, +{-0.770311f,0.392963f,0.502197f},{-0.783195f,0.381897f,0.490674f},{-0.808129f,0.360481f,0.465812f}, +{-0.820131f,0.350173f,0.452509f},{-0.831792f,0.340157f,0.438652f},{-0.84309f,0.330454f,0.424264f}, +{-0.854004f,0.32108f,0.409371f},{-0.874608f,0.303383f,0.378179f},{-0.884264f,0.29509f,0.361938f}, +{-0.893469f,0.287184f,0.34531f},{-0.90221f,0.279676f,0.328326f},{-0.906037f,-0.0817656f,0.415224f}, +{-0.916358f,-0.09063f,0.389967f},{-0.925555f,0.259626f,0.275577f},{-0.918261f,0.26589f,0.293425f}, +{-0.932352f,0.253788f,0.257509f},{-0.93865f,0.248379f,0.239258f},{-0.944446f,0.243401f,0.220857f}, +{-0.949741f,0.238853f,0.20234f},{-0.954536f,0.234735f,0.183742f},{-0.962641f,0.227774f,0.146431f}, +{-0.973538f,-0.13974f,0.180824f},{-0.977561f,-0.143196f,0.154497f},{-0.968805f,0.222479f,0.109178f}, +{-0.965962f,0.224922f,0.127782f},{-0.971179f,0.22044f,0.0906467f},{-0.975595f,0.216648f,0.0357604f}, +{-0.943289f,0.331972f,1.5621e-016f},{-0.825457f,0.564465f,6.56678e-035f},{-0.29793f,0.346881f,0.889332f}, +{-0.382604f,0.367801f,0.847547f},{-0.42174f,0.334188f,0.842884f},{-0.441525f,0.317195f,0.839311f}, +{-0.248878f,0.110725f,0.962185f},{-0.461418f,0.30011f,0.834882f},{-0.48139f,0.282956f,0.829578f}, +{-0.501409f,0.265762f,0.823383f},{-0.521445f,0.248554f,0.816282f},{-0.541462f,0.231361f,0.808264f}, +{-0.561427f,0.214213f,0.79932f},{-0.346402f,-0.297518f,0.889657f},{-0.498084f,-0.103313f,0.860952f}, +{-0.475944f,-0.0842968f,0.875426f},{-0.620651f,0.163347f,0.766883f},{-0.640047f,0.146689f,0.754203f}, +{-0.659207f,0.130232f,0.740598f},{-0.678094f,0.11401f,0.726078f},{-0.696673f,0.0980537f,0.710657f}, +{-0.767173f,0.0375018f,0.640343f},{-0.783674f,0.0233294f,0.620734f},{-0.799662f,0.00959819f,0.600374f}, +{-0.731206f,-0.303536f,0.610904f},{-0.602981f,-0.517889f,0.606799f},{-0.844264f,-0.0287092f,0.535159f}, +{-0.857927f,-0.0404448f,0.512177f},{-0.870953f,-0.0516324f,0.488646f},{-0.883323f,-0.0622568f,0.464612f}, +{-0.895022f,-0.072305f,0.440122f},{-0.824484f,-0.383652f,0.415977f},{-0.925977f,-0.0988912f,0.3644f}, +{-0.813504f,-0.374221f,0.445163f},{-0.934889f,-0.106546f,0.338573f},{-0.950583f,-0.120025f,0.286331f}, +{-0.957369f,-0.125853f,0.260012f},{-0.963451f,-0.131077f,0.233625f},{-0.968838f,-0.135704f,0.207214f}, +{-0.980921f,-0.146082f,0.128274f},{-0.894338f,-0.443647f,0.0577667f},{-0.892671f,-0.442216f,0.0870897f}, +{-0.987169f,-0.151448f,0.0506043f},{-0.271464f,0.0913273f,0.958106f},{-0.294173f,0.0718233f,0.95305f}, +{-0.316971f,0.0522418f,0.946995f},{-0.339824f,0.0326136f,0.939923f},{-0.362696f,0.0129702f,0.931817f}, +{-0.385546f,-0.00665603f,0.922665f},{-0.408337f,-0.0262309f,0.912454f},{-0.453578f,-0.0650871f,0.888837f}, +{-0.519956f,-0.122098f,0.845422f},{-0.541517f,-0.140616f,0.828846f},{-0.562725f,-0.158831f,0.811242f}, +{-0.583538f,-0.176707f,0.792627f},{-0.643204f,-0.227954f,0.730976f},{-0.662041f,-0.244132f,0.708591f}, +{-0.697922f,-0.27495f,0.661292f},{-0.714903f,-0.289534f,0.636461f},{-0.761673f,-0.329704f,0.557808f}, +{-0.775794f,-0.341832f,0.530373f},{-0.789149f,-0.353302f,0.502416f},{-0.801723f,-0.364102f,0.473994f}, +{-0.844021f,-0.400431f,0.356769f},{-0.852574f,-0.407777f,0.326857f},{-0.860319f,-0.41443f,0.296814f}, +{-0.867263f,-0.420393f,0.266692f},{-0.873412f,-0.425675f,0.236543f},{-0.878777f,-0.430282f,0.206418f}, +{-0.887205f,-0.437521f,0.146429f},{-0.8903f,-0.440179f,0.116657f},{-0.0673616f,-0.0578556f,0.99605f}, +{-0.0897231f,-0.0770615f,0.992981f},{-0.156257f,-0.134206f,0.978556f},{-0.178186f,-0.153041f,0.972023f}, +{-0.199959f,-0.171741f,0.964635f},{-0.221556f,-0.19029f,0.956401f},{-0.242959f,-0.208673f,0.947326f}, +{-0.285105f,-0.244871f,0.926689f},{-0.305812f,-0.262656f,0.915145f},{-0.32625f,-0.28021f,0.902798f}, +{-0.477988f,-0.410535f,0.776523f},{-0.512046f,-0.439786f,0.737833f},{-0.528407f,-0.453839f,0.717507f}, +{-0.544305f,-0.467493f,0.696551f},{-0.589075f,-0.505946f,0.630087f},{-0.616357f,-0.529378f,0.582978f}, +{-0.653193f,-0.561015f,0.508529f},{-0.684867f,-0.58822f,0.430063f},{-0.694234f,-0.596265f,0.403122f}, +{-0.718647f,-0.617232f,0.320268f},{-0.725531f,-0.623145f,0.292055f},{-0.731777f,-0.62851f,0.263585f}, +{-0.737381f,-0.633323f,0.234884f},{-0.746642f,-0.641277f,0.176888f},{-0.750291f,-0.64441f,0.147645f}, +{-0.75328f,-0.646978f,0.118272f},{-0.755608f,-0.648978f,0.0887941f},{-0.757272f,-0.650407f,0.0592391f}, +{-0.758272f,-0.651265f,0.0296323f},{-6.73779e-016f,-5.78696e-016f,1.0f},{9.28992e-017f,7.97894e-017f,1.0f}, +{7.40149e-017f,1.0f,1.85037e-017f},{-0.104013f,0.994576f,-2.52608e-018f},{0.105163f,0.994455f,-1.75194e-017f}, +{0.310578f,0.950548f,3.401e-017f},{0.194653f,0.980872f,4.88637e-017f},{0.382179f,0.924088f,2.46819e-017f}, +{0.670096f,0.742274f,5.21559e-017f},{0.555293f,0.831655f,1.71547e-017f},{0.50141f,0.86521f,-5.09311e-017f}, +{0.809606f,0.586974f,3.41454e-017f},{0.707075f,0.707139f,-4.75018e-018f},{0.831545f,0.555458f,1.51199e-017f}, +{0.913862f,0.406026f,-1.53953e-017f},{0.978254f,0.207408f,-1.49117e-017f},{0.923954f,0.382504f,8.43939e-018f}, +{1.0f,-1.57282e-016f,0.0f},{0.980825f,0.19489f,8.3164e-018f},{-0.196168f,0.98057f,-3.53809e-017f}, +{-0.308272f,0.951298f,-2.33067e-017f},{-0.384009f,0.923329f,6.85621e-017f},{-0.556611f,0.830773f,-3.33196e-017f}, +{-0.499433f,0.866353f,3.37942e-017f},{-0.707766f,0.706447f,2.28697e-017f},{-0.66887f,0.743379f,5.57946e-017f}, +{-0.808947f,0.587881f,2.83047e-017f},{-0.831851f,0.554999f,-3.91541e-017f},{-0.924075f,0.382212f,2.82894e-017f}, +{-0.913543f,0.406743f,-1.3996e-017f},{-0.98085f,0.194766f,1.44155e-017f},{-0.978165f,0.20783f,1.53825e-017f}, +{-1.0f,1.21431e-016f,0.0f},{-1.0f,1.22587e-016f,0.0f},{-0.475871f,0.197004f,-0.857167f}, +{-0.428277f,0.286082f,-0.857167f},{0.515038f,2.65357e-011f,-0.857167f},{-0.505162f,0.100376f,-0.857167f}, +{-0.515038f,8.7125e-012f,-0.857167f},{-0.36417f,0.364203f,-0.857167f},{-0.285997f,0.428334f,-0.857167f}, +{-0.196837f,0.475941f,-0.857167f},{-0.100254f,0.505186f,-0.857167f},{3.87126e-016f,0.515038f,-0.857167f}, +{0.19778f,0.47555f,-0.857167f},{0.101034f,0.505031f,-0.857167f},{0.364526f,0.363847f,-0.857167f}, +{0.286676f,0.42788f,-0.857167f},{0.475934f,0.196854f,-0.857167f},{0.428435f,0.285846f,-0.857167f}, +{0.515038f,5.63228e-016f,-0.857167f},{0.505175f,0.100312f,-0.857167f},{0.743195f,0.669075f,0.0f}, +{0.866128f,0.499822f,0.0f},{0.808688f,0.588238f,0.0f},{-4.44089e-017f,1.0f,0.0f}, +{-0.156467f,0.987683f,0.0f},{0.89086f,0.454278f,0.0f},{0.940023f,0.341112f,0.0f}, +{0.951024f,0.309116f,0.0f},{0.984831f,0.173514f,0.0f},{0.987686f,0.156452f,0.0f}, +{1.0f,5.55112e-018f,0.0f},{0.706727f,0.707486f,0.0f},{0.587512f,0.809215f,0.0f}, +{0.587575f,0.80917f,0.0f},{0.453641f,0.891185f,0.0f},{0.40683f,0.913504f,0.0f}, +{0.308716f,0.951154f,0.0f},{0.208031f,0.978122f,0.0f},{0.156246f,0.987718f,0.0f}, +{-0.40677f,0.91353f,0.0f},{-0.208006f,0.978127f,0.0f},{-0.309067f,0.95104f,0.0f}, +{-0.707621f,0.706592f,0.0f},{-0.587567f,0.809176f,0.0f},{-0.587746f,0.809045f,0.0f}, +{-0.454023f,0.89099f,0.0f},{-0.939985f,0.341216f,0.0f},{-0.866205f,0.499689f,0.0f}, +{-0.891077f,0.453852f,0.0f},{-0.743115f,0.669164f,0.0f},{-0.809929f,0.586527f,0.0f}, +{-0.987719f,0.156239f,0.0f},{-0.984781f,0.173802f,0.0f},{-0.951116f,0.308833f,0.0f}, +{-1.0f,-2.22045e-016f,0.0f},{-0.104013f,-0.994576f,-1.75012e-017f},{0.105163f,-0.994455f,-1.77626e-017f}, +{0.310578f,-0.950548f,4.93869e-018f},{0.194653f,-0.980872f,8.23072e-018f},{0.382179f,-0.924088f,-3.16302e-018f}, +{0.670096f,-0.742274f,-6.30166e-018f},{0.555293f,-0.831655f,-1.21778e-017f},{0.50141f,-0.86521f,-1.26379e-018f}, +{0.809606f,-0.586974f,-3.60649e-017f},{0.707075f,-0.707139f,4.52306e-017f},{0.831545f,-0.555458f,-2.40794e-017f}, +{0.913862f,-0.406026f,1.43248e-017f},{0.978254f,-0.207408f,2.12095e-017f},{0.923954f,-0.382504f,-2.4773e-017f}, +{0.980825f,-0.19489f,2.03008e-018f},{-0.196168f,-0.98057f,3.17611e-018f},{-0.308272f,-0.951298f,-1.70678e-017f}, +{-0.384009f,-0.923329f,2.2205e-019f},{-0.556611f,-0.830773f,-7.08082e-018f},{-0.499433f,-0.866353f,-8.66378e-019f}, +{-0.707766f,-0.706447f,5.72963e-018f},{-0.66887f,-0.743379f,-1.08295e-017f},{-0.808947f,-0.587881f,-2.8066e-018f}, +{-0.831851f,-0.554999f,-9.62021e-019f},{-0.924075f,-0.382212f,-1.06868e-018f},{-0.913543f,-0.406743f,-2.11299e-018f}, +{-0.98085f,-0.194766f,1.44155e-017f},{-0.978165f,-0.20783f,0.0f},{-1.0f,-2.31296e-018f,0.0f}, +{-0.475871f,-0.197004f,0.857167f},{-0.428277f,-0.286082f,0.857167f},{0.515038f,8.88154e-011f,0.857167f}, +{-0.505162f,-0.100376f,0.857167f},{-0.515038f,-8.71138e-012f,0.857167f},{-0.36417f,-0.364203f,0.857167f}, +{-0.285997f,-0.428334f,0.857167f},{-0.196837f,-0.475941f,0.857167f},{-0.100254f,-0.505186f,0.857167f}, +{-4.12517e-017f,-0.515038f,0.857167f},{0.19778f,-0.47555f,0.857167f},{0.101034f,-0.505031f,0.857167f}, +{0.364526f,-0.363847f,0.857167f},{0.286676f,-0.42788f,0.857167f},{0.475934f,-0.196854f,0.857167f}, +{0.428435f,-0.285846f,0.857167f},{0.515038f,4.59894e-016f,0.857167f},{0.505175f,-0.100312f,0.857167f}, +{0.743195f,-0.669075f,0.0f},{0.866128f,-0.499822f,0.0f},{0.808688f,-0.588238f,0.0f}, +{-0.156467f,-0.987683f,0.0f},{0.89086f,-0.454278f,0.0f},{0.940023f,-0.341112f,0.0f}, +{0.951024f,-0.309116f,0.0f},{0.984831f,-0.173514f,0.0f},{0.987686f,-0.156452f,0.0f}, +{1.0f,-1.30451e-016f,0.0f},{1.0f,-1.33227e-016f,0.0f},{0.706727f,-0.707486f,0.0f}, +{0.587512f,-0.809215f,0.0f},{0.587575f,-0.80917f,0.0f},{0.453641f,-0.891185f,0.0f}, +{0.40683f,-0.913504f,0.0f},{0.308716f,-0.951154f,0.0f},{0.208031f,-0.978122f,0.0f}, +{0.156246f,-0.987718f,0.0f},{-0.40677f,-0.91353f,0.0f},{-0.208006f,-0.978127f,0.0f}, +{-0.309067f,-0.95104f,0.0f},{-0.707621f,-0.706592f,0.0f},{-0.587567f,-0.809176f,0.0f}, +{-0.587746f,-0.809045f,0.0f},{-0.454023f,-0.89099f,0.0f},{-0.939985f,-0.341216f,0.0f}, +{-0.866205f,-0.499689f,0.0f},{-0.891077f,-0.453852f,0.0f},{-0.743115f,-0.669164f,0.0f}, +{-0.809929f,-0.586527f,0.0f},{-0.987719f,-0.156239f,0.0f},{-0.984781f,-0.173802f,0.0f}, +{-0.951116f,-0.308833f,0.0f},{-1.0f,2.22045e-017f,0.0f},{0.866025f,0.5f,1.20185e-017f}, +{-0.866025f,-0.5f,-1.20185e-017f},{-0.866025f,-0.5f,-1.29482e-017f},{0.866025f,-0.5f,-6.93889e-018f}, +{2.77556e-016f,-1.0f,-1.73472e-017f},{3.33067e-016f,-1.0f,-1.73472e-017f},{3.33067e-016f,-1.0f,2.08167e-017f}, +{2.77556e-016f,-1.0f,-6.85322e-019f},{-3.84593e-017f,1.0f,-6.16298e-033f},{-3.84593e-017f,1.0f,0.0f}, +{-1.45717e-016f,0.0f,1.0f},{8.88178e-017f,0.0f,1.0f},{-1.52656e-016f,0.0f,1.0f}, +{-1.59595e-016f,0.0f,1.0f},{1.38778e-016f,0.0f,1.0f},{-0.866025f,0.5f,-2.75508e-017f}, +{-0.866025f,0.5f,-2.61136e-017f},{-0.866025f,0.5f,-1.89555e-018f},{0.987719f,0.156239f,0.0f}, +{1.0f,-1.41553e-016f,0.0f},{0.984848f,0.173419f,0.0f},{0.707621f,0.706592f,0.0f}, +{0.809929f,0.586527f,0.0f},{0.74297f,0.669325f,0.0f},{0.940139f,0.34079f,0.0f}, +{0.891077f,0.453852f,0.0f},{0.951116f,0.308833f,0.0f},{0.207738f,0.978184f,0.0f}, +{-0.000204802f,1.0f,0.0f},{0.156467f,0.987683f,0.0f},{0.587839f,0.808978f,0.0f}, +{0.406907f,0.91347f,0.0f},{0.454023f,0.89099f,0.0f},{-0.588053f,0.808823f,0.0f}, +{-0.453641f,0.891185f,0.0f},{-0.407167f,0.913354f,0.0f},{-0.308716f,0.951154f,0.0f}, +{-0.156246f,0.987718f,0.0f},{-0.208137f,0.9781f,0.0f},{-0.706727f,0.707486f,0.0f}, +{-0.743046f,0.669241f,0.0f},{-0.866091f,0.499886f,0.0f},{-0.89086f,0.454278f,0.0f}, +{-0.808688f,0.588238f,0.0f},{-0.9402f,0.340622f,0.0f},{-0.951024f,0.309116f,0.0f}, +{-0.9849f,0.173126f,0.0f},{-0.987686f,0.156452f,0.0f},{-0.587512f,0.809215f,0.0f}, +{4.44089e-017f,1.0f,0.0f},{0.309067f,0.95104f,0.0f},{0.587746f,0.809045f,0.0f}, +{0.866141f,0.499799f,0.0f},{-4.44089e-016f,0.0f,1.0f},{4.44089e-016f,0.0f,1.0f}, +{8.88178e-016f,0.0f,1.0f},{0.0f,-8.88178e-016f,1.0f},{0.0f,6.66134e-016f,1.0f}, +{0.470509f,0.209488f,0.857167f},{0.416639f,0.302781f,0.857167f},{-0.515038f,-9.57464e-011f,0.857167f}, +{0.503792f,0.107041f,0.857167f},{0.515038f,8.71144e-012f,0.857167f},{0.344494f,0.382869f,0.857167f}, +{0.257227f,0.446205f,0.857167f},{0.158772f,0.489955f,0.857167f},{0.0535708f,0.512244f,0.857167f}, +{-0.054163f,0.512182f,0.857167f},{-0.258245f,0.445616f,0.857167f},{-0.159959f,0.489568f,0.857167f}, +{-0.416978f,0.302314f,0.857167f},{-0.345125f,0.382299f,0.857167f},{-0.503838f,0.106823f,0.857167f}, +{-0.470674f,0.209119f,0.857167f},{-0.515038f,-3.74123e-016f,0.857167f},{1.0f,-1.29526e-016f,0.0f}, +{0.978165f,0.20783f,-8.77813e-017f},{0.978254f,0.207408f,1.53513e-017f},{0.50141f,0.86521f,6.40384e-017f}, +{0.670096f,0.742274f,7.43956e-017f},{0.66887f,0.743379f,-5.51477e-018f},{0.809606f,0.586974f,-5.99229e-017f}, +{0.913862f,0.406026f,3.0052e-017f},{0.913543f,0.406743f,1.50525e-017f},{0.105163f,0.994455f,-2.0347e-017f}, +{0.104013f,0.994576f,1.92463e-018f},{-0.104013f,0.994576f,-5.52101e-017f},{0.499433f,0.866353f,-3.20615e-017f}, +{0.308272f,0.951298f,1.76026e-017f},{0.310578f,0.950548f,5.2766e-017f},{-0.310578f,0.950548f,-2.94305e-017f}, +{-0.50141f,0.86521f,1.66462e-017f},{-0.499433f,0.866353f,2.40461e-017f},{-0.308272f,0.951298f,5.70418e-018f}, +{-0.105163f,0.994455f,1.64552e-017f},{-0.670096f,0.742274f,-3.4671e-017f},{-0.809606f,0.586974f,3.04307e-018f}, +{-0.808947f,0.587881f,1.56371e-017f},{-0.66887f,0.743379f,-5.77706e-017f},{-0.913543f,0.406743f,8.0545e-018f}, +{-0.913862f,0.406026f,1.26789e-017f},{-0.978254f,0.207408f,-9.04189e-018f},{-0.978165f,0.20783f,-1.02592e-017f}, +{-1.0f,-2.89121e-019f,0.0f},{-1.0f,2.31296e-018f,0.0f},{0.808947f,0.587881f,-2.1756e-017f}, +{0.987719f,-0.156239f,0.0f},{0.984848f,-0.173419f,0.0f},{0.707621f,-0.706592f,0.0f}, +{0.809929f,-0.586527f,0.0f},{0.743022f,-0.669267f,0.0f},{0.940139f,-0.34079f,0.0f}, +{0.891077f,-0.453852f,0.0f},{0.951116f,-0.308833f,0.0f},{0.208043f,-0.97812f,0.0f}, +{0.000184774f,-1.0f,0.0f},{0.156467f,-0.987683f,0.0f},{0.587964f,-0.808887f,0.0f}, +{0.40712f,-0.913375f,0.0f},{0.454023f,-0.89099f,0.0f},{-0.587927f,-0.808914f,0.0f}, +{-0.453641f,-0.891185f,0.0f},{-0.406953f,-0.913449f,0.0f},{-0.308716f,-0.951154f,0.0f}, +{-0.156246f,-0.987718f,0.0f},{-0.207832f,-0.978164f,0.0f},{-0.706727f,-0.707486f,0.0f}, +{-0.742993f,-0.669299f,0.0f},{-0.866091f,-0.499886f,0.0f},{-0.89086f,-0.454278f,0.0f}, +{-0.808688f,-0.588238f,0.0f},{-0.9402f,-0.340622f,0.0f},{-0.951024f,-0.309116f,0.0f}, +{-0.9849f,-0.173126f,0.0f},{-1.0f,-2.88658e-016f,0.0f},{-0.987686f,-0.156452f,0.0f}, +{-1.0f,-2.66454e-016f,0.0f},{-0.587512f,-0.809215f,0.0f},{8.88178e-017f,-1.0f,0.0f}, +{0.309067f,-0.95104f,0.0f},{0.587746f,-0.809045f,0.0f},{0.866141f,-0.499799f,0.0f}, +{-0.0f,2.77556e-017f,-1.0f},{-0.0f,1.38778e-017f,-1.0f},{0.0f,-2.77556e-017f,-1.0f}, +{2.77556e-017f,-0.0f,-1.0f},{-2.43605e-017f,0.0f,-1.0f},{-0.0f,2.08167e-017f,-1.0f}, +{-0.0f,5.55112e-017f,-1.0f},{-0.0f,2.07242e-017f,-1.0f},{0.470509f,-0.209488f,-0.857167f}, +{0.416639f,-0.302781f,-0.857167f},{-0.515038f,-1.96047e-011f,-0.857167f},{0.503792f,-0.107041f,-0.857167f}, +{0.515038f,-8.71228e-012f,-0.857167f},{0.344494f,-0.382869f,-0.857167f},{0.257227f,-0.446205f,-0.857167f}, +{0.158772f,-0.489955f,-0.857167f},{0.0535708f,-0.512244f,-0.857167f},{-0.054163f,-0.512182f,-0.857167f}, +{-0.258245f,-0.445616f,-0.857167f},{-0.159959f,-0.489568f,-0.857167f},{-0.416978f,-0.302314f,-0.857167f}, +{-0.345125f,-0.382299f,-0.857167f},{-0.503838f,-0.106823f,-0.857167f},{-0.470674f,-0.209119f,-0.857167f}, +{-0.515038f,-5.77524e-016f,-0.857167f},{0.978165f,-0.20783f,7.23987e-017f},{0.978254f,-0.207408f,0.0f}, +{0.50141f,-0.86521f,1.85559e-017f},{0.670096f,-0.742274f,-2.21274e-017f},{0.66887f,-0.743379f,-2.47532e-017f}, +{0.809606f,-0.586974f,5.99229e-017f},{0.913862f,-0.406026f,0.0f},{0.913543f,-0.406743f,0.0f}, +{0.105163f,-0.994455f,2.22929e-017f},{0.104013f,-0.994576f,1.84034e-017f},{-0.104013f,-0.994576f,-1.64787e-017f}, +{0.499433f,-0.866353f,0.0f},{0.308272f,-0.951298f,1.76026e-017f},{0.310578f,-0.950548f,1.75887e-017f}, +{-0.310578f,-0.950548f,0.0f},{-0.50141f,-0.86521f,8.0048e-018f},{-0.499433f,-0.866353f,-3.39469e-018f}, +{-0.308272f,-0.951298f,8.80128e-018f},{-0.105163f,-0.994455f,2.22929e-017f},{-0.670096f,-0.742274f,-3.33889e-019f}, +{-0.809606f,-0.586974f,-1.35765e-018f},{-0.808947f,-0.587881f,-1.01698e-018f},{-0.66887f,-0.743379f,1.65048e-017f}, +{-0.913543f,-0.406743f,-2.8802e-018f},{-0.913862f,-0.406026f,-7.51299e-018f},{-0.978254f,-0.207408f,3.91078e-018f}, +{-0.978165f,-0.20783f,2.24517e-019f},{-1.0f,1.24033e-016f,0.0f},{-1.0f,1.249e-016f,0.0f}, +{0.808947f,-0.587881f,0.0f},{0.0580986f,-0.998311f,1.85037e-017f},{0.161621f,-0.986853f,-2.52608e-018f}, +{-0.047209f,-0.998885f,-1.75194e-017f},{-0.254828f,-0.966986f,3.401e-017f},{-0.137337f,-0.990524f,4.88637e-017f}, +{-0.327845f,-0.944731f,2.46819e-017f},{-0.625839f,-0.779952f,5.21559e-017f},{-0.506037f,-0.862512f,1.71547e-017f}, +{-0.450295f,-0.89288f,-5.09311e-017f},{-0.774136f,-0.633019f,3.41454e-017f},{-0.664797f,-0.747024f,-4.75018e-018f}, +{-0.797869f,-0.602831f,1.51199e-017f},{-0.888728f,-0.458434f,-1.53953e-017f},{-0.964552f,-0.263893f,-1.49117e-017f}, +{-0.90017f,-0.435538f,8.43939e-018f},{-0.998311f,-0.0580986f,0.0f},{-0.967845f,-0.251545f,8.3164e-018f}, +{0.252807f,-0.967517f,-3.53809e-017f},{0.36302f,-0.931781f,-2.33067e-017f},{0.437005f,-0.899459f,6.85621e-017f}, +{0.603937f,-0.797032f,-3.33196e-017f},{0.548923f,-0.835873f,3.37942e-017f},{0.747614f,-0.664134f,2.28697e-017f}, +{0.71093f,-0.703263f,5.57946e-017f},{0.841736f,-0.539889f,2.83047e-017f},{0.862691f,-0.505732f,-3.91541e-017f}, +{0.94472f,-0.327879f,2.82894e-017f},{0.935631f,-0.35298f,-1.3996e-017f},{0.990509f,-0.137451f,1.44155e-017f}, +{0.988587f,-0.150649f,1.53825e-017f},{0.998311f,0.0580986f,0.0f},{0.486513f,-0.169024f,-0.857167f}, +{0.444175f,-0.260716f,-0.857167f},{-0.514168f,-0.029923f,-0.857167f},{0.510141f,-0.070857f,-0.857167f}, +{0.514168f,0.029923f,-0.857167f},{0.384715f,-0.34243f,-0.857167f},{0.310399f,-0.410994f,-0.857167f}, +{0.224156f,-0.463701f,-0.857167f},{0.129435f,-0.498508f,-0.857167f},{0.029923f,-0.514168f,-0.857167f}, +{-0.169817f,-0.486237f,-0.857167f},{-0.071522f,-0.510048f,-0.857167f},{-0.342771f,-0.384411f,-0.857167f}, +{-0.261332f,-0.443813f,-0.857167f},{-0.463693f,-0.224172f,-0.857167f},{-0.411104f,-0.310254f,-0.857167f}, +{-0.498494f,-0.129492f,-0.857167f},{-0.703068f,-0.711123f,0.0f},{-0.835626f,-0.549298f,0.0f}, +{-0.773146f,-0.634228f,0.0f},{0.0580986f,-0.998311f,0.0f},{0.213586f,-0.976924f,0.0f}, +{-0.862963f,-0.505268f,0.0f},{-0.918617f,-0.39515f,0.0f},{-0.931459f,-0.363847f,0.0f}, +{-0.973087f,-0.230439f,0.0f},{-0.976928f,-0.213571f,0.0f},{-0.66443f,-0.747351f,0.0f}, +{-0.539506f,-0.841982f,0.0f},{-0.539571f,-0.84194f,0.0f},{-0.401098f,-0.916035f,0.0f}, +{-0.353069f,-0.935597f,0.0f},{-0.252934f,-0.967484f,0.0f},{-0.150852f,-0.988556f,0.0f}, +{-0.0985972f,-0.995127f,0.0f},{0.459158f,-0.888355f,0.0f},{0.264483f,-0.96439f,0.0f}, +{0.363799f,-0.931478f,0.0f},{0.747478f,-0.664287f,0.0f},{0.633586f,-0.773672f,0.0f}, +{0.633758f,-0.773531f,0.0f},{0.505021f,-0.863107f,0.0f},{0.958221f,-0.286028f,0.0f}, +{0.893773f,-0.44852f,0.0f},{0.91594f,-0.401315f,0.0f},{0.780737f,-0.62486f,0.0f}, +{0.842638f,-0.538481f,0.0f},{0.995128f,-0.0985905f,0.0f},{0.993215f,-0.116295f,0.0f}, +{0.967452f,-0.253053f,0.0f},{-0.0580986f,0.998311f,0.0f},{0.0460542f,0.998939f,-1.75012e-017f}, +{-0.162762f,0.986665f,-1.77626e-017f},{-0.365279f,0.930898f,4.93869e-018f},{-0.251312f,0.967906f,8.23072e-018f}, +{-0.435222f,0.900323f,-3.16302e-018f},{-0.71209f,0.702089f,-6.30166e-018f},{-0.602673f,0.797988f,-1.21778e-017f}, +{-0.55083f,0.834617f,-1.26379e-018f},{-0.842341f,0.538945f,-3.60649e-017f},{-0.746964f,0.664864f,4.52306e-017f}, +{-0.862411f,0.506208f,-2.40794e-017f},{-0.935907f,0.352246f,1.43248e-017f},{-0.988652f,0.150223f,2.12095e-017f}, +{-0.944616f,0.328178f,-2.4773e-017f},{-0.990491f,0.137576f,2.03008e-018f},{0.138867f,0.990311f,3.17611e-018f}, +{0.252482f,0.967602f,-1.70678e-017f},{0.329717f,0.94408f,2.2205e-019f},{0.507404f,0.861708f,-7.08082e-018f}, +{0.448255f,0.893906f,-8.66378e-019f},{0.665526f,0.746374f,5.72963e-018f},{0.624551f,0.780984f,-1.08295e-017f}, +{0.773426f,0.633887f,-2.8066e-018f},{0.798201f,0.602391f,-9.62021e-019f},{0.900308f,0.435254f,-1.06868e-018f}, +{0.888368f,0.459131f,-2.11299e-018f},{0.967877f,0.251423f,1.44155e-017f},{0.964438f,0.264309f,0.0f}, +{0.463622f,0.224319f,0.857167f},{0.410933f,0.310481f,0.857167f},{-0.514168f,-0.029923f,0.857167f}, +{0.498477f,0.129555f,0.857167f},{0.514168f,0.029923f,0.857167f},{0.342396f,0.384746f,0.857167f}, +{0.260628f,0.444227f,0.857167f},{0.168853f,0.486573f,0.857167f},{0.070734f,0.510158f,0.857167f}, +{-0.029923f,0.514168f,0.857167f},{-0.225074f,0.463256f,0.857167f},{-0.130205f,0.498308f,0.857167f}, +{-0.385049f,0.342054f,0.857167f},{-0.311051f,0.410502f,0.857167f},{-0.486567f,0.16887f,0.857167f}, +{-0.444319f,0.260471f,0.857167f},{-0.51015f,0.0707922f,0.857167f},{-0.780812f,0.624766f,0.0f}, +{-0.893704f,0.448657f,0.0f},{-0.841497f,0.540261f,0.0f},{0.0988201f,0.995105f,0.0f}, +{-0.915748f,0.401752f,0.0f},{-0.958253f,0.285922f,0.0f},{-0.967377f,0.253341f,0.0f}, +{-0.993249f,0.116004f,0.0f},{-0.995107f,0.0988045f,0.0f},{-0.746637f,0.665231f,0.0f}, +{-0.633534f,0.773715f,0.0f},{-0.633594f,0.773666f,0.0f},{-0.504651f,0.863323f,0.0f}, +{-0.459216f,0.888325f,0.0f},{-0.363455f,0.931612f,0.0f},{-0.264507f,0.964384f,0.0f}, +{-0.213367f,0.976972f,0.0f},{0.353009f,0.93562f,0.0f},{0.150827f,0.98856f,0.0f}, +{0.25329f,0.96739f,0.0f},{0.665374f,0.74651f,0.0f},{0.539562f,0.841946f,0.0f}, +{0.539749f,0.841826f,0.0f},{0.401491f,0.915863f,0.0f},{0.918573f,0.395251f,0.0f}, +{0.83571f,0.54917f,0.0f},{0.863204f,0.504856f,0.0f},{0.702982f,0.711208f,0.0f}, +{0.774485f,0.632592f,0.0f},{0.976973f,0.213361f,0.0f},{0.973019f,0.230723f,0.0f}, +{0.931567f,0.36357f,0.0f},{-0.835513f,-0.54947f,1.20185e-017f},{0.835513f,0.54947f,-1.20185e-017f}, +{0.835513f,0.54947f,-1.29482e-017f},{0.835513f,0.54947f,0.0f},{-0.893612f,0.448841f,0.0f}, +{-0.893612f,0.448841f,-6.93889e-018f},{-0.0580986f,0.998311f,-1.73472e-017f},{-0.0580986f,0.998311f,2.08167e-017f}, +{-0.0580986f,0.998311f,-6.85322e-019f},{0.0580986f,-0.998311f,-6.16298e-033f},{-2.2167e-016f,-1.29005e-017f,1.0f}, +{1.66252e-016f,9.67536e-018f,1.0f},{1.10835e-016f,6.45024e-018f,1.0f},{-1.10835e-016f,-6.45024e-018f,1.0f}, +{-8.31261e-017f,-4.83768e-018f,1.0f},{1.45471e-016f,8.46594e-018f,1.0f},{-6.92717e-018f,-4.0314e-019f,1.0f}, +{-8.86678e-017f,-5.16019e-018f,1.0f},{-2.77087e-017f,-1.61256e-018f,1.0f},{1.52398e-016f,8.86908e-018f,1.0f}, +{1.59325e-016f,9.27222e-018f,1.0f},{-1.38543e-016f,-8.0628e-018f,1.0f},{-5.54174e-017f,-3.22512e-018f,1.0f}, +{2.2167e-016f,1.29005e-017f,1.0f},{-1.66252e-016f,-9.67536e-018f,1.0f},{0.893612f,-0.448841f,-2.75508e-017f}, +{0.893612f,-0.448841f,-2.61136e-017f},{0.893612f,-0.448841f,-1.89555e-018f},{-0.976973f,-0.213361f,0.0f}, +{-0.973109f,-0.230345f,0.0f},{-0.665374f,-0.74651f,0.0f},{-0.774485f,-0.632592f,0.0f}, +{-0.702828f,-0.71136f,0.0f},{-0.918752f,-0.394835f,0.0f},{-0.863204f,-0.504856f,0.0f}, +{-0.931567f,-0.36357f,0.0f},{-0.150556f,-0.988601f,0.0f},{0.058303f,-0.998299f,0.0f}, +{-0.0988201f,-0.995105f,0.0f},{-0.539845f,-0.841764f,0.0f},{-0.353148f,-0.935567f,0.0f}, +{-0.401491f,-0.915863f,0.0f},{0.634051f,-0.773291f,0.0f},{0.504651f,-0.863323f,0.0f}, +{0.459544f,-0.888155f,0.0f},{0.363455f,-0.931612f,0.0f},{0.213367f,-0.976972f,0.0f}, +{0.264611f,-0.964355f,0.0f},{0.746637f,-0.665231f,0.0f},{0.780673f,-0.62494f,0.0f}, +{0.893671f,-0.448723f,0.0f},{0.915748f,-0.401752f,0.0f},{0.841497f,-0.540261f,0.0f}, +{0.958402f,-0.285423f,0.0f},{0.967377f,-0.253341f,0.0f},{0.993294f,-0.115612f,0.0f}, +{0.995107f,-0.0988045f,0.0f},{0.633534f,-0.773715f,0.0f},{-0.25329f,-0.96739f,0.0f}, +{-0.539749f,-0.841826f,0.0f},{-0.835641f,-0.549276f,0.0f},{-1.29005e-017f,2.2167e-016f,1.0f}, +{1.93507e-017f,-3.32504e-016f,1.0f},{1.29005e-017f,-2.2167e-016f,1.0f},{4.43339e-016f,2.5801e-017f,1.0f}, +{-4.43339e-016f,-2.5801e-017f,1.0f},{-8.86678e-016f,-5.16019e-017f,1.0f},{-2.5801e-017f,4.43339e-016f,1.0f}, +{-5.16019e-017f,8.86678e-016f,1.0f},{3.87014e-017f,-6.65009e-016f,1.0f},{2.5801e-017f,-4.43339e-016f,1.0f}, +{-0.457544f,-0.23647f,0.857167f},{-0.398344f,-0.326476f,0.857167f},{-0.496722f,-0.136129f,0.857167f}, +{-0.321668f,-0.402236f,0.857167f},{-0.230869f,-0.460395f,0.857167f},{-0.130038f,-0.498352f,0.857167f}, +{-0.0237196f,-0.514492f,0.857167f},{0.0838285f,-0.50817f,0.857167f},{0.283699f,-0.42986f,0.857167f}, +{0.188132f,-0.479448f,0.857167f},{0.433838f,-0.277577f,0.857167f},{0.366753f,-0.361602f,0.857167f}, +{0.509194f,-0.0773705f,0.857167f},{0.482028f,-0.18142f,0.857167f},{-0.964438f,-0.264309f,-8.77813e-017f}, +{-0.964552f,-0.263893f,1.53513e-017f},{-0.450295f,-0.89288f,6.40384e-017f},{-0.625839f,-0.779952f,7.43956e-017f}, +{-0.624551f,-0.780984f,-5.51477e-018f},{-0.774136f,-0.633019f,-5.99229e-017f},{-0.888728f,-0.458434f,3.0052e-017f}, +{-0.888368f,-0.459131f,1.50525e-017f},{-0.047209f,-0.998885f,-2.0347e-017f},{-0.0460542f,-0.998939f,1.92463e-018f}, +{0.161621f,-0.986853f,-5.52101e-017f},{-0.448255f,-0.893906f,-3.20615e-017f},{-0.252482f,-0.967602f,1.76026e-017f}, +{-0.254827f,-0.966987f,5.2766e-017f},{0.365279f,-0.930898f,-2.94305e-017f},{0.55083f,-0.834617f,1.66462e-017f}, +{0.548923f,-0.835873f,2.40461e-017f},{0.36302f,-0.931781f,5.70418e-018f},{0.162762f,-0.986665f,1.64552e-017f}, +{0.71209f,-0.702089f,-3.4671e-017f},{0.842341f,-0.538945f,3.04307e-018f},{0.841736f,-0.539889f,1.56371e-017f}, +{0.71093f,-0.703263f,-5.77706e-017f},{0.935631f,-0.35298f,8.0545e-018f},{0.935907f,-0.352246f,1.26789e-017f}, +{0.988652f,-0.150223f,-9.04189e-018f},{0.988587f,-0.150649f,-1.02592e-017f},{-0.773426f,-0.633887f,-2.1756e-017f}, +{-0.995128f,0.0985905f,0.0f},{-0.99326f,0.115908f,0.0f},{-0.747478f,0.664287f,0.0f}, +{-0.842638f,0.538481f,0.0f},{-0.78065f,0.624968f,0.0f},{-0.958351f,0.285594f,0.0f}, +{-0.91594f,0.401315f,0.0f},{-0.967452f,0.253053f,0.0f},{-0.264519f,0.964381f,0.0f}, +{-0.058283f,0.9983f,0.0f},{-0.213586f,0.976924f,0.0f},{-0.633966f,0.773361f,0.0f}, +{-0.459498f,0.888179f,0.0f},{-0.505021f,0.863107f,0.0f},{0.539937f,0.841705f,0.0f}, +{0.401098f,0.916035f,0.0f},{0.353196f,0.935549f,0.0f},{0.252934f,0.967484f,0.0f}, +{0.0985972f,0.995127f,0.0f},{0.150651f,0.988587f,0.0f},{0.66443f,0.747351f,0.0f}, +{0.702853f,0.711335f,0.0f},{0.835585f,0.54936f,0.0f},{0.862963f,0.505268f,0.0f}, +{0.773146f,0.634228f,0.0f},{0.918822f,0.394671f,0.0f},{0.931459f,0.363847f,0.0f}, +{0.973178f,0.230054f,0.0f},{0.976928f,0.213571f,0.0f},{0.539506f,0.841982f,0.0f}, +{-0.363799f,0.931478f,0.0f},{-0.633758f,0.773531f,0.0f},{-0.893716f,0.448633f,0.0f}, +{1.61256e-018f,-2.77087e-017f,-1.0f},{8.0628e-019f,-1.38543e-017f,-1.0f},{-8.0628e-019f,1.38543e-017f,-1.0f}, +{-1.61256e-018f,2.77087e-017f,-1.0f},{1.38543e-017f,8.0628e-019f,-1.0f},{5.54174e-017f,3.22512e-018f,-1.0f}, +{2.07815e-017f,1.20942e-018f,-1.0f},{-2.77087e-017f,-1.61256e-018f,-1.0f},{2.43194e-017f,1.41531e-018f,-1.0f}, +{1.20942e-018f,-2.07815e-017f,-1.0f},{3.22512e-018f,-5.54174e-017f,-1.0f},{1.20404e-018f,-2.06892e-017f,-1.0f}, +{-0.481885f,0.181798f,-0.857167f},{-0.433526f,0.278063f,-0.857167f},{-0.50916f,0.0775901f,-0.857167f}, +{-0.366156f,0.362207f,-0.857167f},{-0.282716f,0.430506f,-0.857167f},{-0.186969f,0.479903f,-0.857167f}, +{-0.083241f,0.508267f,-0.857167f},{0.0243144f,0.514464f,-0.857167f},{0.231919f,0.459867f,-0.857167f}, +{0.131246f,0.498035f,-0.857167f},{0.39871f,0.326029f,-0.857167f},{0.322331f,0.401705f,-0.857167f}, +{0.496781f,0.135915f,-0.857167f},{0.457729f,0.236111f,-0.857167f},{-0.988587f,0.150649f,7.23987e-017f}, +{-0.988652f,0.150223f,0.0f},{-0.55083f,0.834617f,1.85559e-017f},{-0.71209f,0.702089f,-2.21274e-017f}, +{-0.71093f,0.703263f,-2.47532e-017f},{-0.842341f,0.538945f,5.99229e-017f},{-0.935907f,0.352246f,0.0f}, +{-0.935631f,0.35298f,0.0f},{-0.162762f,0.986665f,2.22929e-017f},{-0.161621f,0.986853f,1.84034e-017f}, +{0.0460541f,0.998939f,-1.64787e-017f},{-0.548923f,0.835873f,0.0f},{-0.36302f,0.931781f,1.76026e-017f}, +{-0.365278f,0.930898f,1.75887e-017f},{0.254828f,0.966986f,0.0f},{0.450295f,0.89288f,8.0048e-018f}, +{0.448255f,0.893906f,-3.39469e-018f},{0.252482f,0.967602f,8.80128e-018f},{0.047209f,0.998885f,2.22929e-017f}, +{0.625839f,0.779952f,-3.33889e-019f},{0.774136f,0.633019f,-1.35765e-018f},{0.773426f,0.633887f,-1.01698e-018f}, +{0.624551f,0.780984f,1.65048e-017f},{0.888368f,0.459131f,-2.8802e-018f},{0.888728f,0.458434f,-7.51299e-018f}, +{0.964552f,0.263893f,3.91078e-018f},{0.964438f,0.264309f,2.24517e-019f},{-0.841736f,0.539889f,0.0f}, +{-7.40149e-017f,-1.0f,1.85037e-017f},{0.104013f,-0.994576f,-2.52608e-018f},{-0.105163f,-0.994455f,-1.75194e-017f}, +{-0.310578f,-0.950548f,3.401e-017f},{-0.194653f,-0.980872f,4.88637e-017f},{-0.382179f,-0.924088f,2.46819e-017f}, +{-0.670096f,-0.742274f,5.21559e-017f},{-0.555293f,-0.831655f,1.71547e-017f},{-0.50141f,-0.86521f,-5.09311e-017f}, +{-0.809606f,-0.586974f,3.41454e-017f},{-0.707075f,-0.707139f,-4.75018e-018f},{-0.831545f,-0.555458f,1.51199e-017f}, +{-0.913862f,-0.406026f,-1.53953e-017f},{-0.978254f,-0.207408f,-1.49117e-017f},{-0.923954f,-0.382504f,8.43939e-018f}, +{-0.980825f,-0.19489f,8.3164e-018f},{0.196168f,-0.98057f,-3.53809e-017f},{0.308272f,-0.951298f,-2.33067e-017f}, +{0.384009f,-0.923329f,6.85621e-017f},{0.556611f,-0.830773f,-3.33196e-017f},{0.499433f,-0.866353f,3.37942e-017f}, +{0.707766f,-0.706447f,2.28697e-017f},{0.66887f,-0.743379f,5.57946e-017f},{0.808947f,-0.587881f,2.83047e-017f}, +{0.831851f,-0.554999f,-3.91541e-017f},{0.924075f,-0.382212f,2.82894e-017f},{0.913543f,-0.406743f,-1.3996e-017f}, +{0.98085f,-0.194766f,1.44155e-017f},{0.978165f,-0.20783f,1.53825e-017f},{1.0f,-1.21431e-016f,0.0f}, +{1.0f,-1.22587e-016f,0.0f},{0.475871f,-0.197004f,-0.857167f},{0.428277f,-0.286082f,-0.857167f}, +{-0.515038f,-2.65357e-011f,-0.857167f},{0.505162f,-0.100376f,-0.857167f},{0.515038f,-8.7125e-012f,-0.857167f}, +{0.36417f,-0.364203f,-0.857167f},{0.285997f,-0.428334f,-0.857167f},{0.196837f,-0.475941f,-0.857167f}, +{0.100254f,-0.505186f,-0.857167f},{-3.87126e-016f,-0.515038f,-0.857167f},{-0.19778f,-0.47555f,-0.857167f}, +{-0.101034f,-0.505031f,-0.857167f},{-0.364526f,-0.363847f,-0.857167f},{-0.286676f,-0.42788f,-0.857167f}, +{-0.475934f,-0.196854f,-0.857167f},{-0.428435f,-0.285846f,-0.857167f},{-0.515038f,-5.63228e-016f,-0.857167f}, +{-0.505175f,-0.100312f,-0.857167f},{-0.743195f,-0.669075f,0.0f},{-0.866128f,-0.499822f,0.0f}, +{-0.940023f,-0.341112f,0.0f},{-0.984831f,-0.173514f,0.0f},{-1.0f,-5.55112e-018f,0.0f}, +{-0.587575f,-0.80917f,0.0f},{-0.40683f,-0.913504f,0.0f},{-0.208031f,-0.978122f,0.0f}, +{0.40677f,-0.91353f,0.0f},{0.208006f,-0.978127f,0.0f},{0.587567f,-0.809176f,0.0f}, +{0.939985f,-0.341216f,0.0f},{0.866205f,-0.499689f,0.0f},{0.743115f,-0.669164f,0.0f}, +{0.984781f,-0.173802f,0.0f},{1.0f,1.77636e-016f,0.0f},{1.0f,2.22045e-016f,0.0f}, +{0.104013f,0.994576f,-1.75012e-017f},{-0.105163f,0.994455f,-1.77626e-017f},{-0.310578f,0.950548f,4.93869e-018f}, +{-0.194653f,0.980872f,8.23072e-018f},{-0.382179f,0.924088f,-3.16302e-018f},{-0.670096f,0.742274f,-6.30166e-018f}, +{-0.555293f,0.831655f,-1.21778e-017f},{-0.50141f,0.86521f,-1.26379e-018f},{-0.809606f,0.586974f,-3.60649e-017f}, +{-0.707075f,0.707139f,4.52306e-017f},{-0.831545f,0.555458f,-2.40794e-017f},{-0.913862f,0.406026f,1.43248e-017f}, +{-0.978254f,0.207408f,2.12095e-017f},{-0.923954f,0.382504f,-2.4773e-017f},{-1.0f,-1.57282e-016f,0.0f}, +{-0.980825f,0.19489f,2.03008e-018f},{0.196168f,0.98057f,3.17611e-018f},{0.308272f,0.951298f,-1.70678e-017f}, +{0.384009f,0.923329f,2.2205e-019f},{0.556611f,0.830773f,-7.08082e-018f},{0.499433f,0.866353f,-8.66378e-019f}, +{0.707766f,0.706447f,5.72963e-018f},{0.66887f,0.743379f,-1.08295e-017f},{0.808947f,0.587881f,-2.8066e-018f}, +{0.831851f,0.554999f,-9.62021e-019f},{0.924075f,0.382212f,-1.06868e-018f},{0.913543f,0.406743f,-2.11299e-018f}, +{0.98085f,0.194766f,1.44155e-017f},{0.978165f,0.20783f,0.0f},{1.0f,2.31296e-018f,0.0f}, +{0.475871f,0.197004f,0.857167f},{0.428277f,0.286082f,0.857167f},{-0.515038f,-8.88154e-011f,0.857167f}, +{0.505162f,0.100376f,0.857167f},{0.515038f,8.71138e-012f,0.857167f},{0.36417f,0.364203f,0.857167f}, +{0.285997f,0.428334f,0.857167f},{0.196837f,0.475941f,0.857167f},{0.100254f,0.505186f,0.857167f}, +{4.12517e-017f,0.515038f,0.857167f},{-0.19778f,0.47555f,0.857167f},{-0.101034f,0.505031f,0.857167f}, +{-0.364526f,0.363847f,0.857167f},{-0.286676f,0.42788f,0.857167f},{-0.475934f,0.196854f,0.857167f}, +{-0.428435f,0.285846f,0.857167f},{-0.515038f,-4.59894e-016f,0.857167f},{-0.505175f,0.100312f,0.857167f}, +{-0.743195f,0.669075f,0.0f},{-0.866128f,0.499822f,0.0f},{-0.940023f,0.341112f,0.0f}, +{-0.984831f,0.173514f,0.0f},{-1.0f,1.30451e-016f,0.0f},{-1.0f,1.33227e-016f,0.0f}, +{-0.587575f,0.80917f,0.0f},{-0.40683f,0.913504f,0.0f},{-0.208031f,0.978122f,0.0f}, +{0.40677f,0.91353f,0.0f},{0.208006f,0.978127f,0.0f},{0.587567f,0.809176f,0.0f}, +{0.939985f,0.341216f,0.0f},{0.866205f,0.499689f,0.0f},{0.743115f,0.669164f,0.0f}, +{0.984781f,0.173802f,0.0f},{1.0f,-2.22045e-017f,0.0f},{-0.866025f,-0.5f,1.20185e-017f}, +{0.866025f,0.5f,-1.20185e-017f},{0.866025f,0.5f,-1.29482e-017f},{-0.866025f,0.5f,-6.93889e-018f}, +{-2.77556e-016f,1.0f,-1.73472e-017f},{-3.33067e-016f,1.0f,-1.73472e-017f},{-3.33067e-016f,1.0f,2.08167e-017f}, +{-2.77556e-016f,1.0f,-6.85322e-019f},{3.84593e-017f,-1.0f,-6.16298e-033f},{3.84593e-017f,-1.0f,0.0f}, +{1.45717e-016f,0.0f,1.0f},{-8.88178e-017f,0.0f,1.0f},{1.52656e-016f,0.0f,1.0f}, +{1.59595e-016f,0.0f,1.0f},{0.866025f,-0.5f,-2.75508e-017f},{0.866025f,-0.5f,-2.61136e-017f}, +{0.866025f,-0.5f,-1.89555e-018f},{-1.0f,1.41553e-016f,0.0f},{-0.984848f,-0.173419f,0.0f}, +{-0.74297f,-0.669325f,0.0f},{-0.940139f,-0.34079f,0.0f},{-0.207738f,-0.978184f,0.0f}, +{0.000204802f,-1.0f,0.0f},{-0.587839f,-0.808978f,0.0f},{-0.406907f,-0.91347f,0.0f}, +{0.588053f,-0.808823f,0.0f},{0.407167f,-0.913354f,0.0f},{0.208137f,-0.9781f,0.0f}, +{0.743046f,-0.669241f,0.0f},{0.866091f,-0.499886f,0.0f},{0.9402f,-0.340622f,0.0f}, +{0.9849f,-0.173126f,0.0f},{-4.44089e-017f,-1.0f,0.0f},{-0.866141f,-0.499799f,0.0f}, +{0.0f,-3.33067e-016f,1.0f},{-8.88178e-016f,0.0f,1.0f},{0.0f,8.88178e-016f,1.0f}, +{0.0f,-6.66134e-016f,1.0f},{-0.470509f,-0.209488f,0.857167f},{-0.416639f,-0.302781f,0.857167f}, +{0.515038f,9.57464e-011f,0.857167f},{-0.503792f,-0.107041f,0.857167f},{-0.515038f,-8.71144e-012f,0.857167f}, +{-0.344494f,-0.382869f,0.857167f},{-0.257227f,-0.446205f,0.857167f},{-0.158772f,-0.489955f,0.857167f}, +{-0.0535708f,-0.512244f,0.857167f},{0.054163f,-0.512182f,0.857167f},{0.258245f,-0.445616f,0.857167f}, +{0.159959f,-0.489568f,0.857167f},{0.416978f,-0.302314f,0.857167f},{0.345125f,-0.382299f,0.857167f}, +{0.503838f,-0.106823f,0.857167f},{0.470674f,-0.209119f,0.857167f},{0.515038f,3.74123e-016f,0.857167f}, +{-1.0f,1.29526e-016f,0.0f},{-0.978165f,-0.20783f,-8.77813e-017f},{-0.978254f,-0.207408f,1.53513e-017f}, +{-0.50141f,-0.86521f,6.40384e-017f},{-0.670096f,-0.742274f,7.43956e-017f},{-0.66887f,-0.743379f,-5.51477e-018f}, +{-0.809606f,-0.586974f,-5.99229e-017f},{-0.913862f,-0.406026f,3.0052e-017f},{-0.913543f,-0.406743f,1.50525e-017f}, +{-0.105163f,-0.994455f,-2.0347e-017f},{-0.104013f,-0.994576f,1.92463e-018f},{0.104013f,-0.994576f,-5.52101e-017f}, +{-0.499433f,-0.866353f,-3.20615e-017f},{-0.308272f,-0.951298f,1.76026e-017f},{-0.310578f,-0.950548f,5.2766e-017f}, +{0.310578f,-0.950548f,-2.94305e-017f},{0.50141f,-0.86521f,1.66462e-017f},{0.499433f,-0.866353f,2.40461e-017f}, +{0.308272f,-0.951298f,5.70418e-018f},{0.105163f,-0.994455f,1.64552e-017f},{0.670096f,-0.742274f,-3.4671e-017f}, +{0.809606f,-0.586974f,3.04307e-018f},{0.808947f,-0.587881f,1.56371e-017f},{0.66887f,-0.743379f,-5.77706e-017f}, +{0.913543f,-0.406743f,8.0545e-018f},{0.913862f,-0.406026f,1.26789e-017f},{0.978254f,-0.207408f,-9.04189e-018f}, +{0.978165f,-0.20783f,-1.02592e-017f},{1.0f,2.89121e-019f,0.0f},{1.0f,-2.31296e-018f,0.0f}, +{-0.808947f,-0.587881f,-2.1756e-017f},{-0.984848f,0.173419f,0.0f},{-0.743022f,0.669267f,0.0f}, +{-0.940139f,0.34079f,0.0f},{-0.208043f,0.97812f,0.0f},{-0.000184774f,1.0f,0.0f}, +{-0.587964f,0.808887f,0.0f},{-0.40712f,0.913375f,0.0f},{0.587927f,0.808914f,0.0f}, +{0.406953f,0.913449f,0.0f},{0.207832f,0.978164f,0.0f},{0.742993f,0.669299f,0.0f}, +{0.866091f,0.499886f,0.0f},{0.9402f,0.340622f,0.0f},{0.9849f,0.173126f,0.0f}, +{1.0f,2.88658e-016f,0.0f},{1.0f,2.66454e-016f,0.0f},{-0.866141f,0.499799f,0.0f}, +{0.0f,2.77556e-017f,-1.0f},{2.43605e-017f,0.0f,-1.0f},{0.0f,-2.08167e-017f,-1.0f}, +{0.0f,-2.07242e-017f,-1.0f},{-0.470509f,0.209488f,-0.857167f},{-0.416639f,0.302781f,-0.857167f}, +{0.515038f,1.96047e-011f,-0.857167f},{-0.503792f,0.107041f,-0.857167f},{-0.515038f,8.71228e-012f,-0.857167f}, +{-0.344494f,0.382869f,-0.857167f},{-0.257227f,0.446205f,-0.857167f},{-0.158772f,0.489955f,-0.857167f}, +{-0.0535708f,0.512244f,-0.857167f},{0.054163f,0.512182f,-0.857167f},{0.258245f,0.445616f,-0.857167f}, +{0.159959f,0.489568f,-0.857167f},{0.416978f,0.302314f,-0.857167f},{0.345125f,0.382299f,-0.857167f}, +{0.503838f,0.106823f,-0.857167f},{0.470674f,0.209119f,-0.857167f},{0.515038f,5.77524e-016f,-0.857167f}, +{-0.978165f,0.20783f,7.23987e-017f},{-0.978254f,0.207408f,0.0f},{-0.50141f,0.86521f,1.85559e-017f}, +{-0.670096f,0.742274f,-2.21274e-017f},{-0.66887f,0.743379f,-2.47532e-017f},{-0.809606f,0.586974f,5.99229e-017f}, +{-0.913862f,0.406026f,0.0f},{-0.913543f,0.406743f,0.0f},{-0.105163f,0.994455f,2.22929e-017f}, +{-0.104013f,0.994576f,1.84034e-017f},{0.104013f,0.994576f,-1.64787e-017f},{-0.499433f,0.866353f,0.0f}, +{-0.308272f,0.951298f,1.76026e-017f},{-0.310578f,0.950548f,1.75887e-017f},{0.310578f,0.950548f,0.0f}, +{0.50141f,0.86521f,8.0048e-018f},{0.499433f,0.866353f,-3.39469e-018f},{0.308272f,0.951298f,8.80128e-018f}, +{0.105163f,0.994455f,2.22929e-017f},{0.670096f,0.742274f,-3.33889e-019f},{0.809606f,0.586974f,-1.35765e-018f}, +{0.808947f,0.587881f,-1.01698e-018f},{0.66887f,0.743379f,1.65048e-017f},{0.913543f,0.406743f,-2.8802e-018f}, +{0.913862f,0.406026f,-7.51299e-018f},{0.978254f,0.207408f,3.91078e-018f},{0.978165f,0.20783f,2.24517e-019f}, +{1.0f,-1.24033e-016f,0.0f},{1.0f,-1.249e-016f,0.0f},{-0.808947f,0.587881f,0.0f}, +{0.173171f,-0.984892f,2.40319e-017f},{-9.25186e-018f,-1.0f,2.31296e-017f},{-7.40149e-017f,-1.0f,2.31296e-017f}, +{-0.174653f,-0.98463f,9.17788e-018f},{-0.341361f,-0.939932f,-5.87441e-017f},{-0.173171f,-0.984892f,7.35351e-017f}, +{-0.343547f,-0.939135f,2.8923e-017f},{-0.499433f,-0.866353f,-2.69892e-017f},{-0.50141f,-0.86521f,-6.36638e-017f}, +{-0.642401f,-0.766369f,-5.10181e-017f},{-0.766786f,-0.641903f,3.93107e-017f},{-0.765783f,-0.643099f,-1.29623e-017f}, +{-0.643858f,-0.765145f,-1.31306e-016f},{-0.866509f,-0.499162f,-1.50895e-017f},{-0.865824f,-0.500349f,-1.69498e-017f}, +{-0.93996f,-0.341285f,-1.43832e-017f},{-0.939558f,-0.34239f,-3.55344e-017f},{-0.984877f,-0.173254f,-3.11529e-017f}, +{-0.984896f,-0.173146f,1.83632e-017f},{-1.0f,9.25186e-018f,0.0f},{0.174653f,-0.98463f,-9.02129e-017f}, +{0.343547f,-0.939135f,-6.09442e-017f},{0.341361f,-0.939932f,5.80656e-017f},{0.499433f,-0.866353f,4.22428e-017f}, +{0.50141f,-0.86521f,-6.73633e-017f},{0.643858f,-0.765145f,-3.72305e-018f},{0.642401f,-0.766369f,-4.75242e-017f}, +{0.766786f,-0.641903f,4.43387e-018f},{0.765783f,-0.643099f,-3.19634e-017f},{0.865824f,-0.500349f,-2.50327e-018f}, +{0.866509f,-0.499162f,2.18382e-017f},{0.93996f,-0.341285f,0.0f},{0.939558f,-0.34239f,0.0f}, +{0.984896f,-0.173146f,0.0f},{0.984877f,-0.173254f,-1.60292e-017f},{1.0f,-1.23454e-016f,0.0f}, +{-0.865936f,-0.500155f,0.0f},{-0.854507f,-0.51944f,0.0f},{-0.775519f,-0.631325f,0.0f}, +{0.0683073f,-0.997664f,0.0f},{-0.0681817f,-0.997673f,0.0f},{-0.917149f,-0.398545f,0.0f}, +{-0.923845f,-0.382766f,0.0f},{-0.962855f,-0.270019f,0.0f},{-0.966227f,-0.257693f,0.0f}, +{-0.990676f,-0.13624f,0.0f},{-0.991539f,-0.129812f,0.0f},{-0.743005f,-0.669286f,0.0f}, +{-0.587506f,-0.80922f,0.0f},{-0.682437f,-0.730944f,0.0f},{-0.460028f,-0.887904f,0.0f}, +{-0.576624f,-0.81701f,0.0f},{-0.334824f,-0.942281f,0.0f},{-0.406692f,-0.913565f,0.0f}, +{-0.207937f,-0.978142f,0.0f},{-0.203392f,-0.979097f,0.0f},{0.334953f,-0.942235f,0.0f}, +{0.406678f,-0.913572f,0.0f},{0.207869f,-0.978157f,0.0f},{0.203541f,-0.979066f,0.0f}, +{0.682558f,-0.730831f,0.0f},{0.587343f,-0.809338f,0.0f},{0.576674f,-0.816974f,0.0f}, +{0.460094f,-0.88787f,0.0f},{0.865951f,-0.500129f,0.0f},{0.854435f,-0.519558f,0.0f}, +{0.917715f,-0.397241f,0.0f},{0.74294f,-0.669358f,0.0f},{0.775729f,-0.631066f,0.0f}, +{0.966174f,-0.257891f,0.0f},{0.96322f,-0.268715f,0.0f},{0.990678f,-0.136227f,0.0f}, +{0.92384f,-0.38278f,0.0f},{0.991509f,-0.130039f,0.0f},{-3.33067e-016f,1.0f,-4.16334e-017f}, +{-3.33067e-016f,1.0f,-2.77556e-017f},{-3.33067e-016f,1.0f,-5.55111e-017f},{0.173171f,0.984892f,1.78986e-017f}, +{-9.25186e-018f,1.0f,-1.67181e-035f},{-0.174653f,0.98463f,-2.90351e-018f},{-0.341361f,0.939932f,-2.3159e-017f}, +{-0.173171f,0.984892f,-2.19044e-018f},{-0.343547f,0.939135f,8.62609e-018f},{-0.499433f,0.866353f,1.29071e-017f}, +{-0.50141f,0.86521f,-1.57974e-018f},{-0.642401f,0.766369f,2.86405e-017f},{-0.766786f,0.641903f,-2.87549e-017f}, +{-0.765783f,0.643099f,-1.1667e-017f},{-0.643858f,0.765145f,5.31763e-017f},{-0.866509f,0.499162f,-3.48634e-017f}, +{-0.865824f,0.500349f,-7.01556e-018f},{-0.93996f,0.341285f,1.42356e-017f},{-0.939558f,0.34239f,-6.37547e-017f}, +{-0.984877f,0.173254f,1.97007e-017f},{-0.984896f,0.173146f,-1.94221e-019f},{-1.0f,-9.25186e-018f,0.0f}, +{0.174653f,0.98463f,-4.41838e-018f},{0.343547f,0.939135f,1.79971e-017f},{0.341361f,0.939932f,-2.17403e-017f}, +{0.499433f,0.866353f,-1.08297e-018f},{0.50141f,0.86521f,-1.19599e-017f},{0.643858f,0.765145f,4.09797e-017f}, +{0.642401f,0.766369f,-9.28657e-019f},{0.766786f,0.641903f,-1.10847e-018f},{0.765783f,0.643099f,-3.30704e-017f}, +{0.865824f,0.500349f,2.31458e-017f},{0.866509f,0.499162f,-2.05856e-017f},{0.93996f,0.341285f,1.35881e-018f}, +{0.939558f,0.34239f,0.0f},{0.984896f,0.173146f,0.0f},{0.984877f,0.173254f,-1.60292e-017f}, +{1.0f,2.02384e-018f,0.0f},{-0.865936f,0.500155f,0.0f},{-0.854507f,0.51944f,0.0f}, +{-0.775519f,0.631325f,0.0f},{0.0683073f,0.997664f,0.0f},{-0.0681817f,0.997673f,0.0f}, +{-0.917149f,0.398545f,0.0f},{-0.923845f,0.382766f,0.0f},{-0.962855f,0.270019f,0.0f}, +{-0.966227f,0.257693f,0.0f},{-0.990676f,0.13624f,0.0f},{-0.991539f,0.129812f,0.0f}, +{-1.0f,1.19209e-007f,0.0f},{-0.743005f,0.669286f,0.0f},{-0.587506f,0.80922f,0.0f}, +{-0.682437f,0.730944f,0.0f},{-0.460028f,0.887904f,0.0f},{-0.576624f,0.81701f,0.0f}, +{-0.334824f,0.942281f,0.0f},{-0.406692f,0.913565f,0.0f},{-0.207937f,0.978142f,0.0f}, +{-0.203392f,0.979097f,0.0f},{0.334953f,0.942235f,0.0f},{0.406678f,0.913572f,0.0f}, +{0.207869f,0.978157f,0.0f},{0.203541f,0.979066f,0.0f},{0.682558f,0.730831f,0.0f}, +{0.587343f,0.809338f,0.0f},{0.576674f,0.816974f,0.0f},{0.460094f,0.88787f,0.0f}, +{0.865951f,0.500129f,0.0f},{0.854435f,0.519558f,0.0f},{0.917715f,0.397241f,0.0f}, +{0.74294f,0.669358f,0.0f},{0.775729f,0.631066f,0.0f},{0.966174f,0.257891f,0.0f}, +{0.96322f,0.268715f,0.0f},{0.990678f,0.136227f,0.0f},{0.92384f,0.38278f,0.0f}, +{0.991509f,0.130039f,0.0f},{0.866025f,0.5f,1.70981e-017f},{0.866025f,0.5f,1.85927e-018f}, +{-0.866025f,0.5f,1.38778e-017f},{-0.984877f,0.173254f,1.60292e-017f},{-0.984896f,0.173146f,0.0f}, +{-0.765783f,0.643099f,2.97493e-017f},{-0.766786f,0.641903f,-3.5471e-017f},{-0.865824f,0.500349f,-2.31458e-017f}, +{-0.866509f,0.499162f,2.30909e-017f},{-0.93996f,0.341285f,0.0f},{-0.939558f,0.34239f,0.0f}, +{-0.343547f,0.939135f,-2.17219e-017f},{-0.341361f,0.939932f,2.17403e-017f},{-0.174653f,0.98463f,4.03966e-018f}, +{-0.642401f,0.766369f,0.0f},{-0.50141f,0.86521f,2.31949e-017f},{0.174653f,0.98463f,4.03966e-018f}, +{0.341361f,0.939932f,1.77925e-017f},{0.173171f,0.984892f,4.00538e-018f},{9.25186e-018f,1.0f,0.0f}, +{0.643858f,0.765145f,-1.25718e-017f},{0.642401f,0.766369f,-3.47348e-017f},{0.50141f,0.86521f,1.0006e-017f}, +{0.499433f,0.866353f,-4.24336e-018f},{0.343547f,0.939135f,-2.91481e-018f},{0.766786f,0.641903f,-9.27937e-018f}, +{0.865824f,0.500349f,1.55228e-017f},{0.765783f,0.643099f,-1.85933e-018f},{0.866509f,0.499162f,-1.44318e-018f}, +{0.939558f,0.34239f,1.07308e-017f},{0.984877f,0.173254f,9.86413e-018f},{0.93996f,0.341285f,3.39702e-018f}, +{0.984896f,0.173146f,-1.1702e-017f},{-0.173171f,0.984892f,-1.87748e-017f},{-0.643858f,0.765145f,-3.53951e-017f}, +{3.84593e-017f,-1.0f,2.46519e-032f},{9.71445e-017f,0.0f,1.0f},{9.28077e-017f,0.0f,1.0f}, +{6.245e-017f,0.0f,1.0f},{-9.02056e-017f,0.0f,1.0f},{9.36751e-017f,0.0f,1.0f}, +{-8.08815e-017f,0.0f,1.0f},{-4.16334e-017f,0.0f,1.0f},{0.866025f,-0.5f,4.83767e-017f}, +{0.866025f,-0.5f,-3.32262e-017f},{-0.991509f,-0.130039f,0.0f},{-0.854435f,-0.519558f,0.0f}, +{-0.917715f,-0.397241f,0.0f},{-0.865951f,-0.500129f,0.0f},{-0.92384f,-0.38278f,0.0f}, +{-0.96322f,-0.268715f,0.0f},{-0.966174f,-0.257891f,0.0f},{-0.775729f,-0.631066f,0.0f}, +{-0.74294f,-0.669358f,0.0f},{-0.682558f,-0.730831f,0.0f},{-0.207869f,-0.978157f,0.0f}, +{-0.0683073f,-0.997664f,0.0f},{-0.406678f,-0.913572f,0.0f},{-0.334953f,-0.942235f,0.0f}, +{-0.460094f,-0.88787f,0.0f},{0.576624f,-0.81701f,0.0f},{0.460028f,-0.887904f,0.0f}, +{0.587506f,-0.80922f,0.0f},{0.334824f,-0.942281f,0.0f},{0.203392f,-0.979097f,0.0f}, +{0.207937f,-0.978142f,0.0f},{0.682437f,-0.730944f,0.0f},{0.743005f,-0.669286f,0.0f}, +{0.775519f,-0.631325f,0.0f},{0.865936f,-0.500155f,0.0f},{0.917149f,-0.398545f,0.0f}, +{0.854507f,-0.51944f,0.0f},{0.923845f,-0.382766f,0.0f},{0.962855f,-0.270019f,0.0f}, +{0.966227f,-0.257693f,0.0f},{0.991539f,-0.129812f,0.0f},{0.990676f,-0.13624f,0.0f}, +{1.0f,-1.19209e-007f,0.0f},{0.406692f,-0.913565f,0.0f},{0.0681817f,-0.997673f,0.0f}, +{-0.203541f,-0.979066f,0.0f},{-0.576674f,-0.816974f,0.0f},{-0.587343f,-0.809338f,0.0f}, +{-0.990678f,-0.136227f,0.0f},{-0.984877f,-0.173254f,1.60292e-017f},{-0.984896f,-0.173146f,0.0f}, +{-0.765783f,-0.643099f,6.51739e-017f},{-0.766786f,-0.641903f,3.5471e-017f},{-0.865824f,-0.500349f,0.0f}, +{-0.866509f,-0.499162f,-2.30909e-017f},{-0.93996f,-0.341285f,0.0f},{-0.939558f,-0.34239f,0.0f}, +{-0.343547f,-0.939135f,6.51656e-017f},{-0.341361f,-0.939932f,-6.52209e-017f},{-0.174653f,-0.98463f,9.10966e-017f}, +{-0.642401f,-0.766369f,6.51687e-017f},{-0.499433f,-0.866353f,-4.00769e-017f},{-0.50141f,-0.86521f,8.0048e-017f}, +{0.174653f,-0.98463f,-1.13871e-017f},{0.341361f,-0.939932f,6.91687e-017f},{0.173171f,-0.984892f,-7.63514e-017f}, +{7.40149e-017f,-1.0f,-2.31296e-017f},{9.25186e-018f,-1.0f,-2.31296e-017f},{0.643858f,-0.765145f,8.9189e-017f}, +{0.642401f,-0.766369f,-3.71463e-018f},{0.50141f,-0.86521f,2.08077e-017f},{0.499433f,-0.866353f,3.00576e-017f}, +{0.343547f,-0.939135f,-2.9668e-017f},{0.766786f,-0.641903f,3.71175e-018f},{0.865824f,-0.500349f,1.19628e-017f}, +{0.765783f,-0.643099f,4.04648e-017f},{0.866509f,-0.499162f,4.98303e-017f},{0.939558f,-0.34239f,3.49929e-018f}, +{0.984877f,-0.173254f,1.39894e-018f},{0.93996f,-0.341285f,1.29405e-018f},{0.984896f,-0.173146f,-5.94412e-018f}, +{-0.173171f,-0.984892f,-3.0791e-017f},{-0.643858f,-0.765145f,2.97844e-017f},{-0.991509f,0.130039f,0.0f}, +{-0.854435f,0.519558f,0.0f},{-0.917715f,0.397241f,0.0f},{-0.865951f,0.500129f,0.0f}, +{-0.92384f,0.38278f,0.0f},{-0.96322f,0.268715f,0.0f},{-0.966174f,0.257891f,0.0f}, +{-0.775729f,0.631066f,0.0f},{-0.74294f,0.669358f,0.0f},{-0.682558f,0.730831f,0.0f}, +{-0.207869f,0.978157f,0.0f},{-0.0683073f,0.997664f,0.0f},{-0.406678f,0.913572f,0.0f}, +{-0.334953f,0.942235f,0.0f},{-0.460094f,0.88787f,0.0f},{0.576624f,0.81701f,0.0f}, +{0.460028f,0.887904f,0.0f},{0.587506f,0.80922f,0.0f},{0.334824f,0.942281f,0.0f}, +{0.203392f,0.979097f,0.0f},{0.207937f,0.978142f,0.0f},{0.682437f,0.730944f,0.0f}, +{0.743005f,0.669286f,0.0f},{0.775519f,0.631325f,0.0f},{0.865936f,0.500155f,0.0f}, +{0.917149f,0.398545f,0.0f},{0.854507f,0.51944f,0.0f},{0.923845f,0.382766f,0.0f}, +{0.962855f,0.270019f,0.0f},{0.966227f,0.257693f,0.0f},{0.991539f,0.129812f,0.0f}, +{0.990676f,0.13624f,0.0f},{0.406692f,0.913565f,0.0f},{0.0681817f,0.997673f,0.0f}, +{-0.203541f,0.979066f,0.0f},{-0.576674f,0.816974f,0.0f},{-0.587343f,0.809338f,0.0f}, +{-0.990678f,0.136227f,0.0f},{-1.56125e-017f,0.0f,-1.0f},{2.24376e-017f,0.0f,-1.0f}, +{0.0f,6.66133e-018f,-1.0f},{-0.826318f,0.563203f,8.5792e-016f},{-0.642788f,0.766044f,2.41345e-015f}, +{-0.411158f,0.911564f,4.62954e-015f},{-0.158603f,0.987342f,-9.23504e-017f},{-0.411158f,0.911564f,2.06582e-015f}, +{0.0871557f,0.996195f,0.0f},{-0.944801f,0.327644f,-1.14754e-015f},{-0.996195f,0.0871557f,0.0f}, +{0.911564f,-0.411158f,6.02585e-016f},{0.766044f,-0.642788f,2.94214e-015f},{0.563203f,-0.826318f,9.64676e-016f}, +{0.327644f,-0.944801f,-9.8684e-016f},{0.563203f,-0.826318f,5.93271e-017f},{0.0871557f,-0.996195f,0.0f}, +{0.987342f,-0.158603f,0.0f},{0.996195f,0.0871557f,0.0f},{0.563203f,0.826318f,-8.5792e-016f}, +{0.766044f,0.642788f,3.08747e-015f},{0.911564f,0.411158f,3.8213e-016f},{0.987342f,0.158603f,-1.87973e-016f}, +{0.996195f,-0.0871557f,0.0f},{0.327644f,0.944801f,6.91476e-016f},{-0.411158f,-0.911564f,-9.85162e-016f}, +{-0.642788f,-0.766044f,2.97296e-015f},{-0.826318f,-0.563203f,-3.47088e-015f},{-0.944801f,-0.327644f,3.94878e-016f}, +{-0.996195f,-0.0871557f,0.0f},{-0.158603f,-0.987342f,4.08313e-016f},{0.826318f,-0.563203f,0.0f}, +{0.642788f,-0.766044f,-2.49102e-015f},{0.411158f,-0.911564f,1.48326e-015f},{0.158603f,-0.987342f,4.46669e-015f}, +{0.411158f,-0.911564f,1.36553e-015f},{-0.0871557f,-0.996195f,0.0f},{0.944801f,-0.327644f,3.04041e-016f}, +{-0.911564f,0.411158f,-6.75921e-016f},{-0.766044f,0.642788f,-3.67481e-016f},{-0.766044f,0.642788f,1.28733e-015f}, +{-0.563203f,0.826318f,6.30798e-016f},{-0.327644f,0.944801f,4.06883e-015f},{-0.563203f,0.826318f,-1.38054e-015f}, +{-0.0871557f,0.996195f,0.0f},{-0.987342f,0.158603f,8.16626e-016f},{0.563203f,0.826318f,-4.26026e-015f}, +{0.766044f,0.642788f,4.25258e-016f},{0.911564f,0.411158f,1.0983e-015f},{0.987342f,0.158603f,1.5422e-016f}, +{0.327644f,0.944801f,-6.58982e-018f},{-0.411158f,-0.911564f,2.34676e-015f},{-0.642788f,-0.766044f,1.45647e-015f}, +{-0.826318f,-0.563203f,1.2984e-017f},{-0.944801f,-0.327644f,-2.78891e-016f},{-0.158603f,-0.987342f,-4.78492e-018f}, +{0.826318f,-0.563203f,-4.23761e-015f},{0.642788f,-0.766044f,4.40666e-016f},{0.411158f,-0.911564f,1.12007e-015f}, +{0.158603f,-0.987342f,2.37841e-016f},{0.944801f,-0.327644f,-1.31796e-017f},{-0.911564f,0.411158f,2.35503e-015f}, +{-0.766044f,0.642788f,1.50818e-015f},{-0.563203f,0.826318f,-2.90842e-017f},{-0.327644f,0.944801f,-4.12948e-016f}, +{-0.987342f,0.158603f,4.78492e-018f},{-0.563203f,-0.826318f,-4.27159e-015f},{-0.766044f,-0.642788f,4.67628e-016f}, +{-0.911564f,-0.411158f,1.14986e-015f},{-0.987342f,-0.158603f,2.73989e-016f},{-0.327644f,-0.944801f,0.0f}, +{0.411158f,0.911564f,2.32608e-015f},{0.642788f,0.766044f,1.46294e-015f},{0.826318f,0.563203f,-3.1681e-017f}, +{0.944801f,0.327644f,-2.83939e-016f},{0.158603f,0.987342f,-1.59497e-018f},{0.826318f,-0.563203f,1.44993e-015f}, +{0.642788f,-0.766044f,2.4393e-015f},{0.411158f,-0.911564f,-4.18125e-015f},{0.158603f,-0.987342f,8.31771e-016f}, +{0.411158f,-0.911564f,-1.65888e-015f},{0.944801f,-0.327644f,0.0f},{-0.911564f,0.411158f,-2.19033e-015f}, +{-0.766044f,0.642788f,-3.6771e-015f},{-0.766044f,0.642788f,-1.19489e-015f},{-0.563203f,0.826318f,-7.29772e-016f}, +{-0.327644f,0.944801f,-3.40246e-015f},{-0.563203f,0.826318f,1.11462e-015f},{-0.987342f,0.158603f,4.08313e-016f}, +{-0.563203f,-0.826318f,-2.65912e-016f},{-0.766044f,-0.642788f,2.72372e-015f},{-0.911564f,-0.411158f,-8.55226e-016f}, +{-0.987342f,-0.158603f,2.40746e-015f},{-0.911564f,-0.411158f,-5.99094e-016f},{-0.327644f,-0.944801f,-6.91476e-016f}, +{0.411158f,0.911564f,4.55913e-016f},{0.642788f,0.766044f,3.70792e-015f},{0.826318f,0.563203f,6.53453e-016f}, +{0.944801f,0.327644f,-4.49072e-015f},{0.158603f,0.987342f,5.67178e-016f},{-0.826318f,0.563203f,-5.92007e-016f}, +{-0.642788f,0.766044f,-1.03426e-016f},{-0.411158f,0.911564f,-6.48711e-016f},{-0.158603f,0.987342f,-2.75969e-015f}, +{-0.944801f,0.327644f,1.68699e-015f},{0.911564f,-0.411158f,7.33362e-017f},{0.766044f,-0.642788f,9.35257e-016f}, +{0.563203f,-0.826318f,2.43257e-016f},{0.327644f,-0.944801f,-1.38084e-015f},{-0.563203f,-0.826318f,2.11031e-015f}, +{-0.766044f,-0.642788f,-8.23554e-016f},{-0.911564f,-0.411158f,-1.36865e-015f},{-0.987342f,-0.158603f,-1.67467e-016f}, +{-0.327644f,-0.944801f,-1.31796e-017f},{0.411158f,0.911564f,2.33642e-015f},{0.642788f,0.766044f,4.84808e-018f}, +{0.826318f,0.563203f,-6.03969e-016f},{0.944801f,0.327644f,-2.44862e-016f},{0.158603f,0.987342f,2.54184e-015f}, +{-0.826318f,0.563203f,2.11031e-015f},{-0.642788f,0.766044f,-8.5822e-016f},{-0.411158f,0.911564f,-1.4099e-015f}, +{-0.158603f,0.987342f,-1.68553e-016f},{-0.944801f,0.327644f,-6.58982e-018f},{0.911564f,-0.411158f,2.34056e-015f}, +{0.766044f,-0.642788f,-1.93923e-017f},{0.563203f,-0.826318f,-5.38529e-016f},{0.327644f,-0.944801f,-2.89548e-016f}, +{0.987342f,-0.158603f,2.53865e-015f},{0.563203f,0.826318f,2.15562e-015f},{0.766044f,0.642788f,-8.11999e-016f}, +{0.911564f,0.411158f,-1.3824e-015f},{0.987342f,0.158603f,-1.10685e-016f},{-0.411158f,-0.911564f,2.34883e-015f}, +{-0.642788f,-0.766044f,2.74725e-017f},{-0.826318f,-0.563203f,-5.36452e-016f},{-0.944801f,-0.327644f,-3.24435e-016f}, +{-0.158603f,-0.987342f,2.54503e-015f},{-0.563203f,-0.826318f,3.03281e-015f},{-0.766044f,-0.642788f,-3.0099e-015f}, +{-0.911564f,-0.411158f,-9.44011e-016f},{-0.987342f,-0.158603f,2.45238e-016f},{-0.911564f,-0.411158f,1.24043e-017f}, +{-0.327644f,-0.944801f,5.39456e-016f},{0.411158f,0.911564f,3.82577e-016f},{0.642788f,0.766044f,4.75332e-016f}, +{0.826318f,0.563203f,-1.81339e-015f},{0.944801f,0.327644f,3.44751e-015f},{0.158603f,0.987342f,0.0f}, +{-0.826318f,0.563203f,-4.28292e-015f},{-0.642788f,0.766044f,4.67628e-016f},{-0.411158f,0.911564f,1.0983e-015f}, +{-0.158603f,0.987342f,2.69956e-016f},{-0.944801f,0.327644f,6.58982e-018f},{0.911564f,-0.411158f,2.34469e-015f}, +{0.766044f,-0.642788f,1.47748e-015f},{0.563203f,-0.826318f,-1.45421e-017f},{0.327644f,-0.944801f,-3.87636e-016f}, +{0.987342f,-0.158603f,-3.18994e-018f},{0.563203f,0.826318f,-5.92007e-016f},{0.766044f,0.642788f,-1.03426e-016f}, +{0.911564f,0.411158f,-6.48711e-016f},{0.987342f,0.158603f,-2.75969e-015f},{0.327644f,0.944801f,1.68699e-015f}, +{-0.411158f,-0.911564f,-1.97032e-015f},{-0.642788f,-0.766044f,-3.61548e-015f},{-0.642788f,-0.766044f,-1.25652e-015f}, +{-0.826318f,-0.563203f,-7.52427e-016f},{-0.944801f,-0.327644f,-3.40576e-015f},{-0.826318f,-0.563203f,1.09197e-015f}, +{-0.104013f,0.994576f,-6.6149e-017f},{0.105163f,0.994455f,3.5074e-016f},{0.104013f,0.994576f,-2.77314e-017f}, +{-0.105163f,0.994455f,6.61477e-016f},{-0.308272f,0.951298f,-6.26411e-016f},{-0.310578f,0.950548f,-2.09449e-015f}, +{-0.50141f,0.86521f,-1.84452e-015f},{-0.66887f,0.743379f,-1.74439e-015f},{-0.499433f,0.866353f,-2.26521e-016f}, +{-0.670096f,0.742274f,-5.94667e-016f},{-0.808947f,0.587881f,-3.87528e-016f},{-0.809606f,0.586974f,-1.45655e-015f}, +{-0.913543f,0.406743f,-1.77092e-016f},{-0.913862f,0.406026f,3.24871e-015f},{-0.978165f,0.20783f,4.08599e-015f}, +{-0.978254f,0.207408f,-1.59112e-015f},{-1.0f,1.18424e-015f,0.0f},{0.308272f,0.951298f,9.4669e-016f}, +{0.499433f,0.866353f,1.42515e-015f},{0.310578f,0.950548f,1.52945e-016f},{0.50141f,0.86521f,6.9607e-017f}, +{0.66887f,0.743379f,0.0f},{0.670096f,0.742274f,1.78483e-015f},{0.808947f,0.587881f,-2.08258e-015f}, +{0.913543f,0.406743f,6.54457e-017f},{0.809606f,0.586974f,-1.98983e-015f},{0.913862f,0.406026f,0.0f}, +{0.978254f,0.207408f,-5.0369e-015f},{1.0f,-9.4739e-015f,0.0f},{-0.104013f,0.994576f,9.38801e-017f}, +{0.105163f,0.994455f,4.30745e-016f},{0.104013f,0.994576f,-2.27768e-016f},{-0.105163f,0.994455f,5.01467e-016f}, +{-0.308272f,0.951298f,-4.73345e-016f},{-0.310578f,0.950548f,-2.03714e-015f},{-0.50141f,0.86521f,-1.7053e-015f}, +{-0.66887f,0.743379f,-1.60982e-015f},{-0.670096f,0.742274f,-6.24525e-016f},{-0.808947f,0.587881f,-3.81616e-016f}, +{-0.809606f,0.586974f,-1.44179e-015f},{-0.913543f,0.406743f,-2.19018e-016f},{-0.913862f,0.406026f,3.22523e-015f}, +{-0.978165f,0.20783f,4.08922e-015f},{-0.978254f,0.207408f,-1.62446e-015f},{0.308272f,0.951298f,7.93624e-016f}, +{0.499433f,0.866353f,1.28576e-015f},{0.310578f,0.950548f,7.64725e-017f},{0.50141f,0.86521f,-6.9607e-017f}, +{0.670096f,0.742274f,1.6654e-015f},{0.913543f,0.406743f,0.0f},{0.809606f,0.586974f,-2.08427e-015f}, +{0.978165f,0.20783f,3.34403e-017f},{0.978254f,0.207408f,-5.07027e-015f},{-0.104013f,0.994576f,-1.73895e-016f}, +{0.105163f,0.994455f,1.6001e-016f},{0.104013f,0.994576f,1.73895e-016f},{-0.105163f,0.994455f,-4.00024e-017f}, +{-0.308272f,0.951298f,-6.71751e-016f},{-0.310578f,0.950548f,1.61654e-016f},{-0.50141f,0.86521f,-1.38259e-015f}, +{-0.66887f,0.743379f,-6.41222e-016f},{-0.499433f,0.866353f,1.60719e-016f},{-0.670096f,0.742274f,-1.27144e-015f}, +{-0.808947f,0.587881f,4.64432e-016f},{-0.809606f,0.586974f,1.42408e-015f},{-0.913543f,0.406743f,-2.92513e-016f}, +{-0.913862f,0.406026f,1.97537e-015f},{-0.978165f,0.20783f,1.58084e-015f},{-0.978254f,0.207408f,-1.89991e-015f}, +{-1.0f,1.0066e-014f,0.0f},{0.308272f,0.951298f,0.0f},{0.499433f,0.866353f,-1.28576e-015f}, +{0.50141f,0.86521f,-1.36045e-015f},{0.66887f,0.743379f,1.72196e-015f},{0.670096f,0.742274f,-5.97167e-017f}, +{0.913543f,0.406743f,2.35185e-015f},{0.809606f,0.586974f,0.0f},{0.913862f,0.406026f,2.35267e-015f}, +{0.978165f,0.20783f,-5.00299e-015f},{0.978254f,0.207408f,-3.33724e-017f},{-0.104013f,0.994576f,-3.33924e-016f}, +{0.105163f,0.994455f,8.00048e-017f},{0.104013f,0.994576f,3.73931e-016f},{-0.105163f,0.994455f,1.20007e-016f}, +{-0.308272f,0.951298f,-8.24817e-016f},{-0.310578f,0.950548f,1.043e-016f},{-0.50141f,0.86521f,-1.52181e-015f}, +{-0.66887f,0.743379f,-7.75785e-016f},{-0.499433f,0.866353f,-6.5802e-017f},{-0.670096f,0.742274f,-1.24159e-015f}, +{-0.808947f,0.587881f,4.5852e-016f},{-0.809606f,0.586974f,1.40933e-015f},{-0.913543f,0.406743f,-2.50587e-016f}, +{-0.913862f,0.406026f,1.99885e-015f},{-0.978165f,0.20783f,1.57761e-015f},{-0.978254f,0.207408f,-1.86657e-015f}, +{0.308272f,0.951298f,1.53066e-016f},{0.499433f,0.866353f,-1.14636e-015f},{0.50141f,0.86521f,-1.22124e-015f}, +{0.670096f,0.742274f,5.97167e-017f},{0.913543f,0.406743f,2.4173e-015f},{0.809606f,0.586974f,9.44452e-017f}, +{0.978165f,0.20783f,-5.03643e-015f},{0.978254f,0.207408f,0.0f},{-0.104013f,0.994576f,2.55628e-015f}, +{0.105163f,0.994455f,3.84446e-015f},{0.104013f,0.994576f,-8.36797e-018f},{-0.105163f,0.994455f,2.54746e-015f}, +{-0.308272f,0.951298f,-1.84919e-015f},{-0.310578f,0.950548f,6.24273e-016f},{-0.50141f,0.86521f,-2.49577e-015f}, +{-0.66887f,0.743379f,-1.86669e-015f},{-0.499433f,0.866353f,4.20202e-015f},{-0.670096f,0.742274f,-6.0878e-016f}, +{-0.808947f,0.587881f,-5.61965e-016f},{-0.809606f,0.586974f,-5.29626e-016f},{-0.913543f,0.406743f,-4.68477e-016f}, +{-0.913862f,0.406026f,1.88599e-016f},{-0.978165f,0.20783f,-8.08443e-016f},{-0.978254f,0.207408f,3.31428e-016f}, +{0.308272f,0.951298f,-1.21213e-015f},{0.499433f,0.866353f,-2.23036e-015f},{0.310578f,0.950548f,3.68317e-015f}, +{0.50141f,0.86521f,-2.3081e-015f},{0.66887f,0.743379f,1.96759e-015f},{0.670096f,0.742274f,1.0782e-016f}, +{0.808947f,0.587881f,-1.95242e-016f},{0.809606f,0.586974f,6.51336e-017f},{0.913862f,0.406026f,-2.23761e-015f}, +{0.978165f,0.20783f,1.07009e-015f},{0.978254f,0.207408f,-1.06792e-015f},{-0.104013f,0.994576f,2.54791e-015f}, +{0.105163f,0.994455f,2.56439e-015f},{0.104013f,0.994576f,8.36797e-018f},{-0.105163f,0.994455f,-1.27162e-015f}, +{-0.308272f,0.951298f,-1.82439e-015f},{-0.310578f,0.950548f,-1.79786e-015f},{-0.50141f,0.86521f,-1.67057e-015f}, +{-0.66887f,0.743379f,-8.96351e-016f},{-0.499433f,0.866353f,-3.97345e-015f},{-0.670096f,0.742274f,2.57549e-015f}, +{-0.808947f,0.587881f,1.24903e-015f},{-0.809606f,0.586974f,6.51412e-018f},{-0.913543f,0.406743f,-4.18802e-016f}, +{-0.913862f,0.406026f,4.82137e-016f},{-0.978165f,0.20783f,5.39336e-016f},{-0.978254f,0.207408f,3.75279e-016f}, +{-1.0f,3.70074e-017f,0.0f},{0.308272f,0.951298f,-2.53585e-015f},{0.499433f,0.866353f,2.23036e-015f}, +{0.310578f,0.950548f,4.89424e-015f},{0.50141f,0.86521f,8.06778e-017f},{0.66887f,0.743379f,-3.93518e-015f}, +{0.670096f,0.742274f,-5.7328e-015f},{0.808947f,0.587881f,-1.51346e-015f},{0.913862f,0.406026f,-1.47042e-016f}, +{0.978254f,0.207408f,-9.10514e-016f},{0.105163f,0.994455f,3.84869e-015f},{0.104013f,0.994576f,2.51039e-017f}, +{-0.310578f,0.950548f,5.86794e-016f},{-0.50141f,0.86521f,-2.45543e-015f},{-0.66887f,0.743379f,-1.85997e-015f}, +{-0.499433f,0.866353f,4.16184e-015f},{-0.670096f,0.742274f,-7.23339e-016f},{-0.808947f,0.587881f,-7.32801e-016f}, +{-0.809606f,0.586974f,-5.96795e-016f},{-0.913543f,0.406743f,-3.41009e-016f},{-0.913862f,0.406026f,2.10425e-016f}, +{-0.978165f,0.20783f,-9.90731e-016f},{-0.978254f,0.207408f,1.24376e-016f},{0.308272f,0.951298f,-1.19972e-015f}, +{0.499433f,0.866353f,-2.27054e-015f},{0.310578f,0.950548f,3.67068e-015f},{0.50141f,0.86521f,-2.22742e-015f}, +{0.66887f,0.743379f,1.91378e-015f},{0.670096f,0.742274f,-1.0782e-016f},{0.808947f,0.587881f,-1.30161e-016f}, +{0.809606f,0.586974f,1.30267e-016f},{0.913862f,0.406026f,-2.09057e-015f},{0.978165f,0.20783f,1.22748e-015f}, +{0.105163f,0.994455f,2.56015e-015f},{0.104013f,0.994576f,1.67359e-017f},{-0.105163f,0.994455f,-1.29277e-015f}, +{-0.310578f,0.950548f,-1.78537e-015f},{-0.50141f,0.86521f,-1.66048e-015f},{-0.66887f,0.743379f,-9.97247e-016f}, +{-0.499433f,0.866353f,-3.84287e-015f},{-0.670096f,0.742274f,2.54179e-015f},{-0.808947f,0.587881f,1.41783e-015f}, +{-0.809606f,0.586974f,2.30411e-016f},{-0.913543f,0.406743f,-4.4866e-016f},{-0.913862f,0.406026f,6.14245e-016f}, +{-0.978165f,0.20783f,6.54611e-016f},{-0.978254f,0.207408f,1.60695e-016f},{-1.0f,3.14563e-016f,0.0f}, +{0.308272f,0.951298f,-2.44905e-015f},{0.499433f,0.866353f,2.15e-015f},{0.310578f,0.950548f,4.91923e-015f}, +{0.50141f,0.86521f,4.03389e-017f},{0.66887f,0.743379f,-3.82756e-015f},{0.670096f,0.742274f,-5.62498e-015f}, +{0.808947f,0.587881f,-1.64362e-015f},{0.913543f,0.406743f,-1.46991e-016f},{0.978165f,0.20783f,1.57389e-016f}, +{-0.104013f,0.994576f,-3.07782e-016f},{0.104013f,0.994576f,-3.61655e-016f},{-0.105163f,0.994455f,-4.46105e-016f}, +{-0.308272f,0.951298f,-7.65328e-017f},{-0.310578f,0.950548f,3.61544e-016f},{-0.50141f,0.86521f,2.00587e-015f}, +{-0.66887f,0.743379f,5.42625e-016f},{-0.499433f,0.866353f,-2.73223e-015f},{-0.808947f,0.587881f,2.6919e-016f}, +{-0.809606f,0.586974f,1.35895e-015f},{-0.913543f,0.406743f,2.90454e-015f},{-0.913862f,0.406026f,-3.57547e-015f}, +{-0.978165f,0.20783f,6.07001e-016f},{-0.978254f,0.207408f,-2.30818e-015f},{0.308272f,0.951298f,-3.96812e-016f}, +{0.499433f,0.866353f,0.0f},{0.310578f,0.950548f,8.76033e-016f},{0.50141f,0.86521f,1.22124e-015f}, +{0.66887f,0.743379f,-1.72196e-015f},{0.670096f,0.742274f,-1.78483e-015f},{0.808947f,0.587881f,0.0f}, +{0.913862f,0.406026f,4.70535e-015f},{1.0f,9.4739e-015f,0.0f},{-0.104013f,0.994576f,-5.75557e-016f}, +{-0.308272f,0.951298f,1.21873e-016f},{-0.50141f,0.86521f,-2.53104e-016f},{-0.66887f,0.743379f,-3.18355e-016f}, +{-0.670096f,0.742274f,-7.32345e-016f},{-0.808947f,0.587881f,-3.37532e-015f},{-0.809606f,0.586974f,-2.35366e-015f}, +{-0.913543f,0.406743f,6.26179e-016f},{-0.913862f,0.406026f,1.68129e-015f},{-0.978165f,0.20783f,3.11538e-015f}, +{-0.978254f,0.207408f,-2.35245e-015f},{-1.0f,-1.0066e-014f,0.0f},{0.310578f,0.950548f,1.27581e-015f}, +{0.808947f,0.587881f,6.24774e-015f},{0.913543f,0.406743f,4.7037e-015f},{-0.104013f,0.994576f,-7.35586e-016f}, +{0.104013f,0.994576f,-1.61619e-016f},{-0.308272f,0.951298f,-3.11924e-017f},{-0.310578f,0.950548f,3.0419e-016f}, +{-0.50141f,0.86521f,-3.92318e-016f},{-0.66887f,0.743379f,-4.52917e-016f},{-0.670096f,0.742274f,-7.02486e-016f}, +{-0.808947f,0.587881f,-3.38123e-015f},{-0.809606f,0.586974f,-2.36842e-015f},{-0.913543f,0.406743f,6.68105e-016f}, +{-0.913862f,0.406026f,1.70476e-015f},{-0.978165f,0.20783f,3.11215e-015f},{-0.978254f,0.207408f,-2.31911e-015f}, +{0.499433f,0.866353f,1.39398e-016f},{0.310578f,0.950548f,1.35229e-015f},{0.50141f,0.86521f,1.36045e-015f}, +{0.670096f,0.742274f,-1.6654e-015f},{0.913543f,0.406743f,4.76915e-015f},{-0.104013f,0.994576f,-4.67811e-016f}, +{-0.105163f,0.994455f,-2.86095e-016f},{-0.308272f,0.951298f,-2.29599e-016f},{-0.50141f,0.86521f,1.86666e-015f}, +{-0.66887f,0.743379f,4.08063e-016f},{-0.499433f,0.866353f,-2.95875e-015f},{-0.808947f,0.587881f,2.63278e-016f}, +{-0.809606f,0.586974f,1.34419e-015f},{-0.913543f,0.406743f,2.94646e-015f},{-0.913862f,0.406026f,-3.55199e-015f}, +{-0.978165f,0.20783f,6.03768e-016f},{-0.978254f,0.207408f,-2.27484e-015f},{0.308272f,0.951298f,-2.43746e-016f}, +{0.310578f,0.950548f,9.52505e-016f},{-0.104013f,0.994576f,-1.28023e-015f},{0.105163f,0.994455f,-6.40039e-015f}, +{0.104013f,0.994576f,-1.2635e-015f},{-0.105163f,0.994455f,-3.84023e-015f},{-0.308272f,0.951298f,-3.07371e-015f}, +{-0.50141f,0.86521f,8.55453e-016f},{-0.66887f,0.743379f,4.91897e-016f},{-0.499433f,0.866353f,-2.5192e-015f}, +{-0.670096f,0.742274f,2.12958e-015f},{-0.808947f,0.587881f,4.21337e-015f},{-0.809606f,0.586974f,-3.09392e-017f}, +{-0.913543f,0.406743f,-1.09766e-015f},{-0.913862f,0.406026f,-7.15687e-016f},{-0.978165f,0.20783f,4.50713e-016f}, +{-0.978254f,0.207408f,2.11367e-017f},{0.308272f,0.951298f,3.69838e-015f},{0.499433f,0.866353f,-2.15e-015f}, +{0.310578f,0.950548f,2.44712e-015f},{0.50141f,0.86521f,2.26776e-015f},{0.808947f,0.587881f,1.30161e-016f}, +{0.809606f,0.586974f,-1.51112e-015f},{0.913862f,0.406026f,1.47042e-016f},{0.978254f,0.207408f,1.57403e-016f}, +{-0.104013f,0.994576f,-1.2886e-015f},{0.105163f,0.994455f,-2.54323e-015f},{0.104013f,0.994576f,-1.29697e-015f}, +{-0.105163f,0.994455f,-2.56439e-015f},{-0.308272f,0.951298f,2.43665e-015f},{-0.310578f,0.950548f,-1.77287e-015f}, +{-0.50141f,0.86521f,-2.01694e-017f},{-0.66887f,0.743379f,-4.04454e-016f},{-0.499433f,0.866353f,2.22032e-015f}, +{-0.670096f,0.742274f,-1.08838e-015f},{-0.808947f,0.587881f,-7.85202e-016f},{-0.809606f,0.586974f,2.0208e-015f}, +{-0.913543f,0.406743f,-1.10599e-015f},{-0.913862f,0.406026f,9.7451e-016f},{-0.978165f,0.20783f,-1.11392e-015f}, +{-0.978254f,0.207408f,1.58514e-016f},{0.308272f,0.951298f,-2.42425e-015f},{0.499433f,0.866353f,-4.46073e-015f}, +{0.310578f,0.950548f,2.47211e-015f},{0.50141f,0.86521f,-1.21017e-016f},{0.66887f,0.743379f,3.71993e-015f}, +{0.670096f,0.742274f,1.91093e-015f},{0.808947f,0.587881f,1.51346e-015f},{0.913543f,0.406743f,-1.19412e-015f}, +{0.913862f,0.406026f,-1.04529e-015f},{0.978254f,0.207408f,3.14806e-016f},{-0.104013f,0.994576f,-1.27605e-015f}, +{0.105163f,0.994455f,-2.56015e-015f},{0.104013f,0.994576f,-1.27187e-015f},{-0.105163f,0.994455f,-2.55169e-015f}, +{-0.308272f,0.951298f,2.44285e-015f},{-0.310578f,0.950548f,-1.89781e-015f},{-0.50141f,0.86521f,1.51271e-017f}, +{-0.66887f,0.743379f,-4.24633e-016f},{-0.499433f,0.866353f,2.28059e-015f},{-0.670096f,0.742274f,-1.03447e-015f}, +{-0.808947f,0.587881f,-8.25877e-016f},{-0.809606f,0.586974f,1.78876e-015f},{-0.913543f,0.406743f,-1.13241e-015f}, +{-0.913862f,0.406026f,9.48088e-016f},{-0.978165f,0.20783f,-1.26731e-015f},{-0.978254f,0.207408f,1.76191e-016f}, +{0.308272f,0.951298f,-2.48625e-015f},{0.499433f,0.866353f,-4.54109e-015f},{0.310578f,0.950548f,2.45961e-015f}, +{0.66887f,0.743379f,3.77374e-015f},{0.670096f,0.742274f,2.01875e-015f},{0.808947f,0.587881f,1.64362e-015f}, +{0.913543f,0.406743f,-1.04713e-015f},{0.913862f,0.406026f,-1.19233e-015f},{0.105163f,0.994455f,-6.40462e-015f}, +{0.104013f,0.994576f,-1.27605e-015f},{-0.105163f,0.994455f,-3.83177e-015f},{-0.308272f,0.951298f,-3.06751e-015f}, +{-0.310578f,0.950548f,6.18026e-016f},{-0.50141f,0.86521f,8.60495e-016f},{-0.66887f,0.743379f,3.50643e-016f}, +{-0.499433f,0.866353f,-2.39364e-015f},{-0.670096f,0.742274f,2.21045e-015f},{-0.808947f,0.587881f,4.28049e-015f}, +{-0.809606f,0.586974f,3.82652e-017f},{-0.913543f,0.406743f,-1.05976e-015f},{-0.913862f,0.406026f,-7.14539e-016f}, +{-0.978165f,0.20783f,6.42838e-016f},{-0.978254f,0.207408f,2.38181e-016f},{0.308272f,0.951298f,3.71078e-015f}, +{0.310578f,0.950548f,2.39715e-015f},{0.50141f,0.86521f,2.18708e-015f},{0.66887f,0.743379f,5.38112e-017f}, +{0.670096f,0.742274f,5.39099e-017f},{0.808947f,0.587881f,-6.50806e-017f},{0.809606f,0.586974f,-1.31572e-015f}, +{0.978165f,0.20783f,9.12701e-016f},{0.978254f,0.207408f,-1.57403e-016f},{-2.9992e-017f,1.0f,4.35009e-018f}, +{0.307814f,0.951446f,8.09361e-016f},{-3.30053e-017f,1.0f,4.35009e-018f},{-0.587751f,0.809042f,-3.83595e-016f}, +{-0.309304f,0.950963f,-1.80891e-016f},{-0.588229f,0.808694f,-7.54388e-016f},{-0.307814f,0.951446f,1.83345e-017f}, +{-0.807656f,0.589654f,2.20949e-015f},{-0.952103f,0.305779f,4.58604e-015f},{-0.950842f,0.309676f,1.56814e-015f}, +{-0.811958f,0.583716f,-1.76798e-015f},{0.309304f,0.950963f,4.15271e-016f},{0.587751f,0.809042f,-2.12505e-018f}, +{0.588229f,0.808694f,1.51231e-015f},{0.811958f,0.583716f,6.63961e-019f},{0.807656f,0.589654f,-2.07933e-015f}, +{0.952103f,0.305779f,2.44947e-015f},{0.950842f,0.309676f,-2.44821e-015f},{-7.14668e-017f,1.0f,1.76219e-017f}, +{0.307814f,0.951446f,4.05503e-016f},{-7.63065e-017f,1.0f,1.76219e-017f},{-0.587751f,0.809042f,1.91069e-015f}, +{-0.309304f,0.950963f,-8.01418e-016f},{-0.588229f,0.808694f,2.00475e-016f},{-0.307814f,0.951446f,1.92778e-016f}, +{-0.807656f,0.589654f,1.55906e-015f},{-0.952103f,0.305779f,3.26471e-015f},{-0.950842f,0.309676f,7.07118e-016f}, +{-0.811958f,0.583716f,-1.04241e-015f},{0.309304f,0.950963f,8.97608e-018f},{0.587751f,0.809042f,7.59323e-016f}, +{0.588229f,0.808694f,-7.62656e-016f},{0.811958f,0.583716f,-2.08933e-015f},{0.807656f,0.589654f,2.08126e-015f}, +{0.952103f,0.305779f,1.03838e-019f},{0.950842f,0.309676f,2.44827e-015f},{1.0f,1.89478e-014f,0.0f}, +{0.0f,1.0f,1.28722e-015f},{0.307814f,0.951446f,-3.67724e-015f},{1.18424e-015f,1.0f,1.28722e-015f}, +{-0.587751f,0.809042f,2.57397e-016f},{-0.309304f,0.950963f,6.12825e-016f},{-0.588229f,0.808694f,-1.47886e-018f}, +{-0.307814f,0.951446f,2.45098e-015f},{-0.807656f,0.589654f,2.89271e-015f},{-0.952103f,0.305779f,-6.10308e-016f}, +{-0.950842f,0.309676f,-1.03589e-015f},{-0.811958f,0.583716f,9.97398e-016f},{0.309304f,0.950963f,0.0f}, +{0.587751f,0.809042f,4.16564e-015f},{0.588229f,0.808694f,5.91545e-018f},{0.811958f,0.583716f,1.63307e-017f}, +{0.807656f,0.589654f,-1.51802e-015f},{0.952103f,0.305779f,0.0f},{0.950842f,0.309676f,7.97239e-016f}, +{1.0f,-6.93889e-017f,0.0f},{0.0f,1.0f,-6.43608e-016f},{0.307814f,0.951446f,1.22162e-015f}, +{1.48864e-033f,1.0f,-6.43608e-016f},{-0.587751f,0.809042f,-5.23661e-016f},{-0.309304f,0.950963f,-1.22332e-015f}, +{-0.588229f,0.808694f,1.03948e-015f},{-0.307814f,0.951446f,-1.83553e-015f},{-0.807656f,0.589654f,5.20805e-016f}, +{-0.952103f,0.305779f,2.13798e-016f},{-0.950842f,0.309676f,8.91809e-016f},{-0.811958f,0.583716f,6.21714e-016f}, +{0.587751f,0.809042f,1.04141e-015f},{0.588229f,0.808694f,-1.03505e-015f},{0.811958f,0.583716f,1.51907e-015f}, +{0.807656f,0.589654f,1.51802e-015f},{0.950842f,0.309676f,-7.97239e-016f},{0.307814f,0.951446f,-3.79309e-016f}, +{-0.587751f,0.809042f,7.51249e-016f},{-0.309304f,0.950963f,-7.78103e-016f},{-0.588229f,0.808694f,2.7896e-018f}, +{-0.807656f,0.589654f,4.02884e-015f},{-0.952103f,0.305779f,-5.00781e-015f},{-1.0f,1.89478e-014f,0.0f}, +{-0.950842f,0.309676f,5.45e-016f},{-0.811958f,0.583716f,-7.88142e-016f},{-1.0f,1.06581e-014f,0.0f}, +{0.309304f,0.950963f,1.71297e-017f},{0.587751f,0.809042f,1.511e-015f},{0.588229f,0.808694f,-2.04514e-018f}, +{0.807656f,0.589654f,2.07918e-015f},{0.952103f,0.305779f,-2.45277e-015f},{0.950842f,0.309676f,2.44755e-015f}, +{0.0f,1.0f,-1.28722e-015f},{0.307814f,0.951446f,-3.09549e-018f},{-1.18424e-015f,1.0f,-1.28722e-015f}, +{-0.587751f,0.809042f,7.78103e-016f},{-0.309304f,0.950963f,-1.83536e-015f},{-0.588229f,0.808694f,1.55997e-015f}, +{-0.307814f,0.951446f,-1.22317e-015f},{-0.807656f,0.589654f,-2.70499e-015f},{-0.952103f,0.305779f,5.82801e-016f}, +{-0.950842f,0.309676f,6.707e-016f},{-0.811958f,0.583716f,-2.47768e-015f},{0.309304f,0.950963f,-2.44819e-015f}, +{0.587751f,0.809042f,0.0f},{0.588229f,0.808694f,-2.07601e-015f},{0.0f,1.0f,6.43608e-016f}, +{0.307814f,0.951446f,-4.90196e-015f},{-1.48864e-033f,1.0f,6.43608e-016f},{-0.588229f,0.808694f,-5.21961e-016f}, +{-0.307814f,0.951446f,3.06334e-015f},{-0.807656f,0.589654f,-5.22835e-016f},{-0.952103f,0.305779f,-1.18305e-016f}, +{-0.950842f,0.309676f,-6.59069e-016f},{-0.811958f,0.583716f,7.15635e-016f},{0.309304f,0.950963f,1.22409e-015f}, +{0.588229f,0.808694f,1.04688e-015f},{0.307814f,0.951446f,8.01726e-016f},{-0.587751f,0.809042f,-1.69861e-016f}, +{-0.309304f,0.950963f,1.93934e-016f},{-0.588229f,0.808694f,-1.31388e-015f},{-0.307814f,0.951446f,5.89001e-016f}, +{-0.807656f,0.589654f,-1.94968e-015f},{-0.952103f,0.305779f,3.28386e-015f},{-0.950842f,0.309676f,-1.06186e-015f}, +{-0.811958f,0.583716f,5.25337e-016f},{0.309304f,0.950963f,-3.89165e-016f},{0.587751f,0.809042f,-7.53802e-016f}, +{0.588229f,0.808694f,7.51699e-016f},{0.811958f,0.583716f,1.00283e-018f},{0.807656f,0.589654f,-2.07725e-015f}, +{0.950842f,0.309676f,3.9552e-019f},{1.0f,-1.89478e-014f,0.0f},{-0.761438f,0.648238f,2.94694e-016f}, +{-0.718339f,0.695693f,3.39459e-016f},{-0.718357f,0.695675f,-3.39456e-016f},{0.0960133f,0.99538f,-2.46936e-016f}, +{0.0320605f,0.999486f,-9.42991e-016f},{0.0960396f,0.995378f,3.20316e-016f},{-0.032044f,0.999486f,-4.9277e-016f}, +{0.032044f,0.999486f,6.25231e-016f},{0.159589f,0.987184f,8.58394e-016f},{0.15962f,0.987179f,1.45997e-016f}, +{0.22251f,0.974931f,-4.52703e-016f},{0.222542f,0.974923f,-7.64298e-016f},{0.284517f,0.958671f,-4.25434e-016f}, +{0.284548f,0.958662f,-2.51271e-016f},{0.345353f,0.938473f,-6.8736e-016f},{0.518376f,0.855153f,5.08747e-016f}, +{0.462522f,0.886608f,-1.07923e-015f},{0.462558f,0.886589f,2.04673e-016f},{0.345385f,0.938461f,-1.21586e-015f}, +{0.404803f,0.914404f,-3.09674e-016f},{0.404769f,0.914419f,1.8029e-016f},{0.572101f,0.820183f,6.61372e-016f}, +{0.518412f,0.855131f,-5.92076e-016f},{0.572134f,0.82016f,-4.37334e-016f},{0.623475f,0.781843f,1.31467e-016f}, +{0.672313f,0.740267f,1.23799e-015f},{0.672288f,0.740289f,-8.27861e-016f},{0.623505f,0.781819f,8.6137e-016f}, +{0.718339f,0.695693f,-8.99733e-016f},{0.718357f,0.695675f,-5.67888e-016f},{0.761438f,0.648238f,-1.33697e-016f}, +{0.761447f,0.648227f,2.16584e-016f},{0.801409f,0.598117f,-3.98106e-016f},{0.801406f,0.598121f,2.48774e-016f}, +{0.981554f,0.191184f,4.00667e-016f},{0.967317f,0.25357f,-1.85681e-016f},{0.981559f,0.191157f,-7.78912e-016f}, +{0.871315f,0.490723f,-1.02521e-015f},{0.90096f,0.433902f,2.05671e-017f},{0.871302f,0.490747f,-7.5201e-016f}, +{0.838075f,0.545555f,3.05312e-016f},{0.838084f,0.545542f,1.28783e-015f},{0.900965f,0.433892f,-3.31874e-016f}, +{0.926902f,0.375304f,-2.89443e-016f},{0.926953f,0.375176f,3.48902e-016f},{0.949042f,0.315149f,7.91723e-016f}, +{0.94917f,0.314763f,1.83311e-017f},{0.967287f,0.253683f,-1.2494e-015f},{0.991791f,0.12787f,1.80602e-016f}, +{0.997946f,0.0640673f,-2.96278e-017f},{0.997945f,0.0640792f,-1.66986e-016f},{0.991787f,0.127897f,-1.01412e-015f}, +{1.0f,-1.4803e-017f,0.0f},{-0.0320605f,0.999486f,-2.5793e-018f},{-0.0960397f,0.995377f,3.1259e-016f}, +{-0.0960134f,0.99538f,7.93068e-016f},{-0.159589f,0.987184f,3.0484e-016f},{-0.15962f,0.987179f,1.05577e-015f}, +{-0.222542f,0.974923f,-1.16968e-015f},{-0.22251f,0.97493f,-9.5911e-016f},{-0.284548f,0.958662f,-3.77177e-016f}, +{-0.284517f,0.958671f,3.77173e-016f},{-0.345353f,0.938473f,3.02004e-016f},{-0.345385f,0.938461f,-7.97082e-017f}, +{-0.404803f,0.914404f,0.0f},{-0.404769f,0.914419f,6.53655e-016f},{-0.462558f,0.886589f,2.10881e-016f}, +{-0.462522f,0.886608f,-5.70627e-016f},{-0.518376f,0.855153f,-2.33487e-016f},{-0.518412f,0.855131f,3.58598e-016f}, +{-0.572134f,0.82016f,2.17902e-016f},{-0.572101f,0.820183f,-1.38078e-016f},{-0.623505f,0.781819f,-3.02538e-016f}, +{-0.623476f,0.781843f,-2.516e-016f},{-0.672288f,0.740289f,1.06108e-015f},{-0.672313f,0.740267f,-5.84618e-016f}, +{-0.761447f,0.648227f,2.94685e-016f},{-0.801409f,0.598117f,-6.42849e-016f},{-0.801406f,0.598121f,6.353e-017f}, +{-0.838075f,0.545555f,2.16275e-016f},{-0.838084f,0.545542f,-4.07081e-017f},{-0.871315f,0.490723f,1.40196e-016f}, +{-0.871302f,0.490747f,4.56042e-016f},{-0.900965f,0.433892f,1.44967e-016f},{-0.90096f,0.433902f,1.44966e-016f}, +{-0.926902f,0.375304f,9.24079e-017f},{-0.926953f,0.375176f,0.0f},{-0.94917f,0.314763f,2.02584e-016f}, +{-0.949042f,0.315149f,2.02832e-016f},{-0.967317f,0.25357f,0.0f},{-0.967287f,0.253683f,-1.63272e-016f}, +{-0.981554f,0.191184f,0.0f},{-0.981559f,0.191157f,0.0f},{-0.991791f,0.12787f,0.0f}, +{-0.991787f,0.127897f,0.0f},{-0.997946f,0.0640673f,0.0f},{-0.997945f,0.0640791f,-2.01813e-016f}, +{-1.0f,5.92119e-017f,0.0f},{-0.761438f,0.648238f,-1.22517e-016f},{-0.718339f,0.695693f,1.08295e-016f}, +{-0.718357f,0.695675f,2.3117e-016f},{0.0960133f,0.99538f,5.02084e-017f},{0.0320605f,0.999486f,-7.73789e-018f}, +{0.0960396f,0.995378f,6.56751e-017f},{-0.032044f,0.999486f,0.0f},{0.032044f,0.999486f,-7.73392e-018f}, +{0.159589f,0.987184f,1.97357e-016f},{0.15962f,0.987179f,1.28416e-017f},{0.22251f,0.974931f,1.50038e-016f}, +{0.222542f,0.974923f,-1.56867e-016f},{0.284517f,0.958671f,1.54252e-016f},{0.284548f,0.958662f,-7.46707e-017f}, +{0.345353f,0.938473f,2.7603e-016f},{0.518376f,0.855153f,-1.14686e-016f},{0.462522f,0.886608f,-2.41867e-016f}, +{0.462558f,0.886589f,-1.76763e-016f},{0.345385f,0.938461f,2.28326e-016f},{0.404803f,0.914404f,-2.28546e-016f}, +{0.404769f,0.914419f,5.6987e-017f},{0.572101f,0.820183f,-2.07117e-016f},{0.518412f,0.855131f,2.98183e-016f}, +{0.572134f,0.82016f,2.07129e-016f},{0.623475f,0.781843f,3.69924e-016f},{0.672313f,0.740267f,2.31169e-016f}, +{0.672288f,0.740289f,5.2187e-016f},{0.623505f,0.781819f,6.95605e-017f},{0.718339f,0.695693f,-4.01349e-016f}, +{0.718357f,0.695675f,3.64397e-016f},{0.761438f,0.648238f,1.44968e-016f},{0.761447f,0.648227f,4.58818e-016f}, +{0.801409f,0.598117f,-2.05097e-016f},{0.801406f,0.598121f,-6.80769e-016f},{0.981554f,0.191184f,1.41704e-015f}, +{0.967317f,0.25357f,3.82454e-016f},{0.981559f,0.191157f,-1.05674e-015f},{0.871315f,0.490723f,-9.36431e-016f}, +{0.90096f,0.433902f,4.48018e-017f},{0.871302f,0.490747f,-3.7096e-016f},{0.838075f,0.545555f,3.69875e-016f}, +{0.838084f,0.545542f,1.37433e-015f},{0.900965f,0.433892f,-3.75604e-016f},{0.926902f,0.375304f,-3.03308e-017f}, +{0.926953f,0.375176f,3.109e-016f},{0.949042f,0.315149f,-4.05339e-016f},{0.94917f,0.314763f,-5.01206e-016f}, +{0.967287f,0.253683f,-2.42347e-016f},{0.991791f,0.12787f,-1.89542e-017f},{0.997946f,0.0640673f,-1.23846e-016f}, +{0.997945f,0.0640792f,-2.32866e-016f},{0.991787f,0.127897f,-1.33263e-017f},{-0.0320605f,0.999486f,-1.28965e-018f}, +{-0.0960397f,0.995377f,5.40854e-017f},{-0.0960134f,0.99538f,0.0f},{-0.159589f,0.987184f,-2.56782e-017f}, +{-0.15962f,0.987179f,2.56832e-017f},{-0.222542f,0.974923f,-1.56867e-016f},{-0.22251f,0.97493f,-1.38967e-016f}, +{-0.284548f,0.958662f,-6.86764e-017f},{-0.284517f,0.958671f,2.28896e-017f},{-0.345353f,0.938473f,3.57572e-016f}, +{-0.345385f,0.938461f,-5.5573e-017f},{-0.404803f,0.914404f,6.51336e-017f},{-0.404769f,0.914419f,1.6282e-016f}, +{-0.462558f,0.886589f,3.72132e-017f},{-0.462522f,0.886608f,7.44207e-017f},{-0.518376f,0.855153f,2.33487e-016f}, +{-0.518412f,0.855131f,1.08358e-016f},{-0.572134f,0.82016f,-1.38086e-016f},{-0.572101f,0.820183f,2.63938e-016f}, +{-0.623505f,0.781819f,-2.00646e-016f},{-0.623476f,0.781843f,0.0f},{-0.672288f,0.740289f,0.0f}, +{-0.672313f,0.740267f,1.08176e-016f},{-0.761447f,0.648227f,0.0f},{-0.801409f,0.598117f,0.0f}, +{-0.801406f,0.598121f,-1.28948e-016f},{-0.838075f,0.545555f,-1.34848e-016f},{-0.838084f,0.545542f,0.0f}, +{-0.871315f,0.490723f,0.0f},{-0.900965f,0.433892f,0.0f},{-0.90096f,0.433902f,-1.34297e-016f}, +{-0.926902f,0.375304f,-1.4914e-016f},{-0.926953f,0.375176f,2.98297e-016f},{-0.94917f,0.314763f,0.0f}, +{-0.949042f,0.315149f,0.0f},{-0.967317f,0.25357f,-1.55643e-016f},{-0.967287f,0.253683f,7.63412e-018f}, +{-0.981554f,0.191184f,1.57934e-016f},{-0.981559f,0.191157f,1.2303e-016f},{-0.991787f,0.127897f,2.41896e-016f}, +{-0.997945f,0.0640791f,-1.60571e-016f},{-0.761438f,0.648238f,0.0f},{-0.718339f,0.695693f,2.23877e-016f}, +{-0.718357f,0.695675f,-4.47741e-016f},{0.0960133f,0.99538f,3.51215e-016f},{0.0320605f,0.999486f,3.42273e-016f}, +{-0.032044f,0.999486f,-4.72146e-016f},{0.032044f,0.999486f,1.27624e-015f},{0.159589f,0.987184f,7.94198e-016f}, +{0.15962f,0.987179f,-5.022e-016f},{0.22251f,0.974931f,-3.78511e-016f},{0.222542f,0.974923f,5.9166e-016f}, +{0.284517f,0.958671f,3.08504e-016f},{0.284548f,0.958662f,8.02594e-016f},{0.345353f,0.938473f,-7.5501e-016f}, +{0.518376f,0.855153f,-8.32879e-016f},{0.462522f,0.886608f,-5.02391e-016f},{0.462558f,0.886589f,6.82274e-017f}, +{0.345385f,0.938461f,-1.39465e-015f},{0.404803f,0.914404f,2.03832e-016f},{0.404769f,0.914419f,-8.20038e-017f}, +{0.572101f,0.820183f,-1.06879e-015f},{0.518412f,0.855131f,6.78507e-016f},{0.572134f,0.82016f,6.60622e-016f}, +{0.623475f,0.781843f,9.80918e-016f},{0.672313f,0.740267f,2.57355e-016f},{0.672288f,0.740289f,-2.9505e-016f}, +{0.623505f,0.781819f,4.08838e-016f},{0.718339f,0.695693f,-1.96803e-016f},{0.718357f,0.695675f,2.10791e-016f}, +{0.761438f,0.648238f,-4.65431e-016f},{0.761447f,0.648227f,-3.46836e-016f},{0.801409f,0.598117f,3.19296e-016f}, +{0.801406f,0.598121f,2.0836e-016f},{0.981554f,0.191184f,-1.63198e-016f},{0.967317f,0.25357f,1.39352e-016f}, +{0.981559f,0.191157f,1.09203e-016f},{0.871315f,0.490723f,2.84009e-016f},{0.90096f,0.433902f,9.59966e-017f}, +{0.871302f,0.490747f,0.0f},{0.838075f,0.545555f,-2.20643e-016f},{0.838084f,0.545542f,3.61373e-016f}, +{0.900965f,0.433892f,-1.38293e-016f},{0.926902f,0.375304f,-1.28524e-016f},{0.926953f,0.375176f,1.80871e-017f}, +{0.949042f,0.315149f,6.82655e-017f},{0.94917f,0.314763f,1.30547e-016f},{0.967287f,0.253683f,1.42883e-016f}, +{0.991791f,0.12787f,4.92136e-017f},{0.997946f,0.0640673f,-3.34814e-017f},{0.997945f,0.0640792f,-3.21075e-017f}, +{0.991787f,0.127897f,-4.36713e-017f},{1.0f,-1.18424e-016f,0.0f},{1.0f,-1.22125e-016f,0.0f}, +{-0.0320605f,0.999486f,6.63911e-016f},{-0.0960397f,0.995377f,-2.58504e-016f},{-0.0960134f,0.99538f,8.3169e-016f}, +{-0.159589f,0.987184f,9.53038e-016f},{-0.15962f,0.987179f,3.17678e-016f},{-0.222542f,0.974923f,-8.69587e-016f}, +{-0.22251f,0.97493f,3.99e-016f},{-0.284548f,0.958662f,-7.08571e-016f},{-0.284517f,0.958671f,1.83117e-016f}, +{-0.345353f,0.938473f,4.92873e-016f},{-0.345385f,0.938461f,-4.13146e-016f},{-0.404803f,0.914404f,1.30267e-016f}, +{-0.404769f,0.914419f,-2.60512e-016f},{-0.462558f,0.886589f,-1.23983e-017f},{-0.462522f,0.886608f,2.72945e-016f}, +{-0.518376f,0.855153f,5.50383e-016f},{-0.518412f,0.855131f,0.0f},{-0.572134f,0.82016f,-5.27861e-016f}, +{-0.572101f,0.820183f,-3.68209e-016f},{-0.623505f,0.781819f,-1.15607e-015f},{-0.623476f,0.781843f,9.04474e-016f}, +{-0.672288f,0.740289f,4.3269e-016f},{-0.672313f,0.740267f,-1.38559e-015f},{-0.761447f,0.648227f,4.90073e-016f}, +{-0.801409f,0.598117f,-7.08269e-016f},{-0.801406f,0.598121f,5.15791e-016f},{-0.838075f,0.545555f,1.42991e-015f}, +{-0.838084f,0.545542f,5.39397e-016f},{-0.871315f,0.490723f,1.4374e-015f},{-0.871302f,0.490747f,8.05705e-016f}, +{-0.900965f,0.433892f,2.79256e-016f},{-0.90096f,0.433902f,-2.79263e-016f},{-0.926902f,0.375304f,-1.19312e-015f}, +{-0.94917f,0.314763f,-6.10893e-016f},{-0.949042f,0.315149f,6.10811e-016f},{-0.981559f,0.191157f,1.26348e-015f}, +{-0.991791f,0.12787f,-1.27665e-015f},{-0.997946f,0.0640673f,-4.12342e-017f},{-0.997945f,0.0640791f,0.0f}, +{-1.0f,2.96059e-017f,0.0f},{-0.761438f,0.648238f,6.98673e-016f},{-0.718339f,0.695693f,2.38452e-016f}, +{-0.718357f,0.695675f,2.23871e-016f},{0.0960133f,0.99538f,9.26924e-017f},{0.0320605f,0.999486f,0.0f}, +{0.0960396f,0.995378f,-1.60158e-016f},{-0.032044f,0.999486f,1.81443e-016f},{0.032044f,0.999486f,1.03119e-017f}, +{0.159589f,0.987184f,-1.02713e-016f},{0.15962f,0.987179f,5.13664e-017f},{0.22251f,0.974931f,-3.58022e-017f}, +{0.222542f,0.974923f,-1.14241e-016f},{0.284517f,0.958671f,7.7126e-017f},{0.284548f,0.958662f,-2.31376e-016f}, +{0.345353f,0.938473f,-1.99332e-017f},{0.518376f,0.855153f,1.59511e-016f},{0.462522f,0.886608f,-7.44207e-017f}, +{0.462558f,0.886589f,7.44265e-017f},{0.345385f,0.938461f,1.31073e-016f},{0.404803f,0.914404f,-2.03832e-016f}, +{0.404769f,0.914419f,3.42516e-016f},{0.572101f,0.820183f,0.0f},{0.518412f,0.855131f,1.37592e-016f}, +{0.572134f,0.82016f,-9.20575e-017f},{0.623475f,0.781843f,2.70309e-016f},{0.672313f,0.740267f,1.21844e-016f}, +{0.672288f,0.740289f,4.072e-017f},{0.623505f,0.781819f,-2.46886e-017f},{0.718339f,0.695693f,5.59692e-017f}, +{0.718357f,0.695675f,-1.58167e-017f},{0.761438f,0.648238f,9.58184e-017f},{0.761447f,0.648227f,0.0f}, +{0.801409f,0.598117f,-1.73215e-016f},{0.801406f,0.598121f,-4.04141e-017f},{0.981554f,0.191184f,-1.63905e-016f}, +{0.967317f,0.25357f,-7.6878e-017f},{0.981559f,0.191157f,5.28888e-017f},{0.871315f,0.490723f,1.89545e-016f}, +{0.90096f,0.433902f,2.2772e-016f},{0.871302f,0.490747f,-3.40821e-016f},{0.838075f,0.545555f,-1.33657e-016f}, +{0.838084f,0.545542f,-1.67369e-016f},{0.900965f,0.433892f,2.95425e-017f},{0.926902f,0.375304f,4.04643e-016f}, +{0.926953f,0.375176f,-1.73096e-017f},{0.949042f,0.315149f,7.36158e-017f},{0.94917f,0.314763f,-7.22027e-018f}, +{0.967287f,0.253683f,-1.19283e-019f},{0.991791f,0.12787f,8.57703e-019f},{0.997946f,0.0640673f,-5.42011e-017f}, +{0.997945f,0.0640792f,-2.44892e-017f},{0.991787f,0.127897f,-1.77286e-016f},{1.0f,-1.59132e-016f,0.0f}, +{-0.0320605f,0.999486f,0.0f},{-0.0960397f,0.995377f,0.0f},{-0.159589f,0.987184f,-1.02713e-016f}, +{-0.15962f,0.987179f,2.10205e-016f},{-0.222542f,0.974923f,-7.16149e-017f},{-0.22251f,0.97493f,7.16044e-017f}, +{-0.284548f,0.958662f,-3.08501e-016f},{-0.284517f,0.958671f,-9.15586e-017f},{-0.345353f,0.938473f,0.0f}, +{-0.345385f,0.938461f,0.0f},{-0.404769f,0.914419f,0.0f},{-0.462522f,0.886608f,0.0f}, +{-0.518376f,0.855153f,-5.84395e-017f},{-0.518412f,0.855131f,-3.33654e-016f},{-0.572134f,0.82016f,0.0f}, +{-0.623505f,0.781819f,-6.52885e-016f},{-0.672288f,0.740289f,8.6538e-016f},{-0.672313f,0.740267f,-2.38221e-016f}, +{-0.761447f,0.648227f,1.18875e-015f},{-0.801409f,0.598117f,-1.54738e-015f},{-0.801406f,0.598121f,-5.15791e-016f}, +{-0.838075f,0.545555f,3.6383e-016f},{-0.871315f,0.490723f,1.12157e-015f},{-0.871302f,0.490747f,1.12155e-015f}, +{-0.900965f,0.433892f,5.79868e-016f},{-0.90096f,0.433902f,-5.79865e-016f},{-0.926902f,0.375304f,0.0f}, +{-0.926953f,0.375176f,-5.96594e-016f},{-0.94917f,0.314763f,6.10893e-016f},{-0.967317f,0.25357f,-1.40834e-015f}, +{-0.967287f,0.253683f,1.63272e-016f},{-0.981559f,0.191157f,1.38651e-015f},{-0.991791f,0.12787f,-1.19435e-015f}, +{-0.991787f,0.127897f,8.23157e-017f},{-1.0f,1.4803e-017f,0.0f},{-0.104013f,0.994576f,3.5353e-016f}, +{0.105163f,0.994455f,-6.06197e-016f},{0.104013f,0.994576f,-5.89909e-016f},{-0.105163f,0.994455f,9.60058e-016f}, +{-0.308272f,0.951298f,4.26112e-018f},{-0.310578f,0.950548f,-4.99725e-017f},{-0.50141f,0.86521f,-3.27865e-016f}, +{-0.66887f,0.743379f,-5.14273e-016f},{-0.499433f,0.866353f,9.45034e-016f},{-0.670096f,0.742274f,-6.85702e-016f}, +{-0.808947f,0.587881f,-3.17829e-016f},{-0.809606f,0.586974f,-1.49813e-016f},{-0.913543f,0.406743f,4.89574e-016f}, +{-0.913862f,0.406026f,-3.27139e-016f},{-0.978165f,0.20783f,4.59595e-016f},{-0.978254f,0.207408f,2.95231e-016f}, +{-1.0f,-1.33227e-015f,0.0f},{0.499433f,0.866353f,-5.57591e-016f},{0.310578f,0.950548f,0.0f}, +{0.50141f,0.86521f,-1.61356e-016f},{0.66887f,0.743379f,-9.56889e-016f},{0.670096f,0.742274f,-6.93373e-016f}, +{0.808947f,0.587881f,-1.18042e-016f},{0.913543f,0.406743f,5.23566e-016f},{0.809606f,0.586974f,4.03822e-016f}, +{0.913862f,0.406026f,2.94084e-016f},{1.0f,1.18424e-015f,0.0f},{-0.104013f,0.994576f,3.36794e-016f}, +{0.105163f,0.994455f,-6.5696e-016f},{0.104013f,0.994576f,-6.56853e-016f},{-0.105163f,0.994455f,8.92374e-016f}, +{-0.308272f,0.951298f,2.27468e-016f},{-0.310578f,0.950548f,2.49863e-017f},{-0.50141f,0.86521f,-4.69051e-016f}, +{-0.499433f,0.866353f,9.65124e-016f},{-0.670096f,0.742274f,-7.26134e-016f},{-0.808947f,0.587881f,-9.00466e-017f}, +{-0.809606f,0.586974f,-5.2113e-017f},{-0.913543f,0.406743f,4.25266e-016f},{-0.913862f,0.406026f,-5.24727e-016f}, +{-0.978165f,0.20783f,6.42805e-016f},{-0.978254f,0.207408f,9.93815e-018f},{-1.0f,1.25825e-015f,0.0f}, +{0.308272f,0.951298f,-9.9203e-017f},{0.310578f,0.950548f,-9.99451e-017f},{0.809606f,0.586974f,-3.77781e-016f}, +{0.913862f,0.406026f,5.88168e-016f},{0.978254f,0.207408f,-6.29612e-016f},{1.0f,-1.18424e-015f,0.0f}, +{-0.104013f,0.994576f,9.93647e-016f},{0.105163f,0.994455f,1.31392e-015f},{0.104013f,0.994576f,5.02078e-017f}, +{-0.105163f,0.994455f,3.20019e-016f},{-0.308272f,0.951298f,-6.08002e-016f},{-0.50141f,0.86521f,5.07418e-016f}, +{-0.66887f,0.743379f,-6.33884e-016f},{-0.499433f,0.866353f,-4.48944e-016f},{-0.670096f,0.742274f,-8.85355e-017f}, +{-0.808947f,0.587881f,3.44309e-016f},{-0.809606f,0.586974f,7.94639e-016f},{-0.913543f,0.406743f,3.42322e-016f}, +{-0.913862f,0.406026f,3.83328e-016f},{-0.978165f,0.20783f,5.54168e-016f},{-0.978254f,0.207408f,1.60699e-016f}, +{0.308272f,0.951298f,1.22453e-015f},{0.499433f,0.866353f,5.57591e-016f},{0.310578f,0.950548f,-1.22356e-015f}, +{0.66887f,0.743379f,4.78444e-016f},{0.670096f,0.742274f,-2.1564e-016f},{0.913543f,0.406743f,-5.23566e-016f}, +{0.809606f,0.586974f,1.15938e-015f},{-0.104013f,0.994576f,9.76911e-016f},{0.105163f,0.994455f,1.26316e-015f}, +{0.104013f,0.994576f,-1.67359e-017f},{-0.105163f,0.994455f,2.52336e-016f},{-0.308272f,0.951298f,-3.84795e-016f}, +{-0.50141f,0.86521f,3.66232e-016f},{-0.499433f,0.866353f,-4.28854e-016f},{-0.670096f,0.742274f,-1.28968e-016f}, +{-0.808947f,0.587881f,5.72092e-016f},{-0.809606f,0.586974f,8.92339e-016f},{-0.913543f,0.406743f,2.78013e-016f}, +{-0.913862f,0.406026f,1.85741e-016f},{-0.978165f,0.20783f,7.37379e-016f},{-0.978254f,0.207408f,-1.24594e-016f}, +{0.308272f,0.951298f,1.12532e-015f},{0.310578f,0.950548f,-1.3235e-015f},{0.809606f,0.586974f,3.77781e-016f}, +{-0.104013f,0.994576f,9.26703e-016f},{0.105163f,0.994455f,1.17855e-015f},{0.104013f,0.994576f,-3.34719e-017f}, +{-0.105163f,0.994455f,3.87703e-016f},{-0.308272f,0.951298f,-3.10392e-016f},{-0.310578f,0.950548f,2.49863e-016f}, +{-0.50141f,0.86521f,7.29282e-016f},{-0.66887f,0.743379f,1.18511e-017f},{-0.499433f,0.866353f,-3.48494e-016f}, +{-0.670096f,0.742274f,-1.02013e-016f},{-0.808947f,0.587881f,1.97878e-016f},{-0.809606f,0.586974f,1.21801e-015f}, +{-0.913543f,0.406743f,2.04518e-016f},{-0.913862f,0.406026f,5.70787e-017f},{-0.978165f,0.20783f,8.92923e-016f}, +{-0.978254f,0.207408f,-6.1033e-016f},{-1.0f,2.51651e-015f,0.0f},{0.308272f,0.951298f,1.02612e-015f}, +{0.50141f,0.86521f,3.22711e-016f},{0.670096f,0.742274f,-4.31279e-016f},{0.808947f,0.587881f,-8.99009e-016f}, +{0.978254f,0.207408f,-1.25922e-015f},{0.104013f,0.994576f,1.33888e-016f},{-0.308272f,0.951298f,-7.56806e-016f}, +{-0.310578f,0.950548f,4.99725e-017f},{-0.50141f,0.86521f,5.27588e-016f},{-0.66887f,0.743379f,-1.11819e-015f}, +{-0.499433f,0.866353f,-3.88674e-016f},{-0.670096f,0.742274f,-6.41112e-016f},{-0.808947f,0.587881f,-7.94601e-016f}, +{-0.809606f,0.586974f,1.00632e-015f},{-0.913543f,0.406743f,7.28172e-016f},{-0.913862f,0.406026f,8.29049e-016f}, +{-0.978165f,0.20783f,2.91649e-016f},{-0.978254f,0.207408f,-5.20414e-017f},{-1.0f,-2.66454e-015f,0.0f}, +{0.499433f,0.866353f,8.7903e-016f},{0.310578f,0.950548f,-1.12361e-015f},{0.50141f,0.86521f,0.0f}, +{0.670096f,0.742274f,0.0f},{0.809606f,0.586974f,1.41992e-015f},{0.104013f,0.994576f,-5.06229e-016f}, +{-0.105163f,0.994455f,1.02774e-015f},{-0.308272f,0.951298f,-1.44543e-016f},{-0.50141f,0.86521f,-3.07696e-016f}, +{-0.66887f,0.743379f,-9.98574e-016f},{-0.499433f,0.866353f,1.0053e-015f},{-0.670096f,0.742274f,-1.23828e-015f}, +{-0.808947f,0.587881f,-1.45674e-015f},{-0.809606f,0.586974f,6.18708e-017f},{-0.913543f,0.406743f,8.75425e-016f}, +{-0.913862f,0.406026f,1.18582e-016f},{-0.978165f,0.20783f,1.97076e-016f},{-0.978254f,0.207408f,8.24911e-017f}, +{0.499433f,0.866353f,-2.36152e-016f},{0.310578f,0.950548f,9.99451e-017f},{0.670096f,0.742274f,-4.77733e-016f}, +{0.809606f,0.586974f,6.64356e-016f},{0.105163f,0.994455f,-7.07722e-016f},{0.104013f,0.994576f,-7.40532e-016f}, +{-0.308272f,0.951298f,3.0187e-016f},{-0.310578f,0.950548f,9.99451e-017f},{-0.50141f,0.86521f,-1.4634e-016f}, +{-0.66887f,0.743379f,-2.72122e-016f},{-0.499433f,0.866353f,1.16602e-015f},{-0.670096f,0.742274f,-6.4527e-016f}, +{-0.808947f,0.587881f,-4.8053e-016f},{-0.809606f,0.586974f,-2.8008e-016f},{-0.913543f,0.406743f,6.18191e-016f}, +{-0.913862f,0.406026f,-5.15537e-016f},{-0.978165f,0.20783f,-3.56243e-016f},{-0.978254f,0.207408f,9.60179e-017f}, +{-1.0f,2.66454e-015f,0.0f},{0.308272f,0.951298f,9.9203e-017f},{0.310578f,0.950548f,-2.99835e-016f}, +{0.66887f,0.743379f,-1.38738e-015f},{0.670096f,0.742274f,-4.64542e-017f},{0.808947f,0.587881f,6.62925e-016f}, +{0.913543f,0.406743f,-6.43974e-017f},{0.809606f,0.586974f,-8.98849e-016f},{0.978165f,0.20783f,1.25911e-015f}, +{0.826318f,-0.563203f,2.17827e-015f},{0.642788f,-0.766044f,-8.27406e-016f},{0.411158f,-0.911564f,-1.4099e-015f}, +{0.158603f,-0.987342f,-1.62037e-016f},{0.944801f,-0.327644f,1.31796e-017f},{-0.911564f,0.411158f,2.34469e-015f}, +{-0.766044f,0.642788f,-2.74725e-017f},{-0.563203f,0.826318f,-5.49955e-016f},{-0.327644f,0.944801f,-2.4991e-016f}, +{-0.987342f,0.158603f,2.54184e-015f},{0.0746326f,0.997211f,-2.34456e-017f},{-0.074795f,0.997199f,-5.19989e-016f}, +{-0.0746326f,0.997211f,2.89595e-016f},{0.222381f,0.97496f,-5.69819e-016f},{0.074795f,0.997199f,1.28888e-016f}, +{0.222585f,0.974913f,-9.61018e-016f},{0.365177f,0.930938f,7.43247e-016f},{0.365379f,0.930859f,1.64673e-015f}, +{0.49999f,0.866031f,-6.16426e-016f},{0.499833f,0.866122f,1.18802e-015f},{0.623256f,0.782018f,-4.36855e-016f}, +{0.82663f,0.562746f,-2.05696e-015f},{0.900794f,0.434246f,-2.67821e-015f},{0.826061f,0.563581f,3.78148e-015f}, +{0.623488f,0.781833f,2.4348e-015f},{0.732917f,0.680318f,-3.91184e-015f},{0.733034f,0.680192f,-2.46978e-015f}, +{0.901683f,0.432397f,-1.33326e-016f},{0.955502f,0.294984f,9.24071e-016f},{0.955572f,0.294759f,-1.22029e-015f}, +{0.988846f,0.148938f,2.44716e-015f},{0.988818f,0.149126f,-1.41507e-015f},{-0.222381f,0.97496f,-5.76348e-016f}, +{-0.365177f,0.930938f,3.67387e-017f},{-0.222585f,0.974913f,-4.28956e-017f},{-0.365379f,0.930859f,7.43524e-017f}, +{-0.499834f,0.866121f,1.2601e-015f},{-0.499989f,0.866031f,-1.2789e-015f},{-0.623256f,0.782018f,-1.648e-015f}, +{-0.732917f,0.680318f,3.01013e-017f},{-0.623488f,0.781833f,-3.28495e-015f},{-0.733034f,0.680192f,-1.85694e-015f}, +{-0.826061f,0.563581f,-2.135e-015f},{-0.82663f,0.562746f,-4.26401e-015f},{-0.900794f,0.434246f,2.32224e-015f}, +{-0.955502f,0.294984f,2.79226e-018f},{-0.901683f,0.432397f,-1.33512e-017f},{-0.955572f,0.294759f,-3.07218e-018f}, +{-0.988818f,0.149126f,8.60722e-020f},{-0.988846f,0.148938f,1.12747e-019f},{0.0746326f,0.997211f,2.56725e-015f}, +{-0.074795f,0.997199f,-1.28361e-015f},{-0.0746326f,0.997211f,3.84937e-015f},{0.222381f,0.97496f,-6.27044e-015f}, +{0.074795f,0.997199f,-1.28211e-015f},{0.222585f,0.974913f,-1.87791e-015f},{0.365177f,0.930938f,-1.10171e-017f}, +{0.365379f,0.930859f,-2.40011e-015f},{0.49999f,0.866031f,-3.0455e-015f},{0.499833f,0.866122f,2.50346e-015f}, +{0.623256f,0.782018f,-7.54969e-016f},{0.82663f,0.562746f,1.35373e-016f},{0.900794f,0.434246f,8.30693e-016f}, +{0.826061f,0.563581f,-3.70334e-017f},{0.623488f,0.781833f,7.8614e-016f},{0.732917f,0.680318f,0.0f}, +{0.733034f,0.680192f,-9.83866e-017f},{0.901683f,0.432397f,-2.82436e-016f},{0.955502f,0.294984f,-5.75977e-016f}, +{0.955572f,0.294759f,6.52881e-016f},{0.988846f,0.148938f,8.2274e-016f},{0.988818f,0.149126f,1.39061e-016f}, +{-0.222381f,0.97496f,-2.50997e-015f},{-0.365177f,0.930938f,4.80796e-015f},{-0.222585f,0.974913f,3.76477e-015f}, +{-0.365379f,0.930859f,2.39643e-015f},{-0.499834f,0.866121f,-2.22977e-015f},{-0.623256f,0.782018f,0.0f}, +{-0.732917f,0.680318f,-2.94819e-017f},{-0.623488f,0.781833f,-6.0634e-015f},{-0.733034f,0.680192f,-2.94867e-017f}, +{-0.826061f,0.563581f,2.9018e-015f},{-0.82663f,0.562746f,2.831e-015f},{-0.900794f,0.434246f,7.24697e-017f}, +{-0.955502f,0.294984f,-7.68711e-017f},{-0.901683f,0.432397f,-1.11318e-015f},{-0.955572f,0.294759f,0.0f}, +{-0.988818f,0.149126f,-7.67832e-016f},{-0.988846f,0.148938f,-7.95536e-017f},{0.0746326f,0.997211f,7.26226e-017f}, +{-0.074795f,0.997199f,-3.86026e-017f},{-0.0746326f,0.997211f,1.39011e-018f},{0.222381f,0.97496f,-2.83567e-016f}, +{0.074795f,0.997199f,-1.59944e-016f},{0.222585f,0.974913f,4.17819e-017f},{0.365177f,0.930938f,-1.96876e-016f}, +{0.365379f,0.930859f,-1.1752e-015f},{0.49999f,0.866031f,1.15346e-015f},{0.499833f,0.866122f,-2.59619e-016f}, +{0.623256f,0.782018f,-2.04138e-015f},{0.82663f,0.562746f,6.03166e-016f},{0.900794f,0.434246f,5.46692e-016f}, +{0.826061f,0.563581f,-1.66803e-015f},{0.623488f,0.781833f,1.23095e-015f},{0.732917f,0.680318f,9.23191e-016f}, +{0.733034f,0.680192f,-2.70567e-015f},{0.901683f,0.432397f,-2.81735e-015f},{0.955502f,0.294984f,3.82595e-015f}, +{0.955572f,0.294759f,5.47878e-016f},{0.988846f,0.148938f,-6.9894e-016f},{0.988818f,0.149126f,-2.60585e-015f}, +{-0.222381f,0.97496f,-2.90095e-016f},{-0.222585f,0.974913f,2.43619e-016f},{-0.499989f,0.866031f,1.29548e-015f}, +{-0.623256f,0.782018f,-3.25253e-015f},{-0.732917f,0.680318f,-1.85674e-015f},{-0.623488f,0.781833f,-1.67982e-015f}, +{-0.733034f,0.680192f,3.02069e-017f},{-0.826061f,0.563581f,4.24491e-015f},{-0.82663f,0.562746f,-7.8038e-018f}, +{-0.955502f,0.294984f,-4.91695e-015f},{-0.955572f,0.294759f,4.91703e-015f},{0.0746326f,0.997211f,-2.56725e-015f}, +{-0.074795f,0.997199f,2.56722e-015f},{-0.0746326f,0.997211f,3.85238e-015f},{0.222381f,0.97496f,-2.51444e-015f}, +{0.074795f,0.997199f,0.0f},{0.222585f,0.974913f,6.27462e-016f},{0.365177f,0.930938f,-4.18677e-015f}, +{0.365379f,0.930859f,-7.34878e-018f},{0.49999f,0.866031f,-8.31048e-016f},{0.499833f,0.866122f,-2.98827e-016f}, +{0.623256f,0.782018f,-2.42255e-016f},{0.82663f,0.562746f,2.14345e-016f},{0.900794f,0.434246f,-3.01398e-016f}, +{0.826061f,0.563581f,-6.76994e-016f},{0.623488f,0.781833f,-1.27366e-015f},{0.732917f,0.680318f,2.83318e-015f}, +{0.733034f,0.680192f,5.45378e-016f},{0.901683f,0.432397f,-2.82967e-015f},{0.955502f,0.294984f,1.20141e-015f}, +{0.955572f,0.294759f,1.26105e-015f},{0.988846f,0.148938f,-3.11202e-016f},{0.988818f,0.149126f,-3.47669e-016f}, +{-0.222381f,0.97496f,2.50997e-015f},{-0.365177f,0.930938f,2.41132e-015f},{-0.222585f,0.974913f,8.95358e-018f}, +{-0.365379f,0.930859f,1.46976e-017f},{-0.499989f,0.866031f,4.45908e-015f},{-0.623256f,0.782018f,-5.01415e-017f}, +{-0.732917f,0.680318f,2.94819e-017f},{-0.623488f,0.781833f,6.03832e-015f},{-0.733034f,0.680192f,1.81008e-015f}, +{-0.826061f,0.563581f,-1.4509e-015f},{-0.82663f,0.562746f,0.0f},{-0.900794f,0.434246f,0.0f}, +{-0.955502f,0.294984f,-1.51883e-015f},{-0.955572f,0.294759f,-7.68766e-017f},{-0.988818f,0.149126f,-7.95513e-017f}, +{-0.988846f,0.148938f,0.0f},{-0.933821f,0.357739f,0.0f},{-0.904255f,0.426992f,0.0f}, +{-0.904263f,0.426976f,0.0f},{-0.869576f,0.4938f,0.0f},{-0.869571f,0.493808f,0.0f}, +{-0.829957f,0.557828f,0.0f},{-0.829967f,0.557812f,0.0f},{-0.785637f,0.618687f,0.0f}, +{-0.78564f,0.618684f,0.0f},{-0.736896f,0.676006f,0.0f},{-0.736809f,0.6761f,0.0f}, +{-0.683915f,0.729561f,0.0f},{-0.683922f,0.729555f,0.0f},{-0.627048f,0.77898f,0.0f}, +{-0.627107f,0.778933f,0.0f},{-0.566722f,0.823909f,0.0f},{-0.566664f,0.823949f,0.0f}, +{-0.503086f,0.864236f,0.0f},{-0.503098f,0.864229f,0.0f},{-0.436614f,0.899649f,0.0f}, +{-0.436655f,0.899629f,0.0f},{-0.367737f,0.92993f,0.0f},{-0.367679f,0.929953f,0.0f}, +{-0.296679f,0.954977f,0.0f},{-0.296721f,0.954964f,0.0f},{-0.223998f,0.97459f,0.0f}, +{-0.224026f,0.974583f,0.0f},{-0.150064f,0.988676f,0.0f},{-0.150035f,0.988681f,0.0f}, +{-0.0752244f,0.997167f,0.0f},{-0.0752458f,0.997165f,0.0f},{-1.35203e-015f,1.0f,0.0f}, +{-1.54518e-015f,1.0f,0.0f},{-0.933815f,0.357756f,0.0f},{-0.958087f,0.286476f,0.0f}, +{-0.958085f,0.286485f,0.0f},{-0.976924f,0.213586f,0.0f},{-0.97692f,0.213604f,0.0f}, +{-0.990224f,0.139487f,0.0f},{-0.990225f,0.139483f,0.0f},{-0.997917f,0.0645077f,0.0f}, +{-0.997909f,0.0646351f,0.0f},{-0.999943f,-0.0106703f,0.0f},{-0.999943f,-0.0106617f,0.0f}, +{-0.996308f,-0.0858467f,0.0f},{-0.996302f,-0.0859221f,0.0f},{-0.987014f,-0.160636f,0.0f}, +{-0.987025f,-0.160567f,0.0f},{-0.972136f,-0.234419f,0.0f},{-0.972139f,-0.234405f,0.0f}, +{-0.95175f,-0.306876f,0.0f},{-0.951735f,-0.306919f,0.0f},{-0.925942f,-0.377666f,0.0f}, +{-0.925965f,-0.377609f,0.0f},{-0.894907f,-0.446253f,0.0f},{-0.894927f,-0.446213f,0.0f}, +{-0.858816f,-0.512285f,0.0f},{-0.858801f,-0.51231f,0.0f},{-0.81782f,-0.575474f,0.0f}, +{-0.817838f,-0.575449f,0.0f},{-0.772206f,-0.635373f,0.0f},{-0.772219f,-0.635356f,0.0f}, +{-0.722222f,-0.691661f,0.0f},{-0.357739f,-0.933821f,0.0f},{-0.426992f,-0.904255f,0.0f}, +{-0.426976f,-0.904263f,0.0f},{-0.4938f,-0.869576f,0.0f},{-0.493808f,-0.869571f,0.0f}, +{-0.557828f,-0.829957f,0.0f},{-0.557812f,-0.829967f,0.0f},{-0.618687f,-0.785637f,0.0f}, +{-0.618684f,-0.78564f,0.0f},{-0.676006f,-0.736896f,0.0f},{-0.6761f,-0.736809f,0.0f}, +{-0.729561f,-0.683915f,0.0f},{-0.729555f,-0.683922f,0.0f},{-0.77898f,-0.627048f,0.0f}, +{-0.778933f,-0.627107f,0.0f},{-0.823909f,-0.566722f,0.0f},{-0.823949f,-0.566664f,0.0f}, +{-0.864236f,-0.503086f,0.0f},{-0.864229f,-0.503098f,0.0f},{-0.899649f,-0.436614f,0.0f}, +{-0.899629f,-0.436655f,0.0f},{-0.92993f,-0.367737f,0.0f},{-0.929953f,-0.367679f,0.0f}, +{-0.954977f,-0.296679f,0.0f},{-0.954964f,-0.296721f,0.0f},{-0.97459f,-0.223998f,0.0f}, +{-0.974583f,-0.224026f,0.0f},{-0.988676f,-0.150064f,0.0f},{-0.988681f,-0.150035f,0.0f}, +{-0.997167f,-0.0752244f,0.0f},{-0.997165f,-0.0752458f,0.0f},{-1.0f,7.72589e-016f,0.0f}, +{-0.357756f,-0.933815f,0.0f},{-0.286476f,-0.958087f,0.0f},{-0.286485f,-0.958085f,0.0f}, +{-0.213586f,-0.976924f,0.0f},{-0.213604f,-0.97692f,0.0f},{-0.139487f,-0.990224f,0.0f}, +{-0.139483f,-0.990225f,0.0f},{-0.0645077f,-0.997917f,0.0f},{-0.0646351f,-0.997909f,0.0f}, +{0.0106703f,-0.999943f,0.0f},{0.0106617f,-0.999943f,0.0f},{0.0858467f,-0.996308f,0.0f}, +{0.0859221f,-0.996302f,0.0f},{0.160636f,-0.987014f,0.0f},{0.160567f,-0.987025f,0.0f}, +{0.234419f,-0.972136f,0.0f},{0.234405f,-0.972139f,0.0f},{0.306876f,-0.95175f,0.0f}, +{0.306919f,-0.951735f,0.0f},{0.377666f,-0.925942f,0.0f},{0.377609f,-0.925965f,0.0f}, +{0.446253f,-0.894907f,0.0f},{0.446213f,-0.894927f,0.0f},{0.512285f,-0.858816f,0.0f}, +{0.51231f,-0.858801f,0.0f},{0.575474f,-0.81782f,0.0f},{0.575449f,-0.817838f,0.0f}, +{0.635373f,-0.772206f,0.0f},{0.635356f,-0.772219f,0.0f},{0.691661f,-0.722222f,0.0f}, +{0.933821f,-0.357739f,0.0f},{0.904255f,-0.426992f,0.0f},{0.904263f,-0.426976f,0.0f}, +{0.869576f,-0.4938f,0.0f},{0.869571f,-0.493808f,0.0f},{0.829957f,-0.557828f,0.0f}, +{0.829967f,-0.557812f,0.0f},{0.785637f,-0.618687f,0.0f},{0.78564f,-0.618684f,0.0f}, +{0.736896f,-0.676006f,0.0f},{0.736809f,-0.6761f,0.0f},{0.683915f,-0.729561f,0.0f}, +{0.683922f,-0.729555f,0.0f},{0.627048f,-0.77898f,0.0f},{0.627107f,-0.778933f,0.0f}, +{0.566722f,-0.823909f,0.0f},{0.566664f,-0.823949f,0.0f},{0.503086f,-0.864236f,0.0f}, +{0.503098f,-0.864229f,0.0f},{0.436614f,-0.899649f,0.0f},{0.436655f,-0.899629f,0.0f}, +{0.367737f,-0.92993f,0.0f},{0.367679f,-0.929953f,0.0f},{0.296679f,-0.954977f,0.0f}, +{0.296721f,-0.954964f,0.0f},{0.223998f,-0.97459f,0.0f},{0.224026f,-0.974583f,0.0f}, +{0.150064f,-0.988676f,0.0f},{0.150035f,-0.988681f,0.0f},{0.0752244f,-0.997167f,0.0f}, +{0.0752458f,-0.997165f,0.0f},{1.93147e-015f,-1.0f,0.0f},{1.54518e-015f,-1.0f,0.0f}, +{0.933815f,-0.357756f,0.0f},{0.958087f,-0.286476f,0.0f},{0.958085f,-0.286485f,0.0f}, +{0.976924f,-0.213586f,0.0f},{0.97692f,-0.213604f,0.0f},{0.990224f,-0.139487f,0.0f}, +{0.990225f,-0.139483f,0.0f},{0.997917f,-0.0645077f,0.0f},{0.997909f,-0.0646351f,0.0f}, +{0.999943f,0.0106703f,0.0f},{0.999943f,0.0106617f,0.0f},{0.996308f,0.0858467f,0.0f}, +{0.996302f,0.0859221f,0.0f},{0.987014f,0.160636f,0.0f},{0.987025f,0.160567f,0.0f}, +{0.972136f,0.234419f,0.0f},{0.972139f,0.234405f,0.0f},{0.95175f,0.306876f,0.0f}, +{0.951735f,0.306919f,0.0f},{0.925942f,0.377666f,0.0f},{0.925965f,0.377609f,0.0f}, +{0.894907f,0.446253f,0.0f},{0.894927f,0.446213f,0.0f},{0.858816f,0.512285f,0.0f}, +{0.858801f,0.51231f,0.0f},{0.81782f,0.575474f,0.0f},{0.817838f,0.575449f,0.0f}, +{0.772206f,0.635373f,0.0f},{0.772219f,0.635356f,0.0f},{0.722222f,0.691661f,0.0f}, +{0.0f,8.67362e-019f,1.0f},{0.0f,-3.25261e-019f,1.0f},{0.0f,-1.0842e-019f,1.0f}, +{0.0f,4.87891e-019f,1.0f},{0.0f,-1.6263e-019f,1.0f},{0.0f,7.04731e-019f,1.0f}, +{0.0f,2.1684e-019f,1.0f},{0.0f,-5.96311e-019f,1.0f},{0.0f,-4.87891e-019f,1.0f}, +{0.0f,-7.04731e-019f,1.0f},{0.0f,1.6263e-019f,1.0f},{0.0f,5.42101e-020f,1.0f}, +{0.0f,3.79471e-019f,1.0f},{0.0f,5.42101e-019f,1.0f},{0.0f,-3.79471e-019f,1.0f}, +{0.0f,-7.58942e-019f,1.0f},{0.0f,-6.50521e-019f,1.0f},{0.0f,7.86047e-019f,1.0f}, +{0.0f,-7.45389e-019f,1.0f},{0.0f,5.69206e-019f,1.0f},{0.0f,2.84603e-019f,1.0f}, +{0.0f,-3.15096e-019f,1.0f},{0.0f,2.43945e-019f,1.0f},{0.0f,-5.42101e-019f,1.0f}, +{0.0f,-2.1684e-019f,1.0f},{0.0f,-3.59142e-019f,1.0f},{0.0f,3.65918e-019f,1.0f}, +{0.0f,2.17158e-019f,1.0f},{0.0f,-6.10181e-019f,1.0f},{0.0f,6.77626e-019f,1.0f}, +{0.0f,-6.87791e-019f,1.0f},{0.0f,-4.60786e-019f,1.0f},{0.0f,-7.31836e-019f,1.0f}, +{0.0f,8.02987e-019f,1.0f},{0.0f,-6.77626e-019f,1.0f},{0.0f,-5.74712e-019f,1.0f}, +{0.0f,-1.76183e-019f,1.0f},{0.0f,2.71051e-019f,1.0f},{0.0f,7.58942e-019f,1.0f}, +{0.0f,-2.71051e-019f,1.0f},{0.0f,-8.13152e-019f,1.0f},{0.0f,5.96311e-019f,1.0f}, +{0.0f,-5.14996e-019f,1.0f},{0.0f,6.50521e-019f,1.0f},{0.0f,3.25261e-019f,1.0f}, +{0.0f,-5.42101e-020f,1.0f},{0.0f,1.0842e-019f,1.0f},{0.0f,4.60786e-019f,1.0f}, +{0.0f,8.26704e-019f,1.0f},{0.0f,2.25311e-019f,1.0f},{0.0f,6.60686e-019f,1.0f}, +{0.0f,-5.57348e-019f,1.0f},{4.16334e-016f,1.0f,0.0f},{0.999314f,0.0370361f,0.0f}, +{0.999323f,-0.036793f,0.0f},{0.999323f,0.0367929f,0.0f},{0.993826f,0.110947f,0.0f}, +{0.993828f,0.110936f,0.0f},{0.982882f,0.184236f,0.0f},{0.982886f,0.184212f,0.0f}, +{0.96655f,0.256477f,0.0f},{0.966539f,0.256521f,0.0f},{0.944889f,0.32739f,0.0f}, +{0.944907f,0.327338f,0.0f},{0.918057f,0.396448f,0.0f},{0.918074f,0.396408f,0.0f}, +{0.886197f,0.463309f,0.0f},{0.886182f,0.463337f,0.0f},{0.849433f,0.527696f,0.0f}, +{0.849456f,0.527659f,0.0f},{0.808016f,0.58916f,0.0f},{0.80806f,0.5891f,0.0f}, +{0.762212f,0.647328f,0.0f},{0.762181f,0.647364f,0.0f},{0.712153f,0.702024f,0.0f}, +{0.712214f,0.701962f,0.0f},{0.658207f,0.752837f,0.0f},{0.658254f,0.752796f,0.0f}, +{0.600685f,0.799486f,0.0f},{0.600678f,0.799491f,0.0f},{0.539832f,0.841773f,0.0f}, +{0.539844f,0.841765f,0.0f},{0.476025f,0.879432f,0.0f},{0.476043f,0.879422f,0.0f}, +{0.409619f,0.912257f,0.0f},{0.409607f,0.912262f,0.0f},{0.340942f,0.940084f,0.0f}, +{0.340954f,0.94008f,0.0f},{0.270403f,0.962747f,0.0f},{0.270418f,0.962743f,0.0f}, +{0.1984f,0.980121f,0.0f},{0.198377f,0.980126f,0.0f},{0.125268f,0.992123f,0.0f}, +{0.125266f,0.992123f,0.0f},{0.0513531f,0.998681f,0.0f},{0.0515068f,0.998673f,0.0f}, +{-0.0226075f,0.999744f,0.0f},{-0.0226241f,0.999744f,0.0f},{-0.0966381f,0.99532f,0.0f}, +{-0.0965597f,0.995327f,0.0f},{-0.170063f,0.985433f,0.0f},{-0.170003f,0.985444f,0.0f}, +{-0.242529f,0.970144f,0.0f},{-0.242546f,0.97014f,0.0f},{-0.313741f,0.949509f,0.0f}, +{-0.313692f,0.949525f,0.0f},{-0.383193f,0.923668f,0.0f},{-0.383138f,0.923691f,0.0f}, +{-0.450489f,0.892782f,0.0f},{-0.450523f,0.892765f,0.0f},{-0.515387f,0.856957f,0.0f}, +{-0.51536f,0.856974f,0.0f},{-0.577428f,0.816442f,0.0f},{-0.577403f,0.816459f,0.0f}, +{-0.636279f,0.771459f,0.0f},{-0.636295f,0.771446f,0.0f},{-0.691661f,0.722222f,0.0f}, +{0.999314f,-0.0370363f,0.0f},{0.993828f,-0.110936f,0.0f},{0.993826f,-0.110947f,0.0f}, +{0.982882f,-0.184236f,0.0f},{0.982886f,-0.184212f,0.0f},{0.966539f,-0.256521f,0.0f}, +{0.96655f,-0.256477f,0.0f},{0.944907f,-0.327338f,0.0f},{0.944889f,-0.32739f,0.0f}, +{0.918057f,-0.396448f,0.0f},{0.918074f,-0.396408f,0.0f},{0.886182f,-0.463337f,0.0f}, +{0.886197f,-0.463309f,0.0f},{0.849456f,-0.527659f,0.0f},{0.849433f,-0.527696f,0.0f}, +{0.808016f,-0.58916f,0.0f},{0.80806f,-0.5891f,0.0f},{0.762181f,-0.647364f,0.0f}, +{0.762212f,-0.647328f,0.0f},{0.712214f,-0.701962f,0.0f},{0.712153f,-0.702024f,0.0f}, +{0.658207f,-0.752837f,0.0f},{0.658255f,-0.752795f,0.0f},{0.600678f,-0.799491f,0.0f}, +{0.600685f,-0.799486f,0.0f},{0.539843f,-0.841765f,0.0f},{0.539832f,-0.841773f,0.0f}, +{0.476025f,-0.879432f,0.0f},{0.476043f,-0.879422f,0.0f},{0.409606f,-0.912262f,0.0f}, +{0.409619f,-0.912257f,0.0f},{0.340954f,-0.94008f,0.0f},{0.340942f,-0.940084f,0.0f}, +{0.270403f,-0.962747f,0.0f},{0.270418f,-0.962743f,0.0f},{0.198378f,-0.980126f,0.0f}, +{0.1984f,-0.980121f,0.0f},{0.125266f,-0.992123f,0.0f},{0.125268f,-0.992123f,0.0f}, +{0.0513531f,-0.998681f,0.0f},{0.0515067f,-0.998673f,0.0f},{-0.0226239f,-0.999744f,0.0f}, +{-0.0226076f,-0.999744f,0.0f},{-0.0965598f,-0.995327f,0.0f},{-0.0966381f,-0.99532f,0.0f}, +{-0.170063f,-0.985433f,0.0f},{-0.170003f,-0.985444f,0.0f},{-0.242546f,-0.97014f,0.0f}, +{-0.242529f,-0.970144f,0.0f},{-0.313693f,-0.949525f,0.0f},{-0.313741f,-0.949509f,0.0f}, +{-0.383193f,-0.923668f,0.0f},{-0.383138f,-0.923691f,0.0f},{-0.450523f,-0.892765f,0.0f}, +{-0.450489f,-0.892782f,0.0f},{-0.51536f,-0.856974f,0.0f},{-0.515387f,-0.856957f,0.0f}, +{-0.577428f,-0.816442f,0.0f},{-0.577403f,-0.816459f,0.0f},{-0.636295f,-0.771446f,0.0f}, +{-0.636279f,-0.771459f,0.0f},{-0.691661f,-0.722222f,0.0f},{6.5746e-016f,-1.0f,0.0f}, +{-2.22045e-016f,-1.0f,0.0f},{1.0f,1.22298e-016f,0.0f},{1.0f,1.11022e-016f,0.0f}, +{-0.0752459f,-0.997165f,0.0f},{-9.09877e-012f,-1.0f,0.0f},{-1.02144e-013f,-1.0f,0.0f}, +{-0.296679f,-0.954977f,0.0f},{-0.223998f,-0.97459f,0.0f},{-0.296721f,-0.954964f,0.0f}, +{-0.224026f,-0.974583f,0.0f},{-0.150034f,-0.988681f,0.0f},{-0.150064f,-0.988676f,0.0f}, +{-0.436614f,-0.899649f,0.0f},{-0.503098f,-0.864229f,0.0f},{-0.503086f,-0.864236f,0.0f}, +{-0.367737f,-0.92993f,0.0f},{-0.436655f,-0.899629f,0.0f},{-0.367679f,-0.929953f,0.0f}, +{-0.736896f,-0.676006f,0.0f},{-0.683915f,-0.729561f,0.0f},{-0.683922f,-0.729555f,0.0f}, +{-0.627048f,-0.77898f,0.0f},{-0.566664f,-0.823949f,0.0f},{-0.627107f,-0.778933f,0.0f}, +{-0.829957f,-0.557828f,0.0f},{-0.829967f,-0.557812f,0.0f},{-0.869576f,-0.4938f,0.0f}, +{-0.736809f,-0.6761f,0.0f},{-0.78564f,-0.618684f,0.0f},{-0.785637f,-0.618687f,0.0f}, +{-0.933821f,-0.357739f,0.0f},{-0.958087f,-0.286476f,0.0f},{-0.933815f,-0.357756f,0.0f}, +{-0.904263f,-0.426976f,0.0f},{-0.904255f,-0.426992f,0.0f},{-0.869571f,-0.493808f,0.0f}, +{-0.997917f,-0.0645078f,0.0f},{-0.990224f,-0.139487f,0.0f},{-0.990224f,-0.139483f,0.0f}, +{-0.97692f,-0.213603f,0.0f},{-0.958085f,-0.286485f,0.0f},{-0.976924f,-0.213586f,0.0f}, +{-0.996308f,0.0858467f,0.0f},{-0.999943f,0.0106617f,0.0f},{-0.996302f,0.085922f,0.0f}, +{-0.997909f,-0.0646351f,0.0f},{-0.999943f,0.0106703f,0.0f},{-0.972139f,0.234405f,0.0f}, +{-0.987025f,0.160567f,0.0f},{-0.972136f,0.234419f,0.0f},{-0.987014f,0.160636f,0.0f}, +{-0.951735f,0.306919f,0.0f},{-0.95175f,0.306876f,0.0f},{-0.925942f,0.377666f,0.0f}, +{-0.925965f,0.377609f,0.0f},{-0.894927f,0.446213f,0.0f},{-0.894907f,0.446253f,0.0f}, +{-0.858801f,0.51231f,0.0f},{-0.858815f,0.512285f,0.0f},{-0.81782f,0.575474f,0.0f}, +{-0.817838f,0.575449f,0.0f},{-0.772219f,0.635356f,0.0f},{-0.772206f,0.635373f,0.0f}, +{-0.722222f,0.691661f,0.0f},{-0.566722f,-0.823909f,0.0f},{-0.0752244f,-0.997167f,0.0f}, +{-1.0f,4.16334e-017f,0.0f},{4.44089e-016f,-1.0f,0.0f},{8.88178e-016f,-1.0f,0.0f}, +{-1.0f,0.0f,-5.55112e-017f},{1.11022e-016f,-1.0f,0.0f},{9.71445e-017f,-1.0f,0.0f}, +{-0.997165f,0.0752459f,0.0f},{-1.0f,9.10186e-012f,0.0f},{-1.0f,1.03206e-013f,0.0f}, +{-0.954977f,0.296679f,0.0f},{-0.97459f,0.223998f,0.0f},{-0.954964f,0.296721f,0.0f}, +{-0.974583f,0.224026f,0.0f},{-0.988681f,0.150034f,0.0f},{-0.988676f,0.150064f,0.0f}, +{-0.899649f,0.436614f,0.0f},{-0.864229f,0.503098f,0.0f},{-0.864236f,0.503086f,0.0f}, +{-0.92993f,0.367737f,0.0f},{-0.899629f,0.436655f,0.0f},{-0.929953f,0.367679f,0.0f}, +{-0.676006f,0.736896f,0.0f},{-0.729561f,0.683915f,0.0f},{-0.729555f,0.683922f,0.0f}, +{-0.77898f,0.627048f,0.0f},{-0.823949f,0.566664f,0.0f},{-0.778933f,0.627107f,0.0f}, +{-0.557828f,0.829957f,0.0f},{-0.557812f,0.829967f,0.0f},{-0.4938f,0.869576f,0.0f}, +{-0.6761f,0.736809f,0.0f},{-0.618684f,0.78564f,0.0f},{-0.618687f,0.785637f,0.0f}, +{-0.357739f,0.933821f,0.0f},{-0.286476f,0.958087f,0.0f},{-0.357756f,0.933815f,0.0f}, +{-0.426976f,0.904263f,0.0f},{-0.426992f,0.904255f,0.0f},{-0.493808f,0.869571f,0.0f}, +{-0.0645078f,0.997917f,0.0f},{-0.139487f,0.990224f,0.0f},{-0.139483f,0.990224f,0.0f}, +{-0.213603f,0.97692f,0.0f},{-0.286485f,0.958085f,0.0f},{-0.213586f,0.976924f,0.0f}, +{0.0858467f,0.996308f,0.0f},{0.0106617f,0.999943f,0.0f},{0.085922f,0.996302f,0.0f}, +{-0.0646351f,0.997909f,0.0f},{0.0106703f,0.999943f,0.0f},{0.234405f,0.972139f,0.0f}, +{0.160567f,0.987025f,0.0f},{0.234419f,0.972136f,0.0f},{0.160636f,0.987014f,0.0f}, +{0.306919f,0.951735f,0.0f},{0.306876f,0.95175f,0.0f},{0.377666f,0.925942f,0.0f}, +{0.377609f,0.925965f,0.0f},{0.446213f,0.894927f,0.0f},{0.446253f,0.894907f,0.0f}, +{0.51231f,0.858801f,0.0f},{0.512285f,0.858815f,0.0f},{0.575474f,0.81782f,0.0f}, +{0.575449f,0.817838f,0.0f},{0.635356f,0.772219f,0.0f},{0.635373f,0.772206f,0.0f}, +{0.691661f,0.722222f,0.0f},{-0.823909f,0.566722f,0.0f},{-0.997167f,0.0752244f,0.0f}, +{-1.32706e-016f,1.0f,0.0f},{-1.38778e-016f,1.0f,0.0f},{8.88178e-016f,1.0f,0.0f}, +{-1.0f,4.81386e-016f,0.0f},{-1.0f,4.71845e-016f,0.0f},{0.0752459f,0.997165f,0.0f}, +{9.09877e-012f,1.0f,0.0f},{1.00502e-013f,1.0f,0.0f},{0.296679f,0.954977f,0.0f}, +{0.223998f,0.97459f,0.0f},{0.296721f,0.954964f,0.0f},{0.224026f,0.974583f,0.0f}, +{0.150034f,0.988681f,0.0f},{0.150064f,0.988676f,0.0f},{0.436614f,0.899649f,0.0f}, +{0.503098f,0.864229f,0.0f},{0.503086f,0.864236f,0.0f},{0.367737f,0.92993f,0.0f}, +{0.436655f,0.899629f,0.0f},{0.367679f,0.929953f,0.0f},{0.736896f,0.676006f,0.0f}, +{0.683915f,0.729561f,0.0f},{0.683922f,0.729555f,0.0f},{0.627048f,0.77898f,0.0f}, +{0.566664f,0.823949f,0.0f},{0.627107f,0.778933f,0.0f},{0.829957f,0.557828f,0.0f}, +{0.829967f,0.557812f,0.0f},{0.869576f,0.4938f,0.0f},{0.736809f,0.6761f,0.0f}, +{0.78564f,0.618684f,0.0f},{0.785637f,0.618687f,0.0f},{0.933821f,0.357739f,0.0f}, +{0.958087f,0.286476f,0.0f},{0.933815f,0.357756f,0.0f},{0.904263f,0.426976f,0.0f}, +{0.904255f,0.426992f,0.0f},{0.869571f,0.493808f,0.0f},{0.997917f,0.0645078f,0.0f}, +{0.990224f,0.139487f,0.0f},{0.990224f,0.139483f,0.0f},{0.97692f,0.213603f,0.0f}, +{0.958085f,0.286485f,0.0f},{0.976924f,0.213586f,0.0f},{0.996308f,-0.0858467f,0.0f}, +{0.999943f,-0.0106617f,0.0f},{0.996302f,-0.085922f,0.0f},{0.997909f,0.0646351f,0.0f}, +{0.999943f,-0.0106703f,0.0f},{0.972139f,-0.234405f,0.0f},{0.987025f,-0.160567f,0.0f}, +{0.972136f,-0.234419f,0.0f},{0.987014f,-0.160636f,0.0f},{0.951735f,-0.306919f,0.0f}, +{0.95175f,-0.306876f,0.0f},{0.925942f,-0.377666f,0.0f},{0.925965f,-0.377609f,0.0f}, +{0.894927f,-0.446213f,0.0f},{0.894907f,-0.446253f,0.0f},{0.858801f,-0.51231f,0.0f}, +{0.858815f,-0.512285f,0.0f},{0.81782f,-0.575474f,0.0f},{0.817838f,-0.575449f,0.0f}, +{0.772219f,-0.635356f,0.0f},{0.772206f,-0.635373f,0.0f},{0.722222f,-0.691661f,0.0f}, +{0.566722f,0.823909f,0.0f},{0.0752244f,0.997167f,0.0f},{1.0f,4.57967e-016f,0.0f}, +{1.0f,4.85723e-016f,0.0f},{-7.21645e-016f,1.0f,0.0f},{1.0f,-3.50885e-016f,0.0f}, +{0.332491f,0.943106f,-1.06997e-016f},{0.412177f,0.911104f,-1.88488e-015f},{0.412177f,0.911104f,-1.20772e-015f}, +{0.250506f,0.968115f,-9.4629e-017f},{0.167145f,0.985932f,6.49454e-016f},{0.0833404f,0.996521f,-1.06395e-016f}, +{-3.81317e-016f,1.0f,0.0f},{-2.02575e-016f,1.0f,0.0f},{0.488686f,0.87246f,7.69425e-016f}, +{0.561215f,0.82767f,0.0f},{0.629065f,0.777353f,3.23897e-015f},{0.629065f,0.777353f,1.61948e-015f}, +{0.412177f,-0.911104f,-1.23041e-015f},{0.332491f,-0.943106f,8.18039e-016f},{0.332491f,-0.943106f,1.62429e-016f}, +{0.488686f,-0.87246f,8.39281e-016f},{0.561215f,-0.82767f,-1.49714e-015f},{0.629065f,-0.777353f,3.04377e-015f}, +{0.250506f,-0.968115f,4.00341e-016f},{0.167145f,-0.985932f,-3.50985e-016f},{0.0833404f,-0.996521f,0.0f}, +{-1.90659e-016f,-1.0f,0.0f},{-0.911104f,-0.412177f,-2.15889e-015f},{-0.943106f,-0.332491f,3.90051e-016f}, +{-0.87246f,-0.488686f,9.96209e-016f},{-0.82767f,-0.561215f,7.42388e-016f},{-0.777353f,-0.629065f,4.00085e-015f}, +{-0.968115f,-0.250506f,-7.78858e-017f},{-0.985932f,-0.167145f,-8.04095e-016f},{-0.996521f,-0.0833404f,1.60342e-016f}, +{-1.0f,-2.02575e-016f,0.0f},{-1.0f,1.90659e-016f,0.0f},{-0.943106f,0.332491f,-6.79919e-016f}, +{-0.911104f,0.412177f,-8.69141e-016f},{-0.911104f,0.412177f,-1.91981e-016f},{-0.968115f,0.250506f,-5.56861e-017f}, +{-0.985932f,0.167145f,7.53839e-017f},{-0.996521f,0.0833404f,-8.12926e-017f},{-1.0f,-1.90659e-016f,0.0f}, +{-1.0f,-1.19162e-017f,0.0f},{-0.87246f,0.488686f,0.0f},{-0.82767f,0.561215f,-1.44481e-015f}, +{-0.777353f,0.629065f,2.98881e-015f},{0.911104f,0.412177f,3.3858e-016f},{0.943106f,0.332491f,-5.79735e-016f}, +{0.943106f,0.332491f,-9.31849e-016f},{0.87246f,0.488686f,9.08471e-016f},{0.82767f,0.561215f,-1.65643e-016f}, +{0.777353f,0.629065f,1.61602e-015f},{0.968115f,0.250506f,3.11543e-016f},{0.985932f,0.167145f,-3.50985e-016f}, +{0.996521f,0.0833404f,-2.14554e-016f},{1.0f,-2.02575e-016f,0.0f},{1.0f,-1.90659e-016f,0.0f}, +{0.943106f,-0.332491f,-5.28171e-016f},{0.911104f,-0.412177f,-7.22542e-016f},{0.911104f,-0.412177f,-4.85178e-016f}, +{0.968115f,-0.250506f,-1.141e-016f},{0.985932f,-0.167145f,1.15043e-016f},{0.996521f,-0.0833404f,-8.63033e-017f}, +{1.0f,3.81317e-016f,0.0f},{1.0f,1.19162e-017f,0.0f},{0.87246f,-0.488686f,0.0f}, +{0.82767f,-0.561215f,-1.57798e-015f},{0.777353f,-0.629065f,3.23897e-015f},{-0.412177f,0.911104f,1.70163e-015f}, +{-0.332491f,0.943106f,-1.00772e-015f},{-0.488686f,0.87246f,-7.17115e-016f},{-0.561215f,0.82767f,-1.39145e-015f}, +{-0.629065f,0.777353f,1.16234e-015f},{-0.250506f,0.968115f,-6.44911e-016f},{-0.167145f,0.985932f,7.93192e-017f}, +{-0.0833404f,0.996521f,0.0f},{-3.93233e-016f,1.0f,0.0f},{-0.332491f,-0.943106f,1.14584e-015f}, +{-0.412177f,-0.911104f,3.3858e-016f},{-0.250506f,-0.968115f,7.28254e-016f},{-0.167145f,-0.985932f,2.83812e-016f}, +{-0.0833404f,-0.996521f,6.91185e-017f},{1.33461e-015f,-1.0f,0.0f},{1.23928e-015f,-1.0f,0.0f}, +{-0.488686f,-0.87246f,3.48283e-016f},{-0.561215f,-0.82767f,-3.02279e-015f},{-0.629065f,-0.777353f,3.48912e-015f}, +{-0.603231f,-0.797567f,9.7061e-017f},{-0.707107f,-0.707107f,6.25761e-016f},{-0.489042f,-0.87226f,5.61393e-016f}, +{-0.368095f,-0.929788f,5.98419e-016f},{-0.244052f,-0.969762f,0.0f},{-0.12036f,-0.99273f,0.0f}, +{1.25607e-015f,-1.0f,0.0f},{1.00486e-015f,-1.0f,0.0f},{-0.797567f,-0.603231f,2.27018e-016f}, +{-0.87226f,-0.489042f,1.04745e-016f},{-0.929788f,-0.368095f,-3.82645e-016f},{-0.969762f,-0.244052f,7.06879e-017f}, +{-0.99273f,-0.12036f,-1.00206e-016f},{-1.0f,2.51215e-016f,0.0f},{-1.0f,-2.35514e-016f,0.0f}, +{0.603231f,0.797567f,-4.82864e-016f},{0.489042f,0.87226f,1.74403e-016f},{0.368095f,0.929788f,4.73817e-016f}, +{0.244052f,0.969762f,0.0f},{0.12036f,0.99273f,0.0f},{1.68e-015f,1.0f,0.0f}, +{1.7585e-015f,1.0f,0.0f},{0.797567f,0.603231f,9.27704e-016f},{0.87226f,0.489042f,6.15491e-016f}, +{0.929788f,0.368095f,-8.95393e-016f},{0.969762f,0.244052f,2.10774e-016f},{0.99273f,0.12036f,-1.30495e-016f}, +{1.0f,1.00486e-015f,0.0f},{1.0f,1.13047e-015f,0.0f},{0.603231f,0.797567f,-7.6998e-016f}, +{0.707107f,0.707107f,2.84437e-016f},{0.489042f,0.87226f,-1.0441e-015f},{0.244052f,0.969762f,-7.02683e-016f}, +{0.12036f,0.99273f,1.27786e-015f},{1.00486e-015f,1.0f,0.0f},{0.797567f,0.603231f,-2.25391e-016f}, +{0.87226f,0.489042f,5.37527e-016f},{0.929788f,0.368095f,-1.30546e-016f},{0.969762f,0.244052f,-2.98079e-017f}, +{0.99273f,0.12036f,-3.75669e-017f},{1.0f,-2.51215e-016f,0.0f},{1.0f,-2.82617e-016f,0.0f}, +{-0.797567f,0.603231f,-2.90369e-016f},{-0.707107f,0.707107f,7.11093e-016f},{-0.87226f,0.489042f,-5.95448e-016f}, +{-0.929788f,0.368095f,1.49605e-016f},{-0.969762f,0.244052f,-3.14148e-016f},{-0.99273f,0.12036f,4.80237e-018f}, +{-1.0f,1.6329e-015f,0.0f},{-1.0f,1.50729e-015f,0.0f},{-0.603231f,0.797567f,-4.64789e-016f}, +{-0.603231f,0.797567f,7.02313e-016f},{-0.489042f,0.87226f,-7.50922e-016f},{-0.368095f,0.929788f,6.962e-016f}, +{-0.244052f,0.969762f,-1.23453e-015f},{-0.12036f,0.99273f,-8.00113e-016f},{2.26093e-015f,1.0f,0.0f}, +{-0.797567f,0.603231f,-6.10381e-016f},{-0.707107f,0.707107f,7.96424e-016f},{-0.87226f,0.489042f,1.12279e-015f}, +{-0.929788f,0.368095f,5.98419e-016f},{-0.969762f,0.244052f,-1.24829e-015f},{-0.99273f,0.12036f,3.87325e-017f}, +{-1.0f,1.00486e-015f,0.0f},{-0.603231f,0.797567f,-3.24079e-016f},{-0.489042f,0.87226f,-5.55587e-016f}, +{-0.368095f,0.929788f,1.15329e-016f},{-0.244052f,0.969762f,1.60913e-016f},{-0.12036f,0.99273f,-5.63777e-017f}, +{1.57009e-017f,1.0f,0.0f},{0.797567f,-0.603231f,-6.2538e-017f},{0.707107f,-0.707107f,9.67086e-016f}, +{0.87226f,-0.489042f,-4.82706e-016f},{0.929788f,-0.368095f,-5.98419e-016f},{0.969762f,-0.244052f,-7.02683e-016f}, +{0.99273f,-0.12036f,3.87325e-017f},{1.0f,-1.13047e-015f,0.0f},{1.0f,-1.00486e-015f,0.0f}, +{0.603231f,-0.797567f,-5.48656e-016f},{0.489042f,-0.87226f,-2.23293e-016f},{0.368095f,-0.929788f,7.5955e-017f}, +{0.244052f,-0.969762f,1.54765e-016f},{0.12036f,-0.99273f,-8.23468e-017f},{2.51215e-016f,-1.0f,0.0f}, +{2.82617e-016f,-1.0f,0.0f},{0.797567f,-0.603231f,1.00269e-015f},{0.707107f,-0.707107f,3.98212e-016f}, +{0.87226f,-0.489042f,-4.89153e-016f},{0.929788f,-0.368095f,3.86513e-016f},{0.969762f,-0.244052f,-4.70184e-016f}, +{0.99273f,-0.12036f,-1.59732e-016f},{1.0f,1.57009e-017f,0.0f},{0.603231f,-0.797567f,5.30581e-016f}, +{0.489042f,-0.87226f,5.79743e-016f},{0.368095f,-0.929788f,2.62961e-017f},{0.244052f,-0.969762f,-7.6875e-016f}, +{0.12036f,-0.99273f,-3.81312e-016f},{-1.00486e-015f,-1.0f,0.0f},{8.79252e-016f,-1.0f,0.0f}, +{-0.603231f,-0.797567f,8.4228e-016f},{-0.707107f,-0.707107f,-3.41324e-016f},{-0.489042f,-0.87226f,-5.59328e-016f}, +{-0.368095f,-0.929788f,3.99015e-016f},{-0.244052f,-0.969762f,1.56037e-016f},{-0.12036f,-0.99273f,1.59732e-016f}, +{3.14019e-017f,-1.0f,0.0f},{-0.797567f,-0.603231f,-7.07442e-016f},{-0.87226f,-0.489042f,-6.64671e-016f}, +{-0.929788f,-0.368095f,-5.51379e-016f},{-0.969762f,-0.244052f,-2.00745e-016f},{-0.99273f,-0.12036f,-3.9822e-016f}, +{-1.0f,-2.00972e-015f,0.0f},{0.988818f,-0.149126f,-7.67832e-016f},{0.826061f,-0.563581f,2.9018e-015f}, +{0.82663f,-0.562746f,2.8975e-015f},{0.900794f,-0.434246f,-7.24697e-017f},{0.901683f,-0.432397f,-1.11318e-015f}, +{0.955572f,-0.294759f,0.0f},{0.955502f,-0.294984f,-7.68711e-017f},{0.499989f,-0.866031f,2.01123e-017f}, +{0.499834f,-0.866121f,-2.20966e-015f},{0.365379f,-0.930859f,2.41113e-015f},{0.623256f,-0.782018f,2.50708e-017f}, +{0.623488f,-0.781833f,-6.03832e-015f},{-0.074795f,-0.997199f,-1.28511e-015f},{-0.0746326f,-0.997211f,2.56875e-015f}, +{0.0746326f,-0.997211f,3.85238e-015f},{0.074795f,-0.997199f,-1.28511e-015f},{0.222585f,-0.974913f,3.76477e-015f}, +{0.222381f,-0.97496f,-2.51891e-015f},{-0.499833f,-0.866122f,2.51854e-015f},{-0.365177f,-0.930938f,-7.34471e-018f}, +{-0.365379f,-0.930859f,-2.39643e-015f},{-0.222381f,-0.97496f,-6.27044e-015f},{-0.222585f,-0.974913f,-1.88686e-015f}, +{-0.732917f,-0.680318f,-2.02688e-017f},{-0.623488f,-0.781833f,7.70465e-016f},{-0.733034f,-0.680192f,-1.18659e-016f}, +{-0.49999f,-0.866031f,-3.06059e-015f},{-0.623256f,-0.782018f,-7.70638e-016f},{-0.82663f,-0.562746f,1.58233e-016f}, +{-0.826061f,-0.563581f,-1.93807e-017f},{-0.901683f,-0.432397f,-2.42199e-016f},{-0.900794f,-0.434246f,7.97856e-016f}, +{-0.955502f,-0.294984f,-5.27632e-016f},{-0.955572f,-0.294759f,7.01229e-016f},{-0.988846f,-0.148938f,8.05299e-016f}, +{-0.988818f,-0.149126f,2.80723e-016f},{0.365177f,-0.930938f,4.77858e-015f},{0.733034f,-0.680192f,0.0f}, +{0.988818f,-0.149126f,9.73577e-020f},{0.988846f,-0.148938f,7.13987e-020f},{0.826061f,-0.563581f,-2.13745e-015f}, +{0.82663f,-0.562746f,-4.24488e-015f},{0.900794f,-0.434246f,2.32072e-015f},{0.901683f,-0.432397f,1.82527e-017f}, +{0.955572f,-0.294759f,7.88519e-018f},{0.955502f,-0.294984f,7.95502e-018f},{0.499989f,-0.866031f,-1.26807e-015f}, +{0.499834f,-0.866121f,1.34088e-015f},{0.365379f,-0.930859f,2.5686e-017f},{0.732917f,-0.680318f,-2.92946e-017f}, +{0.623256f,-0.782018f,-1.62692e-015f},{0.623488f,-0.781833f,-3.16995e-015f},{-0.074795f,-0.997199f,1.5066e-016f}, +{-0.0746326f,-0.997211f,-4.20003e-017f},{0.0746326f,-0.997211f,2.25086e-016f},{0.074795f,-0.997199f,-4.64395e-016f}, +{0.222585f,-0.974913f,2.5747e-017f},{0.222381f,-0.97496f,-5.07382e-016f},{-0.499833f,-0.866122f,1.1214e-015f}, +{-0.365177f,-0.930938f,7.49806e-016f},{-0.365379f,-0.930859f,1.72838e-015f},{-0.222381f,-0.97496f,-6.03215e-016f}, +{-0.222585f,-0.974913f,-9.94176e-016f},{-0.732917f,-0.680318f,-3.92441e-015f},{-0.623488f,-0.781833f,2.38377e-015f}, +{-0.733034f,-0.680192f,-2.48228e-015f},{-0.49999f,-0.866031f,-6.48069e-016f},{-0.623256f,-0.782018f,-4.09408e-016f}, +{-0.82663f,-0.562746f,-2.05981e-015f},{-0.826061f,-0.563581f,3.7841e-015f},{-0.901683f,-0.432397f,-1.58751e-016f}, +{-0.900794f,-0.434246f,-2.68865e-015f},{-0.955502f,-0.294984f,9.23116e-016f},{-0.955572f,-0.294759f,-1.22049e-015f}, +{-0.988846f,-0.148938f,2.44713e-015f},{-0.988818f,-0.149126f,-1.4151e-015f},{0.365177f,-0.930938f,2.58547e-017f}, +{0.733034f,-0.680192f,-1.91654e-015f},{1.0f,-8.32667e-017f,0.0f},{0.988818f,-0.149126f,-7.95513e-017f}, +{0.988846f,-0.148938f,7.95536e-017f},{0.826061f,-0.563581f,-1.38444e-015f},{0.82663f,-0.562746f,-6.65032e-017f}, +{0.900794f,-0.434246f,0.0f},{0.901683f,-0.432397f,7.25413e-017f},{0.955572f,-0.294759f,-7.68766e-017f}, +{0.955502f,-0.294984f,-1.44196e-015f},{0.499989f,-0.866031f,4.43896e-015f},{0.499834f,-0.866121f,-2.24988e-015f}, +{0.732917f,-0.680318f,2.94819e-017f},{0.623488f,-0.781833f,6.01324e-015f},{-0.074795f,-0.997199f,1.50433e-018f}, +{-0.0746326f,-0.997211f,-2.56575e-015f},{0.074795f,-0.997199f,2.56722e-015f},{0.222585f,-0.974913f,8.95358e-018f}, +{0.222381f,-0.97496f,2.50102e-015f},{-0.499833f,-0.866122f,-3.03854e-016f},{-0.365177f,-0.930938f,-4.19778e-015f}, +{-0.365379f,-0.930859f,-3.67439e-018f},{-0.222381f,-0.97496f,-2.50997e-015f},{-0.222585f,-0.974913f,6.22985e-016f}, +{-0.732917f,-0.680318f,2.82765e-015f},{-0.623488f,-0.781833f,-1.30187e-015f},{-0.733034f,-0.680192f,5.98822e-016f}, +{-0.49999f,-0.866031f,-8.36077e-016f},{-0.623256f,-0.782018f,-2.20318e-016f},{-0.82663f,-0.562746f,1.53038e-016f}, +{-0.826061f,-0.563581f,-6.75955e-016f},{-0.901683f,-0.432397f,-2.88011e-015f},{-0.900794f,-0.434246f,-3.52353e-016f}, +{-0.955502f,-0.294984f,1.16297e-015f},{-0.955572f,-0.294759f,1.22171e-015f},{-0.988846f,-0.148938f,-3.33616e-016f}, +{-0.988818f,-0.149126f,-3.70082e-016f},{0.365177f,-0.930938f,2.39664e-015f},{0.733034f,-0.680192f,1.72162e-015f}, +{0.826061f,-0.563581f,4.24246e-015f},{0.82663f,-0.562746f,1.13183e-017f},{0.955572f,-0.294759f,4.92799e-015f}, +{0.955502f,-0.294984f,-4.91179e-015f},{0.499989f,-0.866031f,1.30631e-015f},{0.732917f,-0.680318f,-1.91614e-015f}, +{0.623256f,-0.782018f,-3.23145e-015f},{0.623488f,-0.781833f,-1.56482e-015f},{-0.074795f,-0.997199f,-1.38172e-016f}, +{-0.0746326f,-0.997211f,5.40679e-017f},{0.0746326f,-0.997211f,-6.31192e-017f},{0.074795f,-0.997199f,1.69913e-017f}, +{0.222585f,-0.974913f,3.12261e-016f},{0.222381f,-0.97496f,-2.21129e-016f},{-0.499833f,-0.866122f,-3.26236e-016f}, +{-0.365177f,-0.930938f,-1.90317e-016f},{-0.365379f,-0.930859f,-1.09355e-015f},{-0.222381f,-0.97496f,-3.16963e-016f}, +{-0.222585f,-0.974913f,8.62413e-018f},{-0.732917f,-0.680318f,9.10624e-016f},{-0.623488f,-0.781833f,1.17992e-015f}, +{-0.733034f,-0.680192f,-2.71817e-015f},{-0.49999f,-0.866031f,1.12181e-015f},{-0.623256f,-0.782018f,-2.01394e-015f}, +{-0.82663f,-0.562746f,6.00315e-016f},{-0.826061f,-0.563581f,-1.66541e-015f},{-0.901683f,-0.432397f,-2.84278e-015f}, +{-0.900794f,-0.434246f,5.36253e-016f},{-0.955502f,-0.294984f,3.825e-015f},{-0.955572f,-0.294759f,5.47672e-016f}, +{-0.988846f,-0.148938f,-6.98966e-016f},{-0.988818f,-0.149126f,-2.60588e-015f},{0.733034f,-0.680192f,-2.93964e-017f}, +{1.0f,1.50359e-014f,-3.86165e-015f},{1.0f,2.12271e-014f,-3.86165e-015f},{0.158603f,0.987342f,7.37193e-016f}, +{0.826318f,0.563203f,-1.71427e-015f},{0.642788f,0.766044f,1.27963e-015f},{0.411158f,0.911564f,0.0f}, +{0.944801f,0.327644f,-1.17949e-017f},{-1.0f,-6.25927e-015f,0.0f},{-1.0f,2.50371e-014f,0.0f}, +{-0.327644f,-0.944801f,7.67486e-016f},{-0.911564f,-0.411158f,-2.06375e-015f},{-0.766044f,-0.642788f,-9.796e-016f}, +{-0.563203f,-0.826318f,-7.24964e-016f},{-0.987342f,-0.158603f,-4.26542e-015f},{-1.0f,-3.70074e-015f,0.0f}, +{-0.978254f,-0.207408f,-6.29612e-016f},{-0.50141f,-0.86521f,-1.61356e-016f},{-0.670096f,-0.742274f,0.0f}, +{-0.66887f,-0.743379f,9.08934e-016f},{-0.809606f,-0.586974f,3.77781e-016f},{-0.913862f,-0.406026f,5.88168e-016f}, +{-0.913543f,-0.406743f,-5.23566e-016f},{-0.105163f,-0.994455f,1.28008e-015f},{-0.104013f,-0.994576f,6.69438e-017f}, +{0.104013f,-0.994576f,9.09967e-016f},{-0.499433f,-0.866353f,7.1831e-016f},{-0.308272f,-0.951298f,1.22453e-015f}, +{-0.310578f,-0.950548f,-1.12361e-015f},{0.310578f,-0.950548f,-4.99725e-017f},{0.50141f,-0.86521f,3.66232e-016f}, +{0.499433f,-0.866353f,-6.29753e-016f},{0.308272f,-0.951298f,-5.08799e-016f},{0.105163f,-0.994455f,2.86178e-016f}, +{0.670096f,-0.742274f,-4.81031e-017f},{0.809606f,-0.586974f,1.13659e-015f},{0.808947f,-0.587881f,6.20902e-016f}, +{0.66887f,-0.743379f,-9.0294e-016f},{0.913543f,-0.406743f,5.2606e-016f},{0.913862f,-0.406026f,3.46568e-016f}, +{0.978254f,-0.207408f,-1.03704e-015f},{0.978165f,-0.20783f,1.66019e-015f},{1.0f,1.33227e-015f,0.0f}, +{-0.808947f,-0.587881f,-3.78365e-016f},{-0.978254f,-0.207408f,-1.25922e-015f},{-0.50141f,-0.86521f,3.22711e-016f}, +{-0.670096f,-0.742274f,-4.31279e-016f},{-0.66887f,-0.743379f,4.78444e-016f},{-0.913862f,-0.406026f,0.0f}, +{-0.105163f,-0.994455f,1.17855e-015f},{-0.104013f,-0.994576f,-3.34719e-017f},{0.104013f,-0.994576f,9.26703e-016f}, +{-0.499433f,-0.866353f,5.57591e-016f},{-0.308272f,-0.951298f,1.02612e-015f},{-0.310578f,-0.950548f,-1.22356e-015f}, +{0.310578f,-0.950548f,2.49863e-016f},{0.50141f,-0.86521f,7.29282e-016f},{0.499433f,-0.866353f,-3.48494e-016f}, +{0.308272f,-0.951298f,-3.10392e-016f},{0.105163f,-0.994455f,3.87703e-016f},{0.670096f,-0.742274f,-1.02013e-016f}, +{0.809606f,-0.586974f,1.21801e-015f},{0.808947f,-0.587881f,1.97878e-016f},{0.66887f,-0.743379f,1.18511e-017f}, +{0.913543f,-0.406743f,2.04518e-016f},{0.913862f,-0.406026f,5.70787e-017f},{0.978254f,-0.207408f,-6.1033e-016f}, +{0.978165f,-0.20783f,8.92923e-016f},{1.0f,-2.51651e-015f,0.0f},{-0.808947f,-0.587881f,-8.99009e-016f}, +{-0.670096f,-0.742274f,-9.09012e-016f},{-0.66887f,-0.743379f,-9.56889e-016f},{-0.809606f,-0.586974f,-3.77781e-016f}, +{-0.913543f,-0.406743f,5.23566e-016f},{-0.105163f,-0.994455f,-7.41564e-016f},{-0.104013f,-0.994576f,-6.73588e-016f}, +{0.104013f,-0.994576f,2.86586e-016f},{-0.499433f,-0.866353f,-5.57591e-016f},{-0.308272f,-0.951298f,-1.98406e-016f}, +{-0.310578f,-0.950548f,0.0f},{0.50141f,-0.86521f,-1.06001e-016f},{0.499433f,-0.866353f,1.04548e-015f}, +{0.308272f,-0.951298f,3.0187e-016f},{0.105163f,-0.994455f,1.02774e-015f},{0.670096f,-0.742274f,-6.99179e-016f}, +{0.809606f,-0.586974f,2.73555e-016f},{0.808947f,-0.587881f,-4.6426e-016f},{0.66887f,-0.743379f,1.31462e-016f}, +{0.913543f,-0.406743f,3.51771e-016f},{0.913862f,-0.406026f,-6.53389e-016f},{0.978254f,-0.207408f,-4.75798e-016f}, +{0.978165f,-0.20783f,7.98349e-016f},{-0.978254f,-0.207408f,0.0f},{-0.50141f,-0.86521f,0.0f}, +{-0.670096f,-0.742274f,-4.77733e-016f},{-0.809606f,-0.586974f,6.64356e-016f},{-0.105163f,-0.994455f,-6.06197e-016f}, +{-0.104013f,-0.994576f,-5.06229e-016f},{0.104013f,-0.994576f,3.5353e-016f},{-0.499433f,-0.866353f,-2.36152e-016f}, +{-0.308272f,-0.951298f,0.0f},{-0.310578f,-0.950548f,9.99451e-017f},{0.310578f,-0.950548f,4.99725e-017f}, +{0.50141f,-0.86521f,-3.07696e-016f},{0.499433f,-0.866353f,1.0053e-015f},{0.308272f,-0.951298f,-1.44543e-016f}, +{0.670096f,-0.742274f,-1.23828e-015f},{0.809606f,-0.586974f,6.18708e-017f},{0.808947f,-0.587881f,-1.45674e-015f}, +{0.66887f,-0.743379f,-9.98574e-016f},{0.913543f,-0.406743f,8.75425e-016f},{0.913862f,-0.406026f,1.18582e-016f}, +{0.978254f,-0.207408f,8.24911e-017f},{0.978165f,-0.20783f,1.97076e-016f},{1.0f,2.66454e-015f,0.0f}, +{-0.670096f,-0.742274f,-6.93373e-016f},{-0.809606f,-0.586974f,4.03822e-016f},{-0.913862f,-0.406026f,2.94084e-016f}, +{-0.104013f,-0.994576f,-5.89909e-016f},{0.50141f,-0.86521f,-3.27865e-016f},{0.499433f,-0.866353f,9.45034e-016f}, +{0.308272f,-0.951298f,4.26112e-018f},{0.105163f,-0.994455f,9.60058e-016f},{0.670096f,-0.742274f,-6.85702e-016f}, +{0.809606f,-0.586974f,-1.49813e-016f},{0.808947f,-0.587881f,-3.17829e-016f},{0.66887f,-0.743379f,-5.14273e-016f}, +{0.913543f,-0.406743f,4.89574e-016f},{0.913862f,-0.406026f,-3.27139e-016f},{0.978254f,-0.207408f,2.95231e-016f}, +{0.978165f,-0.20783f,4.59595e-016f},{-0.808947f,-0.587881f,-1.18042e-016f},{-0.105163f,-0.994455f,-6.5696e-016f}, +{-0.104013f,-0.994576f,-6.56853e-016f},{0.104013f,-0.994576f,3.36794e-016f},{-0.308272f,-0.951298f,-9.9203e-017f}, +{-0.310578f,-0.950548f,-9.99451e-017f},{0.310578f,-0.950548f,2.49863e-017f},{0.50141f,-0.86521f,-4.69051e-016f}, +{0.499433f,-0.866353f,9.65124e-016f},{0.308272f,-0.951298f,2.27468e-016f},{0.105163f,-0.994455f,8.92374e-016f}, +{0.670096f,-0.742274f,-7.26134e-016f},{0.809606f,-0.586974f,-5.2113e-017f},{0.808947f,-0.587881f,-9.00466e-017f}, +{0.913543f,-0.406743f,4.25266e-016f},{0.913862f,-0.406026f,-5.24727e-016f},{0.978254f,-0.207408f,9.93815e-018f}, +{0.978165f,-0.20783f,6.42805e-016f},{1.0f,-1.25825e-015f,0.0f},{-0.670096f,-0.742274f,-2.1564e-016f}, +{-0.809606f,-0.586974f,1.15938e-015f},{-0.105163f,-0.994455f,1.31392e-015f},{-0.104013f,-0.994576f,5.02078e-017f}, +{0.104013f,-0.994576f,9.93647e-016f},{0.50141f,-0.86521f,5.07418e-016f},{0.499433f,-0.866353f,-4.48944e-016f}, +{0.308272f,-0.951298f,-6.08002e-016f},{0.105163f,-0.994455f,3.20019e-016f},{0.670096f,-0.742274f,-8.85355e-017f}, +{0.809606f,-0.586974f,7.94639e-016f},{0.808947f,-0.587881f,3.44309e-016f},{0.66887f,-0.743379f,-6.33884e-016f}, +{0.913543f,-0.406743f,3.42322e-016f},{0.913862f,-0.406026f,3.83328e-016f},{0.978254f,-0.207408f,1.60699e-016f}, +{0.978165f,-0.20783f,5.54168e-016f},{-0.105163f,-0.994455f,1.26316e-015f},{-0.104013f,-0.994576f,-1.67359e-017f}, +{0.104013f,-0.994576f,9.76911e-016f},{-0.308272f,-0.951298f,1.12532e-015f},{-0.310578f,-0.950548f,-1.3235e-015f}, +{0.499433f,-0.866353f,-4.28854e-016f},{0.308272f,-0.951298f,-3.84795e-016f},{0.105163f,-0.994455f,2.52336e-016f}, +{0.670096f,-0.742274f,-1.28968e-016f},{0.809606f,-0.586974f,8.92339e-016f},{0.808947f,-0.587881f,5.72092e-016f}, +{0.913543f,-0.406743f,2.78013e-016f},{0.913862f,-0.406026f,1.85741e-016f},{0.978254f,-0.207408f,-1.24594e-016f}, +{0.978165f,-0.20783f,7.37379e-016f},{1.0f,-1.55431e-016f,0.0f},{0.997945f,-0.0640791f,-1.60571e-016f}, +{0.997946f,-0.0640673f,-1.60571e-016f},{0.967287f,-0.253683f,-1.63272e-016f},{0.967317f,-0.25357f,0.0f}, +{0.981554f,-0.191184f,0.0f},{0.981559f,-0.191157f,-1.2303e-016f},{0.991791f,-0.12787f,0.0f}, +{0.991787f,-0.127897f,0.0f},{0.900965f,-0.433892f,0.0f},{0.90096f,-0.433902f,-1.44966e-016f}, +{0.871315f,-0.490723f,0.0f},{0.94917f,-0.314763f,2.02584e-016f},{0.949042f,-0.315149f,3.05405e-016f}, +{0.926953f,-0.375176f,2.98297e-016f},{0.761438f,-0.648238f,6.25816e-016f},{0.761447f,-0.648227f,-3.3112e-016f}, +{0.801406f,-0.598121f,3.21425e-016f},{0.838075f,-0.545555f,4.07138e-017f},{0.838084f,-0.545542f,0.0f}, +{0.871302f,-0.490747f,1.40194e-016f},{0.623505f,-0.781819f,-3.51916e-016f},{0.623476f,-0.781843f,1.00318e-016f}, +{0.572134f,-0.82016f,5.27861e-016f},{0.718357f,-0.695675f,0.0f},{0.718339f,-0.695693f,-3.39459e-016f}, +{0.672313f,-0.740267f,-8.44706e-016f},{0.404769f,-0.914419f,-3.26828e-016f},{0.404803f,-0.914404f,-8.17642e-016f}, +{0.462522f,-0.886608f,7.071e-016f},{0.462558f,-0.886589f,5.70615e-016f},{0.518412f,-0.855131f,5.08662e-016f}, +{0.518376f,-0.855153f,-4.17039e-017f},{0.222542f,-0.974923f,-8.69587e-016f},{0.22251f,-0.97493f,-5.9167e-016f}, +{0.15962f,-0.987179f,-1.07473e-016f},{0.345353f,-0.938473f,6.04008e-016f},{0.284517f,-0.958671f,7.31456e-016f}, +{0.284548f,-0.958662f,-2.28921e-017f},{0.032044f,-0.999486f,-3.39684e-016f},{-0.032044f,-0.999486f,7.88628e-016f}, +{0.0320605f,-0.999486f,1.46027e-015f},{0.0960134f,-0.99538f,9.37778e-016f},{0.0960397f,-0.995377f,4.49568e-016f}, +{0.159589f,-0.987184f,-7.04325e-016f},{-0.22251f,-0.974931f,3.06907e-016f},{-0.159589f,-0.987184f,1.06859e-015f}, +{-0.15962f,-0.987179f,1.95683e-016f},{-0.0960133f,-0.99538f,-1.13812e-016f},{-0.0320605f,-0.999486f,-7.97648e-016f}, +{-0.0960396f,-0.995378f,4.84338e-016f},{-0.345353f,-0.938473f,1.99332e-017f},{-0.284548f,-0.958662f,-6.68238e-016f}, +{-0.345385f,-0.938461f,-1.09868e-015f},{-0.222542f,-0.974923f,-1.56867e-016f},{-0.284517f,-0.958671f,1.31362e-016f}, +{-0.462522f,-0.886608f,-9.48993e-016f},{-0.462558f,-0.886589f,1.0854e-016f},{-0.518376f,-0.855153f,5.61804e-016f}, +{-0.404803f,-0.914404f,3.25668e-017f},{-0.404769f,-0.914419f,-4.32364e-016f},{-0.572101f,-0.820183f,-6.26037e-016f}, +{-0.572134f,-0.82016f,4.29683e-017f},{-0.623475f,-0.781843f,-1.50578e-016f},{-0.518412f,-0.855131f,-1.71017e-016f}, +{-0.672313f,-0.740267f,8.82394e-016f},{-0.718357f,-0.695675f,-6.31165e-017f},{-0.718339f,-0.695693f,-4.2354e-016f}, +{-0.623505f,-0.781819f,-2.57672e-017f},{-0.672288f,-0.740289f,-7.50757e-016f},{-0.761438f,-0.648238f,8.28847e-016f}, +{-0.761447f,-0.648227f,1.98992e-016f},{-0.801409f,-0.598117f,4.42136e-016f},{-0.801406f,-0.598121f,2.0439e-016f}, +{-0.838084f,-0.545542f,1.01789e-015f},{-0.838075f,-0.545555f,-1.0489e-015f},{-0.871302f,-0.490747f,-1.02965e-015f}, +{-0.871315f,-0.490723f,-1.83478e-016f},{-0.900965f,-0.433892f,-6.58133e-016f},{-0.90096f,-0.433902f,-2.94448e-016f}, +{-0.926953f,-0.375176f,-1.1596e-017f},{-0.926902f,-0.375304f,-5.21943e-017f},{-0.949042f,-0.315149f,1.00427e-015f}, +{-0.94917f,-0.314763f,-3.79986e-016f},{-0.967317f,-0.25357f,1.01039e-017f},{-0.967287f,-0.253683f,-1.05575e-015f}, +{-0.981559f,-0.191157f,-6.7854e-016f},{-0.981554f,-0.191184f,5.82473e-016f},{-0.991787f,-0.127897f,-9.23871e-016f}, +{-0.991791f,-0.12787f,2.70854e-016f},{-0.997946f,-0.0640673f,1.3089e-017f},{-0.997945f,-0.0640792f,-1.24113e-016f}, +{-1.0f,-2.36848e-016f,0.0f},{0.345385f,-0.938461f,1.26357e-015f},{0.572101f,-0.820183f,3.5599e-016f}, +{0.672288f,-0.740289f,2.38228e-016f},{0.926902f,-0.375304f,0.0f},{0.801409f,-0.598117f,-3.19533e-016f}, +{1.0f,-1.25825e-016f,0.0f},{0.997945f,-0.0640791f,-4.12418e-017f},{0.967287f,-0.253683f,0.0f}, +{0.981559f,-0.191157f,1.57935e-016f},{0.991791f,-0.12787f,8.2298e-017f},{0.900965f,-0.433892f,1.44967e-016f}, +{0.90096f,-0.433902f,1.44966e-016f},{0.871315f,-0.490723f,-1.40196e-016f},{0.94917f,-0.314763f,-3.05447e-016f}, +{0.949042f,-0.315149f,-3.55535e-016f},{0.926953f,-0.375176f,0.0f},{0.761438f,-0.648238f,0.0f}, +{0.761447f,-0.648227f,0.0f},{0.801406f,-0.598121f,-2.57895e-016f},{0.838075f,-0.545555f,-4.07138e-017f}, +{0.838084f,-0.545542f,-1.34849e-016f},{0.871302f,-0.490747f,0.0f},{0.623505f,-0.781819f,0.0f}, +{0.572134f,-0.82016f,3.55988e-016f},{0.718357f,-0.695675f,1.15585e-016f},{0.718339f,-0.695693f,-1.15582e-016f}, +{0.672313f,-0.740267f,0.0f},{0.404769f,-0.914419f,0.0f},{0.404803f,-0.914404f,-3.25668e-017f}, +{0.462522f,-0.886608f,7.44207e-017f},{0.462558f,-0.886589f,-7.44265e-017f},{0.518412f,-0.855131f,-4.17067e-017f}, +{0.518376f,-0.855153f,0.0f},{0.222542f,-0.974923f,-1.79037e-017f},{0.22251f,-0.97493f,8.95056e-017f}, +{0.15962f,-0.987179f,8.98911e-017f},{0.345353f,-0.938473f,1.94488e-016f},{0.284517f,-0.958671f,4.57793e-017f}, +{0.284548f,-0.958662f,0.0f},{0.032044f,-0.999486f,9.02291e-018f},{-0.032044f,-0.999486f,1.69842e-016f}, +{0.0320605f,-0.999486f,1.5953e-016f},{0.0960134f,-0.99538f,-7.72437e-018f},{0.0960397f,-0.995377f,-7.72649e-018f}, +{0.159589f,-0.987184f,7.70345e-017f},{-0.22251f,-0.974931f,-2.89725e-017f},{-0.159589f,-0.987184f,-1.28391e-017f}, +{-0.15962f,-0.987179f,1.6526e-016f},{-0.0960133f,-0.99538f,0.0f},{-0.0320605f,-0.999486f,0.0f}, +{-0.0960396f,-0.995378f,-7.72648e-017f},{-0.345353f,-0.938473f,-6.16091e-017f},{-0.284548f,-0.958662f,-2.28921e-017f}, +{-0.345385f,-0.938461f,2.77865e-017f},{-0.222542f,-0.974923f,-1.70086e-016f},{-0.284517f,-0.958671f,3.43345e-017f}, +{-0.462522f,-0.886608f,4.27945e-016f},{-0.462558f,-0.886589f,3.44227e-016f},{-0.518376f,-0.855153f,8.12819e-017f}, +{-0.404803f,-0.914404f,5.78629e-019f},{-0.404769f,-0.914419f,-7.35659e-017f},{-0.572101f,-0.820183f,3.96619e-016f}, +{-0.572134f,-0.82016f,-5.38623e-018f},{-0.623475f,-0.781843f,1.1316e-016f},{-0.518412f,-0.855131f,-1.01149e-016f}, +{-0.672313f,-0.740267f,-1.55504e-016f},{-0.718357f,-0.695675f,5.36867e-017f},{-0.718339f,-0.695693f,2.73285e-018f}, +{-0.623505f,-0.781819f,2.14069e-016f},{-0.672288f,-0.740289f,-7.16643e-016f},{-0.761438f,-0.648238f,4.41224e-016f}, +{-0.761447f,-0.648227f,1.00012e-015f},{-0.801409f,-0.598117f,4.432e-016f},{-0.801406f,-0.598121f,-2.6222e-016f}, +{-0.838084f,-0.545542f,8.80097e-016f},{-0.838075f,-0.545555f,-1.06829e-015f},{-0.871302f,-0.490747f,-6.92209e-016f}, +{-0.871315f,-0.490723f,-2.64336e-017f},{-0.900965f,-0.433892f,-5.15123e-016f},{-0.90096f,-0.433902f,-2.3532e-016f}, +{-0.926953f,-0.375176f,3.47011e-016f},{-0.926902f,-0.375304f,-3.89492e-016f},{-0.949042f,-0.315149f,5.83544e-016f}, +{-0.94917f,-0.314763f,-4.7857e-016f},{-0.967317f,-0.25357f,-2.47062e-016f},{-0.967287f,-0.253683f,-8.80075e-016f}, +{-0.981559f,-0.191157f,-5.74475e-016f},{-0.981554f,-0.191184f,6.34e-016f},{-0.991787f,-0.127897f,-1.01223e-015f}, +{-0.991791f,-0.12787f,3.3853e-016f},{-0.997946f,-0.0640673f,4.63968e-017f},{-0.997945f,-0.0640792f,-6.26115e-017f}, +{0.345385f,-0.938461f,5.5573e-017f},{0.572101f,-0.820183f,-9.20521e-017f},{0.672288f,-0.740289f,0.0f}, +{0.926902f,-0.375304f,-2.98281e-016f},{0.801409f,-0.598117f,-3.21425e-016f},{0.997945f,-0.0640791f,0.0f}, +{0.997946f,-0.0640673f,-4.12342e-017f},{0.967317f,-0.25357f,1.632e-016f},{0.981554f,-0.191184f,-1.14042e-015f}, +{0.981559f,-0.191157f,0.0f},{0.90096f,-0.433902f,0.0f},{0.871315f,-0.490723f,3.15833e-016f}, +{0.94917f,-0.314763f,8.13477e-016f},{0.949042f,-0.315149f,1.22162e-015f},{0.761447f,-0.648227f,4.90073e-016f}, +{0.801406f,-0.598121f,9.00746e-016f},{0.838075f,-0.545555f,-1.27065e-017f},{0.838084f,-0.545542f,7.27679e-016f}, +{0.871302f,-0.490747f,2.44929e-016f},{0.623505f,-0.781819f,-6.05077e-016f},{0.623476f,-0.781843f,-2.516e-016f}, +{0.572134f,-0.82016f,-2.63931e-016f},{0.718357f,-0.695675f,-9.10081e-016f},{0.718339f,-0.695693f,9.24657e-016f}, +{0.672313f,-0.740267f,-2.81956e-016f},{0.404769f,-0.914419f,1.0468e-015f},{0.404803f,-0.914404f,-8.82776e-016f}, +{0.462522f,-0.886608f,2.85314e-016f},{0.462558f,-0.886589f,0.0f},{0.518412f,-0.855131f,-2.75184e-016f}, +{0.518376f,-0.855153f,8.25574e-016f},{0.222542f,-0.974923f,-8.5252e-017f},{0.22251f,-0.97493f,0.0f}, +{0.15962f,-0.987179f,6.35356e-016f},{0.345353f,-0.938473f,4.92873e-016f},{0.284517f,-0.958671f,4.00063e-016f}, +{0.284548f,-0.958662f,-8.33935e-016f},{0.032044f,-0.999486f,-3.21639e-016f},{-0.032044f,-0.999486f,1.50507e-016f}, +{0.0320605f,-0.999486f,1.81454e-016f},{0.0960134f,-0.99538f,-3.51215e-016f},{0.0960397f,-0.995377f,5.1138e-016f}, +{0.159589f,-0.987184f,5.84002e-016f},{-0.22251f,-0.974931f,4.34802e-016f},{-0.159589f,-0.987184f,1.07483e-016f}, +{-0.15962f,-0.987179f,7.94194e-016f},{-0.0960133f,-0.99538f,-8.3169e-016f},{-0.0320605f,-0.999486f,-1.71136e-016f}, +{-0.0960396f,-0.995378f,5.42286e-016f},{-0.345353f,-0.938473f,9.12026e-017f},{-0.284548f,-0.958662f,8.33935e-016f}, +{-0.345385f,-0.938461f,-2.46427e-016f},{-0.222542f,-0.974923f,7.84335e-017f},{-0.284517f,-0.958671f,7.85693e-016f}, +{-0.462522f,-0.886608f,-6.04745e-016f},{-0.462558f,-0.886589f,-7.16369e-016f},{-0.518376f,-0.855153f,-5.64993e-016f}, +{-0.404803f,-0.914404f,9.31047e-016f},{-0.404769f,-0.914419f,9.04416e-017f},{-0.572101f,-0.820183f,-3.36032e-016f}, +{-0.572134f,-0.82016f,4.41925e-016f},{-0.623475f,-0.781843f,-3.96109e-016f},{-0.518412f,-0.855131f,4.05468e-016f}, +{-0.672313f,-0.740267f,3.95309e-016f},{-0.718357f,-0.695675f,-3.52831e-017f},{-0.718339f,-0.695693f,-6.88355e-016f}, +{-0.623505f,-0.781819f,1.49682e-015f},{-0.672288f,-0.740289f,4.2753e-016f},{-0.761438f,-0.648238f,-2.74417e-016f}, +{-0.761447f,-0.648227f,-4.56317e-016f},{-0.801409f,-0.598117f,3.33218e-016f},{-0.801406f,-0.598121f,-2.93513e-016f}, +{-0.838084f,-0.545542f,-1.79534e-016f},{-0.838075f,-0.545555f,-4.11108e-017f},{-0.871302f,-0.490747f,1.62859e-016f}, +{-0.871315f,-0.490723f,1.48747e-016f},{-0.900965f,-0.433892f,-8.17489e-017f},{-0.90096f,-0.433902f,3.84887e-018f}, +{-0.926953f,-0.375176f,-5.46007e-017f},{-0.926902f,-0.375304f,-2.73406e-016f},{-0.949042f,-0.315149f,2.13422e-016f}, +{-0.94917f,-0.314763f,1.10395e-016f},{-0.967317f,-0.25357f,1.75065e-016f},{-0.967287f,-0.253683f,1.53602e-017f}, +{-0.981559f,-0.191157f,7.35095e-017f},{-0.981554f,-0.191184f,6.1315e-017f},{-0.991787f,-0.127897f,-1.7478e-017f}, +{-0.991791f,-0.12787f,7.54132e-017f},{-0.997946f,-0.0640673f,-1.02416e-016f},{-0.997945f,-0.0640792f,5.95282e-017f}, +{-1.0f,-3.70074e-018f,0.0f},{0.345385f,-0.938461f,4.92855e-016f},{0.572101f,-0.820183f,1.04271e-016f}, +{0.672288f,-0.740289f,2.81994e-016f},{0.926902f,-0.375304f,-3.55013e-016f},{0.801409f,-0.598117f,-1.60901e-015f}, +{1.0f,2.36848e-016f,0.0f},{1.0f,-2.81256e-016f,0.0f},{0.997946f,-0.0640673f,0.0f}, +{0.967287f,-0.253683f,1.63272e-016f},{0.967317f,-0.25357f,-1.632e-016f},{0.981554f,-0.191184f,-1.26347e-015f}, +{0.991787f,-0.127897f,8.23157e-017f},{0.900965f,-0.433892f,1.43899e-015f},{0.871315f,-0.490723f,1.12157e-015f}, +{0.94917f,-0.314763f,0.0f},{0.949042f,-0.315149f,6.10811e-016f},{0.926953f,-0.375176f,-5.96594e-016f}, +{0.801406f,-0.598121f,7.08268e-016f},{0.838075f,-0.545555f,-5.39391e-016f},{0.838084f,-0.545542f,7.14954e-016f}, +{0.871302f,-0.490747f,1.12155e-015f},{0.623505f,-0.781819f,-2.51592e-016f},{0.623476f,-0.781843f,6.52874e-016f}, +{0.572134f,-0.82016f,-3.6823e-016f},{0.718357f,-0.695675f,4.6234e-016f},{0.718339f,-0.695693f,0.0f}, +{0.672313f,-0.740267f,-2.38221e-016f},{0.404769f,-0.914419f,1.30256e-016f},{0.404803f,-0.914404f,2.60534e-016f}, +{0.518412f,-0.855131f,3.33654e-016f},{0.518376f,-0.855153f,5.84395e-017f},{0.222542f,-0.974923f,0.0f}, +{0.22251f,-0.97493f,7.16044e-017f},{0.15962f,-0.987179f,0.0f},{0.345353f,-0.938473f,0.0f}, +{0.284517f,-0.958671f,2.16945e-016f},{0.032044f,-0.999486f,1.03119e-017f},{-0.032044f,-0.999486f,2.06238e-017f}, +{0.0320605f,-0.999486f,1.50502e-016f},{0.0960134f,-0.99538f,0.0f},{0.0960397f,-0.995377f,0.0f}, +{0.159589f,-0.987184f,5.13564e-017f},{-0.22251f,-0.974931f,7.84341e-017f},{-0.159589f,-0.987184f,-7.70345e-017f}, +{-0.15962f,-0.987179f,2.56832e-017f},{-0.0960133f,-0.99538f,6.17949e-017f},{-0.0320605f,-0.999486f,-1.03172e-017f}, +{-0.0960396f,-0.995378f,-3.09059e-017f},{-0.345353f,-0.938473f,-5.55679e-017f},{-0.284548f,-0.958662f,2.91603e-016f}, +{-0.345385f,-0.938461f,-2.62146e-016f},{-0.222542f,-0.974923f,-7.84335e-017f},{-0.284517f,-0.958671f,-1.08473e-016f}, +{-0.462522f,-0.886608f,-4.03026e-017f},{-0.462558f,-0.886589f,3.72132e-017f},{-0.518376f,-0.855153f,4.17039e-017f}, +{-0.404803f,-0.914404f,2.29125e-016f},{-0.404769f,-0.914419f,7.35659e-017f},{-0.572101f,-0.820183f,-3.29923e-017f}, +{-0.572134f,-0.82016f,0.0f},{-0.623475f,-0.781843f,-1.44509e-016f},{-0.518412f,-0.855131f,-9.58855e-017f}, +{-0.672313f,-0.740267f,8.38658e-017f},{-0.718357f,-0.695675f,-1.14673e-016f},{-0.718339f,-0.695693f,-2.16261e-016f}, +{-0.623505f,-0.781819f,-3.0773e-016f},{-0.672288f,-0.740289f,-3.35459e-016f},{-0.761438f,-0.648238f,1.14033e-016f}, +{-0.761447f,-0.648227f,4.30418e-017f},{-0.801409f,-0.598117f,-4.72926e-019f},{-0.801406f,-0.598121f,6.3766e-017f}, +{-0.838084f,-0.545542f,9.9944e-017f},{-0.838075f,-0.545555f,6.62327e-017f},{-0.871302f,-0.490747f,-2.76664e-016f}, +{-0.871315f,-0.490723f,1.68095e-016f},{-0.900965f,-0.433892f,2.94656e-016f},{-0.90096f,-0.433902f,-2.73174e-016f}, +{-0.926953f,-0.375176f,5.54887e-018f},{-0.926902f,-0.375304f,4.60141e-016f},{-0.949042f,-0.315149f,3.69163e-017f}, +{-0.94917f,-0.314763f,-2.45758e-016f},{-0.967317f,-0.25357f,-1.94496e-016f},{-0.967287f,-0.253683f,6.21497e-017f}, +{-0.981559f,-0.191157f,1.73188e-016f},{-0.981554f,-0.191184f,-1.08839e-017f},{-0.991787f,-0.127897f,-8.76052e-017f}, +{-0.991791f,-0.12787f,-7.90167e-017f},{-0.997946f,-0.0640673f,-1.42163e-017f},{-0.997945f,-0.0640792f,1.54958e-017f}, +{0.345385f,-0.938461f,1.11146e-016f},{0.572101f,-0.820183f,0.0f},{0.672288f,-0.740289f,1.94462e-016f}, +{0.801409f,-0.598117f,-5.15793e-016f},{1.0f,-2.36848e-016f,0.0f},{-0.797567f,-0.603231f,0.0f}, +{-0.87226f,-0.489042f,0.0f},{-0.797567f,-0.603231f,0.0f},{-0.969762f,-0.244052f,0.0f}, +{-0.99273f,-0.12036f,0.0f},{-0.969762f,-0.244052f,0.0f},{-1.0f,6.28037e-016f,0.0f}, +{-0.603231f,-0.797567f,0.0f},{-0.489042f,-0.87226f,0.0f},{-0.603231f,-0.797567f,0.0f}, +{-0.368095f,-0.929788f,0.0f},{-0.244052f,-0.969762f,0.0f},{-0.12036f,-0.99273f,0.0f}, +{-0.244052f,-0.969762f,0.0f},{-8.1854e-013f,-1.0f,0.0f},{2.88897e-015f,-1.0f,0.0f}, +{-0.603231f,0.797567f,0.0f},{-0.489042f,0.87226f,0.0f},{-0.603231f,0.797567f,0.0f}, +{-0.244052f,0.969762f,0.0f},{-0.12036f,0.99273f,0.0f},{-0.244052f,0.969762f,0.0f}, +{-1.25607e-016f,1.0f,0.0f},{2.00972e-015f,1.0f,0.0f},{-0.797567f,0.603231f,0.0f}, +{-0.87226f,0.489042f,0.0f},{-0.797567f,0.603231f,0.0f},{-0.929788f,0.368095f,0.0f}, +{-0.969762f,0.244052f,0.0f},{-0.99273f,0.12036f,0.0f},{-0.969762f,0.244052f,0.0f}, +{-1.0f,8.22559e-013f,0.0f},{-1.0f,-1.88411e-015f,0.0f},{0.797567f,0.603231f,0.0f}, +{0.87226f,0.489042f,0.0f},{0.797567f,0.603231f,0.0f},{0.969762f,0.244052f,0.0f}, +{0.99273f,0.12036f,0.0f},{0.969762f,0.244052f,0.0f},{1.0f,-2.26093e-015f,0.0f}, +{1.0f,-3.01458e-015f,0.0f},{0.603231f,0.797567f,0.0f},{0.489042f,0.87226f,0.0f}, +{0.603231f,0.797567f,0.0f},{0.368095f,0.929788f,0.0f},{0.244052f,0.969762f,0.0f}, +{0.12036f,0.99273f,0.0f},{0.244052f,0.969762f,0.0f},{8.23564e-013f,1.0f,0.0f}, +{0.603231f,-0.797567f,0.0f},{0.489042f,-0.87226f,0.0f},{0.603231f,-0.797567f,0.0f}, +{0.244052f,-0.969762f,0.0f},{0.12036f,-0.99273f,0.0f},{0.244052f,-0.969762f,0.0f}, +{-2.26093e-015f,-1.0f,0.0f},{-3.01458e-015f,-1.0f,0.0f},{0.797567f,-0.603231f,0.0f}, +{0.87226f,-0.489042f,0.0f},{0.797567f,-0.603231f,0.0f},{0.929788f,-0.368095f,0.0f}, +{0.969762f,-0.244052f,0.0f},{0.99273f,-0.12036f,0.0f},{0.969762f,-0.244052f,0.0f}, +{1.0f,-8.23564e-013f,0.0f},{1.0f,1.50729e-015f,0.0f},{-1.0f,-1.89478e-014f,0.0f}, +{-0.950842f,-0.309676f,2.44782e-015f},{-0.952103f,-0.305779f,2.15167e-019f},{8.16528e-017f,-1.0f,1.84438e-017f}, +{-0.309304f,-0.950963f,4.14988e-018f},{-0.307814f,-0.951446f,3.80951e-016f},{-0.588229f,-0.808694f,-7.42514e-016f}, +{-0.811958f,-0.583716f,-2.09799e-015f},{-0.807656f,-0.589654f,2.07649e-015f},{0.587751f,-0.809042f,1.88339e-015f}, +{0.309304f,-0.950963f,-7.93445e-016f},{0.588229f,-0.808694f,1.89378e-016f},{5.24206e-017f,-1.0f,1.84438e-017f}, +{0.307814f,-0.951446f,2.20274e-016f},{0.950842f,-0.309676f,7.07655e-016f},{0.807656f,-0.589654f,1.56255e-015f}, +{0.811958f,-0.583716f,-1.04521e-015f},{0.952103f,-0.305779f,3.26521e-015f},{-0.587751f,-0.809042f,7.71131e-016f}, +{-1.0f,-9.4739e-015f,0.0f},{-1.0f,-1.38778e-017f,0.0f},{-0.950842f,-0.309676f,-7.97239e-016f}, +{-0.952103f,-0.305779f,0.0f},{0.0f,-1.0f,-6.43608e-016f},{-0.309304f,-0.950963f,0.0f}, +{-0.307814f,-0.951446f,1.22472e-015f},{-0.588229f,-0.808694f,-1.04096e-015f},{-0.811958f,-0.583716f,1.50274e-015f}, +{-0.807656f,-0.589654f,1.51802e-015f},{0.587751f,-0.809042f,-5.16272e-016f},{0.309304f,-0.950963f,-1.22487e-015f}, +{0.588229f,-0.808694f,1.03505e-015f},{-1.48864e-033f,-1.0f,-6.43608e-016f},{0.307814f,-0.951446f,-1.84017e-015f}, +{0.950842f,-0.309676f,8.81649e-016f},{0.807656f,-0.589654f,5.11667e-016f},{0.811958f,-0.583716f,6.28859e-016f}, +{0.952103f,-0.305779f,2.03625e-016f},{-0.587751f,-0.809042f,1.04141e-015f},{-0.950842f,-0.309676f,7.97239e-016f}, +{0.0f,-1.0f,1.28722e-015f},{-0.307814f,-0.951446f,-3.67415e-015f},{-0.588229f,-0.808694f,0.0f}, +{-0.811958f,-0.583716f,0.0f},{-0.807656f,-0.589654f,-1.51802e-015f},{0.587751f,-0.809042f,2.64786e-016f}, +{0.309304f,-0.950963f,6.11269e-016f},{0.588229f,-0.808694f,-5.91545e-018f},{-1.18424e-015f,-1.0f,1.28722e-015f}, +{0.307814f,-0.951446f,2.44634e-015f},{0.950842f,-0.309676f,-1.04605e-015f},{0.807656f,-0.589654f,2.88358e-015f}, +{0.811958f,-0.583716f,1.00454e-015f},{0.952103f,-0.305779f,-6.20481e-016f},{-0.587751f,-0.809042f,4.16564e-015f}, +{-0.950842f,-0.309676f,-2.44566e-015f},{-0.952103f,-0.305779f,2.45155e-015f},{4.91127e-017f,-1.0f,-8.5099e-018f}, +{-0.309304f,-0.950963f,4.13264e-016f},{-0.307814f,-0.951446f,8.07812e-016f},{-0.588229f,-0.808694f,1.50932e-015f}, +{-0.811958f,-0.583716f,-1.44928e-018f},{-0.807656f,-0.589654f,-2.07994e-015f},{0.587751f,-0.809042f,-3.86108e-016f}, +{0.309304f,-0.950963f,-1.81296e-016f},{0.588229f,-0.808694f,-7.56836e-016f},{5.40884e-017f,-1.0f,-8.5099e-018f}, +{0.307814f,-0.951446f,1.76305e-017f},{0.950842f,-0.309676f,1.56858e-015f},{0.807656f,-0.589654f,2.21017e-015f}, +{0.811958f,-0.583716f,-1.76554e-015f},{0.952103f,-0.305779f,4.58535e-015f},{-0.587751f,-0.809042f,-1.30906e-017f}, +{0.0f,-1.0f,6.43608e-016f},{-0.309304f,-0.950963f,1.22409e-015f},{-0.307814f,-0.951446f,-4.89886e-015f}, +{-0.588229f,-0.808694f,1.04096e-015f},{0.587751f,-0.809042f,7.85491e-016f},{0.588229f,-0.808694f,-5.26397e-016f}, +{1.48864e-033f,-1.0f,6.43608e-016f},{0.307814f,-0.951446f,3.0587e-015f},{0.950842f,-0.309676f,-6.69229e-016f}, +{0.807656f,-0.589654f,-5.31973e-016f},{0.811958f,-0.583716f,7.2278e-016f},{0.952103f,-0.305779f,-1.28478e-016f}, +{-0.587751f,-0.809042f,0.0f},{0.0f,-1.0f,-1.28722e-015f},{-0.309304f,-0.950963f,-2.44819e-015f}, +{-0.588229f,-0.808694f,-2.08193e-015f},{0.309304f,-0.950963f,-1.83692e-015f},{0.588229f,-0.808694f,1.55553e-015f}, +{1.18424e-015f,-1.0f,-1.28722e-015f},{0.307814f,-0.951446f,-1.22781e-015f},{0.950842f,-0.309676f,6.6054e-016f}, +{0.807656f,-0.589654f,-2.71413e-015f},{0.811958f,-0.583716f,-2.47054e-015f},{0.952103f,-0.305779f,5.72628e-016f}, +{-0.950842f,-0.309676f,-6.17708e-020f},{-0.309304f,-0.950963f,-3.93991e-016f},{-0.307814f,-0.951446f,7.77175e-016f}, +{-0.588229f,-0.808694f,7.71841e-016f},{-0.811958f,-0.583716f,-7.65821e-018f},{-0.807656f,-0.589654f,-2.08202e-015f}, +{0.587751f,-0.809042f,-1.97153e-016f},{0.309304f,-0.950963f,2.01908e-016f},{0.588229f,-0.808694f,-1.32498e-015f}, +{0.307814f,-0.951446f,6.16497e-016f},{0.950842f,-0.309676f,-1.06132e-015f},{0.807656f,-0.589654f,-1.94619e-015f}, +{0.811958f,-0.583716f,5.2254e-016f},{0.952103f,-0.305779f,3.28436e-015f},{-0.587751f,-0.809042f,-7.41994e-016f}, +{-1.0f,9.4739e-015f,0.0f},{-0.950842f,-0.309676f,2.4501e-015f},{-0.952103f,-0.305779f,-2.45069e-015f}, +{-0.309304f,-0.950963f,1.51228e-017f},{-0.307814f,-0.951446f,-3.80858e-016f},{-0.588229f,-0.808694f,-5.03529e-018f}, +{-0.807656f,-0.589654f,2.07857e-015f},{0.587751f,-0.809042f,7.48736e-016f},{0.309304f,-0.950963f,-7.78507e-016f}, +{0.588229f,-0.808694f,3.41962e-019f},{0.950842f,-0.309676f,5.45443e-016f},{0.807656f,-0.589654f,4.02952e-015f}, +{0.811958f,-0.583716f,-7.85697e-016f},{0.952103f,-0.305779f,-5.00849e-015f},{1.0f,-1.06581e-014f,0.0f}, +{-0.587751f,-0.809042f,1.50003e-015f},{-0.978165f,-0.20783f,9.12701e-016f},{-0.978254f,-0.207408f,-1.22532e-015f}, +{-0.50141f,-0.86521f,-2.22742e-015f},{-0.66887f,-0.743379f,2.0214e-015f},{-0.809606f,-0.586974f,-1.30267e-016f}, +{-0.913862f,-0.406026f,-1.94353e-015f},{-0.913543f,-0.406743f,0.0f},{-0.105163f,-0.994455f,3.84023e-015f}, +{-0.104013f,-0.994576f,-8.36797e-018f},{0.104013f,-0.994576f,2.56047e-015f},{-0.499433f,-0.866353f,-2.3509e-015f}, +{-0.308272f,-0.951298f,-1.22453e-015f},{-0.310578f,-0.950548f,3.62071e-015f},{0.310578f,-0.950548f,5.86794e-016f}, +{0.50141f,-0.86521f,-2.52602e-015f},{0.499433f,-0.866353f,4.17189e-015f},{0.308272f,-0.951298f,-1.78719e-015f}, +{0.105163f,-0.994455f,2.56862e-015f},{0.670096f,-0.742274f,-7.90726e-016f},{0.809606f,-0.586974f,-4.90953e-016f}, +{0.808947f,-0.587881f,-5.53829e-016f},{0.66887f,-0.743379f,-1.94741e-015f},{0.913543f,-0.406743f,-2.89332e-016f}, +{0.913862f,-0.406026f,1.7826e-016f},{0.978254f,-0.207408f,1.65571e-016f},{0.978165f,-0.20783f,-9.99953e-016f}, +{-0.808947f,-0.587881f,0.0f},{-0.50141f,-0.86521f,4.03389e-017f},{-0.670096f,-0.742274f,-5.84062e-015f}, +{-0.66887f,-0.743379f,-3.82756e-015f},{-0.913543f,-0.406743f,-1.46991e-016f},{-0.105163f,-0.994455f,2.56862e-015f}, +{0.104013f,-0.994576f,2.56883e-015f},{-0.499433f,-0.866353f,2.19018e-015f},{-0.308272f,-0.951298f,-2.44905e-015f}, +{-0.310578f,-0.950548f,4.89424e-015f},{0.310578f,-0.950548f,-1.88531e-015f},{0.50141f,-0.86521f,-1.70082e-015f}, +{0.499433f,-0.866353f,-3.94332e-015f},{0.308272f,-0.951298f,-1.81199e-015f},{0.105163f,-0.994455f,-1.27585e-015f}, +{0.670096f,-0.742274f,2.60918e-015f},{0.809606f,-0.586974f,9.60728e-017f},{0.808947f,-0.587881f,1.32834e-015f}, +{0.66887f,-0.743379f,-9.1653e-016f},{0.913543f,-0.406743f,-4.16505e-016f},{0.913862f,-0.406026f,5.90121e-016f}, +{0.978254f,-0.207408f,3.34195e-017f},{0.978165f,-0.20783f,6.34323e-016f},{1.0f,-3.14563e-016f,0.0f}, +{-0.808947f,-0.587881f,-1.51346e-015f},{-0.978165f,-0.20783f,1.57389e-016f},{-0.978254f,-0.207408f,-1.06792e-015f}, +{-0.670096f,-0.742274f,-5.67889e-015f},{-0.66887f,-0.743379f,-3.77374e-015f},{-0.809606f,-0.586974f,0.0f}, +{-0.105163f,-0.994455f,2.56015e-015f},{0.104013f,-0.994576f,2.56465e-015f},{-0.499433f,-0.866353f,2.27054e-015f}, +{-0.308272f,-0.951298f,-2.43665e-015f},{-0.310578f,-0.950548f,4.88175e-015f},{0.310578f,-0.950548f,-1.81035e-015f}, +{0.50141f,-0.86521f,-1.69074e-015f},{0.499433f,-0.866353f,-3.89811e-015f},{0.308272f,-0.951298f,-1.81819e-015f}, +{0.105163f,-0.994455f,-1.28008e-015f},{0.670096f,-0.742274f,2.46093e-015f},{0.809606f,-0.586974f,4.51872e-017f}, +{0.808947f,-0.587881f,1.19615e-015f},{0.66887f,-0.743379f,-8.76172e-016f},{0.913543f,-0.406743f,-4.37176e-016f}, +{0.913862f,-0.406026f,6.8432e-016f},{0.978254f,-0.207408f,2.10037e-016f},{0.978165f,-0.20783f,4.6264e-016f}, +{-0.808947f,-0.587881f,-1.64362e-015f},{-0.978165f,-0.20783f,1.22748e-015f},{-0.66887f,-0.743379f,1.80616e-015f}, +{-0.809606f,-0.586974f,6.51336e-017f},{-0.913862f,-0.406026f,-2.09057e-015f},{-0.105163f,-0.994455f,3.82754e-015f}, +{-0.104013f,-0.994576f,0.0f},{0.104013f,-0.994576f,2.57302e-015f},{-0.499433f,-0.866353f,-2.27054e-015f}, +{-0.308272f,-0.951298f,-1.23693e-015f},{-0.310578f,-0.950548f,3.65819e-015f},{0.310578f,-0.950548f,5.80547e-016f}, +{0.50141f,-0.86521f,-2.54115e-015f},{0.499433f,-0.866353f,4.11664e-015f},{0.308272f,-0.951298f,-1.80579e-015f}, +{0.105163f,-0.994455f,2.57285e-015f},{0.670096f,-0.742274f,-6.28996e-016f},{0.809606f,-0.586974f,-5.7237e-016f}, +{0.808947f,-0.587881f,-5.701e-016f},{0.66887f,-0.743379f,-2.03485e-015f},{0.913543f,-0.406743f,-4.37471e-016f}, +{0.913862f,-0.406026f,1.49541e-016f},{0.978254f,-0.207408f,1.87245e-016f},{0.978165f,-0.20783f,-1.1409e-015f}, +{-0.978254f,-0.207408f,-5.00352e-015f},{-0.50141f,-0.86521f,6.9607e-017f},{-0.670096f,-0.742274f,1.78483e-015f}, +{-0.66887f,-0.743379f,-1.19611e-016f},{-0.809606f,-0.586974f,-2.08427e-015f},{-0.913543f,-0.406743f,-6.54457e-017f}, +{-0.105163f,-0.994455f,1.9073e-016f},{-0.104013f,-0.994576f,-3.4779e-016f},{0.104013f,-0.994576f,1.73895e-016f}, +{-0.499433f,-0.866353f,1.49485e-015f},{-0.308272f,-0.951298f,8.70157e-016f},{-0.310578f,-0.950548f,-7.64725e-017f}, +{0.310578f,-0.950548f,-1.90331e-015f},{0.50141f,-0.86521f,-1.84452e-015f},{0.499433f,-0.866353f,-3.48494e-017f}, +{0.308272f,-0.951298f,-3.58546e-016f},{0.105163f,-0.994455f,4.61465e-016f},{0.670096f,-0.742274f,-7.66352e-016f}, +{0.809606f,-0.586974f,-1.39162e-015f},{0.808947f,-0.587881f,-4.28911e-016f},{0.66887f,-0.743379f,-1.68458e-015f}, +{0.913543f,-0.406743f,-2.14927e-016f},{0.913862f,-0.406026f,3.22114e-015f},{0.978254f,-0.207408f,-1.64157e-015f}, +{0.978165f,-0.20783f,4.10552e-015f},{-0.808947f,-0.587881f,-2.08258e-015f},{-0.978165f,-0.20783f,-5.03643e-015f}, +{-0.978254f,-0.207408f,3.33724e-017f},{-0.50141f,-0.86521f,-1.22124e-015f},{-0.670096f,-0.742274f,5.97167e-017f}, +{-0.66887f,-0.743379f,1.60235e-015f},{-0.913862f,-0.406026f,2.35267e-015f},{-0.913543f,-0.406743f,2.28641e-015f}, +{-0.105163f,-0.994455f,-8.00048e-017f},{-0.104013f,-0.994576f,5.3873e-017f},{0.104013f,-0.994576f,-9.38801e-017f}, +{-0.499433f,-0.866353f,-1.07666e-015f},{-0.308272f,-0.951298f,7.65328e-017f},{0.310578f,-0.950548f,2.95481e-016f}, +{0.50141f,-0.86521f,-1.52181e-015f},{0.499433f,-0.866353f,1.2587e-016f},{0.308272f,-0.951298f,-5.56952e-016f}, +{0.105163f,-0.994455f,-8.00048e-017f},{0.670096f,-0.742274f,-1.41327e-015f},{0.809606f,-0.586974f,1.47426e-015f}, +{0.808947f,-0.587881f,4.17136e-016f},{0.66887f,-0.743379f,-7.15979e-016f},{0.913543f,-0.406743f,-2.88423e-016f}, +{0.913862f,-0.406026f,1.97129e-015f},{0.978254f,-0.207408f,-1.91702e-015f},{0.978165f,-0.20783f,1.59714e-015f}, +{1.0f,-1.0066e-014f,0.0f},{-0.50141f,-0.86521f,-1.43006e-015f},{-0.66887f,-0.743379f,1.78177e-015f}, +{-0.913543f,-0.406743f,2.4173e-015f},{-0.105163f,-0.994455f,0.0f},{-0.104013f,-0.994576f,1.33888e-016f}, +{0.104013f,-0.994576f,6.6149e-017f},{-0.499433f,-0.866353f,-1.35545e-015f},{-0.308272f,-0.951298f,2.29599e-016f}, +{0.310578f,-0.950548f,1.42536e-016f},{0.50141f,-0.86521f,-1.55661e-015f},{0.499433f,-0.866353f,3.87464e-017f}, +{0.308272f,-0.951298f,-6.71751e-016f},{0.105163f,-0.994455f,-4.00024e-017f},{0.670096f,-0.742274f,-1.21919e-015f}, +{0.809606f,-0.586974f,1.4477e-015f},{0.808947f,-0.587881f,4.93992e-016f},{0.66887f,-0.743379f,-8.50541e-016f}, +{0.913543f,-0.406743f,-2.17864e-016f},{0.913862f,-0.406026f,2.0356e-015f},{0.978254f,-0.207408f,-1.90767e-015f}, +{0.978165f,-0.20783f,1.60331e-015f},{-0.50141f,-0.86521f,-1.39214e-016f},{-0.670096f,-0.742274f,1.72512e-015f}, +{-0.66887f,-0.743379f,5.98056e-017f},{-0.913543f,-0.406743f,6.54457e-017f},{-0.105163f,-0.994455f,2.70735e-016f}, +{-0.104013f,-0.994576f,-2.67775e-016f},{0.104013f,-0.994576f,3.33924e-016f},{-0.499433f,-0.866353f,1.21606e-015f}, +{-0.308272f,-0.951298f,1.02322e-015f},{0.310578f,-0.950548f,-2.05626e-015f},{0.50141f,-0.86521f,-1.87932e-015f}, +{0.499433f,-0.866353f,-1.21973e-016f},{0.308272f,-0.951298f,-4.73345e-016f},{0.105163f,-0.994455f,5.01467e-016f}, +{0.670096f,-0.742274f,-5.72273e-016f},{0.809606f,-0.586974f,-1.41818e-015f},{0.808947f,-0.587881f,-3.52056e-016f}, +{0.66887f,-0.743379f,-1.81914e-015f},{0.913543f,-0.406743f,-1.44369e-016f},{0.913862f,-0.406026f,3.28545e-015f}, +{0.978254f,-0.207408f,-1.63222e-015f},{0.978165f,-0.20783f,4.11169e-015f},{-0.50141f,-0.86521f,-4.03389e-017f}, +{-0.670096f,-0.742274f,1.91093e-015f},{-0.66887f,-0.743379f,3.82756e-015f},{-0.913862f,-0.406026f,-1.04529e-015f}, +{-0.913543f,-0.406743f,-1.04713e-015f},{-0.105163f,-0.994455f,-2.54323e-015f},{-0.104013f,-0.994576f,-1.29697e-015f}, +{0.104013f,-0.994576f,-1.28442e-015f},{-0.499433f,-0.866353f,-4.42055e-015f},{-0.308272f,-0.951298f,-2.37465e-015f}, +{-0.310578f,-0.950548f,2.40964e-015f},{0.50141f,-0.86521f,3.52965e-017f},{0.499433f,-0.866353f,2.27557e-015f}, +{0.308272f,-0.951298f,2.46765e-015f},{0.105163f,-0.994455f,-2.55169e-015f},{0.670096f,-0.742274f,-1.08164e-015f}, +{0.809606f,-0.586974f,1.7623e-015f},{0.808947f,-0.587881f,-8.13675e-016f},{0.66887f,-0.743379f,-5.12076e-016f}, +{0.913543f,-0.406743f,-1.07269e-015f},{0.913862f,-0.406026f,8.92948e-016f},{0.978254f,-0.207408f,2.07703e-016f}, +{0.978165f,-0.20783f,-1.28498e-015f},{-0.808947f,-0.587881f,1.57854e-015f},{-0.978165f,-0.20783f,1.07009e-015f}, +{-0.50141f,-0.86521f,2.3081e-015f},{-0.670096f,-0.742274f,-5.39099e-017f},{-0.66887f,-0.743379f,-5.38112e-017f}, +{-0.809606f,-0.586974f,-1.64139e-015f},{-0.913862f,-0.406026f,1.47042e-016f},{-0.105163f,-0.994455f,-6.3877e-015f}, +{-0.104013f,-0.994576f,-1.25931e-015f},{0.104013f,-0.994576f,-1.27187e-015f},{-0.308272f,-0.951298f,3.63638e-015f}, +{-0.310578f,-0.950548f,2.44712e-015f},{0.50141f,-0.86521f,8.45368e-016f},{0.499433f,-0.866353f,-2.48405e-015f}, +{0.308272f,-0.951298f,-3.07371e-015f},{0.105163f,-0.994455f,-3.84446e-015f},{0.670096f,-0.742274f,2.29805e-015f}, +{0.809606f,-0.586974f,-1.2864e-016f},{0.808947f,-0.587881f,4.24795e-015f},{0.66887f,-0.743379f,4.38086e-016f}, +{0.913543f,-0.406743f,-1.06091e-015f},{0.913862f,-0.406026f,-6.1115e-016f},{0.978254f,-0.207408f,-6.34059e-017f}, +{0.978165f,-0.20783f,2.90712e-016f},{-0.808947f,-0.587881f,-6.50806e-017f},{-1.0f,-3.70074e-017f,0.0f}, +{-0.978165f,-0.20783f,-3.14777e-016f},{-0.978254f,-0.207408f,1.57403e-016f},{-0.670096f,-0.742274f,1.80311e-015f}, +{-0.913862f,-0.406026f,-1.33937e-015f},{-0.913543f,-0.406743f,-1.34111e-015f},{-0.105163f,-0.994455f,-2.56862e-015f}, +{-0.104013f,-0.994576f,-1.24676e-015f},{0.104013f,-0.994576f,-1.29697e-015f},{-0.308272f,-0.951298f,-2.42425e-015f}, +{-0.310578f,-0.950548f,2.42213e-015f},{0.50141f,-0.86521f,0.0f},{0.499433f,-0.866353f,2.20023e-015f}, +{0.308272f,-0.951298f,2.46145e-015f},{0.105163f,-0.994455f,-2.56439e-015f},{0.670096f,-0.742274f,-1.10185e-015f}, +{0.809606f,-0.586974f,2.00044e-015f},{0.808947f,-0.587881f,-6.46906e-016f},{0.66887f,-0.743379f,-4.85171e-016f}, +{0.913543f,-0.406743f,-9.18809e-016f},{0.913862f,-0.406026f,9.41196e-016f},{0.978254f,-0.207408f,2.63205e-017f}, +{0.978165f,-0.20783f,-1.29405e-015f},{-0.808947f,-0.587881f,1.51346e-015f},{-0.978254f,-0.207408f,-1.57403e-016f}, +{-0.50141f,-0.86521f,2.18708e-015f},{-0.670096f,-0.742274f,1.0782e-016f},{-0.66887f,-0.743379f,-1.07622e-016f}, +{-0.809606f,-0.586974f,-1.51112e-015f},{-0.105163f,-0.994455f,-6.39193e-015f},{-0.104013f,-0.994576f,-1.27187e-015f}, +{0.104013f,-0.994576f,-1.25931e-015f},{-0.499433f,-0.866353f,-2.23036e-015f},{-0.308272f,-0.951298f,3.67358e-015f}, +{0.50141f,-0.86521f,8.65538e-016f},{0.499433f,-0.866353f,-2.50916e-015f},{0.308272f,-0.951298f,-3.06131e-015f}, +{0.105163f,-0.994455f,-3.82754e-015f},{0.670096f,-0.742274f,2.06893e-015f},{0.809606f,-0.586974f,-5.53643e-017f}, +{0.808947f,-0.587881f,4.16863e-015f},{0.66887f,-0.743379f,5.79341e-016f},{0.913543f,-0.406743f,-8.98992e-016f}, +{0.913862f,-0.406026f,-7.47853e-016f},{0.978254f,-0.207408f,6.23321e-017f},{0.978165f,-0.20783f,2.84103e-016f}, +{-0.50141f,-0.86521f,1.36045e-015f},{-0.670096f,-0.742274f,-1.6654e-015f},{-0.66887f,-0.743379f,-1.84157e-015f}, +{-0.913543f,-0.406743f,4.63826e-015f},{-0.104013f,-0.994576f,-4.81677e-016f},{0.104013f,-0.994576f,-4.95542e-016f}, +{-0.499433f,-0.866353f,2.09097e-016f},{-0.310578f,-0.950548f,1.12287e-015f},{0.310578f,-0.950548f,4.95371e-016f}, +{0.50141f,-0.86521f,-3.92318e-016f},{0.308272f,-0.951298f,2.36673e-016f},{0.670096f,-0.742274f,-8.74172e-016f}, +{0.809606f,-0.586974f,-2.30349e-015f},{0.808947f,-0.587881f,-3.42262e-015f},{0.66887f,-0.743379f,-3.93111e-016f}, +{0.913543f,-0.406743f,6.30269e-016f},{0.913862f,-0.406026f,1.6772e-015f},{0.978254f,-0.207408f,-2.36956e-015f}, +{0.978165f,-0.20783f,3.13168e-015f},{1.0f,1.0066e-014f,0.0f},{-0.808947f,-0.587881f,6.24774e-015f}, +{-0.50141f,-0.86521f,1.15163e-015f},{-0.670096f,-0.742274f,-1.72512e-015f},{-0.66887f,-0.743379f,-1.66215e-015f}, +{-0.913543f,-0.406743f,4.76915e-015f},{-0.104013f,-0.994576f,-4.01663e-016f},{0.104013f,-0.994576f,-3.35513e-016f}, +{-0.499433f,-0.866353f,-6.96989e-017f},{0.310578f,-0.950548f,3.42426e-016f},{0.50141f,-0.86521f,-4.27122e-016f}, +{0.308272f,-0.951298f,1.21873e-016f},{0.670096f,-0.742274f,-6.80093e-016f},{0.809606f,-0.586974f,-2.33005e-015f}, +{0.808947f,-0.587881f,-3.34576e-015f},{0.66887f,-0.743379f,-5.27674e-016f},{0.913543f,-0.406743f,7.00828e-016f}, +{0.913862f,-0.406026f,1.74151e-015f},{0.978254f,-0.207408f,-2.3602e-015f},{0.978165f,-0.20783f,3.13785e-015f}, +{-0.913862f,-0.406026f,4.70535e-015f},{0.104013f,-0.994576f,-6.77384e-017f},{-0.308272f,-0.951298f,-1.67214e-016f}, +{-0.310578f,-0.950548f,7.23088e-016f},{0.50141f,-0.86521f,1.83186e-015f},{0.499433f,-0.866353f,-2.8542e-015f}, +{0.308272f,-0.951298f,-7.65328e-017f},{0.105163f,-0.994455f,-4.46105e-016f},{0.809606f,-0.586974f,1.38256e-015f}, +{0.808947f,-0.587881f,2.9875e-016f},{0.66887f,-0.743379f,3.33306e-016f},{0.913543f,-0.406743f,2.97918e-015f}, +{0.913862f,-0.406026f,-3.51524e-015f},{0.978254f,-0.207408f,-2.31593e-015f},{0.978165f,-0.20783f,6.29469e-016f}, +{0.104013f,-0.994576f,-2.27768e-016f},{-0.308272f,-0.951298f,-3.20279e-016f},{0.50141f,-0.86521f,1.86666e-015f}, +{0.499433f,-0.866353f,-2.76708e-015f},{0.308272f,-0.951298f,3.82664e-017f},{0.105163f,-0.994455f,-4.86107e-016f}, +{0.809606f,-0.586974f,1.40912e-015f},{0.808947f,-0.587881f,2.21895e-016f},{0.66887f,-0.743379f,4.67868e-016f}, +{0.913543f,-0.406743f,2.90863e-015f},{0.913862f,-0.406026f,-3.57955e-015f},{0.978254f,-0.207408f,-2.32529e-015f}, +{0.978165f,-0.20783f,6.23297e-016f},{1.0503e-015f,1.0f,-4.4248e-016f},{1.32669e-015f,1.0f,-4.4248e-016f}, +{-0.987342f,0.158603f,0.0f},{-0.563203f,0.826318f,-2.43092e-015f},{-0.766044f,0.642788f,-2.58564e-017f}, +{-0.911564f,0.411158f,-2.41291e-015f},{-0.327644f,0.944801f,1.60877e-016f},{-5.81917e-015f,-1.0f,0.0f}, +{-3.12964e-015f,-1.0f,0.0f},{0.944801f,-0.327644f,-2.48504e-015f},{0.411158f,-0.911564f,5.40403e-016f}, +{0.642788f,-0.766044f,-2.51303e-015f},{0.826318f,-0.563203f,-2.17261e-015f},{0.158603f,-0.987342f,1.69056e-016f}, +{-1.0f,-1.42312e-031f,5.14886e-015f},{-1.0f,-7.0757e-015f,5.14886e-015f},{-0.158603f,-0.987342f,4.87746e-016f}, +{-0.826318f,-0.563203f,2.94231e-016f},{-0.642788f,-0.766044f,-4.19866e-015f},{-0.411158f,-0.911564f,3.66681e-017f}, +{-0.944801f,-0.327644f,4.51725e-015f},{1.0f,-6.25927e-015f,0.0f},{0.327644f,0.944801f,-7.60102e-017f}, +{0.911564f,0.411158f,-8.94506e-016f},{0.766044f,0.642788f,-2.51041e-015f},{0.563203f,0.826318f,1.48317e-015f}, +{0.987342f,0.158603f,-9.73349e-016f},{2.81922e-015f,-1.0f,2.81578e-016f},{2.21116e-015f,-1.0f,2.81578e-016f}, +{0.987342f,-0.158603f,5.08369e-015f},{0.563203f,-0.826318f,-1.72179e-015f},{0.766044f,-0.642788f,2.02384e-015f}, +{0.911564f,-0.411158f,1.10722e-015f},{0.327644f,-0.944801f,-4.42325e-016f},{2.93403e-016f,1.0f,0.0f}, +{-2.34723e-015f,1.0f,0.0f},{-0.944801f,0.327644f,5.27185e-017f},{-0.411158f,0.911564f,-1.08478e-015f}, +{-0.642788f,0.766044f,-1.94526e-015f},{-0.826318f,0.563203f,3.28157e-015f},{-0.158603f,0.987342f,-5.96628e-016f}, +{-0.158603f,0.987342f,-7.51139e-016f},{-1.50359e-014f,1.0f,-3.86165e-015f},{-2.12271e-014f,1.0f,-3.86165e-015f}, +{-0.563203f,0.826318f,-1.74542e-015f},{-0.766044f,0.642788f,1.27192e-015f},{-0.911564f,0.411158f,0.0f}, +{-0.327644f,0.944801f,-1.40602e-017f},{6.25927e-015f,-1.0f,0.0f},{-2.50371e-014f,-1.0f,0.0f}, +{0.944801f,-0.327644f,-7.60102e-017f},{0.411158f,-0.911564f,-1.34268e-016f},{0.642788f,-0.766044f,-1.4597e-015f}, +{0.826318f,-0.563203f,3.3239e-017f},{0.158603f,-0.987342f,-2.36033e-015f},{-1.0f,-1.50359e-014f,-3.86165e-015f}, +{-1.0f,-2.12271e-014f,-3.86165e-015f},{-0.158603f,-0.987342f,7.37193e-016f},{-0.826318f,-0.563203f,-1.7256e-015f}, +{-0.642788f,-0.766044f,1.218e-015f},{-0.411158f,-0.911564f,-7.33362e-017f},{-0.944801f,-0.327644f,-1.94144e-017f}, +{1.0f,6.25927e-015f,0.0f},{1.0f,-2.50371e-014f,0.0f},{0.327644f,0.944801f,8.43496e-016f}, +{0.911564f,0.411158f,-2.04101e-015f},{0.766044f,0.642788f,-9.60208e-016f},{0.563203f,0.826318f,-7.24964e-016f}, +{0.987342f,0.158603f,-4.26811e-015f},{1.50359e-014f,-1.0f,-3.86165e-015f},{2.12271e-014f,-1.0f,-3.86165e-015f}, +{0.987342f,-0.158603f,8.96059e-016f},{0.563203f,-0.826318f,-1.76241e-015f},{0.766044f,-0.642788f,1.23341e-015f}, +{0.911564f,-0.411158f,0.0f},{0.327644f,-0.944801f,-1.48839e-017f},{-6.25927e-015f,1.0f,0.0f}, +{2.50371e-014f,1.0f,0.0f},{-0.944801f,0.327644f,9.19506e-016f},{-0.411158f,0.911564f,-2.04721e-015f}, +{-0.642788f,0.766044f,-9.47279e-016f},{-0.826318f,0.563203f,-6.58486e-016f},{-0.158603f,0.987342f,-4.27439e-015f}, +{-1.0f,-5.52789e-017f,-2.01127e-016f},{-1.0f,-4.42231e-016f,-2.01127e-016f},{-0.158603f,-0.987342f,2.56736e-015f}, +{-0.826318f,-0.563203f,2.03441e-015f},{-0.642788f,-0.766044f,-1.89456e-015f},{-0.411158f,-0.911564f,-2.2806e-015f}, +{-0.944801f,-0.327644f,-6.80855e-016f},{1.0f,-1.02691e-015f,0.0f},{1.0f,7.82409e-016f,0.0f}, +{0.327644f,0.944801f,-4.81193e-015f},{0.911564f,0.411158f,1.02824e-016f},{0.766044f,0.642788f,0.0f}, +{0.563203f,0.826318f,-1.01834e-015f},{0.987342f,0.158603f,1.80074e-016f},{2.43227e-015f,-1.0f,2.81578e-016f}, +{2.65339e-015f,-1.0f,2.81578e-016f},{0.987342f,-0.158603f,-2.51632e-015f},{0.563203f,-0.826318f,-1.48159e-015f}, +{0.766044f,-0.642788f,5.18888e-016f},{0.911564f,-0.411158f,-1.17338e-015f},{0.327644f,-0.944801f,-1.30642e-017f}, +{1.95602e-016f,1.0f,0.0f},{-0.944801f,0.327644f,-4.86465e-015f},{-0.411158f,0.911564f,3.45909e-016f}, +{-0.642788f,0.766044f,5.06146e-016f},{-0.826318f,0.563203f,2.08199e-015f},{-0.158603f,0.987342f,3.01313e-016f}, +{-0.158603f,0.987342f,7.86925e-017f},{1.0f,1.10558e-016f,-2.41353e-016f},{1.0f,4.42231e-016f,-2.41353e-016f}, +{0.158603f,0.987342f,2.56736e-015f},{0.826318f,0.563203f,-1.66982e-016f},{0.642788f,0.766044f,-1.94627e-015f}, +{0.944801f,0.327644f,-1.31395e-015f},{-1.0f,1.95602e-016f,0.0f},{-1.0f,-2.34723e-015f,0.0f}, +{-0.327644f,-0.944801f,-2.37961e-015f},{-0.911564f,-0.411158f,5.88225e-016f},{-0.766044f,-0.642788f,1.27192e-015f}, +{-0.563203f,-0.826318f,-1.10896e-015f},{-0.987342f,-0.158603f,-2.16372e-016f},{1.42312e-031f,-1.0f,5.14886e-015f}, +{7.0757e-015f,-1.0f,5.14886e-015f},{0.987342f,-0.158603f,4.08313e-016f},{0.563203f,-0.826318f,2.82904e-016f}, +{0.766044f,-0.642788f,-4.12933e-015f},{0.327644f,-0.944801f,4.50922e-015f},{6.25927e-015f,1.0f,0.0f}, +{-0.944801f,0.327644f,0.0f},{-0.411158f,0.911564f,-8.71765e-016f},{-0.642788f,0.766044f,-2.4393e-015f}, +{-0.826318f,0.563203f,1.44993e-015f},{-0.158603f,0.987342f,-9.70258e-016f},{1.0f,1.42312e-031f,5.14886e-015f}, +{1.0f,7.0757e-015f,5.14886e-015f},{0.158603f,0.987342f,4.08313e-016f},{0.826318f,0.563203f,2.46089e-016f}, +{0.642788f,0.766044f,-4.11392e-015f},{0.411158f,0.911564f,3.66681e-017f},{0.944801f,0.327644f,4.51313e-015f}, +{-1.0f,6.25927e-015f,0.0f},{-0.911564f,-0.411158f,-8.90371e-016f},{-0.766044f,-0.642788f,-2.52334e-015f}, +{-0.563203f,-0.826318f,1.38345e-015f},{-0.987342f,-0.158603f,-9.72053e-016f},{-1.50359e-014f,1.0f,3.86165e-015f}, +{-1.41514e-014f,1.0f,3.86165e-015f},{-0.563203f,0.826318f,2.60249e-016f},{-0.766044f,0.642788f,-4.12933e-015f}, +{-0.911564f,0.411158f,3.66681e-017f},{-0.327644f,0.944801f,4.53578e-015f},{-1.7213e-014f,-1.0f,0.0f}, +{1.25185e-014f,-1.0f,0.0f},{0.944801f,-0.327644f,1.68699e-015f},{0.411158f,-0.911564f,-2.19388e-015f}, +{0.642788f,-0.766044f,-9.92528e-016f},{0.826318f,-0.563203f,2.89985e-015f},{0.158603f,-0.987342f,-9.67866e-016f}, +{1.0f,8.84462e-016f,1.20676e-016f},{1.0f,4.42231e-016f,1.20676e-016f},{0.826318f,0.563203f,-7.99752e-016f}, +{0.642788f,0.766044f,5.96458e-016f},{0.411158f,0.911564f,1.10722e-015f},{0.944801f,0.327644f,-1.19869e-015f}, +{-1.0f,2.93403e-016f,0.0f},{-0.327644f,-0.944801f,-5.27185e-017f},{-0.327644f,-0.944801f,-2.43232e-015f}, +{-0.911564f,-0.411158f,6.36047e-016f},{-0.563203f,-0.826318f,1.06365e-015f},{-0.987342f,-0.158603f,-1.62229e-016f}, +{1.43725e-015f,1.0f,-3.21804e-016f},{1.76892e-015f,1.0f,-3.21804e-016f},{-0.987342f,0.158603f,2.51632e-015f}, +{-0.563203f,0.826318f,3.20933e-016f},{-0.766044f,0.642788f,1.73942e-015f},{-0.911564f,0.411158f,2.37984e-015f}, +{-0.327644f,0.944801f,5.5243e-017f},{-2.68953e-015f,-1.0f,0.0f},{0.944801f,-0.327644f,-4.81193e-015f}, +{0.411158f,-0.911564f,-1.59493e-015f},{0.642788f,-0.766044f,3.34044e-015f},{0.826318f,-0.563203f,-1.01834e-015f}, +{0.158603f,-0.987342f,-8.62776e-016f},{-1.0f,1.93476e-015f,-2.81578e-016f},{-1.0f,2.21116e-015f,-2.81578e-016f}, +{-0.158603f,-0.987342f,5.10921e-015f},{-0.826318f,-0.563203f,-2.16142e-015f},{-0.642788f,-0.766044f,1.58252e-015f}, +{-0.411158f,-0.911564f,-1.1403e-015f},{-0.944801f,-0.327644f,-1.28754e-015f},{1.0f,-2.78733e-015f,0.0f}, +{1.0f,-1.56482e-015f,0.0f},{0.327644f,0.944801f,0.0f},{0.911564f,0.411158f,2.03571e-015f}, +{0.766044f,0.642788f,-4.90281e-015f},{0.563203f,0.826318f,3.19095e-015f},{0.987342f,0.158603f,-6.10433e-016f} +}; +GLfloat textures[1][2]={{0.0f,0.0f}}; +/*Material indicies*/ +/*{material index,face count}*/ +static int material_ref [1][2] = { +{0,77848} +}; +void MyMaterial(GLenum mode, GLfloat * f, GLfloat alpha) +{ + GLfloat d[4]; + d[0] = f[0]; + d[1] = f[1]; + d[2] = f[2]; + d[3] = alpha; + glMaterialfv(GL_FRONT_AND_BACK, mode, d); +} + +/* + * SelectMaterial uses OpenGL commands to define facet colors. + * + * Returns: + * Nothing + */ + +void SelectMaterial(int i) +{ +// +// Define the reflective properties of the 3D Object faces. +// + glEnd(); + GLfloat alpha = materials[i].alpha; + MyMaterial(GL_AMBIENT, materials[i].ambient, alpha); + MyMaterial(GL_DIFFUSE, materials[i].diffuse, alpha); + MyMaterial(GL_SPECULAR, materials[i].specular, alpha); + MyMaterial(GL_EMISSION, materials[i].emission, alpha); + glMaterialf(GL_FRONT_AND_BACK, GL_SHININESS, materials[i].phExp); + glBegin(GL_TRIANGLES); + +}; + +GLint generatePixhawkCheetah(float red, float green, float blue) +{ + unsigned int i; + int j; + + GLint lid=glGenLists(1); + int mcount=0; + int mindex=0; + glNewList(lid, GL_COMPILE); + + glColor3f(red, green, blue); + + glBegin (GL_TRIANGLES); + for(i=0;i +#else #include +#endif /** * @brief Creates a display list which renders a Pixhawk Cheetah MAV. diff --git a/src/ui/map3D/CheetahModel.h b/src/ui/map3D/CheetahModel.h index a1398748c0efc8220dbc2779c1627bf25d90e8f2..02bb2b2ac264ea2e7662bbb90e20c191d5f08b2d 100644 --- a/src/ui/map3D/CheetahModel.h +++ b/src/ui/map3D/CheetahModel.h @@ -32,7 +32,11 @@ This file is part of the QGROUNDCONTROL project #ifndef CHEETAHMODEL_H_ #define CHEETAHMODEL_H_ +#if (defined __APPLE__) & (defined __MACH__) +#include +#else #include +#endif /** * @brief Container for display list which renders the Pixhawk Cheetah MAV. diff --git a/src/ui/map3D/Q3DWidget.cc b/src/ui/map3D/Q3DWidget.cc index 04ee667966fe9343355de3712673befba66269b1..1151a15a9e608bc6e50606a70d7a7bb3a7200fed 100755 --- a/src/ui/map3D/Q3DWidget.cc +++ b/src/ui/map3D/Q3DWidget.cc @@ -32,8 +32,9 @@ This file is part of the QGROUNDCONTROL project #include "Q3DWidget.h" #include -#include -#include + +//#include +//#include static const float KEY_ROTATE_AMOUNT = 5.0f; static const float KEY_MOVE_AMOUNT = 10.0f; @@ -63,9 +64,9 @@ Q3DWidget::Q3DWidget(QWidget* parent) , timerFuncData(NULL) { cameraPose.state = IDLE; - cameraPose.pan = 0.0f; - cameraPose.tilt = 180.0f; - cameraPose.distance = 10.0f; + cameraPose.pan = 50.0f; + cameraPose.tilt = 200.0f; + cameraPose.distance = 5.0f; cameraPose.xOffset = 0.0f; cameraPose.yOffset = 0.0f; cameraPose.zOffset = 0.0f; diff --git a/src/ui/map3D/Q3DWidget.h b/src/ui/map3D/Q3DWidget.h index e964b687cbfbf2168f5262574b21d73bf46677cf..5a62f8b0fc1990eae0b3164c3ff237d4af5c905e 100644 --- a/src/ui/map3D/Q3DWidget.h +++ b/src/ui/map3D/Q3DWidget.h @@ -32,7 +32,6 @@ This file is part of the QGROUNDCONTROL project #ifndef Q3DWIDGET_H_ #define Q3DWIDGET_H_ -#include #include #include #include diff --git a/src/ui/map3D/QMap3DWidget.cc b/src/ui/map3D/QMap3DWidget.cc index f255deead1e67f8e924a7b564328034214c3d270..b1aa5080cd3354da11df83f5f09e8f04a958be2f 100644 --- a/src/ui/map3D/QMap3DWidget.cc +++ b/src/ui/map3D/QMap3DWidget.cc @@ -31,7 +31,6 @@ This file is part of the QGROUNDCONTROL project #include "QMap3DWidget.h" -#include #include #include #include @@ -44,7 +43,7 @@ QMap3DWidget::QMap3DWidget(QWidget* parent) : Q3DWidget(parent) , uas(NULL) , lastRedrawTime(0.0) - , displayGrid(false) + , displayGrid(true) , displayTrail(false) , lockCamera(true) , updateLastUnlockedPose(true) @@ -52,7 +51,7 @@ QMap3DWidget::QMap3DWidget(QWidget* parent) { setFocusPolicy(Qt::StrongFocus); - initialize(10, 10, 1000, 900, 10.0f); + initialize(10, 10, 1000, 900, 15.0f); setCameraParams(0.05f, 0.5f, 0.01f, 0.5f, 30.0f, 0.01f, 400.0f); int32_t argc = 0; @@ -64,7 +63,7 @@ QMap3DWidget::QMap3DWidget(QWidget* parent) buildLayout(); - font.reset(new FTTextureFont("images/Vera.ttf")); + //font.reset(new FTTextureFont("images/Vera.ttf")); connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); @@ -93,17 +92,21 @@ QMap3DWidget::buildLayout(void) lockCameraCheckBox->setText("Lock Camera"); lockCameraCheckBox->setChecked(lockCamera); + //positionLabel = new QLabel(this); + //positionLabel->setText(tr("Waiting for first position update.. ")); + QGridLayout* layout = new QGridLayout(this); layout->setMargin(0); layout->setSpacing(2); layout->addWidget(gridCheckBox, 1, 0); layout->addWidget(trailCheckBox, 1, 1); - layout->addWidget(recenterButton, 1, 2); - layout->addWidget(lockCameraCheckBox, 1, 3); + layout->addItem(new QSpacerItem(0, 0, QSizePolicy::Expanding, QSizePolicy::Expanding), 1, 2); + layout->addWidget(recenterButton, 1, 3); + layout->addWidget(lockCameraCheckBox, 1, 4); layout->setRowStretch(0, 100); layout->setRowStretch(1, 1); - layout->setColumnStretch(0, 1); - layout->setColumnStretch(1, 50); + //layout->setColumnStretch(0, 1); + layout->setColumnStretch(2, 50); setLayout(layout); connect(gridCheckBox, SIGNAL(stateChanged(int)), @@ -208,31 +211,46 @@ QMap3DWidget::displayHandler(void) glVertex2f(getWindowWidth(), 0.0f); glEnd(); - char buffer[7][255]; - - sprintf(buffer[0], "x = %.2f", robotX); - sprintf(buffer[1], "y = %.2f", robotY); - sprintf(buffer[2], "z = %.2f", robotZ); - sprintf(buffer[3], "r = %.2f", robotRoll); - sprintf(buffer[4], "p = %.2f", robotPitch); - sprintf(buffer[5], "y = %.2f", robotYaw); - std::pair mouseWorldCoords = getPositionIn3DMode(getMouseX(), getMouseY()); - sprintf(buffer[6], "Cursor [%.2f %.2f]", - mouseWorldCoords.first + robotX, mouseWorldCoords.second + robotY); - font->FaceSize(10); - glColor3f(1.0f, 1.0f, 1.0f); - glPushMatrix(); + // QT QPAINTER OPENGL PAINTING + + QPainter painter; + painter.begin(this); + painter.setRenderHint(QPainter::Antialiasing, true); + painter.setRenderHint(QPainter::HighQualityAntialiasing, true); + paintText(QString("x = %1 y = %2 z = %3 r = %4 p = %5 y = %6 Cursor [%7 %8]").arg(robotX, 0, 'f', 2).arg(robotY, 0, 'f', 2).arg(robotZ, 0, 'f', 2).arg(robotRoll, 0, 'f', 2).arg(robotPitch, 0, 'f', 2).arg(robotYaw, 0, 'f', 2).arg( mouseWorldCoords.first + robotX, 0, 'f', 2).arg( mouseWorldCoords.second + robotY, 0, 'f', 2), + QColor(255, 255, 255), + 12, + 5, + 5, + &painter); +} - glTranslatef(0.0f, 30.0f, 0.0f); - for (int32_t i = 0; i < 7; ++i) - { - glTranslatef(60.0f, 0.0f, 0.0f); - font->Render(buffer[i]); - } - glPopMatrix(); +void QMap3DWidget::paintText(QString text, QColor color, float fontSize, float refX, float refY, QPainter* painter) +{ + QPen prevPen = painter->pen(); + + float pPositionX = refX; + float pPositionY = refY; + + QFont font("Bitstream Vera Sans"); + // Enforce minimum font size of 5 pixels + int fSize = qMax(5, (int)(fontSize)); + font.setPixelSize(fSize); + + QFontMetrics metrics = QFontMetrics(font); + int border = qMax(4, metrics.leading()); + QRect rect = metrics.boundingRect(0, 0, width() - 2*border, int(height()*0.125), + Qt::AlignLeft | Qt::TextWordWrap, text); + painter->setPen(color); + painter->setFont(font); + painter->setRenderHint(QPainter::TextAntialiasing); + painter->drawText(pPositionX, pPositionY, + rect.width(), rect.height(), + Qt::AlignCenter | Qt::TextWordWrap, text); + painter->setPen(prevPen); } void @@ -382,17 +400,33 @@ QMap3DWidget::drawPlatform(float roll, float pitch, float yaw) { glPushMatrix(); - glRotatef(yaw, 0.0f, 0.0f, 1.0f); - glRotatef(pitch, 0.0f, 1.0f, 0.0f); - glRotatef(roll, 1.0f, 0.0f, 0.0f); + glRotatef((yaw*180.0f)/M_PI, 0.0f, 0.0f, 1.0f); + glRotatef((pitch*180.0f)/M_PI, 0.0f, 1.0f, 0.0f); + glRotatef((roll*180.0f)/M_PI, 1.0f, 0.0f, 0.0f); glLineWidth(3.0f); - glColor3f(0.0f, 1.0f, 0.0f); + + // X AXIS + glColor3f(1.0f, 0.0f, 0.0f); glBegin(GL_LINES); glVertex3f(0.0f, 0.0f, 0.0f); glVertex3f(0.3f, 0.0f, 0.0f); glEnd(); + // Y AXIS + glColor3f(0.0f, 1.0f, 0.0f); + glBegin(GL_LINES); + glVertex3f(0.0f, 0.0f, 0.0f); + glVertex3f(0.0f, 0.15f, 0.0f); + glEnd(); + + // Z AXIS + glColor3f(0.0f, 0.0f, 1.0f); + glBegin(GL_LINES); + glVertex3f(0.0f, 0.0f, 0.0f); + glVertex3f(0.0f, 0.0f, 0.15f); + glEnd(); + cheetahModel->draw(); glPopMatrix(); diff --git a/src/ui/map3D/QMap3DWidget.h b/src/ui/map3D/QMap3DWidget.h index f171151f67e84ff87c98f056fd06f8021c553de7..29be16986edcfc91e8bf1bdfb0f9f9fee8c72cb1 100644 --- a/src/ui/map3D/QMap3DWidget.h +++ b/src/ui/map3D/QMap3DWidget.h @@ -32,10 +32,11 @@ This file is part of the QGROUNDCONTROL project #ifndef QMAP3DWIDGET_H #define QMAP3DWIDGET_H +#include + #include "Q3DWidget.h" class CheetahModel; -class FTTextureFont; class UASInterface; /** @@ -76,6 +77,7 @@ private slots: protected: UASInterface* uas; + void paintText(QString text, QColor color, float fontSize, float refX, float refY, QPainter* painter); private: void drawPlatform(float roll, float pitch, float yaw); @@ -106,7 +108,6 @@ private: Pose3D targetPosition; QScopedPointer cheetahModel; - QScopedPointer font; }; #endif // QMAP3DWIDGET_H diff --git a/src/ui/uas/UASView.cc b/src/ui/uas/UASView.cc index 764bcf77bfdf8c845e43128a42a389e9161a7653..cd7bdd259537f665f651c9084c0aba24fff8c90f 100644 --- a/src/ui/uas/UASView.cc +++ b/src/ui/uas/UASView.cc @@ -109,7 +109,7 @@ UASView::UASView(UASInterface* uas, QWidget *parent) : // Heartbeat fade refreshTimer = new QTimer(this); connect(refreshTimer, SIGNAL(timeout()), this, SLOT(refresh())); - refreshTimer->start(180); + refreshTimer->start(updateInterval); } UASView::~UASView() @@ -195,7 +195,7 @@ void UASView::receiveHeartbeat(UASInterface* uas) m_ui->heartbeatIcon->setStyleSheet(colorstyle); m_ui->heartbeatIcon->setAutoFillBackground(true); refreshTimer->stop(); - refreshTimer->start(100); + refreshTimer->start(updateInterval); } } @@ -330,6 +330,21 @@ void UASView::updateLoad(UASInterface* uas, double load) void UASView::refresh() { + //setUpdatesEnabled(false); + //setUpdatesEnabled(true); + //repaint(); + + static quint64 lastupdate = 0; + qDebug() << "UASVIEW update diff: " << MG::TIME::getGroundTimeNow() - lastupdate; + lastupdate = MG::TIME::getGroundTimeNow(); + + // FIXME + static int generalUpdateCount = 0; + + if (generalUpdateCount == 4) + { + generalUpdateCount = 0; + qDebug() << "UPDATING EVERYTHING"; // State m_ui->stateLabel->setText(state); m_ui->statusTextLabel->setText(stateDesc); @@ -411,6 +426,8 @@ void UASView::refresh() QString timeText; timeText = timeText.sprintf("%02d:%02d:%02d", hours, min, sec); m_ui->timeElapsedLabel->setText(timeText); +} + generalUpdateCount++; // Fade heartbeat icon // Make color darker @@ -421,6 +438,9 @@ void UASView::refresh() heartbeatColor.red(), heartbeatColor.green(), heartbeatColor.blue()); m_ui->heartbeatIcon->setStyleSheet(colorstyle); m_ui->heartbeatIcon->setAutoFillBackground(true); + //setUpdatesEnabled(true); + + //setUpdatesEnabled(false); } void UASView::changeEvent(QEvent *e) diff --git a/src/ui/uas/UASView.h b/src/ui/uas/UASView.h index ba7ccf494ac217e76fc959eed92342308571fcd4..2d69aa21b37788dc64fa345712bdfdaa9c979a43 100644 --- a/src/ui/uas/UASView.h +++ b/src/ui/uas/UASView.h @@ -99,6 +99,7 @@ protected: float lon; float alt; float groundDistance; + static const int updateInterval = 300; void mouseDoubleClickEvent (QMouseEvent * event);